diff --git a/.gitignore b/.gitignore index 370335e6a05af2d..4562e47817a3215 100644 --- a/.gitignore +++ b/.gitignore @@ -14,6 +14,8 @@ model2.png a.out .hypothesis +/docs_site/ + *.dylib *.DSYM *.d @@ -43,6 +45,7 @@ persist selfdrive/pandad/pandad cereal/services.h cereal/gen +cereal/messaging/bridge selfdrive/logcatd/logcatd selfdrive/mapd/default_speeds_by_region.json system/proclogd/proclogd @@ -52,9 +55,6 @@ selfdrive/test/longitudinal_maneuvers/out selfdrive/car/tests/cars_dump system/camerad/camerad system/camerad/test/ae_gray_test -selfdrive/modeld/_modeld -selfdrive/modeld/_dmonitoringmodeld -/src/ notebooks hyperthneed @@ -76,6 +76,7 @@ selfdrive/modeld/models/*.thneed selfdrive/modeld/models/*.pkl *.bz2 +*.zst build/ @@ -83,3 +84,22 @@ build/ poetry.toml Pipfile + +### VisualStudioCode ### +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json +!.vscode/*.code-snippets + +# Local History for Visual Studio Code +.history/ + +# Built Visual Studio Code Extensions +*.vsix + +### VisualStudioCode Patch ### +# Ignore all local history of files +.history +.ionide diff --git a/.python-version b/.python-version deleted file mode 100644 index 0c7d5f5f5d7616c..000000000000000 --- a/.python-version +++ /dev/null @@ -1 +0,0 @@ -3.11.4 diff --git a/Jenkinsfile b/Jenkinsfile index 321237716b291de..f7d62024bc61ed9 100644 --- a/Jenkinsfile +++ b/Jenkinsfile @@ -12,10 +12,12 @@ def retryWithDelay(int maxRetries, int delay, Closure body) { def device(String ip, String step_label, String cmd) { withCredentials([file(credentialsId: 'id_rsa', variable: 'key_file')]) { def ssh_cmd = """ -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' +ssh -o ConnectTimeout=5 -o ServerAliveInterval=5 -o ServerAliveCountMax=2 -o BatchMode=yes -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' exec /usr/bin/bash <<'END' set -e +export TERM=xterm-256color + shopt -s huponexit # kill all child processes when the shell exits export CI=1 @@ -25,8 +27,9 @@ export TEST_DIR=${env.TEST_DIR} export SOURCE_DIR=${env.SOURCE_DIR} export GIT_BRANCH=${env.GIT_BRANCH} export GIT_COMMIT=${env.GIT_COMMIT} +export CI_ARTIFACTS_TOKEN=${env.CI_ARTIFACTS_TOKEN} +export GITHUB_COMMENTS_TOKEN=${env.GITHUB_COMMENTS_TOKEN} export AZURE_TOKEN='${env.AZURE_TOKEN}' -export MAPBOX_TOKEN='${env.MAPBOX_TOKEN}' # only use 1 thread for tici tests since most require HIL export PYTEST_ADDOPTS="-n 0" @@ -63,9 +66,7 @@ fi ln -snf ${env.TEST_DIR} /data/pythonpath cd ${env.TEST_DIR} || true -${cmd} -exit 0 - +time ${cmd} END""" sh script: ssh_cmd, label: step_label @@ -80,15 +81,32 @@ def deviceStage(String stageName, String deviceType, List extra_env, def steps) def extra = extra_env.collect { "export ${it}" }.join('\n'); def branch = env.BRANCH_NAME ?: 'master'; + def gitDiff = sh returnStdout: true, script: 'curl -s -H "Authorization: Bearer ${GITHUB_COMMENTS_TOKEN}" https://api.github.com/repos/commaai/openpilot/compare/master...${GIT_BRANCH} | jq .files[].filename || echo "/"', label: 'Getting changes' 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') { + timeout(time: 35, unit: 'MINUTES') { retry (3) { + def date = sh(script: 'date', returnStdout: true).trim(); + device(device_ip, "set time", "date -s '" + date + "'") device(device_ip, "git checkout", extra + "\n" + readFile("selfdrive/test/setup_device_ci.sh")) } steps.each { item -> - device(device_ip, item[0], item[1]) + def name = item[0] + def cmd = item[1] + + def args = item[2] + def diffPaths = args.diffPaths ?: [] + def cmdTimeout = args.timeout ?: 9999 + + if (branch != "master" && diffPaths && !hasPathChanged(gitDiff, diffPaths)) { + println "Skipping ${name}: no changes in ${diffPaths}." + return + } else { + timeout(time: cmdTimeout, unit: 'SECONDS') { + device(device_ip, name, cmd) + } + } } } } @@ -96,52 +114,38 @@ def deviceStage(String stageName, String deviceType, List extra_env, def steps) } } -def pcStage(String stageName, Closure body) { - node { - stage(stageName) { - if (currentBuild.result != null) { - return - } - - checkout scm - - def dockerArgs = "--user=batman -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/scons_cache:/tmp/scons_cache -e PYTHONPATH=${env.WORKSPACE} --cpus=8 --memory 16g -e PYTEST_ADDOPTS='-n8'"; - - def openpilot_base = retryWithDelay (3, 15) { - return docker.build("openpilot-base:build-${env.GIT_COMMIT}", "-f Dockerfile.openpilot_base .") - } - - lock(resource: "", label: 'pc', inversePrecedence: true, quantity: 1) { - openpilot_base.inside(dockerArgs) { - timeout(time: 20, unit: 'MINUTES') { - try { - retryWithDelay (3, 15) { - sh "git config --global --add safe.directory '*'" - sh "git submodule update --init --recursive" - sh "git lfs pull" - } - body() - } finally { - sh "rm -rf ${env.WORKSPACE}/* || true" - sh "rm -rf .* || true" - } - } - } - } +def hasPathChanged(String gitDiff, List paths) { + for (path in paths) { + if (gitDiff.contains(path)) { + return true } } + return false } def setupCredentials() { withCredentials([ string(credentialsId: 'azure_token', variable: 'AZURE_TOKEN'), - string(credentialsId: 'mapbox_token', variable: 'MAPBOX_TOKEN') ]) { env.AZURE_TOKEN = "${AZURE_TOKEN}" - env.MAPBOX_TOKEN = "${MAPBOX_TOKEN}" + } + + withCredentials([ + string(credentialsId: 'ci_artifacts_pat', variable: 'CI_ARTIFACTS_TOKEN'), + ]) { + env.CI_ARTIFACTS_TOKEN = "${CI_ARTIFACTS_TOKEN}" + } + + withCredentials([ + string(credentialsId: 'post_comments_github_pat', variable: 'GITHUB_COMMENTS_TOKEN'), + ]) { + env.GITHUB_COMMENTS_TOKEN = "${GITHUB_COMMENTS_TOKEN}" } } +def step(String name, String cmd, Map args = [:]) { + return [name, cmd, args] +} node { env.CI = "1" @@ -166,82 +170,90 @@ node { try { if (env.BRANCH_NAME == 'devel-staging') { deviceStage("build release3-staging", "tici-needs-can", [], [ - ["build release3-staging", "RELEASE_BRANCH=release3-staging $SOURCE_DIR/release/build_release.sh"], + step("build release3-staging", "RELEASE_BRANCH=release3-staging $SOURCE_DIR/release/build_release.sh"), ]) } if (env.BRANCH_NAME == 'master-ci') { - deviceStage("build nightly", "tici-needs-can", [], [ - ["build nightly", "RELEASE_BRANCH=nightly $SOURCE_DIR/release/build_release.sh"], - ]) + parallel ( + 'nightly': { + deviceStage("build nightly", "tici-needs-can", [], [ + step("build nightly", "RELEASE_BRANCH=nightly $SOURCE_DIR/release/build_release.sh"), + ]) + }, + 'nightly-dev': { + deviceStage("build nightly-dev", "tici-needs-can", [], [ + step("build nightly-dev", "PANDA_DEBUG_BUILD=1 RELEASE_BRANCH=nightly-dev $SOURCE_DIR/release/build_release.sh"), + ]) + }, + ) } if (!env.BRANCH_NAME.matches(excludeRegex)) { parallel ( // tici tests 'onroad tests': { - deviceStage("onroad", "tici-needs-can", [], [ + deviceStage("onroad", "tici-needs-can", ["UNSAFE=1"], [ // 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 system/manager && ./build.py"], - ["check dirty", "release/check-dirty.sh"], - ["onroad tests", "pytest selfdrive/test/test_onroad.py -s"], - ["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], + step("build openpilot", "cd system/manager && ./build.py"), + step("check dirty", "release/check-dirty.sh"), + step("onroad tests", "pytest selfdrive/test/test_onroad.py -s", [timeout: 60]), + //["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], ]) }, 'HW + Unit Tests': { deviceStage("tici-hardware", "tici-common", ["UNSAFE=1"], [ - ["build", "cd system/manager && ./build.py"], - ["test pandad", "pytest selfdrive/pandad/tests/test_pandad.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/ubloxd/tests/test_pigeond.py"], - ["test manager", "pytest system/manager/test/test_manager.py"], + step("build", "cd system/manager && ./build.py"), + step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda", "selfdrive/pandad/"]]), + step("test power draw", "pytest -s system/hardware/tici/tests/test_power_draw.py"), + step("test encoder", "LD_LIBRARY_PATH=/usr/local/lib pytest system/loggerd/tests/test_encoder.py"), + step("test pigeond", "pytest system/ubloxd/tests/test_pigeond.py"), + step("test manager", "pytest system/manager/test/test_manager.py"), ]) }, 'loopback': { deviceStage("loopback", "tici-loopback", ["UNSAFE=1"], [ - ["build openpilot", "cd system/manager && ./build.py"], - ["test pandad loopback", "pytest selfdrive/pandad/tests/test_pandad_loopback.py"], + step("build openpilot", "cd system/manager && ./build.py"), + step("test pandad loopback", "pytest selfdrive/pandad/tests/test_pandad_loopback.py"), ]) }, 'camerad': { deviceStage("AR0231", "tici-ar0231", ["UNSAFE=1"], [ - ["build", "cd system/manager && ./build.py"], - ["test camerad", "pytest system/camerad/test/test_camerad.py"], - ["test exposure", "pytest system/camerad/test/test_exposure.py"], + step("build", "cd system/manager && ./build.py"), + step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]), + step("test exposure", "pytest system/camerad/test/test_exposure.py"), ]) deviceStage("OX03C10", "tici-ox03c10", ["UNSAFE=1"], [ - ["build", "cd system/manager && ./build.py"], - ["test camerad", "pytest system/camerad/test/test_camerad.py"], - ["test exposure", "pytest system/camerad/test/test_exposure.py"], + step("build", "cd system/manager && ./build.py"), + step("test camerad", "pytest system/camerad/test/test_camerad.py", [timeout: 60]), + step("test exposure", "pytest system/camerad/test/test_exposure.py"), ]) }, 'sensord': { deviceStage("LSM + MMC", "tici-lsmc", ["UNSAFE=1"], [ - ["build", "cd system/manager && ./build.py"], - ["test sensord", "pytest system/sensord/tests/test_sensord.py"], + step("build", "cd system/manager && ./build.py"), + step("test sensord", "pytest system/sensord/tests/test_sensord.py"), ]) deviceStage("BMX + LSM", "tici-bmx-lsm", ["UNSAFE=1"], [ - ["build", "cd system/manager && ./build.py"], - ["test sensord", "pytest system/sensord/tests/test_sensord.py"], + step("build", "cd system/manager && ./build.py"), + step("test sensord", "pytest system/sensord/tests/test_sensord.py"), ]) }, 'replay': { deviceStage("model-replay", "tici-replay", ["UNSAFE=1"], [ - ["build", "cd system/manager && ./build.py"], - ["model replay", "selfdrive/test/process_replay/model_replay.py"], + step("build", "cd system/manager && ./build.py", [diffPaths: ["selfdrive/modeld/", "tinygrad_repo", "selfdrive/test/process_replay/model_replay.py"]]), + step("model replay", "selfdrive/test/process_replay/model_replay.py", [diffPaths: ["selfdrive/modeld/"]]), ]) }, 'tizi': { deviceStage("tizi", "tizi", ["UNSAFE=1"], [ - ["build openpilot", "cd system/manager && ./build.py"], - ["test pandad loopback", "SINGLE_PANDA=1 pytest selfdrive/pandad/tests/test_pandad_loopback.py"], - ["test pandad spi", "pytest selfdrive/pandad/tests/test_pandad_spi.py"], - ["test pandad", "pytest selfdrive/pandad/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 qcomgpsd", "pytest system/qcomgpsd/tests/test_qcomgpsd.py"], + step("build openpilot", "cd system/manager && ./build.py"), + step("test pandad loopback", "SINGLE_PANDA=1 pytest selfdrive/pandad/tests/test_pandad_loopback.py"), + step("test pandad spi", "pytest selfdrive/pandad/tests/test_pandad_spi.py"), + step("test pandad", "pytest selfdrive/pandad/tests/test_pandad.py", [diffPaths: ["panda", "selfdrive/pandad/"]]), + step("test amp", "pytest system/hardware/tici/tests/test_amplifier.py"), + step("test qcomgpsd", "pytest system/qcomgpsd/tests/test_qcomgpsd.py"), ]) }, diff --git a/README.md b/README.md index db74ee6a1a27924..38d32ec3b69761b 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,34 @@ -[![openpilot on the comma 3X](https://github.com/commaai/openpilot/assets/8762862/f09e6d29-db2d-4179-80c2-51e8d92bdb5c)](https://comma.ai/shop/comma-3x) +
+ +

openpilot

+ +

+ openpilot is an operating system for robotics. +
+ Currently, it upgrades the driver assistance system in 275+ supported cars. +

+ +

+ Docs + · + Roadmap + · + Contribute + · + Community + · + Try it on a comma 3X +

+ +Quick start: `bash <(curl -fsSL openpilot.comma.ai)` -What is openpilot? ------- +![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) +[![License: MIT](https://img.shields.io/badge/License-MIT-yellow.svg)](LICENSE) +[![X Follow](https://img.shields.io/twitter/follow/comma_ai)](https://x.com/comma_ai) +[![Discord](https://img.shields.io/discord/469524606043160576)](https://discord.comma.ai) -[openpilot](http://github.com/commaai/openpilot) is an open source driver assistance system. Currently, openpilot performs the functions of Adaptive Cruise Control (ACC), Automated Lane Centering (ALC), Forward Collision Warning (FCW), and Lane Departure Warning (LDW) for a growing variety of [supported car makes, models, and model years](docs/CARS.md). In addition, while openpilot is engaged, a camera-based Driver Monitoring (DM) feature alerts distracted and asleep drivers. See more about [the vehicle integration](docs/INTEGRATION.md) and [limitations](docs/LIMITATIONS.md). +
@@ -19,7 +44,7 @@ To start using openpilot in a car 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). +3. **Supported Car:** Ensure that you have one of [the 275+ 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). 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. @@ -36,7 +61,7 @@ openpilot is developed by [comma](https://comma.ai/) and by users like you. We w * Code documentation lives at https://docs.comma.ai * Information about running openpilot lives on the [community wiki](https://github.com/commaai/openpilot/wiki) -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) and offers lots of [bounties](https://comma.ai/bounties) for external contributors. Safety and Testing ---- @@ -49,18 +74,6 @@ Safety and Testing * 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 ------- - -By default, openpilot uploads the driving data to our servers. You can also access your data through [comma connect](https://connect.comma.ai/). We use your data to train better models and improve openpilot for everyone. - -openpilot is open source software: the user is free to disable data collection if they wish to do so. - -openpilot logs the road-facing cameras, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. -The driver-facing camera is only logged if you explicitly opt-in in settings. The microphone is not recorded. - -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. - Licensing ------ @@ -72,9 +85,14 @@ Any user of this software shall indemnify and hold harmless Comma.ai, Inc. and i YOU ARE RESPONSIBLE FOR COMPLYING WITH LOCAL LAWS AND REGULATIONS. NO WARRANTY EXPRESSED OR IMPLIED.** ---- +User Data and comma Account +------ - +By default, openpilot uploads the driving data to our servers. You can also access your data through [comma connect](https://connect.comma.ai/). We use your data to train better models and improve openpilot for everyone. -![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) +openpilot is open source software: the user is free to disable data collection if they wish to do so. + +openpilot logs the road-facing cameras, CAN, GPS, IMU, magnetometer, thermal sensors, crashes, and operating system logs. +The driver-facing camera is only logged if you explicitly opt-in in settings. The microphone is not recorded. + +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. diff --git a/RELEASES.md b/RELEASES.md index ea6524fa6f3df6f..dbec5206ccb9816 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,17 @@ +Version 0.9.8 (2024-XX-XX) +======================== +* New driving model + * Trained in brand new ML simulator + * Model now gates applying positive accel in Chill mode +* New driving monitoring model + * Reduced false positives related to passengers +* Image processing pipeline moved to the ISP + * More GPU time for driving models + * Power draw reduced 0.5W, which means your device runs cooler +* Added toggle to enable driver monitoring even when openpilot is not engaged +* Enable openpilot longitudinal control for Ford Q3 vehicles +* New Toyota TSS2 longitudinal tune + Version 0.9.7 (2024-06-13) ======================== * New driving model diff --git a/SConstruct b/SConstruct index 944d650d742d991..8aa46b9359767e8 100644 --- a/SConstruct +++ b/SConstruct @@ -64,6 +64,10 @@ AddOption('--pc-thneed', dest='pc_thneed', help='use thneed on pc') +AddOption('--mutation', + action='store_true', + help='generate mutation-ready code') + AddOption('--minimal', action='store_false', dest='extras', @@ -102,7 +106,6 @@ if arch == "larch64": libpath = [ "/usr/local/lib", - "/usr/lib", "/system/vendor/lib64", f"#third_party/acados/{arch}/lib", ] @@ -169,10 +172,6 @@ else: if arch != "Darwin": ldflags += ["-Wl,--as-needed", "-Wl,--no-undefined"] -# Enable swaglog include in submodules -cflags += ['-DSWAGLOG="\\"common/swaglog.h\\""'] -cxxflags += ['-DSWAGLOG="\\"common/swaglog.h\\""'] - ccflags_option = GetOption('ccflags') if ccflags_option: ccflags += ccflags_option.split(' ') @@ -187,12 +186,9 @@ env = Environment( "-Werror", "-Wshadow", "-Wno-unknown-warning-option", - "-Wno-deprecated-register", - "-Wno-register", "-Wno-inconsistent-missing-override", "-Wno-c99-designator", "-Wno-reorder-init-list", - "-Wno-error=unused-but-set-variable", "-Wno-vla-cxx-extension", ] + cflags + ccflags, @@ -206,13 +202,8 @@ env = Environment( "#third_party/json11", "#third_party/linux/include", "#third_party/snpe/include", - "#third_party/qrcode", "#third_party", - "#cereal", "#msgq", - "#opendbc/can", - "#third_party/maplibre-native-qt/include", - f"#third_party/maplibre-native-qt/{arch}/include" ], CC='clang', @@ -234,7 +225,7 @@ env = Environment( COMPILATIONDB_USE_ABSPATH=True, REDNOSE_ROOT="#", tools=["default", "cython", "compilation_db", "rednose_filter"], - toolpath=["#rednose_repo/site_scons/site_tools"], + toolpath=["#site_scons/site_tools", "#rednose_repo/site_scons/site_tools"], ) if arch == "Darwin": @@ -273,11 +264,12 @@ if arch == "Darwin": else: envCython["LINKFLAGS"] = ["-pthread", "-shared"] -Export('envCython') +np_version = SCons.Script.Value(np.__version__) +Export('envCython', 'np_version') # Qt build environment qt_env = env.Clone() -qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning", "DBus", "Xml"] +qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "DBus", "Xml"] qt_libs = [] if arch == "Darwin": @@ -317,21 +309,17 @@ try: except SCons.Errors.UserError: qt_env.Tool('qt') -qt_env['CPPPATH'] += qt_dirs# + ["#selfdrive/ui/qt/"] +qt_env['CPPPATH'] += qt_dirs + ["#third_party/qrcode"] qt_flags = [ "-D_REENTRANT", "-DQT_NO_DEBUG", "-DQT_WIDGETS_LIB", "-DQT_GUI_LIB", - "-DQT_QUICK_LIB", - "-DQT_QUICKWIDGETS_LIB", - "-DQT_QML_LIB", "-DQT_CORE_LIB", "-DQT_MESSAGELOGCONTEXT", ] qt_env['CXXFLAGS'] += qt_flags -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['LIBPATH'] += ['#selfdrive/ui', ] qt_env['LIBS'] = qt_libs if GetOption("clazy"): @@ -351,25 +339,27 @@ Export('env', 'qt_env', 'arch', 'real_arch') SConscript(['common/SConscript']) Import('_common', '_gpucommon') -common = [_common, 'json11'] +common = [_common, 'json11', 'zmq'] gpucommon = [_gpucommon] Export('common', 'gpucommon') # Build messaging (cereal + msgq + socketmaster + their dependencies) -SConscript(['msgq_repo/SConscript']) +# Enable swaglog include in submodules +env_swaglog = env.Clone() +env_swaglog['CXXFLAGS'].append('-DSWAGLOG="\\"common/swaglog.h\\""') +SConscript(['msgq_repo/SConscript'], exports={'env': env_swaglog}) +SConscript(['opendbc/can/SConscript'], exports={'env': env_swaglog}) + SConscript(['cereal/SConscript']) + Import('socketmaster', 'msgq') messaging = [socketmaster, msgq, 'zmq', 'capnp', 'kj',] Export('messaging') # Build other submodules -SConscript([ - 'body/board/SConscript', - 'opendbc/can/SConscript', - 'panda/SConscript', -]) +SConscript(['panda/SConscript']) # Build rednose library SConscript(['rednose/SConscript']) diff --git a/body/.gitignore b/body/.gitignore deleted file mode 100644 index cd74bc6017249cd..000000000000000 --- a/body/.gitignore +++ /dev/null @@ -1,15 +0,0 @@ -*.pyc -.*.swp -.*.swo -*.o -*.so -*.os -*.d -*.dump -a.out -*~ -.#* -.vscode* -.DS_Store -board/obj/ -.sconsign.dblite diff --git a/body/README.md b/body/README.md deleted file mode 100644 index 641aaa41eefb630..000000000000000 --- a/body/README.md +++ /dev/null @@ -1,18 +0,0 @@ -# comma body - -This the firmware for the comma body robotics dev kit. - - -Learn more at [commabody.com](https://commabody.com/). - -## building - -Compile: `scons` - -Flash bootstub and app: `board/recover.sh` # STM flasher should be connected to debug port, needs openocd - -Flash app through CAN bus with panda: - -`board/flash_base.sh` # base motherboard - -`board/flash_knee.sh` # knee motherboard diff --git a/body/SConstruct b/body/SConstruct deleted file mode 100644 index 4c48fe59234af7c..000000000000000 --- a/body/SConstruct +++ /dev/null @@ -1 +0,0 @@ -SConscript('board/SConscript') diff --git a/body/board/SConscript b/body/board/SConscript deleted file mode 100644 index 39927c8be1fdd6f..000000000000000 --- a/body/board/SConscript +++ /dev/null @@ -1,197 +0,0 @@ -import os -import subprocess - -PREFIX = "arm-none-eabi-" -BUILDER = "DEV" - -common_flags = [] -build_projects = {} - -build_projects["body"] = { - "MAIN": "main.c", - "STARTUP_FILE": "startup_stm32f413xx.s", - "LINKER_SCRIPT": "stm32fx_flash.ld", - "APP_START_ADDRESS": "0x08004000", - "PROJECT_FLAGS": [ - "-mcpu=cortex-m4", - "-mhard-float", - "-DSTM32F4", - "-DSTM32F413xx", - "-mfpu=fpv4-sp-d16", - "-fsingle-precision-constant", - "-Os", - "-g", - ], -} - -if os.getenv("RELEASE"): - BUILD_TYPE = "RELEASE" - cert_fn = os.getenv("CERT") - assert cert_fn is not None, 'No certificate file specified. Please set CERT env variable' - assert os.path.exists(cert_fn), 'Certificate file not found. Please specify absolute path' -else: - BUILD_TYPE = "DEBUG" - cert_fn = File("../certs/debug").srcnode().relpath - common_flags += ["-DALLOW_DEBUG"] - -if os.getenv("DEBUG"): - common_flags += ["-DDEBUG"] - -includes = [ - "inc/STM32F4xx_HAL_Driver/Inc", - "inc", - "..", - ".", -] - -c_sources = [ - ["hal_flash", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c"], - ["hal_pwr", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c"], - ["hal_rcc", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c"], - ["hal_i2c", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c"], - ["hal_i2c_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c"], - ["hal_tim", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c"], - ["hal_tim_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c"], - ["hal_adc_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c"], - ["hal_cortex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c"], - ["hal_flash_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c"], - ["hal_gpio", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c"], - ["hal_rcc_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c"], - ["hal", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c"], - ["hal_adc", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c"], - ["hal_dma", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c"], - ["system", "inc/system_stm32f4xx.c"], - ["it", "inc/stm32f4xx_it.c"], - ["bldc", "bldc/bldc.c"], - ["bldc_data", "bldc/BLDC_controller_data.c"], - ["bldc_con", "bldc/BLDC_controller.c"], - ["util", "util.c"], -] - -c_bstub_sources = [ - ["hal_pwr", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c"], - ["hal_rcc", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c"], - ["hal_cortex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c"], - ["hal_gpio", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c"], - ["hal_rcc_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c"], - ["hal", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c"], - ["system", "inc/system_stm32f4xx.c"], - ["it", "inc/stm32f4xx_it.c"], - ["util", "util.c"], -] - -def get_version(builder, build_type): - try: - git = subprocess.check_output(["git", "rev-parse", "--short=8", "HEAD"], encoding='utf8').strip() - except subprocess.CalledProcessError: - git = "00000000" - return f"{git}" - - -def to_c_uint32(x): - nums = [] - for _ in range(0x20): - nums.append(x % (2**32)) - x //= (2**32) - return "{" + 'U,'.join(map(str, nums)) + "U}" - - -def get_key_header(name): - from Crypto.PublicKey import RSA - - public_fn = f'../certs/{name}.pub' - rsa = RSA.importKey(open(public_fn).read()) - assert(rsa.size_in_bits() == 1024) - - rr = pow(2**1024, 2, rsa.n) - n0inv = 2**32 - pow(rsa.n, -1, 2**32) - - r = [ - f"RSAPublicKey {name}_rsa_key = {{", - f" .len = 0x20,", - f" .n0inv = {n0inv}U,", - f" .n = {to_c_uint32(rsa.n)},", - f" .rr = {to_c_uint32(rr)},", - f" .exponent = {rsa.e},", - f"}};", - ] - return r - -def objcopy(source, target, env, for_signature): - return '$OBJCOPY -O binary %s %s' % (source[0], target[0]) - -# Common autogenerated includes -git_ver = get_version(BUILDER, BUILD_TYPE) -with open("obj/gitversion.h", "w") as f: - f.write(f'const uint8_t gitversion[8] = "{git_ver}";\n') - -certs = [get_key_header(n) for n in ["debug", "release"]] -with open("obj/cert.h", "w") as f: - for cert in certs: - f.write("\n".join(cert) + "\n") - -for project_name in build_projects: - project = build_projects[project_name] - linkerscript_fn = File(project["LINKER_SCRIPT"]).srcnode().relpath - - flags = [ - "-Wall", - "-Wextra", - "-Wstrict-prototypes", - "-Werror", - "-mlittle-endian", - "-mthumb", - "-nostdlib", - "-fno-builtin", - f"-T{linkerscript_fn}", - "-std=gnu11", - "-fdata-sections", - "-ffunction-sections", - "-Wl,--gc-sections", - ] + project["PROJECT_FLAGS"] + common_flags - - project_env = Environment( - ENV=os.environ, - CC=PREFIX + 'gcc', - AS=PREFIX + 'gcc', - OBJCOPY=PREFIX + 'objcopy', - OBJDUMP=PREFIX + 'objdump', - ASCOM="$AS $ASFLAGS -o $TARGET -c $SOURCES", - CFLAGS=flags, - ASFLAGS=flags, - LINKFLAGS=flags, - LIBS = ['gcc',], - CPPPATH=includes, - BUILDERS={ - 'Objcopy': Builder(generator=objcopy, suffix='.bin', src_suffix='.elf') - } - ) - startup = project_env.Object(project["STARTUP_FILE"]) - - c_bstub_obj_list = [] - for c in c_bstub_sources: - c_bstub_obj_list.append(project_env.Object(f"{c[0]}-{project_name}", c[1])) - - # Bootstub - crypto_obj = [ - project_env.Object(f"rsa-{project_name}", "../crypto/rsa.c"), - project_env.Object(f"sha-{project_name}", "../crypto/sha.c") - ] - bootstub_obj = project_env.Object(f"bootstub-{project_name}", "bootstub.c") - bootstub_elf = project_env.Program(f"obj/bootstub.{project_name}.elf", [startup] + crypto_obj + c_bstub_obj_list + [bootstub_obj]) - bootstub_bin = project_env.Objcopy(f"obj/bootstub.{project_name}.bin", bootstub_elf) - - c_obj_list = [] - for c in c_sources: - c_obj_list.append(project_env.Object(f"{c[0]}-{project_name}", c[1])) - - # Build main - main_obj = project_env.Object(f"main-{project_name}", project["MAIN"]) - obj_list = [startup, main_obj] + c_obj_list - main_elf = project_env.Program(f"obj/{project_name}.elf", obj_list, - LINKFLAGS=[f"-Wl,--section-start,.isr_vector={project['APP_START_ADDRESS']}"] + flags) - main_bin = project_env.Objcopy(f"obj/{project_name}.bin", main_elf) - - # Sign main - 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/bldc/BLDC_controller.c b/body/board/bldc/BLDC_controller.c deleted file mode 100644 index ae63bd4053ebb52..000000000000000 --- a/body/board/bldc/BLDC_controller.c +++ /dev/null @@ -1,3376 +0,0 @@ -/* - * File: BLDC_controller.c - * - * Code generated for Simulink model 'BLDC_controller'. - * - * Model version : 1.1297 - * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 - * C/C++ source code generated on : Sun Mar 6 11:02:11 2022 - * - * Target selection: ert.tlc - * Embedded hardware selection: ARM Compatible->ARM Cortex - * Emulation hardware selection: - * Differs from embedded hardware (MATLAB Host) - * Code generation objectives: - * 1. Execution efficiency - * 2. RAM efficiency - * Validation result: Not run - */ - -#include "BLDC_controller.h" - -/* Named constants for Chart: '/F03_02_Control_Mode_Manager' */ -#define IN_ACTIVE ((uint8_T)1U) -#define IN_NO_ACTIVE_CHILD ((uint8_T)0U) -#define IN_OPEN ((uint8_T)2U) -#define IN_SPEED_MODE ((uint8_T)1U) -#define IN_TORQUE_MODE ((uint8_T)2U) -#define IN_VOLTAGE_MODE ((uint8_T)3U) -#define OPEN_MODE ((uint8_T)0U) -#define SPD_MODE ((uint8_T)2U) -#define TRQ_MODE ((uint8_T)3U) -#define VLT_MODE ((uint8_T)1U) -#ifndef UCHAR_MAX -#include -#endif - -#if ( UCHAR_MAX != (0xFFU) ) || ( SCHAR_MAX != (0x7F) ) -#error Code was generated for compiler with different sized uchar/char. \ -Consider adjusting Test hardware word size settings on the \ -Hardware Implementation pane to match your compiler word sizes as \ -defined in limits.h of the compiler. Alternatively, you can \ -select the Test hardware is the same as production hardware option and \ -select the Enable portable word sizes option on the Code Generation > \ -Verification pane for ERT based targets, which will disable the \ -preprocessor word size checks. -#endif - -#if ( USHRT_MAX != (0xFFFFU) ) || ( SHRT_MAX != (0x7FFF) ) -#error Code was generated for compiler with different sized ushort/short. \ -Consider adjusting Test hardware word size settings on the \ -Hardware Implementation pane to match your compiler word sizes as \ -defined in limits.h of the compiler. Alternatively, you can \ -select the Test hardware is the same as production hardware option and \ -select the Enable portable word sizes option on the Code Generation > \ -Verification pane for ERT based targets, which will disable the \ -preprocessor word size checks. -#endif - -#if ( UINT_MAX != (0xFFFFFFFFU) ) || ( INT_MAX != (0x7FFFFFFF) ) -#error Code was generated for compiler with different sized uint/int. \ -Consider adjusting Test hardware word size settings on the \ -Hardware Implementation pane to match your compiler word sizes as \ -defined in limits.h of the compiler. Alternatively, you can \ -select the Test hardware is the same as production hardware option and \ -select the Enable portable word sizes option on the Code Generation > \ -Verification pane for ERT based targets, which will disable the \ -preprocessor word size checks. -#endif - -#if ( ULONG_MAX != (0xFFFFFFFFU) ) || ( LONG_MAX != (0x7FFFFFFF) ) -#error Code was generated for compiler with different sized ulong/long. \ -Consider adjusting Test hardware word size settings on the \ -Hardware Implementation pane to match your compiler word sizes as \ -defined in limits.h of the compiler. Alternatively, you can \ -select the Test hardware is the same as production hardware option and \ -select the Enable portable word sizes option on the Code Generation > \ -Verification pane for ERT based targets, which will disable the \ -preprocessor word size checks. -#endif - -#if 0 - -/* Skip this size verification because of preprocessor limitation */ -#if ( ULLONG_MAX != (0xFFFFFFFFFFFFFFFFULL) ) || ( LLONG_MAX != (0x7FFFFFFFFFFFFFFFLL) ) -#error Code was generated for compiler with different sized ulong_long/long_long. \ -Consider adjusting Test hardware word size settings on the \ -Hardware Implementation pane to match your compiler word sizes as \ -defined in limits.h of the compiler. Alternatively, you can \ -select the Test hardware is the same as production hardware option and \ -select the Enable portable word sizes option on the Code Generation > \ -Verification pane for ERT based targets, which will disable the \ -preprocessor word size checks. -#endif -#endif - -uint8_T plook_u8s16_evencka(int16_T u, int16_T bp0, uint16_T bpSpace, uint32_T - maxIndex); -uint8_T plook_u8u16_evencka(uint16_T u, uint16_T bp0, uint16_T bpSpace, uint32_T - maxIndex); -int32_T div_nde_s32_floor(int32_T numerator, int32_T denominator); -extern void Counter_Init(DW_Counter *localDW, int16_T rtp_z_cntInit); -extern int16_T Counter(int16_T rtu_inc, int16_T rtu_max, boolean_T rtu_rst, - DW_Counter *localDW); -extern void Low_Pass_Filter_Reset(DW_Low_Pass_Filter *localDW); -extern void Low_Pass_Filter(const int16_T rtu_u[2], uint16_T rtu_coef, int16_T - rty_y[2], DW_Low_Pass_Filter *localDW); -extern void Counter_b_Init(DW_Counter_b *localDW, uint16_T rtp_z_cntInit); -extern void Counter_n(uint16_T rtu_inc, uint16_T rtu_max, boolean_T rtu_rst, - uint16_T *rty_cnt, DW_Counter_b *localDW); -extern void either_edge(boolean_T rtu_u, boolean_T *rty_y, DW_either_edge - *localDW); -extern void Debounce_Filter_Init(DW_Debounce_Filter *localDW); -extern void Debounce_Filter(boolean_T rtu_u, uint16_T rtu_tAcv, uint16_T - rtu_tDeacv, boolean_T *rty_y, DW_Debounce_Filter *localDW); -extern void I_backCalc_fixdt_Init(DW_I_backCalc_fixdt *localDW, int32_T - rtp_yInit); -extern void I_backCalc_fixdt_Reset(DW_I_backCalc_fixdt *localDW, int32_T - rtp_yInit); -extern void I_backCalc_fixdt(int16_T rtu_err, uint16_T rtu_I, uint16_T rtu_Kb, - int16_T rtu_satMax, int16_T rtu_satMin, int16_T *rty_out, DW_I_backCalc_fixdt * - localDW); -extern void PI_clamp_fixdt_Init(DW_PI_clamp_fixdt *localDW); -extern void PI_clamp_fixdt_Reset(DW_PI_clamp_fixdt *localDW); -extern void PI_clamp_fixdt(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, - int32_T rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T - rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt *localDW); -extern void PI_clamp_fixdt_d_Init(DW_PI_clamp_fixdt_m *localDW); -extern void PI_clamp_fixdt_b_Reset(DW_PI_clamp_fixdt_m *localDW); -extern void PI_clamp_fixdt_l(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, - int16_T rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T - rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt_m *localDW); -extern void PI_clamp_fixdt_f_Init(DW_PI_clamp_fixdt_g *localDW); -extern void PI_clamp_fixdt_g_Reset(DW_PI_clamp_fixdt_g *localDW); -extern void PI_clamp_fixdt_k(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, - int16_T rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T - rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt_g *localDW); -uint8_T plook_u8s16_evencka(int16_T u, int16_T bp0, uint16_T bpSpace, uint32_T - maxIndex) -{ - uint8_T bpIndex; - uint16_T fbpIndex; - - /* Prelookup - Index only - Index Search method: 'even' - Extrapolation method: 'Clip' - Use previous index: 'off' - Use last breakpoint for index at or above upper limit: 'on' - Remove protection against out-of-range input in generated code: 'off' - */ - if (u <= bp0) { - bpIndex = 0U; - } else { - fbpIndex = (uint16_T)((uint32_T)(uint16_T)(u - bp0) / bpSpace); - if (fbpIndex < maxIndex) { - bpIndex = (uint8_T)fbpIndex; - } else { - bpIndex = (uint8_T)maxIndex; - } - } - - return bpIndex; -} - -uint8_T plook_u8u16_evencka(uint16_T u, uint16_T bp0, uint16_T bpSpace, uint32_T - maxIndex) -{ - uint8_T bpIndex; - uint16_T fbpIndex; - - /* Prelookup - Index only - Index Search method: 'even' - Extrapolation method: 'Clip' - Use previous index: 'off' - Use last breakpoint for index at or above upper limit: 'on' - Remove protection against out-of-range input in generated code: 'off' - */ - if (u <= bp0) { - bpIndex = 0U; - } else { - fbpIndex = (uint16_T)((uint32_T)(uint16_T)((uint32_T)u - bp0) / bpSpace); - if (fbpIndex < maxIndex) { - bpIndex = (uint8_T)fbpIndex; - } else { - bpIndex = (uint8_T)maxIndex; - } - } - - return bpIndex; -} - -int32_T div_nde_s32_floor(int32_T numerator, int32_T denominator) -{ - return (((numerator < 0) != (denominator < 0)) && (numerator % denominator != - 0) ? -1 : 0) + numerator / denominator; -} - -/* System initialize for atomic system: '/Counter' */ -void Counter_Init(DW_Counter *localDW, int16_T rtp_z_cntInit) -{ - /* InitializeConditions for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = rtp_z_cntInit; -} - -/* Output and update for atomic system: '/Counter' */ -int16_T Counter(int16_T rtu_inc, int16_T rtu_max, boolean_T rtu_rst, DW_Counter * - localDW) -{ - int16_T rtu_rst_0; - int16_T rty_cnt_0; - - /* Switch: '/Switch1' incorporates: - * Constant: '/Constant23' - * UnitDelay: '/UnitDelay' - */ - if (rtu_rst) { - rtu_rst_0 = 0; - } else { - rtu_rst_0 = localDW->UnitDelay_DSTATE; - } - - /* End of Switch: '/Switch1' */ - - /* Sum: '/Sum1' */ - rty_cnt_0 = (int16_T)(rtu_inc + rtu_rst_0); - - /* MinMax: '/MinMax' */ - if (rty_cnt_0 < rtu_max) { - /* Update for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = rty_cnt_0; - } else { - /* Update for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = rtu_max; - } - - /* End of MinMax: '/MinMax' */ - return rty_cnt_0; -} - -/* System reset for atomic system: '/Low_Pass_Filter' */ -void Low_Pass_Filter_Reset(DW_Low_Pass_Filter *localDW) -{ - /* InitializeConditions for UnitDelay: '/UnitDelay1' */ - localDW->UnitDelay1_DSTATE[0] = 0; - localDW->UnitDelay1_DSTATE[1] = 0; -} - -/* Output and update for atomic system: '/Low_Pass_Filter' */ -void Low_Pass_Filter(const int16_T rtu_u[2], uint16_T rtu_coef, int16_T rty_y[2], - DW_Low_Pass_Filter *localDW) -{ - int32_T rtb_Sum3_g; - - /* Sum: '/Sum2' incorporates: - * UnitDelay: '/UnitDelay1' - */ - rtb_Sum3_g = rtu_u[0] - (localDW->UnitDelay1_DSTATE[0] >> 16); - if (rtb_Sum3_g > 32767) { - rtb_Sum3_g = 32767; - } else { - if (rtb_Sum3_g < -32768) { - rtb_Sum3_g = -32768; - } - } - - /* Sum: '/Sum3' incorporates: - * Product: '/Divide3' - * Sum: '/Sum2' - * UnitDelay: '/UnitDelay1' - */ - rtb_Sum3_g = rtu_coef * rtb_Sum3_g + localDW->UnitDelay1_DSTATE[0]; - - /* DataTypeConversion: '/Data Type Conversion' */ - rty_y[0] = (int16_T)(rtb_Sum3_g >> 16); - - /* Update for UnitDelay: '/UnitDelay1' */ - localDW->UnitDelay1_DSTATE[0] = rtb_Sum3_g; - - /* Sum: '/Sum2' incorporates: - * UnitDelay: '/UnitDelay1' - */ - rtb_Sum3_g = rtu_u[1] - (localDW->UnitDelay1_DSTATE[1] >> 16); - if (rtb_Sum3_g > 32767) { - rtb_Sum3_g = 32767; - } else { - if (rtb_Sum3_g < -32768) { - rtb_Sum3_g = -32768; - } - } - - /* Sum: '/Sum3' incorporates: - * Product: '/Divide3' - * Sum: '/Sum2' - * UnitDelay: '/UnitDelay1' - */ - rtb_Sum3_g = rtu_coef * rtb_Sum3_g + localDW->UnitDelay1_DSTATE[1]; - - /* DataTypeConversion: '/Data Type Conversion' */ - rty_y[1] = (int16_T)(rtb_Sum3_g >> 16); - - /* Update for UnitDelay: '/UnitDelay1' */ - localDW->UnitDelay1_DSTATE[1] = rtb_Sum3_g; -} - -/* - * System initialize for atomic system: - * '/Counter' - * '/Counter' - */ -void Counter_b_Init(DW_Counter_b *localDW, uint16_T rtp_z_cntInit) -{ - /* InitializeConditions for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = rtp_z_cntInit; -} - -/* - * Output and update for atomic system: - * '/Counter' - * '/Counter' - */ -void Counter_n(uint16_T rtu_inc, uint16_T rtu_max, boolean_T rtu_rst, uint16_T - *rty_cnt, DW_Counter_b *localDW) -{ - uint16_T rtu_rst_0; - - /* Switch: '/Switch1' incorporates: - * Constant: '/Constant23' - * UnitDelay: '/UnitDelay' - */ - if (rtu_rst) { - rtu_rst_0 = 0U; - } else { - rtu_rst_0 = localDW->UnitDelay_DSTATE; - } - - /* End of Switch: '/Switch1' */ - - /* Sum: '/Sum1' */ - *rty_cnt = (uint16_T)((uint32_T)rtu_inc + rtu_rst_0); - - /* MinMax: '/MinMax' */ - if (*rty_cnt < rtu_max) { - /* Update for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = *rty_cnt; - } else { - /* Update for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = rtu_max; - } - - /* End of MinMax: '/MinMax' */ -} - -/* - * Output and update for atomic system: - * '/either_edge' - * '/either_edge' - */ -void either_edge(boolean_T rtu_u, boolean_T *rty_y, DW_either_edge *localDW) -{ - /* RelationalOperator: '/Relational Operator' incorporates: - * UnitDelay: '/UnitDelay' - */ - *rty_y = (rtu_u != localDW->UnitDelay_DSTATE); - - /* Update for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = rtu_u; -} - -/* System initialize for atomic system: '/Debounce_Filter' */ -void Debounce_Filter_Init(DW_Debounce_Filter *localDW) -{ - /* SystemInitialize for IfAction SubSystem: '/Qualification' */ - - /* SystemInitialize for Atomic SubSystem: '/Counter' */ - Counter_b_Init(&localDW->Counter_n1, 0U); - - /* End of SystemInitialize for SubSystem: '/Counter' */ - - /* End of SystemInitialize for SubSystem: '/Qualification' */ - - /* SystemInitialize for IfAction SubSystem: '/Dequalification' */ - - /* SystemInitialize for Atomic SubSystem: '/Counter' */ - Counter_b_Init(&localDW->Counter_e, 0U); - - /* End of SystemInitialize for SubSystem: '/Counter' */ - - /* End of SystemInitialize for SubSystem: '/Dequalification' */ -} - -/* Output and update for atomic system: '/Debounce_Filter' */ -void Debounce_Filter(boolean_T rtu_u, uint16_T rtu_tAcv, uint16_T rtu_tDeacv, - boolean_T *rty_y, DW_Debounce_Filter *localDW) -{ - uint16_T rtb_Sum1_n; - boolean_T rtb_RelationalOperator_g; - - /* Outputs for Atomic SubSystem: '/either_edge' */ - either_edge(rtu_u, &rtb_RelationalOperator_g, &localDW->either_edge_p); - - /* End of Outputs for SubSystem: '/either_edge' */ - - /* If: '/If2' incorporates: - * Constant: '/Constant6' - * Constant: '/Constant6' - * Inport: '/yPrev' - * Logic: '/Logical Operator1' - * Logic: '/Logical Operator2' - * Logic: '/Logical Operator3' - * Logic: '/Logical Operator4' - * UnitDelay: '/UnitDelay' - */ - if (rtu_u && (!localDW->UnitDelay_DSTATE)) { - /* Outputs for IfAction SubSystem: '/Qualification' incorporates: - * ActionPort: '/Action Port' - */ - - /* Outputs for Atomic SubSystem: '/Counter' */ - Counter_n(1U, rtu_tAcv, rtb_RelationalOperator_g, &rtb_Sum1_n, - &localDW->Counter_n1); - - /* End of Outputs for SubSystem: '/Counter' */ - - /* Switch: '/Switch2' incorporates: - * Constant: '/Constant6' - * RelationalOperator: '/Relational Operator2' - */ - *rty_y = ((rtb_Sum1_n > rtu_tAcv) || localDW->UnitDelay_DSTATE); - - /* End of Outputs for SubSystem: '/Qualification' */ - } else if ((!rtu_u) && localDW->UnitDelay_DSTATE) { - /* Outputs for IfAction SubSystem: '/Dequalification' incorporates: - * ActionPort: '/Action Port' - */ - - /* Outputs for Atomic SubSystem: '/Counter' */ - Counter_n(1U, rtu_tDeacv, rtb_RelationalOperator_g, &rtb_Sum1_n, - &localDW->Counter_e); - - /* End of Outputs for SubSystem: '/Counter' */ - - /* Switch: '/Switch2' incorporates: - * Constant: '/Constant6' - * RelationalOperator: '/Relational Operator2' - */ - *rty_y = ((!(rtb_Sum1_n > rtu_tDeacv)) && localDW->UnitDelay_DSTATE); - - /* End of Outputs for SubSystem: '/Dequalification' */ - } else { - /* Outputs for IfAction SubSystem: '/Default' incorporates: - * ActionPort: '/Action Port' - */ - *rty_y = localDW->UnitDelay_DSTATE; - - /* End of Outputs for SubSystem: '/Default' */ - } - - /* End of If: '/If2' */ - - /* Update for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = *rty_y; -} - -/* - * System initialize for atomic system: - * '/I_backCalc_fixdt' - * '/I_backCalc_fixdt1' - * '/I_backCalc_fixdt' - */ -void I_backCalc_fixdt_Init(DW_I_backCalc_fixdt *localDW, int32_T rtp_yInit) -{ - /* InitializeConditions for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE_m = rtp_yInit; -} - -/* - * System reset for atomic system: - * '/I_backCalc_fixdt' - * '/I_backCalc_fixdt1' - * '/I_backCalc_fixdt' - */ -void I_backCalc_fixdt_Reset(DW_I_backCalc_fixdt *localDW, int32_T rtp_yInit) -{ - /* InitializeConditions for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE = 0; - - /* InitializeConditions for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE_m = rtp_yInit; -} - -/* - * Output and update for atomic system: - * '/I_backCalc_fixdt' - * '/I_backCalc_fixdt1' - * '/I_backCalc_fixdt' - */ -void I_backCalc_fixdt(int16_T rtu_err, uint16_T rtu_I, uint16_T rtu_Kb, int16_T - rtu_satMax, int16_T rtu_satMin, int16_T *rty_out, - DW_I_backCalc_fixdt *localDW) -{ - int32_T rtb_Sum1_o; - int16_T rtb_DataTypeConversion1_gf; - - /* Sum: '/Sum2' incorporates: - * Product: '/Divide2' - * UnitDelay: '/UnitDelay' - */ - rtb_Sum1_o = (rtu_err * rtu_I) >> 4; - if ((rtb_Sum1_o < 0) && (localDW->UnitDelay_DSTATE < MIN_int32_T - rtb_Sum1_o)) - { - rtb_Sum1_o = MIN_int32_T; - } else if ((rtb_Sum1_o > 0) && (localDW->UnitDelay_DSTATE > MAX_int32_T - - rtb_Sum1_o)) { - rtb_Sum1_o = MAX_int32_T; - } else { - rtb_Sum1_o += localDW->UnitDelay_DSTATE; - } - - /* End of Sum: '/Sum2' */ - - /* Sum: '/Sum1' incorporates: - * UnitDelay: '/UnitDelay' - */ - rtb_Sum1_o += localDW->UnitDelay_DSTATE_m; - - /* DataTypeConversion: '/Data Type Conversion1' */ - rtb_DataTypeConversion1_gf = (int16_T)(rtb_Sum1_o >> 12); - - /* Switch: '/Switch2' incorporates: - * RelationalOperator: '/LowerRelop1' - * RelationalOperator: '/UpperRelop' - * Switch: '/Switch' - */ - if (rtb_DataTypeConversion1_gf > rtu_satMax) { - *rty_out = rtu_satMax; - } else if (rtb_DataTypeConversion1_gf < rtu_satMin) { - /* Switch: '/Switch' */ - *rty_out = rtu_satMin; - } else { - *rty_out = rtb_DataTypeConversion1_gf; - } - - /* End of Switch: '/Switch2' */ - - /* Update for UnitDelay: '/UnitDelay' incorporates: - * Product: '/Divide1' - * Sum: '/Sum3' - */ - localDW->UnitDelay_DSTATE = (int16_T)(*rty_out - rtb_DataTypeConversion1_gf) * - rtu_Kb; - - /* Update for UnitDelay: '/UnitDelay' */ - localDW->UnitDelay_DSTATE_m = rtb_Sum1_o; -} - -/* System initialize for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt_Init(DW_PI_clamp_fixdt *localDW) -{ - /* InitializeConditions for Delay: '/Resettable Delay' */ - localDW->icLoad = 1U; -} - -/* System reset for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt_Reset(DW_PI_clamp_fixdt *localDW) -{ - /* InitializeConditions for UnitDelay: '/UnitDelay1' */ - localDW->UnitDelay1_DSTATE = false; - - /* InitializeConditions for Delay: '/Resettable Delay' */ - localDW->icLoad = 1U; -} - -/* Output and update for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, int32_T - rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T - rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt - *localDW) -{ - boolean_T rtb_LowerRelop1_c0; - boolean_T rtb_UpperRelop_f; - int32_T rtb_Sum1_p0; - int32_T q0; - int32_T tmp; - int16_T tmp_0; - - /* Sum: '/Sum2' incorporates: - * Product: '/Divide2' - */ - q0 = rtu_err * rtu_I; - if ((q0 < 0) && (rtu_ext_limProt < MIN_int32_T - q0)) { - q0 = MIN_int32_T; - } else if ((q0 > 0) && (rtu_ext_limProt > MAX_int32_T - q0)) { - q0 = MAX_int32_T; - } else { - q0 += rtu_ext_limProt; - } - - /* Delay: '/Resettable Delay' */ - if (localDW->icLoad != 0) { - localDW->ResettableDelay_DSTATE = rtu_init; - } - - /* Switch: '/Switch1' incorporates: - * Constant: '/Constant' - * Sum: '/Sum2' - * UnitDelay: '/UnitDelay1' - */ - if (localDW->UnitDelay1_DSTATE) { - tmp = 0; - } else { - tmp = q0; - } - - /* End of Switch: '/Switch1' */ - - /* Sum: '/Sum1' incorporates: - * Delay: '/Resettable Delay' - */ - rtb_Sum1_p0 = tmp + localDW->ResettableDelay_DSTATE; - - /* Product: '/Divide5' */ - tmp = (rtu_err * rtu_P) >> 11; - if (tmp > 32767) { - tmp = 32767; - } else { - if (tmp < -32768) { - tmp = -32768; - } - } - - /* Sum: '/Sum1' incorporates: - * DataTypeConversion: '/Data Type Conversion1' - * Product: '/Divide5' - */ - tmp = (((rtb_Sum1_p0 >> 16) << 1) + tmp) >> 1; - if (tmp > 32767) { - tmp = 32767; - } else { - if (tmp < -32768) { - tmp = -32768; - } - } - - /* RelationalOperator: '/LowerRelop1' incorporates: - * Sum: '/Sum1' - */ - rtb_LowerRelop1_c0 = ((int16_T)tmp > rtu_satMax); - - /* RelationalOperator: '/UpperRelop' incorporates: - * Sum: '/Sum1' - */ - rtb_UpperRelop_f = ((int16_T)tmp < rtu_satMin); - - /* Switch: '/Switch1' incorporates: - * Sum: '/Sum1' - * Switch: '/Switch3' - */ - if (rtb_LowerRelop1_c0) { - *rty_out = rtu_satMax; - } else if (rtb_UpperRelop_f) { - /* Switch: '/Switch3' */ - *rty_out = rtu_satMin; - } else { - *rty_out = (int16_T)tmp; - } - - /* End of Switch: '/Switch1' */ - - /* Signum: '/SignDeltaU2' incorporates: - * Sum: '/Sum2' - */ - if (q0 < 0) { - q0 = -1; - } else { - q0 = (q0 > 0); - } - - /* End of Signum: '/SignDeltaU2' */ - - /* Signum: '/SignDeltaU3' incorporates: - * Sum: '/Sum1' - */ - if ((int16_T)tmp < 0) { - tmp_0 = -1; - } else { - tmp_0 = (int16_T)((int16_T)tmp > 0); - } - - /* End of Signum: '/SignDeltaU3' */ - - /* Update for UnitDelay: '/UnitDelay1' incorporates: - * DataTypeConversion: '/DataTypeConv4' - * Logic: '/AND1' - * Logic: '/AND1' - * RelationalOperator: '/Equal1' - */ - localDW->UnitDelay1_DSTATE = ((q0 == tmp_0) && (rtb_LowerRelop1_c0 || - rtb_UpperRelop_f)); - - /* Update for Delay: '/Resettable Delay' */ - localDW->icLoad = 0U; - localDW->ResettableDelay_DSTATE = rtb_Sum1_p0; -} - -/* System initialize for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt_d_Init(DW_PI_clamp_fixdt_m *localDW) -{ - /* InitializeConditions for Delay: '/Resettable Delay' */ - localDW->icLoad = 1U; -} - -/* System reset for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt_b_Reset(DW_PI_clamp_fixdt_m *localDW) -{ - /* InitializeConditions for UnitDelay: '/UnitDelay1' */ - localDW->UnitDelay1_DSTATE = false; - - /* InitializeConditions for Delay: '/Resettable Delay' */ - localDW->icLoad = 1U; -} - -/* Output and update for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt_l(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, int16_T - rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T - rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt_m - *localDW) -{ - boolean_T rtb_LowerRelop1_l; - boolean_T rtb_UpperRelop_l; - int32_T rtb_Sum1_ni; - int32_T q0; - int32_T tmp; - int16_T tmp_0; - - /* Sum: '/Sum2' incorporates: - * Product: '/Divide2' - */ - q0 = rtu_err * rtu_I; - if ((q0 < 0) && (rtu_ext_limProt < MIN_int32_T - q0)) { - q0 = MIN_int32_T; - } else if ((q0 > 0) && (rtu_ext_limProt > MAX_int32_T - q0)) { - q0 = MAX_int32_T; - } else { - q0 += rtu_ext_limProt; - } - - /* Delay: '/Resettable Delay' */ - if (localDW->icLoad != 0) { - localDW->ResettableDelay_DSTATE = rtu_init << 16; - } - - /* Switch: '/Switch1' incorporates: - * Constant: '/Constant' - * Sum: '/Sum2' - * UnitDelay: '/UnitDelay1' - */ - if (localDW->UnitDelay1_DSTATE) { - tmp = 0; - } else { - tmp = q0; - } - - /* End of Switch: '/Switch1' */ - - /* Sum: '/Sum1' incorporates: - * Delay: '/Resettable Delay' - */ - rtb_Sum1_ni = tmp + localDW->ResettableDelay_DSTATE; - - /* Product: '/Divide5' */ - tmp = (rtu_err * rtu_P) >> 11; - if (tmp > 32767) { - tmp = 32767; - } else { - if (tmp < -32768) { - tmp = -32768; - } - } - - /* Sum: '/Sum1' incorporates: - * DataTypeConversion: '/Data Type Conversion1' - * Product: '/Divide5' - */ - tmp = (((rtb_Sum1_ni >> 16) << 1) + tmp) >> 1; - if (tmp > 32767) { - tmp = 32767; - } else { - if (tmp < -32768) { - tmp = -32768; - } - } - - /* RelationalOperator: '/LowerRelop1' incorporates: - * Sum: '/Sum1' - */ - rtb_LowerRelop1_l = ((int16_T)tmp > rtu_satMax); - - /* RelationalOperator: '/UpperRelop' incorporates: - * Sum: '/Sum1' - */ - rtb_UpperRelop_l = ((int16_T)tmp < rtu_satMin); - - /* Switch: '/Switch1' incorporates: - * Sum: '/Sum1' - * Switch: '/Switch3' - */ - if (rtb_LowerRelop1_l) { - *rty_out = rtu_satMax; - } else if (rtb_UpperRelop_l) { - /* Switch: '/Switch3' */ - *rty_out = rtu_satMin; - } else { - *rty_out = (int16_T)tmp; - } - - /* End of Switch: '/Switch1' */ - - /* Signum: '/SignDeltaU2' incorporates: - * Sum: '/Sum2' - */ - if (q0 < 0) { - q0 = -1; - } else { - q0 = (q0 > 0); - } - - /* End of Signum: '/SignDeltaU2' */ - - /* Signum: '/SignDeltaU3' incorporates: - * Sum: '/Sum1' - */ - if ((int16_T)tmp < 0) { - tmp_0 = -1; - } else { - tmp_0 = (int16_T)((int16_T)tmp > 0); - } - - /* End of Signum: '/SignDeltaU3' */ - - /* Update for UnitDelay: '/UnitDelay1' incorporates: - * DataTypeConversion: '/DataTypeConv4' - * Logic: '/AND1' - * Logic: '/AND1' - * RelationalOperator: '/Equal1' - */ - localDW->UnitDelay1_DSTATE = ((q0 == tmp_0) && (rtb_LowerRelop1_l || - rtb_UpperRelop_l)); - - /* Update for Delay: '/Resettable Delay' */ - localDW->icLoad = 0U; - localDW->ResettableDelay_DSTATE = rtb_Sum1_ni; -} - -/* System initialize for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt_f_Init(DW_PI_clamp_fixdt_g *localDW) -{ - /* InitializeConditions for Delay: '/Resettable Delay' */ - localDW->icLoad = 1U; -} - -/* System reset for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt_g_Reset(DW_PI_clamp_fixdt_g *localDW) -{ - /* InitializeConditions for UnitDelay: '/UnitDelay1' */ - localDW->UnitDelay1_DSTATE = false; - - /* InitializeConditions for Delay: '/Resettable Delay' */ - localDW->icLoad = 1U; -} - -/* Output and update for atomic system: '/PI_clamp_fixdt' */ -void PI_clamp_fixdt_k(int16_T rtu_err, uint16_T rtu_P, uint16_T rtu_I, int16_T - rtu_init, int16_T rtu_satMax, int16_T rtu_satMin, int32_T - rtu_ext_limProt, int16_T *rty_out, DW_PI_clamp_fixdt_g - *localDW) -{ - boolean_T rtb_LowerRelop1_i3; - boolean_T rtb_UpperRelop_i; - int16_T rtb_Sum1_bm; - int16_T tmp; - int32_T tmp_0; - int32_T q0; - - /* Sum: '/Sum2' incorporates: - * Product: '/Divide2' - */ - q0 = rtu_err * rtu_I; - if ((q0 < 0) && (rtu_ext_limProt < MIN_int32_T - q0)) { - q0 = MIN_int32_T; - } else if ((q0 > 0) && (rtu_ext_limProt > MAX_int32_T - q0)) { - q0 = MAX_int32_T; - } else { - q0 += rtu_ext_limProt; - } - - /* Delay: '/Resettable Delay' */ - if (localDW->icLoad != 0) { - localDW->ResettableDelay_DSTATE = rtu_init; - } - - /* Switch: '/Switch1' incorporates: - * Constant: '/Constant' - * Sum: '/Sum2' - * UnitDelay: '/UnitDelay1' - */ - if (localDW->UnitDelay1_DSTATE) { - tmp = 0; - } else { - tmp = (int16_T)(((q0 < 0 ? 65535 : 0) + q0) >> 16); - } - - /* End of Switch: '/Switch1' */ - - /* Sum: '/Sum1' incorporates: - * Delay: '/Resettable Delay' - */ - rtb_Sum1_bm = (int16_T)(tmp + localDW->ResettableDelay_DSTATE); - - /* Product: '/Divide5' */ - tmp_0 = (rtu_err * rtu_P) >> 11; - if (tmp_0 > 32767) { - tmp_0 = 32767; - } else { - if (tmp_0 < -32768) { - tmp_0 = -32768; - } - } - - /* Sum: '/Sum1' incorporates: - * Product: '/Divide5' - */ - tmp_0 = ((rtb_Sum1_bm << 1) + tmp_0) >> 1; - if (tmp_0 > 32767) { - tmp_0 = 32767; - } else { - if (tmp_0 < -32768) { - tmp_0 = -32768; - } - } - - /* RelationalOperator: '/LowerRelop1' incorporates: - * Sum: '/Sum1' - */ - rtb_LowerRelop1_i3 = ((int16_T)tmp_0 > rtu_satMax); - - /* RelationalOperator: '/UpperRelop' incorporates: - * Sum: '/Sum1' - */ - rtb_UpperRelop_i = ((int16_T)tmp_0 < rtu_satMin); - - /* Switch: '/Switch1' incorporates: - * Sum: '/Sum1' - * Switch: '/Switch3' - */ - if (rtb_LowerRelop1_i3) { - *rty_out = rtu_satMax; - } else if (rtb_UpperRelop_i) { - /* Switch: '/Switch3' */ - *rty_out = rtu_satMin; - } else { - *rty_out = (int16_T)tmp_0; - } - - /* End of Switch: '/Switch1' */ - - /* Signum: '/SignDeltaU2' incorporates: - * Sum: '/Sum2' - */ - if (q0 < 0) { - q0 = -1; - } else { - q0 = (q0 > 0); - } - - /* End of Signum: '/SignDeltaU2' */ - - /* Signum: '/SignDeltaU3' incorporates: - * Sum: '/Sum1' - */ - if ((int16_T)tmp_0 < 0) { - tmp = -1; - } else { - tmp = (int16_T)((int16_T)tmp_0 > 0); - } - - /* End of Signum: '/SignDeltaU3' */ - - /* Update for UnitDelay: '/UnitDelay1' incorporates: - * DataTypeConversion: '/DataTypeConv4' - * Logic: '/AND1' - * Logic: '/AND1' - * RelationalOperator: '/Equal1' - */ - localDW->UnitDelay1_DSTATE = ((q0 == tmp) && (rtb_LowerRelop1_i3 || - rtb_UpperRelop_i)); - - /* Update for Delay: '/Resettable Delay' */ - localDW->icLoad = 0U; - localDW->ResettableDelay_DSTATE = rtb_Sum1_bm; -} - -/* Model step function */ -void BLDC_controller_step(RT_MODEL *const rtM) -{ - P *rtP = ((P *) rtM->defaultParam); - DW *rtDW = ((DW *) rtM->dwork); - ExtU *rtU = (ExtU *) rtM->inputs; - ExtY *rtY = (ExtY *) rtM->outputs; - boolean_T rtb_LogicalOperator; - int8_T rtb_Sum2_h; - boolean_T rtb_RelationalOperator4_d; - boolean_T rtb_UnitDelay5_e; - uint8_T rtb_a_elecAngle_XA_g; - boolean_T rtb_LogicalOperator1_j; - boolean_T rtb_LogicalOperator2_p; - boolean_T rtb_RelationalOperator1_mv; - int16_T rtb_Switch1_l; - int16_T rtb_Saturation; - int16_T rtb_Saturation1; - int32_T rtb_Sum1_jt; - int16_T rtb_Merge_m; - int16_T rtb_Merge1; - uint16_T rtb_Divide14_e; - uint16_T rtb_Divide1_f; - int16_T rtb_TmpSignalConversionAtLow_Pa[2]; - int32_T rtb_Switch1; - int32_T rtb_Sum1; - int32_T rtb_Gain3; - uint8_T Sum; - int16_T Switch2; - int16_T Abs5; - int16_T DataTypeConversion2; - int16_T tmp[4]; - int8_T UnitDelay3; - - /* Outputs for Atomic SubSystem: '/BLDC_controller' */ - /* Sum: '/Sum' incorporates: - * Gain: '/g_Ha' - * Gain: '/g_Hb' - * Inport: '/b_hallA ' - * Inport: '/b_hallB' - * Inport: '/b_hallC' - */ - Sum = (uint8_T)((uint32_T)(uint8_T)((uint32_T)(uint8_T)(rtU->b_hallA << 2) + - (uint8_T)(rtU->b_hallB << 1)) + rtU->b_hallC); - - /* Logic: '/Logical Operator' incorporates: - * Inport: '/b_hallA ' - * Inport: '/b_hallB' - * Inport: '/b_hallC' - * UnitDelay: '/UnitDelay1' - * UnitDelay: '/UnitDelay2' - * UnitDelay: '/UnitDelay3' - */ - rtb_LogicalOperator = (boolean_T)((rtU->b_hallA != 0) ^ (rtU->b_hallB != 0) ^ - (rtU->b_hallC != 0) ^ (rtDW->UnitDelay3_DSTATE_fy != 0) ^ - (rtDW->UnitDelay1_DSTATE != 0)) ^ (rtDW->UnitDelay2_DSTATE_f != 0); - - /* If: '/If2' incorporates: - * If: '/If2' - * Inport: '/z_counterRawPrev' - * UnitDelay: '/UnitDelay3' - */ - if (rtb_LogicalOperator) { - /* Outputs for IfAction SubSystem: '/F01_03_Direction_Detection' incorporates: - * ActionPort: '/Action Port' - */ - /* UnitDelay: '/UnitDelay3' */ - UnitDelay3 = rtDW->Switch2_e; - - /* Sum: '/Sum2' incorporates: - * Constant: '/vec_hallToPos' - * Selector: '/Selector' - * UnitDelay: '/UnitDelay2' - */ - rtb_Sum2_h = (int8_T)(rtConstP.vec_hallToPos_Value[Sum] - - rtDW->UnitDelay2_DSTATE_b); - - /* Switch: '/Switch2' incorporates: - * Constant: '/Constant20' - * Constant: '/Constant23' - * Constant: '/Constant24' - * Constant: '/Constant8' - * Logic: '/Logical Operator3' - * RelationalOperator: '/Relational Operator1' - * RelationalOperator: '/Relational Operator6' - */ - if ((rtb_Sum2_h == 1) || (rtb_Sum2_h == -5)) { - rtDW->Switch2_e = 1; - } else { - rtDW->Switch2_e = -1; - } - - /* End of Switch: '/Switch2' */ - - /* Update for UnitDelay: '/UnitDelay2' incorporates: - * Constant: '/vec_hallToPos' - * Selector: '/Selector' - */ - rtDW->UnitDelay2_DSTATE_b = rtConstP.vec_hallToPos_Value[Sum]; - - /* End of Outputs for SubSystem: '/F01_03_Direction_Detection' */ - - /* Outputs for IfAction SubSystem: '/Raw_Motor_Speed_Estimation' incorporates: - * ActionPort: '/Action Port' - */ - rtDW->z_counterRawPrev = rtDW->UnitDelay3_DSTATE; - - /* Sum: '/Sum7' incorporates: - * Inport: '/z_counterRawPrev' - * UnitDelay: '/UnitDelay3' - * UnitDelay: '/UnitDelay4' - */ - Switch2 = (int16_T)(rtDW->z_counterRawPrev - rtDW->UnitDelay4_DSTATE); - - /* Abs: '/Abs2' */ - if (Switch2 < 0) { - rtb_Switch1_l = (int16_T)-Switch2; - } else { - rtb_Switch1_l = Switch2; - } - - /* End of Abs: '/Abs2' */ - - /* Relay: '/dz_cntTrnsDet' */ - if (rtb_Switch1_l >= rtP->dz_cntTrnsDetHi) { - rtDW->dz_cntTrnsDet_Mode = true; - } else { - if (rtb_Switch1_l <= rtP->dz_cntTrnsDetLo) { - rtDW->dz_cntTrnsDet_Mode = false; - } - } - - rtDW->dz_cntTrnsDet = rtDW->dz_cntTrnsDet_Mode; - - /* End of Relay: '/dz_cntTrnsDet' */ - - /* RelationalOperator: '/Relational Operator4' */ - rtb_RelationalOperator4_d = (rtDW->Switch2_e != UnitDelay3); - - /* Switch: '/Switch3' incorporates: - * Constant: '/Constant4' - * Logic: '/Logical Operator1' - * Switch: '/Switch1' - * Switch: '/Switch2' - * UnitDelay: '/UnitDelay1' - */ - if (rtb_RelationalOperator4_d && rtDW->UnitDelay1_DSTATE_n) { - rtb_Switch1_l = 0; - } else if (rtb_RelationalOperator4_d) { - /* Switch: '/Switch2' incorporates: - * UnitDelay: '/UnitDelay4' - */ - rtb_Switch1_l = rtDW->UnitDelay4_DSTATE_e; - } else if (rtDW->dz_cntTrnsDet) { - /* Switch: '/Switch1' incorporates: - * Constant: '/cf_speedCoef' - * Product: '/Divide14' - * Switch: '/Switch2' - */ - rtb_Switch1_l = (int16_T)((rtP->cf_speedCoef << 4) / - rtDW->z_counterRawPrev); - } else { - /* Switch: '/Switch1' incorporates: - * Constant: '/cf_speedCoef' - * Gain: '/g_Ha' - * Product: '/Divide13' - * Sum: '/Sum13' - * Switch: '/Switch2' - * UnitDelay: '/UnitDelay2' - * UnitDelay: '/UnitDelay3' - * UnitDelay: '/UnitDelay5' - */ - rtb_Switch1_l = (int16_T)(((uint16_T)(rtP->cf_speedCoef << 2) << 4) / - (int16_T)(((rtDW->UnitDelay2_DSTATE + rtDW->UnitDelay3_DSTATE_o) + - rtDW->UnitDelay5_DSTATE) + rtDW->z_counterRawPrev)); - } - - /* End of Switch: '/Switch3' */ - - /* Product: '/Divide11' */ - rtDW->Divide11 = (int16_T)(rtb_Switch1_l * rtDW->Switch2_e); - - /* Update for UnitDelay: '/UnitDelay4' */ - rtDW->UnitDelay4_DSTATE = rtDW->z_counterRawPrev; - - /* Update for UnitDelay: '/UnitDelay2' incorporates: - * UnitDelay: '/UnitDelay3' - */ - rtDW->UnitDelay2_DSTATE = rtDW->UnitDelay3_DSTATE_o; - - /* Update for UnitDelay: '/UnitDelay3' incorporates: - * UnitDelay: '/UnitDelay5' - */ - rtDW->UnitDelay3_DSTATE_o = rtDW->UnitDelay5_DSTATE; - - /* Update for UnitDelay: '/UnitDelay5' */ - rtDW->UnitDelay5_DSTATE = rtDW->z_counterRawPrev; - - /* Update for UnitDelay: '/UnitDelay1' */ - rtDW->UnitDelay1_DSTATE_n = rtb_RelationalOperator4_d; - - /* End of Outputs for SubSystem: '/Raw_Motor_Speed_Estimation' */ - } - - /* End of If: '/If2' */ - - /* Outputs for Atomic SubSystem: '/Counter' */ - - /* Constant: '/Constant6' incorporates: - * Constant: '/z_maxCntRst2' - */ - rtb_Switch1_l = (int16_T) Counter(1, rtP->z_maxCntRst, rtb_LogicalOperator, - &rtDW->Counter_e); - - /* End of Outputs for SubSystem: '/Counter' */ - - /* Switch: '/Switch2' incorporates: - * Constant: '/Constant4' - * Constant: '/z_maxCntRst' - * RelationalOperator: '/Relational Operator2' - */ - if (rtb_Switch1_l > rtP->z_maxCntRst) { - Switch2 = 0; - } else { - Switch2 = rtDW->Divide11; - } - - /* End of Switch: '/Switch2' */ - - /* Abs: '/Abs5' */ - if (Switch2 < 0) { - Abs5 = (int16_T)-Switch2; - } else { - Abs5 = Switch2; - } - - /* End of Abs: '/Abs5' */ - - /* Relay: '/n_commDeacv' */ - if (Abs5 >= rtP->n_commDeacvHi) { - rtDW->n_commDeacv_Mode = true; - } else { - if (Abs5 <= rtP->n_commAcvLo) { - rtDW->n_commDeacv_Mode = false; - } - } - - /* Logic: '/Logical Operator3' incorporates: - * Constant: '/b_angleMeasEna' - * Logic: '/Logical Operator1' - * Logic: '/Logical Operator2' - * Relay: '/n_commDeacv' - */ - rtb_LogicalOperator = (rtP->b_angleMeasEna || (rtDW->n_commDeacv_Mode && - (!rtDW->dz_cntTrnsDet))); - - /* UnitDelay: '/UnitDelay2' */ - rtb_RelationalOperator4_d = rtDW->UnitDelay2_DSTATE_c; - - /* UnitDelay: '/UnitDelay5' */ - rtb_UnitDelay5_e = rtDW->UnitDelay5_DSTATE_m; - - /* DataTypeConversion: '/Data Type Conversion2' incorporates: - * Inport: '/r_inpTgt' - */ - DataTypeConversion2 = (int16_T)(rtU->r_inpTgt << 4); - - /* Saturate: '/Saturation' incorporates: - * Inport: '/i_phaAB' - */ - rtb_Gain3 = rtU->i_phaAB << 4; - if (rtb_Gain3 >= 27200) { - rtb_Saturation = 27200; - } else if (rtb_Gain3 <= -27200) { - rtb_Saturation = -27200; - } else { - rtb_Saturation = (int16_T)(rtU->i_phaAB << 4); - } - - /* End of Saturate: '/Saturation' */ - - /* Saturate: '/Saturation1' incorporates: - * Inport: '/i_phaBC' - */ - rtb_Gain3 = rtU->i_phaBC << 4; - if (rtb_Gain3 >= 27200) { - rtb_Saturation1 = 27200; - } else if (rtb_Gain3 <= -27200) { - rtb_Saturation1 = -27200; - } else { - rtb_Saturation1 = (int16_T)(rtU->i_phaBC << 4); - } - - /* End of Saturate: '/Saturation1' */ - - /* If: '/If1' incorporates: - * Constant: '/b_angleMeasEna' - */ - if (!rtP->b_angleMeasEna) { - /* Outputs for IfAction SubSystem: '/F01_05_Electrical_Angle_Estimation' incorporates: - * ActionPort: '/Action Port' - */ - /* Switch: '/Switch2' incorporates: - * Constant: '/Constant16' - * Product: '/Divide1' - * Product: '/Divide3' - * RelationalOperator: '/Relational Operator7' - * Sum: '/Sum3' - * Switch: '/Switch3' - */ - if (rtb_LogicalOperator) { - /* MinMax: '/MinMax' */ - rtb_Merge_m = rtb_Switch1_l; - if (!(rtb_Merge_m < rtDW->z_counterRawPrev)) { - rtb_Merge_m = rtDW->z_counterRawPrev; - } - - /* End of MinMax: '/MinMax' */ - - /* Switch: '/Switch3' incorporates: - * Constant: '/vec_hallToPos' - * Constant: '/Constant16' - * RelationalOperator: '/Relational Operator7' - * Selector: '/Selector' - * Sum: '/Sum1' - */ - if (rtDW->Switch2_e == 1) { - rtb_Sum2_h = rtConstP.vec_hallToPos_Value[Sum]; - } else { - rtb_Sum2_h = (int8_T)(rtConstP.vec_hallToPos_Value[Sum] + 1); - } - - rtb_Merge_m = (int16_T)(((int16_T)((int16_T)((rtb_Merge_m << 14) / - rtDW->z_counterRawPrev) * rtDW->Switch2_e) + (rtb_Sum2_h << 14)) >> 2); - } else { - if (rtDW->Switch2_e == 1) { - /* Switch: '/Switch3' incorporates: - * Constant: '/vec_hallToPos' - * Selector: '/Selector' - */ - rtb_Sum2_h = rtConstP.vec_hallToPos_Value[Sum]; - } else { - /* Switch: '/Switch3' incorporates: - * Constant: '/vec_hallToPos' - * Selector: '/Selector' - * Sum: '/Sum1' - */ - rtb_Sum2_h = (int8_T)(rtConstP.vec_hallToPos_Value[Sum] + 1); - } - - rtb_Merge_m = (int16_T)(rtb_Sum2_h << 12); - } - - /* End of Switch: '/Switch2' */ - - /* MinMax: '/MinMax1' incorporates: - * Constant: '/Constant1' - */ - if (!(rtb_Merge_m > 0)) { - rtb_Merge_m = 0; - } - - /* End of MinMax: '/MinMax1' */ - - /* SignalConversion: '/Signal Conversion2' incorporates: - * Product: '/Divide2' - */ - rtb_Merge_m = (int16_T)((15 * rtb_Merge_m) >> 4); - - /* End of Outputs for SubSystem: '/F01_05_Electrical_Angle_Estimation' */ - } else { - /* Outputs for IfAction SubSystem: '/F01_06_Electrical_Angle_Measurement' incorporates: - * ActionPort: '/Action Port' - */ - /* Sum: '/Sum1' incorporates: - * Constant: '/Constant2' - * Constant: '/n_polePairs' - * Inport: '/a_mechAngle' - * Product: '/Divide' - */ - rtb_Sum1_jt = rtU->a_mechAngle * rtP->n_polePairs - 480; - - /* DataTypeConversion: '/Data Type Conversion20' incorporates: - * Constant: '/a_elecPeriod' - * Product: '/Divide2' - * Product: '/Divide3' - * Sum: '/Sum3' - */ - rtb_Merge_m = (int16_T)((int16_T)(rtb_Sum1_jt - ((int16_T)((int16_T) - div_nde_s32_floor(rtb_Sum1_jt, 5760) * 360) << 4)) << 2); - - /* End of Outputs for SubSystem: '/F01_06_Electrical_Angle_Measurement' */ - } - - /* End of If: '/If1' */ - - /* If: '/If1' incorporates: - * Constant: '/z_ctrlTypSel' - */ - rtb_Sum2_h = rtDW->If1_ActiveSubsystem; - UnitDelay3 = -1; - if (rtP->z_ctrlTypSel == 2) { - UnitDelay3 = 0; - } - - rtDW->If1_ActiveSubsystem = UnitDelay3; - if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { - /* Disable for If: '/If2' */ - if (rtDW->If2_ActiveSubsystem_a == 0) { - /* Disable for Outport: '/iq' */ - rtDW->DataTypeConversion[0] = 0; - - /* Disable for Outport: '/iqAbs' */ - rtDW->Abs5_h = 0; - - /* Disable for Outport: '/id' */ - rtDW->DataTypeConversion[1] = 0; - } - - rtDW->If2_ActiveSubsystem_a = -1; - - /* End of Disable for If: '/If2' */ - - /* Disable for Outport: '/r_sin' */ - rtDW->r_sin_M1 = 0; - - /* Disable for Outport: '/r_cos' */ - rtDW->r_cos_M1 = 0; - - /* Disable for Outport: '/iq' */ - rtDW->DataTypeConversion[0] = 0; - - /* Disable for Outport: '/id' */ - rtDW->DataTypeConversion[1] = 0; - - /* Disable for Outport: '/iqAbs' */ - rtDW->Abs5_h = 0; - } - - if (UnitDelay3 == 0) { - /* Outputs for IfAction SubSystem: '/Clarke_Park_Transform_Forward' incorporates: - * ActionPort: '/Action Port' - */ - /* If: '/If1' incorporates: - * Constant: '/z_selPhaCurMeasABC' - */ - if (rtP->z_selPhaCurMeasABC == 0) { - /* Outputs for IfAction SubSystem: '/Clarke_PhasesAB' incorporates: - * ActionPort: '/Action Port' - */ - /* Gain: '/Gain4' */ - rtb_Gain3 = 18919 * rtb_Saturation; - - /* Gain: '/Gain2' */ - rtb_Sum1_jt = 18919 * rtb_Saturation1; - - /* Sum: '/Sum1' incorporates: - * Gain: '/Gain2' - * Gain: '/Gain4' - */ - rtb_Gain3 = (((rtb_Gain3 < 0 ? 32767 : 0) + rtb_Gain3) >> 15) + (int16_T) - (((rtb_Sum1_jt < 0 ? 16383 : 0) + rtb_Sum1_jt) >> 14); - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - rtb_Merge1 = (int16_T)rtb_Gain3; - - /* End of Sum: '/Sum1' */ - /* End of Outputs for SubSystem: '/Clarke_PhasesAB' */ - } else if (rtP->z_selPhaCurMeasABC == 1) { - /* Outputs for IfAction SubSystem: '/Clarke_PhasesBC' incorporates: - * ActionPort: '/Action Port' - */ - /* Sum: '/Sum3' */ - rtb_Gain3 = rtb_Saturation - rtb_Saturation1; - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Gain: '/Gain2' incorporates: - * Sum: '/Sum3' - */ - rtb_Gain3 *= 18919; - rtb_Merge1 = (int16_T)(((rtb_Gain3 < 0 ? 32767 : 0) + rtb_Gain3) >> 15); - - /* Sum: '/Sum1' */ - rtb_Gain3 = -rtb_Saturation - rtb_Saturation1; - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - rtb_Saturation = (int16_T)rtb_Gain3; - - /* End of Sum: '/Sum1' */ - /* End of Outputs for SubSystem: '/Clarke_PhasesBC' */ - } else { - /* Outputs for IfAction SubSystem: '/Clarke_PhasesAC' incorporates: - * ActionPort: '/Action Port' - */ - /* Gain: '/Gain4' */ - rtb_Gain3 = 18919 * rtb_Saturation; - - /* Gain: '/Gain2' */ - rtb_Sum1_jt = 18919 * rtb_Saturation1; - - /* Sum: '/Sum1' incorporates: - * Gain: '/Gain2' - * Gain: '/Gain4' - */ - rtb_Gain3 = -(((rtb_Gain3 < 0 ? 32767 : 0) + rtb_Gain3) >> 15) - (int16_T) - (((rtb_Sum1_jt < 0 ? 16383 : 0) + rtb_Sum1_jt) >> 14); - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - rtb_Merge1 = (int16_T)rtb_Gain3; - - /* End of Sum: '/Sum1' */ - /* End of Outputs for SubSystem: '/Clarke_PhasesAC' */ - } - - /* End of If: '/If1' */ - - /* PreLookup: '/a_elecAngle_XA' */ - rtb_a_elecAngle_XA_g = plook_u8s16_evencka(rtb_Merge_m, 0, 128U, 180U); - - /* Interpolation_n-D: '/r_sin_M1' */ - rtDW->r_sin_M1 = rtConstP.r_sin_M1_Table[rtb_a_elecAngle_XA_g]; - - /* Interpolation_n-D: '/r_cos_M1' */ - rtDW->r_cos_M1 = rtConstP.r_cos_M1_Table[rtb_a_elecAngle_XA_g]; - - /* If: '/If2' incorporates: - * Constant: '/cf_currFilt' - * Inport: '/b_motEna' - */ - rtb_Sum2_h = rtDW->If2_ActiveSubsystem_a; - UnitDelay3 = -1; - if (rtU->b_motEna) { - UnitDelay3 = 0; - } - - rtDW->If2_ActiveSubsystem_a = UnitDelay3; - if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { - /* Disable for Outport: '/iq' */ - rtDW->DataTypeConversion[0] = 0; - - /* Disable for Outport: '/iqAbs' */ - rtDW->Abs5_h = 0; - - /* Disable for Outport: '/id' */ - rtDW->DataTypeConversion[1] = 0; - } - - if (UnitDelay3 == 0) { - if (0 != rtb_Sum2_h) { - /* SystemReset for IfAction SubSystem: '/Current_Filtering' incorporates: - * ActionPort: '/Action Port' - */ - - /* SystemReset for Atomic SubSystem: '/Low_Pass_Filter' */ - - /* SystemReset for If: '/If2' */ - Low_Pass_Filter_Reset(&rtDW->Low_Pass_Filter_m); - - /* End of SystemReset for SubSystem: '/Low_Pass_Filter' */ - - /* End of SystemReset for SubSystem: '/Current_Filtering' */ - } - - /* Sum: '/Sum6' incorporates: - * Product: '/Divide1' - * Product: '/Divide4' - */ - rtb_Gain3 = (int16_T)((rtb_Merge1 * rtDW->r_cos_M1) >> 14) - (int16_T) - ((rtb_Saturation * rtDW->r_sin_M1) >> 14); - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Outputs for IfAction SubSystem: '/Current_Filtering' incorporates: - * ActionPort: '/Action Port' - */ - /* SignalConversion: '/TmpSignal ConversionAtLow_Pass_FilterInport1' incorporates: - * Sum: '/Sum6' - */ - rtb_TmpSignalConversionAtLow_Pa[0] = (int16_T)rtb_Gain3; - - /* End of Outputs for SubSystem: '/Current_Filtering' */ - - /* Sum: '/Sum1' incorporates: - * Product: '/Divide2' - * Product: '/Divide3' - */ - rtb_Gain3 = (int16_T)((rtb_Saturation * rtDW->r_cos_M1) >> 14) + (int16_T) - ((rtb_Merge1 * rtDW->r_sin_M1) >> 14); - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Outputs for IfAction SubSystem: '/Current_Filtering' incorporates: - * ActionPort: '/Action Port' - */ - /* SignalConversion: '/TmpSignal ConversionAtLow_Pass_FilterInport1' incorporates: - * Sum: '/Sum1' - */ - rtb_TmpSignalConversionAtLow_Pa[1] = (int16_T)rtb_Gain3; - - /* Outputs for Atomic SubSystem: '/Low_Pass_Filter' */ - Low_Pass_Filter(rtb_TmpSignalConversionAtLow_Pa, rtP->cf_currFilt, - rtDW->DataTypeConversion, &rtDW->Low_Pass_Filter_m); - - /* End of Outputs for SubSystem: '/Low_Pass_Filter' */ - - /* Abs: '/Abs5' incorporates: - * Constant: '/cf_currFilt' - */ - if (rtDW->DataTypeConversion[0] < 0) { - rtDW->Abs5_h = (int16_T)-rtDW->DataTypeConversion[0]; - } else { - rtDW->Abs5_h = rtDW->DataTypeConversion[0]; - } - - /* End of Abs: '/Abs5' */ - /* End of Outputs for SubSystem: '/Current_Filtering' */ - } - - /* End of If: '/If2' */ - /* End of Outputs for SubSystem: '/Clarke_Park_Transform_Forward' */ - } - - /* End of If: '/If1' */ - - /* Chart: '/Task_Scheduler' incorporates: - * UnitDelay: '/UnitDelay2' - * UnitDelay: '/UnitDelay5' - * UnitDelay: '/UnitDelay6' - */ - if (rtDW->UnitDelay2_DSTATE_c) { - /* Outputs for Function Call SubSystem: '/F02_Diagnostics' */ - /* If: '/If2' incorporates: - * Constant: '/CTRL_COMM2' - * Constant: '/t_errDequal' - * Constant: '/t_errQual' - * Constant: '/b_diagEna' - * RelationalOperator: '/Relational Operator2' - */ - if (rtP->b_diagEna) { - /* Outputs for IfAction SubSystem: '/Diagnostics_Enabled' incorporates: - * ActionPort: '/Action Port' - */ - /* Switch: '/Switch3' incorporates: - * Abs: '/Abs4' - * Constant: '/n_stdStillDet' - * Constant: '/CTRL_COMM4' - * Constant: '/r_errInpTgtThres' - * Inport: '/b_motEna' - * Logic: '/Logical Operator1' - * RelationalOperator: '/Relational Operator9' - * RelationalOperator: '/Relational Operator7' - * S-Function (sfix_bitop): '/Bitwise Operator1' - * UnitDelay: '/UnitDelay' - * UnitDelay: '/UnitDelay4' - */ - if ((rtDW->UnitDelay_DSTATE_e & 4) != 0) { - rtb_RelationalOperator1_mv = true; - } else { - if (rtDW->UnitDelay4_DSTATE_eu < 0) { - /* Abs: '/Abs4' incorporates: - * UnitDelay: '/UnitDelay4' - */ - rtb_Saturation1 = (int16_T)-rtDW->UnitDelay4_DSTATE_eu; - } else { - /* Abs: '/Abs4' incorporates: - * UnitDelay: '/UnitDelay4' - */ - rtb_Saturation1 = rtDW->UnitDelay4_DSTATE_eu; - } - - rtb_RelationalOperator1_mv = (rtU->b_motEna && (Abs5 < - rtP->n_stdStillDet) && (rtb_Saturation1 > rtP->r_errInpTgtThres)); - } - - /* End of Switch: '/Switch3' */ - - /* Sum: '/Sum' incorporates: - * Constant: '/CTRL_COMM' - * Constant: '/CTRL_COMM1' - * DataTypeConversion: '/Data Type Conversion3' - * Gain: '/g_Hb' - * Gain: '/g_Hb1' - * RelationalOperator: '/Relational Operator1' - * RelationalOperator: '/Relational Operator3' - */ - rtb_a_elecAngle_XA_g = (uint8_T)(((uint32_T)((Sum == 7) << 1) + (Sum == 0)) - + (rtb_RelationalOperator1_mv << 2)); - - /* Outputs for Atomic SubSystem: '/Debounce_Filter' */ - Debounce_Filter(rtb_a_elecAngle_XA_g != 0, rtP->t_errQual, - rtP->t_errDequal, &rtDW->Merge_p, &rtDW->Debounce_Filter_k); - - /* End of Outputs for SubSystem: '/Debounce_Filter' */ - - /* Outputs for Atomic SubSystem: '/either_edge' */ - either_edge(rtDW->Merge_p, &rtb_RelationalOperator1_mv, - &rtDW->either_edge_i); - - /* End of Outputs for SubSystem: '/either_edge' */ - - /* Switch: '/Switch1' incorporates: - * Constant: '/CTRL_COMM2' - * Constant: '/t_errDequal' - * Constant: '/t_errQual' - * RelationalOperator: '/Relational Operator2' - */ - if (rtb_RelationalOperator1_mv) { - /* Outport: '/z_errCode' */ - rtY->z_errCode = rtb_a_elecAngle_XA_g; - } else { - /* Outport: '/z_errCode' incorporates: - * UnitDelay: '/UnitDelay' - */ - rtY->z_errCode = rtDW->UnitDelay_DSTATE_e; - } - - /* End of Switch: '/Switch1' */ - - /* Update for UnitDelay: '/UnitDelay' incorporates: - * Outport: '/z_errCode' - */ - rtDW->UnitDelay_DSTATE_e = rtY->z_errCode; - - /* End of Outputs for SubSystem: '/Diagnostics_Enabled' */ - } - - /* End of If: '/If2' */ - /* End of Outputs for SubSystem: '/F02_Diagnostics' */ - - /* Outputs for Function Call SubSystem: '/F03_Control_Mode_Manager' */ - /* Logic: '/Logical Operator4' incorporates: - * Constant: '/constant8' - * Inport: '/b_motEna' - * Inport: '/z_ctrlModReq' - * Logic: '/Logical Operator7' - * RelationalOperator: '/Relational Operator10' - */ - rtb_RelationalOperator1_mv = (rtDW->Merge_p || (!rtU->b_motEna) || - (rtU->z_ctrlModReq == 0)); - - /* Logic: '/Logical Operator1' incorporates: - * Constant: '/b_cruiseCtrlEna' - * Constant: '/constant1' - * Inport: '/z_ctrlModReq' - * RelationalOperator: '/Relational Operator1' - */ - rtb_LogicalOperator1_j = ((rtU->z_ctrlModReq == 2) || rtP->b_cruiseCtrlEna); - - /* Logic: '/Logical Operator2' incorporates: - * Constant: '/b_cruiseCtrlEna' - * Constant: '/constant' - * Inport: '/z_ctrlModReq' - * Logic: '/Logical Operator5' - * RelationalOperator: '/Relational Operator4' - */ - rtb_LogicalOperator2_p = ((rtU->z_ctrlModReq == 3) && (!rtP->b_cruiseCtrlEna)); - - /* Chart: '/F03_02_Control_Mode_Manager' incorporates: - * Constant: '/constant5' - * Inport: '/z_ctrlModReq' - * Logic: '/Logical Operator3' - * Logic: '/Logical Operator6' - * Logic: '/Logical Operator9' - * RelationalOperator: '/Relational Operator5' - */ - if (rtDW->is_active_c1_BLDC_controller == 0U) { - rtDW->is_active_c1_BLDC_controller = 1U; - rtDW->is_c1_BLDC_controller = IN_OPEN; - rtDW->z_ctrlMod = OPEN_MODE; - } else if (rtDW->is_c1_BLDC_controller == IN_ACTIVE) { - if (rtb_RelationalOperator1_mv) { - rtDW->is_ACTIVE = IN_NO_ACTIVE_CHILD; - rtDW->is_c1_BLDC_controller = IN_OPEN; - rtDW->z_ctrlMod = OPEN_MODE; - } else { - switch (rtDW->is_ACTIVE) { - case IN_SPEED_MODE: - rtDW->z_ctrlMod = SPD_MODE; - if (!rtb_LogicalOperator1_j) { - rtDW->is_ACTIVE = IN_NO_ACTIVE_CHILD; - if (rtb_LogicalOperator2_p) { - rtDW->is_ACTIVE = IN_TORQUE_MODE; - rtDW->z_ctrlMod = TRQ_MODE; - } else { - rtDW->is_ACTIVE = IN_VOLTAGE_MODE; - rtDW->z_ctrlMod = VLT_MODE; - } - } - break; - - case IN_TORQUE_MODE: - rtDW->z_ctrlMod = TRQ_MODE; - if (!rtb_LogicalOperator2_p) { - rtDW->is_ACTIVE = IN_NO_ACTIVE_CHILD; - if (rtb_LogicalOperator1_j) { - rtDW->is_ACTIVE = IN_SPEED_MODE; - rtDW->z_ctrlMod = SPD_MODE; - } else { - rtDW->is_ACTIVE = IN_VOLTAGE_MODE; - rtDW->z_ctrlMod = VLT_MODE; - } - } - break; - - default: - rtDW->z_ctrlMod = VLT_MODE; - if (rtb_LogicalOperator2_p || rtb_LogicalOperator1_j) { - rtDW->is_ACTIVE = IN_NO_ACTIVE_CHILD; - if (rtb_LogicalOperator2_p) { - rtDW->is_ACTIVE = IN_TORQUE_MODE; - rtDW->z_ctrlMod = TRQ_MODE; - } else if (rtb_LogicalOperator1_j) { - rtDW->is_ACTIVE = IN_SPEED_MODE; - rtDW->z_ctrlMod = SPD_MODE; - } else { - rtDW->is_ACTIVE = IN_VOLTAGE_MODE; - rtDW->z_ctrlMod = VLT_MODE; - } - } - break; - } - } - } else { - rtDW->z_ctrlMod = OPEN_MODE; - if ((!rtb_RelationalOperator1_mv) && ((rtU->z_ctrlModReq == 1) || - rtb_LogicalOperator1_j || rtb_LogicalOperator2_p)) { - rtDW->is_c1_BLDC_controller = IN_ACTIVE; - if (rtb_LogicalOperator2_p) { - rtDW->is_ACTIVE = IN_TORQUE_MODE; - rtDW->z_ctrlMod = TRQ_MODE; - } else if (rtb_LogicalOperator1_j) { - rtDW->is_ACTIVE = IN_SPEED_MODE; - rtDW->z_ctrlMod = SPD_MODE; - } else { - rtDW->is_ACTIVE = IN_VOLTAGE_MODE; - rtDW->z_ctrlMod = VLT_MODE; - } - } - } - - /* End of Chart: '/F03_02_Control_Mode_Manager' */ - - /* If: '/If1' incorporates: - * Constant: '/z_ctrlTypSel' - * Inport: '/r_inpTgt' - * Saturate: '/Saturation' - */ - if (rtP->z_ctrlTypSel == 2) { - /* Outputs for IfAction SubSystem: '/FOC_Control_Type' incorporates: - * ActionPort: '/Action Port' - */ - /* SignalConversion: '/TmpSignal ConversionAtSelectorInport1' incorporates: - * Constant: '/Vd_max' - * Constant: '/constant1' - * Constant: '/i_max' - * Constant: '/n_max' - */ - tmp[0] = 0; - tmp[1] = rtP->Vd_max; - tmp[2] = rtP->n_max; - tmp[3] = rtP->i_max; - - /* End of Outputs for SubSystem: '/FOC_Control_Type' */ - - /* Saturate: '/Saturation' */ - if (DataTypeConversion2 > 16000) { - DataTypeConversion2 = 16000; - } else { - if (DataTypeConversion2 < -16000) { - DataTypeConversion2 = -16000; - } - } - - /* Outputs for IfAction SubSystem: '/FOC_Control_Type' incorporates: - * ActionPort: '/Action Port' - */ - /* Product: '/Divide1' incorporates: - * Inport: '/z_ctrlModReq' - * Product: '/Divide4' - * Selector: '/Selector' - */ - rtb_Saturation = (int16_T)(((uint16_T)((tmp[rtU->z_ctrlModReq] << 5) / 125) - * DataTypeConversion2) >> 12); - - /* End of Outputs for SubSystem: '/FOC_Control_Type' */ - } else if (DataTypeConversion2 > 16000) { - /* Outputs for IfAction SubSystem: '/Default_Control_Type' incorporates: - * ActionPort: '/Action Port' - */ - /* Saturate: '/Saturation' incorporates: - * Inport: '/r_inpTgt' - */ - rtb_Saturation = 16000; - - /* End of Outputs for SubSystem: '/Default_Control_Type' */ - } else if (DataTypeConversion2 < -16000) { - /* Outputs for IfAction SubSystem: '/Default_Control_Type' incorporates: - * ActionPort: '/Action Port' - */ - /* Saturate: '/Saturation' incorporates: - * Inport: '/r_inpTgt' - */ - rtb_Saturation = -16000; - - /* End of Outputs for SubSystem: '/Default_Control_Type' */ - } else { - /* Outputs for IfAction SubSystem: '/Default_Control_Type' incorporates: - * ActionPort: '/Action Port' - */ - rtb_Saturation = DataTypeConversion2; - - /* End of Outputs for SubSystem: '/Default_Control_Type' */ - } - - /* End of If: '/If1' */ - - /* If: '/If2' incorporates: - * Inport: '/r_inpTgtScaRaw' - */ - rtb_Sum2_h = rtDW->If2_ActiveSubsystem_f; - UnitDelay3 = (int8_T)!(rtDW->z_ctrlMod == 0); - rtDW->If2_ActiveSubsystem_f = UnitDelay3; - switch (UnitDelay3) { - case 0: - if (UnitDelay3 != rtb_Sum2_h) { - /* SystemReset for IfAction SubSystem: '/Open_Mode' incorporates: - * ActionPort: '/Action Port' - */ - /* SystemReset for Atomic SubSystem: '/rising_edge_init' */ - /* SystemReset for If: '/If2' incorporates: - * UnitDelay: '/UnitDelay' - * UnitDelay: '/UnitDelay' - */ - rtDW->UnitDelay_DSTATE_b = true; - - /* End of SystemReset for SubSystem: '/rising_edge_init' */ - - /* SystemReset for Atomic SubSystem: '/Rate_Limiter' */ - rtDW->UnitDelay_DSTATE = 0; - - /* End of SystemReset for SubSystem: '/Rate_Limiter' */ - /* End of SystemReset for SubSystem: '/Open_Mode' */ - } - - /* Outputs for IfAction SubSystem: '/Open_Mode' incorporates: - * ActionPort: '/Action Port' - */ - /* DataTypeConversion: '/Data Type Conversion' incorporates: - * UnitDelay: '/UnitDelay4' - */ - rtb_Gain3 = rtDW->UnitDelay4_DSTATE_eu << 12; - rtb_Sum1_jt = (rtb_Gain3 & 134217728) != 0 ? rtb_Gain3 | -134217728 : - rtb_Gain3 & 134217727; - - /* Outputs for Atomic SubSystem: '/rising_edge_init' */ - /* UnitDelay: '/UnitDelay' */ - rtb_RelationalOperator1_mv = rtDW->UnitDelay_DSTATE_b; - - /* Update for UnitDelay: '/UnitDelay' incorporates: - * Constant: '/Constant' - */ - rtDW->UnitDelay_DSTATE_b = false; - - /* End of Outputs for SubSystem: '/rising_edge_init' */ - - /* Outputs for Atomic SubSystem: '/Rate_Limiter' */ - /* Switch: '/Switch1' incorporates: - * UnitDelay: '/UnitDelay' - */ - if (rtb_RelationalOperator1_mv) { - rtb_Switch1 = rtb_Sum1_jt; - } else { - rtb_Switch1 = rtDW->UnitDelay_DSTATE; - } - - /* End of Switch: '/Switch1' */ - - /* Sum: '/Sum1' */ - rtb_Gain3 = -rtb_Switch1; - rtb_Sum1 = (rtb_Gain3 & 134217728) != 0 ? rtb_Gain3 | -134217728 : - rtb_Gain3 & 134217727; - - /* Switch: '/Switch2' incorporates: - * Constant: '/dV_openRate' - * RelationalOperator: '/LowerRelop1' - */ - if (rtb_Sum1 > rtP->dV_openRate) { - rtb_Sum1 = rtP->dV_openRate; - } else { - /* Gain: '/Gain3' */ - rtb_Gain3 = -rtP->dV_openRate; - rtb_Gain3 = (rtb_Gain3 & 134217728) != 0 ? rtb_Gain3 | -134217728 : - rtb_Gain3 & 134217727; - - /* Switch: '/Switch' incorporates: - * RelationalOperator: '/UpperRelop' - */ - if (rtb_Sum1 < rtb_Gain3) { - rtb_Sum1 = rtb_Gain3; - } - - /* End of Switch: '/Switch' */ - } - - /* End of Switch: '/Switch2' */ - - /* Sum: '/Sum2' */ - rtb_Gain3 = rtb_Sum1 + rtb_Switch1; - rtb_Switch1 = (rtb_Gain3 & 134217728) != 0 ? rtb_Gain3 | -134217728 : - rtb_Gain3 & 134217727; - - /* Switch: '/Switch2' */ - if (rtb_RelationalOperator1_mv) { - /* Update for UnitDelay: '/UnitDelay' */ - rtDW->UnitDelay_DSTATE = rtb_Sum1_jt; - } else { - /* Update for UnitDelay: '/UnitDelay' */ - rtDW->UnitDelay_DSTATE = rtb_Switch1; - } - - /* End of Switch: '/Switch2' */ - /* End of Outputs for SubSystem: '/Rate_Limiter' */ - - /* DataTypeConversion: '/Data Type Conversion1' */ - rtDW->Merge1 = (int16_T)(rtb_Switch1 >> 12); - - /* End of Outputs for SubSystem: '/Open_Mode' */ - break; - - case 1: - /* Outputs for IfAction SubSystem: '/Default_Mode' incorporates: - * ActionPort: '/Action Port' - */ - rtDW->Merge1 = rtb_Saturation; - - /* End of Outputs for SubSystem: '/Default_Mode' */ - break; - } - - /* End of If: '/If2' */ - - /* Abs: '/Abs1' */ - if (rtDW->Merge1 < 0) { - rtDW->Abs1 = (int16_T)-rtDW->Merge1; - } else { - rtDW->Abs1 = rtDW->Merge1; - } - - /* End of Abs: '/Abs1' */ - /* End of Outputs for SubSystem: '/F03_Control_Mode_Manager' */ - } else if (rtDW->UnitDelay5_DSTATE_m) { - /* Outputs for Function Call SubSystem: '/F04_Field_Weakening' */ - /* If: '/If3' incorporates: - * Constant: '/b_fieldWeakEna' - */ - if (rtP->b_fieldWeakEna) { - /* Outputs for IfAction SubSystem: '/Field_Weakening_Enabled' incorporates: - * ActionPort: '/Action Port' - */ - /* Abs: '/Abs5' */ - if (DataTypeConversion2 < 0) { - DataTypeConversion2 = (int16_T)-DataTypeConversion2; - } - - /* End of Abs: '/Abs5' */ - - /* Switch: '/Switch2' incorporates: - * Constant: '/r_fieldWeakHi' - * Constant: '/r_fieldWeakLo' - * RelationalOperator: '/LowerRelop1' - * RelationalOperator: '/UpperRelop' - * Switch: '/Switch' - */ - if (DataTypeConversion2 > rtP->r_fieldWeakHi) { - DataTypeConversion2 = rtP->r_fieldWeakHi; - } else { - if (DataTypeConversion2 < rtP->r_fieldWeakLo) { - /* Switch: '/Switch' incorporates: - * Constant: '/r_fieldWeakLo' - */ - DataTypeConversion2 = rtP->r_fieldWeakLo; - } - } - - /* End of Switch: '/Switch2' */ - - /* Product: '/Divide14' incorporates: - * Constant: '/r_fieldWeakHi' - * Constant: '/r_fieldWeakLo' - * Sum: '/Sum1' - * Sum: '/Sum3' - */ - rtb_Divide14_e = (uint16_T)(((int16_T)(DataTypeConversion2 - - rtP->r_fieldWeakLo) << 15) / (int16_T)(rtP->r_fieldWeakHi - - rtP->r_fieldWeakLo)); - - /* Switch: '/Switch2' incorporates: - * Constant: '/n_fieldWeakAuthHi' - * Constant: '/n_fieldWeakAuthLo' - * RelationalOperator: '/LowerRelop1' - * RelationalOperator: '/UpperRelop' - * Switch: '/Switch' - */ - if (Abs5 > rtP->n_fieldWeakAuthHi) { - rtb_Saturation = rtP->n_fieldWeakAuthHi; - } else if (Abs5 < rtP->n_fieldWeakAuthLo) { - /* Switch: '/Switch' incorporates: - * Constant: '/n_fieldWeakAuthLo' - */ - rtb_Saturation = rtP->n_fieldWeakAuthLo; - } else { - rtb_Saturation = Abs5; - } - - /* End of Switch: '/Switch2' */ - - /* Product: '/Divide1' incorporates: - * Constant: '/n_fieldWeakAuthHi' - * Constant: '/n_fieldWeakAuthLo' - * Sum: '/Sum2' - * Sum: '/Sum4' - */ - rtb_Divide1_f = (uint16_T)(((int16_T)(rtb_Saturation - - rtP->n_fieldWeakAuthLo) << 15) / (int16_T)(rtP->n_fieldWeakAuthHi - - rtP->n_fieldWeakAuthLo)); - - /* Switch: '/Switch1' incorporates: - * MinMax: '/MinMax1' - * RelationalOperator: '/Relational Operator6' - */ - if (rtb_Divide14_e < rtb_Divide1_f) { - /* MinMax: '/MinMax' */ - if (!(rtb_Divide14_e > rtb_Divide1_f)) { - rtb_Divide14_e = rtb_Divide1_f; - } - - /* End of MinMax: '/MinMax' */ - } else { - if (rtb_Divide1_f < rtb_Divide14_e) { - /* MinMax: '/MinMax1' */ - rtb_Divide14_e = rtb_Divide1_f; - } - } - - /* End of Switch: '/Switch1' */ - - /* Switch: '/Switch2' incorporates: - * Constant: '/z_ctrlTypSel' - * Constant: '/CTRL_COMM2' - * Constant: '/a_phaAdvMax' - * Constant: '/id_fieldWeakMax' - * RelationalOperator: '/Relational Operator1' - */ - if (rtP->z_ctrlTypSel == 2) { - rtb_Saturation1 = rtP->id_fieldWeakMax; - } else { - rtb_Saturation1 = rtP->a_phaAdvMax; - } - - /* End of Switch: '/Switch2' */ - - /* Product: '/Divide3' */ - rtDW->Divide3 = (int16_T)((rtb_Saturation1 * rtb_Divide14_e) >> 15); - - /* End of Outputs for SubSystem: '/Field_Weakening_Enabled' */ - } - - /* End of If: '/If3' */ - /* End of Outputs for SubSystem: '/F04_Field_Weakening' */ - - /* Outputs for Function Call SubSystem: '/Motor_Limitations' */ - /* If: '/If1' incorporates: - * Constant: '/z_ctrlTypSel' - * Constant: '/Vd_max1' - * Constant: '/i_max' - */ - rtb_Sum2_h = rtDW->If1_ActiveSubsystem_o; - UnitDelay3 = -1; - if (rtP->z_ctrlTypSel == 2) { - UnitDelay3 = 0; - } - - rtDW->If1_ActiveSubsystem_o = UnitDelay3; - if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { - /* Disable for SwitchCase: '/Switch Case' */ - rtDW->SwitchCase_ActiveSubsystem_d = -1; - } - - if (UnitDelay3 == 0) { - /* Outputs for IfAction SubSystem: '/Motor_Limitations_Enabled' incorporates: - * ActionPort: '/Action Port' - */ - rtDW->Vd_max1 = rtP->Vd_max; - - /* Gain: '/Gain3' incorporates: - * Constant: '/Vd_max1' - */ - rtDW->Gain3 = (int16_T)-rtDW->Vd_max1; - - /* Interpolation_n-D: '/Vq_max_M1' incorporates: - * Abs: '/Abs5' - * PreLookup: '/Vq_max_XA' - * UnitDelay: '/UnitDelay4' - */ - if (rtDW->Switch1 < 0) { - rtb_Saturation1 = (int16_T)-rtDW->Switch1; - } else { - rtb_Saturation1 = rtDW->Switch1; - } - - rtDW->Vq_max_M1 = rtP->Vq_max_M1[plook_u8s16_evencka(rtb_Saturation1, - rtP->Vq_max_XA[0], (uint16_T)(rtP->Vq_max_XA[1] - rtP->Vq_max_XA[0]), - 45U)]; - - /* End of Interpolation_n-D: '/Vq_max_M1' */ - - /* Gain: '/Gain5' */ - rtDW->Gain5 = (int16_T)-rtDW->Vq_max_M1; - rtDW->i_max = rtP->i_max; - - /* Interpolation_n-D: '/iq_maxSca_M1' incorporates: - * Constant: '/i_max' - * Product: '/Divide4' - */ - rtb_Gain3 = rtDW->Divide3 << 16; - rtb_Gain3 = (rtb_Gain3 == MIN_int32_T) && (rtDW->i_max == -1) ? - MAX_int32_T : rtb_Gain3 / rtDW->i_max; - if (rtb_Gain3 < 0) { - rtb_Gain3 = 0; - } else { - if (rtb_Gain3 > 65535) { - rtb_Gain3 = 65535; - } - } - - /* Product: '/Divide1' incorporates: - * Interpolation_n-D: '/iq_maxSca_M1' - * PreLookup: '/iq_maxSca_XA' - * Product: '/Divide4' - */ - rtDW->Divide1_n = (int16_T) - ((rtConstP.iq_maxSca_M1_Table[plook_u8u16_evencka((uint16_T)rtb_Gain3, - 0U, 1311U, 49U)] * rtDW->i_max) >> 16); - - /* Gain: '/Gain1' */ - rtDW->Gain1 = (int16_T)-rtDW->Divide1_n; - - /* SwitchCase: '/Switch Case' incorporates: - * Constant: '/n_max1' - * Constant: '/Constant1' - * Constant: '/cf_KbLimProt' - * Constant: '/cf_nKiLimProt' - * Constant: '/Constant' - * Constant: '/Constant1' - * Constant: '/cf_KbLimProt' - * Constant: '/cf_iqKiLimProt' - * Constant: '/cf_nKiLimProt' - * Sum: '/Sum1' - * Sum: '/Sum1' - * Sum: '/Sum2' - */ - rtb_Sum2_h = rtDW->SwitchCase_ActiveSubsystem_d; - UnitDelay3 = -1; - switch (rtDW->z_ctrlMod) { - case 1: - UnitDelay3 = 0; - break; - - case 2: - UnitDelay3 = 1; - break; - - case 3: - UnitDelay3 = 2; - break; - } - - rtDW->SwitchCase_ActiveSubsystem_d = UnitDelay3; - switch (UnitDelay3) { - case 0: - if (UnitDelay3 != rtb_Sum2_h) { - /* SystemReset for IfAction SubSystem: '/Voltage_Mode_Protection' incorporates: - * ActionPort: '/Action Port' - */ - - /* SystemReset for Atomic SubSystem: '/I_backCalc_fixdt' */ - - /* SystemReset for SwitchCase: '/Switch Case' */ - I_backCalc_fixdt_Reset(&rtDW->I_backCalc_fixdt_i, 65536000); - - /* End of SystemReset for SubSystem: '/I_backCalc_fixdt' */ - - /* SystemReset for Atomic SubSystem: '/I_backCalc_fixdt1' */ - I_backCalc_fixdt_Reset(&rtDW->I_backCalc_fixdt1, 65536000); - - /* End of SystemReset for SubSystem: '/I_backCalc_fixdt1' */ - - /* End of SystemReset for SubSystem: '/Voltage_Mode_Protection' */ - } - - /* Outputs for IfAction SubSystem: '/Voltage_Mode_Protection' incorporates: - * ActionPort: '/Action Port' - */ - - /* Outputs for Atomic SubSystem: '/I_backCalc_fixdt' */ - I_backCalc_fixdt((int16_T)(rtDW->Divide1_n - rtDW->Abs5_h), - rtP->cf_iqKiLimProt, rtP->cf_KbLimProt, rtDW->Abs1, 0, - &rtDW->Switch2_a, &rtDW->I_backCalc_fixdt_i); - - /* End of Outputs for SubSystem: '/I_backCalc_fixdt' */ - - /* Outputs for Atomic SubSystem: '/I_backCalc_fixdt1' */ - I_backCalc_fixdt((int16_T)(rtP->n_max - Abs5), rtP->cf_nKiLimProt, - rtP->cf_KbLimProt, rtDW->Abs1, 0, &rtDW->Switch2_o, - &rtDW->I_backCalc_fixdt1); - - /* End of Outputs for SubSystem: '/I_backCalc_fixdt1' */ - - /* End of Outputs for SubSystem: '/Voltage_Mode_Protection' */ - break; - - case 1: - /* Outputs for IfAction SubSystem: '/Speed_Mode_Protection' incorporates: - * ActionPort: '/Action Port' - */ - /* Switch: '/Switch2' incorporates: - * RelationalOperator: '/LowerRelop1' - * RelationalOperator: '/UpperRelop' - * Switch: '/Switch' - */ - if (rtDW->DataTypeConversion[0] > rtDW->Divide1_n) { - rtb_Saturation1 = rtDW->Divide1_n; - } else if (rtDW->DataTypeConversion[0] < rtDW->Gain1) { - /* Switch: '/Switch' */ - rtb_Saturation1 = rtDW->Gain1; - } else { - rtb_Saturation1 = rtDW->DataTypeConversion[0]; - } - - /* End of Switch: '/Switch2' */ - - /* Product: '/Divide1' incorporates: - * Constant: '/cf_iqKiLimProt' - * Sum: '/Sum3' - */ - rtDW->Divide1 = (int16_T)(rtb_Saturation1 - rtDW->DataTypeConversion[0]) - * rtP->cf_iqKiLimProt; - - /* End of Outputs for SubSystem: '/Speed_Mode_Protection' */ - break; - - case 2: - if (UnitDelay3 != rtb_Sum2_h) { - /* SystemReset for IfAction SubSystem: '/Torque_Mode_Protection' incorporates: - * ActionPort: '/Action Port' - */ - - /* SystemReset for Atomic SubSystem: '/I_backCalc_fixdt' */ - - /* SystemReset for SwitchCase: '/Switch Case' */ - I_backCalc_fixdt_Reset(&rtDW->I_backCalc_fixdt_j, 58982400); - - /* End of SystemReset for SubSystem: '/I_backCalc_fixdt' */ - - /* End of SystemReset for SubSystem: '/Torque_Mode_Protection' */ - } - - /* Outputs for IfAction SubSystem: '/Torque_Mode_Protection' incorporates: - * ActionPort: '/Action Port' - */ - - /* Outputs for Atomic SubSystem: '/I_backCalc_fixdt' */ - I_backCalc_fixdt((int16_T)(rtP->n_max - Abs5), rtP->cf_nKiLimProt, - rtP->cf_KbLimProt, rtDW->Vq_max_M1, 0, &rtDW->Switch2_i, - &rtDW->I_backCalc_fixdt_j); - - /* End of Outputs for SubSystem: '/I_backCalc_fixdt' */ - - /* End of Outputs for SubSystem: '/Torque_Mode_Protection' */ - break; - } - - /* End of SwitchCase: '/Switch Case' */ - - /* Gain: '/Gain4' */ - rtDW->Gain4 = (int16_T)-rtDW->i_max; - - /* End of Outputs for SubSystem: '/Motor_Limitations_Enabled' */ - } - - /* End of If: '/If1' */ - /* End of Outputs for SubSystem: '/Motor_Limitations' */ - } else { - if (rtDW->UnitDelay6_DSTATE) { - /* Outputs for Function Call SubSystem: '/FOC' */ - /* If: '/If1' incorporates: - * Constant: '/z_ctrlTypSel' - */ - rtb_Sum2_h = rtDW->If1_ActiveSubsystem_j; - UnitDelay3 = -1; - if (rtP->z_ctrlTypSel == 2) { - UnitDelay3 = 0; - } - - rtDW->If1_ActiveSubsystem_j = UnitDelay3; - if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { - /* Disable for SwitchCase: '/Switch Case' */ - rtDW->SwitchCase_ActiveSubsystem = -1; - - /* Disable for If: '/If1' */ - rtDW->If1_ActiveSubsystem_a = -1; - } - - if (UnitDelay3 == 0) { - /* Outputs for IfAction SubSystem: '/FOC_Enabled' incorporates: - * ActionPort: '/Action Port' - */ - /* SwitchCase: '/Switch Case' incorporates: - * Constant: '/cf_nKi' - * Constant: '/cf_nKp' - * Inport: '/r_inpTgtSca' - * Sum: '/Sum3' - * UnitDelay: '/UnitDelay4' - */ - rtb_Sum2_h = rtDW->SwitchCase_ActiveSubsystem; - switch (rtDW->z_ctrlMod) { - case 1: - break; - - case 2: - UnitDelay3 = 1; - break; - - case 3: - UnitDelay3 = 2; - break; - - default: - UnitDelay3 = 3; - break; - } - - rtDW->SwitchCase_ActiveSubsystem = UnitDelay3; - switch (UnitDelay3) { - case 0: - /* Outputs for IfAction SubSystem: '/Voltage_Mode' incorporates: - * ActionPort: '/Action Port' - */ - /* MinMax: '/MinMax' */ - if (rtDW->Abs1 < rtDW->Switch2_a) { - DataTypeConversion2 = rtDW->Abs1; - } else { - DataTypeConversion2 = rtDW->Switch2_a; - } - - if (!(DataTypeConversion2 < rtDW->Switch2_o)) { - DataTypeConversion2 = rtDW->Switch2_o; - } - - /* End of MinMax: '/MinMax' */ - - /* Signum: '/SignDeltaU2' */ - if (rtDW->Merge1 < 0) { - rtb_Saturation1 = -1; - } else { - rtb_Saturation1 = (int16_T)(rtDW->Merge1 > 0); - } - - /* End of Signum: '/SignDeltaU2' */ - - /* Product: '/Divide1' */ - rtb_Saturation = (int16_T)(DataTypeConversion2 * rtb_Saturation1); - - /* Switch: '/Switch2' incorporates: - * RelationalOperator: '/LowerRelop1' - * RelationalOperator: '/UpperRelop' - * Switch: '/Switch' - */ - if (rtb_Saturation > rtDW->Vq_max_M1) { - /* SignalConversion: '/Signal Conversion2' */ - rtDW->Merge = rtDW->Vq_max_M1; - } else if (rtb_Saturation < rtDW->Gain5) { - /* Switch: '/Switch' incorporates: - * SignalConversion: '/Signal Conversion2' - */ - rtDW->Merge = rtDW->Gain5; - } else { - /* SignalConversion: '/Signal Conversion2' incorporates: - * Switch: '/Switch' - */ - rtDW->Merge = rtb_Saturation; - } - - /* End of Switch: '/Switch2' */ - /* End of Outputs for SubSystem: '/Voltage_Mode' */ - break; - - case 1: - if (UnitDelay3 != rtb_Sum2_h) { - /* SystemReset for IfAction SubSystem: '/Speed_Mode' incorporates: - * ActionPort: '/Action Port' - */ - - /* SystemReset for Atomic SubSystem: '/PI_clamp_fixdt' */ - - /* SystemReset for SwitchCase: '/Switch Case' */ - PI_clamp_fixdt_b_Reset(&rtDW->PI_clamp_fixdt_l4); - - /* End of SystemReset for SubSystem: '/PI_clamp_fixdt' */ - - /* End of SystemReset for SubSystem: '/Speed_Mode' */ - } - - /* Outputs for IfAction SubSystem: '/Speed_Mode' incorporates: - * ActionPort: '/Action Port' - */ - /* DataTypeConversion: '/Data Type Conversion2' incorporates: - * Constant: '/n_cruiseMotTgt' - */ - rtb_Saturation = (int16_T)(rtP->n_cruiseMotTgt << 4); - - /* Switch: '/Switch4' incorporates: - * Constant: '/b_cruiseCtrlEna' - * Logic: '/Logical Operator1' - * RelationalOperator: '/Relational Operator3' - */ - if (rtP->b_cruiseCtrlEna && (rtb_Saturation != 0)) { - /* Switch: '/Switch3' incorporates: - * MinMax: '/MinMax4' - */ - if (rtb_Saturation > 0) { - rtb_TmpSignalConversionAtLow_Pa[0] = rtDW->Vq_max_M1; - - /* MinMax: '/MinMax3' */ - if (rtDW->Merge1 > rtDW->Gain5) { - rtb_TmpSignalConversionAtLow_Pa[1] = rtDW->Merge1; - } else { - rtb_TmpSignalConversionAtLow_Pa[1] = rtDW->Gain5; - } - - /* End of MinMax: '/MinMax3' */ - } else { - if (rtDW->Vq_max_M1 < rtDW->Merge1) { - /* MinMax: '/MinMax4' */ - rtb_TmpSignalConversionAtLow_Pa[0] = rtDW->Vq_max_M1; - } else { - rtb_TmpSignalConversionAtLow_Pa[0] = rtDW->Merge1; - } - - rtb_TmpSignalConversionAtLow_Pa[1] = rtDW->Gain5; - } - - /* End of Switch: '/Switch3' */ - } else { - rtb_TmpSignalConversionAtLow_Pa[0] = rtDW->Vq_max_M1; - rtb_TmpSignalConversionAtLow_Pa[1] = rtDW->Gain5; - } - - /* End of Switch: '/Switch4' */ - - /* Switch: '/Switch2' incorporates: - * Constant: '/b_cruiseCtrlEna' - */ - if (!rtP->b_cruiseCtrlEna) { - rtb_Saturation = rtDW->Merge1; - } - - /* End of Switch: '/Switch2' */ - - /* Sum: '/Sum3' */ - rtb_Gain3 = rtb_Saturation - Switch2; - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Outputs for Atomic SubSystem: '/PI_clamp_fixdt' */ - PI_clamp_fixdt_l((int16_T)rtb_Gain3, rtP->cf_nKp, rtP->cf_nKi, - rtDW->UnitDelay4_DSTATE_eu, - rtb_TmpSignalConversionAtLow_Pa[0], - rtb_TmpSignalConversionAtLow_Pa[1], rtDW->Divide1, - &rtDW->Merge, &rtDW->PI_clamp_fixdt_l4); - - /* End of Outputs for SubSystem: '/PI_clamp_fixdt' */ - - /* End of Outputs for SubSystem: '/Speed_Mode' */ - break; - - case 2: - if (UnitDelay3 != rtb_Sum2_h) { - /* SystemReset for IfAction SubSystem: '/Torque_Mode' incorporates: - * ActionPort: '/Action Port' - */ - - /* SystemReset for Atomic SubSystem: '/PI_clamp_fixdt' */ - - /* SystemReset for SwitchCase: '/Switch Case' */ - PI_clamp_fixdt_g_Reset(&rtDW->PI_clamp_fixdt_kh); - - /* End of SystemReset for SubSystem: '/PI_clamp_fixdt' */ - - /* End of SystemReset for SubSystem: '/Torque_Mode' */ - } - - /* Outputs for IfAction SubSystem: '/Torque_Mode' incorporates: - * ActionPort: '/Action Port' - */ - /* Gain: '/Gain4' */ - rtb_Saturation = (int16_T)-rtDW->Switch2_i; - - /* Switch: '/Switch2' incorporates: - * RelationalOperator: '/LowerRelop1' - * RelationalOperator: '/UpperRelop' - * Switch: '/Switch' - */ - if (rtDW->Merge1 > rtDW->Divide1_n) { - rtb_Saturation1 = rtDW->Divide1_n; - } else if (rtDW->Merge1 < rtDW->Gain1) { - /* Switch: '/Switch' */ - rtb_Saturation1 = rtDW->Gain1; - } else { - rtb_Saturation1 = rtDW->Merge1; - } - - /* End of Switch: '/Switch2' */ - - /* Sum: '/Sum2' */ - rtb_Gain3 = rtb_Saturation1 - rtDW->DataTypeConversion[0]; - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* MinMax: '/MinMax1' */ - if (rtDW->Vq_max_M1 < rtDW->Switch2_i) { - rtb_Saturation1 = rtDW->Vq_max_M1; - } else { - rtb_Saturation1 = rtDW->Switch2_i; - } - - /* End of MinMax: '/MinMax1' */ - - /* MinMax: '/MinMax2' */ - if (!(rtb_Saturation > rtDW->Gain5)) { - rtb_Saturation = rtDW->Gain5; - } - - /* End of MinMax: '/MinMax2' */ - - /* Outputs for Atomic SubSystem: '/PI_clamp_fixdt' */ - - /* SignalConversion: '/Signal Conversion2' incorporates: - * Constant: '/cf_iqKi' - * Constant: '/cf_iqKp' - * Constant: '/constant2' - * Sum: '/Sum2' - * UnitDelay: '/UnitDelay4' - */ - PI_clamp_fixdt_k((int16_T)rtb_Gain3, rtP->cf_iqKp, rtP->cf_iqKi, - rtDW->UnitDelay4_DSTATE_eu, rtb_Saturation1, - rtb_Saturation, 0, &rtDW->Merge, - &rtDW->PI_clamp_fixdt_kh); - - /* End of Outputs for SubSystem: '/PI_clamp_fixdt' */ - - /* End of Outputs for SubSystem: '/Torque_Mode' */ - break; - - case 3: - /* Outputs for IfAction SubSystem: '/Open_Mode' incorporates: - * ActionPort: '/Action Port' - */ - rtDW->Merge = rtDW->Merge1; - - /* End of Outputs for SubSystem: '/Open_Mode' */ - break; - } - - /* End of SwitchCase: '/Switch Case' */ - - /* If: '/If1' incorporates: - * Constant: '/cf_idKi1' - * Constant: '/cf_idKp1' - * Constant: '/constant1' - * Constant: '/constant2' - * Sum: '/Sum3' - */ - rtb_Sum2_h = rtDW->If1_ActiveSubsystem_a; - UnitDelay3 = -1; - if (rtb_LogicalOperator) { - UnitDelay3 = 0; - } - - rtDW->If1_ActiveSubsystem_a = UnitDelay3; - if (UnitDelay3 == 0) { - if (0 != rtb_Sum2_h) { - /* SystemReset for IfAction SubSystem: '/Vd_Calculation' incorporates: - * ActionPort: '/Action Port' - */ - - /* SystemReset for Atomic SubSystem: '/PI_clamp_fixdt' */ - - /* SystemReset for If: '/If1' */ - PI_clamp_fixdt_Reset(&rtDW->PI_clamp_fixdt_i); - - /* End of SystemReset for SubSystem: '/PI_clamp_fixdt' */ - - /* End of SystemReset for SubSystem: '/Vd_Calculation' */ - } - - /* Outputs for IfAction SubSystem: '/Vd_Calculation' incorporates: - * ActionPort: '/Action Port' - */ - /* Gain: '/toNegative' */ - rtb_Saturation = (int16_T)-rtDW->Divide3; - - /* Switch: '/Switch2' incorporates: - * RelationalOperator: '/LowerRelop1' - * RelationalOperator: '/UpperRelop' - * Switch: '/Switch' - */ - if (rtb_Saturation > rtDW->i_max) { - rtb_Saturation = rtDW->i_max; - } else { - if (rtb_Saturation < rtDW->Gain4) { - /* Switch: '/Switch' */ - rtb_Saturation = rtDW->Gain4; - } - } - - /* End of Switch: '/Switch2' */ - - /* Sum: '/Sum3' */ - rtb_Gain3 = rtb_Saturation - rtDW->DataTypeConversion[1]; - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Outputs for Atomic SubSystem: '/PI_clamp_fixdt' */ - PI_clamp_fixdt((int16_T)rtb_Gain3, rtP->cf_idKp, rtP->cf_idKi, 0, - rtDW->Vd_max1, rtDW->Gain3, 0, &rtDW->Switch1, - &rtDW->PI_clamp_fixdt_i); - - /* End of Outputs for SubSystem: '/PI_clamp_fixdt' */ - - /* End of Outputs for SubSystem: '/Vd_Calculation' */ - } - - /* End of If: '/If1' */ - /* End of Outputs for SubSystem: '/FOC_Enabled' */ - } - - /* End of If: '/If1' */ - /* End of Outputs for SubSystem: '/FOC' */ - } - } - - /* End of Chart: '/Task_Scheduler' */ - - /* If: '/If2' incorporates: - * Constant: '/z_ctrlTypSel' - * Constant: '/CTRL_COMM1' - * RelationalOperator: '/Relational Operator6' - * Switch: '/Switch2' - */ - rtb_Sum2_h = rtDW->If2_ActiveSubsystem; - UnitDelay3 = -1; - if (rtP->z_ctrlTypSel == 2) { - rtb_Saturation = rtDW->Merge; - UnitDelay3 = 0; - } else { - rtb_Saturation = rtDW->Merge1; - } - - rtDW->If2_ActiveSubsystem = UnitDelay3; - if ((rtb_Sum2_h != UnitDelay3) && (rtb_Sum2_h == 0)) { - /* Disable for Outport: '/V_phaABC_FOC' */ - rtDW->Gain4_e[0] = 0; - rtDW->Gain4_e[1] = 0; - rtDW->Gain4_e[2] = 0; - } - - if (UnitDelay3 == 0) { - /* Outputs for IfAction SubSystem: '/Clarke_Park_Transform_Inverse' incorporates: - * ActionPort: '/Action Port' - */ - /* Sum: '/Sum6' incorporates: - * Product: '/Divide1' - * Product: '/Divide4' - */ - rtb_Gain3 = (int16_T)((rtDW->Switch1 * rtDW->r_cos_M1) >> 14) - (int16_T) - ((rtDW->Merge * rtDW->r_sin_M1) >> 14); - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Sum: '/Sum1' incorporates: - * Product: '/Divide2' - * Product: '/Divide3' - */ - rtb_Sum1_jt = (int16_T)((rtDW->Switch1 * rtDW->r_sin_M1) >> 14) + (int16_T) - ((rtDW->Merge * rtDW->r_cos_M1) >> 14); - if (rtb_Sum1_jt > 32767) { - rtb_Sum1_jt = 32767; - } else { - if (rtb_Sum1_jt < -32768) { - rtb_Sum1_jt = -32768; - } - } - - /* Gain: '/Gain1' incorporates: - * Sum: '/Sum1' - */ - rtb_Sum1_jt *= 14189; - - /* Sum: '/Sum6' incorporates: - * Gain: '/Gain1' - * Gain: '/Gain3' - * Sum: '/Sum6' - */ - rtb_Sum1_jt = (((rtb_Sum1_jt < 0 ? 16383 : 0) + rtb_Sum1_jt) >> 14) - - ((int16_T)(((int16_T)rtb_Gain3 < 0) + (int16_T)rtb_Gain3) >> 1); - if (rtb_Sum1_jt > 32767) { - rtb_Sum1_jt = 32767; - } else { - if (rtb_Sum1_jt < -32768) { - rtb_Sum1_jt = -32768; - } - } - - /* Sum: '/Sum2' incorporates: - * Sum: '/Sum6' - * Sum: '/Sum6' - */ - rtb_Switch1 = -(int16_T)rtb_Gain3 - (int16_T)rtb_Sum1_jt; - if (rtb_Switch1 > 32767) { - rtb_Switch1 = 32767; - } else { - if (rtb_Switch1 < -32768) { - rtb_Switch1 = -32768; - } - } - - /* MinMax: '/MinMax1' incorporates: - * Sum: '/Sum2' - * Sum: '/Sum6' - * Sum: '/Sum6' - */ - DataTypeConversion2 = (int16_T)rtb_Gain3; - if (!((int16_T)rtb_Gain3 < (int16_T)rtb_Sum1_jt)) { - DataTypeConversion2 = (int16_T)rtb_Sum1_jt; - } - - if (!(DataTypeConversion2 < (int16_T)rtb_Switch1)) { - DataTypeConversion2 = (int16_T)rtb_Switch1; - } - - /* MinMax: '/MinMax2' incorporates: - * Sum: '/Sum2' - * Sum: '/Sum6' - * Sum: '/Sum6' - */ - rtb_Saturation1 = (int16_T)rtb_Gain3; - if (!((int16_T)rtb_Gain3 > (int16_T)rtb_Sum1_jt)) { - rtb_Saturation1 = (int16_T)rtb_Sum1_jt; - } - - if (!(rtb_Saturation1 > (int16_T)rtb_Switch1)) { - rtb_Saturation1 = (int16_T)rtb_Switch1; - } - - /* Sum: '/Add' incorporates: - * MinMax: '/MinMax1' - * MinMax: '/MinMax2' - */ - rtb_Sum1 = DataTypeConversion2 + rtb_Saturation1; - if (rtb_Sum1 > 32767) { - rtb_Sum1 = 32767; - } else { - if (rtb_Sum1 < -32768) { - rtb_Sum1 = -32768; - } - } - - /* Gain: '/Gain2' incorporates: - * Sum: '/Add' - */ - rtb_Merge1 = (int16_T)(rtb_Sum1 >> 1); - - /* Sum: '/Add1' incorporates: - * Sum: '/Sum6' - */ - rtb_Gain3 = (int16_T)rtb_Gain3 - rtb_Merge1; - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Gain: '/Gain4' incorporates: - * Sum: '/Add1' - */ - rtDW->Gain4_e[0] = (int16_T)((18919 * rtb_Gain3) >> 14); - - /* Sum: '/Add1' incorporates: - * Sum: '/Sum6' - */ - rtb_Gain3 = (int16_T)rtb_Sum1_jt - rtb_Merge1; - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Gain: '/Gain4' incorporates: - * Sum: '/Add1' - */ - rtDW->Gain4_e[1] = (int16_T)((18919 * rtb_Gain3) >> 14); - - /* Sum: '/Add1' incorporates: - * Sum: '/Sum2' - */ - rtb_Gain3 = (int16_T)rtb_Switch1 - rtb_Merge1; - if (rtb_Gain3 > 32767) { - rtb_Gain3 = 32767; - } else { - if (rtb_Gain3 < -32768) { - rtb_Gain3 = -32768; - } - } - - /* Gain: '/Gain4' incorporates: - * Sum: '/Add1' - */ - rtDW->Gain4_e[2] = (int16_T)((18919 * rtb_Gain3) >> 14); - - /* End of Outputs for SubSystem: '/Clarke_Park_Transform_Inverse' */ - } - - /* End of If: '/If2' */ - - /* If: '/If' incorporates: - * Constant: '/vec_hallToPos' - * Constant: '/z_ctrlTypSel' - * Constant: '/CTRL_COMM2' - * Constant: '/CTRL_COMM3' - * Inport: '/V_phaABC_FOC_in' - * Logic: '/Logical Operator1' - * Logic: '/Logical Operator2' - * LookupNDDirect: '/z_commutMap_M1' - * RelationalOperator: '/Relational Operator1' - * RelationalOperator: '/Relational Operator2' - * Selector: '/Selector' - * - * About '/z_commutMap_M1': - * 2-dimensional Direct Look-Up returning a Column - */ - if (rtb_LogicalOperator && (rtP->z_ctrlTypSel == 2)) { - /* Outputs for IfAction SubSystem: '/FOC_Method' incorporates: - * ActionPort: '/Action Port' - */ - DataTypeConversion2 = rtDW->Gain4_e[0]; - rtb_Saturation1 = rtDW->Gain4_e[1]; - rtb_Merge1 = rtDW->Gain4_e[2]; - - /* End of Outputs for SubSystem: '/FOC_Method' */ - } else if (rtb_LogicalOperator && (rtP->z_ctrlTypSel == 1)) { - /* Outputs for IfAction SubSystem: '/SIN_Method' incorporates: - * ActionPort: '/Action Port' - */ - /* Switch: '/Switch_PhaAdv' incorporates: - * Constant: '/b_fieldWeakEna' - * Product: '/Divide2' - * Product: '/Divide3' - * Sum: '/Sum3' - */ - if (rtP->b_fieldWeakEna) { - /* Sum: '/Sum3' incorporates: - * Product: '/Product2' - */ - DataTypeConversion2 = (int16_T)((int16_T)((int16_T)(rtDW->Divide3 * - rtDW->Switch2_e) << 2) + rtb_Merge_m); - DataTypeConversion2 -= (int16_T)((int16_T)((int16_T)div_nde_s32_floor - (DataTypeConversion2, 23040) * 360) << 6); - } else { - DataTypeConversion2 = rtb_Merge_m; - } - - /* End of Switch: '/Switch_PhaAdv' */ - - /* PreLookup: '/a_elecAngle_XA' */ - Sum = plook_u8s16_evencka(DataTypeConversion2, 0, 128U, 180U); - - /* Product: '/Divide2' incorporates: - * Interpolation_n-D: '/r_sin3PhaA_M1' - * Interpolation_n-D: '/r_sin3PhaB_M1' - * Interpolation_n-D: '/r_sin3PhaC_M1' - */ - DataTypeConversion2 = (int16_T)((rtb_Saturation * - rtConstP.r_sin3PhaA_M1_Table[Sum]) >> 14); - rtb_Saturation1 = (int16_T)((rtb_Saturation * - rtConstP.r_sin3PhaB_M1_Table[Sum]) >> 14); - rtb_Merge1 = (int16_T)((rtb_Saturation * rtConstP.r_sin3PhaC_M1_Table[Sum]) >> - 14); - - /* End of Outputs for SubSystem: '/SIN_Method' */ - } else { - /* Outputs for IfAction SubSystem: '/COM_Method' incorporates: - * ActionPort: '/Action Port' - */ - if (rtConstP.vec_hallToPos_Value[Sum] > 5) { - /* LookupNDDirect: '/z_commutMap_M1' - * - * About '/z_commutMap_M1': - * 2-dimensional Direct Look-Up returning a Column - */ - rtb_Sum2_h = 5; - } else if (rtConstP.vec_hallToPos_Value[Sum] < 0) { - /* LookupNDDirect: '/z_commutMap_M1' - * - * About '/z_commutMap_M1': - * 2-dimensional Direct Look-Up returning a Column - */ - rtb_Sum2_h = 0; - } else { - /* LookupNDDirect: '/z_commutMap_M1' incorporates: - * Constant: '/vec_hallToPos' - * Selector: '/Selector' - * - * About '/z_commutMap_M1': - * 2-dimensional Direct Look-Up returning a Column - */ - rtb_Sum2_h = rtConstP.vec_hallToPos_Value[Sum]; - } - - /* LookupNDDirect: '/z_commutMap_M1' incorporates: - * Constant: '/vec_hallToPos' - * Selector: '/Selector' - * - * About '/z_commutMap_M1': - * 2-dimensional Direct Look-Up returning a Column - */ - rtb_Sum1_jt = rtb_Sum2_h * 3; - - /* Product: '/Divide2' incorporates: - * LookupNDDirect: '/z_commutMap_M1' - * - * About '/z_commutMap_M1': - * 2-dimensional Direct Look-Up returning a Column - */ - DataTypeConversion2 = (int16_T)(rtb_Saturation * - rtConstP.z_commutMap_M1_table[rtb_Sum1_jt]); - rtb_Saturation1 = (int16_T)(rtConstP.z_commutMap_M1_table[1 + rtb_Sum1_jt] * - rtb_Saturation); - rtb_Merge1 = (int16_T)(rtConstP.z_commutMap_M1_table[2 + rtb_Sum1_jt] * - rtb_Saturation); - - /* End of Outputs for SubSystem: '/COM_Method' */ - } - - /* End of If: '/If' */ - - /* Outport: '/DC_phaA' incorporates: - * DataTypeConversion: '/Data Type Conversion6' - */ - rtY->DC_phaA = (int16_T)(DataTypeConversion2 >> 4); - - /* Outport: '/DC_phaB' incorporates: - * DataTypeConversion: '/Data Type Conversion6' - */ - rtY->DC_phaB = (int16_T)(rtb_Saturation1 >> 4); - - /* Update for UnitDelay: '/UnitDelay3' incorporates: - * Inport: '/b_hallA ' - */ - rtDW->UnitDelay3_DSTATE_fy = rtU->b_hallA; - - /* Update for UnitDelay: '/UnitDelay1' incorporates: - * Inport: '/b_hallB' - */ - rtDW->UnitDelay1_DSTATE = rtU->b_hallB; - - /* Update for UnitDelay: '/UnitDelay2' incorporates: - * Inport: '/b_hallC' - */ - rtDW->UnitDelay2_DSTATE_f = rtU->b_hallC; - - /* Update for UnitDelay: '/UnitDelay3' */ - rtDW->UnitDelay3_DSTATE = rtb_Switch1_l; - - /* Update for UnitDelay: '/UnitDelay4' */ - rtDW->UnitDelay4_DSTATE_e = Abs5; - - /* Update for UnitDelay: '/UnitDelay2' incorporates: - * UnitDelay: '/UnitDelay6' - */ - rtDW->UnitDelay2_DSTATE_c = rtDW->UnitDelay6_DSTATE; - - /* Update for UnitDelay: '/UnitDelay5' */ - rtDW->UnitDelay5_DSTATE_m = rtb_RelationalOperator4_d; - - /* Update for UnitDelay: '/UnitDelay6' */ - rtDW->UnitDelay6_DSTATE = rtb_UnitDelay5_e; - - /* Update for UnitDelay: '/UnitDelay4' */ - rtDW->UnitDelay4_DSTATE_eu = rtb_Saturation; - - /* Outport: '/DC_phaC' incorporates: - * DataTypeConversion: '/Data Type Conversion6' - */ - rtY->DC_phaC = (int16_T)(rtb_Merge1 >> 4); - - /* Outport: '/n_mot' incorporates: - * DataTypeConversion: '/Data Type Conversion1' - */ - rtY->n_mot = (int16_T)(Switch2 >> 4); - - /* Outport: '/a_elecAngle' incorporates: - * DataTypeConversion: '/Data Type Conversion3' - */ - rtY->a_elecAngle = (int16_T)(rtb_Merge_m >> 6); - - /* End of Outputs for SubSystem: '/BLDC_controller' */ - - /* Outport: '/iq' */ - rtY->iq = rtDW->DataTypeConversion[0]; - - /* Outport: '/id' */ - rtY->id = rtDW->DataTypeConversion[1]; -} - -/* Model initialize function */ -void BLDC_controller_initialize(RT_MODEL *const rtM) -{ - P *rtP = ((P *) rtM->defaultParam); - DW *rtDW = ((DW *) rtM->dwork); - - /* Start for Atomic SubSystem: '/BLDC_controller' */ - /* Start for If: '/If1' */ - rtDW->If1_ActiveSubsystem = -1; - - /* Start for IfAction SubSystem: '/Clarke_Park_Transform_Forward' */ - /* Start for If: '/If2' */ - rtDW->If2_ActiveSubsystem_a = -1; - - /* End of Start for SubSystem: '/Clarke_Park_Transform_Forward' */ - - /* Start for Chart: '/Task_Scheduler' incorporates: - * SubSystem: '/F03_Control_Mode_Manager' - */ - /* Start for If: '/If2' */ - rtDW->If2_ActiveSubsystem_f = -1; - - /* Start for Chart: '/Task_Scheduler' incorporates: - * SubSystem: '/Motor_Limitations' - */ - /* Start for If: '/If1' */ - rtDW->If1_ActiveSubsystem_o = -1; - - /* Start for IfAction SubSystem: '/Motor_Limitations_Enabled' */ - /* Start for SwitchCase: '/Switch Case' */ - rtDW->SwitchCase_ActiveSubsystem_d = -1; - - /* End of Start for SubSystem: '/Motor_Limitations_Enabled' */ - - /* Start for Chart: '/Task_Scheduler' incorporates: - * SubSystem: '/FOC' - */ - /* Start for If: '/If1' */ - rtDW->If1_ActiveSubsystem_j = -1; - - /* Start for IfAction SubSystem: '/FOC_Enabled' */ - /* Start for SwitchCase: '/Switch Case' */ - rtDW->SwitchCase_ActiveSubsystem = -1; - - /* Start for If: '/If1' */ - rtDW->If1_ActiveSubsystem_a = -1; - - /* End of Start for SubSystem: '/FOC_Enabled' */ - - /* Start for If: '/If2' */ - rtDW->If2_ActiveSubsystem = -1; - - /* End of Start for SubSystem: '/BLDC_controller' */ - - /* SystemInitialize for Atomic SubSystem: '/BLDC_controller' */ - /* InitializeConditions for UnitDelay: '/UnitDelay3' */ - rtDW->UnitDelay3_DSTATE = rtP->z_maxCntRst; - - /* InitializeConditions for UnitDelay: '/UnitDelay2' */ - rtDW->UnitDelay2_DSTATE_c = true; - - /* SystemInitialize for IfAction SubSystem: '/Raw_Motor_Speed_Estimation' */ - /* SystemInitialize for Outport: '/z_counter' */ - rtDW->z_counterRawPrev = rtP->z_maxCntRst; - - /* End of SystemInitialize for SubSystem: '/Raw_Motor_Speed_Estimation' */ - - /* SystemInitialize for Atomic SubSystem: '/Counter' */ - Counter_Init(&rtDW->Counter_e, rtP->z_maxCntRst); - - /* End of SystemInitialize for SubSystem: '/Counter' */ - - /* SystemInitialize for Chart: '/Task_Scheduler' incorporates: - * SubSystem: '/F02_Diagnostics' - */ - - /* SystemInitialize for IfAction SubSystem: '/Diagnostics_Enabled' */ - - /* SystemInitialize for Atomic SubSystem: '/Debounce_Filter' */ - Debounce_Filter_Init(&rtDW->Debounce_Filter_k); - - /* End of SystemInitialize for SubSystem: '/Debounce_Filter' */ - - /* End of SystemInitialize for SubSystem: '/Diagnostics_Enabled' */ - - /* SystemInitialize for Chart: '/Task_Scheduler' incorporates: - * SubSystem: '/F03_Control_Mode_Manager' - */ - /* SystemInitialize for IfAction SubSystem: '/Open_Mode' */ - /* SystemInitialize for Atomic SubSystem: '/rising_edge_init' */ - /* InitializeConditions for UnitDelay: '/UnitDelay' */ - rtDW->UnitDelay_DSTATE_b = true; - - /* End of SystemInitialize for SubSystem: '/rising_edge_init' */ - /* End of SystemInitialize for SubSystem: '/Open_Mode' */ - - /* SystemInitialize for Chart: '/Task_Scheduler' incorporates: - * SubSystem: '/Motor_Limitations' - */ - /* SystemInitialize for IfAction SubSystem: '/Motor_Limitations_Enabled' */ - - /* SystemInitialize for IfAction SubSystem: '/Voltage_Mode_Protection' */ - - /* SystemInitialize for Atomic SubSystem: '/I_backCalc_fixdt' */ - I_backCalc_fixdt_Init(&rtDW->I_backCalc_fixdt_i, 65536000); - - /* End of SystemInitialize for SubSystem: '/I_backCalc_fixdt' */ - - /* SystemInitialize for Atomic SubSystem: '/I_backCalc_fixdt1' */ - I_backCalc_fixdt_Init(&rtDW->I_backCalc_fixdt1, 65536000); - - /* End of SystemInitialize for SubSystem: '/I_backCalc_fixdt1' */ - - /* End of SystemInitialize for SubSystem: '/Voltage_Mode_Protection' */ - - /* SystemInitialize for IfAction SubSystem: '/Torque_Mode_Protection' */ - - /* SystemInitialize for Atomic SubSystem: '/I_backCalc_fixdt' */ - I_backCalc_fixdt_Init(&rtDW->I_backCalc_fixdt_j, 58982400); - - /* End of SystemInitialize for SubSystem: '/I_backCalc_fixdt' */ - - /* End of SystemInitialize for SubSystem: '/Torque_Mode_Protection' */ - - /* SystemInitialize for Outport: '/Vd_max' */ - rtDW->Vd_max1 = 14400; - - /* SystemInitialize for Outport: '/Vd_min' */ - rtDW->Gain3 = -14400; - - /* SystemInitialize for Outport: '/Vq_max' */ - rtDW->Vq_max_M1 = 14400; - - /* SystemInitialize for Outport: '/Vq_min' */ - rtDW->Gain5 = -14400; - - /* SystemInitialize for Outport: '/id_max' */ - rtDW->i_max = 12000; - - /* SystemInitialize for Outport: '/id_min' */ - rtDW->Gain4 = -12000; - - /* SystemInitialize for Outport: '/iq_max' */ - rtDW->Divide1_n = 12000; - - /* SystemInitialize for Outport: '/iq_min' */ - rtDW->Gain1 = -12000; - - /* End of SystemInitialize for SubSystem: '/Motor_Limitations_Enabled' */ - - /* SystemInitialize for Chart: '/Task_Scheduler' incorporates: - * SubSystem: '/FOC' - */ - - /* SystemInitialize for IfAction SubSystem: '/FOC_Enabled' */ - - /* SystemInitialize for IfAction SubSystem: '/Speed_Mode' */ - - /* SystemInitialize for Atomic SubSystem: '/PI_clamp_fixdt' */ - PI_clamp_fixdt_d_Init(&rtDW->PI_clamp_fixdt_l4); - - /* End of SystemInitialize for SubSystem: '/PI_clamp_fixdt' */ - - /* End of SystemInitialize for SubSystem: '/Speed_Mode' */ - - /* SystemInitialize for IfAction SubSystem: '/Torque_Mode' */ - - /* SystemInitialize for Atomic SubSystem: '/PI_clamp_fixdt' */ - PI_clamp_fixdt_f_Init(&rtDW->PI_clamp_fixdt_kh); - - /* End of SystemInitialize for SubSystem: '/PI_clamp_fixdt' */ - - /* End of SystemInitialize for SubSystem: '/Torque_Mode' */ - - /* SystemInitialize for IfAction SubSystem: '/Vd_Calculation' */ - - /* SystemInitialize for Atomic SubSystem: '/PI_clamp_fixdt' */ - PI_clamp_fixdt_Init(&rtDW->PI_clamp_fixdt_i); - - /* End of SystemInitialize for SubSystem: '/PI_clamp_fixdt' */ - - /* End of SystemInitialize for SubSystem: '/Vd_Calculation' */ - - /* End of SystemInitialize for SubSystem: '/FOC_Enabled' */ - - /* End of SystemInitialize for SubSystem: '/BLDC_controller' */ -} - -/* - * File trailer for generated code. - * - * [EOF] - */ diff --git a/body/board/bldc/BLDC_controller.h b/body/board/bldc/BLDC_controller.h deleted file mode 100644 index 9d663c24c08a646..000000000000000 --- a/body/board/bldc/BLDC_controller.h +++ /dev/null @@ -1,550 +0,0 @@ -/* - * File: BLDC_controller.h - * - * Code generated for Simulink model 'BLDC_controller'. - * - * Model version : 1.1297 - * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 - * C/C++ source code generated on : Sun Mar 6 11:02:11 2022 - * - * Target selection: ert.tlc - * Embedded hardware selection: ARM Compatible->ARM Cortex - * Emulation hardware selection: - * Differs from embedded hardware (MATLAB Host) - * Code generation objectives: - * 1. Execution efficiency - * 2. RAM efficiency - * Validation result: Not run - */ - -#ifndef RTW_HEADER_BLDC_controller_h_ -#define RTW_HEADER_BLDC_controller_h_ -#include "rtwtypes.h" -#ifndef BLDC_controller_COMMON_INCLUDES_ -# define BLDC_controller_COMMON_INCLUDES_ -#include "rtwtypes.h" -#endif /* BLDC_controller_COMMON_INCLUDES_ */ - -/* Macros for accessing real-time model data structure */ - -/* Forward declaration for rtModel */ -typedef struct tag_RTM RT_MODEL; - -/* Block signals and states (auto storage) for system '/Counter' */ -typedef struct { - int16_T UnitDelay_DSTATE; /* '/UnitDelay' */ -} DW_Counter; - -/* Block signals and states (auto storage) for system '/Low_Pass_Filter' */ -typedef struct { - int32_T UnitDelay1_DSTATE[2]; /* '/UnitDelay1' */ -} DW_Low_Pass_Filter; - -/* Block signals and states (auto storage) for system '/Counter' */ -typedef struct { - uint16_T UnitDelay_DSTATE; /* '/UnitDelay' */ -} DW_Counter_b; - -/* Block signals and states (auto storage) for system '/either_edge' */ -typedef struct { - boolean_T UnitDelay_DSTATE; /* '/UnitDelay' */ -} DW_either_edge; - -/* Block signals and states (auto storage) for system '/Debounce_Filter' */ -typedef struct { - DW_either_edge either_edge_p; /* '/either_edge' */ - DW_Counter_b Counter_e; /* '/Counter' */ - DW_Counter_b Counter_n1; /* '/Counter' */ - boolean_T UnitDelay_DSTATE; /* '/UnitDelay' */ -} DW_Debounce_Filter; - -/* Block signals and states (auto storage) for system '/I_backCalc_fixdt' */ -typedef struct { - int32_T UnitDelay_DSTATE; /* '/UnitDelay' */ - int32_T UnitDelay_DSTATE_m; /* '/UnitDelay' */ -} DW_I_backCalc_fixdt; - -/* Block signals and states (auto storage) for system '/PI_clamp_fixdt' */ -typedef struct { - int32_T ResettableDelay_DSTATE; /* '/Resettable Delay' */ - uint8_T icLoad; /* '/Resettable Delay' */ - boolean_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ -} DW_PI_clamp_fixdt; - -/* Block signals and states (auto storage) for system '/PI_clamp_fixdt' */ -typedef struct { - int32_T ResettableDelay_DSTATE; /* '/Resettable Delay' */ - uint8_T icLoad; /* '/Resettable Delay' */ - boolean_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ -} DW_PI_clamp_fixdt_m; - -/* Block signals and states (auto storage) for system '/PI_clamp_fixdt' */ -typedef struct { - int16_T ResettableDelay_DSTATE; /* '/Resettable Delay' */ - uint8_T icLoad; /* '/Resettable Delay' */ - boolean_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ -} DW_PI_clamp_fixdt_g; - -/* Block signals and states (auto storage) for system '' */ -typedef struct { - DW_PI_clamp_fixdt_g PI_clamp_fixdt_kh;/* '/PI_clamp_fixdt' */ - DW_PI_clamp_fixdt_m PI_clamp_fixdt_l4;/* '/PI_clamp_fixdt' */ - DW_PI_clamp_fixdt PI_clamp_fixdt_i; /* '/PI_clamp_fixdt' */ - DW_I_backCalc_fixdt I_backCalc_fixdt_j;/* '/I_backCalc_fixdt' */ - DW_I_backCalc_fixdt I_backCalc_fixdt1;/* '/I_backCalc_fixdt1' */ - DW_I_backCalc_fixdt I_backCalc_fixdt_i;/* '/I_backCalc_fixdt' */ - DW_either_edge either_edge_i; /* '/either_edge' */ - DW_Debounce_Filter Debounce_Filter_k;/* '/Debounce_Filter' */ - DW_Low_Pass_Filter Low_Pass_Filter_m;/* '/Low_Pass_Filter' */ - DW_Counter Counter_e; /* '/Counter' */ - int32_T Divide1; /* '/Divide1' */ - int32_T UnitDelay_DSTATE; /* '/UnitDelay' */ - int16_T Gain4_e[3]; /* '/Gain4' */ - int16_T DataTypeConversion[2]; /* '/Data Type Conversion' */ - int16_T z_counterRawPrev; /* '/z_counterRawPrev' */ - int16_T Merge; /* '/Merge' */ - int16_T Switch1; /* '/Switch1' */ - int16_T Vd_max1; /* '/Vd_max1' */ - int16_T Gain3; /* '/Gain3' */ - int16_T Vq_max_M1; /* '/Vq_max_M1' */ - int16_T Gain5; /* '/Gain5' */ - int16_T i_max; /* '/i_max' */ - int16_T Divide1_n; /* '/Divide1' */ - int16_T Gain1; /* '/Gain1' */ - int16_T Gain4; /* '/Gain4' */ - int16_T Switch2_i; /* '/Switch2' */ - int16_T Switch2_o; /* '/Switch2' */ - int16_T Switch2_a; /* '/Switch2' */ - int16_T Divide3; /* '/Divide3' */ - int16_T Merge1; /* '/Merge1' */ - int16_T Abs1; /* '/Abs1' */ - int16_T Abs5_h; /* '/Abs5' */ - int16_T Divide11; /* '/Divide11' */ - int16_T r_sin_M1; /* '/r_sin_M1' */ - int16_T r_cos_M1; /* '/r_cos_M1' */ - int16_T UnitDelay3_DSTATE; /* '/UnitDelay3' */ - int16_T UnitDelay4_DSTATE; /* '/UnitDelay4' */ - int16_T UnitDelay2_DSTATE; /* '/UnitDelay2' */ - int16_T UnitDelay3_DSTATE_o; /* '/UnitDelay3' */ - int16_T UnitDelay5_DSTATE; /* '/UnitDelay5' */ - int16_T UnitDelay4_DSTATE_e; /* '/UnitDelay4' */ - int16_T UnitDelay4_DSTATE_eu; /* '/UnitDelay4' */ - int8_T Switch2_e; /* '/Switch2' */ - int8_T UnitDelay2_DSTATE_b; /* '/UnitDelay2' */ - int8_T If1_ActiveSubsystem; /* '/If1' */ - int8_T If2_ActiveSubsystem; /* '/If2' */ - int8_T If1_ActiveSubsystem_j; /* '/If1' */ - int8_T SwitchCase_ActiveSubsystem; /* '/Switch Case' */ - int8_T If1_ActiveSubsystem_a; /* '/If1' */ - int8_T If1_ActiveSubsystem_o; /* '/If1' */ - int8_T SwitchCase_ActiveSubsystem_d; /* '/Switch Case' */ - int8_T If2_ActiveSubsystem_f; /* '/If2' */ - int8_T If2_ActiveSubsystem_a; /* '/If2' */ - uint8_T z_ctrlMod; /* '/F03_02_Control_Mode_Manager' */ - uint8_T UnitDelay3_DSTATE_fy; /* '/UnitDelay3' */ - uint8_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ - uint8_T UnitDelay2_DSTATE_f; /* '/UnitDelay2' */ - uint8_T UnitDelay_DSTATE_e; /* '/UnitDelay' */ - uint8_T is_active_c1_BLDC_controller;/* '/F03_02_Control_Mode_Manager' */ - uint8_T is_c1_BLDC_controller; /* '/F03_02_Control_Mode_Manager' */ - uint8_T is_ACTIVE; /* '/F03_02_Control_Mode_Manager' */ - boolean_T Merge_p; /* '/Merge' */ - boolean_T dz_cntTrnsDet; /* '/dz_cntTrnsDet' */ - boolean_T UnitDelay2_DSTATE_c; /* '/UnitDelay2' */ - boolean_T UnitDelay5_DSTATE_m; /* '/UnitDelay5' */ - boolean_T UnitDelay6_DSTATE; /* '/UnitDelay6' */ - boolean_T UnitDelay_DSTATE_b; /* '/UnitDelay' */ - boolean_T UnitDelay1_DSTATE_n; /* '/UnitDelay1' */ - boolean_T n_commDeacv_Mode; /* '/n_commDeacv' */ - boolean_T dz_cntTrnsDet_Mode; /* '/dz_cntTrnsDet' */ -} DW; - -/* Constant parameters (auto storage) */ -typedef struct { - /* Computed Parameter: r_sin_M1_Table - * Referenced by: '/r_sin_M1' - */ - int16_T r_sin_M1_Table[181]; - - /* Computed Parameter: r_cos_M1_Table - * Referenced by: '/r_cos_M1' - */ - int16_T r_cos_M1_Table[181]; - - /* Computed Parameter: r_sin3PhaA_M1_Table - * Referenced by: '/r_sin3PhaA_M1' - */ - int16_T r_sin3PhaA_M1_Table[181]; - - /* Computed Parameter: r_sin3PhaB_M1_Table - * Referenced by: '/r_sin3PhaB_M1' - */ - int16_T r_sin3PhaB_M1_Table[181]; - - /* Computed Parameter: r_sin3PhaC_M1_Table - * Referenced by: '/r_sin3PhaC_M1' - */ - int16_T r_sin3PhaC_M1_Table[181]; - - /* Computed Parameter: iq_maxSca_M1_Table - * Referenced by: '/iq_maxSca_M1' - */ - uint16_T iq_maxSca_M1_Table[50]; - - /* Computed Parameter: z_commutMap_M1_table - * Referenced by: '/z_commutMap_M1' - */ - int8_T z_commutMap_M1_table[18]; - - /* Computed Parameter: vec_hallToPos_Value - * Referenced by: '/vec_hallToPos' - */ - int8_T vec_hallToPos_Value[8]; -} ConstP; - -/* External inputs (root inport signals with auto storage) */ -typedef struct { - boolean_T b_motEna; /* '/b_motEna' */ - uint8_T z_ctrlModReq; /* '/z_ctrlModReq' */ - int16_T r_inpTgt; /* '/r_inpTgt' */ - uint8_T b_hallA; /* '/b_hallA ' */ - uint8_T b_hallB; /* '/b_hallB' */ - uint8_T b_hallC; /* '/b_hallC' */ - int16_T i_phaAB; /* '/i_phaAB' */ - int16_T i_phaBC; /* '/i_phaBC' */ - int16_T i_DCLink; /* '/i_DCLink' */ - int16_T a_mechAngle; /* '/a_mechAngle' */ -} ExtU; - -/* External outputs (root outports fed by signals with auto storage) */ -typedef struct { - int16_T DC_phaA; /* '/DC_phaA' */ - int16_T DC_phaB; /* '/DC_phaB' */ - int16_T DC_phaC; /* '/DC_phaC' */ - uint8_T z_errCode; /* '/z_errCode' */ - int16_T n_mot; /* '/n_mot' */ - int16_T a_elecAngle; /* '/a_elecAngle' */ - int16_T iq; /* '/iq' */ - int16_T id; /* '/id' */ -} ExtY; - -/* Parameters (auto storage) */ -struct P_ { - int32_T dV_openRate; /* Variable: dV_openRate - * Referenced by: '/dV_openRate' - */ - int16_T dz_cntTrnsDetHi; /* Variable: dz_cntTrnsDetHi - * Referenced by: '/dz_cntTrnsDet' - */ - int16_T dz_cntTrnsDetLo; /* Variable: dz_cntTrnsDetLo - * Referenced by: '/dz_cntTrnsDet' - */ - int16_T n_cruiseMotTgt; /* Variable: n_cruiseMotTgt - * Referenced by: '/n_cruiseMotTgt' - */ - int16_T z_maxCntRst; /* Variable: z_maxCntRst - * Referenced by: - * '/Counter' - * '/z_maxCntRst' - * '/z_maxCntRst2' - * '/UnitDelay3' - * '/z_counter' - */ - uint16_T cf_speedCoef; /* Variable: cf_speedCoef - * Referenced by: '/cf_speedCoef' - */ - uint16_T t_errDequal; /* Variable: t_errDequal - * Referenced by: '/t_errDequal' - */ - uint16_T t_errQual; /* Variable: t_errQual - * Referenced by: '/t_errQual' - */ - int16_T Vd_max; /* Variable: Vd_max - * Referenced by: - * '/Vd_max' - * '/Vd_max1' - */ - int16_T Vq_max_M1[46]; /* Variable: Vq_max_M1 - * Referenced by: '/Vq_max_M1' - */ - int16_T Vq_max_XA[46]; /* Variable: Vq_max_XA - * Referenced by: '/Vq_max_XA' - */ - int16_T a_phaAdvMax; /* Variable: a_phaAdvMax - * Referenced by: '/a_phaAdvMax' - */ - int16_T i_max; /* Variable: i_max - * Referenced by: - * '/i_max' - * '/i_max' - */ - int16_T id_fieldWeakMax; /* Variable: id_fieldWeakMax - * Referenced by: '/id_fieldWeakMax' - */ - int16_T n_commAcvLo; /* Variable: n_commAcvLo - * Referenced by: '/n_commDeacv' - */ - int16_T n_commDeacvHi; /* Variable: n_commDeacvHi - * Referenced by: '/n_commDeacv' - */ - int16_T n_fieldWeakAuthHi; /* Variable: n_fieldWeakAuthHi - * Referenced by: '/n_fieldWeakAuthHi' - */ - int16_T n_fieldWeakAuthLo; /* Variable: n_fieldWeakAuthLo - * Referenced by: '/n_fieldWeakAuthLo' - */ - int16_T n_max; /* Variable: n_max - * Referenced by: - * '/n_max' - * '/n_max1' - */ - int16_T n_stdStillDet; /* Variable: n_stdStillDet - * Referenced by: '/n_stdStillDet' - */ - int16_T r_errInpTgtThres; /* Variable: r_errInpTgtThres - * Referenced by: '/r_errInpTgtThres' - */ - int16_T r_fieldWeakHi; /* Variable: r_fieldWeakHi - * Referenced by: '/r_fieldWeakHi' - */ - int16_T r_fieldWeakLo; /* Variable: r_fieldWeakLo - * Referenced by: '/r_fieldWeakLo' - */ - uint16_T cf_KbLimProt; /* Variable: cf_KbLimProt - * Referenced by: - * '/cf_KbLimProt' - * '/cf_KbLimProt' - */ - uint16_T cf_idKp; /* Variable: cf_idKp - * Referenced by: '/cf_idKp1' - */ - uint16_T cf_iqKp; /* Variable: cf_iqKp - * Referenced by: '/cf_iqKp' - */ - uint16_T cf_nKp; /* Variable: cf_nKp - * Referenced by: '/cf_nKp' - */ - uint16_T cf_currFilt; /* Variable: cf_currFilt - * Referenced by: '/cf_currFilt' - */ - uint16_T cf_idKi; /* Variable: cf_idKi - * Referenced by: '/cf_idKi1' - */ - uint16_T cf_iqKi; /* Variable: cf_iqKi - * Referenced by: '/cf_iqKi' - */ - uint16_T cf_iqKiLimProt; /* Variable: cf_iqKiLimProt - * Referenced by: - * '/cf_iqKiLimProt' - * '/cf_iqKiLimProt' - */ - uint16_T cf_nKi; /* Variable: cf_nKi - * Referenced by: '/cf_nKi' - */ - uint16_T cf_nKiLimProt; /* Variable: cf_nKiLimProt - * Referenced by: - * '/cf_nKiLimProt' - * '/cf_nKiLimProt' - */ - uint8_T n_polePairs; /* Variable: n_polePairs - * Referenced by: '/n_polePairs' - */ - uint8_T z_ctrlTypSel; /* Variable: z_ctrlTypSel - * Referenced by: '/z_ctrlTypSel' - */ - uint8_T z_selPhaCurMeasABC; /* Variable: z_selPhaCurMeasABC - * Referenced by: '/z_selPhaCurMeasABC' - */ - boolean_T b_angleMeasEna; /* Variable: b_angleMeasEna - * Referenced by: - * '/b_angleMeasEna' - * '/b_angleMeasEna' - */ - boolean_T b_cruiseCtrlEna; /* Variable: b_cruiseCtrlEna - * Referenced by: '/b_cruiseCtrlEna' - */ - boolean_T b_diagEna; /* Variable: b_diagEna - * Referenced by: '/b_diagEna' - */ - boolean_T b_fieldWeakEna; /* Variable: b_fieldWeakEna - * Referenced by: - * '/b_fieldWeakEna' - * '/b_fieldWeakEna' - */ -}; - -/* Parameters (auto storage) */ -typedef struct P_ P; - -/* Real-time Model Data Structure */ -struct tag_RTM { - P *defaultParam; - ExtU *inputs; - ExtY *outputs; - DW *dwork; -}; - -/* Constant parameters (auto storage) */ -extern const ConstP rtConstP; - -/* Model entry point functions */ -extern void BLDC_controller_initialize(RT_MODEL *const rtM); -extern void BLDC_controller_step(RT_MODEL *const rtM); - -/*- - * These blocks were eliminated from the model due to optimizations: - * - * Block '/Scope2' : Unused code path elimination - * Block '/Scope' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Scope12' : Unused code path elimination - * Block '/Scope8' : Unused code path elimination - * Block '/toNegative' : Unused code path elimination - * Block '/Scope' : Unused code path elimination - * Block '/Data Type Conversion' : Eliminate redundant data type conversion - * Block '/Data Type Conversion1' : Eliminate redundant data type conversion - */ - -/*- - * The generated code includes comments that allow you to trace directly - * back to the appropriate location in the model. The basic format - * is /block_name, where system is the system number (uniquely - * assigned by Simulink) and block_name is the name of the block. - * - * Note that this particular code originates from a subsystem build, - * and has its own system numbers different from the parent model. - * Refer to the system hierarchy for this subsystem below, and use the - * MATLAB hilite_system command to trace the generated code back - * to the parent model. For example, - * - * hilite_system('BLDCmotor_FOC_R2017b_fixdt/BLDC_controller') - opens subsystem BLDCmotor_FOC_R2017b_fixdt/BLDC_controller - * hilite_system('BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/Kp') - opens and selects block Kp - * - * Here is the system hierarchy for this model - * - * '' : 'BLDCmotor_FOC_R2017b_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/Call_Scheduler' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F04_Field_Weakening' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/Task_Scheduler' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_01_Edge_Detector' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_02_Position_Calculation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_03_Direction_Detection' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_04_Speed_Estimation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_05_Electrical_Angle_Estimation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_06_Electrical_Angle_Measurement' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_04_Speed_Estimation/Counter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_04_Speed_Estimation/Raw_Motor_Speed_Estimation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_04_Speed_Estimation/Counter/rst_Delay' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_06_Electrical_Angle_Measurement/Modulo_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/either_edge' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Default' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Dequalification' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Qualification' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/either_edge' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Dequalification/Counter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Dequalification/Counter/rst_Delay' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Qualification/Counter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Qualification/Counter/rst_Delay' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_01_Mode_Transition_Calculation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_02_Control_Mode_Manager' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Default_Control_Type' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Default_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/FOC_Control_Type' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode/Rate_Limiter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode/rising_edge_init' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode/Rate_Limiter/Delay_Init1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode/Rate_Limiter/Saturation Dynamic' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F04_Field_Weakening/Field_Weakening_Enabled' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F04_Field_Weakening/Field_Weakening_Enabled/Saturation Dynamic' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F04_Field_Weakening/Field_Weakening_Enabled/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Inverse' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Clarke_Transform' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Current_Filtering' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Park_Transform' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Sine_Cosine_Approximation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Clarke_Transform/Clarke_PhasesAB' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Clarke_Transform/Clarke_PhasesAC' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Clarke_Transform/Clarke_PhasesBC' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Current_Filtering/Low_Pass_Filter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Inverse/Inv_Clarke_Transform' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Inverse/Inv_Park_Transform' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Open_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Voltage_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode/PI_clamp_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode/PI_clamp_fixdt/Clamping_circuit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode/PI_clamp_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode/PI_clamp_fixdt/Saturation_hit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/PI_clamp_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/PI_clamp_fixdt/Clamping_circuit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/PI_clamp_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/PI_clamp_fixdt/Saturation_hit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/PI_clamp_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/Saturation Dynamic' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/PI_clamp_fixdt/Clamping_circuit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/PI_clamp_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/PI_clamp_fixdt/Saturation_hit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Voltage_Mode/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Speed_Mode_Protection' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Torque_Mode_Protection' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Speed_Mode_Protection/Saturation Dynamic' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Torque_Mode_Protection/I_backCalc_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Torque_Mode_Protection/I_backCalc_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Torque_Mode_Protection/I_backCalc_fixdt/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt1/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt1/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/COM_Method' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/FOC_Method' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/SIN_Method' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/SIN_Method/Final_Phase_Advance_Calculation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/SIN_Method/Final_Phase_Advance_Calculation/Modulo_fixdt' - */ -#endif /* RTW_HEADER_BLDC_controller_h_ */ - -/* - * File trailer for generated code. - * - * [EOF] - */ diff --git a/body/board/bldc/BLDC_controller_data.c b/body/board/bldc/BLDC_controller_data.c deleted file mode 100644 index 626c5371980b893..000000000000000 --- a/body/board/bldc/BLDC_controller_data.c +++ /dev/null @@ -1,386 +0,0 @@ -/* - * File: BLDC_controller_data.c - * - * Code generated for Simulink model 'BLDC_controller'. - * - * Model version : 1.1297 - * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 - * C/C++ source code generated on : Sun Mar 6 11:02:11 2022 - * - * Target selection: ert.tlc - * Embedded hardware selection: ARM Compatible->ARM Cortex - * Emulation hardware selection: - * Differs from embedded hardware (MATLAB Host) - * Code generation objectives: - * 1. Execution efficiency - * 2. RAM efficiency - * Validation result: Not run - */ - -#include "BLDC_controller.h" - -/* Constant parameters (auto storage) */ -const ConstP rtConstP = { - /* Computed Parameter: r_sin_M1_Table - * Referenced by: '/r_sin_M1' - */ - { 8192, 8682, 9162, 9630, 10087, 10531, 10963, 11381, 11786, 12176, 12551, - 12911, 13255, 13583, 13894, 14189, 14466, 14726, 14968, 15191, 15396, 15582, - 15749, 15897, 16026, 16135, 16225, 16294, 16344, 16374, 16384, 16374, 16344, - 16294, 16225, 16135, 16026, 15897, 15749, 15582, 15396, 15191, 14968, 14726, - 14466, 14189, 13894, 13583, 13255, 12911, 12551, 12176, 11786, 11381, 10963, - 10531, 10087, 9630, 9162, 8682, 8192, 7692, 7182, 6664, 6138, 5604, 5063, - 4516, 3964, 3406, 2845, 2280, 1713, 1143, 572, 0, -572, -1143, -1713, -2280, - -2845, -3406, -3964, -4516, -5063, -5604, -6138, -6664, -7182, -7692, -8192, - -8682, -9162, -9630, -10087, -10531, -10963, -11381, -11786, -12176, -12551, - -12911, -13255, -13583, -13894, -14189, -14466, -14726, -14968, -15191, - -15396, -15582, -15749, -15897, -16026, -16135, -16225, -16294, -16344, - -16374, -16384, -16374, -16344, -16294, -16225, -16135, -16026, -15897, - -15749, -15582, -15396, -15191, -14968, -14726, -14466, -14189, -13894, - -13583, -13255, -12911, -12551, -12176, -11786, -11381, -10963, -10531, - -10087, -9630, -9162, -8682, -8192, -7692, -7182, -6664, -6138, -5604, -5063, - -4516, -3964, -3406, -2845, -2280, -1713, -1143, -572, 0, 572, 1143, 1713, - 2280, 2845, 3406, 3964, 4516, 5063, 5604, 6138, 6664, 7182, 7692, 8192 }, - - /* Computed Parameter: r_cos_M1_Table - * Referenced by: '/r_cos_M1' - */ - { 14189, 13894, 13583, 13255, 12911, 12551, 12176, 11786, 11381, 10963, 10531, - 10087, 9630, 9162, 8682, 8192, 7692, 7182, 6664, 6138, 5604, 5063, 4516, - 3964, 3406, 2845, 2280, 1713, 1143, 572, 0, -572, -1143, -1713, -2280, -2845, - -3406, -3964, -4516, -5063, -5604, -6138, -6664, -7182, -7692, -8192, -8682, - -9162, -9630, -10087, -10531, -10963, -11381, -11786, -12176, -12551, -12911, - -13255, -13583, -13894, -14189, -14466, -14726, -14968, -15191, -15396, - -15582, -15749, -15897, -16026, -16135, -16225, -16294, -16344, -16374, - -16384, -16374, -16344, -16294, -16225, -16135, -16026, -15897, -15749, - -15582, -15396, -15191, -14968, -14726, -14466, -14189, -13894, -13583, - -13255, -12911, -12551, -12176, -11786, -11381, -10963, -10531, -10087, - -9630, -9162, -8682, -8192, -7692, -7182, -6664, -6138, -5604, -5063, -4516, - -3964, -3406, -2845, -2280, -1713, -1143, -572, 0, 572, 1143, 1713, 2280, - 2845, 3406, 3964, 4516, 5063, 5604, 6138, 6664, 7182, 7692, 8192, 8682, 9162, - 9630, 10087, 10531, 10963, 11381, 11786, 12176, 12551, 12911, 13255, 13583, - 13894, 14189, 14466, 14726, 14968, 15191, 15396, 15582, 15749, 15897, 16026, - 16135, 16225, 16294, 16344, 16374, 16384, 16374, 16344, 16294, 16225, 16135, - 16026, 15897, 15749, 15582, 15396, 15191, 14968, 14726, 14466, 14189 }, - - /* Computed Parameter: r_sin3PhaA_M1_Table - * Referenced by: '/r_sin3PhaA_M1' - */ - { -13091, -13634, -14126, -14565, -14953, -15289, -15577, -15816, -16009, - -16159, -16269, -16340, -16377, -16383, -16362, -16317, -16253, -16172, - -16079, -15977, -15870, -15762, -15656, -15555, -15461, -15377, -15306, - -15248, -15206, -15180, -15172, -15180, -15206, -15248, -15306, -15377, - -15461, -15555, -15656, -15762, -15870, -15977, -16079, -16172, -16253, - -16317, -16362, -16383, -16377, -16340, -16269, -16159, -16009, -15816, - -15577, -15289, -14953, -14565, -14126, -13634, -13091, -12496, -11849, - -11154, -10411, -9623, -8791, -7921, -7014, -6075, -5107, -4115, -3104, - -2077, -1041, 0, 1041, 2077, 3104, 4115, 5107, 6075, 7014, 7921, 8791, 9623, - 10411, 11154, 11849, 12496, 13091, 13634, 14126, 14565, 14953, 15289, 15577, - 15816, 16009, 16159, 16269, 16340, 16377, 16383, 16362, 16317, 16253, 16172, - 16079, 15977, 15870, 15762, 15656, 15555, 15461, 15377, 15306, 15248, 15206, - 15180, 15172, 15180, 15206, 15248, 15306, 15377, 15461, 15555, 15656, 15762, - 15870, 15977, 16079, 16172, 16253, 16317, 16362, 16383, 16377, 16340, 16269, - 16159, 16009, 15816, 15577, 15289, 14953, 14565, 14126, 13634, 13091, 12496, - 11849, 11154, 10411, 9623, 8791, 7921, 7014, 6075, 5107, 4115, 3104, 2077, - 1041, 0, -1041, -2077, -3104, -4115, -5107, -6075, -7014, -7921, -8791, - -9623, -10411, -11154, -11849, -12496, -13091 }, - - /* Computed Parameter: r_sin3PhaB_M1_Table - * Referenced by: '/r_sin3PhaB_M1' - */ - { 15172, 15180, 15206, 15248, 15306, 15377, 15461, 15555, 15656, 15762, 15870, - 15977, 16079, 16172, 16253, 16317, 16362, 16383, 16377, 16340, 16269, 16159, - 16009, 15816, 15577, 15289, 14953, 14565, 14126, 13634, 13091, 12496, 11849, - 11154, 10411, 9623, 8791, 7921, 7014, 6075, 5107, 4115, 3104, 2077, 1041, 0, - -1041, -2077, -3104, -4115, -5107, -6075, -7014, -7921, -8791, -9623, -10411, - -11154, -11849, -12496, -13091, -13634, -14126, -14565, -14953, -15289, - -15577, -15816, -16009, -16159, -16269, -16340, -16377, -16383, -16362, - -16317, -16253, -16172, -16079, -15977, -15870, -15762, -15656, -15555, - -15461, -15377, -15306, -15248, -15206, -15180, -15172, -15180, -15206, - -15248, -15306, -15377, -15461, -15555, -15656, -15762, -15870, -15977, - -16079, -16172, -16253, -16317, -16362, -16383, -16377, -16340, -16269, - -16159, -16009, -15816, -15577, -15289, -14953, -14565, -14126, -13634, - -13091, -12496, -11849, -11154, -10411, -9623, -8791, -7921, -7014, -6075, - -5107, -4115, -3104, -2077, -1041, 0, 1041, 2077, 3104, 4115, 5107, 6075, - 7014, 7921, 8791, 9623, 10411, 11154, 11849, 12496, 13091, 13634, 14126, - 14565, 14953, 15289, 15577, 15816, 16009, 16159, 16269, 16340, 16377, 16383, - 16362, 16317, 16253, 16172, 16079, 15977, 15870, 15762, 15656, 15555, 15461, - 15377, 15306, 15248, 15206, 15180, 15172 }, - - /* Computed Parameter: r_sin3PhaC_M1_Table - * Referenced by: '/r_sin3PhaC_M1' - */ - { -13091, -12496, -11849, -11154, -10411, -9623, -8791, -7921, -7014, -6075, - -5107, -4115, -3104, -2077, -1041, 0, 1041, 2077, 3104, 4115, 5107, 6075, - 7014, 7921, 8791, 9623, 10411, 11154, 11849, 12496, 13091, 13634, 14126, - 14565, 14953, 15289, 15577, 15816, 16009, 16159, 16269, 16340, 16377, 16383, - 16362, 16317, 16253, 16172, 16079, 15977, 15870, 15762, 15656, 15555, 15461, - 15377, 15306, 15248, 15206, 15180, 15172, 15180, 15206, 15248, 15306, 15377, - 15461, 15555, 15656, 15762, 15870, 15977, 16079, 16172, 16253, 16317, 16362, - 16383, 16377, 16340, 16269, 16159, 16009, 15816, 15577, 15289, 14953, 14565, - 14126, 13634, 13091, 12496, 11849, 11154, 10411, 9623, 8791, 7921, 7014, - 6075, 5107, 4115, 3104, 2077, 1041, 0, -1041, -2077, -3104, -4115, -5107, - -6075, -7014, -7921, -8791, -9623, -10411, -11154, -11849, -12496, -13091, - -13634, -14126, -14565, -14953, -15289, -15577, -15816, -16009, -16159, - -16269, -16340, -16377, -16383, -16362, -16317, -16253, -16172, -16079, - -15977, -15870, -15762, -15656, -15555, -15461, -15377, -15306, -15248, - -15206, -15180, -15172, -15180, -15206, -15248, -15306, -15377, -15461, - -15555, -15656, -15762, -15870, -15977, -16079, -16172, -16253, -16317, - -16362, -16383, -16377, -16340, -16269, -16159, -16009, -15816, -15577, - -15289, -14953, -14565, -14126, -13634, -13091 }, - - /* Computed Parameter: iq_maxSca_M1_Table - * Referenced by: '/iq_maxSca_M1' - */ - { 65535U, 65523U, 65484U, 65418U, 65326U, 65207U, 65062U, 64890U, 64691U, - 64465U, 64211U, 63930U, 63620U, 63281U, 62913U, 62516U, 62088U, 61630U, - 61140U, 60618U, 60062U, 59473U, 58848U, 58187U, 57489U, 56752U, 55974U, - 55155U, 54291U, 53381U, 52422U, 51413U, 50349U, 49227U, 48043U, 46792U, - 45470U, 44069U, 42581U, 40997U, 39307U, 37494U, 35541U, 33422U, 31105U, - 28540U, 25655U, 22323U, 18304U, 12974U }, - - /* Computed Parameter: z_commutMap_M1_table - * Referenced by: '/z_commutMap_M1' - */ - { -1, 1, 0, -1, 0, 1, 0, -1, 1, 1, -1, 0, 1, 0, -1, 0, 1, -1 }, - - /* Computed Parameter: vec_hallToPos_Value - * Referenced by: '/vec_hallToPos' - */ - { 0, 2, 0, 1, 4, 3, 5, 0 } -}; - -P rtP_Left = { - /* Variable: dV_openRate - * Referenced by: '/dV_openRate' - */ - 12288, - - /* Variable: dz_cntTrnsDetHi - * Referenced by: '/dz_cntTrnsDet' - */ - 40, - - /* Variable: dz_cntTrnsDetLo - * Referenced by: '/dz_cntTrnsDet' - */ - 20, - - /* Variable: n_cruiseMotTgt - * Referenced by: '/n_cruiseMotTgt' - */ - 0, - - /* Variable: z_maxCntRst - * Referenced by: - * '/Counter' - * '/z_maxCntRst' - * '/z_maxCntRst2' - * '/UnitDelay3' - * '/z_counter' - */ - 2000, - - /* Variable: cf_speedCoef - * Referenced by: '/cf_speedCoef' - */ - 10667U, - - /* Variable: t_errDequal - * Referenced by: '/t_errDequal' - */ - 9600U, - - /* Variable: t_errQual - * Referenced by: '/t_errQual' - */ - 1280U, - - /* Variable: Vd_max - * Referenced by: - * '/Vd_max' - * '/Vd_max1' - */ - 14400, - - /* Variable: Vq_max_M1 - * Referenced by: '/Vq_max_M1' - */ - { 14400, 14396, 14386, 14368, 14343, 14311, 14271, 14225, 14171, 14109, 14040, - 13963, 13879, 13786, 13685, 13576, 13459, 13333, 13198, 13053, 12900, 12736, - 12562, 12377, 12181, 11973, 11753, 11520, 11273, 11011, 10733, 10438, 10124, - 9790, 9433, 9051, 8640, 8196, 7713, 7184, 6597, 5935, 5170, 4245, 3019, 0 }, - - /* Variable: Vq_max_XA - * Referenced by: '/Vq_max_XA' - */ - { 0, 320, 640, 960, 1280, 1600, 1920, 2240, 2560, 2880, 3200, 3520, 3840, 4160, - 4480, 4800, 5120, 5440, 5760, 6080, 6400, 6720, 7040, 7360, 7680, 8000, 8320, - 8640, 8960, 9280, 9600, 9920, 10240, 10560, 10880, 11200, 11520, 11840, - 12160, 12480, 12800, 13120, 13440, 13760, 14080, 14400 }, - - /* Variable: a_phaAdvMax - * Referenced by: '/a_phaAdvMax' - */ - 400, - - /* Variable: i_max - * Referenced by: - * '/i_max' - * '/i_max' - */ - 12000, - - /* Variable: id_fieldWeakMax - * Referenced by: '/id_fieldWeakMax' - */ - 4000, - - /* Variable: n_commAcvLo - * Referenced by: '/n_commDeacv' - */ - 240, - - /* Variable: n_commDeacvHi - * Referenced by: '/n_commDeacv' - */ - 480, - - /* Variable: n_fieldWeakAuthHi - * Referenced by: '/n_fieldWeakAuthHi' - */ - 6400, - - /* Variable: n_fieldWeakAuthLo - * Referenced by: '/n_fieldWeakAuthLo' - */ - 4800, - - /* Variable: n_max - * Referenced by: - * '/n_max' - * '/n_max1' - */ - 16000, - - /* Variable: n_stdStillDet - * Referenced by: '/n_stdStillDet' - */ - 48, - - /* Variable: r_errInpTgtThres - * Referenced by: '/r_errInpTgtThres' - */ - 9600, - - /* Variable: r_fieldWeakHi - * Referenced by: '/r_fieldWeakHi' - */ - 16000, - - /* Variable: r_fieldWeakLo - * Referenced by: '/r_fieldWeakLo' - */ - 12000, - - /* Variable: cf_KbLimProt - * Referenced by: - * '/cf_KbLimProt' - * '/cf_KbLimProt' - */ - 768U, - - /* Variable: cf_idKp - * Referenced by: '/cf_idKp1' - */ - 819U, - - /* Variable: cf_iqKp - * Referenced by: '/cf_iqKp' - */ - 1229U, - - /* Variable: cf_nKp - * Referenced by: '/cf_nKp' - */ - 4833U, - - /* Variable: cf_currFilt - * Referenced by: '/cf_currFilt' - */ - 7864U, - - /* Variable: cf_idKi - * Referenced by: '/cf_idKi1' - */ - 737U, - - /* Variable: cf_iqKi - * Referenced by: '/cf_iqKi' - */ - 1229U, - - /* Variable: cf_iqKiLimProt - * Referenced by: - * '/cf_iqKiLimProt' - * '/cf_iqKiLimProt' - */ - 737U, - - /* Variable: cf_nKi - * Referenced by: '/cf_nKi' - */ - 251U, - - /* Variable: cf_nKiLimProt - * Referenced by: - * '/cf_nKiLimProt' - * '/cf_nKiLimProt' - */ - 246U, - - /* Variable: n_polePairs - * Referenced by: '/n_polePairs' - */ - 15U, - - /* Variable: z_ctrlTypSel - * Referenced by: '/z_ctrlTypSel' - */ - 2U, - - /* Variable: z_selPhaCurMeasABC - * Referenced by: '/z_selPhaCurMeasABC' - */ - 0U, - - /* Variable: b_angleMeasEna - * Referenced by: - * '/b_angleMeasEna' - * '/b_angleMeasEna' - */ - 0, - - /* Variable: b_cruiseCtrlEna - * Referenced by: '/b_cruiseCtrlEna' - */ - 0, - - /* Variable: b_diagEna - * Referenced by: '/b_diagEna' - */ - 1, - - /* Variable: b_fieldWeakEna - * Referenced by: - * '/b_fieldWeakEna' - * '/b_fieldWeakEna' - */ - 0 -}; /* Modifiable parameters */ - -/* - * File trailer for generated code. - * - * [EOF] - */ diff --git a/body/board/bldc/bldc.c b/body/board/bldc/bldc.c deleted file mode 100644 index 1c5ea11f50a54b7..000000000000000 --- a/body/board/bldc/bldc.c +++ /dev/null @@ -1,270 +0,0 @@ -/* -* This file implements FOC motor control. -* This control method offers superior performanace -* compared to previous cummutation method. The new method features: -* ► reduced noise and vibrations -* ► smooth torque output -* ► improved motor efficiency -> lower energy consumption -* -* Copyright (C) 2019-2020 Emanuel FERU -* -* This program is free software: you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation, either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, -* but WITHOUT ANY WARRANTY; without even the implied warranty of -* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -* GNU General Public License for more details. -* -* You should have received a copy of the GNU General Public License -* along with this program. If not, see . -*/ - -#include "stm32f4xx_hal.h" -#include "defines.h" -#include "config.h" -#include "util.h" - -// Matlab includes and defines - from auto-code generation -// ############################################################################### -#include "BLDC_controller.h" /* Model's header file */ -#include "rtwtypes.h" - -extern board_t board; - -extern RT_MODEL *const rtM_Left; -extern RT_MODEL *const rtM_Right; - -extern DW rtDW_Left; /* Observable states */ -extern ExtU rtU_Left; /* External inputs */ -extern ExtY rtY_Left; /* External outputs */ -extern P rtP_Left; - -extern DW rtDW_Right; /* Observable states */ -extern ExtU rtU_Right; /* External inputs */ -extern ExtY rtY_Right; /* External outputs */ -// ############################################################################### - -static int16_t pwm_margin; /* This margin allows to have a window in the PWM signal for proper FOC Phase currents measurement */ - -extern uint8_t ctrlModReq; -static int16_t curDC_max = (I_DC_MAX * A2BIT_CONV); -int16_t curL_phaA = 0, curL_phaB = 0, curL_DC = 0; -int16_t curR_phaB = 0, curR_phaC = 0, curR_DC = 0; - -volatile int pwml = 0; -volatile int pwmr = 0; - -extern volatile adc_buf_t adc_buffer; - -uint8_t buzzerFreq = 0; -uint8_t buzzerPattern = 0; -uint8_t buzzerCount = 0; -volatile uint32_t buzzerTimer = 0; -static uint8_t buzzerPrev = 0; -static uint8_t buzzerIdx = 0; - -uint8_t enable_motors = 0; // initially motors are disabled for SAFETY -static uint8_t enableFin = 0; - -static const uint16_t pwm_res = CORE_FREQ / 2 / PWM_FREQ; - -static uint16_t offsetcount = 0; -static int16_t offsetrlA = 2000; -static int16_t offsetrlB = 2000; -static int16_t offsetrrB = 2000; -static int16_t offsetrrC = 2000; -static int16_t offsetdcl = 2000; -static int16_t offsetdcr = 2000; - -int16_t batVoltage = (400 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE; -static int32_t batVoltageFixdt = (400 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE << 16; // Fixed-point filter output initialized at 400 V*100/cell = 4 V/cell converted to fixed-point - -int32_t motPosL = 0; -int32_t motPosR = 0; - -// DMA interrupt frequency =~ 16 kHz -void DMA2_Stream0_IRQHandler(void) { - DMA2->LIFCR = DMA_LIFCR_CTCIF0; - - if(offsetcount < 2000) { // calibrate ADC offsets - offsetcount++; - offsetrlA = (adc_buffer.rlA + offsetrlA) / 2; - offsetrlB = (adc_buffer.rlB + offsetrlB) / 2; - offsetrrB = (adc_buffer.rrB + offsetrrB) / 2; - offsetrrC = (adc_buffer.rrC + offsetrrC) / 2; - offsetdcl = (adc_buffer.dcl + offsetdcl) / 2; - offsetdcr = (adc_buffer.dcr + offsetdcr) / 2; - return; - } - - if (buzzerTimer % 1000 == 0) { // Filter battery voltage at a slower sampling rate - filtLowPass32(adc_buffer.batt1, BAT_FILT_COEF, &batVoltageFixdt); - batVoltage = (int16_t)(batVoltageFixdt >> 16); // convert fixed-point to integer - } - - // Get Left motor currents - curL_phaA = (int16_t)(offsetrlA - adc_buffer.rlA); - curL_phaB = (int16_t)(offsetrlB - adc_buffer.rlB); - curL_DC = (int16_t)(offsetdcl - adc_buffer.dcl); - - // Get Right motor currents - curR_phaB = (int16_t)(offsetrrB - adc_buffer.rrB); - curR_phaC = (int16_t)(offsetrrC - adc_buffer.rrC); - curR_DC = (int16_t)(offsetdcr - adc_buffer.dcr); - - // Disable PWM when current limit is reached (current chopping) - // This is the Level 2 of current protection. The Level 1 should kick in first given by I_MOT_MAX - if(ABS(curL_DC) > curDC_max || enable_motors == 0) { - LEFT_TIM->BDTR &= ~TIM_BDTR_MOE; - } else { - LEFT_TIM->BDTR |= TIM_BDTR_MOE; - } - - if(ABS(curR_DC) > curDC_max || enable_motors == 0) { - RIGHT_TIM->BDTR &= ~TIM_BDTR_MOE; - } else { - RIGHT_TIM->BDTR |= TIM_BDTR_MOE; - } - - // Create square wave for buzzer - buzzerTimer++; - if (buzzerFreq != 0 && (buzzerTimer / 5000) % (buzzerPattern + 1) == 0) { - if (buzzerPrev == 0) { - buzzerPrev = 1; - if (++buzzerIdx > (buzzerCount + 2)) { // pause 2 periods - buzzerIdx = 1; - } - } - if (buzzerTimer % buzzerFreq == 0 && (buzzerIdx <= buzzerCount || buzzerCount == 0)) { - HAL_GPIO_TogglePin(BUZZER_PORT, BUZZER_PIN); - } - } else if (buzzerPrev) { - HAL_GPIO_WritePin(BUZZER_PORT, BUZZER_PIN, GPIO_PIN_RESET); - buzzerPrev = 0; - } - - // Adjust pwm_margin depending on the selected Control Type - if (rtP_Left.z_ctrlTypSel == FOC_CTRL) { - pwm_margin = 110; - } else { - pwm_margin = 0; - } - - // ############################### MOTOR CONTROL ############################### - - int ul, vl, wl; - int ur, vr, wr; - static boolean_T OverrunFlag = false; - - if (OverrunFlag) { - return; - } - OverrunFlag = true; - - /* Make sure to stop BOTH motors in case of an error */ - enableFin = enable_motors && !rtY_Left.z_errCode && !rtY_Right.z_errCode; - - // ========================= LEFT MOTOR ============================ - uint8_t hall_ul = !(board.hall_left.hall_portA->IDR & board.hall_left.hall_pinA); - uint8_t hall_vl = !(board.hall_left.hall_portB->IDR & board.hall_left.hall_pinB); - uint8_t hall_wl = !(board.hall_left.hall_portC->IDR & board.hall_left.hall_pinC); - - rtU_Left.b_motEna = enableFin; - rtU_Left.z_ctrlModReq = ctrlModReq; - rtU_Left.r_inpTgt = pwml; - rtU_Left.b_hallA = hall_wl; - rtU_Left.b_hallB = hall_vl; - rtU_Left.b_hallC = hall_ul; - rtU_Left.i_phaAB = curL_phaA; - rtU_Left.i_phaBC = curL_phaB; - rtU_Left.i_DCLink = curL_DC; - - #ifdef MOTOR_LEFT_ENA - BLDC_controller_step(rtM_Left); - #endif - - ul = rtY_Left.DC_phaA; - vl = rtY_Left.DC_phaB; - wl = rtY_Left.DC_phaC; - - /* Apply commands */ - LEFT_TIM->LEFT_TIM_U = (uint16_t)CLAMP(ul + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); - LEFT_TIM->LEFT_TIM_V = (uint16_t)CLAMP(vl + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); - LEFT_TIM->LEFT_TIM_W = (uint16_t)CLAMP(wl + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); - // ================================================================= - - - // ========================= RIGHT MOTOR =========================== - uint8_t hall_ur = !(board.hall_right.hall_portA->IDR & board.hall_right.hall_pinA); - uint8_t hall_vr = !(board.hall_right.hall_portB->IDR & board.hall_right.hall_pinB); - uint8_t hall_wr = !(board.hall_right.hall_portC->IDR & board.hall_right.hall_pinC); - - rtU_Right.b_motEna = enableFin; - rtU_Right.z_ctrlModReq = ctrlModReq; - rtU_Right.r_inpTgt = pwmr; - rtU_Right.b_hallA = hall_ur; - rtU_Right.b_hallB = hall_vr; - rtU_Right.b_hallC = hall_wr; - rtU_Right.i_phaAB = curR_phaB; - rtU_Right.i_phaBC = curR_phaC; - rtU_Right.i_DCLink = curR_DC; - - #ifdef MOTOR_RIGHT_ENA - BLDC_controller_step(rtM_Right); - #endif - - ur = rtY_Right.DC_phaA; - vr = rtY_Right.DC_phaB; - wr = rtY_Right.DC_phaC; - - /* Apply commands */ - RIGHT_TIM->RIGHT_TIM_U = (uint16_t)CLAMP(ur + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); - RIGHT_TIM->RIGHT_TIM_V = (uint16_t)CLAMP(vr + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); - RIGHT_TIM->RIGHT_TIM_W = (uint16_t)CLAMP(wr + pwm_res / 2, pwm_margin, pwm_res-pwm_margin); - // ================================================================= - - OverrunFlag = false; - - static int16_t motAngleLeftLast = 0; - static int16_t motAngleRightLast = 0; - static int32_t cycleDegsL = 0; // wheel encoder roll over count in deg - static int32_t cycleDegsR = 0; // wheel encoder roll over count in deg - int16_t diffL = 0; - int16_t diffR = 0; - static int16_t cnt = 0; - - if (enable_motors == 0) { // Reset everything if motors are disabled - cycleDegsL = 0; - cycleDegsR = 0; - diffL = 0; - diffR = 0; - cnt = 0; - } - if (cnt == 0) { - motAngleLeftLast = rtY_Left.a_elecAngle; - motAngleRightLast = rtY_Right.a_elecAngle; - } - - diffL = rtY_Left.a_elecAngle - motAngleLeftLast; - if (diffL < -180) { - cycleDegsL = cycleDegsL - 360; - } else if (diffL > 180) { - cycleDegsL = cycleDegsL + 360; - } - motPosL = cycleDegsL + (360 - rtY_Left.a_elecAngle); - - diffR = rtY_Right.a_elecAngle - motAngleRightLast; - if (diffR < -180) { - cycleDegsR = cycleDegsR - 360; - } else if (diffR > 180) { - cycleDegsR = cycleDegsR + 360; - } - motPosR = cycleDegsR + (360 - rtY_Right.a_elecAngle); - - motAngleLeftLast = rtY_Left.a_elecAngle; - motAngleRightLast = rtY_Right.a_elecAngle; - cnt++; -} diff --git a/body/board/bldc/rtwtypes.h b/body/board/bldc/rtwtypes.h deleted file mode 100644 index 3f68038730a6176..000000000000000 --- a/body/board/bldc/rtwtypes.h +++ /dev/null @@ -1,104 +0,0 @@ -/* - * File: rtwtypes.h - * - * Code generated for Simulink model 'BLDC_controller'. - * - * Model version : 1.1297 - * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 - * C/C++ source code generated on : Sun Mar 6 11:02:11 2022 - * - * Target selection: ert.tlc - * Embedded hardware selection: ARM Compatible->ARM Cortex - * Emulation hardware selection: - * Differs from embedded hardware (MATLAB Host) - * Code generation objectives: - * 1. Execution efficiency - * 2. RAM efficiency - * Validation result: Not run - */ - -#ifndef RTWTYPES_H -#define RTWTYPES_H - -/* Logical type definitions */ -#if (!defined(__cplusplus)) -# ifndef false -# define false (0U) -# endif - -# ifndef true -# define true (1U) -# endif -#endif - -/*=======================================================================* - * Target hardware information - * Device type: MATLAB Host - * Number of bits: char: 8 short: 16 int: 32 - * long: 32 long long: 64 - * native word size: 64 - * Byte ordering: LittleEndian - * Signed integer division rounds to: Zero - * Shift right on a signed integer as arithmetic shift: on - *=======================================================================*/ - -/*=======================================================================* - * Fixed width word size data types: * - * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * - * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * - * real32_T, real64_T - 32 and 64 bit floating point numbers * - *=======================================================================*/ -typedef signed char int8_T; -typedef unsigned char uint8_T; -typedef short int16_T; -typedef unsigned short uint16_T; -typedef int int32_T; -typedef unsigned int uint32_T; -typedef long long int64_T; -typedef unsigned long long uint64_T; -typedef float real32_T; -typedef double real64_T; - -/*===========================================================================* - * Generic type definitions: boolean_T, char_T, byte_T, int_T, uint_T, * - * real_T, time_T, ulong_T, ulonglong_T. * - *===========================================================================*/ -typedef double real_T; -typedef double time_T; -typedef unsigned char boolean_T; -typedef int int_T; -typedef unsigned int uint_T; -typedef unsigned long ulong_T; -typedef unsigned long long ulonglong_T; -typedef char char_T; -typedef unsigned char uchar_T; -typedef char_T byte_T; - -/*=======================================================================* - * Min and Max: * - * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * - * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * - *=======================================================================*/ -#define MAX_int8_T ((int8_T)(127)) -#define MIN_int8_T ((int8_T)(-128)) -#define MAX_uint8_T ((uint8_T)(255U)) -#define MAX_int16_T ((int16_T)(32767)) -#define MIN_int16_T ((int16_T)(-32768)) -#define MAX_uint16_T ((uint16_T)(65535U)) -#define MAX_int32_T ((int32_T)(2147483647)) -#define MIN_int32_T ((int32_T)(-2147483647-1)) -#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU)) -#define MAX_int64_T ((int64_T)(9223372036854775807LL)) -#define MIN_int64_T ((int64_T)(-9223372036854775807LL-1LL)) -#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFULL)) - -/* Block D-Work pointer type */ -typedef void * pointer_T; - -#endif /* RTWTYPES_H */ - -/* - * File trailer for generated code. - * - * [EOF] - */ diff --git a/body/board/boards.h b/body/board/boards.h deleted file mode 100644 index 777232540dbbcf1..000000000000000 --- a/body/board/boards.h +++ /dev/null @@ -1,90 +0,0 @@ -extern uint8_t hw_type; -board_t board; - -void board_detect(void) { - hw_type = board_id(); - // 0 = base, 3 = knee - if (hw_type == HW_TYPE_BASE) { - board.hall_left.hall_portA = GPIOC; - board.hall_left.hall_pinA = GPIO_PIN_13; - board.hall_left.hall_portB = GPIOC; - board.hall_left.hall_pinB = GPIO_PIN_14; - board.hall_left.hall_portC = GPIOC; - board.hall_left.hall_pinC = GPIO_PIN_15; - - board.hall_right.hall_portA = GPIOC; - board.hall_right.hall_pinA = GPIO_PIN_10; - board.hall_right.hall_portB = GPIOC; - board.hall_right.hall_pinB = GPIO_PIN_11; - board.hall_right.hall_portC = GPIOC; - board.hall_right.hall_pinC = GPIO_PIN_12; - - board.CAN = CAN2; - board.can_alt_tx = GPIO_AF9_CAN2; - board.can_alt_rx = GPIO_AF9_CAN2; - board.can_pinRX = GPIO_PIN_5; - board.can_portRX = GPIOB; - board.can_pinTX = GPIO_PIN_6; - board.can_portTX = GPIOB; - board.can_pinEN = GPIO_PIN_7; - board.can_portEN = GPIOB; - - board.ignition_pin = GPIO_PIN_9; - board.ignition_port = GPIOB; - - board.led_pinR = GPIO_PIN_2; - board.led_portR = GPIOD; - board.led_pinG = GPIO_PIN_15; - board.led_portG = GPIOA; - board.led_pinB = GPIO_PIN_1; - board.led_portB = GPIOC; - - board.can_addr_offset = 0x0U; - board.uds_offset = 0x0U; - - } else if (hw_type == HW_TYPE_KNEE) { - board.hall_left.hall_portA = GPIOC; - board.hall_left.hall_pinA = GPIO_PIN_14; - board.hall_left.hall_portB = GPIOC; - board.hall_left.hall_pinB = GPIO_PIN_15; - board.hall_left.hall_portC = GPIOC; - board.hall_left.hall_pinC = GPIO_PIN_13; - - board.hall_right.hall_portA = GPIOD; - board.hall_right.hall_pinA = GPIO_PIN_2; - board.hall_right.hall_portB = GPIOC; - board.hall_right.hall_pinB = GPIO_PIN_0; - board.hall_right.hall_portC = GPIOC; - board.hall_right.hall_pinC = GPIO_PIN_1; - - board.CAN = CAN1; - board.can_alt_tx = GPIO_AF8_CAN1; - board.can_alt_rx = GPIO_AF9_CAN1; - board.can_pinRX = GPIO_PIN_11; - board.can_portRX = GPIOA; - board.can_pinTX = GPIO_PIN_9; - board.can_portTX = GPIOB; - board.can_pinEN = 0; // No pin, pulled down with 10k resistor - board.can_portEN = GPIOB; - - board.ignition_pin = 0; // No pin, always enabled - board.ignition_port = GPIOB; - - board.led_pinR = GPIO_PIN_2; - board.led_portR = GPIOB; - board.led_pinG = GPIO_PIN_15; - board.led_portG = GPIOA; - board.led_pinB = GPIO_PIN_5; - board.led_portB = GPIOB; - - board.can_addr_offset = KNEE_ADDR_OFFSET; - board.uds_offset = 0x10U; - - #ifndef BOOTSTUB - MX_I2C_Init(); - #endif - } else { - // Fail to detect, halt - while(1) {} - } -} diff --git a/body/board/bootstub.c b/body/board/bootstub.c deleted file mode 100644 index f75a93924ae933d..000000000000000 --- a/body/board/bootstub.c +++ /dev/null @@ -1,119 +0,0 @@ -#define BOOTSTUB - -#define VERS_TAG 0x53524556 -#define MIN_VERSION 2 - -#define RECOVERY_MODE_DELAY 5 - -// ********************* Includes ********************* -#include -#include -#include "libc.h" -#include "stm32f4xx_hal.h" -#include "defines.h" -#include "setup.h" -#include "drivers/clock.h" -#include "early_init.h" - -#include "crypto/rsa.h" -#include "crypto/sha.h" - -#include "obj/cert.h" -#include "obj/gitversion.h" - -#include "drivers/llbxcan.h" -#include "drivers/llflash.h" -#include "provision.h" -#include "util.h" -#include "boards.h" - -#include "flasher.h" - -uint8_t hw_type; // type of the board detected(0 - base, 3 - knee) - -void __initialize_hardware_early(void) { - early_initialization(); -} - -void fail(void) { - soft_flasher_start(); -} - -// know where to sig check -extern void *_app_start[]; - -int main(void) { - HAL_Init(); - HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); - HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); - HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); - HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); - HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); - HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); - HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0); - HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); - - SystemClock_Config(); - MX_GPIO_Clocks_Init(); - - board_detect(); - MX_GPIO_Common_Init(); - - out_enable(POWERSWITCH, true); - out_enable(LED_RED, false); - out_enable(LED_GREEN, false); - out_enable(LED_BLUE, false); - - if(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && (hw_type == HW_TYPE_BASE)) { - uint16_t cnt_press = 0; - while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { - HAL_Delay(10); - cnt_press++; - if (cnt_press == (RECOVERY_MODE_DELAY * 100)) { - out_enable(LED_GREEN, true); - soft_flasher_start(); - } - } - } - - if (enter_bootloader_mode == ENTER_SOFTLOADER_MAGIC) { - enter_bootloader_mode = 0; - soft_flasher_start(); - } - - // validate length - int len = (int)_app_start[0]; - if ((len < 8) || (len > (0x1000000 - 0x4000 - 4 - RSANUMBYTES))) goto fail; - - // compute SHA hash - uint8_t digest[SHA_DIGEST_SIZE]; - SHA_hash(&_app_start[1], len-4, digest); - - // verify version, last bytes in the signed area - uint32_t vers[2] = {0}; - memcpy(&vers, ((void*)&_app_start[0]) + len - sizeof(vers), sizeof(vers)); - if (vers[0] != VERS_TAG || vers[1] < MIN_VERSION) { - goto fail; - } - - // verify RSA signature - if (RSA_verify(&release_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { - goto good; - } - - // allow debug if built from source -#ifdef ALLOW_DEBUG - if (RSA_verify(&debug_rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { - goto good; - } -#endif - -// here is a failure -fail: - fail(); - return 0; -good: - // jump to flash - ((void(*)(void)) _app_start[1])(); - return 0; -} diff --git a/body/board/canloader.py b/body/board/canloader.py deleted file mode 100755 index 624e6bf7a4159e8..000000000000000 --- a/body/board/canloader.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python3 -import os -import time -import argparse -import _thread -from panda import Panda, MCU_TYPE_F4 # pylint: disable=import-error -from panda.tests.pedal.canhandle import CanHandle # pylint: disable=import-error - - -def heartbeat_thread(p): - while True: - try: - p.send_heartbeat() - time.sleep(0.5) - except Exception: - continue - -def flush_panda(): - while(1): - if len(p.can_recv()) == 0: - break - -def flasher(p, addr, file): - p.can_send(addr, b"\xce\xfa\xad\xde\x1e\x0b\xb0\x0a", 0) - time.sleep(0.1) - print("flashing", file) - flush_panda() - code = open(file, "rb").read() - retries = 3 # How many times to retry on timeout error - while(retries+1>0): - try: - Panda.flash_static(CanHandle(p, 0), code, MCU_TYPE_F4) - except TimeoutError: - print("Timeout, trying again...") - retries -= 1 - else: - print("Successfully flashed") - break - - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Flash body over can') - parser.add_argument("board", type=str, nargs='?', help="choose base or knee") - parser.add_argument("fn", type=str, nargs='?', help="flash file") - args = parser.parse_args() - - assert args.board in ["base", "knee"] - assert os.path.isfile(args.fn) - - addr = 0x250 if args.board == "base" else 0x350 - - p = Panda() - _thread.start_new_thread(heartbeat_thread, (p,)) - p.set_safety_mode(Panda.SAFETY_BODY) - - print("Flashing motherboard") - flasher(p, addr, args.fn) - - print("CAN flashing done") diff --git a/body/board/comms.h b/body/board/comms.h deleted file mode 100644 index 342163c8832498c..000000000000000 --- a/body/board/comms.h +++ /dev/null @@ -1,190 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef COMMS_H -#define COMMS_H - -#define OFFSET 0x8U -#define BROADCAST_ADDR 0x7DFU -#define FALLBACK_ADDR 0x7E0U -#define FALLBACK_R_ADDR (FALLBACK_ADDR + OFFSET) -#define ENGINE_ADDR 0x720U -#define ENGINE_R_ADDR (ENGINE_ADDR + OFFSET) -#define DEBUG_ADDR 0x721U -#define DEBUG_R_ADDR (DEBUG_ADDR + OFFSET) - -#include "drivers/llbxcan.h" -#include "uds.h" - -extern P rtP_Left; -extern P rtP_Right; -extern volatile int16_t cmdL; // global variable for Left Command -extern volatile int16_t cmdR; // global variable for Right Command -extern uint8_t hw_type; -extern board_t board; - -extern uint32_t enter_bootloader_mode; -extern volatile uint32_t torque_cmd_timeout; - -extern volatile uint32_t ignition_off_counter; - -const uint8_t crc_poly = 0xD5U; // standard crc8 -uint32_t current_idx = 0; - -typedef struct { - volatile uint32_t w_ptr; - volatile uint32_t r_ptr; - uint32_t fifo_size; - CAN_FIFOMailBox_TypeDef *elems; -} can_ring; - -#define can_buffer(x, size) \ - CAN_FIFOMailBox_TypeDef elems_##x[size]; \ - can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = (size), .elems = (CAN_FIFOMailBox_TypeDef *)&(elems_##x) }; - -can_buffer(tx_q, 0x1A0) - -bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { - bool ret = 0; - - if (q->w_ptr != q->r_ptr) { - *elem = q->elems[q->r_ptr]; - if ((q->r_ptr + 1U) == q->fifo_size) { - q->r_ptr = 0; - } else { - q->r_ptr += 1U; - } - ret = 1; - } - return ret; -} - -bool can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { - bool ret = false; - uint32_t next_w_ptr; - - if ((q->w_ptr + 1U) == q->fifo_size) { - next_w_ptr = 0; - } else { - next_w_ptr = q->w_ptr + 1U; - } - if (next_w_ptr != q->r_ptr) { - q->elems[q->w_ptr] = *elem; - q->w_ptr = next_w_ptr; - ret = true; - } - return ret; -} - -void can_send_msg(uint32_t addr, uint32_t dhr, uint32_t dlr, uint8_t len) { - CAN_FIFOMailBox_TypeDef to_push; - - to_push.RDHR = dhr; - to_push.RDLR = dlr; - to_push.RDTR = len; - to_push.RIR = ((addr >= 0x800U) ? ((addr << 3) | (1U << 2)) : (addr << 21)) | 1; - - can_push(&can_tx_q, &to_push); -} - -void process_can(void) { - __disable_irq(); - CAN_FIFOMailBox_TypeDef to_send; - if ((board.CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { - if (can_pop(&can_tx_q, &to_send)) { - board.CAN->sTxMailBox[0].TDLR = to_send.RDLR; - board.CAN->sTxMailBox[0].TDHR = to_send.RDHR; - board.CAN->sTxMailBox[0].TDTR = to_send.RDTR; - board.CAN->sTxMailBox[0].TIR = to_send.RIR; - } - } - __enable_irq(); -} - -void can_rx(void) { - while ((board.CAN->RF0R & CAN_RF0R_FMP0) != 0) { - uint32_t address = board.CAN->sFIFOMailBox[0].RIR >> 21; - if (address == (0x250U + board.can_addr_offset)) { - if ((GET_MAILBOX_BYTES_04(&board.CAN->sFIFOMailBox[0]) == 0xdeadface) && (GET_MAILBOX_BYTES_48(&board.CAN->sFIFOMailBox[0]) == 0x0ab00b1e)) { - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - } - #define MSG_TRQ_LEN 6 - uint8_t dat[MSG_TRQ_LEN]; - for (int i=0; isFIFOMailBox[0], i); - } - uint16_t valueL = ((dat[0] << 8U) | dat[1]); - uint16_t valueR = ((dat[2] << 8U) | dat[3]); - - uint8_t idx = dat[4] & 0xFU; - if (crc_checksum(dat, 5, crc_poly) == dat[5]) { - if (((current_idx + 1U) & 0xFU) == idx) { - cmdL = valueL; - cmdR = valueR; - torque_cmd_timeout = 0; - } - current_idx = idx; - } - out_enable(LED_BLUE, true); - } else if (address == (0x251U + board.can_addr_offset)) { - #define MSG_SPD_LEN 5 - uint8_t dat[MSG_TRQ_LEN]; - for (int i=0; isFIFOMailBox[0], i); - } - uint16_t valueL = ((dat[0] << 8U) | dat[1]); - uint16_t valueR = ((dat[2] << 8U) | dat[3]); - - if (crc_checksum(dat, 4, crc_poly) == dat[4]) { - if ((valueL == 0) || (valueR == 0)) { - rtP_Left.n_max = rtP_Right.n_max = N_MOT_MAX << 4; - } else { - rtP_Left.n_max = valueL << 4; - rtP_Right.n_max = valueR << 4; - } - } - out_enable(LED_BLUE, true); - } else if ((address == BROADCAST_ADDR) || // Process UBS and OBD2 requests - (address == FALLBACK_ADDR) || - (address == (ENGINE_ADDR + board.uds_offset)) || - (address == (DEBUG_ADDR + board.uds_offset))) { - process_uds(address, GET_MAILBOX_BYTES_04(&board.CAN->sFIFOMailBox[0])); - out_enable(LED_BLUE, true); - } else if ((hw_type == HW_TYPE_BASE) && (address == 0x203U + KNEE_ADDR_OFFSET)) { // detect knee by body and set flag for use with UDS message - knee_detected = 1; - } else if ((hw_type == HW_TYPE_KNEE) && (address == 0x202U)) { // CAN based ignition for knee - ignition_off_counter = 0; - } - // next - board.CAN->RF0R |= CAN_RF0R_RFOM0; - } -} - -void CAN1_TX_IRQHandler(void) { - // clear interrupt - board.CAN->TSR |= CAN_TSR_RQCP0; - process_can(); -} - -void CAN1_SCE_IRQHandler(void) { - llcan_clear_send(board.CAN); -} - -void CAN1_RX0_IRQHandler(void) { - can_rx(); -} - -void CAN2_TX_IRQHandler(void) { - // clear interrupt - board.CAN->TSR |= CAN_TSR_RQCP0; - process_can(); -} - -void CAN2_SCE_IRQHandler(void) { - llcan_clear_send(board.CAN); -} - -void CAN2_RX0_IRQHandler(void) { - can_rx(); -} - -#endif diff --git a/body/board/config.h b/body/board/config.h deleted file mode 100644 index a6271ec749c8733..000000000000000 --- a/body/board/config.h +++ /dev/null @@ -1,79 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef CONFIG_H -#define CONFIG_H - -#include "stm32f4xx_hal.h" - -#define CORE_FREQ 96000000U // MCU frequency in hertz -#define I2C_CLOCKSPEED 100 // I2C clock in kHz -#define PWM_FREQ 16000 // PWM frequency in Hz / is also used for buzzer -#define DEAD_TIME 48 // PWM deadtime -#define DELAY_IN_MAIN_LOOP 5 // in ms. default 5. it is independent of all the timing critical stuff. do not touch if you do not know what you are doing. -#define A2BIT_CONV 50 // A to bit for current conversion on ADC. Example: 1 A = 50, 2 A = 100, etc - -#define IGNITION_OFF_DELAY 5 // Stop sending CAN messages after 5 seconds - -#define ADC_CONV_CLOCK_CYCLES (ADC_SAMPLETIME_15CYCLES) -#define ADC_CLOCK_DIV (4) -#define ADC_TOTAL_CONV_TIME (ADC_CLOCK_DIV * ADC_CONV_CLOCK_CYCLES) // = ((SystemCoreClock / ADC_CLOCK_HZ) * ADC_CONV_CLOCK_CYCLES), where ADC_CLOCK_HZ = SystemCoreClock/ADC_CLOCK_DIV - -#define KNEE_ADDR_OFFSET 0x100U -#define ANGLE_TO_DEGREES 0.021972656 // Convert 14 bit angle sensor output to degrees -#define GEARBOX_RATIO_LEFT 19 -#define GEARBOX_RATIO_RIGHT 19 -#define TRQ_LIMIT_LEFT 400 // Torque limit for knee gearbox(left) -#define TRQ_LIMIT_RIGHT 200 // Torque limit for hip gearbox(right) - -#define BAT_FILT_COEF 655 // battery voltage filter coefficient in fixed-point. coef_fixedPoint = coef_floatingPoint * 2^16. In this case 655 = 0.01 * 2^16 -#define BAT_CALIB_REAL_VOLTAGE 3192 // input voltage measured by multimeter (multiplied by 100). In this case 43.00 V * 100 = 4300 -#define BAT_CALIB_ADC 1275 // adc-value measured by mainboard (value nr 5 on UART debug output) -#define BAT_CELLS 7 // battery number of cells. Normal Hoverboard battery: 10s -#define VOLTS_PER_PERCENT 0.00814 // Volts per percent, for conversion of volts to percentage -#define BAT_LVL2 (358 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE // 24% -#define BAT_LVL1 (351 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE // 15% -#define BAT_DEAD (339 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE // 0% - -#define TEMP_FILT_COEF 655 // temperature filter coefficient in fixed-point. coef_fixedPoint = coef_floatingPoint * 2^16. In this case 655 = 0.01 * 2^16 -#define TEMP_CAL_LOW_ADC 945 // temperature 1: ADC value -#define TEMP_CAL_LOW_DEG_C 250 // temperature 1: measured temperature [°C * 10]. Here 35.8 °C -#define TEMP_CAL_HIGH_ADC 949 // temperature 2: ADC value -#define TEMP_CAL_HIGH_DEG_C 251 // temperature 2: measured temperature [°C * 10]. Here 48.9 °C -#define TEMP_WARNING_ENABLE 0 // to beep or not to beep, 1 or 0, DO NOT ACTIVITE WITHOUT CALIBRATION! -#define TEMP_WARNING 600 // annoying fast beeps [°C * 10]. Here 60.0 °C -#define TEMP_POWEROFF_ENABLE 0 // to poweroff or not to poweroff, 1 or 0, DO NOT ACTIVITE WITHOUT CALIBRATION! -#define TEMP_POWEROFF 650 // overheat poweroff. (while not driving) [°C * 10]. Here 65.0 °C - -#define COM_CTRL 0 // [-] Commutation Control Type -#define SIN_CTRL 1 // [-] Sinusoidal Control Type -#define FOC_CTRL 2 // [-] Field Oriented Control (FOC) Type - -#define OPEN_MODE 0 // [-] OPEN mode -#define VLT_MODE 1 // [-] VOLTAGE mode -#define SPD_MODE 2 // [-] SPEED mode -#define TRQ_MODE 3 // [-] TORQUE mode - -// Enable/Disable Motor -#define MOTOR_LEFT_ENA // [-] Enable LEFT motor. Comment-out if this motor is not needed to be operational -#define MOTOR_RIGHT_ENA // [-] Enable RIGHT motor. Comment-out if this motor is not needed to be operational - -// Control selections -#define CTRL_TYP_SEL FOC_CTRL // [-] Control type selection: COM_CTRL, SIN_CTRL, FOC_CTRL (default) -#define CTRL_MOD_REQ TRQ_MODE // [-] Control mode request: OPEN_MODE, VLT_MODE (default), SPD_MODE, TRQ_MODE. Note: SPD_MODE and TRQ_MODE are only available for CTRL_FOC! -#define DIAG_ENA 1 // [-] Motor Diagnostics enable flag: 0 = Disabled, 1 = Enabled (default) - -// Limitation settings -#define I_MOT_MAX 15 // [A] Maximum single motor current limit -#define I_DC_MAX 17 // [A] Maximum stage2 DC Link current limit for Commutation and Sinusoidal types (This is the final current protection. Above this value, current chopping is applied. To avoid this make sure that I_DC_MAX = I_MOT_MAX + 2A) -#define N_MOT_MAX 100 // [rpm] Maximum motor speed limit // 100 ~= 52m/m -#define TORQUE_BASE_MAX 1000 - -// Field Weakening / Phase Advance -#define FIELD_WEAK_ENA 0 // [-] Field Weakening / Phase Advance enable flag: 0 = Disabled (default), 1 = Enabled -#define FIELD_WEAK_MAX 5 // [A] Maximum Field Weakening D axis current (only for FOC). Higher current results in higher maximum speed. Up to 10A has been tested using 10" wheels. -#define PHASE_ADV_MAX 25 // [deg] Maximum Phase Advance angle (only for SIN). Higher angle results in higher maximum speed. -#define FIELD_WEAK_HI 1000 // (1000, 1500] Input target High threshold for reaching maximum Field Weakening / Phase Advance. Do NOT set this higher than 1500. -#define FIELD_WEAK_LO 750 // ( 500, 1000] Input target Low threshold for starting Field Weakening / Phase Advance. Do NOT set this higher than 1000. - -#define SPEED_COEFFICIENT 16384 // Default for SPEED_COEFFICIENT 1.0f [-] higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14 - -#endif diff --git a/body/board/defines.h b/body/board/defines.h deleted file mode 100644 index bc7459a51f736aa..000000000000000 --- a/body/board/defines.h +++ /dev/null @@ -1,188 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef DEFINES_H -#define DEFINES_H - -#include "stm32f4xx_hal.h" -#include "config.h" - -#define LEFT_TIM TIM8 -#define LEFT_TIM_U CCR1 -#define LEFT_TIM_UH_PIN GPIO_PIN_6 -#define LEFT_TIM_UH_PORT GPIOC -#define LEFT_TIM_UL_PIN GPIO_PIN_7 -#define LEFT_TIM_UL_PORT GPIOA -#define LEFT_TIM_V CCR2 -#define LEFT_TIM_VH_PIN GPIO_PIN_7 -#define LEFT_TIM_VH_PORT GPIOC -#define LEFT_TIM_VL_PIN GPIO_PIN_0 -#define LEFT_TIM_VL_PORT GPIOB -#define LEFT_TIM_W CCR3 -#define LEFT_TIM_WH_PIN GPIO_PIN_8 -#define LEFT_TIM_WH_PORT GPIOC -#define LEFT_TIM_WL_PIN GPIO_PIN_1 -#define LEFT_TIM_WL_PORT GPIOB - -#define RIGHT_TIM TIM1 -#define RIGHT_TIM_U CCR1 -#define RIGHT_TIM_UH_PIN GPIO_PIN_8 -#define RIGHT_TIM_UH_PORT GPIOA -#define RIGHT_TIM_UL_PIN GPIO_PIN_13 -#define RIGHT_TIM_UL_PORT GPIOB -#define RIGHT_TIM_V CCR2 -#define RIGHT_TIM_VH_PIN GPIO_PIN_9 -#define RIGHT_TIM_VH_PORT GPIOA -#define RIGHT_TIM_VL_PIN GPIO_PIN_14 -#define RIGHT_TIM_VL_PORT GPIOB -#define RIGHT_TIM_W CCR3 -#define RIGHT_TIM_WH_PIN GPIO_PIN_10 -#define RIGHT_TIM_WH_PORT GPIOA -#define RIGHT_TIM_WL_PIN GPIO_PIN_15 -#define RIGHT_TIM_WL_PORT GPIOB - -#define LEFT_DC_CUR_PIN GPIO_PIN_3 -#define LEFT_U_CUR_PIN GPIO_PIN_5 -#define LEFT_V_CUR_PIN GPIO_PIN_6 - -#define LEFT_DC_CUR_PORT GPIOA -#define LEFT_U_CUR_PORT GPIOA -#define LEFT_V_CUR_PORT GPIOA - -#define RIGHT_DC_CUR_PIN GPIO_PIN_2 -#define RIGHT_U_CUR_PIN GPIO_PIN_0 -#define RIGHT_V_CUR_PIN GPIO_PIN_1 - -#define RIGHT_DC_CUR_PORT GPIOA -#define RIGHT_U_CUR_PORT GPIOA -#define RIGHT_V_CUR_PORT GPIOA - -#define BATT_PIN GPIO_PIN_4 -#define BATT_PORT GPIOA - -#define BUZZER_PIN GPIO_PIN_2 -#define BUZZER_PORT GPIOC - -#define OFF_PIN GPIO_PIN_4 -#define OFF_PORT GPIOC - -#define BUTTON_PIN GPIO_PIN_8 -#define BUTTON_PORT GPIOB - -#define CHARGER_PIN GPIO_PIN_12 -#define CHARGER_PORT GPIOA - -#define SW_I2C1_SCL_GPIO GPIOB -#define SW_I2C1_SDA_GPIO GPIOB -#define SW_I2C1_SCL_PIN GPIO_PIN_3 -#define SW_I2C1_SDA_PIN GPIO_PIN_4 - -// UID pins -#define KEY1_PIN GPIO_PIN_10 -#define KEY1_PORT GPIOB -#define KEY2_PIN GPIO_PIN_9 -#define KEY2_PORT GPIOC - -#define DELAY_TIM_FREQUENCY_US 1000000 - -#define MILLI_R (R * 1000) -#define MILLI_PSI (PSI * 1000) -#define MILLI_V (V * 1000) - -#define NO 0 -#define YES 1 -#define ABS(a) (((a) < 0) ? -(a) : (a)) -#define LIMIT(x, lowhigh) (((x) > (lowhigh)) ? (lowhigh) : (((x) < (-lowhigh)) ? (-lowhigh) : (x))) -#define SAT(x, lowhigh) (((x) > (lowhigh)) ? (1.0f) : (((x) < (-lowhigh)) ? (-1.0f) : (0.0f))) -#define SAT2(x, low, high) (((x) > (high)) ? (1.0f) : (((x) < (low)) ? (-1.0f) : (0.0f))) -#define STEP(from, to, step) (((from) < (to)) ? (MIN((from) + (step), (to))) : (MAX((from) - (step), (to)))) -#define DEG(a) ((a)*M_PI / 180.0f) -#define RAD(a) ((a)*180.0f / M_PI) -#define SIGN(a) (((a) < 0) ? (-1) : (((a) > 0) ? (1) : (0))) -#define CLAMP(x, low, high) (((x) > (high)) ? (high) : (((x) < (low)) ? (low) : (x))) -#define IN_RANGE(x, low, high) (((x) >= (low)) && ((x) <= (high))) -#define SCALE(value, high, max) MIN(MAX(((max) - (value)) / ((max) - (high)), 0.0f), 1.0f) -#define MIN(a, b) (((a) < (b)) ? (a) : (b)) -#define MAX(a, b) (((a) > (b)) ? (a) : (b)) -#define MIN3(a, b, c) MIN(a, MIN(b, c)) -#define MAX3(a, b, c) MAX(a, MAX(b, c)) -#define ARRAY_LEN(x) (uint32_t)(sizeof(x) / sizeof(*(x))) -#define MAP(x, in_min, in_max, out_min, out_max) (((((x) - (in_min)) * ((out_max) - (out_min))) / ((in_max) - (in_min))) + (out_min)) - -#define GET_MAILBOX_BYTE(msg, b) (((int)(b) > 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0xFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) -#define GET_MAILBOX_BYTES_04(msg) ((msg)->RDLR) -#define GET_MAILBOX_BYTES_48(msg) ((msg)->RDHR) - -#define BOOT_NORMAL 0xdeadb111U -#define ENTER_SOFTLOADER_MAGIC 0xdeadc0deU - -#define APP_START_ADDRESS 0x8004000U -#define DEVICE_SERIAL_NUMBER_ADDRESS 0x1FFF79C0U - -#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * ((int)(!(pred))))])) - -#define LED_RED 0 -#define LED_GREEN 1 -#define LED_BLUE 2 -#define IGNITION 3 -#define POWERSWITCH 4 -#define TRANSCEIVER 5 - -#define HW_TYPE_BASE 0 -#define HW_TYPE_KNEE 3 - -typedef struct { - uint32_t rrB; - uint32_t rrC; - uint32_t rlA; - uint32_t rlB; - uint32_t dcr; - uint32_t dcl; - uint32_t batt1; - uint32_t temp; -} adc_buf_t; - -typedef struct { - GPIO_TypeDef* hall_portA; - uint16_t hall_pinA; - GPIO_TypeDef* hall_portB; - uint16_t hall_pinB; - GPIO_TypeDef* hall_portC; - uint16_t hall_pinC; -} hall_sensor; - -typedef struct { - hall_sensor hall_left; - hall_sensor hall_right; - - CAN_TypeDef* CAN; - uint8_t can_alt_tx; - uint8_t can_alt_rx; - GPIO_TypeDef* can_portTX; - uint16_t can_pinTX; - GPIO_TypeDef* can_portRX; - uint16_t can_pinRX; - GPIO_TypeDef* can_portEN; - uint16_t can_pinEN; - - GPIO_TypeDef* ignition_port; - uint16_t ignition_pin; - - uint16_t can_addr_offset; - uint8_t uds_offset; - - GPIO_TypeDef* led_portR; - uint16_t led_pinR; - GPIO_TypeDef* led_portG; - uint16_t led_pinG; - GPIO_TypeDef* led_portB; - uint16_t led_pinB; - -} board_t; - -typedef struct { - uint8_t left_i2c : 1; - uint8_t left_angle : 1; - uint8_t right_i2c : 1; - uint8_t right_angle : 1; -} fault_status_t; - -#endif // DEFINES_H diff --git a/body/board/drivers/angle_sensor.h b/body/board/drivers/angle_sensor.h deleted file mode 100644 index 72f0a857e0e18b3..000000000000000 --- a/body/board/drivers/angle_sensor.h +++ /dev/null @@ -1,69 +0,0 @@ -// Default addresses for AS5048B -#define AS5048_ADDRESS_LEFT 0x40 -#define AS5048_ADDRESS_RIGHT 0x41 -#define UNKNOWN_IMU 0x68 - -#define AS5048B_PROG_REG 0x03 -#define AS5048B_ADDR_REG 0x15 -#define AS5048B_ZEROMSB_REG 0x16 //bits 0..7 -#define AS5048B_ZEROLSB_REG 0x17 //bits 0..5 -#define AS5048B_GAIN_REG 0xFA -#define AS5048B_DIAG_REG 0xFB -#define AS5048B_MAGNMSB_REG 0xFC //bits 0..7 -#define AS5048B_MAGNLSB_REG 0xFD //bits 0..5 -#define AS5048B_ANGLMSB_REG 0xFE //bits 0..7 -#define AS5048B_ANGLLSB_REG 0xFF //bits 0..5 - -extern I2C_HandleTypeDef hi2c1; - -const uint8_t init_imu_regaddr[] = {0x76, 0x4c, 0x4e, 0x4f, 0x50, 0x51, 0x52, 0x53}; -const uint8_t init_imu_data[] = {0x00, 0x12, 0x2f, 0x26, 0x67, 0x04, 0x00, 0x00}; - -fault_status_t fault_status = {0}; - -void angle_sensor_read(uint16_t *sensor_angle) { - - if (fault_status.left_i2c && fault_status.right_i2c) { // Try to reinitialize halted I2C - if (HAL_I2C_Init(&hi2c1) == HAL_OK) { - fault_status.left_i2c = 0; - fault_status.right_i2c = 0; - } - } - - uint8_t buf[2]; - if (HAL_I2C_Mem_Read(&hi2c1, (AS5048_ADDRESS_LEFT<<1), AS5048B_ANGLMSB_REG, I2C_MEMADD_SIZE_8BIT, buf, 2, 10) == HAL_OK) { - sensor_angle[0] = (buf[0] << 6) | (buf[1] & 0x3F); - fault_status.left_i2c = 0; - } else { - fault_status.left_i2c = 1; - } - if (HAL_I2C_Mem_Read(&hi2c1, (AS5048_ADDRESS_RIGHT<<1), AS5048B_ANGLMSB_REG, I2C_MEMADD_SIZE_8BIT, buf, 2, 10) == HAL_OK) { - sensor_angle[1] = (buf[0] << 6) | (buf[1] & 0x3F); - fault_status.right_i2c = 0; - } else { - fault_status.right_i2c = 1; - } -} - -void IMU_soft_init(void) { - i2c_port_init(); - - for (int8_t i = 3; i > 0; i--) { - SW_I2C_WriteControl_8Bit((UNKNOWN_IMU<<1), 0x75, 0x00); - } - for (int8_t i = sizeof(init_imu_regaddr)-1; i >= 0; i--) { - SW_I2C_WriteControl_8Bit((UNKNOWN_IMU<<1), init_imu_regaddr[i], init_imu_data[i]); - } -} - -void IMU_soft_sensor_read(uint16_t *unknown_imu_data) { - static uint8_t buf[12]; - - SW_I2C_WriteControl_8Bit((UNKNOWN_IMU<<1), 0x76, 0x00); - SW_I2C_Multi_ReadnControl_8Bit((UNKNOWN_IMU<<1), 0x1F, 6, buf); - SW_I2C_Multi_ReadnControl_8Bit((UNKNOWN_IMU<<1), 0x25, 6, &buf[6]); - - for (int8_t i = 5; i >= 0; i--) { - unknown_imu_data[i] = (buf[i*2] << 8) | (buf[(i*2)+1]); - } -} diff --git a/body/board/drivers/clock.h b/body/board/drivers/clock.h deleted file mode 100644 index 39a301f9288ede1..000000000000000 --- a/body/board/drivers/clock.h +++ /dev/null @@ -1,63 +0,0 @@ -void Error_Handler(void) -{ - /* USER CODE BEGIN Error_Handler_Debug */ - /* User can add his own implementation to report the HAL error return state */ - __disable_irq(); - while (1) - { - } - /* USER CODE END Error_Handler_Debug */ -} -/** System Clock Configuration -*/ -void SystemClock_Config(void) { - RCC_OscInitTypeDef RCC_OscInitStruct; - RCC_ClkInitTypeDef RCC_ClkInitStruct; - - /** Configure the main internal regulator output voltage - */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - __HAL_RCC_PWR_CLK_ENABLE(); - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /**Initializes the CPU, AHB and APB busses clocks - */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; - RCC_OscInitStruct.HSIState = RCC_HSI_ON; - RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; - - RCC_OscInitStruct.PLL.PLLM = 8; - RCC_OscInitStruct.PLL.PLLN = 96; // Gives 96 Mhz core clock - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 2; - RCC_OscInitStruct.PLL.PLLR = 2; - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { - Error_Handler(); - } - - /**Initializes the CPU, AHB and APB busses clocks - */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK - |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - - if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { - Error_Handler(); - } - - /**Configure the Systick interrupt time - */ - HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000); - - /**Configure the Systick - */ - HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); - - /* SysTick_IRQn interrupt configuration */ - HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); -} diff --git a/body/board/drivers/i2c_soft.h b/body/board/drivers/i2c_soft.h deleted file mode 100644 index aa6280bd9a56c1a..000000000000000 --- a/body/board/drivers/i2c_soft.h +++ /dev/null @@ -1,305 +0,0 @@ -#define SW_I2C_WAIT_TIME 22 - -#define I2C_READ 0x01 -#define READ_CMD 1 -#define WRITE_CMD 0 - - -void SW_I2C_init(void) -{ - GPIO_InitTypeDef GPIO_InitStructure = { 0 }; - - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; - - GPIO_InitStructure.Pin = SW_I2C1_SCL_PIN; - HAL_GPIO_Init(SW_I2C1_SCL_GPIO, &GPIO_InitStructure); - GPIO_InitStructure.Pin = SW_I2C1_SDA_PIN; - HAL_GPIO_Init(SW_I2C1_SDA_GPIO, &GPIO_InitStructure); -} - -uint8_t SW_I2C_ReadVal_SDA(void) -{ - uint8_t ret; - ret = (uint16_t)HAL_GPIO_ReadPin(SW_I2C1_SDA_GPIO, SW_I2C1_SDA_PIN); - return ret; -} - -void sda_high(void) -{ - HAL_GPIO_WritePin(SW_I2C1_SDA_GPIO, SW_I2C1_SDA_PIN, GPIO_PIN_SET); -} - - -void sda_low(void) -{ - HAL_GPIO_WritePin(SW_I2C1_SDA_GPIO, SW_I2C1_SDA_PIN, GPIO_PIN_RESET); -} - - -void scl_high(void) -{ - HAL_GPIO_WritePin(SW_I2C1_SCL_GPIO, SW_I2C1_SCL_PIN, GPIO_PIN_SET); -} - - -void scl_low(void) -{ - HAL_GPIO_WritePin(SW_I2C1_SCL_GPIO, SW_I2C1_SCL_PIN, GPIO_PIN_RESET); -} - -void sda_out(uint8_t out) -{ - if (out) { - sda_high(); - } else { - sda_low(); - } -} - -void sda_in_mode(void) -{ - GPIO_InitTypeDef GPIO_InitStructure = { 0 }; - - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStructure.Mode = GPIO_MODE_INPUT; - - GPIO_InitStructure.Pin = SW_I2C1_SDA_PIN; - HAL_GPIO_Init(SW_I2C1_SDA_GPIO, &GPIO_InitStructure); -} - -void sda_out_mode(void) -{ - GPIO_InitTypeDef GPIO_InitStructure = { 0 }; - - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_OD; - - GPIO_InitStructure.Pin = SW_I2C1_SDA_PIN; - HAL_GPIO_Init(SW_I2C1_SDA_GPIO, &GPIO_InitStructure); -} - -void i2c_clk_data_out(void) -{ - scl_high(); - delay(SW_I2C_WAIT_TIME); - scl_low(); -} - -void i2c_port_init(void) -{ - sda_high(); - scl_high(); -} - -void i2c_start_condition(void) -{ - sda_high(); - scl_high(); - - delay(SW_I2C_WAIT_TIME); - sda_low(); - delay(SW_I2C_WAIT_TIME); - scl_low(); - - delay(SW_I2C_WAIT_TIME << 1); -} - -void i2c_stop_condition(void) -{ - sda_low(); - scl_high(); - - delay(SW_I2C_WAIT_TIME); - sda_high(); - delay(SW_I2C_WAIT_TIME); -} - -uint8_t i2c_check_ack(void) -{ - uint8_t ack; - int i; - unsigned int temp; - - sda_in_mode(); - - scl_high(); - - ack = 0; - delay(SW_I2C_WAIT_TIME); - - for (i = 10; i > 0; i--) { - temp = !(SW_I2C_ReadVal_SDA()); - if (temp) - { - ack = 1; - break; - } - } - scl_low(); - sda_out_mode(); - - delay(SW_I2C_WAIT_TIME); - return ack; -} - -void i2c_check_not_ack(void) -{ - sda_in_mode(); - i2c_clk_data_out(); - sda_out_mode(); - delay(SW_I2C_WAIT_TIME); -} - -void i2c_slave_address(uint8_t IICID, uint8_t readwrite) -{ - int x; - - if (readwrite) { - IICID |= I2C_READ; - } else { - IICID &= ~I2C_READ; - } - - scl_low(); - - for (x = 7; x >= 0; x--) { - sda_out(IICID & (1 << x)); - delay(SW_I2C_WAIT_TIME); - i2c_clk_data_out(); - } -} - -void i2c_register_address(uint8_t addr) -{ - int x; - - scl_low(); - - for (x = 7; x >= 0; x--) { - sda_out(addr & (1 << x)); - delay(SW_I2C_WAIT_TIME); - i2c_clk_data_out(); - } -} - -void i2c_send_ack(void) -{ - sda_out_mode(); - sda_low(); - - delay(SW_I2C_WAIT_TIME); - scl_high(); - - delay(SW_I2C_WAIT_TIME << 1); - - sda_low(); - delay(SW_I2C_WAIT_TIME << 1); - - scl_low(); - - sda_out_mode(); - - delay(SW_I2C_WAIT_TIME); -} - -void SW_I2C_Write_Data(uint8_t data) -{ - int x; - - scl_low(); - - for (x = 7; x >= 0; x--) { - sda_out(data & (1 << x)); - delay(SW_I2C_WAIT_TIME); - i2c_clk_data_out(); - } -} - -uint8_t SW_I2C_Read_Data(void) -{ - int x; - uint8_t readdata = 0; - - sda_in_mode(); - - for (x = 8; x--;) { - scl_high(); - - readdata <<= 1; - if (SW_I2C_ReadVal_SDA()) { readdata |= 0x01; } - - delay(SW_I2C_WAIT_TIME); - scl_low(); - - delay(SW_I2C_WAIT_TIME); - } - - sda_out_mode(); - return readdata; -} - -uint8_t SW_I2C_WriteControl_8Bit(uint8_t IICID, uint8_t regaddr, uint8_t data) -{ - uint8_t returnack = true; - - i2c_start_condition(); - - i2c_slave_address(IICID, WRITE_CMD); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - i2c_register_address(regaddr); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - SW_I2C_Write_Data(data); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - i2c_stop_condition(); - - return returnack; -} - -uint8_t SW_I2C_Multi_ReadnControl_8Bit(uint8_t IICID, uint8_t regaddr, uint8_t rcnt, uint8_t (*pdata)) -{ - uint8_t returnack = true; - uint8_t index; - - i2c_port_init(); - - i2c_start_condition(); - - i2c_slave_address(IICID, WRITE_CMD); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - i2c_register_address(regaddr); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - i2c_start_condition(); - - i2c_slave_address(IICID, READ_CMD); - if (!i2c_check_ack()) { returnack = false; } - - for ( index = 0 ; index < (rcnt-1) ; index++) { - delay(SW_I2C_WAIT_TIME); - pdata[index] = SW_I2C_Read_Data(); - i2c_send_ack(); - } - - pdata[rcnt-1] = SW_I2C_Read_Data(); - - i2c_check_not_ack(); - - i2c_stop_condition(); - - return returnack; -} diff --git a/body/board/drivers/llbxcan.h b/body/board/drivers/llbxcan.h deleted file mode 100644 index 15ebb27ed8f3338..000000000000000 --- a/body/board/drivers/llbxcan.h +++ /dev/null @@ -1,125 +0,0 @@ -// SAE 2284-3 : minimum 16 tq, SJW 3, sample point at 81.3% -#define CAN_QUANTA 16U -#define CAN_SEQ1 12U -#define CAN_SEQ2 3U -#define CAN_SJW 3U - -#define CAN_PCLK (CORE_FREQ / 2U / 1000U) -#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) -#define CAN_INIT_TIMEOUT_MS 500 - -bool llcan_set_speed(CAN_TypeDef *CAN_obj, uint32_t speed, bool loopback, bool silent) { - bool ret = true; - - // initialization mode - CAN1->MCR = CAN_MCR_INRQ; // When we want to use only CAN2 - need to do that - CAN_obj->MCR = CAN_MCR_INRQ; - uint32_t timeout_counter = 0U; - while((CAN_obj->MSR & CAN_MSR_INAK) != CAN_MSR_INAK){ - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - ret = false; - break; - } - } - - if(ret){ - // set time quanta from defines - CAN_obj->BTR = ((CAN_BTR_TS1_0 * (CAN_SEQ1-1)) | - (CAN_BTR_TS2_0 * (CAN_SEQ2-1)) | - (CAN_BTR_SJW_0 * (CAN_SJW-1)) | - (can_speed_to_prescaler(speed) - 1U)); - - // silent loopback mode for debugging - if (loopback) { - CAN_obj->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM; - } - if (silent) { - CAN_obj->BTR |= CAN_BTR_SILM; - } - - CAN_obj->MCR |= CAN_MCR_AWUM; // Automatic wakeup mode - CAN_obj->MCR |= CAN_MCR_ABOM; // Automatic bus-off management - CAN_obj->MCR &= ~CAN_MCR_NART; // Automatic retransmission - CAN_obj->MCR |= CAN_MCR_TXFP; // Priority driven by the request order (chronologically) - CAN_obj->MCR &= ~CAN_MCR_INRQ; - - timeout_counter = 0U; - while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - ret = false; - break; - } - } - } - - return ret; -} - -bool llcan_init(CAN_TypeDef *CAN_obj) { - bool ret = true; - - // Enter init mode - CAN_obj->FMR |= CAN_FMR_FINIT; - - // Wait for INAK bit to be set - uint32_t timeout_counter = 0U; - while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - ret = false; - break; - } - } - - if(ret){ - // no mask - // For some weird reason some of these registers do not want to set properly on CAN2 and CAN3. Probably something to do with the single/dual mode and their different filters. - // Filters MUST be set always through CAN1(Master) as CAN2/3 are Slave - CAN1->sFilterRegister[0].FR1 = 0U; - CAN1->sFilterRegister[0].FR2 = 0U; - CAN1->sFilterRegister[14].FR1 = 0U; - CAN1->sFilterRegister[14].FR2 = 0U; - CAN1->FA1R |= 1U | (1U << 14); - - // Exit init mode, do not wait - CAN_obj->FMR &= ~CAN_FMR_FINIT; - - // enable certain CAN interrupts - CAN1->IER = 0U; // When we want to use only CAN2 - need to do that - CAN_obj->IER = CAN_IER_FMPIE0 | CAN_IER_TMEIE | CAN_IER_WKUIE; - - if (CAN_obj == CAN1) { - HAL_NVIC_EnableIRQ(CAN1_TX_IRQn); - HAL_NVIC_SetPriority(CAN1_RX0_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); - HAL_NVIC_SetPriority(CAN1_SCE_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN1_SCE_IRQn); - } else { - HAL_NVIC_SetPriority(CAN2_TX_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN2_TX_IRQn); - HAL_NVIC_SetPriority(CAN2_RX0_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN2_RX0_IRQn); - HAL_NVIC_SetPriority(CAN2_SCE_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN2_SCE_IRQn); - } - } - return ret; -} - -void llcan_clear_send(CAN_TypeDef *CAN_obj) { - CAN_obj->TSR |= CAN_TSR_ABRQ0; - CAN_obj->MSR &= ~CAN_MSR_ERRI; - // cppcheck-suppress selfAssignment ; needed to clear the register - CAN_obj->MSR = CAN_obj->MSR; -} diff --git a/body/board/drivers/llflash.h b/body/board/drivers/llflash.h deleted file mode 100644 index 7ce5a25f0b166b6..000000000000000 --- a/body/board/drivers/llflash.h +++ /dev/null @@ -1,26 +0,0 @@ -bool flash_is_locked(void) { - return (FLASH->CR & FLASH_CR_LOCK); -} - -void flash_unlock(void) { - FLASH->KEYR = 0x45670123; - FLASH->KEYR = 0xCDEF89AB; -} - -bool flash_erase_sector(uint8_t sector, bool unlocked) { - // don't erase the bootloader(sector 0) - if (sector != 0 && sector < 12 && unlocked) { - FLASH->CR = (sector << 3) | FLASH_CR_SER; - FLASH->CR |= FLASH_CR_STRT; - while (FLASH->SR & FLASH_SR_BSY); - return true; - } - return false; -} - -void flash_write_word(void *prog_ptr, uint32_t data) { - uint32_t *pp = prog_ptr; - FLASH->CR = FLASH_CR_PSIZE_1 | FLASH_CR_PG; - *pp = data; - while (FLASH->SR & FLASH_SR_BSY); -} diff --git a/body/board/early_init.h b/body/board/early_init.h deleted file mode 100644 index ccfe0a07aa7fc20..000000000000000 --- a/body/board/early_init.h +++ /dev/null @@ -1,15 +0,0 @@ -// Early bringup -extern void *g_pfnVectors; -extern uint32_t enter_bootloader_mode; - -void early_initialization(void) { - SystemInit(); - // after it's been in the bootloader, things are initted differently, so we reset - if ((enter_bootloader_mode != BOOT_NORMAL) && - (enter_bootloader_mode != ENTER_SOFTLOADER_MAGIC)) { - enter_bootloader_mode = BOOT_NORMAL; - NVIC_SystemReset(); - } - // setup interrupt table - SCB->VTOR = (uint32_t)&g_pfnVectors; // TODO: check if SystemInit is enough! -} diff --git a/body/board/flash_base.sh b/body/board/flash_base.sh deleted file mode 100755 index b06818a5cb98e34..000000000000000 --- a/body/board/flash_base.sh +++ /dev/null @@ -1,6 +0,0 @@ -#!/usr/bin/env sh -set -e - -scons -u - -./canloader.py base obj/body.bin.signed diff --git a/body/board/flash_knee.sh b/body/board/flash_knee.sh deleted file mode 100755 index c6a2c05ddcd3852..000000000000000 --- a/body/board/flash_knee.sh +++ /dev/null @@ -1,6 +0,0 @@ -#!/usr/bin/env sh -set -e - -scons -u - -./canloader.py knee obj/body.bin.signed diff --git a/body/board/flasher.h b/body/board/flasher.h deleted file mode 100644 index 43cfa47ff941616..000000000000000 --- a/body/board/flasher.h +++ /dev/null @@ -1,288 +0,0 @@ -typedef union { - uint16_t w; - struct BW { - uint8_t msb; - uint8_t lsb; - } - bw; -} -uint16_t_uint8_t; - -typedef union _USB_Setup { - uint32_t d8[2]; - struct _SetupPkt_Struc - { - uint8_t bmRequestType; - uint8_t bRequest; - uint16_t_uint8_t wValue; - uint16_t_uint8_t wIndex; - uint16_t_uint8_t wLength; - } b; -} -USB_Setup_TypeDef; - -uint32_t *prog_ptr = NULL; -bool unlocked = false; -extern uint8_t hw_type; - -#define CAN_BL_INPUT 0x1 -#define CAN_BL_OUTPUT 0x2 - -int can_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp) { - int resp_len = 0; - - // flasher machine - memset(resp, 0, 4); - memcpy(resp+4, "\xde\xad\xd0\x0d", 4); - resp[0] = 0xff; - resp[2] = setup->b.bRequest; - resp[3] = ~setup->b.bRequest; - *((uint32_t **)&resp[8]) = prog_ptr; - resp_len = 0xc; - - int sec; - switch (setup->b.bRequest) { - // **** 0xb0: flasher echo - case 0xb0: - resp[1] = 0xff; - break; - // **** 0xb1: unlock flash - case 0xb1: - if (flash_is_locked()) { - flash_unlock(); - resp[1] = 0xff; - } - out_enable(LED_BLUE, true); - unlocked = true; - prog_ptr = (uint32_t *)APP_START_ADDRESS; - break; - // **** 0xb2: erase sector - case 0xb2: - sec = setup->b.wValue.w; - if (flash_erase_sector(sec, unlocked)) { - resp[1] = 0xff; - } - break; - // **** 0xd0: fetch serial number - case 0xd0: - // addresses are OTP - if (setup->b.wValue.w == 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: - switch (setup->b.wValue.w) { - case 1: - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - break; - } - break; - // **** 0xd6: get version - case 0xd6: - COMPILE_TIME_ASSERT(sizeof(gitversion) <= 0x40U); - memcpy(resp, gitversion, sizeof(gitversion)); - resp_len = sizeof(gitversion); - break; - // **** 0xd8: reset ST - case 0xd8: - NVIC_SystemReset(); - break; - } - return resp_len; -} - -void flash_data(void *data, int len) { - out_enable(LED_RED, false); - for (int i = 0; i < len/4; i++) { - flash_write_word(prog_ptr, *(uint32_t*)(data+(i*4))); - prog_ptr++; - } - out_enable(LED_RED, true); -} - -int prep_data(uint8_t *data, uint8_t *data_out) { - int resp_len = 0; - switch (data[0]) { - case 0: - // control transfer - resp_len = can_control_msg((USB_Setup_TypeDef *)(data+4), data_out); - break; - case 2: - // ep 2, flash! - flash_data(data+4, data[2]); - break; - } - return resp_len; -} - -void CAN2_TX_IRQHandler(void) { - // clear interrupt - board.CAN->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 (!(board.CAN->TSR & CAN_TSR_TME0)); - - // send continue - board.CAN->sTxMailBox[0].TDLR = ((uint32_t*)odat)[0]; - board.CAN->sTxMailBox[0].TDHR = ((uint32_t*)odat)[1]; - board.CAN->sTxMailBox[0].TDTR = 8; - board.CAN->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1; -} - -void CAN2_RX0_IRQHandler(void) { - while (board.CAN->RF0R & CAN_RF0R_FMP0) { - if ((board.CAN->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) { - uint8_t dat[8]; - for (int i = 0; i < 8; i++) { - dat[i] = GET_MAILBOX_BYTE(&board.CAN->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 (!(board.CAN->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) { - // call the function - memset(isotp_buf_out, 0, ISOTP_BUF_SIZE); - isotp_buf_out_remain = prep_data(isotp_buf, 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 - board.CAN->RF0R |= CAN_RF0R_RFOM0; - } -} - -void CAN2_SCE_IRQHandler(void) { - llcan_clear_send(board.CAN); -} - -void CAN1_TX_IRQHandler(void) { - CAN2_TX_IRQHandler(); -} - -void CAN1_RX0_IRQHandler(void) { - CAN2_RX0_IRQHandler(); -} - -void CAN1_SCE_IRQHandler(void) { - CAN2_SCE_IRQHandler(); -} - -void check_powerdown(void) { - if(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && (hw_type == HW_TYPE_BASE)) { - uint16_t cnt_press = 0; - while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { - HAL_Delay(10); - cnt_press++; - if (cnt_press == (2 * 100)) { - out_enable(POWERSWITCH, false); - while(1) { - // Temporarily, to see that we went to power off but can't switch the latch - HAL_GPIO_TogglePin(board.led_portR, board.led_pinR); - HAL_Delay(100); - } - } - } - } -} - - -void soft_flasher_start(void) { - enter_bootloader_mode = 0; - - out_enable(TRANSCEIVER, true); - - __HAL_RCC_CAN1_CLK_ENABLE(); // Also needed for CAN2, dumb... - __HAL_RCC_CAN2_CLK_ENABLE(); - - // init can - llcan_set_speed(board.CAN, 5000, false, false); - llcan_init(board.CAN); - - out_enable(LED_BLUE, true); - // Wait for power button release, only for the base - if (hw_type == HW_TYPE_BASE) { - while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {} - } - out_enable(LED_GREEN, false); - - uint64_t cnt = 0; - - for (cnt=0;;cnt++) { - // blink the green LED fast - out_enable(LED_BLUE, false); - delay(500000); - out_enable(LED_BLUE, true); - delay(500000); - check_powerdown(); - } -} diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h deleted file mode 100644 index ae83378c19e46e1..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h +++ /dev/null @@ -1,3840 +0,0 @@ -/** - ****************************************************************************** - * @file stm32_hal_legacy.h - * @author MCD Application Team - * @brief This file contains aliases definition for the STM32Cube HAL constants - * macros and functions maintained for legacy purpose. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2019 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32_HAL_LEGACY -#define STM32_HAL_LEGACY - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup HAL_AES_Aliased_Defines HAL CRYP Aliased Defines maintained for legacy purpose - * @{ - */ -#define AES_FLAG_RDERR CRYP_FLAG_RDERR -#define AES_FLAG_WRERR CRYP_FLAG_WRERR -#define AES_CLEARFLAG_CCF CRYP_CLEARFLAG_CCF -#define AES_CLEARFLAG_RDERR CRYP_CLEARFLAG_RDERR -#define AES_CLEARFLAG_WRERR CRYP_CLEARFLAG_WRERR -#if defined(STM32U5) -#define CRYP_DATATYPE_32B CRYP_NO_SWAP -#define CRYP_DATATYPE_16B CRYP_HALFWORD_SWAP -#define CRYP_DATATYPE_8B CRYP_BYTE_SWAP -#define CRYP_DATATYPE_1B CRYP_BIT_SWAP -#define CRYP_CCF_CLEAR CRYP_CLEAR_CCF -#define CRYP_ERR_CLEAR CRYP_CLEAR_RWEIF -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup HAL_ADC_Aliased_Defines HAL ADC Aliased Defines maintained for legacy purpose - * @{ - */ -#define ADC_RESOLUTION12b ADC_RESOLUTION_12B -#define ADC_RESOLUTION10b ADC_RESOLUTION_10B -#define ADC_RESOLUTION8b ADC_RESOLUTION_8B -#define ADC_RESOLUTION6b ADC_RESOLUTION_6B -#define OVR_DATA_OVERWRITTEN ADC_OVR_DATA_OVERWRITTEN -#define OVR_DATA_PRESERVED ADC_OVR_DATA_PRESERVED -#define EOC_SINGLE_CONV ADC_EOC_SINGLE_CONV -#define EOC_SEQ_CONV ADC_EOC_SEQ_CONV -#define EOC_SINGLE_SEQ_CONV ADC_EOC_SINGLE_SEQ_CONV -#define REGULAR_GROUP ADC_REGULAR_GROUP -#define INJECTED_GROUP ADC_INJECTED_GROUP -#define REGULAR_INJECTED_GROUP ADC_REGULAR_INJECTED_GROUP -#define AWD_EVENT ADC_AWD_EVENT -#define AWD1_EVENT ADC_AWD1_EVENT -#define AWD2_EVENT ADC_AWD2_EVENT -#define AWD3_EVENT ADC_AWD3_EVENT -#define OVR_EVENT ADC_OVR_EVENT -#define JQOVF_EVENT ADC_JQOVF_EVENT -#define ALL_CHANNELS ADC_ALL_CHANNELS -#define REGULAR_CHANNELS ADC_REGULAR_CHANNELS -#define INJECTED_CHANNELS ADC_INJECTED_CHANNELS -#define SYSCFG_FLAG_SENSOR_ADC ADC_FLAG_SENSOR -#define SYSCFG_FLAG_VREF_ADC ADC_FLAG_VREFINT -#define ADC_CLOCKPRESCALER_PCLK_DIV1 ADC_CLOCK_SYNC_PCLK_DIV1 -#define ADC_CLOCKPRESCALER_PCLK_DIV2 ADC_CLOCK_SYNC_PCLK_DIV2 -#define ADC_CLOCKPRESCALER_PCLK_DIV4 ADC_CLOCK_SYNC_PCLK_DIV4 -#define ADC_CLOCKPRESCALER_PCLK_DIV6 ADC_CLOCK_SYNC_PCLK_DIV6 -#define ADC_CLOCKPRESCALER_PCLK_DIV8 ADC_CLOCK_SYNC_PCLK_DIV8 -#define ADC_EXTERNALTRIG0_T6_TRGO ADC_EXTERNALTRIGCONV_T6_TRGO -#define ADC_EXTERNALTRIG1_T21_CC2 ADC_EXTERNALTRIGCONV_T21_CC2 -#define ADC_EXTERNALTRIG2_T2_TRGO ADC_EXTERNALTRIGCONV_T2_TRGO -#define ADC_EXTERNALTRIG3_T2_CC4 ADC_EXTERNALTRIGCONV_T2_CC4 -#define ADC_EXTERNALTRIG4_T22_TRGO ADC_EXTERNALTRIGCONV_T22_TRGO -#define ADC_EXTERNALTRIG7_EXT_IT11 ADC_EXTERNALTRIGCONV_EXT_IT11 -#define ADC_CLOCK_ASYNC ADC_CLOCK_ASYNC_DIV1 -#define ADC_EXTERNALTRIG_EDGE_NONE ADC_EXTERNALTRIGCONVEDGE_NONE -#define ADC_EXTERNALTRIG_EDGE_RISING ADC_EXTERNALTRIGCONVEDGE_RISING -#define ADC_EXTERNALTRIG_EDGE_FALLING ADC_EXTERNALTRIGCONVEDGE_FALLING -#define ADC_EXTERNALTRIG_EDGE_RISINGFALLING ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING -#define ADC_SAMPLETIME_2CYCLE_5 ADC_SAMPLETIME_2CYCLES_5 - -#define HAL_ADC_STATE_BUSY_REG HAL_ADC_STATE_REG_BUSY -#define HAL_ADC_STATE_BUSY_INJ HAL_ADC_STATE_INJ_BUSY -#define HAL_ADC_STATE_EOC_REG HAL_ADC_STATE_REG_EOC -#define HAL_ADC_STATE_EOC_INJ HAL_ADC_STATE_INJ_EOC -#define HAL_ADC_STATE_ERROR HAL_ADC_STATE_ERROR_INTERNAL -#define HAL_ADC_STATE_BUSY HAL_ADC_STATE_BUSY_INTERNAL -#define HAL_ADC_STATE_AWD HAL_ADC_STATE_AWD1 - -#if defined(STM32H7) -#define ADC_CHANNEL_VBAT_DIV4 ADC_CHANNEL_VBAT -#endif /* STM32H7 */ -/** - * @} - */ - -/** @defgroup HAL_CEC_Aliased_Defines HAL CEC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define __HAL_CEC_GET_IT __HAL_CEC_GET_FLAG - -/** - * @} - */ - -/** @defgroup HAL_COMP_Aliased_Defines HAL COMP Aliased Defines maintained for legacy purpose - * @{ - */ -#define COMP_WINDOWMODE_DISABLED COMP_WINDOWMODE_DISABLE -#define COMP_WINDOWMODE_ENABLED COMP_WINDOWMODE_ENABLE -#define COMP_EXTI_LINE_COMP1_EVENT COMP_EXTI_LINE_COMP1 -#define COMP_EXTI_LINE_COMP2_EVENT COMP_EXTI_LINE_COMP2 -#define COMP_EXTI_LINE_COMP3_EVENT COMP_EXTI_LINE_COMP3 -#define COMP_EXTI_LINE_COMP4_EVENT COMP_EXTI_LINE_COMP4 -#define COMP_EXTI_LINE_COMP5_EVENT COMP_EXTI_LINE_COMP5 -#define COMP_EXTI_LINE_COMP6_EVENT COMP_EXTI_LINE_COMP6 -#define COMP_EXTI_LINE_COMP7_EVENT COMP_EXTI_LINE_COMP7 -#if defined(STM32L0) -#define COMP_LPTIMCONNECTION_ENABLED ((uint32_t)0x00000003U) /*!< COMPX output generic naming: connected to LPTIM input 1 for COMP1, LPTIM input 2 for COMP2 */ -#endif -#define COMP_OUTPUT_COMP6TIM2OCREFCLR COMP_OUTPUT_COMP6_TIM2OCREFCLR -#if defined(STM32F373xC) || defined(STM32F378xx) -#define COMP_OUTPUT_TIM3IC1 COMP_OUTPUT_COMP1_TIM3IC1 -#define COMP_OUTPUT_TIM3OCREFCLR COMP_OUTPUT_COMP1_TIM3OCREFCLR -#endif /* STM32F373xC || STM32F378xx */ - -#if defined(STM32L0) || defined(STM32L4) -#define COMP_WINDOWMODE_ENABLE COMP_WINDOWMODE_COMP1_INPUT_PLUS_COMMON - -#define COMP_NONINVERTINGINPUT_IO1 COMP_INPUT_PLUS_IO1 -#define COMP_NONINVERTINGINPUT_IO2 COMP_INPUT_PLUS_IO2 -#define COMP_NONINVERTINGINPUT_IO3 COMP_INPUT_PLUS_IO3 -#define COMP_NONINVERTINGINPUT_IO4 COMP_INPUT_PLUS_IO4 -#define COMP_NONINVERTINGINPUT_IO5 COMP_INPUT_PLUS_IO5 -#define COMP_NONINVERTINGINPUT_IO6 COMP_INPUT_PLUS_IO6 - -#define COMP_INVERTINGINPUT_1_4VREFINT COMP_INPUT_MINUS_1_4VREFINT -#define COMP_INVERTINGINPUT_1_2VREFINT COMP_INPUT_MINUS_1_2VREFINT -#define COMP_INVERTINGINPUT_3_4VREFINT COMP_INPUT_MINUS_3_4VREFINT -#define COMP_INVERTINGINPUT_VREFINT COMP_INPUT_MINUS_VREFINT -#define COMP_INVERTINGINPUT_DAC1_CH1 COMP_INPUT_MINUS_DAC1_CH1 -#define COMP_INVERTINGINPUT_DAC1_CH2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_DAC1 COMP_INPUT_MINUS_DAC1_CH1 -#define COMP_INVERTINGINPUT_DAC2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_IO1 COMP_INPUT_MINUS_IO1 -#if defined(STM32L0) -/* Issue fixed on STM32L0 COMP driver: only 2 dedicated IO (IO1 and IO2), */ -/* IO2 was wrongly assigned to IO shared with DAC and IO3 was corresponding */ -/* to the second dedicated IO (only for COMP2). */ -#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO2 -#else -#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_IO2 -#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO3 -#endif -#define COMP_INVERTINGINPUT_IO4 COMP_INPUT_MINUS_IO4 -#define COMP_INVERTINGINPUT_IO5 COMP_INPUT_MINUS_IO5 - -#define COMP_OUTPUTLEVEL_LOW COMP_OUTPUT_LEVEL_LOW -#define COMP_OUTPUTLEVEL_HIGH COMP_OUTPUT_LEVEL_HIGH - -/* Note: Literal "COMP_FLAG_LOCK" kept for legacy purpose. */ -/* To check COMP lock state, use macro "__HAL_COMP_IS_LOCKED()". */ -#if defined(COMP_CSR_LOCK) -#define COMP_FLAG_LOCK COMP_CSR_LOCK -#elif defined(COMP_CSR_COMP1LOCK) -#define COMP_FLAG_LOCK COMP_CSR_COMP1LOCK -#elif defined(COMP_CSR_COMPxLOCK) -#define COMP_FLAG_LOCK COMP_CSR_COMPxLOCK -#endif - -#if defined(STM32L4) -#define COMP_BLANKINGSRCE_TIM1OC5 COMP_BLANKINGSRC_TIM1_OC5_COMP1 -#define COMP_BLANKINGSRCE_TIM2OC3 COMP_BLANKINGSRC_TIM2_OC3_COMP1 -#define COMP_BLANKINGSRCE_TIM3OC3 COMP_BLANKINGSRC_TIM3_OC3_COMP1 -#define COMP_BLANKINGSRCE_TIM3OC4 COMP_BLANKINGSRC_TIM3_OC4_COMP2 -#define COMP_BLANKINGSRCE_TIM8OC5 COMP_BLANKINGSRC_TIM8_OC5_COMP2 -#define COMP_BLANKINGSRCE_TIM15OC1 COMP_BLANKINGSRC_TIM15_OC1_COMP2 -#define COMP_BLANKINGSRCE_NONE COMP_BLANKINGSRC_NONE -#endif - -#if defined(STM32L0) -#define COMP_MODE_HIGHSPEED COMP_POWERMODE_MEDIUMSPEED -#define COMP_MODE_LOWSPEED COMP_POWERMODE_ULTRALOWPOWER -#else -#define COMP_MODE_HIGHSPEED COMP_POWERMODE_HIGHSPEED -#define COMP_MODE_MEDIUMSPEED COMP_POWERMODE_MEDIUMSPEED -#define COMP_MODE_LOWPOWER COMP_POWERMODE_LOWPOWER -#define COMP_MODE_ULTRALOWPOWER COMP_POWERMODE_ULTRALOWPOWER -#endif - -#endif -/** - * @} - */ - -/** @defgroup HAL_CORTEX_Aliased_Defines HAL CORTEX Aliased Defines maintained for legacy purpose - * @{ - */ -#define __HAL_CORTEX_SYSTICKCLK_CONFIG HAL_SYSTICK_CLKSourceConfig -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup HAL_CRC_Aliased_Defines HAL CRC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define CRC_OUTPUTDATA_INVERSION_DISABLED CRC_OUTPUTDATA_INVERSION_DISABLE -#define CRC_OUTPUTDATA_INVERSION_ENABLED CRC_OUTPUTDATA_INVERSION_ENABLE - -/** - * @} - */ - -/** @defgroup HAL_DAC_Aliased_Defines HAL DAC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define DAC1_CHANNEL_1 DAC_CHANNEL_1 -#define DAC1_CHANNEL_2 DAC_CHANNEL_2 -#define DAC2_CHANNEL_1 DAC_CHANNEL_1 -#define DAC_WAVE_NONE 0x00000000U -#define DAC_WAVE_NOISE DAC_CR_WAVE1_0 -#define DAC_WAVE_TRIANGLE DAC_CR_WAVE1_1 -#define DAC_WAVEGENERATION_NONE DAC_WAVE_NONE -#define DAC_WAVEGENERATION_NOISE DAC_WAVE_NOISE -#define DAC_WAVEGENERATION_TRIANGLE DAC_WAVE_TRIANGLE - -#if defined(STM32G4) || defined(STM32H7) || defined (STM32U5) -#define DAC_CHIPCONNECT_DISABLE DAC_CHIPCONNECT_EXTERNAL -#define DAC_CHIPCONNECT_ENABLE DAC_CHIPCONNECT_INTERNAL -#endif - -#if defined(STM32L1) || defined(STM32L4) || defined(STM32G0) || defined(STM32L5) || defined(STM32H7) || defined(STM32F4) || defined(STM32G4) -#define HAL_DAC_MSP_INIT_CB_ID HAL_DAC_MSPINIT_CB_ID -#define HAL_DAC_MSP_DEINIT_CB_ID HAL_DAC_MSPDEINIT_CB_ID -#endif - -/** - * @} - */ - -/** @defgroup HAL_DMA_Aliased_Defines HAL DMA Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_REMAPDMA_ADC_DMA_CH2 DMA_REMAP_ADC_DMA_CH2 -#define HAL_REMAPDMA_USART1_TX_DMA_CH4 DMA_REMAP_USART1_TX_DMA_CH4 -#define HAL_REMAPDMA_USART1_RX_DMA_CH5 DMA_REMAP_USART1_RX_DMA_CH5 -#define HAL_REMAPDMA_TIM16_DMA_CH4 DMA_REMAP_TIM16_DMA_CH4 -#define HAL_REMAPDMA_TIM17_DMA_CH2 DMA_REMAP_TIM17_DMA_CH2 -#define HAL_REMAPDMA_USART3_DMA_CH32 DMA_REMAP_USART3_DMA_CH32 -#define HAL_REMAPDMA_TIM16_DMA_CH6 DMA_REMAP_TIM16_DMA_CH6 -#define HAL_REMAPDMA_TIM17_DMA_CH7 DMA_REMAP_TIM17_DMA_CH7 -#define HAL_REMAPDMA_SPI2_DMA_CH67 DMA_REMAP_SPI2_DMA_CH67 -#define HAL_REMAPDMA_USART2_DMA_CH67 DMA_REMAP_USART2_DMA_CH67 -#define HAL_REMAPDMA_I2C1_DMA_CH76 DMA_REMAP_I2C1_DMA_CH76 -#define HAL_REMAPDMA_TIM1_DMA_CH6 DMA_REMAP_TIM1_DMA_CH6 -#define HAL_REMAPDMA_TIM2_DMA_CH7 DMA_REMAP_TIM2_DMA_CH7 -#define HAL_REMAPDMA_TIM3_DMA_CH6 DMA_REMAP_TIM3_DMA_CH6 - -#define IS_HAL_REMAPDMA IS_DMA_REMAP -#define __HAL_REMAPDMA_CHANNEL_ENABLE __HAL_DMA_REMAP_CHANNEL_ENABLE -#define __HAL_REMAPDMA_CHANNEL_DISABLE __HAL_DMA_REMAP_CHANNEL_DISABLE - -#if defined(STM32L4) - -#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI1 HAL_DMAMUX1_REQ_GEN_EXTI1 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI2 HAL_DMAMUX1_REQ_GEN_EXTI2 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI3 HAL_DMAMUX1_REQ_GEN_EXTI3 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI4 HAL_DMAMUX1_REQ_GEN_EXTI4 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI5 HAL_DMAMUX1_REQ_GEN_EXTI5 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI6 HAL_DMAMUX1_REQ_GEN_EXTI6 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI7 HAL_DMAMUX1_REQ_GEN_EXTI7 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI8 HAL_DMAMUX1_REQ_GEN_EXTI8 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI9 HAL_DMAMUX1_REQ_GEN_EXTI9 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI10 HAL_DMAMUX1_REQ_GEN_EXTI10 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI11 HAL_DMAMUX1_REQ_GEN_EXTI11 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI12 HAL_DMAMUX1_REQ_GEN_EXTI12 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI13 HAL_DMAMUX1_REQ_GEN_EXTI13 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI14 HAL_DMAMUX1_REQ_GEN_EXTI14 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI15 HAL_DMAMUX1_REQ_GEN_EXTI15 -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH3_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH3_EVT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX1_REQUEST_GEN_DSI_TE HAL_DMAMUX1_REQ_GEN_DSI_TE -#define HAL_DMAMUX1_REQUEST_GEN_DSI_EOT HAL_DMAMUX1_REQ_GEN_DSI_EOT -#define HAL_DMAMUX1_REQUEST_GEN_DMA2D_EOT HAL_DMAMUX1_REQ_GEN_DMA2D_EOT -#define HAL_DMAMUX1_REQUEST_GEN_LTDC_IT HAL_DMAMUX1_REQ_GEN_LTDC_IT - -#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT -#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING -#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING -#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING - -#if defined(STM32L4R5xx) || defined(STM32L4R9xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx) -#define DMA_REQUEST_DCMI_PSSI DMA_REQUEST_DCMI -#endif - -#endif /* STM32L4 */ - -#if defined(STM32G0) -#define DMA_REQUEST_DAC1_CHANNEL1 DMA_REQUEST_DAC1_CH1 -#define DMA_REQUEST_DAC1_CHANNEL2 DMA_REQUEST_DAC1_CH2 -#define DMA_REQUEST_TIM16_TRIG_COM DMA_REQUEST_TIM16_COM -#define DMA_REQUEST_TIM17_TRIG_COM DMA_REQUEST_TIM17_COM - -#define LL_DMAMUX_REQ_TIM16_TRIG_COM LL_DMAMUX_REQ_TIM16_COM -#define LL_DMAMUX_REQ_TIM17_TRIG_COM LL_DMAMUX_REQ_TIM17_COM -#endif - -#if defined(STM32H7) - -#define DMA_REQUEST_DAC1 DMA_REQUEST_DAC1_CH1 -#define DMA_REQUEST_DAC2 DMA_REQUEST_DAC1_CH2 - -#define BDMA_REQUEST_LP_UART1_RX BDMA_REQUEST_LPUART1_RX -#define BDMA_REQUEST_LP_UART1_TX BDMA_REQUEST_LPUART1_TX - -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX1_REQ_GEN_LPTIM3_OUT -#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0 -#define HAL_DMAMUX1_REQUEST_GEN_TIM12_TRGO HAL_DMAMUX1_REQ_GEN_TIM12_TRGO - -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH0_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH0_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH1_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH1_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH2_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH2_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH3_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH3_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH4_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH4_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH5_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH5_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH6_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH6_EVT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_RX_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_TX_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM2_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX2_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM3_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX2_REQ_GEN_LPTIM3_OUT -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM4_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM4_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM5_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM5_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_I2C4_WKUP HAL_DMAMUX2_REQ_GEN_I2C4_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_SPI6_WKUP HAL_DMAMUX2_REQ_GEN_SPI6_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_COMP1_OUT HAL_DMAMUX2_REQ_GEN_COMP1_OUT -#define HAL_DMAMUX2_REQUEST_GEN_COMP2_OUT HAL_DMAMUX2_REQ_GEN_COMP2_OUT -#define HAL_DMAMUX2_REQUEST_GEN_RTC_WKUP HAL_DMAMUX2_REQ_GEN_RTC_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_EXTI0 HAL_DMAMUX2_REQ_GEN_EXTI0 -#define HAL_DMAMUX2_REQUEST_GEN_EXTI2 HAL_DMAMUX2_REQ_GEN_EXTI2 -#define HAL_DMAMUX2_REQUEST_GEN_I2C4_IT_EVT HAL_DMAMUX2_REQ_GEN_I2C4_IT_EVT -#define HAL_DMAMUX2_REQUEST_GEN_SPI6_IT HAL_DMAMUX2_REQ_GEN_SPI6_IT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_TX_IT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_RX_IT -#define HAL_DMAMUX2_REQUEST_GEN_ADC3_IT HAL_DMAMUX2_REQ_GEN_ADC3_IT -#define HAL_DMAMUX2_REQUEST_GEN_ADC3_AWD1_OUT HAL_DMAMUX2_REQ_GEN_ADC3_AWD1_OUT -#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH0_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH0_IT -#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH1_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH1_IT - -#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT -#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING -#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING -#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING - -#define DFSDM_FILTER_EXT_TRIG_LPTIM1 DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT -#define DFSDM_FILTER_EXT_TRIG_LPTIM2 DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT -#define DFSDM_FILTER_EXT_TRIG_LPTIM3 DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT - -#define DAC_TRIGGER_LP1_OUT DAC_TRIGGER_LPTIM1_OUT -#define DAC_TRIGGER_LP2_OUT DAC_TRIGGER_LPTIM2_OUT - -#endif /* STM32H7 */ -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Defines HAL FLASH Aliased Defines maintained for legacy purpose - * @{ - */ - -#define TYPEPROGRAM_BYTE FLASH_TYPEPROGRAM_BYTE -#define TYPEPROGRAM_HALFWORD FLASH_TYPEPROGRAM_HALFWORD -#define TYPEPROGRAM_WORD FLASH_TYPEPROGRAM_WORD -#define TYPEPROGRAM_DOUBLEWORD FLASH_TYPEPROGRAM_DOUBLEWORD -#define TYPEERASE_SECTORS FLASH_TYPEERASE_SECTORS -#define TYPEERASE_PAGES FLASH_TYPEERASE_PAGES -#define TYPEERASE_PAGEERASE FLASH_TYPEERASE_PAGES -#define TYPEERASE_MASSERASE FLASH_TYPEERASE_MASSERASE -#define WRPSTATE_DISABLE OB_WRPSTATE_DISABLE -#define WRPSTATE_ENABLE OB_WRPSTATE_ENABLE -#define HAL_FLASH_TIMEOUT_VALUE FLASH_TIMEOUT_VALUE -#define OBEX_PCROP OPTIONBYTE_PCROP -#define OBEX_BOOTCONFIG OPTIONBYTE_BOOTCONFIG -#define PCROPSTATE_DISABLE OB_PCROP_STATE_DISABLE -#define PCROPSTATE_ENABLE OB_PCROP_STATE_ENABLE -#define TYPEERASEDATA_BYTE FLASH_TYPEERASEDATA_BYTE -#define TYPEERASEDATA_HALFWORD FLASH_TYPEERASEDATA_HALFWORD -#define TYPEERASEDATA_WORD FLASH_TYPEERASEDATA_WORD -#define TYPEPROGRAMDATA_BYTE FLASH_TYPEPROGRAMDATA_BYTE -#define TYPEPROGRAMDATA_HALFWORD FLASH_TYPEPROGRAMDATA_HALFWORD -#define TYPEPROGRAMDATA_WORD FLASH_TYPEPROGRAMDATA_WORD -#define TYPEPROGRAMDATA_FASTBYTE FLASH_TYPEPROGRAMDATA_FASTBYTE -#define TYPEPROGRAMDATA_FASTHALFWORD FLASH_TYPEPROGRAMDATA_FASTHALFWORD -#define TYPEPROGRAMDATA_FASTWORD FLASH_TYPEPROGRAMDATA_FASTWORD -#define PAGESIZE FLASH_PAGE_SIZE -#define TYPEPROGRAM_FASTBYTE FLASH_TYPEPROGRAM_BYTE -#define TYPEPROGRAM_FASTHALFWORD FLASH_TYPEPROGRAM_HALFWORD -#define TYPEPROGRAM_FASTWORD FLASH_TYPEPROGRAM_WORD -#define VOLTAGE_RANGE_1 FLASH_VOLTAGE_RANGE_1 -#define VOLTAGE_RANGE_2 FLASH_VOLTAGE_RANGE_2 -#define VOLTAGE_RANGE_3 FLASH_VOLTAGE_RANGE_3 -#define VOLTAGE_RANGE_4 FLASH_VOLTAGE_RANGE_4 -#define TYPEPROGRAM_FAST FLASH_TYPEPROGRAM_FAST -#define TYPEPROGRAM_FAST_AND_LAST FLASH_TYPEPROGRAM_FAST_AND_LAST -#define WRPAREA_BANK1_AREAA OB_WRPAREA_BANK1_AREAA -#define WRPAREA_BANK1_AREAB OB_WRPAREA_BANK1_AREAB -#define WRPAREA_BANK2_AREAA OB_WRPAREA_BANK2_AREAA -#define WRPAREA_BANK2_AREAB OB_WRPAREA_BANK2_AREAB -#define IWDG_STDBY_FREEZE OB_IWDG_STDBY_FREEZE -#define IWDG_STDBY_ACTIVE OB_IWDG_STDBY_RUN -#define IWDG_STOP_FREEZE OB_IWDG_STOP_FREEZE -#define IWDG_STOP_ACTIVE OB_IWDG_STOP_RUN -#define FLASH_ERROR_NONE HAL_FLASH_ERROR_NONE -#define FLASH_ERROR_RD HAL_FLASH_ERROR_RD -#define FLASH_ERROR_PG HAL_FLASH_ERROR_PROG -#define FLASH_ERROR_PGP HAL_FLASH_ERROR_PGS -#define FLASH_ERROR_WRP HAL_FLASH_ERROR_WRP -#define FLASH_ERROR_OPTV HAL_FLASH_ERROR_OPTV -#define FLASH_ERROR_OPTVUSR HAL_FLASH_ERROR_OPTVUSR -#define FLASH_ERROR_PROG HAL_FLASH_ERROR_PROG -#define FLASH_ERROR_OP HAL_FLASH_ERROR_OPERATION -#define FLASH_ERROR_PGA HAL_FLASH_ERROR_PGA -#define FLASH_ERROR_SIZE HAL_FLASH_ERROR_SIZE -#define FLASH_ERROR_SIZ HAL_FLASH_ERROR_SIZE -#define FLASH_ERROR_PGS HAL_FLASH_ERROR_PGS -#define FLASH_ERROR_MIS HAL_FLASH_ERROR_MIS -#define FLASH_ERROR_FAST HAL_FLASH_ERROR_FAST -#define FLASH_ERROR_FWWERR HAL_FLASH_ERROR_FWWERR -#define FLASH_ERROR_NOTZERO HAL_FLASH_ERROR_NOTZERO -#define FLASH_ERROR_OPERATION HAL_FLASH_ERROR_OPERATION -#define FLASH_ERROR_ERS HAL_FLASH_ERROR_ERS -#define OB_WDG_SW OB_IWDG_SW -#define OB_WDG_HW OB_IWDG_HW -#define OB_SDADC12_VDD_MONITOR_SET OB_SDACD_VDD_MONITOR_SET -#define OB_SDADC12_VDD_MONITOR_RESET OB_SDACD_VDD_MONITOR_RESET -#define OB_RAM_PARITY_CHECK_SET OB_SRAM_PARITY_SET -#define OB_RAM_PARITY_CHECK_RESET OB_SRAM_PARITY_RESET -#define IS_OB_SDADC12_VDD_MONITOR IS_OB_SDACD_VDD_MONITOR -#define OB_RDP_LEVEL0 OB_RDP_LEVEL_0 -#define OB_RDP_LEVEL1 OB_RDP_LEVEL_1 -#define OB_RDP_LEVEL2 OB_RDP_LEVEL_2 -#if defined(STM32G0) -#define OB_BOOT_LOCK_DISABLE OB_BOOT_ENTRY_FORCED_NONE -#define OB_BOOT_LOCK_ENABLE OB_BOOT_ENTRY_FORCED_FLASH -#else -#define OB_BOOT_ENTRY_FORCED_NONE OB_BOOT_LOCK_DISABLE -#define OB_BOOT_ENTRY_FORCED_FLASH OB_BOOT_LOCK_ENABLE -#endif -#if defined(STM32H7) -#define FLASH_FLAG_SNECCE_BANK1RR FLASH_FLAG_SNECCERR_BANK1 -#define FLASH_FLAG_DBECCE_BANK1RR FLASH_FLAG_DBECCERR_BANK1 -#define FLASH_FLAG_STRBER_BANK1R FLASH_FLAG_STRBERR_BANK1 -#define FLASH_FLAG_SNECCE_BANK2RR FLASH_FLAG_SNECCERR_BANK2 -#define FLASH_FLAG_DBECCE_BANK2RR FLASH_FLAG_DBECCERR_BANK2 -#define FLASH_FLAG_STRBER_BANK2R FLASH_FLAG_STRBERR_BANK2 -#define FLASH_FLAG_WDW FLASH_FLAG_WBNE -#define OB_WRP_SECTOR_All OB_WRP_SECTOR_ALL -#endif /* STM32H7 */ -#if defined(STM32U5) -#define OB_USER_nRST_STOP OB_USER_NRST_STOP -#define OB_USER_nRST_STDBY OB_USER_NRST_STDBY -#define OB_USER_nRST_SHDW OB_USER_NRST_SHDW -#define OB_USER_nSWBOOT0 OB_USER_NSWBOOT0 -#define OB_USER_nBOOT0 OB_USER_NBOOT0 -#define OB_nBOOT0_RESET OB_NBOOT0_RESET -#define OB_nBOOT0_SET OB_NBOOT0_SET -#endif /* STM32U5 */ - -/** - * @} - */ - -/** @defgroup HAL_JPEG_Aliased_Macros HAL JPEG Aliased Macros maintained for legacy purpose - * @{ - */ - -#if defined(STM32H7) -#define __HAL_RCC_JPEG_CLK_ENABLE __HAL_RCC_JPGDECEN_CLK_ENABLE -#define __HAL_RCC_JPEG_CLK_DISABLE __HAL_RCC_JPGDECEN_CLK_DISABLE -#define __HAL_RCC_JPEG_FORCE_RESET __HAL_RCC_JPGDECRST_FORCE_RESET -#define __HAL_RCC_JPEG_RELEASE_RESET __HAL_RCC_JPGDECRST_RELEASE_RESET -#define __HAL_RCC_JPEG_CLK_SLEEP_ENABLE __HAL_RCC_JPGDEC_CLK_SLEEP_ENABLE -#define __HAL_RCC_JPEG_CLK_SLEEP_DISABLE __HAL_RCC_JPGDEC_CLK_SLEEP_DISABLE -#endif /* STM32H7 */ - -/** - * @} - */ - -/** @defgroup HAL_SYSCFG_Aliased_Defines HAL SYSCFG Aliased Defines maintained for legacy purpose - * @{ - */ - -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA9 I2C_FASTMODEPLUS_PA9 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA10 I2C_FASTMODEPLUS_PA10 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB6 I2C_FASTMODEPLUS_PB6 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB7 I2C_FASTMODEPLUS_PB7 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB8 I2C_FASTMODEPLUS_PB8 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB9 I2C_FASTMODEPLUS_PB9 -#define HAL_SYSCFG_FASTMODEPLUS_I2C1 I2C_FASTMODEPLUS_I2C1 -#define HAL_SYSCFG_FASTMODEPLUS_I2C2 I2C_FASTMODEPLUS_I2C2 -#define HAL_SYSCFG_FASTMODEPLUS_I2C3 I2C_FASTMODEPLUS_I2C3 -#if defined(STM32G4) - -#define HAL_SYSCFG_EnableIOAnalogSwitchBooster HAL_SYSCFG_EnableIOSwitchBooster -#define HAL_SYSCFG_DisableIOAnalogSwitchBooster HAL_SYSCFG_DisableIOSwitchBooster -#define HAL_SYSCFG_EnableIOAnalogSwitchVDD HAL_SYSCFG_EnableIOSwitchVDD -#define HAL_SYSCFG_DisableIOAnalogSwitchVDD HAL_SYSCFG_DisableIOSwitchVDD -#endif /* STM32G4 */ - -/** - * @} - */ - - -/** @defgroup LL_FMC_Aliased_Defines LL FMC Aliased Defines maintained for compatibility purpose - * @{ - */ -#if defined(STM32L4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) -#define FMC_NAND_PCC_WAIT_FEATURE_DISABLE FMC_NAND_WAIT_FEATURE_DISABLE -#define FMC_NAND_PCC_WAIT_FEATURE_ENABLE FMC_NAND_WAIT_FEATURE_ENABLE -#define FMC_NAND_PCC_MEM_BUS_WIDTH_8 FMC_NAND_MEM_BUS_WIDTH_8 -#define FMC_NAND_PCC_MEM_BUS_WIDTH_16 FMC_NAND_MEM_BUS_WIDTH_16 -#elif defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) -#define FMC_NAND_WAIT_FEATURE_DISABLE FMC_NAND_PCC_WAIT_FEATURE_DISABLE -#define FMC_NAND_WAIT_FEATURE_ENABLE FMC_NAND_PCC_WAIT_FEATURE_ENABLE -#define FMC_NAND_MEM_BUS_WIDTH_8 FMC_NAND_PCC_MEM_BUS_WIDTH_8 -#define FMC_NAND_MEM_BUS_WIDTH_16 FMC_NAND_PCC_MEM_BUS_WIDTH_16 -#endif -/** - * @} - */ - -/** @defgroup LL_FSMC_Aliased_Defines LL FSMC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define FSMC_NORSRAM_TYPEDEF FSMC_NORSRAM_TypeDef -#define FSMC_NORSRAM_EXTENDED_TYPEDEF FSMC_NORSRAM_EXTENDED_TypeDef -/** - * @} - */ - -/** @defgroup HAL_GPIO_Aliased_Macros HAL GPIO Aliased Macros maintained for legacy purpose - * @{ - */ -#define GET_GPIO_SOURCE GPIO_GET_INDEX -#define GET_GPIO_INDEX GPIO_GET_INDEX - -#if defined(STM32F4) -#define GPIO_AF12_SDMMC GPIO_AF12_SDIO -#define GPIO_AF12_SDMMC1 GPIO_AF12_SDIO -#endif - -#if defined(STM32F7) -#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1 -#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1 -#endif - -#if defined(STM32L4) -#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1 -#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1 -#endif - -#if defined(STM32H7) -#define GPIO_AF7_SDIO1 GPIO_AF7_SDMMC1 -#define GPIO_AF8_SDIO1 GPIO_AF8_SDMMC1 -#define GPIO_AF12_SDIO1 GPIO_AF12_SDMMC1 -#define GPIO_AF9_SDIO2 GPIO_AF9_SDMMC2 -#define GPIO_AF10_SDIO2 GPIO_AF10_SDMMC2 -#define GPIO_AF11_SDIO2 GPIO_AF11_SDMMC2 - -#if defined (STM32H743xx) || defined (STM32H753xx) || defined (STM32H750xx) || defined (STM32H742xx) || \ - defined (STM32H745xx) || defined (STM32H755xx) || defined (STM32H747xx) || defined (STM32H757xx) -#define GPIO_AF10_OTG2_HS GPIO_AF10_OTG2_FS -#define GPIO_AF10_OTG1_FS GPIO_AF10_OTG1_HS -#define GPIO_AF12_OTG2_FS GPIO_AF12_OTG1_FS -#endif /*STM32H743xx || STM32H753xx || STM32H750xx || STM32H742xx || STM32H745xx || STM32H755xx || STM32H747xx || STM32H757xx */ -#endif /* STM32H7 */ - -#define GPIO_AF0_LPTIM GPIO_AF0_LPTIM1 -#define GPIO_AF1_LPTIM GPIO_AF1_LPTIM1 -#define GPIO_AF2_LPTIM GPIO_AF2_LPTIM1 - -#if defined(STM32L0) || defined(STM32L4) || defined(STM32F4) || defined(STM32F2) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(STM32WB) || defined(STM32U5) -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_FAST GPIO_SPEED_FREQ_HIGH -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH -#endif /* STM32L0 || STM32L4 || STM32F4 || STM32F2 || STM32F7 || STM32G4 || STM32H7 || STM32WB || STM32U5*/ - -#if defined(STM32L1) -#define GPIO_SPEED_VERY_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_HIGH -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH -#endif /* STM32L1 */ - -#if defined(STM32F0) || defined(STM32F3) || defined(STM32F1) -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_HIGH -#endif /* STM32F0 || STM32F3 || STM32F1 */ - -#define GPIO_AF6_DFSDM GPIO_AF6_DFSDM1 -/** - * @} - */ - -/** @defgroup HAL_HRTIM_Aliased_Macros HAL HRTIM Aliased Macros maintained for legacy purpose - * @{ - */ -#define HRTIM_TIMDELAYEDPROTECTION_DISABLED HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DISABLED -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_DEEV7 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_DEEV7 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV7 -#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV7 - -#define __HAL_HRTIM_SetCounter __HAL_HRTIM_SETCOUNTER -#define __HAL_HRTIM_GetCounter __HAL_HRTIM_GETCOUNTER -#define __HAL_HRTIM_SetPeriod __HAL_HRTIM_SETPERIOD -#define __HAL_HRTIM_GetPeriod __HAL_HRTIM_GETPERIOD -#define __HAL_HRTIM_SetClockPrescaler __HAL_HRTIM_SETCLOCKPRESCALER -#define __HAL_HRTIM_GetClockPrescaler __HAL_HRTIM_GETCLOCKPRESCALER -#define __HAL_HRTIM_SetCompare __HAL_HRTIM_SETCOMPARE -#define __HAL_HRTIM_GetCompare __HAL_HRTIM_GETCOMPARE - -#if defined(STM32G4) -#define HAL_HRTIM_ExternalEventCounterConfig HAL_HRTIM_ExtEventCounterConfig -#define HAL_HRTIM_ExternalEventCounterEnable HAL_HRTIM_ExtEventCounterEnable -#define HAL_HRTIM_ExternalEventCounterDisable HAL_HRTIM_ExtEventCounterDisable -#define HAL_HRTIM_ExternalEventCounterReset HAL_HRTIM_ExtEventCounterReset -#define HRTIM_TIMEEVENT_A HRTIM_EVENTCOUNTER_A -#define HRTIM_TIMEEVENT_B HRTIM_EVENTCOUNTER_B -#define HRTIM_TIMEEVENTRESETMODE_UNCONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_UNCONDITIONAL -#define HRTIM_TIMEEVENTRESETMODE_CONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_CONDITIONAL -#endif /* STM32G4 */ - -#if defined(STM32H7) -#define HRTIM_OUTPUTSET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9 - -#define HRTIM_OUTPUTRESET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9 -#endif /* STM32H7 */ - -#if defined(STM32F3) -/** @brief Constants defining available sources associated to external events. - */ -#define HRTIM_EVENTSRC_1 (0x00000000U) -#define HRTIM_EVENTSRC_2 (HRTIM_EECR1_EE1SRC_0) -#define HRTIM_EVENTSRC_3 (HRTIM_EECR1_EE1SRC_1) -#define HRTIM_EVENTSRC_4 (HRTIM_EECR1_EE1SRC_1 | HRTIM_EECR1_EE1SRC_0) - -/** @brief Constants defining the DLL calibration periods (in micro seconds) - */ -#define HRTIM_CALIBRATIONRATE_7300 0x00000000U -#define HRTIM_CALIBRATIONRATE_910 (HRTIM_DLLCR_CALRTE_0) -#define HRTIM_CALIBRATIONRATE_114 (HRTIM_DLLCR_CALRTE_1) -#define HRTIM_CALIBRATIONRATE_14 (HRTIM_DLLCR_CALRTE_1 | HRTIM_DLLCR_CALRTE_0) - -#endif /* STM32F3 */ -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Defines HAL I2C Aliased Defines maintained for legacy purpose - * @{ - */ -#define I2C_DUALADDRESS_DISABLED I2C_DUALADDRESS_DISABLE -#define I2C_DUALADDRESS_ENABLED I2C_DUALADDRESS_ENABLE -#define I2C_GENERALCALL_DISABLED I2C_GENERALCALL_DISABLE -#define I2C_GENERALCALL_ENABLED I2C_GENERALCALL_ENABLE -#define I2C_NOSTRETCH_DISABLED I2C_NOSTRETCH_DISABLE -#define I2C_NOSTRETCH_ENABLED I2C_NOSTRETCH_ENABLE -#define I2C_ANALOGFILTER_ENABLED I2C_ANALOGFILTER_ENABLE -#define I2C_ANALOGFILTER_DISABLED I2C_ANALOGFILTER_DISABLE -#if defined(STM32F0) || defined(STM32F1) || defined(STM32F3) || defined(STM32G0) || defined(STM32L4) || defined(STM32L1) || defined(STM32F7) -#define HAL_I2C_STATE_MEM_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_MEM_BUSY_RX HAL_I2C_STATE_BUSY_RX -#define HAL_I2C_STATE_MASTER_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_MASTER_BUSY_RX HAL_I2C_STATE_BUSY_RX -#define HAL_I2C_STATE_SLAVE_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_SLAVE_BUSY_RX HAL_I2C_STATE_BUSY_RX -#endif -/** - * @} - */ - -/** @defgroup HAL_IRDA_Aliased_Defines HAL IRDA Aliased Defines maintained for legacy purpose - * @{ - */ -#define IRDA_ONE_BIT_SAMPLE_DISABLED IRDA_ONE_BIT_SAMPLE_DISABLE -#define IRDA_ONE_BIT_SAMPLE_ENABLED IRDA_ONE_BIT_SAMPLE_ENABLE - -/** - * @} - */ - -/** @defgroup HAL_IWDG_Aliased_Defines HAL IWDG Aliased Defines maintained for legacy purpose - * @{ - */ -#define KR_KEY_RELOAD IWDG_KEY_RELOAD -#define KR_KEY_ENABLE IWDG_KEY_ENABLE -#define KR_KEY_EWA IWDG_KEY_WRITE_ACCESS_ENABLE -#define KR_KEY_DWA IWDG_KEY_WRITE_ACCESS_DISABLE -/** - * @} - */ - -/** @defgroup HAL_LPTIM_Aliased_Defines HAL LPTIM Aliased Defines maintained for legacy purpose - * @{ - */ - -#define LPTIM_CLOCKSAMPLETIME_DIRECTTRANSISTION LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION -#define LPTIM_CLOCKSAMPLETIME_2TRANSISTIONS LPTIM_CLOCKSAMPLETIME_2TRANSITIONS -#define LPTIM_CLOCKSAMPLETIME_4TRANSISTIONS LPTIM_CLOCKSAMPLETIME_4TRANSITIONS -#define LPTIM_CLOCKSAMPLETIME_8TRANSISTIONS LPTIM_CLOCKSAMPLETIME_8TRANSITIONS - -#define LPTIM_CLOCKPOLARITY_RISINGEDGE LPTIM_CLOCKPOLARITY_RISING -#define LPTIM_CLOCKPOLARITY_FALLINGEDGE LPTIM_CLOCKPOLARITY_FALLING -#define LPTIM_CLOCKPOLARITY_BOTHEDGES LPTIM_CLOCKPOLARITY_RISING_FALLING - -#define LPTIM_TRIGSAMPLETIME_DIRECTTRANSISTION LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION -#define LPTIM_TRIGSAMPLETIME_2TRANSISTIONS LPTIM_TRIGSAMPLETIME_2TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_4TRANSISTIONS LPTIM_TRIGSAMPLETIME_4TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_8TRANSISTIONS LPTIM_TRIGSAMPLETIME_8TRANSITIONS - -/* The following 3 definition have also been present in a temporary version of lptim.h */ -/* They need to be renamed also to the right name, just in case */ -#define LPTIM_TRIGSAMPLETIME_2TRANSITION LPTIM_TRIGSAMPLETIME_2TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_4TRANSITION LPTIM_TRIGSAMPLETIME_4TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_8TRANSITION LPTIM_TRIGSAMPLETIME_8TRANSITIONS - -#if defined(STM32U5) -#define LPTIM_ISR_CC1 LPTIM_ISR_CC1IF -#define LPTIM_ISR_CC2 LPTIM_ISR_CC2IF -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup HAL_NAND_Aliased_Defines HAL NAND Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_NAND_Read_Page HAL_NAND_Read_Page_8b -#define HAL_NAND_Write_Page HAL_NAND_Write_Page_8b -#define HAL_NAND_Read_SpareArea HAL_NAND_Read_SpareArea_8b -#define HAL_NAND_Write_SpareArea HAL_NAND_Write_SpareArea_8b - -#define NAND_AddressTypedef NAND_AddressTypeDef - -#define __ARRAY_ADDRESS ARRAY_ADDRESS -#define __ADDR_1st_CYCLE ADDR_1ST_CYCLE -#define __ADDR_2nd_CYCLE ADDR_2ND_CYCLE -#define __ADDR_3rd_CYCLE ADDR_3RD_CYCLE -#define __ADDR_4th_CYCLE ADDR_4TH_CYCLE -/** - * @} - */ - -/** @defgroup HAL_NOR_Aliased_Defines HAL NOR Aliased Defines maintained for legacy purpose - * @{ - */ -#define NOR_StatusTypedef HAL_NOR_StatusTypeDef -#define NOR_SUCCESS HAL_NOR_STATUS_SUCCESS -#define NOR_ONGOING HAL_NOR_STATUS_ONGOING -#define NOR_ERROR HAL_NOR_STATUS_ERROR -#define NOR_TIMEOUT HAL_NOR_STATUS_TIMEOUT - -#define __NOR_WRITE NOR_WRITE -#define __NOR_ADDR_SHIFT NOR_ADDR_SHIFT -/** - * @} - */ - -/** @defgroup HAL_OPAMP_Aliased_Defines HAL OPAMP Aliased Defines maintained for legacy purpose - * @{ - */ - -#define OPAMP_NONINVERTINGINPUT_VP0 OPAMP_NONINVERTINGINPUT_IO0 -#define OPAMP_NONINVERTINGINPUT_VP1 OPAMP_NONINVERTINGINPUT_IO1 -#define OPAMP_NONINVERTINGINPUT_VP2 OPAMP_NONINVERTINGINPUT_IO2 -#define OPAMP_NONINVERTINGINPUT_VP3 OPAMP_NONINVERTINGINPUT_IO3 - -#define OPAMP_SEC_NONINVERTINGINPUT_VP0 OPAMP_SEC_NONINVERTINGINPUT_IO0 -#define OPAMP_SEC_NONINVERTINGINPUT_VP1 OPAMP_SEC_NONINVERTINGINPUT_IO1 -#define OPAMP_SEC_NONINVERTINGINPUT_VP2 OPAMP_SEC_NONINVERTINGINPUT_IO2 -#define OPAMP_SEC_NONINVERTINGINPUT_VP3 OPAMP_SEC_NONINVERTINGINPUT_IO3 - -#define OPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0 -#define OPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1 - -#define IOPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0 -#define IOPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1 - -#define OPAMP_SEC_INVERTINGINPUT_VM0 OPAMP_SEC_INVERTINGINPUT_IO0 -#define OPAMP_SEC_INVERTINGINPUT_VM1 OPAMP_SEC_INVERTINGINPUT_IO1 - -#define OPAMP_INVERTINGINPUT_VINM OPAMP_SEC_INVERTINGINPUT_IO1 - -#define OPAMP_PGACONNECT_NO OPAMP_PGA_CONNECT_INVERTINGINPUT_NO -#define OPAMP_PGACONNECT_VM0 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO0 -#define OPAMP_PGACONNECT_VM1 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO1 - -#if defined(STM32L1) || defined(STM32L4) || defined(STM32L5) || defined(STM32H7) || defined(STM32G4) -#define HAL_OPAMP_MSP_INIT_CB_ID HAL_OPAMP_MSPINIT_CB_ID -#define HAL_OPAMP_MSP_DEINIT_CB_ID HAL_OPAMP_MSPDEINIT_CB_ID -#endif - -#if defined(STM32L4) || defined(STM32L5) -#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALPOWER -#elif defined(STM32G4) -#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALSPEED -#endif - -/** - * @} - */ - -/** @defgroup HAL_I2S_Aliased_Defines HAL I2S Aliased Defines maintained for legacy purpose - * @{ - */ -#define I2S_STANDARD_PHILLIPS I2S_STANDARD_PHILIPS - -#if defined(STM32H7) -#define I2S_IT_TXE I2S_IT_TXP -#define I2S_IT_RXNE I2S_IT_RXP - -#define I2S_FLAG_TXE I2S_FLAG_TXP -#define I2S_FLAG_RXNE I2S_FLAG_RXP -#endif - -#if defined(STM32F7) -#define I2S_CLOCK_SYSCLK I2S_CLOCK_PLL -#endif -/** - * @} - */ - -/** @defgroup HAL_PCCARD_Aliased_Defines HAL PCCARD Aliased Defines maintained for legacy purpose - * @{ - */ - -/* Compact Flash-ATA registers description */ -#define CF_DATA ATA_DATA -#define CF_SECTOR_COUNT ATA_SECTOR_COUNT -#define CF_SECTOR_NUMBER ATA_SECTOR_NUMBER -#define CF_CYLINDER_LOW ATA_CYLINDER_LOW -#define CF_CYLINDER_HIGH ATA_CYLINDER_HIGH -#define CF_CARD_HEAD ATA_CARD_HEAD -#define CF_STATUS_CMD ATA_STATUS_CMD -#define CF_STATUS_CMD_ALTERNATE ATA_STATUS_CMD_ALTERNATE -#define CF_COMMON_DATA_AREA ATA_COMMON_DATA_AREA - -/* Compact Flash-ATA commands */ -#define CF_READ_SECTOR_CMD ATA_READ_SECTOR_CMD -#define CF_WRITE_SECTOR_CMD ATA_WRITE_SECTOR_CMD -#define CF_ERASE_SECTOR_CMD ATA_ERASE_SECTOR_CMD -#define CF_IDENTIFY_CMD ATA_IDENTIFY_CMD - -#define PCCARD_StatusTypedef HAL_PCCARD_StatusTypeDef -#define PCCARD_SUCCESS HAL_PCCARD_STATUS_SUCCESS -#define PCCARD_ONGOING HAL_PCCARD_STATUS_ONGOING -#define PCCARD_ERROR HAL_PCCARD_STATUS_ERROR -#define PCCARD_TIMEOUT HAL_PCCARD_STATUS_TIMEOUT -/** - * @} - */ - -/** @defgroup HAL_RTC_Aliased_Defines HAL RTC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define FORMAT_BIN RTC_FORMAT_BIN -#define FORMAT_BCD RTC_FORMAT_BCD - -#define RTC_ALARMSUBSECONDMASK_None RTC_ALARMSUBSECONDMASK_NONE -#define RTC_TAMPERERASEBACKUP_DISABLED RTC_TAMPER_ERASE_BACKUP_DISABLE -#define RTC_TAMPERMASK_FLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE -#define RTC_TAMPERMASK_FLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE - -#define RTC_MASKTAMPERFLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE -#define RTC_MASKTAMPERFLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE -#define RTC_TAMPERERASEBACKUP_ENABLED RTC_TAMPER_ERASE_BACKUP_ENABLE -#define RTC_TAMPER1_2_INTERRUPT RTC_ALL_TAMPER_INTERRUPT -#define RTC_TAMPER1_2_3_INTERRUPT RTC_ALL_TAMPER_INTERRUPT - -#define RTC_TIMESTAMPPIN_PC13 RTC_TIMESTAMPPIN_DEFAULT -#define RTC_TIMESTAMPPIN_PA0 RTC_TIMESTAMPPIN_POS1 -#define RTC_TIMESTAMPPIN_PI8 RTC_TIMESTAMPPIN_POS1 -#define RTC_TIMESTAMPPIN_PC1 RTC_TIMESTAMPPIN_POS2 - -#define RTC_OUTPUT_REMAP_PC13 RTC_OUTPUT_REMAP_NONE -#define RTC_OUTPUT_REMAP_PB14 RTC_OUTPUT_REMAP_POS1 -#define RTC_OUTPUT_REMAP_PB2 RTC_OUTPUT_REMAP_POS1 - -#define RTC_TAMPERPIN_PC13 RTC_TAMPERPIN_DEFAULT -#define RTC_TAMPERPIN_PA0 RTC_TAMPERPIN_POS1 -#define RTC_TAMPERPIN_PI8 RTC_TAMPERPIN_POS1 - -#if defined(STM32H7) -#define RTC_TAMPCR_TAMPXE RTC_TAMPER_X -#define RTC_TAMPCR_TAMPXIE RTC_TAMPER_X_INTERRUPT - -#define RTC_TAMPER1_INTERRUPT RTC_IT_TAMP1 -#define RTC_TAMPER2_INTERRUPT RTC_IT_TAMP2 -#define RTC_TAMPER3_INTERRUPT RTC_IT_TAMP3 -#define RTC_ALL_TAMPER_INTERRUPT RTC_IT_TAMPALL -#endif /* STM32H7 */ - -/** - * @} - */ - - -/** @defgroup HAL_SMARTCARD_Aliased_Defines HAL SMARTCARD Aliased Defines maintained for legacy purpose - * @{ - */ -#define SMARTCARD_NACK_ENABLED SMARTCARD_NACK_ENABLE -#define SMARTCARD_NACK_DISABLED SMARTCARD_NACK_DISABLE - -#define SMARTCARD_ONEBIT_SAMPLING_DISABLED SMARTCARD_ONE_BIT_SAMPLE_DISABLE -#define SMARTCARD_ONEBIT_SAMPLING_ENABLED SMARTCARD_ONE_BIT_SAMPLE_ENABLE -#define SMARTCARD_ONEBIT_SAMPLING_DISABLE SMARTCARD_ONE_BIT_SAMPLE_DISABLE -#define SMARTCARD_ONEBIT_SAMPLING_ENABLE SMARTCARD_ONE_BIT_SAMPLE_ENABLE - -#define SMARTCARD_TIMEOUT_DISABLED SMARTCARD_TIMEOUT_DISABLE -#define SMARTCARD_TIMEOUT_ENABLED SMARTCARD_TIMEOUT_ENABLE - -#define SMARTCARD_LASTBIT_DISABLED SMARTCARD_LASTBIT_DISABLE -#define SMARTCARD_LASTBIT_ENABLED SMARTCARD_LASTBIT_ENABLE -/** - * @} - */ - - -/** @defgroup HAL_SMBUS_Aliased_Defines HAL SMBUS Aliased Defines maintained for legacy purpose - * @{ - */ -#define SMBUS_DUALADDRESS_DISABLED SMBUS_DUALADDRESS_DISABLE -#define SMBUS_DUALADDRESS_ENABLED SMBUS_DUALADDRESS_ENABLE -#define SMBUS_GENERALCALL_DISABLED SMBUS_GENERALCALL_DISABLE -#define SMBUS_GENERALCALL_ENABLED SMBUS_GENERALCALL_ENABLE -#define SMBUS_NOSTRETCH_DISABLED SMBUS_NOSTRETCH_DISABLE -#define SMBUS_NOSTRETCH_ENABLED SMBUS_NOSTRETCH_ENABLE -#define SMBUS_ANALOGFILTER_ENABLED SMBUS_ANALOGFILTER_ENABLE -#define SMBUS_ANALOGFILTER_DISABLED SMBUS_ANALOGFILTER_DISABLE -#define SMBUS_PEC_DISABLED SMBUS_PEC_DISABLE -#define SMBUS_PEC_ENABLED SMBUS_PEC_ENABLE -#define HAL_SMBUS_STATE_SLAVE_LISTEN HAL_SMBUS_STATE_LISTEN -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Defines HAL SPI Aliased Defines maintained for legacy purpose - * @{ - */ -#define SPI_TIMODE_DISABLED SPI_TIMODE_DISABLE -#define SPI_TIMODE_ENABLED SPI_TIMODE_ENABLE - -#define SPI_CRCCALCULATION_DISABLED SPI_CRCCALCULATION_DISABLE -#define SPI_CRCCALCULATION_ENABLED SPI_CRCCALCULATION_ENABLE - -#define SPI_NSS_PULSE_DISABLED SPI_NSS_PULSE_DISABLE -#define SPI_NSS_PULSE_ENABLED SPI_NSS_PULSE_ENABLE - -#if defined(STM32H7) - -#define SPI_FLAG_TXE SPI_FLAG_TXP -#define SPI_FLAG_RXNE SPI_FLAG_RXP - -#define SPI_IT_TXE SPI_IT_TXP -#define SPI_IT_RXNE SPI_IT_RXP - -#define SPI_FRLVL_EMPTY SPI_RX_FIFO_0PACKET -#define SPI_FRLVL_QUARTER_FULL SPI_RX_FIFO_1PACKET -#define SPI_FRLVL_HALF_FULL SPI_RX_FIFO_2PACKET -#define SPI_FRLVL_FULL SPI_RX_FIFO_3PACKET - -#endif /* STM32H7 */ - -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Defines HAL TIM Aliased Defines maintained for legacy purpose - * @{ - */ -#define CCER_CCxE_MASK TIM_CCER_CCxE_MASK -#define CCER_CCxNE_MASK TIM_CCER_CCxNE_MASK - -#define TIM_DMABase_CR1 TIM_DMABASE_CR1 -#define TIM_DMABase_CR2 TIM_DMABASE_CR2 -#define TIM_DMABase_SMCR TIM_DMABASE_SMCR -#define TIM_DMABase_DIER TIM_DMABASE_DIER -#define TIM_DMABase_SR TIM_DMABASE_SR -#define TIM_DMABase_EGR TIM_DMABASE_EGR -#define TIM_DMABase_CCMR1 TIM_DMABASE_CCMR1 -#define TIM_DMABase_CCMR2 TIM_DMABASE_CCMR2 -#define TIM_DMABase_CCER TIM_DMABASE_CCER -#define TIM_DMABase_CNT TIM_DMABASE_CNT -#define TIM_DMABase_PSC TIM_DMABASE_PSC -#define TIM_DMABase_ARR TIM_DMABASE_ARR -#define TIM_DMABase_RCR TIM_DMABASE_RCR -#define TIM_DMABase_CCR1 TIM_DMABASE_CCR1 -#define TIM_DMABase_CCR2 TIM_DMABASE_CCR2 -#define TIM_DMABase_CCR3 TIM_DMABASE_CCR3 -#define TIM_DMABase_CCR4 TIM_DMABASE_CCR4 -#define TIM_DMABase_BDTR TIM_DMABASE_BDTR -#define TIM_DMABase_DCR TIM_DMABASE_DCR -#define TIM_DMABase_DMAR TIM_DMABASE_DMAR -#define TIM_DMABase_OR1 TIM_DMABASE_OR1 -#define TIM_DMABase_CCMR3 TIM_DMABASE_CCMR3 -#define TIM_DMABase_CCR5 TIM_DMABASE_CCR5 -#define TIM_DMABase_CCR6 TIM_DMABASE_CCR6 -#define TIM_DMABase_OR2 TIM_DMABASE_OR2 -#define TIM_DMABase_OR3 TIM_DMABASE_OR3 -#define TIM_DMABase_OR TIM_DMABASE_OR - -#define TIM_EventSource_Update TIM_EVENTSOURCE_UPDATE -#define TIM_EventSource_CC1 TIM_EVENTSOURCE_CC1 -#define TIM_EventSource_CC2 TIM_EVENTSOURCE_CC2 -#define TIM_EventSource_CC3 TIM_EVENTSOURCE_CC3 -#define TIM_EventSource_CC4 TIM_EVENTSOURCE_CC4 -#define TIM_EventSource_COM TIM_EVENTSOURCE_COM -#define TIM_EventSource_Trigger TIM_EVENTSOURCE_TRIGGER -#define TIM_EventSource_Break TIM_EVENTSOURCE_BREAK -#define TIM_EventSource_Break2 TIM_EVENTSOURCE_BREAK2 - -#define TIM_DMABurstLength_1Transfer TIM_DMABURSTLENGTH_1TRANSFER -#define TIM_DMABurstLength_2Transfers TIM_DMABURSTLENGTH_2TRANSFERS -#define TIM_DMABurstLength_3Transfers TIM_DMABURSTLENGTH_3TRANSFERS -#define TIM_DMABurstLength_4Transfers TIM_DMABURSTLENGTH_4TRANSFERS -#define TIM_DMABurstLength_5Transfers TIM_DMABURSTLENGTH_5TRANSFERS -#define TIM_DMABurstLength_6Transfers TIM_DMABURSTLENGTH_6TRANSFERS -#define TIM_DMABurstLength_7Transfers TIM_DMABURSTLENGTH_7TRANSFERS -#define TIM_DMABurstLength_8Transfers TIM_DMABURSTLENGTH_8TRANSFERS -#define TIM_DMABurstLength_9Transfers TIM_DMABURSTLENGTH_9TRANSFERS -#define TIM_DMABurstLength_10Transfers TIM_DMABURSTLENGTH_10TRANSFERS -#define TIM_DMABurstLength_11Transfers TIM_DMABURSTLENGTH_11TRANSFERS -#define TIM_DMABurstLength_12Transfers TIM_DMABURSTLENGTH_12TRANSFERS -#define TIM_DMABurstLength_13Transfers TIM_DMABURSTLENGTH_13TRANSFERS -#define TIM_DMABurstLength_14Transfers TIM_DMABURSTLENGTH_14TRANSFERS -#define TIM_DMABurstLength_15Transfers TIM_DMABURSTLENGTH_15TRANSFERS -#define TIM_DMABurstLength_16Transfers TIM_DMABURSTLENGTH_16TRANSFERS -#define TIM_DMABurstLength_17Transfers TIM_DMABURSTLENGTH_17TRANSFERS -#define TIM_DMABurstLength_18Transfers TIM_DMABURSTLENGTH_18TRANSFERS - -#if defined(STM32L0) -#define TIM22_TI1_GPIO1 TIM22_TI1_GPIO -#define TIM22_TI1_GPIO2 TIM22_TI1_GPIO -#endif - -#if defined(STM32F3) -#define IS_TIM_HALL_INTERFACE_INSTANCE IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE -#endif - -#if defined(STM32H7) -#define TIM_TIM1_ETR_COMP1_OUT TIM_TIM1_ETR_COMP1 -#define TIM_TIM1_ETR_COMP2_OUT TIM_TIM1_ETR_COMP2 -#define TIM_TIM8_ETR_COMP1_OUT TIM_TIM8_ETR_COMP1 -#define TIM_TIM8_ETR_COMP2_OUT TIM_TIM8_ETR_COMP2 -#define TIM_TIM2_ETR_COMP1_OUT TIM_TIM2_ETR_COMP1 -#define TIM_TIM2_ETR_COMP2_OUT TIM_TIM2_ETR_COMP2 -#define TIM_TIM3_ETR_COMP1_OUT TIM_TIM3_ETR_COMP1 -#define TIM_TIM1_TI1_COMP1_OUT TIM_TIM1_TI1_COMP1 -#define TIM_TIM8_TI1_COMP2_OUT TIM_TIM8_TI1_COMP2 -#define TIM_TIM2_TI4_COMP1_OUT TIM_TIM2_TI4_COMP1 -#define TIM_TIM2_TI4_COMP2_OUT TIM_TIM2_TI4_COMP2 -#define TIM_TIM2_TI4_COMP1COMP2_OUT TIM_TIM2_TI4_COMP1_COMP2 -#define TIM_TIM3_TI1_COMP1_OUT TIM_TIM3_TI1_COMP1 -#define TIM_TIM3_TI1_COMP2_OUT TIM_TIM3_TI1_COMP2 -#define TIM_TIM3_TI1_COMP1COMP2_OUT TIM_TIM3_TI1_COMP1_COMP2 -#endif - -/** - * @} - */ - -/** @defgroup HAL_TSC_Aliased_Defines HAL TSC Aliased Defines maintained for legacy purpose - * @{ - */ -#define TSC_SYNC_POL_FALL TSC_SYNC_POLARITY_FALLING -#define TSC_SYNC_POL_RISE_HIGH TSC_SYNC_POLARITY_RISING -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Defines HAL UART Aliased Defines maintained for legacy purpose - * @{ - */ -#define UART_ONEBIT_SAMPLING_DISABLED UART_ONE_BIT_SAMPLE_DISABLE -#define UART_ONEBIT_SAMPLING_ENABLED UART_ONE_BIT_SAMPLE_ENABLE -#define UART_ONE_BIT_SAMPLE_DISABLED UART_ONE_BIT_SAMPLE_DISABLE -#define UART_ONE_BIT_SAMPLE_ENABLED UART_ONE_BIT_SAMPLE_ENABLE - -#define __HAL_UART_ONEBIT_ENABLE __HAL_UART_ONE_BIT_SAMPLE_ENABLE -#define __HAL_UART_ONEBIT_DISABLE __HAL_UART_ONE_BIT_SAMPLE_DISABLE - -#define __DIV_SAMPLING16 UART_DIV_SAMPLING16 -#define __DIVMANT_SAMPLING16 UART_DIVMANT_SAMPLING16 -#define __DIVFRAQ_SAMPLING16 UART_DIVFRAQ_SAMPLING16 -#define __UART_BRR_SAMPLING16 UART_BRR_SAMPLING16 - -#define __DIV_SAMPLING8 UART_DIV_SAMPLING8 -#define __DIVMANT_SAMPLING8 UART_DIVMANT_SAMPLING8 -#define __DIVFRAQ_SAMPLING8 UART_DIVFRAQ_SAMPLING8 -#define __UART_BRR_SAMPLING8 UART_BRR_SAMPLING8 - -#define __DIV_LPUART UART_DIV_LPUART - -#define UART_WAKEUPMETHODE_IDLELINE UART_WAKEUPMETHOD_IDLELINE -#define UART_WAKEUPMETHODE_ADDRESSMARK UART_WAKEUPMETHOD_ADDRESSMARK - -/** - * @} - */ - - -/** @defgroup HAL_USART_Aliased_Defines HAL USART Aliased Defines maintained for legacy purpose - * @{ - */ - -#define USART_CLOCK_DISABLED USART_CLOCK_DISABLE -#define USART_CLOCK_ENABLED USART_CLOCK_ENABLE - -#define USARTNACK_ENABLED USART_NACK_ENABLE -#define USARTNACK_DISABLED USART_NACK_DISABLE -/** - * @} - */ - -/** @defgroup HAL_WWDG_Aliased_Defines HAL WWDG Aliased Defines maintained for legacy purpose - * @{ - */ -#define CFR_BASE WWDG_CFR_BASE - -/** - * @} - */ - -/** @defgroup HAL_CAN_Aliased_Defines HAL CAN Aliased Defines maintained for legacy purpose - * @{ - */ -#define CAN_FilterFIFO0 CAN_FILTER_FIFO0 -#define CAN_FilterFIFO1 CAN_FILTER_FIFO1 -#define CAN_IT_RQCP0 CAN_IT_TME -#define CAN_IT_RQCP1 CAN_IT_TME -#define CAN_IT_RQCP2 CAN_IT_TME -#define INAK_TIMEOUT CAN_TIMEOUT_VALUE -#define SLAK_TIMEOUT CAN_TIMEOUT_VALUE -#define CAN_TXSTATUS_FAILED ((uint8_t)0x00U) -#define CAN_TXSTATUS_OK ((uint8_t)0x01U) -#define CAN_TXSTATUS_PENDING ((uint8_t)0x02U) - -/** - * @} - */ - -/** @defgroup HAL_ETH_Aliased_Defines HAL ETH Aliased Defines maintained for legacy purpose - * @{ - */ - -#define VLAN_TAG ETH_VLAN_TAG -#define MIN_ETH_PAYLOAD ETH_MIN_ETH_PAYLOAD -#define MAX_ETH_PAYLOAD ETH_MAX_ETH_PAYLOAD -#define JUMBO_FRAME_PAYLOAD ETH_JUMBO_FRAME_PAYLOAD -#define MACMIIAR_CR_MASK ETH_MACMIIAR_CR_MASK -#define MACCR_CLEAR_MASK ETH_MACCR_CLEAR_MASK -#define MACFCR_CLEAR_MASK ETH_MACFCR_CLEAR_MASK -#define DMAOMR_CLEAR_MASK ETH_DMAOMR_CLEAR_MASK - -#define ETH_MMCCR 0x00000100U -#define ETH_MMCRIR 0x00000104U -#define ETH_MMCTIR 0x00000108U -#define ETH_MMCRIMR 0x0000010CU -#define ETH_MMCTIMR 0x00000110U -#define ETH_MMCTGFSCCR 0x0000014CU -#define ETH_MMCTGFMSCCR 0x00000150U -#define ETH_MMCTGFCR 0x00000168U -#define ETH_MMCRFCECR 0x00000194U -#define ETH_MMCRFAECR 0x00000198U -#define ETH_MMCRGUFCR 0x000001C4U - -#define ETH_MAC_TXFIFO_FULL 0x02000000U /* Tx FIFO full */ -#define ETH_MAC_TXFIFONOT_EMPTY 0x01000000U /* Tx FIFO not empty */ -#define ETH_MAC_TXFIFO_WRITE_ACTIVE 0x00400000U /* Tx FIFO write active */ -#define ETH_MAC_TXFIFO_IDLE 0x00000000U /* Tx FIFO read status: Idle */ -#define ETH_MAC_TXFIFO_READ 0x00100000U /* Tx FIFO read status: Read (transferring data to the MAC transmitter) */ -#define ETH_MAC_TXFIFO_WAITING 0x00200000U /* Tx FIFO read status: Waiting for TxStatus from MAC transmitter */ -#define ETH_MAC_TXFIFO_WRITING 0x00300000U /* Tx FIFO read status: Writing the received TxStatus or flushing the TxFIFO */ -#define ETH_MAC_TRANSMISSION_PAUSE 0x00080000U /* MAC transmitter in pause */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_IDLE 0x00000000U /* MAC transmit frame controller: Idle */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_WAITING 0x00020000U /* MAC transmit frame controller: Waiting for Status of previous frame or IFG/backoff period to be over */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_GENRATING_PCF 0x00040000U /* MAC transmit frame controller: Generating and transmitting a Pause control frame (in full duplex mode) */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_TRANSFERRING 0x00060000U /* MAC transmit frame controller: Transferring input frame for transmission */ -#define ETH_MAC_MII_TRANSMIT_ACTIVE 0x00010000U /* MAC MII transmit engine active */ -#define ETH_MAC_RXFIFO_EMPTY 0x00000000U /* Rx FIFO fill level: empty */ -#define ETH_MAC_RXFIFO_BELOW_THRESHOLD 0x00000100U /* Rx FIFO fill level: fill-level below flow-control de-activate threshold */ -#define ETH_MAC_RXFIFO_ABOVE_THRESHOLD 0x00000200U /* Rx FIFO fill level: fill-level above flow-control activate threshold */ -#define ETH_MAC_RXFIFO_FULL 0x00000300U /* Rx FIFO fill level: full */ -#if defined(STM32F1) -#else -#define ETH_MAC_READCONTROLLER_IDLE 0x00000000U /* Rx FIFO read controller IDLE state */ -#define ETH_MAC_READCONTROLLER_READING_DATA 0x00000020U /* Rx FIFO read controller Reading frame data */ -#define ETH_MAC_READCONTROLLER_READING_STATUS 0x00000040U /* Rx FIFO read controller Reading frame status (or time-stamp) */ -#endif -#define ETH_MAC_READCONTROLLER_FLUSHING 0x00000060U /* Rx FIFO read controller Flushing the frame data and status */ -#define ETH_MAC_RXFIFO_WRITE_ACTIVE 0x00000010U /* Rx FIFO write controller active */ -#define ETH_MAC_SMALL_FIFO_NOTACTIVE 0x00000000U /* MAC small FIFO read / write controllers not active */ -#define ETH_MAC_SMALL_FIFO_READ_ACTIVE 0x00000002U /* MAC small FIFO read controller active */ -#define ETH_MAC_SMALL_FIFO_WRITE_ACTIVE 0x00000004U /* MAC small FIFO write controller active */ -#define ETH_MAC_SMALL_FIFO_RW_ACTIVE 0x00000006U /* MAC small FIFO read / write controllers active */ -#define ETH_MAC_MII_RECEIVE_PROTOCOL_ACTIVE 0x00000001U /* MAC MII receive protocol engine active */ - -/** - * @} - */ - -/** @defgroup HAL_DCMI_Aliased_Defines HAL DCMI Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_DCMI_ERROR_OVF HAL_DCMI_ERROR_OVR -#define DCMI_IT_OVF DCMI_IT_OVR -#define DCMI_FLAG_OVFRI DCMI_FLAG_OVRRI -#define DCMI_FLAG_OVFMI DCMI_FLAG_OVRMI - -#define HAL_DCMI_ConfigCROP HAL_DCMI_ConfigCrop -#define HAL_DCMI_EnableCROP HAL_DCMI_EnableCrop -#define HAL_DCMI_DisableCROP HAL_DCMI_DisableCrop - -/** - * @} - */ - -#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \ - || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \ - || defined(STM32H7) -/** @defgroup HAL_DMA2D_Aliased_Defines HAL DMA2D Aliased Defines maintained for legacy purpose - * @{ - */ -#define DMA2D_ARGB8888 DMA2D_OUTPUT_ARGB8888 -#define DMA2D_RGB888 DMA2D_OUTPUT_RGB888 -#define DMA2D_RGB565 DMA2D_OUTPUT_RGB565 -#define DMA2D_ARGB1555 DMA2D_OUTPUT_ARGB1555 -#define DMA2D_ARGB4444 DMA2D_OUTPUT_ARGB4444 - -#define CM_ARGB8888 DMA2D_INPUT_ARGB8888 -#define CM_RGB888 DMA2D_INPUT_RGB888 -#define CM_RGB565 DMA2D_INPUT_RGB565 -#define CM_ARGB1555 DMA2D_INPUT_ARGB1555 -#define CM_ARGB4444 DMA2D_INPUT_ARGB4444 -#define CM_L8 DMA2D_INPUT_L8 -#define CM_AL44 DMA2D_INPUT_AL44 -#define CM_AL88 DMA2D_INPUT_AL88 -#define CM_L4 DMA2D_INPUT_L4 -#define CM_A8 DMA2D_INPUT_A8 -#define CM_A4 DMA2D_INPUT_A4 -/** - * @} - */ -#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 */ - -#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \ - || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \ - || defined(STM32H7) || defined(STM32U5) -/** @defgroup DMA2D_Aliases DMA2D API Aliases - * @{ - */ -#define HAL_DMA2D_DisableCLUT HAL_DMA2D_CLUTLoading_Abort /*!< Aliased to HAL_DMA2D_CLUTLoading_Abort - for compatibility with legacy code */ -/** - * @} - */ - -#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 || STM32U5 */ - -/** @defgroup HAL_PPP_Aliased_Defines HAL PPP Aliased Defines maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup HAL_CRYP_Aliased_Functions HAL CRYP Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_CRYP_ComputationCpltCallback HAL_CRYPEx_ComputationCpltCallback -/** - * @} - */ - -/** @defgroup HAL_DCACHE_Aliased_Functions HAL DCACHE Aliased Functions maintained for legacy purpose - * @{ - */ - -#if defined(STM32U5) -#define HAL_DCACHE_CleanInvalidateByAddr HAL_DCACHE_CleanInvalidByAddr -#define HAL_DCACHE_CleanInvalidateByAddr_IT HAL_DCACHE_CleanInvalidByAddr_IT -#endif /* STM32U5 */ - -/** - * @} - */ - -#if !defined(STM32F2) -/** @defgroup HASH_alias HASH API alias - * @{ - */ -#define HAL_HASHEx_IRQHandler HAL_HASH_IRQHandler /*!< Redirection for compatibility with legacy code */ -/** - * - * @} - */ -#endif /* STM32F2 */ -/** @defgroup HAL_HASH_Aliased_Functions HAL HASH Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_HASH_STATETypeDef HAL_HASH_StateTypeDef -#define HAL_HASHPhaseTypeDef HAL_HASH_PhaseTypeDef -#define HAL_HMAC_MD5_Finish HAL_HASH_MD5_Finish -#define HAL_HMAC_SHA1_Finish HAL_HASH_SHA1_Finish -#define HAL_HMAC_SHA224_Finish HAL_HASH_SHA224_Finish -#define HAL_HMAC_SHA256_Finish HAL_HASH_SHA256_Finish - -/*HASH Algorithm Selection*/ - -#define HASH_AlgoSelection_SHA1 HASH_ALGOSELECTION_SHA1 -#define HASH_AlgoSelection_SHA224 HASH_ALGOSELECTION_SHA224 -#define HASH_AlgoSelection_SHA256 HASH_ALGOSELECTION_SHA256 -#define HASH_AlgoSelection_MD5 HASH_ALGOSELECTION_MD5 - -#define HASH_AlgoMode_HASH HASH_ALGOMODE_HASH -#define HASH_AlgoMode_HMAC HASH_ALGOMODE_HMAC - -#define HASH_HMACKeyType_ShortKey HASH_HMAC_KEYTYPE_SHORTKEY -#define HASH_HMACKeyType_LongKey HASH_HMAC_KEYTYPE_LONGKEY - -#if defined(STM32L4) || defined(STM32L5) || defined(STM32F2) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) - -#define HAL_HASH_MD5_Accumulate HAL_HASH_MD5_Accmlt -#define HAL_HASH_MD5_Accumulate_End HAL_HASH_MD5_Accmlt_End -#define HAL_HASH_MD5_Accumulate_IT HAL_HASH_MD5_Accmlt_IT -#define HAL_HASH_MD5_Accumulate_End_IT HAL_HASH_MD5_Accmlt_End_IT - -#define HAL_HASH_SHA1_Accumulate HAL_HASH_SHA1_Accmlt -#define HAL_HASH_SHA1_Accumulate_End HAL_HASH_SHA1_Accmlt_End -#define HAL_HASH_SHA1_Accumulate_IT HAL_HASH_SHA1_Accmlt_IT -#define HAL_HASH_SHA1_Accumulate_End_IT HAL_HASH_SHA1_Accmlt_End_IT - -#define HAL_HASHEx_SHA224_Accumulate HAL_HASHEx_SHA224_Accmlt -#define HAL_HASHEx_SHA224_Accumulate_End HAL_HASHEx_SHA224_Accmlt_End -#define HAL_HASHEx_SHA224_Accumulate_IT HAL_HASHEx_SHA224_Accmlt_IT -#define HAL_HASHEx_SHA224_Accumulate_End_IT HAL_HASHEx_SHA224_Accmlt_End_IT - -#define HAL_HASHEx_SHA256_Accumulate HAL_HASHEx_SHA256_Accmlt -#define HAL_HASHEx_SHA256_Accumulate_End HAL_HASHEx_SHA256_Accmlt_End -#define HAL_HASHEx_SHA256_Accumulate_IT HAL_HASHEx_SHA256_Accmlt_IT -#define HAL_HASHEx_SHA256_Accumulate_End_IT HAL_HASHEx_SHA256_Accmlt_End_IT - -#endif /* STM32L4 || STM32L5 || STM32F2 || STM32F4 || STM32F7 || STM32H7 */ -/** - * @} - */ - -/** @defgroup HAL_Aliased_Functions HAL Generic Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_EnableDBGSleepMode HAL_DBGMCU_EnableDBGSleepMode -#define HAL_DisableDBGSleepMode HAL_DBGMCU_DisableDBGSleepMode -#define HAL_EnableDBGStopMode HAL_DBGMCU_EnableDBGStopMode -#define HAL_DisableDBGStopMode HAL_DBGMCU_DisableDBGStopMode -#define HAL_EnableDBGStandbyMode HAL_DBGMCU_EnableDBGStandbyMode -#define HAL_DisableDBGStandbyMode HAL_DBGMCU_DisableDBGStandbyMode -#define HAL_DBG_LowPowerConfig(Periph, cmd) (((cmd\ - )==ENABLE)? HAL_DBGMCU_DBG_EnableLowPowerConfig(Periph) : HAL_DBGMCU_DBG_DisableLowPowerConfig(Periph)) -#define HAL_VREFINT_OutputSelect HAL_SYSCFG_VREFINT_OutputSelect -#define HAL_Lock_Cmd(cmd) (((cmd)==ENABLE) ? HAL_SYSCFG_Enable_Lock_VREFINT() : HAL_SYSCFG_Disable_Lock_VREFINT()) -#if defined(STM32L0) -#else -#define HAL_VREFINT_Cmd(cmd) (((cmd)==ENABLE)? HAL_SYSCFG_EnableVREFINT() : HAL_SYSCFG_DisableVREFINT()) -#endif -#define HAL_ADC_EnableBuffer_Cmd(cmd) (((cmd)==ENABLE) ? HAL_ADCEx_EnableVREFINT() : HAL_ADCEx_DisableVREFINT()) -#define HAL_ADC_EnableBufferSensor_Cmd(cmd) (((cmd\ - )==ENABLE) ? HAL_ADCEx_EnableVREFINTTempSensor() : HAL_ADCEx_DisableVREFINTTempSensor()) -#if defined(STM32H7A3xx) || defined(STM32H7B3xx) || defined(STM32H7B0xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xxQ) || defined(STM32H7B0xxQ) -#define HAL_EnableSRDomainDBGStopMode HAL_EnableDomain3DBGStopMode -#define HAL_DisableSRDomainDBGStopMode HAL_DisableDomain3DBGStopMode -#define HAL_EnableSRDomainDBGStandbyMode HAL_EnableDomain3DBGStandbyMode -#define HAL_DisableSRDomainDBGStandbyMode HAL_DisableDomain3DBGStandbyMode -#endif /* STM32H7A3xx || STM32H7B3xx || STM32H7B0xx || STM32H7A3xxQ || STM32H7B3xxQ || STM32H7B0xxQ */ - -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Functions HAL FLASH Aliased Functions maintained for legacy purpose - * @{ - */ -#define FLASH_HalfPageProgram HAL_FLASHEx_HalfPageProgram -#define FLASH_EnableRunPowerDown HAL_FLASHEx_EnableRunPowerDown -#define FLASH_DisableRunPowerDown HAL_FLASHEx_DisableRunPowerDown -#define HAL_DATA_EEPROMEx_Unlock HAL_FLASHEx_DATAEEPROM_Unlock -#define HAL_DATA_EEPROMEx_Lock HAL_FLASHEx_DATAEEPROM_Lock -#define HAL_DATA_EEPROMEx_Erase HAL_FLASHEx_DATAEEPROM_Erase -#define HAL_DATA_EEPROMEx_Program HAL_FLASHEx_DATAEEPROM_Program - -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Functions HAL I2C Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_I2CEx_AnalogFilter_Config HAL_I2CEx_ConfigAnalogFilter -#define HAL_I2CEx_DigitalFilter_Config HAL_I2CEx_ConfigDigitalFilter -#define HAL_FMPI2CEx_AnalogFilter_Config HAL_FMPI2CEx_ConfigAnalogFilter -#define HAL_FMPI2CEx_DigitalFilter_Config HAL_FMPI2CEx_ConfigDigitalFilter - -#define HAL_I2CFastModePlusConfig(SYSCFG_I2CFastModePlus, cmd) (((cmd\ - )==ENABLE)? HAL_I2CEx_EnableFastModePlus(SYSCFG_I2CFastModePlus): HAL_I2CEx_DisableFastModePlus(SYSCFG_I2CFastModePlus)) - -#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4) || defined(STM32L1) -#define HAL_I2C_Master_Sequential_Transmit_IT HAL_I2C_Master_Seq_Transmit_IT -#define HAL_I2C_Master_Sequential_Receive_IT HAL_I2C_Master_Seq_Receive_IT -#define HAL_I2C_Slave_Sequential_Transmit_IT HAL_I2C_Slave_Seq_Transmit_IT -#define HAL_I2C_Slave_Sequential_Receive_IT HAL_I2C_Slave_Seq_Receive_IT -#endif /* STM32H7 || STM32WB || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */ -#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4)|| defined(STM32L1) -#define HAL_I2C_Master_Sequential_Transmit_DMA HAL_I2C_Master_Seq_Transmit_DMA -#define HAL_I2C_Master_Sequential_Receive_DMA HAL_I2C_Master_Seq_Receive_DMA -#define HAL_I2C_Slave_Sequential_Transmit_DMA HAL_I2C_Slave_Seq_Transmit_DMA -#define HAL_I2C_Slave_Sequential_Receive_DMA HAL_I2C_Slave_Seq_Receive_DMA -#endif /* STM32H7 || STM32WB || STM32G0 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */ - -#if defined(STM32F4) -#define HAL_FMPI2C_Master_Sequential_Transmit_IT HAL_FMPI2C_Master_Seq_Transmit_IT -#define HAL_FMPI2C_Master_Sequential_Receive_IT HAL_FMPI2C_Master_Seq_Receive_IT -#define HAL_FMPI2C_Slave_Sequential_Transmit_IT HAL_FMPI2C_Slave_Seq_Transmit_IT -#define HAL_FMPI2C_Slave_Sequential_Receive_IT HAL_FMPI2C_Slave_Seq_Receive_IT -#define HAL_FMPI2C_Master_Sequential_Transmit_DMA HAL_FMPI2C_Master_Seq_Transmit_DMA -#define HAL_FMPI2C_Master_Sequential_Receive_DMA HAL_FMPI2C_Master_Seq_Receive_DMA -#define HAL_FMPI2C_Slave_Sequential_Transmit_DMA HAL_FMPI2C_Slave_Seq_Transmit_DMA -#define HAL_FMPI2C_Slave_Sequential_Receive_DMA HAL_FMPI2C_Slave_Seq_Receive_DMA -#endif /* STM32F4 */ -/** - * @} - */ - -/** @defgroup HAL_PWR_Aliased HAL PWR Aliased maintained for legacy purpose - * @{ - */ - -#if defined(STM32G0) -#define HAL_PWR_ConfigPVD HAL_PWREx_ConfigPVD -#define HAL_PWR_EnablePVD HAL_PWREx_EnablePVD -#define HAL_PWR_DisablePVD HAL_PWREx_DisablePVD -#define HAL_PWR_PVD_IRQHandler HAL_PWREx_PVD_IRQHandler -#endif -#define HAL_PWR_PVDConfig HAL_PWR_ConfigPVD -#define HAL_PWR_DisableBkUpReg HAL_PWREx_DisableBkUpReg -#define HAL_PWR_DisableFlashPowerDown HAL_PWREx_DisableFlashPowerDown -#define HAL_PWR_DisableVddio2Monitor HAL_PWREx_DisableVddio2Monitor -#define HAL_PWR_EnableBkUpReg HAL_PWREx_EnableBkUpReg -#define HAL_PWR_EnableFlashPowerDown HAL_PWREx_EnableFlashPowerDown -#define HAL_PWR_EnableVddio2Monitor HAL_PWREx_EnableVddio2Monitor -#define HAL_PWR_PVD_PVM_IRQHandler HAL_PWREx_PVD_PVM_IRQHandler -#define HAL_PWR_PVDLevelConfig HAL_PWR_ConfigPVD -#define HAL_PWR_Vddio2Monitor_IRQHandler HAL_PWREx_Vddio2Monitor_IRQHandler -#define HAL_PWR_Vddio2MonitorCallback HAL_PWREx_Vddio2MonitorCallback -#define HAL_PWREx_ActivateOverDrive HAL_PWREx_EnableOverDrive -#define HAL_PWREx_DeactivateOverDrive HAL_PWREx_DisableOverDrive -#define HAL_PWREx_DisableSDADCAnalog HAL_PWREx_DisableSDADC -#define HAL_PWREx_EnableSDADCAnalog HAL_PWREx_EnableSDADC -#define HAL_PWREx_PVMConfig HAL_PWREx_ConfigPVM - -#define PWR_MODE_NORMAL PWR_PVD_MODE_NORMAL -#define PWR_MODE_IT_RISING PWR_PVD_MODE_IT_RISING -#define PWR_MODE_IT_FALLING PWR_PVD_MODE_IT_FALLING -#define PWR_MODE_IT_RISING_FALLING PWR_PVD_MODE_IT_RISING_FALLING -#define PWR_MODE_EVENT_RISING PWR_PVD_MODE_EVENT_RISING -#define PWR_MODE_EVENT_FALLING PWR_PVD_MODE_EVENT_FALLING -#define PWR_MODE_EVENT_RISING_FALLING PWR_PVD_MODE_EVENT_RISING_FALLING - -#define CR_OFFSET_BB PWR_CR_OFFSET_BB -#define CSR_OFFSET_BB PWR_CSR_OFFSET_BB -#define PMODE_BIT_NUMBER VOS_BIT_NUMBER -#define CR_PMODE_BB CR_VOS_BB - -#define DBP_BitNumber DBP_BIT_NUMBER -#define PVDE_BitNumber PVDE_BIT_NUMBER -#define PMODE_BitNumber PMODE_BIT_NUMBER -#define EWUP_BitNumber EWUP_BIT_NUMBER -#define FPDS_BitNumber FPDS_BIT_NUMBER -#define ODEN_BitNumber ODEN_BIT_NUMBER -#define ODSWEN_BitNumber ODSWEN_BIT_NUMBER -#define MRLVDS_BitNumber MRLVDS_BIT_NUMBER -#define LPLVDS_BitNumber LPLVDS_BIT_NUMBER -#define BRE_BitNumber BRE_BIT_NUMBER - -#define PWR_MODE_EVT PWR_PVD_MODE_NORMAL - -/** - * @} - */ - -/** @defgroup HAL_SMBUS_Aliased_Functions HAL SMBUS Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_SMBUS_Slave_Listen_IT HAL_SMBUS_EnableListen_IT -#define HAL_SMBUS_SlaveAddrCallback HAL_SMBUS_AddrCallback -#define HAL_SMBUS_SlaveListenCpltCallback HAL_SMBUS_ListenCpltCallback -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Functions HAL SPI Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_SPI_FlushRxFifo HAL_SPIEx_FlushRxFifo -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Functions HAL TIM Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_TIM_DMADelayPulseCplt TIM_DMADelayPulseCplt -#define HAL_TIM_DMAError TIM_DMAError -#define HAL_TIM_DMACaptureCplt TIM_DMACaptureCplt -#define HAL_TIMEx_DMACommutationCplt TIMEx_DMACommutationCplt -#if defined(STM32H7) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) -#define HAL_TIM_SlaveConfigSynchronization HAL_TIM_SlaveConfigSynchro -#define HAL_TIM_SlaveConfigSynchronization_IT HAL_TIM_SlaveConfigSynchro_IT -#define HAL_TIMEx_CommutationCallback HAL_TIMEx_CommutCallback -#define HAL_TIMEx_ConfigCommutationEvent HAL_TIMEx_ConfigCommutEvent -#define HAL_TIMEx_ConfigCommutationEvent_IT HAL_TIMEx_ConfigCommutEvent_IT -#define HAL_TIMEx_ConfigCommutationEvent_DMA HAL_TIMEx_ConfigCommutEvent_DMA -#endif /* STM32H7 || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 */ -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Functions HAL UART Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_UART_WakeupCallback HAL_UARTEx_WakeupCallback -/** - * @} - */ - -/** @defgroup HAL_LTDC_Aliased_Functions HAL LTDC Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_LTDC_LineEvenCallback HAL_LTDC_LineEventCallback -#define HAL_LTDC_Relaod HAL_LTDC_Reload -#define HAL_LTDC_StructInitFromVideoConfig HAL_LTDCEx_StructInitFromVideoConfig -#define HAL_LTDC_StructInitFromAdaptedCommandConfig HAL_LTDCEx_StructInitFromAdaptedCommandConfig -/** - * @} - */ - - -/** @defgroup HAL_PPP_Aliased_Functions HAL PPP Aliased Functions maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -/* Exported macros ------------------------------------------------------------*/ - -/** @defgroup HAL_AES_Aliased_Macros HAL CRYP Aliased Macros maintained for legacy purpose - * @{ - */ -#define AES_IT_CC CRYP_IT_CC -#define AES_IT_ERR CRYP_IT_ERR -#define AES_FLAG_CCF CRYP_FLAG_CCF -/** - * @} - */ - -/** @defgroup HAL_Aliased_Macros HAL Generic Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_GET_BOOT_MODE __HAL_SYSCFG_GET_BOOT_MODE -#define __HAL_REMAPMEMORY_FLASH __HAL_SYSCFG_REMAPMEMORY_FLASH -#define __HAL_REMAPMEMORY_SYSTEMFLASH __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH -#define __HAL_REMAPMEMORY_SRAM __HAL_SYSCFG_REMAPMEMORY_SRAM -#define __HAL_REMAPMEMORY_FMC __HAL_SYSCFG_REMAPMEMORY_FMC -#define __HAL_REMAPMEMORY_FMC_SDRAM __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM -#define __HAL_REMAPMEMORY_FSMC __HAL_SYSCFG_REMAPMEMORY_FSMC -#define __HAL_REMAPMEMORY_QUADSPI __HAL_SYSCFG_REMAPMEMORY_QUADSPI -#define __HAL_FMC_BANK __HAL_SYSCFG_FMC_BANK -#define __HAL_GET_FLAG __HAL_SYSCFG_GET_FLAG -#define __HAL_CLEAR_FLAG __HAL_SYSCFG_CLEAR_FLAG -#define __HAL_VREFINT_OUT_ENABLE __HAL_SYSCFG_VREFINT_OUT_ENABLE -#define __HAL_VREFINT_OUT_DISABLE __HAL_SYSCFG_VREFINT_OUT_DISABLE -#define __HAL_SYSCFG_SRAM2_WRP_ENABLE __HAL_SYSCFG_SRAM2_WRP_0_31_ENABLE - -#define SYSCFG_FLAG_VREF_READY SYSCFG_FLAG_VREFINT_READY -#define SYSCFG_FLAG_RC48 RCC_FLAG_HSI48 -#define IS_SYSCFG_FASTMODEPLUS_CONFIG IS_I2C_FASTMODEPLUS -#define UFB_MODE_BitNumber UFB_MODE_BIT_NUMBER -#define CMP_PD_BitNumber CMP_PD_BIT_NUMBER - -/** - * @} - */ - - -/** @defgroup HAL_ADC_Aliased_Macros HAL ADC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __ADC_ENABLE __HAL_ADC_ENABLE -#define __ADC_DISABLE __HAL_ADC_DISABLE -#define __HAL_ADC_ENABLING_CONDITIONS ADC_ENABLING_CONDITIONS -#define __HAL_ADC_DISABLING_CONDITIONS ADC_DISABLING_CONDITIONS -#define __HAL_ADC_IS_ENABLED ADC_IS_ENABLE -#define __ADC_IS_ENABLED ADC_IS_ENABLE -#define __HAL_ADC_IS_SOFTWARE_START_REGULAR ADC_IS_SOFTWARE_START_REGULAR -#define __HAL_ADC_IS_SOFTWARE_START_INJECTED ADC_IS_SOFTWARE_START_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR ADC_IS_CONVERSION_ONGOING_REGULAR -#define __HAL_ADC_IS_CONVERSION_ONGOING_INJECTED ADC_IS_CONVERSION_ONGOING_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING ADC_IS_CONVERSION_ONGOING -#define __HAL_ADC_CLEAR_ERRORCODE ADC_CLEAR_ERRORCODE - -#define __HAL_ADC_GET_RESOLUTION ADC_GET_RESOLUTION -#define __HAL_ADC_JSQR_RK ADC_JSQR_RK -#define __HAL_ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_SHIFT -#define __HAL_ADC_CFGR_AWD23CR ADC_CFGR_AWD23CR -#define __HAL_ADC_CFGR_INJECT_AUTO_CONVERSION ADC_CFGR_INJECT_AUTO_CONVERSION -#define __HAL_ADC_CFGR_INJECT_CONTEXT_QUEUE ADC_CFGR_INJECT_CONTEXT_QUEUE -#define __HAL_ADC_CFGR_INJECT_DISCCONTINUOUS ADC_CFGR_INJECT_DISCCONTINUOUS -#define __HAL_ADC_CFGR_REG_DISCCONTINUOUS ADC_CFGR_REG_DISCCONTINUOUS -#define __HAL_ADC_CFGR_DISCONTINUOUS_NUM ADC_CFGR_DISCONTINUOUS_NUM -#define __HAL_ADC_CFGR_AUTOWAIT ADC_CFGR_AUTOWAIT -#define __HAL_ADC_CFGR_CONTINUOUS ADC_CFGR_CONTINUOUS -#define __HAL_ADC_CFGR_OVERRUN ADC_CFGR_OVERRUN -#define __HAL_ADC_CFGR_DMACONTREQ ADC_CFGR_DMACONTREQ -#define __HAL_ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_SET -#define __HAL_ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_SET -#define __HAL_ADC_OFR_CHANNEL ADC_OFR_CHANNEL -#define __HAL_ADC_DIFSEL_CHANNEL ADC_DIFSEL_CHANNEL -#define __HAL_ADC_CALFACT_DIFF_SET ADC_CALFACT_DIFF_SET -#define __HAL_ADC_CALFACT_DIFF_GET ADC_CALFACT_DIFF_GET -#define __HAL_ADC_TRX_HIGHTHRESHOLD ADC_TRX_HIGHTHRESHOLD - -#define __HAL_ADC_OFFSET_SHIFT_RESOLUTION ADC_OFFSET_SHIFT_RESOLUTION -#define __HAL_ADC_AWD1THRESHOLD_SHIFT_RESOLUTION ADC_AWD1THRESHOLD_SHIFT_RESOLUTION -#define __HAL_ADC_AWD23THRESHOLD_SHIFT_RESOLUTION ADC_AWD23THRESHOLD_SHIFT_RESOLUTION -#define __HAL_ADC_COMMON_REGISTER ADC_COMMON_REGISTER -#define __HAL_ADC_COMMON_CCR_MULTI ADC_COMMON_CCR_MULTI -#define __HAL_ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE -#define __ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE -#define __HAL_ADC_NONMULTIMODE_OR_MULTIMODEMASTER ADC_NONMULTIMODE_OR_MULTIMODEMASTER -#define __HAL_ADC_COMMON_ADC_OTHER ADC_COMMON_ADC_OTHER -#define __HAL_ADC_MULTI_SLAVE ADC_MULTI_SLAVE - -#define __HAL_ADC_SQR1_L ADC_SQR1_L_SHIFT -#define __HAL_ADC_JSQR_JL ADC_JSQR_JL_SHIFT -#define __HAL_ADC_JSQR_RK_JL ADC_JSQR_RK_JL -#define __HAL_ADC_CR1_DISCONTINUOUS_NUM ADC_CR1_DISCONTINUOUS_NUM -#define __HAL_ADC_CR1_SCAN ADC_CR1_SCAN_SET -#define __HAL_ADC_CONVCYCLES_MAX_RANGE ADC_CONVCYCLES_MAX_RANGE -#define __HAL_ADC_CLOCK_PRESCALER_RANGE ADC_CLOCK_PRESCALER_RANGE -#define __HAL_ADC_GET_CLOCK_PRESCALER ADC_GET_CLOCK_PRESCALER - -#define __HAL_ADC_SQR1 ADC_SQR1 -#define __HAL_ADC_SMPR1 ADC_SMPR1 -#define __HAL_ADC_SMPR2 ADC_SMPR2 -#define __HAL_ADC_SQR3_RK ADC_SQR3_RK -#define __HAL_ADC_SQR2_RK ADC_SQR2_RK -#define __HAL_ADC_SQR1_RK ADC_SQR1_RK -#define __HAL_ADC_CR2_CONTINUOUS ADC_CR2_CONTINUOUS -#define __HAL_ADC_CR1_DISCONTINUOUS ADC_CR1_DISCONTINUOUS -#define __HAL_ADC_CR1_SCANCONV ADC_CR1_SCANCONV -#define __HAL_ADC_CR2_EOCSelection ADC_CR2_EOCSelection -#define __HAL_ADC_CR2_DMAContReq ADC_CR2_DMAContReq -#define __HAL_ADC_JSQR ADC_JSQR - -#define __HAL_ADC_CHSELR_CHANNEL ADC_CHSELR_CHANNEL -#define __HAL_ADC_CFGR1_REG_DISCCONTINUOUS ADC_CFGR1_REG_DISCCONTINUOUS -#define __HAL_ADC_CFGR1_AUTOOFF ADC_CFGR1_AUTOOFF -#define __HAL_ADC_CFGR1_AUTOWAIT ADC_CFGR1_AUTOWAIT -#define __HAL_ADC_CFGR1_CONTINUOUS ADC_CFGR1_CONTINUOUS -#define __HAL_ADC_CFGR1_OVERRUN ADC_CFGR1_OVERRUN -#define __HAL_ADC_CFGR1_SCANDIR ADC_CFGR1_SCANDIR -#define __HAL_ADC_CFGR1_DMACONTREQ ADC_CFGR1_DMACONTREQ - -/** - * @} - */ - -/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_DHR12R1_ALIGNEMENT DAC_DHR12R1_ALIGNMENT -#define __HAL_DHR12R2_ALIGNEMENT DAC_DHR12R2_ALIGNMENT -#define __HAL_DHR12RD_ALIGNEMENT DAC_DHR12RD_ALIGNMENT -#define IS_DAC_GENERATE_WAVE IS_DAC_WAVE - -/** - * @} - */ - -/** @defgroup HAL_DBGMCU_Aliased_Macros HAL DBGMCU Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_FREEZE_TIM1_DBGMCU __HAL_DBGMCU_FREEZE_TIM1 -#define __HAL_UNFREEZE_TIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM1 -#define __HAL_FREEZE_TIM2_DBGMCU __HAL_DBGMCU_FREEZE_TIM2 -#define __HAL_UNFREEZE_TIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM2 -#define __HAL_FREEZE_TIM3_DBGMCU __HAL_DBGMCU_FREEZE_TIM3 -#define __HAL_UNFREEZE_TIM3_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM3 -#define __HAL_FREEZE_TIM4_DBGMCU __HAL_DBGMCU_FREEZE_TIM4 -#define __HAL_UNFREEZE_TIM4_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM4 -#define __HAL_FREEZE_TIM5_DBGMCU __HAL_DBGMCU_FREEZE_TIM5 -#define __HAL_UNFREEZE_TIM5_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM5 -#define __HAL_FREEZE_TIM6_DBGMCU __HAL_DBGMCU_FREEZE_TIM6 -#define __HAL_UNFREEZE_TIM6_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM6 -#define __HAL_FREEZE_TIM7_DBGMCU __HAL_DBGMCU_FREEZE_TIM7 -#define __HAL_UNFREEZE_TIM7_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM7 -#define __HAL_FREEZE_TIM8_DBGMCU __HAL_DBGMCU_FREEZE_TIM8 -#define __HAL_UNFREEZE_TIM8_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM8 - -#define __HAL_FREEZE_TIM9_DBGMCU __HAL_DBGMCU_FREEZE_TIM9 -#define __HAL_UNFREEZE_TIM9_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM9 -#define __HAL_FREEZE_TIM10_DBGMCU __HAL_DBGMCU_FREEZE_TIM10 -#define __HAL_UNFREEZE_TIM10_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM10 -#define __HAL_FREEZE_TIM11_DBGMCU __HAL_DBGMCU_FREEZE_TIM11 -#define __HAL_UNFREEZE_TIM11_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM11 -#define __HAL_FREEZE_TIM12_DBGMCU __HAL_DBGMCU_FREEZE_TIM12 -#define __HAL_UNFREEZE_TIM12_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM12 -#define __HAL_FREEZE_TIM13_DBGMCU __HAL_DBGMCU_FREEZE_TIM13 -#define __HAL_UNFREEZE_TIM13_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM13 -#define __HAL_FREEZE_TIM14_DBGMCU __HAL_DBGMCU_FREEZE_TIM14 -#define __HAL_UNFREEZE_TIM14_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM14 -#define __HAL_FREEZE_CAN2_DBGMCU __HAL_DBGMCU_FREEZE_CAN2 -#define __HAL_UNFREEZE_CAN2_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN2 - - -#define __HAL_FREEZE_TIM15_DBGMCU __HAL_DBGMCU_FREEZE_TIM15 -#define __HAL_UNFREEZE_TIM15_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM15 -#define __HAL_FREEZE_TIM16_DBGMCU __HAL_DBGMCU_FREEZE_TIM16 -#define __HAL_UNFREEZE_TIM16_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM16 -#define __HAL_FREEZE_TIM17_DBGMCU __HAL_DBGMCU_FREEZE_TIM17 -#define __HAL_UNFREEZE_TIM17_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM17 -#define __HAL_FREEZE_RTC_DBGMCU __HAL_DBGMCU_FREEZE_RTC -#define __HAL_UNFREEZE_RTC_DBGMCU __HAL_DBGMCU_UNFREEZE_RTC -#if defined(STM32H7) -#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG1 -#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UnFreeze_WWDG1 -#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG1 -#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UnFreeze_IWDG1 -#else -#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG -#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_WWDG -#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG -#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_IWDG -#endif /* STM32H7 */ -#define __HAL_FREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT -#define __HAL_UNFREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT -#define __HAL_FREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT -#define __HAL_UNFREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT -#define __HAL_FREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT -#define __HAL_UNFREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT -#define __HAL_FREEZE_CAN1_DBGMCU __HAL_DBGMCU_FREEZE_CAN1 -#define __HAL_UNFREEZE_CAN1_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN1 -#define __HAL_FREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM1 -#define __HAL_UNFREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM1 -#define __HAL_FREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM2 -#define __HAL_UNFREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM2 - -/** - * @} - */ - -/** @defgroup HAL_COMP_Aliased_Macros HAL COMP Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined(STM32F3) -#define COMP_START __HAL_COMP_ENABLE -#define COMP_STOP __HAL_COMP_DISABLE -#define COMP_LOCK __HAL_COMP_LOCK - -#if defined(STM32F301x8) || defined(STM32F302x8) || defined(STM32F318xx) || defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP6_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F302xE) || defined(STM32F302xC) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP6_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F303xE) || defined(STM32F398xx) || defined(STM32F303xC) || defined(STM32F358xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP7_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP7_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F373xC) ||defined(STM32F378xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP2_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) -# endif -#else -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP2_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) -#endif - -#define __HAL_COMP_GET_EXTI_LINE COMP_GET_EXTI_LINE - -#if defined(STM32L0) || defined(STM32L4) -/* Note: On these STM32 families, the only argument of this macro */ -/* is COMP_FLAG_LOCK. */ -/* This macro is replaced by __HAL_COMP_IS_LOCKED with only HAL handle */ -/* argument. */ -#define __HAL_COMP_GET_FLAG(__HANDLE__, __FLAG__) (__HAL_COMP_IS_LOCKED(__HANDLE__)) -#endif -/** - * @} - */ - -#if defined(STM32L0) || defined(STM32L4) -/** @defgroup HAL_COMP_Aliased_Functions HAL COMP Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_COMP_Start_IT HAL_COMP_Start /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */ -#define HAL_COMP_Stop_IT HAL_COMP_Stop /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */ -/** - * @} - */ -#endif - -/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_WAVE_NONE) || \ - ((WAVE) == DAC_WAVE_NOISE)|| \ - ((WAVE) == DAC_WAVE_TRIANGLE)) - -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Macros HAL FLASH Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_WRPAREA IS_OB_WRPAREA -#define IS_TYPEPROGRAM IS_FLASH_TYPEPROGRAM -#define IS_TYPEPROGRAMFLASH IS_FLASH_TYPEPROGRAM -#define IS_TYPEERASE IS_FLASH_TYPEERASE -#define IS_NBSECTORS IS_FLASH_NBSECTORS -#define IS_OB_WDG_SOURCE IS_OB_IWDG_SOURCE - -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Macros HAL I2C Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_I2C_RESET_CR2 I2C_RESET_CR2 -#define __HAL_I2C_GENERATE_START I2C_GENERATE_START -#if defined(STM32F1) -#define __HAL_I2C_FREQ_RANGE I2C_FREQRANGE -#else -#define __HAL_I2C_FREQ_RANGE I2C_FREQ_RANGE -#endif /* STM32F1 */ -#define __HAL_I2C_RISE_TIME I2C_RISE_TIME -#define __HAL_I2C_SPEED_STANDARD I2C_SPEED_STANDARD -#define __HAL_I2C_SPEED_FAST I2C_SPEED_FAST -#define __HAL_I2C_SPEED I2C_SPEED -#define __HAL_I2C_7BIT_ADD_WRITE I2C_7BIT_ADD_WRITE -#define __HAL_I2C_7BIT_ADD_READ I2C_7BIT_ADD_READ -#define __HAL_I2C_10BIT_ADDRESS I2C_10BIT_ADDRESS -#define __HAL_I2C_10BIT_HEADER_WRITE I2C_10BIT_HEADER_WRITE -#define __HAL_I2C_10BIT_HEADER_READ I2C_10BIT_HEADER_READ -#define __HAL_I2C_MEM_ADD_MSB I2C_MEM_ADD_MSB -#define __HAL_I2C_MEM_ADD_LSB I2C_MEM_ADD_LSB -#define __HAL_I2C_FREQRANGE I2C_FREQRANGE -/** - * @} - */ - -/** @defgroup HAL_I2S_Aliased_Macros HAL I2S Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_I2S_INSTANCE IS_I2S_ALL_INSTANCE -#define IS_I2S_INSTANCE_EXT IS_I2S_ALL_INSTANCE_EXT - -#if defined(STM32H7) -#define __HAL_I2S_CLEAR_FREFLAG __HAL_I2S_CLEAR_TIFREFLAG -#endif - -/** - * @} - */ - -/** @defgroup HAL_IRDA_Aliased_Macros HAL IRDA Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __IRDA_DISABLE __HAL_IRDA_DISABLE -#define __IRDA_ENABLE __HAL_IRDA_ENABLE - -#define __HAL_IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE -#define __HAL_IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION -#define __IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE -#define __IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION - -#define IS_IRDA_ONEBIT_SAMPLE IS_IRDA_ONE_BIT_SAMPLE - - -/** - * @} - */ - - -/** @defgroup HAL_IWDG_Aliased_Macros HAL IWDG Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_IWDG_ENABLE_WRITE_ACCESS IWDG_ENABLE_WRITE_ACCESS -#define __HAL_IWDG_DISABLE_WRITE_ACCESS IWDG_DISABLE_WRITE_ACCESS -/** - * @} - */ - - -/** @defgroup HAL_LPTIM_Aliased_Macros HAL LPTIM Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_LPTIM_ENABLE_INTERRUPT __HAL_LPTIM_ENABLE_IT -#define __HAL_LPTIM_DISABLE_INTERRUPT __HAL_LPTIM_DISABLE_IT -#define __HAL_LPTIM_GET_ITSTATUS __HAL_LPTIM_GET_IT_SOURCE - -/** - * @} - */ - - -/** @defgroup HAL_OPAMP_Aliased_Macros HAL OPAMP Aliased Macros maintained for legacy purpose - * @{ - */ -#define __OPAMP_CSR_OPAXPD OPAMP_CSR_OPAXPD -#define __OPAMP_CSR_S3SELX OPAMP_CSR_S3SELX -#define __OPAMP_CSR_S4SELX OPAMP_CSR_S4SELX -#define __OPAMP_CSR_S5SELX OPAMP_CSR_S5SELX -#define __OPAMP_CSR_S6SELX OPAMP_CSR_S6SELX -#define __OPAMP_CSR_OPAXCAL_L OPAMP_CSR_OPAXCAL_L -#define __OPAMP_CSR_OPAXCAL_H OPAMP_CSR_OPAXCAL_H -#define __OPAMP_CSR_OPAXLPM OPAMP_CSR_OPAXLPM -#define __OPAMP_CSR_ALL_SWITCHES OPAMP_CSR_ALL_SWITCHES -#define __OPAMP_CSR_ANAWSELX OPAMP_CSR_ANAWSELX -#define __OPAMP_CSR_OPAXCALOUT OPAMP_CSR_OPAXCALOUT -#define __OPAMP_OFFSET_TRIM_BITSPOSITION OPAMP_OFFSET_TRIM_BITSPOSITION -#define __OPAMP_OFFSET_TRIM_SET OPAMP_OFFSET_TRIM_SET - -/** - * @} - */ - - -/** @defgroup HAL_PWR_Aliased_Macros HAL PWR Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_PVD_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT -#define __HAL_PVD_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT -#define __HAL_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE -#define __HAL_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PVM_EVENT_DISABLE __HAL_PWR_PVM_EVENT_DISABLE -#define __HAL_PVM_EVENT_ENABLE __HAL_PWR_PVM_EVENT_ENABLE -#define __HAL_PVM_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_DISABLE -#define __HAL_PVM_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_ENABLE -#define __HAL_PVM_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_DISABLE -#define __HAL_PVM_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_ENABLE -#define __HAL_PWR_INTERNALWAKEUP_DISABLE HAL_PWREx_DisableInternalWakeUpLine -#define __HAL_PWR_INTERNALWAKEUP_ENABLE HAL_PWREx_EnableInternalWakeUpLine -#define __HAL_PWR_PULL_UP_DOWN_CONFIG_DISABLE HAL_PWREx_DisablePullUpPullDownConfig -#define __HAL_PWR_PULL_UP_DOWN_CONFIG_ENABLE HAL_PWREx_EnablePullUpPullDownConfig -#define __HAL_PWR_PVD_EXTI_CLEAR_EGDE_TRIGGER() do { __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();__HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); } while(0) -#define __HAL_PWR_PVD_EXTI_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT -#define __HAL_PWR_PVD_EXTI_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT -#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE -#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PWR_PVD_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_SET_RISING_EDGE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PWR_PVM_DISABLE() do { HAL_PWREx_DisablePVM1();HAL_PWREx_DisablePVM2();HAL_PWREx_DisablePVM3();HAL_PWREx_DisablePVM4(); } while(0) -#define __HAL_PWR_PVM_ENABLE() do { HAL_PWREx_EnablePVM1();HAL_PWREx_EnablePVM2();HAL_PWREx_EnablePVM3();HAL_PWREx_EnablePVM4(); } while(0) -#define __HAL_PWR_SRAM2CONTENT_PRESERVE_DISABLE HAL_PWREx_DisableSRAM2ContentRetention -#define __HAL_PWR_SRAM2CONTENT_PRESERVE_ENABLE HAL_PWREx_EnableSRAM2ContentRetention -#define __HAL_PWR_VDDIO2_DISABLE HAL_PWREx_DisableVddIO2 -#define __HAL_PWR_VDDIO2_ENABLE HAL_PWREx_EnableVddIO2 -#define __HAL_PWR_VDDIO2_EXTI_CLEAR_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PWR_VDDIO2_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_VDDUSB_DISABLE HAL_PWREx_DisableVddUSB -#define __HAL_PWR_VDDUSB_ENABLE HAL_PWREx_EnableVddUSB - -#if defined (STM32F4) -#define __HAL_PVD_EXTI_ENABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_ENABLE_IT() -#define __HAL_PVD_EXTI_DISABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_DISABLE_IT() -#define __HAL_PVD_EXTI_GET_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GET_FLAG() -#define __HAL_PVD_EXTI_CLEAR_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_CLEAR_FLAG() -#define __HAL_PVD_EXTI_GENERATE_SWIT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GENERATE_SWIT() -#else -#define __HAL_PVD_EXTI_CLEAR_FLAG __HAL_PWR_PVD_EXTI_CLEAR_FLAG -#define __HAL_PVD_EXTI_DISABLE_IT __HAL_PWR_PVD_EXTI_DISABLE_IT -#define __HAL_PVD_EXTI_ENABLE_IT __HAL_PWR_PVD_EXTI_ENABLE_IT -#define __HAL_PVD_EXTI_GENERATE_SWIT __HAL_PWR_PVD_EXTI_GENERATE_SWIT -#define __HAL_PVD_EXTI_GET_FLAG __HAL_PWR_PVD_EXTI_GET_FLAG -#endif /* STM32F4 */ -/** - * @} - */ - - -/** @defgroup HAL_RCC_Aliased HAL RCC Aliased maintained for legacy purpose - * @{ - */ - -#define RCC_StopWakeUpClock_MSI RCC_STOP_WAKEUPCLOCK_MSI -#define RCC_StopWakeUpClock_HSI RCC_STOP_WAKEUPCLOCK_HSI - -#define HAL_RCC_CCSCallback HAL_RCC_CSSCallback -#define HAL_RC48_EnableBuffer_Cmd(cmd) (((cmd\ - )==ENABLE) ? HAL_RCCEx_EnableHSI48_VREFINT() : HAL_RCCEx_DisableHSI48_VREFINT()) - -#define __ADC_CLK_DISABLE __HAL_RCC_ADC_CLK_DISABLE -#define __ADC_CLK_ENABLE __HAL_RCC_ADC_CLK_ENABLE -#define __ADC_CLK_SLEEP_DISABLE __HAL_RCC_ADC_CLK_SLEEP_DISABLE -#define __ADC_CLK_SLEEP_ENABLE __HAL_RCC_ADC_CLK_SLEEP_ENABLE -#define __ADC_FORCE_RESET __HAL_RCC_ADC_FORCE_RESET -#define __ADC_RELEASE_RESET __HAL_RCC_ADC_RELEASE_RESET -#define __ADC1_CLK_DISABLE __HAL_RCC_ADC1_CLK_DISABLE -#define __ADC1_CLK_ENABLE __HAL_RCC_ADC1_CLK_ENABLE -#define __ADC1_FORCE_RESET __HAL_RCC_ADC1_FORCE_RESET -#define __ADC1_RELEASE_RESET __HAL_RCC_ADC1_RELEASE_RESET -#define __ADC1_CLK_SLEEP_ENABLE __HAL_RCC_ADC1_CLK_SLEEP_ENABLE -#define __ADC1_CLK_SLEEP_DISABLE __HAL_RCC_ADC1_CLK_SLEEP_DISABLE -#define __ADC2_CLK_DISABLE __HAL_RCC_ADC2_CLK_DISABLE -#define __ADC2_CLK_ENABLE __HAL_RCC_ADC2_CLK_ENABLE -#define __ADC2_FORCE_RESET __HAL_RCC_ADC2_FORCE_RESET -#define __ADC2_RELEASE_RESET __HAL_RCC_ADC2_RELEASE_RESET -#define __ADC3_CLK_DISABLE __HAL_RCC_ADC3_CLK_DISABLE -#define __ADC3_CLK_ENABLE __HAL_RCC_ADC3_CLK_ENABLE -#define __ADC3_FORCE_RESET __HAL_RCC_ADC3_FORCE_RESET -#define __ADC3_RELEASE_RESET __HAL_RCC_ADC3_RELEASE_RESET -#define __AES_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE -#define __AES_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE -#define __AES_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE -#define __AES_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE -#define __AES_FORCE_RESET __HAL_RCC_AES_FORCE_RESET -#define __AES_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET -#define __CRYP_CLK_SLEEP_ENABLE __HAL_RCC_CRYP_CLK_SLEEP_ENABLE -#define __CRYP_CLK_SLEEP_DISABLE __HAL_RCC_CRYP_CLK_SLEEP_DISABLE -#define __CRYP_CLK_ENABLE __HAL_RCC_CRYP_CLK_ENABLE -#define __CRYP_CLK_DISABLE __HAL_RCC_CRYP_CLK_DISABLE -#define __CRYP_FORCE_RESET __HAL_RCC_CRYP_FORCE_RESET -#define __CRYP_RELEASE_RESET __HAL_RCC_CRYP_RELEASE_RESET -#define __AFIO_CLK_DISABLE __HAL_RCC_AFIO_CLK_DISABLE -#define __AFIO_CLK_ENABLE __HAL_RCC_AFIO_CLK_ENABLE -#define __AFIO_FORCE_RESET __HAL_RCC_AFIO_FORCE_RESET -#define __AFIO_RELEASE_RESET __HAL_RCC_AFIO_RELEASE_RESET -#define __AHB_FORCE_RESET __HAL_RCC_AHB_FORCE_RESET -#define __AHB_RELEASE_RESET __HAL_RCC_AHB_RELEASE_RESET -#define __AHB1_FORCE_RESET __HAL_RCC_AHB1_FORCE_RESET -#define __AHB1_RELEASE_RESET __HAL_RCC_AHB1_RELEASE_RESET -#define __AHB2_FORCE_RESET __HAL_RCC_AHB2_FORCE_RESET -#define __AHB2_RELEASE_RESET __HAL_RCC_AHB2_RELEASE_RESET -#define __AHB3_FORCE_RESET __HAL_RCC_AHB3_FORCE_RESET -#define __AHB3_RELEASE_RESET __HAL_RCC_AHB3_RELEASE_RESET -#define __APB1_FORCE_RESET __HAL_RCC_APB1_FORCE_RESET -#define __APB1_RELEASE_RESET __HAL_RCC_APB1_RELEASE_RESET -#define __APB2_FORCE_RESET __HAL_RCC_APB2_FORCE_RESET -#define __APB2_RELEASE_RESET __HAL_RCC_APB2_RELEASE_RESET -#define __BKP_CLK_DISABLE __HAL_RCC_BKP_CLK_DISABLE -#define __BKP_CLK_ENABLE __HAL_RCC_BKP_CLK_ENABLE -#define __BKP_FORCE_RESET __HAL_RCC_BKP_FORCE_RESET -#define __BKP_RELEASE_RESET __HAL_RCC_BKP_RELEASE_RESET -#define __CAN1_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE -#define __CAN1_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE -#define __CAN1_CLK_SLEEP_DISABLE __HAL_RCC_CAN1_CLK_SLEEP_DISABLE -#define __CAN1_CLK_SLEEP_ENABLE __HAL_RCC_CAN1_CLK_SLEEP_ENABLE -#define __CAN1_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET -#define __CAN1_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET -#define __CAN_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE -#define __CAN_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE -#define __CAN_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET -#define __CAN_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET -#define __CAN2_CLK_DISABLE __HAL_RCC_CAN2_CLK_DISABLE -#define __CAN2_CLK_ENABLE __HAL_RCC_CAN2_CLK_ENABLE -#define __CAN2_FORCE_RESET __HAL_RCC_CAN2_FORCE_RESET -#define __CAN2_RELEASE_RESET __HAL_RCC_CAN2_RELEASE_RESET -#define __CEC_CLK_DISABLE __HAL_RCC_CEC_CLK_DISABLE -#define __CEC_CLK_ENABLE __HAL_RCC_CEC_CLK_ENABLE -#define __COMP_CLK_DISABLE __HAL_RCC_COMP_CLK_DISABLE -#define __COMP_CLK_ENABLE __HAL_RCC_COMP_CLK_ENABLE -#define __COMP_FORCE_RESET __HAL_RCC_COMP_FORCE_RESET -#define __COMP_RELEASE_RESET __HAL_RCC_COMP_RELEASE_RESET -#define __COMP_CLK_SLEEP_ENABLE __HAL_RCC_COMP_CLK_SLEEP_ENABLE -#define __COMP_CLK_SLEEP_DISABLE __HAL_RCC_COMP_CLK_SLEEP_DISABLE -#define __CEC_FORCE_RESET __HAL_RCC_CEC_FORCE_RESET -#define __CEC_RELEASE_RESET __HAL_RCC_CEC_RELEASE_RESET -#define __CRC_CLK_DISABLE __HAL_RCC_CRC_CLK_DISABLE -#define __CRC_CLK_ENABLE __HAL_RCC_CRC_CLK_ENABLE -#define __CRC_CLK_SLEEP_DISABLE __HAL_RCC_CRC_CLK_SLEEP_DISABLE -#define __CRC_CLK_SLEEP_ENABLE __HAL_RCC_CRC_CLK_SLEEP_ENABLE -#define __CRC_FORCE_RESET __HAL_RCC_CRC_FORCE_RESET -#define __CRC_RELEASE_RESET __HAL_RCC_CRC_RELEASE_RESET -#define __DAC_CLK_DISABLE __HAL_RCC_DAC_CLK_DISABLE -#define __DAC_CLK_ENABLE __HAL_RCC_DAC_CLK_ENABLE -#define __DAC_FORCE_RESET __HAL_RCC_DAC_FORCE_RESET -#define __DAC_RELEASE_RESET __HAL_RCC_DAC_RELEASE_RESET -#define __DAC1_CLK_DISABLE __HAL_RCC_DAC1_CLK_DISABLE -#define __DAC1_CLK_ENABLE __HAL_RCC_DAC1_CLK_ENABLE -#define __DAC1_CLK_SLEEP_DISABLE __HAL_RCC_DAC1_CLK_SLEEP_DISABLE -#define __DAC1_CLK_SLEEP_ENABLE __HAL_RCC_DAC1_CLK_SLEEP_ENABLE -#define __DAC1_FORCE_RESET __HAL_RCC_DAC1_FORCE_RESET -#define __DAC1_RELEASE_RESET __HAL_RCC_DAC1_RELEASE_RESET -#define __DBGMCU_CLK_ENABLE __HAL_RCC_DBGMCU_CLK_ENABLE -#define __DBGMCU_CLK_DISABLE __HAL_RCC_DBGMCU_CLK_DISABLE -#define __DBGMCU_FORCE_RESET __HAL_RCC_DBGMCU_FORCE_RESET -#define __DBGMCU_RELEASE_RESET __HAL_RCC_DBGMCU_RELEASE_RESET -#define __DFSDM_CLK_DISABLE __HAL_RCC_DFSDM_CLK_DISABLE -#define __DFSDM_CLK_ENABLE __HAL_RCC_DFSDM_CLK_ENABLE -#define __DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE -#define __DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE -#define __DFSDM_FORCE_RESET __HAL_RCC_DFSDM_FORCE_RESET -#define __DFSDM_RELEASE_RESET __HAL_RCC_DFSDM_RELEASE_RESET -#define __DMA1_CLK_DISABLE __HAL_RCC_DMA1_CLK_DISABLE -#define __DMA1_CLK_ENABLE __HAL_RCC_DMA1_CLK_ENABLE -#define __DMA1_CLK_SLEEP_DISABLE __HAL_RCC_DMA1_CLK_SLEEP_DISABLE -#define __DMA1_CLK_SLEEP_ENABLE __HAL_RCC_DMA1_CLK_SLEEP_ENABLE -#define __DMA1_FORCE_RESET __HAL_RCC_DMA1_FORCE_RESET -#define __DMA1_RELEASE_RESET __HAL_RCC_DMA1_RELEASE_RESET -#define __DMA2_CLK_DISABLE __HAL_RCC_DMA2_CLK_DISABLE -#define __DMA2_CLK_ENABLE __HAL_RCC_DMA2_CLK_ENABLE -#define __DMA2_CLK_SLEEP_DISABLE __HAL_RCC_DMA2_CLK_SLEEP_DISABLE -#define __DMA2_CLK_SLEEP_ENABLE __HAL_RCC_DMA2_CLK_SLEEP_ENABLE -#define __DMA2_FORCE_RESET __HAL_RCC_DMA2_FORCE_RESET -#define __DMA2_RELEASE_RESET __HAL_RCC_DMA2_RELEASE_RESET -#define __ETHMAC_CLK_DISABLE __HAL_RCC_ETHMAC_CLK_DISABLE -#define __ETHMAC_CLK_ENABLE __HAL_RCC_ETHMAC_CLK_ENABLE -#define __ETHMAC_FORCE_RESET __HAL_RCC_ETHMAC_FORCE_RESET -#define __ETHMAC_RELEASE_RESET __HAL_RCC_ETHMAC_RELEASE_RESET -#define __ETHMACRX_CLK_DISABLE __HAL_RCC_ETHMACRX_CLK_DISABLE -#define __ETHMACRX_CLK_ENABLE __HAL_RCC_ETHMACRX_CLK_ENABLE -#define __ETHMACTX_CLK_DISABLE __HAL_RCC_ETHMACTX_CLK_DISABLE -#define __ETHMACTX_CLK_ENABLE __HAL_RCC_ETHMACTX_CLK_ENABLE -#define __FIREWALL_CLK_DISABLE __HAL_RCC_FIREWALL_CLK_DISABLE -#define __FIREWALL_CLK_ENABLE __HAL_RCC_FIREWALL_CLK_ENABLE -#define __FLASH_CLK_DISABLE __HAL_RCC_FLASH_CLK_DISABLE -#define __FLASH_CLK_ENABLE __HAL_RCC_FLASH_CLK_ENABLE -#define __FLASH_CLK_SLEEP_DISABLE __HAL_RCC_FLASH_CLK_SLEEP_DISABLE -#define __FLASH_CLK_SLEEP_ENABLE __HAL_RCC_FLASH_CLK_SLEEP_ENABLE -#define __FLASH_FORCE_RESET __HAL_RCC_FLASH_FORCE_RESET -#define __FLASH_RELEASE_RESET __HAL_RCC_FLASH_RELEASE_RESET -#define __FLITF_CLK_DISABLE __HAL_RCC_FLITF_CLK_DISABLE -#define __FLITF_CLK_ENABLE __HAL_RCC_FLITF_CLK_ENABLE -#define __FLITF_FORCE_RESET __HAL_RCC_FLITF_FORCE_RESET -#define __FLITF_RELEASE_RESET __HAL_RCC_FLITF_RELEASE_RESET -#define __FLITF_CLK_SLEEP_ENABLE __HAL_RCC_FLITF_CLK_SLEEP_ENABLE -#define __FLITF_CLK_SLEEP_DISABLE __HAL_RCC_FLITF_CLK_SLEEP_DISABLE -#define __FMC_CLK_DISABLE __HAL_RCC_FMC_CLK_DISABLE -#define __FMC_CLK_ENABLE __HAL_RCC_FMC_CLK_ENABLE -#define __FMC_CLK_SLEEP_DISABLE __HAL_RCC_FMC_CLK_SLEEP_DISABLE -#define __FMC_CLK_SLEEP_ENABLE __HAL_RCC_FMC_CLK_SLEEP_ENABLE -#define __FMC_FORCE_RESET __HAL_RCC_FMC_FORCE_RESET -#define __FMC_RELEASE_RESET __HAL_RCC_FMC_RELEASE_RESET -#define __FSMC_CLK_DISABLE __HAL_RCC_FSMC_CLK_DISABLE -#define __FSMC_CLK_ENABLE __HAL_RCC_FSMC_CLK_ENABLE -#define __GPIOA_CLK_DISABLE __HAL_RCC_GPIOA_CLK_DISABLE -#define __GPIOA_CLK_ENABLE __HAL_RCC_GPIOA_CLK_ENABLE -#define __GPIOA_CLK_SLEEP_DISABLE __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE -#define __GPIOA_CLK_SLEEP_ENABLE __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE -#define __GPIOA_FORCE_RESET __HAL_RCC_GPIOA_FORCE_RESET -#define __GPIOA_RELEASE_RESET __HAL_RCC_GPIOA_RELEASE_RESET -#define __GPIOB_CLK_DISABLE __HAL_RCC_GPIOB_CLK_DISABLE -#define __GPIOB_CLK_ENABLE __HAL_RCC_GPIOB_CLK_ENABLE -#define __GPIOB_CLK_SLEEP_DISABLE __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE -#define __GPIOB_CLK_SLEEP_ENABLE __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE -#define __GPIOB_FORCE_RESET __HAL_RCC_GPIOB_FORCE_RESET -#define __GPIOB_RELEASE_RESET __HAL_RCC_GPIOB_RELEASE_RESET -#define __GPIOC_CLK_DISABLE __HAL_RCC_GPIOC_CLK_DISABLE -#define __GPIOC_CLK_ENABLE __HAL_RCC_GPIOC_CLK_ENABLE -#define __GPIOC_CLK_SLEEP_DISABLE __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE -#define __GPIOC_CLK_SLEEP_ENABLE __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE -#define __GPIOC_FORCE_RESET __HAL_RCC_GPIOC_FORCE_RESET -#define __GPIOC_RELEASE_RESET __HAL_RCC_GPIOC_RELEASE_RESET -#define __GPIOD_CLK_DISABLE __HAL_RCC_GPIOD_CLK_DISABLE -#define __GPIOD_CLK_ENABLE __HAL_RCC_GPIOD_CLK_ENABLE -#define __GPIOD_CLK_SLEEP_DISABLE __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE -#define __GPIOD_CLK_SLEEP_ENABLE __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE -#define __GPIOD_FORCE_RESET __HAL_RCC_GPIOD_FORCE_RESET -#define __GPIOD_RELEASE_RESET __HAL_RCC_GPIOD_RELEASE_RESET -#define __GPIOE_CLK_DISABLE __HAL_RCC_GPIOE_CLK_DISABLE -#define __GPIOE_CLK_ENABLE __HAL_RCC_GPIOE_CLK_ENABLE -#define __GPIOE_CLK_SLEEP_DISABLE __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE -#define __GPIOE_CLK_SLEEP_ENABLE __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE -#define __GPIOE_FORCE_RESET __HAL_RCC_GPIOE_FORCE_RESET -#define __GPIOE_RELEASE_RESET __HAL_RCC_GPIOE_RELEASE_RESET -#define __GPIOF_CLK_DISABLE __HAL_RCC_GPIOF_CLK_DISABLE -#define __GPIOF_CLK_ENABLE __HAL_RCC_GPIOF_CLK_ENABLE -#define __GPIOF_CLK_SLEEP_DISABLE __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE -#define __GPIOF_CLK_SLEEP_ENABLE __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE -#define __GPIOF_FORCE_RESET __HAL_RCC_GPIOF_FORCE_RESET -#define __GPIOF_RELEASE_RESET __HAL_RCC_GPIOF_RELEASE_RESET -#define __GPIOG_CLK_DISABLE __HAL_RCC_GPIOG_CLK_DISABLE -#define __GPIOG_CLK_ENABLE __HAL_RCC_GPIOG_CLK_ENABLE -#define __GPIOG_CLK_SLEEP_DISABLE __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE -#define __GPIOG_CLK_SLEEP_ENABLE __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE -#define __GPIOG_FORCE_RESET __HAL_RCC_GPIOG_FORCE_RESET -#define __GPIOG_RELEASE_RESET __HAL_RCC_GPIOG_RELEASE_RESET -#define __GPIOH_CLK_DISABLE __HAL_RCC_GPIOH_CLK_DISABLE -#define __GPIOH_CLK_ENABLE __HAL_RCC_GPIOH_CLK_ENABLE -#define __GPIOH_CLK_SLEEP_DISABLE __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE -#define __GPIOH_CLK_SLEEP_ENABLE __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE -#define __GPIOH_FORCE_RESET __HAL_RCC_GPIOH_FORCE_RESET -#define __GPIOH_RELEASE_RESET __HAL_RCC_GPIOH_RELEASE_RESET -#define __I2C1_CLK_DISABLE __HAL_RCC_I2C1_CLK_DISABLE -#define __I2C1_CLK_ENABLE __HAL_RCC_I2C1_CLK_ENABLE -#define __I2C1_CLK_SLEEP_DISABLE __HAL_RCC_I2C1_CLK_SLEEP_DISABLE -#define __I2C1_CLK_SLEEP_ENABLE __HAL_RCC_I2C1_CLK_SLEEP_ENABLE -#define __I2C1_FORCE_RESET __HAL_RCC_I2C1_FORCE_RESET -#define __I2C1_RELEASE_RESET __HAL_RCC_I2C1_RELEASE_RESET -#define __I2C2_CLK_DISABLE __HAL_RCC_I2C2_CLK_DISABLE -#define __I2C2_CLK_ENABLE __HAL_RCC_I2C2_CLK_ENABLE -#define __I2C2_CLK_SLEEP_DISABLE __HAL_RCC_I2C2_CLK_SLEEP_DISABLE -#define __I2C2_CLK_SLEEP_ENABLE __HAL_RCC_I2C2_CLK_SLEEP_ENABLE -#define __I2C2_FORCE_RESET __HAL_RCC_I2C2_FORCE_RESET -#define __I2C2_RELEASE_RESET __HAL_RCC_I2C2_RELEASE_RESET -#define __I2C3_CLK_DISABLE __HAL_RCC_I2C3_CLK_DISABLE -#define __I2C3_CLK_ENABLE __HAL_RCC_I2C3_CLK_ENABLE -#define __I2C3_CLK_SLEEP_DISABLE __HAL_RCC_I2C3_CLK_SLEEP_DISABLE -#define __I2C3_CLK_SLEEP_ENABLE __HAL_RCC_I2C3_CLK_SLEEP_ENABLE -#define __I2C3_FORCE_RESET __HAL_RCC_I2C3_FORCE_RESET -#define __I2C3_RELEASE_RESET __HAL_RCC_I2C3_RELEASE_RESET -#define __LCD_CLK_DISABLE __HAL_RCC_LCD_CLK_DISABLE -#define __LCD_CLK_ENABLE __HAL_RCC_LCD_CLK_ENABLE -#define __LCD_CLK_SLEEP_DISABLE __HAL_RCC_LCD_CLK_SLEEP_DISABLE -#define __LCD_CLK_SLEEP_ENABLE __HAL_RCC_LCD_CLK_SLEEP_ENABLE -#define __LCD_FORCE_RESET __HAL_RCC_LCD_FORCE_RESET -#define __LCD_RELEASE_RESET __HAL_RCC_LCD_RELEASE_RESET -#define __LPTIM1_CLK_DISABLE __HAL_RCC_LPTIM1_CLK_DISABLE -#define __LPTIM1_CLK_ENABLE __HAL_RCC_LPTIM1_CLK_ENABLE -#define __LPTIM1_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE -#define __LPTIM1_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE -#define __LPTIM1_FORCE_RESET __HAL_RCC_LPTIM1_FORCE_RESET -#define __LPTIM1_RELEASE_RESET __HAL_RCC_LPTIM1_RELEASE_RESET -#define __LPTIM2_CLK_DISABLE __HAL_RCC_LPTIM2_CLK_DISABLE -#define __LPTIM2_CLK_ENABLE __HAL_RCC_LPTIM2_CLK_ENABLE -#define __LPTIM2_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM2_CLK_SLEEP_DISABLE -#define __LPTIM2_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM2_CLK_SLEEP_ENABLE -#define __LPTIM2_FORCE_RESET __HAL_RCC_LPTIM2_FORCE_RESET -#define __LPTIM2_RELEASE_RESET __HAL_RCC_LPTIM2_RELEASE_RESET -#define __LPUART1_CLK_DISABLE __HAL_RCC_LPUART1_CLK_DISABLE -#define __LPUART1_CLK_ENABLE __HAL_RCC_LPUART1_CLK_ENABLE -#define __LPUART1_CLK_SLEEP_DISABLE __HAL_RCC_LPUART1_CLK_SLEEP_DISABLE -#define __LPUART1_CLK_SLEEP_ENABLE __HAL_RCC_LPUART1_CLK_SLEEP_ENABLE -#define __LPUART1_FORCE_RESET __HAL_RCC_LPUART1_FORCE_RESET -#define __LPUART1_RELEASE_RESET __HAL_RCC_LPUART1_RELEASE_RESET -#define __OPAMP_CLK_DISABLE __HAL_RCC_OPAMP_CLK_DISABLE -#define __OPAMP_CLK_ENABLE __HAL_RCC_OPAMP_CLK_ENABLE -#define __OPAMP_CLK_SLEEP_DISABLE __HAL_RCC_OPAMP_CLK_SLEEP_DISABLE -#define __OPAMP_CLK_SLEEP_ENABLE __HAL_RCC_OPAMP_CLK_SLEEP_ENABLE -#define __OPAMP_FORCE_RESET __HAL_RCC_OPAMP_FORCE_RESET -#define __OPAMP_RELEASE_RESET __HAL_RCC_OPAMP_RELEASE_RESET -#define __OTGFS_CLK_DISABLE __HAL_RCC_OTGFS_CLK_DISABLE -#define __OTGFS_CLK_ENABLE __HAL_RCC_OTGFS_CLK_ENABLE -#define __OTGFS_CLK_SLEEP_DISABLE __HAL_RCC_OTGFS_CLK_SLEEP_DISABLE -#define __OTGFS_CLK_SLEEP_ENABLE __HAL_RCC_OTGFS_CLK_SLEEP_ENABLE -#define __OTGFS_FORCE_RESET __HAL_RCC_OTGFS_FORCE_RESET -#define __OTGFS_RELEASE_RESET __HAL_RCC_OTGFS_RELEASE_RESET -#define __PWR_CLK_DISABLE __HAL_RCC_PWR_CLK_DISABLE -#define __PWR_CLK_ENABLE __HAL_RCC_PWR_CLK_ENABLE -#define __PWR_CLK_SLEEP_DISABLE __HAL_RCC_PWR_CLK_SLEEP_DISABLE -#define __PWR_CLK_SLEEP_ENABLE __HAL_RCC_PWR_CLK_SLEEP_ENABLE -#define __PWR_FORCE_RESET __HAL_RCC_PWR_FORCE_RESET -#define __PWR_RELEASE_RESET __HAL_RCC_PWR_RELEASE_RESET -#define __QSPI_CLK_DISABLE __HAL_RCC_QSPI_CLK_DISABLE -#define __QSPI_CLK_ENABLE __HAL_RCC_QSPI_CLK_ENABLE -#define __QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QSPI_CLK_SLEEP_DISABLE -#define __QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QSPI_CLK_SLEEP_ENABLE -#define __QSPI_FORCE_RESET __HAL_RCC_QSPI_FORCE_RESET -#define __QSPI_RELEASE_RESET __HAL_RCC_QSPI_RELEASE_RESET - -#if defined(STM32WB) -#define __HAL_RCC_QSPI_CLK_DISABLE __HAL_RCC_QUADSPI_CLK_DISABLE -#define __HAL_RCC_QSPI_CLK_ENABLE __HAL_RCC_QUADSPI_CLK_ENABLE -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QUADSPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QUADSPI_CLK_SLEEP_ENABLE -#define __HAL_RCC_QSPI_FORCE_RESET __HAL_RCC_QUADSPI_FORCE_RESET -#define __HAL_RCC_QSPI_RELEASE_RESET __HAL_RCC_QUADSPI_RELEASE_RESET -#define __HAL_RCC_QSPI_IS_CLK_ENABLED __HAL_RCC_QUADSPI_IS_CLK_ENABLED -#define __HAL_RCC_QSPI_IS_CLK_DISABLED __HAL_RCC_QUADSPI_IS_CLK_DISABLED -#define __HAL_RCC_QSPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_QSPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_DISABLED -#define QSPI_IRQHandler QUADSPI_IRQHandler -#endif /* __HAL_RCC_QUADSPI_CLK_ENABLE */ - -#define __RNG_CLK_DISABLE __HAL_RCC_RNG_CLK_DISABLE -#define __RNG_CLK_ENABLE __HAL_RCC_RNG_CLK_ENABLE -#define __RNG_CLK_SLEEP_DISABLE __HAL_RCC_RNG_CLK_SLEEP_DISABLE -#define __RNG_CLK_SLEEP_ENABLE __HAL_RCC_RNG_CLK_SLEEP_ENABLE -#define __RNG_FORCE_RESET __HAL_RCC_RNG_FORCE_RESET -#define __RNG_RELEASE_RESET __HAL_RCC_RNG_RELEASE_RESET -#define __SAI1_CLK_DISABLE __HAL_RCC_SAI1_CLK_DISABLE -#define __SAI1_CLK_ENABLE __HAL_RCC_SAI1_CLK_ENABLE -#define __SAI1_CLK_SLEEP_DISABLE __HAL_RCC_SAI1_CLK_SLEEP_DISABLE -#define __SAI1_CLK_SLEEP_ENABLE __HAL_RCC_SAI1_CLK_SLEEP_ENABLE -#define __SAI1_FORCE_RESET __HAL_RCC_SAI1_FORCE_RESET -#define __SAI1_RELEASE_RESET __HAL_RCC_SAI1_RELEASE_RESET -#define __SAI2_CLK_DISABLE __HAL_RCC_SAI2_CLK_DISABLE -#define __SAI2_CLK_ENABLE __HAL_RCC_SAI2_CLK_ENABLE -#define __SAI2_CLK_SLEEP_DISABLE __HAL_RCC_SAI2_CLK_SLEEP_DISABLE -#define __SAI2_CLK_SLEEP_ENABLE __HAL_RCC_SAI2_CLK_SLEEP_ENABLE -#define __SAI2_FORCE_RESET __HAL_RCC_SAI2_FORCE_RESET -#define __SAI2_RELEASE_RESET __HAL_RCC_SAI2_RELEASE_RESET -#define __SDIO_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE -#define __SDIO_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE -#define __SDMMC_CLK_DISABLE __HAL_RCC_SDMMC_CLK_DISABLE -#define __SDMMC_CLK_ENABLE __HAL_RCC_SDMMC_CLK_ENABLE -#define __SDMMC_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC_CLK_SLEEP_DISABLE -#define __SDMMC_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC_CLK_SLEEP_ENABLE -#define __SDMMC_FORCE_RESET __HAL_RCC_SDMMC_FORCE_RESET -#define __SDMMC_RELEASE_RESET __HAL_RCC_SDMMC_RELEASE_RESET -#define __SPI1_CLK_DISABLE __HAL_RCC_SPI1_CLK_DISABLE -#define __SPI1_CLK_ENABLE __HAL_RCC_SPI1_CLK_ENABLE -#define __SPI1_CLK_SLEEP_DISABLE __HAL_RCC_SPI1_CLK_SLEEP_DISABLE -#define __SPI1_CLK_SLEEP_ENABLE __HAL_RCC_SPI1_CLK_SLEEP_ENABLE -#define __SPI1_FORCE_RESET __HAL_RCC_SPI1_FORCE_RESET -#define __SPI1_RELEASE_RESET __HAL_RCC_SPI1_RELEASE_RESET -#define __SPI2_CLK_DISABLE __HAL_RCC_SPI2_CLK_DISABLE -#define __SPI2_CLK_ENABLE __HAL_RCC_SPI2_CLK_ENABLE -#define __SPI2_CLK_SLEEP_DISABLE __HAL_RCC_SPI2_CLK_SLEEP_DISABLE -#define __SPI2_CLK_SLEEP_ENABLE __HAL_RCC_SPI2_CLK_SLEEP_ENABLE -#define __SPI2_FORCE_RESET __HAL_RCC_SPI2_FORCE_RESET -#define __SPI2_RELEASE_RESET __HAL_RCC_SPI2_RELEASE_RESET -#define __SPI3_CLK_DISABLE __HAL_RCC_SPI3_CLK_DISABLE -#define __SPI3_CLK_ENABLE __HAL_RCC_SPI3_CLK_ENABLE -#define __SPI3_CLK_SLEEP_DISABLE __HAL_RCC_SPI3_CLK_SLEEP_DISABLE -#define __SPI3_CLK_SLEEP_ENABLE __HAL_RCC_SPI3_CLK_SLEEP_ENABLE -#define __SPI3_FORCE_RESET __HAL_RCC_SPI3_FORCE_RESET -#define __SPI3_RELEASE_RESET __HAL_RCC_SPI3_RELEASE_RESET -#define __SRAM_CLK_DISABLE __HAL_RCC_SRAM_CLK_DISABLE -#define __SRAM_CLK_ENABLE __HAL_RCC_SRAM_CLK_ENABLE -#define __SRAM1_CLK_SLEEP_DISABLE __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE -#define __SRAM1_CLK_SLEEP_ENABLE __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE -#define __SRAM2_CLK_SLEEP_DISABLE __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE -#define __SRAM2_CLK_SLEEP_ENABLE __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE -#define __SWPMI1_CLK_DISABLE __HAL_RCC_SWPMI1_CLK_DISABLE -#define __SWPMI1_CLK_ENABLE __HAL_RCC_SWPMI1_CLK_ENABLE -#define __SWPMI1_CLK_SLEEP_DISABLE __HAL_RCC_SWPMI1_CLK_SLEEP_DISABLE -#define __SWPMI1_CLK_SLEEP_ENABLE __HAL_RCC_SWPMI1_CLK_SLEEP_ENABLE -#define __SWPMI1_FORCE_RESET __HAL_RCC_SWPMI1_FORCE_RESET -#define __SWPMI1_RELEASE_RESET __HAL_RCC_SWPMI1_RELEASE_RESET -#define __SYSCFG_CLK_DISABLE __HAL_RCC_SYSCFG_CLK_DISABLE -#define __SYSCFG_CLK_ENABLE __HAL_RCC_SYSCFG_CLK_ENABLE -#define __SYSCFG_CLK_SLEEP_DISABLE __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE -#define __SYSCFG_CLK_SLEEP_ENABLE __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE -#define __SYSCFG_FORCE_RESET __HAL_RCC_SYSCFG_FORCE_RESET -#define __SYSCFG_RELEASE_RESET __HAL_RCC_SYSCFG_RELEASE_RESET -#define __TIM1_CLK_DISABLE __HAL_RCC_TIM1_CLK_DISABLE -#define __TIM1_CLK_ENABLE __HAL_RCC_TIM1_CLK_ENABLE -#define __TIM1_CLK_SLEEP_DISABLE __HAL_RCC_TIM1_CLK_SLEEP_DISABLE -#define __TIM1_CLK_SLEEP_ENABLE __HAL_RCC_TIM1_CLK_SLEEP_ENABLE -#define __TIM1_FORCE_RESET __HAL_RCC_TIM1_FORCE_RESET -#define __TIM1_RELEASE_RESET __HAL_RCC_TIM1_RELEASE_RESET -#define __TIM10_CLK_DISABLE __HAL_RCC_TIM10_CLK_DISABLE -#define __TIM10_CLK_ENABLE __HAL_RCC_TIM10_CLK_ENABLE -#define __TIM10_FORCE_RESET __HAL_RCC_TIM10_FORCE_RESET -#define __TIM10_RELEASE_RESET __HAL_RCC_TIM10_RELEASE_RESET -#define __TIM11_CLK_DISABLE __HAL_RCC_TIM11_CLK_DISABLE -#define __TIM11_CLK_ENABLE __HAL_RCC_TIM11_CLK_ENABLE -#define __TIM11_FORCE_RESET __HAL_RCC_TIM11_FORCE_RESET -#define __TIM11_RELEASE_RESET __HAL_RCC_TIM11_RELEASE_RESET -#define __TIM12_CLK_DISABLE __HAL_RCC_TIM12_CLK_DISABLE -#define __TIM12_CLK_ENABLE __HAL_RCC_TIM12_CLK_ENABLE -#define __TIM12_FORCE_RESET __HAL_RCC_TIM12_FORCE_RESET -#define __TIM12_RELEASE_RESET __HAL_RCC_TIM12_RELEASE_RESET -#define __TIM13_CLK_DISABLE __HAL_RCC_TIM13_CLK_DISABLE -#define __TIM13_CLK_ENABLE __HAL_RCC_TIM13_CLK_ENABLE -#define __TIM13_FORCE_RESET __HAL_RCC_TIM13_FORCE_RESET -#define __TIM13_RELEASE_RESET __HAL_RCC_TIM13_RELEASE_RESET -#define __TIM14_CLK_DISABLE __HAL_RCC_TIM14_CLK_DISABLE -#define __TIM14_CLK_ENABLE __HAL_RCC_TIM14_CLK_ENABLE -#define __TIM14_FORCE_RESET __HAL_RCC_TIM14_FORCE_RESET -#define __TIM14_RELEASE_RESET __HAL_RCC_TIM14_RELEASE_RESET -#define __TIM15_CLK_DISABLE __HAL_RCC_TIM15_CLK_DISABLE -#define __TIM15_CLK_ENABLE __HAL_RCC_TIM15_CLK_ENABLE -#define __TIM15_CLK_SLEEP_DISABLE __HAL_RCC_TIM15_CLK_SLEEP_DISABLE -#define __TIM15_CLK_SLEEP_ENABLE __HAL_RCC_TIM15_CLK_SLEEP_ENABLE -#define __TIM15_FORCE_RESET __HAL_RCC_TIM15_FORCE_RESET -#define __TIM15_RELEASE_RESET __HAL_RCC_TIM15_RELEASE_RESET -#define __TIM16_CLK_DISABLE __HAL_RCC_TIM16_CLK_DISABLE -#define __TIM16_CLK_ENABLE __HAL_RCC_TIM16_CLK_ENABLE -#define __TIM16_CLK_SLEEP_DISABLE __HAL_RCC_TIM16_CLK_SLEEP_DISABLE -#define __TIM16_CLK_SLEEP_ENABLE __HAL_RCC_TIM16_CLK_SLEEP_ENABLE -#define __TIM16_FORCE_RESET __HAL_RCC_TIM16_FORCE_RESET -#define __TIM16_RELEASE_RESET __HAL_RCC_TIM16_RELEASE_RESET -#define __TIM17_CLK_DISABLE __HAL_RCC_TIM17_CLK_DISABLE -#define __TIM17_CLK_ENABLE __HAL_RCC_TIM17_CLK_ENABLE -#define __TIM17_CLK_SLEEP_DISABLE __HAL_RCC_TIM17_CLK_SLEEP_DISABLE -#define __TIM17_CLK_SLEEP_ENABLE __HAL_RCC_TIM17_CLK_SLEEP_ENABLE -#define __TIM17_FORCE_RESET __HAL_RCC_TIM17_FORCE_RESET -#define __TIM17_RELEASE_RESET __HAL_RCC_TIM17_RELEASE_RESET -#define __TIM2_CLK_DISABLE __HAL_RCC_TIM2_CLK_DISABLE -#define __TIM2_CLK_ENABLE __HAL_RCC_TIM2_CLK_ENABLE -#define __TIM2_CLK_SLEEP_DISABLE __HAL_RCC_TIM2_CLK_SLEEP_DISABLE -#define __TIM2_CLK_SLEEP_ENABLE __HAL_RCC_TIM2_CLK_SLEEP_ENABLE -#define __TIM2_FORCE_RESET __HAL_RCC_TIM2_FORCE_RESET -#define __TIM2_RELEASE_RESET __HAL_RCC_TIM2_RELEASE_RESET -#define __TIM3_CLK_DISABLE __HAL_RCC_TIM3_CLK_DISABLE -#define __TIM3_CLK_ENABLE __HAL_RCC_TIM3_CLK_ENABLE -#define __TIM3_CLK_SLEEP_DISABLE __HAL_RCC_TIM3_CLK_SLEEP_DISABLE -#define __TIM3_CLK_SLEEP_ENABLE __HAL_RCC_TIM3_CLK_SLEEP_ENABLE -#define __TIM3_FORCE_RESET __HAL_RCC_TIM3_FORCE_RESET -#define __TIM3_RELEASE_RESET __HAL_RCC_TIM3_RELEASE_RESET -#define __TIM4_CLK_DISABLE __HAL_RCC_TIM4_CLK_DISABLE -#define __TIM4_CLK_ENABLE __HAL_RCC_TIM4_CLK_ENABLE -#define __TIM4_CLK_SLEEP_DISABLE __HAL_RCC_TIM4_CLK_SLEEP_DISABLE -#define __TIM4_CLK_SLEEP_ENABLE __HAL_RCC_TIM4_CLK_SLEEP_ENABLE -#define __TIM4_FORCE_RESET __HAL_RCC_TIM4_FORCE_RESET -#define __TIM4_RELEASE_RESET __HAL_RCC_TIM4_RELEASE_RESET -#define __TIM5_CLK_DISABLE __HAL_RCC_TIM5_CLK_DISABLE -#define __TIM5_CLK_ENABLE __HAL_RCC_TIM5_CLK_ENABLE -#define __TIM5_CLK_SLEEP_DISABLE __HAL_RCC_TIM5_CLK_SLEEP_DISABLE -#define __TIM5_CLK_SLEEP_ENABLE __HAL_RCC_TIM5_CLK_SLEEP_ENABLE -#define __TIM5_FORCE_RESET __HAL_RCC_TIM5_FORCE_RESET -#define __TIM5_RELEASE_RESET __HAL_RCC_TIM5_RELEASE_RESET -#define __TIM6_CLK_DISABLE __HAL_RCC_TIM6_CLK_DISABLE -#define __TIM6_CLK_ENABLE __HAL_RCC_TIM6_CLK_ENABLE -#define __TIM6_CLK_SLEEP_DISABLE __HAL_RCC_TIM6_CLK_SLEEP_DISABLE -#define __TIM6_CLK_SLEEP_ENABLE __HAL_RCC_TIM6_CLK_SLEEP_ENABLE -#define __TIM6_FORCE_RESET __HAL_RCC_TIM6_FORCE_RESET -#define __TIM6_RELEASE_RESET __HAL_RCC_TIM6_RELEASE_RESET -#define __TIM7_CLK_DISABLE __HAL_RCC_TIM7_CLK_DISABLE -#define __TIM7_CLK_ENABLE __HAL_RCC_TIM7_CLK_ENABLE -#define __TIM7_CLK_SLEEP_DISABLE __HAL_RCC_TIM7_CLK_SLEEP_DISABLE -#define __TIM7_CLK_SLEEP_ENABLE __HAL_RCC_TIM7_CLK_SLEEP_ENABLE -#define __TIM7_FORCE_RESET __HAL_RCC_TIM7_FORCE_RESET -#define __TIM7_RELEASE_RESET __HAL_RCC_TIM7_RELEASE_RESET -#define __TIM8_CLK_DISABLE __HAL_RCC_TIM8_CLK_DISABLE -#define __TIM8_CLK_ENABLE __HAL_RCC_TIM8_CLK_ENABLE -#define __TIM8_CLK_SLEEP_DISABLE __HAL_RCC_TIM8_CLK_SLEEP_DISABLE -#define __TIM8_CLK_SLEEP_ENABLE __HAL_RCC_TIM8_CLK_SLEEP_ENABLE -#define __TIM8_FORCE_RESET __HAL_RCC_TIM8_FORCE_RESET -#define __TIM8_RELEASE_RESET __HAL_RCC_TIM8_RELEASE_RESET -#define __TIM9_CLK_DISABLE __HAL_RCC_TIM9_CLK_DISABLE -#define __TIM9_CLK_ENABLE __HAL_RCC_TIM9_CLK_ENABLE -#define __TIM9_FORCE_RESET __HAL_RCC_TIM9_FORCE_RESET -#define __TIM9_RELEASE_RESET __HAL_RCC_TIM9_RELEASE_RESET -#define __TSC_CLK_DISABLE __HAL_RCC_TSC_CLK_DISABLE -#define __TSC_CLK_ENABLE __HAL_RCC_TSC_CLK_ENABLE -#define __TSC_CLK_SLEEP_DISABLE __HAL_RCC_TSC_CLK_SLEEP_DISABLE -#define __TSC_CLK_SLEEP_ENABLE __HAL_RCC_TSC_CLK_SLEEP_ENABLE -#define __TSC_FORCE_RESET __HAL_RCC_TSC_FORCE_RESET -#define __TSC_RELEASE_RESET __HAL_RCC_TSC_RELEASE_RESET -#define __UART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE -#define __UART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE -#define __UART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE -#define __UART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE -#define __UART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET -#define __UART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET -#define __UART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE -#define __UART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE -#define __UART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE -#define __UART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE -#define __UART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET -#define __UART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET -#define __USART1_CLK_DISABLE __HAL_RCC_USART1_CLK_DISABLE -#define __USART1_CLK_ENABLE __HAL_RCC_USART1_CLK_ENABLE -#define __USART1_CLK_SLEEP_DISABLE __HAL_RCC_USART1_CLK_SLEEP_DISABLE -#define __USART1_CLK_SLEEP_ENABLE __HAL_RCC_USART1_CLK_SLEEP_ENABLE -#define __USART1_FORCE_RESET __HAL_RCC_USART1_FORCE_RESET -#define __USART1_RELEASE_RESET __HAL_RCC_USART1_RELEASE_RESET -#define __USART2_CLK_DISABLE __HAL_RCC_USART2_CLK_DISABLE -#define __USART2_CLK_ENABLE __HAL_RCC_USART2_CLK_ENABLE -#define __USART2_CLK_SLEEP_DISABLE __HAL_RCC_USART2_CLK_SLEEP_DISABLE -#define __USART2_CLK_SLEEP_ENABLE __HAL_RCC_USART2_CLK_SLEEP_ENABLE -#define __USART2_FORCE_RESET __HAL_RCC_USART2_FORCE_RESET -#define __USART2_RELEASE_RESET __HAL_RCC_USART2_RELEASE_RESET -#define __USART3_CLK_DISABLE __HAL_RCC_USART3_CLK_DISABLE -#define __USART3_CLK_ENABLE __HAL_RCC_USART3_CLK_ENABLE -#define __USART3_CLK_SLEEP_DISABLE __HAL_RCC_USART3_CLK_SLEEP_DISABLE -#define __USART3_CLK_SLEEP_ENABLE __HAL_RCC_USART3_CLK_SLEEP_ENABLE -#define __USART3_FORCE_RESET __HAL_RCC_USART3_FORCE_RESET -#define __USART3_RELEASE_RESET __HAL_RCC_USART3_RELEASE_RESET -#define __USART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE -#define __USART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE -#define __USART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE -#define __USART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE -#define __USART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET -#define __USART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET -#define __USART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE -#define __USART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE -#define __USART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE -#define __USART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE -#define __USART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET -#define __USART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET -#define __USART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE -#define __USART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE -#define __USART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET -#define __USART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET -#define __USART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE -#define __USART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE -#define __USART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET -#define __USART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET -#define __USB_CLK_DISABLE __HAL_RCC_USB_CLK_DISABLE -#define __USB_CLK_ENABLE __HAL_RCC_USB_CLK_ENABLE -#define __USB_FORCE_RESET __HAL_RCC_USB_FORCE_RESET -#define __USB_CLK_SLEEP_ENABLE __HAL_RCC_USB_CLK_SLEEP_ENABLE -#define __USB_CLK_SLEEP_DISABLE __HAL_RCC_USB_CLK_SLEEP_DISABLE -#define __USB_OTG_FS_CLK_DISABLE __HAL_RCC_USB_OTG_FS_CLK_DISABLE -#define __USB_OTG_FS_CLK_ENABLE __HAL_RCC_USB_OTG_FS_CLK_ENABLE -#define __USB_RELEASE_RESET __HAL_RCC_USB_RELEASE_RESET - -#if defined(STM32H7) -#define __HAL_RCC_WWDG_CLK_DISABLE __HAL_RCC_WWDG1_CLK_DISABLE -#define __HAL_RCC_WWDG_CLK_ENABLE __HAL_RCC_WWDG1_CLK_ENABLE -#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG1_CLK_SLEEP_DISABLE -#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG1_CLK_SLEEP_ENABLE - -#define __HAL_RCC_WWDG_FORCE_RESET ((void)0U) /* Not available on the STM32H7*/ -#define __HAL_RCC_WWDG_RELEASE_RESET ((void)0U) /* Not available on the STM32H7*/ - - -#define __HAL_RCC_WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG1_IS_CLK_ENABLED -#define __HAL_RCC_WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG1_IS_CLK_DISABLED -#endif - -#define __WWDG_CLK_DISABLE __HAL_RCC_WWDG_CLK_DISABLE -#define __WWDG_CLK_ENABLE __HAL_RCC_WWDG_CLK_ENABLE -#define __WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG_CLK_SLEEP_DISABLE -#define __WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG_CLK_SLEEP_ENABLE -#define __WWDG_FORCE_RESET __HAL_RCC_WWDG_FORCE_RESET -#define __WWDG_RELEASE_RESET __HAL_RCC_WWDG_RELEASE_RESET - -#define __TIM21_CLK_ENABLE __HAL_RCC_TIM21_CLK_ENABLE -#define __TIM21_CLK_DISABLE __HAL_RCC_TIM21_CLK_DISABLE -#define __TIM21_FORCE_RESET __HAL_RCC_TIM21_FORCE_RESET -#define __TIM21_RELEASE_RESET __HAL_RCC_TIM21_RELEASE_RESET -#define __TIM21_CLK_SLEEP_ENABLE __HAL_RCC_TIM21_CLK_SLEEP_ENABLE -#define __TIM21_CLK_SLEEP_DISABLE __HAL_RCC_TIM21_CLK_SLEEP_DISABLE -#define __TIM22_CLK_ENABLE __HAL_RCC_TIM22_CLK_ENABLE -#define __TIM22_CLK_DISABLE __HAL_RCC_TIM22_CLK_DISABLE -#define __TIM22_FORCE_RESET __HAL_RCC_TIM22_FORCE_RESET -#define __TIM22_RELEASE_RESET __HAL_RCC_TIM22_RELEASE_RESET -#define __TIM22_CLK_SLEEP_ENABLE __HAL_RCC_TIM22_CLK_SLEEP_ENABLE -#define __TIM22_CLK_SLEEP_DISABLE __HAL_RCC_TIM22_CLK_SLEEP_DISABLE -#define __CRS_CLK_DISABLE __HAL_RCC_CRS_CLK_DISABLE -#define __CRS_CLK_ENABLE __HAL_RCC_CRS_CLK_ENABLE -#define __CRS_CLK_SLEEP_DISABLE __HAL_RCC_CRS_CLK_SLEEP_DISABLE -#define __CRS_CLK_SLEEP_ENABLE __HAL_RCC_CRS_CLK_SLEEP_ENABLE -#define __CRS_FORCE_RESET __HAL_RCC_CRS_FORCE_RESET -#define __CRS_RELEASE_RESET __HAL_RCC_CRS_RELEASE_RESET -#define __RCC_BACKUPRESET_FORCE __HAL_RCC_BACKUPRESET_FORCE -#define __RCC_BACKUPRESET_RELEASE __HAL_RCC_BACKUPRESET_RELEASE - -#define __USB_OTG_FS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET -#define __USB_OTG_FS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET -#define __USB_OTG_FS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE -#define __USB_OTG_FS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE -#define __USB_OTG_HS_CLK_DISABLE __HAL_RCC_USB_OTG_HS_CLK_DISABLE -#define __USB_OTG_HS_CLK_ENABLE __HAL_RCC_USB_OTG_HS_CLK_ENABLE -#define __USB_OTG_HS_ULPI_CLK_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE -#define __USB_OTG_HS_ULPI_CLK_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE -#define __TIM9_CLK_SLEEP_ENABLE __HAL_RCC_TIM9_CLK_SLEEP_ENABLE -#define __TIM9_CLK_SLEEP_DISABLE __HAL_RCC_TIM9_CLK_SLEEP_DISABLE -#define __TIM10_CLK_SLEEP_ENABLE __HAL_RCC_TIM10_CLK_SLEEP_ENABLE -#define __TIM10_CLK_SLEEP_DISABLE __HAL_RCC_TIM10_CLK_SLEEP_DISABLE -#define __TIM11_CLK_SLEEP_ENABLE __HAL_RCC_TIM11_CLK_SLEEP_ENABLE -#define __TIM11_CLK_SLEEP_DISABLE __HAL_RCC_TIM11_CLK_SLEEP_DISABLE -#define __ETHMACPTP_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE -#define __ETHMACPTP_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE -#define __ETHMACPTP_CLK_ENABLE __HAL_RCC_ETHMACPTP_CLK_ENABLE -#define __ETHMACPTP_CLK_DISABLE __HAL_RCC_ETHMACPTP_CLK_DISABLE -#define __HASH_CLK_ENABLE __HAL_RCC_HASH_CLK_ENABLE -#define __HASH_FORCE_RESET __HAL_RCC_HASH_FORCE_RESET -#define __HASH_RELEASE_RESET __HAL_RCC_HASH_RELEASE_RESET -#define __HASH_CLK_SLEEP_ENABLE __HAL_RCC_HASH_CLK_SLEEP_ENABLE -#define __HASH_CLK_SLEEP_DISABLE __HAL_RCC_HASH_CLK_SLEEP_DISABLE -#define __HASH_CLK_DISABLE __HAL_RCC_HASH_CLK_DISABLE -#define __SPI5_CLK_ENABLE __HAL_RCC_SPI5_CLK_ENABLE -#define __SPI5_CLK_DISABLE __HAL_RCC_SPI5_CLK_DISABLE -#define __SPI5_FORCE_RESET __HAL_RCC_SPI5_FORCE_RESET -#define __SPI5_RELEASE_RESET __HAL_RCC_SPI5_RELEASE_RESET -#define __SPI5_CLK_SLEEP_ENABLE __HAL_RCC_SPI5_CLK_SLEEP_ENABLE -#define __SPI5_CLK_SLEEP_DISABLE __HAL_RCC_SPI5_CLK_SLEEP_DISABLE -#define __SPI6_CLK_ENABLE __HAL_RCC_SPI6_CLK_ENABLE -#define __SPI6_CLK_DISABLE __HAL_RCC_SPI6_CLK_DISABLE -#define __SPI6_FORCE_RESET __HAL_RCC_SPI6_FORCE_RESET -#define __SPI6_RELEASE_RESET __HAL_RCC_SPI6_RELEASE_RESET -#define __SPI6_CLK_SLEEP_ENABLE __HAL_RCC_SPI6_CLK_SLEEP_ENABLE -#define __SPI6_CLK_SLEEP_DISABLE __HAL_RCC_SPI6_CLK_SLEEP_DISABLE -#define __LTDC_CLK_ENABLE __HAL_RCC_LTDC_CLK_ENABLE -#define __LTDC_CLK_DISABLE __HAL_RCC_LTDC_CLK_DISABLE -#define __LTDC_FORCE_RESET __HAL_RCC_LTDC_FORCE_RESET -#define __LTDC_RELEASE_RESET __HAL_RCC_LTDC_RELEASE_RESET -#define __LTDC_CLK_SLEEP_ENABLE __HAL_RCC_LTDC_CLK_SLEEP_ENABLE -#define __ETHMAC_CLK_SLEEP_ENABLE __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE -#define __ETHMAC_CLK_SLEEP_DISABLE __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE -#define __ETHMACTX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE -#define __ETHMACTX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE -#define __ETHMACRX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE -#define __ETHMACRX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE -#define __TIM12_CLK_SLEEP_ENABLE __HAL_RCC_TIM12_CLK_SLEEP_ENABLE -#define __TIM12_CLK_SLEEP_DISABLE __HAL_RCC_TIM12_CLK_SLEEP_DISABLE -#define __TIM13_CLK_SLEEP_ENABLE __HAL_RCC_TIM13_CLK_SLEEP_ENABLE -#define __TIM13_CLK_SLEEP_DISABLE __HAL_RCC_TIM13_CLK_SLEEP_DISABLE -#define __TIM14_CLK_SLEEP_ENABLE __HAL_RCC_TIM14_CLK_SLEEP_ENABLE -#define __TIM14_CLK_SLEEP_DISABLE __HAL_RCC_TIM14_CLK_SLEEP_DISABLE -#define __BKPSRAM_CLK_ENABLE __HAL_RCC_BKPSRAM_CLK_ENABLE -#define __BKPSRAM_CLK_DISABLE __HAL_RCC_BKPSRAM_CLK_DISABLE -#define __BKPSRAM_CLK_SLEEP_ENABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE -#define __BKPSRAM_CLK_SLEEP_DISABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE -#define __CCMDATARAMEN_CLK_ENABLE __HAL_RCC_CCMDATARAMEN_CLK_ENABLE -#define __CCMDATARAMEN_CLK_DISABLE __HAL_RCC_CCMDATARAMEN_CLK_DISABLE -#define __USART6_CLK_ENABLE __HAL_RCC_USART6_CLK_ENABLE -#define __USART6_CLK_DISABLE __HAL_RCC_USART6_CLK_DISABLE -#define __USART6_FORCE_RESET __HAL_RCC_USART6_FORCE_RESET -#define __USART6_RELEASE_RESET __HAL_RCC_USART6_RELEASE_RESET -#define __USART6_CLK_SLEEP_ENABLE __HAL_RCC_USART6_CLK_SLEEP_ENABLE -#define __USART6_CLK_SLEEP_DISABLE __HAL_RCC_USART6_CLK_SLEEP_DISABLE -#define __SPI4_CLK_ENABLE __HAL_RCC_SPI4_CLK_ENABLE -#define __SPI4_CLK_DISABLE __HAL_RCC_SPI4_CLK_DISABLE -#define __SPI4_FORCE_RESET __HAL_RCC_SPI4_FORCE_RESET -#define __SPI4_RELEASE_RESET __HAL_RCC_SPI4_RELEASE_RESET -#define __SPI4_CLK_SLEEP_ENABLE __HAL_RCC_SPI4_CLK_SLEEP_ENABLE -#define __SPI4_CLK_SLEEP_DISABLE __HAL_RCC_SPI4_CLK_SLEEP_DISABLE -#define __GPIOI_CLK_ENABLE __HAL_RCC_GPIOI_CLK_ENABLE -#define __GPIOI_CLK_DISABLE __HAL_RCC_GPIOI_CLK_DISABLE -#define __GPIOI_FORCE_RESET __HAL_RCC_GPIOI_FORCE_RESET -#define __GPIOI_RELEASE_RESET __HAL_RCC_GPIOI_RELEASE_RESET -#define __GPIOI_CLK_SLEEP_ENABLE __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE -#define __GPIOI_CLK_SLEEP_DISABLE __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE -#define __GPIOJ_CLK_ENABLE __HAL_RCC_GPIOJ_CLK_ENABLE -#define __GPIOJ_CLK_DISABLE __HAL_RCC_GPIOJ_CLK_DISABLE -#define __GPIOJ_FORCE_RESET __HAL_RCC_GPIOJ_FORCE_RESET -#define __GPIOJ_RELEASE_RESET __HAL_RCC_GPIOJ_RELEASE_RESET -#define __GPIOJ_CLK_SLEEP_ENABLE __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE -#define __GPIOJ_CLK_SLEEP_DISABLE __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE -#define __GPIOK_CLK_ENABLE __HAL_RCC_GPIOK_CLK_ENABLE -#define __GPIOK_CLK_DISABLE __HAL_RCC_GPIOK_CLK_DISABLE -#define __GPIOK_RELEASE_RESET __HAL_RCC_GPIOK_RELEASE_RESET -#define __GPIOK_CLK_SLEEP_ENABLE __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE -#define __GPIOK_CLK_SLEEP_DISABLE __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE -#define __ETH_CLK_ENABLE __HAL_RCC_ETH_CLK_ENABLE -#define __ETH_CLK_DISABLE __HAL_RCC_ETH_CLK_DISABLE -#define __DCMI_CLK_ENABLE __HAL_RCC_DCMI_CLK_ENABLE -#define __DCMI_CLK_DISABLE __HAL_RCC_DCMI_CLK_DISABLE -#define __DCMI_FORCE_RESET __HAL_RCC_DCMI_FORCE_RESET -#define __DCMI_RELEASE_RESET __HAL_RCC_DCMI_RELEASE_RESET -#define __DCMI_CLK_SLEEP_ENABLE __HAL_RCC_DCMI_CLK_SLEEP_ENABLE -#define __DCMI_CLK_SLEEP_DISABLE __HAL_RCC_DCMI_CLK_SLEEP_DISABLE -#define __UART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE -#define __UART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE -#define __UART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET -#define __UART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET -#define __UART7_CLK_SLEEP_ENABLE __HAL_RCC_UART7_CLK_SLEEP_ENABLE -#define __UART7_CLK_SLEEP_DISABLE __HAL_RCC_UART7_CLK_SLEEP_DISABLE -#define __UART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE -#define __UART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE -#define __UART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET -#define __UART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET -#define __UART8_CLK_SLEEP_ENABLE __HAL_RCC_UART8_CLK_SLEEP_ENABLE -#define __UART8_CLK_SLEEP_DISABLE __HAL_RCC_UART8_CLK_SLEEP_DISABLE -#define __OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE -#define __OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE -#define __OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET -#define __OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET -#define __OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE -#define __OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE -#define __HAL_RCC_OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_DISABLED -#define __HAL_RCC_OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET -#define __HAL_RCC_OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET -#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE -#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_DISABLED -#define __SRAM3_CLK_SLEEP_ENABLE __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE -#define __CAN2_CLK_SLEEP_ENABLE __HAL_RCC_CAN2_CLK_SLEEP_ENABLE -#define __CAN2_CLK_SLEEP_DISABLE __HAL_RCC_CAN2_CLK_SLEEP_DISABLE -#define __DAC_CLK_SLEEP_ENABLE __HAL_RCC_DAC_CLK_SLEEP_ENABLE -#define __DAC_CLK_SLEEP_DISABLE __HAL_RCC_DAC_CLK_SLEEP_DISABLE -#define __ADC2_CLK_SLEEP_ENABLE __HAL_RCC_ADC2_CLK_SLEEP_ENABLE -#define __ADC2_CLK_SLEEP_DISABLE __HAL_RCC_ADC2_CLK_SLEEP_DISABLE -#define __ADC3_CLK_SLEEP_ENABLE __HAL_RCC_ADC3_CLK_SLEEP_ENABLE -#define __ADC3_CLK_SLEEP_DISABLE __HAL_RCC_ADC3_CLK_SLEEP_DISABLE -#define __FSMC_FORCE_RESET __HAL_RCC_FSMC_FORCE_RESET -#define __FSMC_RELEASE_RESET __HAL_RCC_FSMC_RELEASE_RESET -#define __FSMC_CLK_SLEEP_ENABLE __HAL_RCC_FSMC_CLK_SLEEP_ENABLE -#define __FSMC_CLK_SLEEP_DISABLE __HAL_RCC_FSMC_CLK_SLEEP_DISABLE -#define __SDIO_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET -#define __SDIO_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET -#define __SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE -#define __SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE -#define __DMA2D_CLK_ENABLE __HAL_RCC_DMA2D_CLK_ENABLE -#define __DMA2D_CLK_DISABLE __HAL_RCC_DMA2D_CLK_DISABLE -#define __DMA2D_FORCE_RESET __HAL_RCC_DMA2D_FORCE_RESET -#define __DMA2D_RELEASE_RESET __HAL_RCC_DMA2D_RELEASE_RESET -#define __DMA2D_CLK_SLEEP_ENABLE __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE -#define __DMA2D_CLK_SLEEP_DISABLE __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE - -/* alias define maintained for legacy */ -#define __HAL_RCC_OTGFS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET -#define __HAL_RCC_OTGFS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET - -#define __ADC12_CLK_ENABLE __HAL_RCC_ADC12_CLK_ENABLE -#define __ADC12_CLK_DISABLE __HAL_RCC_ADC12_CLK_DISABLE -#define __ADC34_CLK_ENABLE __HAL_RCC_ADC34_CLK_ENABLE -#define __ADC34_CLK_DISABLE __HAL_RCC_ADC34_CLK_DISABLE -#define __DAC2_CLK_ENABLE __HAL_RCC_DAC2_CLK_ENABLE -#define __DAC2_CLK_DISABLE __HAL_RCC_DAC2_CLK_DISABLE -#define __TIM18_CLK_ENABLE __HAL_RCC_TIM18_CLK_ENABLE -#define __TIM18_CLK_DISABLE __HAL_RCC_TIM18_CLK_DISABLE -#define __TIM19_CLK_ENABLE __HAL_RCC_TIM19_CLK_ENABLE -#define __TIM19_CLK_DISABLE __HAL_RCC_TIM19_CLK_DISABLE -#define __TIM20_CLK_ENABLE __HAL_RCC_TIM20_CLK_ENABLE -#define __TIM20_CLK_DISABLE __HAL_RCC_TIM20_CLK_DISABLE -#define __HRTIM1_CLK_ENABLE __HAL_RCC_HRTIM1_CLK_ENABLE -#define __HRTIM1_CLK_DISABLE __HAL_RCC_HRTIM1_CLK_DISABLE -#define __SDADC1_CLK_ENABLE __HAL_RCC_SDADC1_CLK_ENABLE -#define __SDADC2_CLK_ENABLE __HAL_RCC_SDADC2_CLK_ENABLE -#define __SDADC3_CLK_ENABLE __HAL_RCC_SDADC3_CLK_ENABLE -#define __SDADC1_CLK_DISABLE __HAL_RCC_SDADC1_CLK_DISABLE -#define __SDADC2_CLK_DISABLE __HAL_RCC_SDADC2_CLK_DISABLE -#define __SDADC3_CLK_DISABLE __HAL_RCC_SDADC3_CLK_DISABLE - -#define __ADC12_FORCE_RESET __HAL_RCC_ADC12_FORCE_RESET -#define __ADC12_RELEASE_RESET __HAL_RCC_ADC12_RELEASE_RESET -#define __ADC34_FORCE_RESET __HAL_RCC_ADC34_FORCE_RESET -#define __ADC34_RELEASE_RESET __HAL_RCC_ADC34_RELEASE_RESET -#define __DAC2_FORCE_RESET __HAL_RCC_DAC2_FORCE_RESET -#define __DAC2_RELEASE_RESET __HAL_RCC_DAC2_RELEASE_RESET -#define __TIM18_FORCE_RESET __HAL_RCC_TIM18_FORCE_RESET -#define __TIM18_RELEASE_RESET __HAL_RCC_TIM18_RELEASE_RESET -#define __TIM19_FORCE_RESET __HAL_RCC_TIM19_FORCE_RESET -#define __TIM19_RELEASE_RESET __HAL_RCC_TIM19_RELEASE_RESET -#define __TIM20_FORCE_RESET __HAL_RCC_TIM20_FORCE_RESET -#define __TIM20_RELEASE_RESET __HAL_RCC_TIM20_RELEASE_RESET -#define __HRTIM1_FORCE_RESET __HAL_RCC_HRTIM1_FORCE_RESET -#define __HRTIM1_RELEASE_RESET __HAL_RCC_HRTIM1_RELEASE_RESET -#define __SDADC1_FORCE_RESET __HAL_RCC_SDADC1_FORCE_RESET -#define __SDADC2_FORCE_RESET __HAL_RCC_SDADC2_FORCE_RESET -#define __SDADC3_FORCE_RESET __HAL_RCC_SDADC3_FORCE_RESET -#define __SDADC1_RELEASE_RESET __HAL_RCC_SDADC1_RELEASE_RESET -#define __SDADC2_RELEASE_RESET __HAL_RCC_SDADC2_RELEASE_RESET -#define __SDADC3_RELEASE_RESET __HAL_RCC_SDADC3_RELEASE_RESET - -#define __ADC1_IS_CLK_ENABLED __HAL_RCC_ADC1_IS_CLK_ENABLED -#define __ADC1_IS_CLK_DISABLED __HAL_RCC_ADC1_IS_CLK_DISABLED -#define __ADC12_IS_CLK_ENABLED __HAL_RCC_ADC12_IS_CLK_ENABLED -#define __ADC12_IS_CLK_DISABLED __HAL_RCC_ADC12_IS_CLK_DISABLED -#define __ADC34_IS_CLK_ENABLED __HAL_RCC_ADC34_IS_CLK_ENABLED -#define __ADC34_IS_CLK_DISABLED __HAL_RCC_ADC34_IS_CLK_DISABLED -#define __CEC_IS_CLK_ENABLED __HAL_RCC_CEC_IS_CLK_ENABLED -#define __CEC_IS_CLK_DISABLED __HAL_RCC_CEC_IS_CLK_DISABLED -#define __CRC_IS_CLK_ENABLED __HAL_RCC_CRC_IS_CLK_ENABLED -#define __CRC_IS_CLK_DISABLED __HAL_RCC_CRC_IS_CLK_DISABLED -#define __DAC1_IS_CLK_ENABLED __HAL_RCC_DAC1_IS_CLK_ENABLED -#define __DAC1_IS_CLK_DISABLED __HAL_RCC_DAC1_IS_CLK_DISABLED -#define __DAC2_IS_CLK_ENABLED __HAL_RCC_DAC2_IS_CLK_ENABLED -#define __DAC2_IS_CLK_DISABLED __HAL_RCC_DAC2_IS_CLK_DISABLED -#define __DMA1_IS_CLK_ENABLED __HAL_RCC_DMA1_IS_CLK_ENABLED -#define __DMA1_IS_CLK_DISABLED __HAL_RCC_DMA1_IS_CLK_DISABLED -#define __DMA2_IS_CLK_ENABLED __HAL_RCC_DMA2_IS_CLK_ENABLED -#define __DMA2_IS_CLK_DISABLED __HAL_RCC_DMA2_IS_CLK_DISABLED -#define __FLITF_IS_CLK_ENABLED __HAL_RCC_FLITF_IS_CLK_ENABLED -#define __FLITF_IS_CLK_DISABLED __HAL_RCC_FLITF_IS_CLK_DISABLED -#define __FMC_IS_CLK_ENABLED __HAL_RCC_FMC_IS_CLK_ENABLED -#define __FMC_IS_CLK_DISABLED __HAL_RCC_FMC_IS_CLK_DISABLED -#define __GPIOA_IS_CLK_ENABLED __HAL_RCC_GPIOA_IS_CLK_ENABLED -#define __GPIOA_IS_CLK_DISABLED __HAL_RCC_GPIOA_IS_CLK_DISABLED -#define __GPIOB_IS_CLK_ENABLED __HAL_RCC_GPIOB_IS_CLK_ENABLED -#define __GPIOB_IS_CLK_DISABLED __HAL_RCC_GPIOB_IS_CLK_DISABLED -#define __GPIOC_IS_CLK_ENABLED __HAL_RCC_GPIOC_IS_CLK_ENABLED -#define __GPIOC_IS_CLK_DISABLED __HAL_RCC_GPIOC_IS_CLK_DISABLED -#define __GPIOD_IS_CLK_ENABLED __HAL_RCC_GPIOD_IS_CLK_ENABLED -#define __GPIOD_IS_CLK_DISABLED __HAL_RCC_GPIOD_IS_CLK_DISABLED -#define __GPIOE_IS_CLK_ENABLED __HAL_RCC_GPIOE_IS_CLK_ENABLED -#define __GPIOE_IS_CLK_DISABLED __HAL_RCC_GPIOE_IS_CLK_DISABLED -#define __GPIOF_IS_CLK_ENABLED __HAL_RCC_GPIOF_IS_CLK_ENABLED -#define __GPIOF_IS_CLK_DISABLED __HAL_RCC_GPIOF_IS_CLK_DISABLED -#define __GPIOG_IS_CLK_ENABLED __HAL_RCC_GPIOG_IS_CLK_ENABLED -#define __GPIOG_IS_CLK_DISABLED __HAL_RCC_GPIOG_IS_CLK_DISABLED -#define __GPIOH_IS_CLK_ENABLED __HAL_RCC_GPIOH_IS_CLK_ENABLED -#define __GPIOH_IS_CLK_DISABLED __HAL_RCC_GPIOH_IS_CLK_DISABLED -#define __HRTIM1_IS_CLK_ENABLED __HAL_RCC_HRTIM1_IS_CLK_ENABLED -#define __HRTIM1_IS_CLK_DISABLED __HAL_RCC_HRTIM1_IS_CLK_DISABLED -#define __I2C1_IS_CLK_ENABLED __HAL_RCC_I2C1_IS_CLK_ENABLED -#define __I2C1_IS_CLK_DISABLED __HAL_RCC_I2C1_IS_CLK_DISABLED -#define __I2C2_IS_CLK_ENABLED __HAL_RCC_I2C2_IS_CLK_ENABLED -#define __I2C2_IS_CLK_DISABLED __HAL_RCC_I2C2_IS_CLK_DISABLED -#define __I2C3_IS_CLK_ENABLED __HAL_RCC_I2C3_IS_CLK_ENABLED -#define __I2C3_IS_CLK_DISABLED __HAL_RCC_I2C3_IS_CLK_DISABLED -#define __PWR_IS_CLK_ENABLED __HAL_RCC_PWR_IS_CLK_ENABLED -#define __PWR_IS_CLK_DISABLED __HAL_RCC_PWR_IS_CLK_DISABLED -#define __SYSCFG_IS_CLK_ENABLED __HAL_RCC_SYSCFG_IS_CLK_ENABLED -#define __SYSCFG_IS_CLK_DISABLED __HAL_RCC_SYSCFG_IS_CLK_DISABLED -#define __SPI1_IS_CLK_ENABLED __HAL_RCC_SPI1_IS_CLK_ENABLED -#define __SPI1_IS_CLK_DISABLED __HAL_RCC_SPI1_IS_CLK_DISABLED -#define __SPI2_IS_CLK_ENABLED __HAL_RCC_SPI2_IS_CLK_ENABLED -#define __SPI2_IS_CLK_DISABLED __HAL_RCC_SPI2_IS_CLK_DISABLED -#define __SPI3_IS_CLK_ENABLED __HAL_RCC_SPI3_IS_CLK_ENABLED -#define __SPI3_IS_CLK_DISABLED __HAL_RCC_SPI3_IS_CLK_DISABLED -#define __SPI4_IS_CLK_ENABLED __HAL_RCC_SPI4_IS_CLK_ENABLED -#define __SPI4_IS_CLK_DISABLED __HAL_RCC_SPI4_IS_CLK_DISABLED -#define __SDADC1_IS_CLK_ENABLED __HAL_RCC_SDADC1_IS_CLK_ENABLED -#define __SDADC1_IS_CLK_DISABLED __HAL_RCC_SDADC1_IS_CLK_DISABLED -#define __SDADC2_IS_CLK_ENABLED __HAL_RCC_SDADC2_IS_CLK_ENABLED -#define __SDADC2_IS_CLK_DISABLED __HAL_RCC_SDADC2_IS_CLK_DISABLED -#define __SDADC3_IS_CLK_ENABLED __HAL_RCC_SDADC3_IS_CLK_ENABLED -#define __SDADC3_IS_CLK_DISABLED __HAL_RCC_SDADC3_IS_CLK_DISABLED -#define __SRAM_IS_CLK_ENABLED __HAL_RCC_SRAM_IS_CLK_ENABLED -#define __SRAM_IS_CLK_DISABLED __HAL_RCC_SRAM_IS_CLK_DISABLED -#define __TIM1_IS_CLK_ENABLED __HAL_RCC_TIM1_IS_CLK_ENABLED -#define __TIM1_IS_CLK_DISABLED __HAL_RCC_TIM1_IS_CLK_DISABLED -#define __TIM2_IS_CLK_ENABLED __HAL_RCC_TIM2_IS_CLK_ENABLED -#define __TIM2_IS_CLK_DISABLED __HAL_RCC_TIM2_IS_CLK_DISABLED -#define __TIM3_IS_CLK_ENABLED __HAL_RCC_TIM3_IS_CLK_ENABLED -#define __TIM3_IS_CLK_DISABLED __HAL_RCC_TIM3_IS_CLK_DISABLED -#define __TIM4_IS_CLK_ENABLED __HAL_RCC_TIM4_IS_CLK_ENABLED -#define __TIM4_IS_CLK_DISABLED __HAL_RCC_TIM4_IS_CLK_DISABLED -#define __TIM5_IS_CLK_ENABLED __HAL_RCC_TIM5_IS_CLK_ENABLED -#define __TIM5_IS_CLK_DISABLED __HAL_RCC_TIM5_IS_CLK_DISABLED -#define __TIM6_IS_CLK_ENABLED __HAL_RCC_TIM6_IS_CLK_ENABLED -#define __TIM6_IS_CLK_DISABLED __HAL_RCC_TIM6_IS_CLK_DISABLED -#define __TIM7_IS_CLK_ENABLED __HAL_RCC_TIM7_IS_CLK_ENABLED -#define __TIM7_IS_CLK_DISABLED __HAL_RCC_TIM7_IS_CLK_DISABLED -#define __TIM8_IS_CLK_ENABLED __HAL_RCC_TIM8_IS_CLK_ENABLED -#define __TIM8_IS_CLK_DISABLED __HAL_RCC_TIM8_IS_CLK_DISABLED -#define __TIM12_IS_CLK_ENABLED __HAL_RCC_TIM12_IS_CLK_ENABLED -#define __TIM12_IS_CLK_DISABLED __HAL_RCC_TIM12_IS_CLK_DISABLED -#define __TIM13_IS_CLK_ENABLED __HAL_RCC_TIM13_IS_CLK_ENABLED -#define __TIM13_IS_CLK_DISABLED __HAL_RCC_TIM13_IS_CLK_DISABLED -#define __TIM14_IS_CLK_ENABLED __HAL_RCC_TIM14_IS_CLK_ENABLED -#define __TIM14_IS_CLK_DISABLED __HAL_RCC_TIM14_IS_CLK_DISABLED -#define __TIM15_IS_CLK_ENABLED __HAL_RCC_TIM15_IS_CLK_ENABLED -#define __TIM15_IS_CLK_DISABLED __HAL_RCC_TIM15_IS_CLK_DISABLED -#define __TIM16_IS_CLK_ENABLED __HAL_RCC_TIM16_IS_CLK_ENABLED -#define __TIM16_IS_CLK_DISABLED __HAL_RCC_TIM16_IS_CLK_DISABLED -#define __TIM17_IS_CLK_ENABLED __HAL_RCC_TIM17_IS_CLK_ENABLED -#define __TIM17_IS_CLK_DISABLED __HAL_RCC_TIM17_IS_CLK_DISABLED -#define __TIM18_IS_CLK_ENABLED __HAL_RCC_TIM18_IS_CLK_ENABLED -#define __TIM18_IS_CLK_DISABLED __HAL_RCC_TIM18_IS_CLK_DISABLED -#define __TIM19_IS_CLK_ENABLED __HAL_RCC_TIM19_IS_CLK_ENABLED -#define __TIM19_IS_CLK_DISABLED __HAL_RCC_TIM19_IS_CLK_DISABLED -#define __TIM20_IS_CLK_ENABLED __HAL_RCC_TIM20_IS_CLK_ENABLED -#define __TIM20_IS_CLK_DISABLED __HAL_RCC_TIM20_IS_CLK_DISABLED -#define __TSC_IS_CLK_ENABLED __HAL_RCC_TSC_IS_CLK_ENABLED -#define __TSC_IS_CLK_DISABLED __HAL_RCC_TSC_IS_CLK_DISABLED -#define __UART4_IS_CLK_ENABLED __HAL_RCC_UART4_IS_CLK_ENABLED -#define __UART4_IS_CLK_DISABLED __HAL_RCC_UART4_IS_CLK_DISABLED -#define __UART5_IS_CLK_ENABLED __HAL_RCC_UART5_IS_CLK_ENABLED -#define __UART5_IS_CLK_DISABLED __HAL_RCC_UART5_IS_CLK_DISABLED -#define __USART1_IS_CLK_ENABLED __HAL_RCC_USART1_IS_CLK_ENABLED -#define __USART1_IS_CLK_DISABLED __HAL_RCC_USART1_IS_CLK_DISABLED -#define __USART2_IS_CLK_ENABLED __HAL_RCC_USART2_IS_CLK_ENABLED -#define __USART2_IS_CLK_DISABLED __HAL_RCC_USART2_IS_CLK_DISABLED -#define __USART3_IS_CLK_ENABLED __HAL_RCC_USART3_IS_CLK_ENABLED -#define __USART3_IS_CLK_DISABLED __HAL_RCC_USART3_IS_CLK_DISABLED -#define __USB_IS_CLK_ENABLED __HAL_RCC_USB_IS_CLK_ENABLED -#define __USB_IS_CLK_DISABLED __HAL_RCC_USB_IS_CLK_DISABLED -#define __WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG_IS_CLK_ENABLED -#define __WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG_IS_CLK_DISABLED - -#if defined(STM32L1) -#define __HAL_RCC_CRYP_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE -#define __HAL_RCC_CRYP_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE -#define __HAL_RCC_CRYP_FORCE_RESET __HAL_RCC_AES_FORCE_RESET -#define __HAL_RCC_CRYP_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET -#endif /* STM32L1 */ - -#if defined(STM32F4) -#define __HAL_RCC_SDMMC1_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET -#define __HAL_RCC_SDMMC1_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET -#define __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE -#define __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE -#define __HAL_RCC_SDMMC1_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE -#define __HAL_RCC_SDMMC1_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE -#define __HAL_RCC_SDMMC1_IS_CLK_ENABLED __HAL_RCC_SDIO_IS_CLK_ENABLED -#define __HAL_RCC_SDMMC1_IS_CLK_DISABLED __HAL_RCC_SDIO_IS_CLK_DISABLED -#define Sdmmc1ClockSelection SdioClockSelection -#define RCC_PERIPHCLK_SDMMC1 RCC_PERIPHCLK_SDIO -#define RCC_SDMMC1CLKSOURCE_CLK48 RCC_SDIOCLKSOURCE_CK48 -#define RCC_SDMMC1CLKSOURCE_SYSCLK RCC_SDIOCLKSOURCE_SYSCLK -#define __HAL_RCC_SDMMC1_CONFIG __HAL_RCC_SDIO_CONFIG -#define __HAL_RCC_GET_SDMMC1_SOURCE __HAL_RCC_GET_SDIO_SOURCE -#endif - -#if defined(STM32F7) || defined(STM32L4) -#define __HAL_RCC_SDIO_FORCE_RESET __HAL_RCC_SDMMC1_FORCE_RESET -#define __HAL_RCC_SDIO_RELEASE_RESET __HAL_RCC_SDMMC1_RELEASE_RESET -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE -#define __HAL_RCC_SDIO_CLK_ENABLE __HAL_RCC_SDMMC1_CLK_ENABLE -#define __HAL_RCC_SDIO_CLK_DISABLE __HAL_RCC_SDMMC1_CLK_DISABLE -#define __HAL_RCC_SDIO_IS_CLK_ENABLED __HAL_RCC_SDMMC1_IS_CLK_ENABLED -#define __HAL_RCC_SDIO_IS_CLK_DISABLED __HAL_RCC_SDMMC1_IS_CLK_DISABLED -#define SdioClockSelection Sdmmc1ClockSelection -#define RCC_PERIPHCLK_SDIO RCC_PERIPHCLK_SDMMC1 -#define __HAL_RCC_SDIO_CONFIG __HAL_RCC_SDMMC1_CONFIG -#define __HAL_RCC_GET_SDIO_SOURCE __HAL_RCC_GET_SDMMC1_SOURCE -#endif - -#if defined(STM32F7) -#define RCC_SDIOCLKSOURCE_CLK48 RCC_SDMMC1CLKSOURCE_CLK48 -#define RCC_SDIOCLKSOURCE_SYSCLK RCC_SDMMC1CLKSOURCE_SYSCLK -#endif - -#if defined(STM32H7) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() __HAL_RCC_USB1_OTG_HS_FORCE_RESET() -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() __HAL_RCC_USB1_OTG_HS_RELEASE_RESET() -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_DISABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_DISABLE() - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() __HAL_RCC_USB2_OTG_FS_FORCE_RESET() -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() __HAL_RCC_USB2_OTG_FS_RELEASE_RESET() -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_DISABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_DISABLE() -#endif - -#define __HAL_RCC_I2SCLK __HAL_RCC_I2S_CONFIG -#define __HAL_RCC_I2SCLK_CONFIG __HAL_RCC_I2S_CONFIG - -#define __RCC_PLLSRC RCC_GET_PLL_OSCSOURCE - -#define IS_RCC_MSIRANGE IS_RCC_MSI_CLOCK_RANGE -#define IS_RCC_RTCCLK_SOURCE IS_RCC_RTCCLKSOURCE -#define IS_RCC_SYSCLK_DIV IS_RCC_HCLK -#define IS_RCC_HCLK_DIV IS_RCC_PCLK -#define IS_RCC_PERIPHCLK IS_RCC_PERIPHCLOCK - -#define RCC_IT_HSI14 RCC_IT_HSI14RDY - -#define RCC_IT_CSSLSE RCC_IT_LSECSS -#define RCC_IT_CSSHSE RCC_IT_CSS - -#define RCC_PLLMUL_3 RCC_PLL_MUL3 -#define RCC_PLLMUL_4 RCC_PLL_MUL4 -#define RCC_PLLMUL_6 RCC_PLL_MUL6 -#define RCC_PLLMUL_8 RCC_PLL_MUL8 -#define RCC_PLLMUL_12 RCC_PLL_MUL12 -#define RCC_PLLMUL_16 RCC_PLL_MUL16 -#define RCC_PLLMUL_24 RCC_PLL_MUL24 -#define RCC_PLLMUL_32 RCC_PLL_MUL32 -#define RCC_PLLMUL_48 RCC_PLL_MUL48 - -#define RCC_PLLDIV_2 RCC_PLL_DIV2 -#define RCC_PLLDIV_3 RCC_PLL_DIV3 -#define RCC_PLLDIV_4 RCC_PLL_DIV4 - -#define IS_RCC_MCOSOURCE IS_RCC_MCO1SOURCE -#define __HAL_RCC_MCO_CONFIG __HAL_RCC_MCO1_CONFIG -#define RCC_MCO_NODIV RCC_MCODIV_1 -#define RCC_MCO_DIV1 RCC_MCODIV_1 -#define RCC_MCO_DIV2 RCC_MCODIV_2 -#define RCC_MCO_DIV4 RCC_MCODIV_4 -#define RCC_MCO_DIV8 RCC_MCODIV_8 -#define RCC_MCO_DIV16 RCC_MCODIV_16 -#define RCC_MCO_DIV32 RCC_MCODIV_32 -#define RCC_MCO_DIV64 RCC_MCODIV_64 -#define RCC_MCO_DIV128 RCC_MCODIV_128 -#define RCC_MCOSOURCE_NONE RCC_MCO1SOURCE_NOCLOCK -#define RCC_MCOSOURCE_LSI RCC_MCO1SOURCE_LSI -#define RCC_MCOSOURCE_LSE RCC_MCO1SOURCE_LSE -#define RCC_MCOSOURCE_SYSCLK RCC_MCO1SOURCE_SYSCLK -#define RCC_MCOSOURCE_HSI RCC_MCO1SOURCE_HSI -#define RCC_MCOSOURCE_HSI14 RCC_MCO1SOURCE_HSI14 -#define RCC_MCOSOURCE_HSI48 RCC_MCO1SOURCE_HSI48 -#define RCC_MCOSOURCE_HSE RCC_MCO1SOURCE_HSE -#define RCC_MCOSOURCE_PLLCLK_DIV1 RCC_MCO1SOURCE_PLLCLK -#define RCC_MCOSOURCE_PLLCLK_NODIV RCC_MCO1SOURCE_PLLCLK -#define RCC_MCOSOURCE_PLLCLK_DIV2 RCC_MCO1SOURCE_PLLCLK_DIV2 - -#if defined(STM32L4) || defined(STM32WB) || defined(STM32G0) || defined(STM32G4) || defined(STM32L5) || defined(STM32WL) -#define RCC_RTCCLKSOURCE_NO_CLK RCC_RTCCLKSOURCE_NONE -#else -#define RCC_RTCCLKSOURCE_NONE RCC_RTCCLKSOURCE_NO_CLK -#endif - -#define RCC_USBCLK_PLLSAI1 RCC_USBCLKSOURCE_PLLSAI1 -#define RCC_USBCLK_PLL RCC_USBCLKSOURCE_PLL -#define RCC_USBCLK_MSI RCC_USBCLKSOURCE_MSI -#define RCC_USBCLKSOURCE_PLLCLK RCC_USBCLKSOURCE_PLL -#define RCC_USBPLLCLK_DIV1 RCC_USBCLKSOURCE_PLL -#define RCC_USBPLLCLK_DIV1_5 RCC_USBCLKSOURCE_PLL_DIV1_5 -#define RCC_USBPLLCLK_DIV2 RCC_USBCLKSOURCE_PLL_DIV2 -#define RCC_USBPLLCLK_DIV3 RCC_USBCLKSOURCE_PLL_DIV3 - -#define HSION_BitNumber RCC_HSION_BIT_NUMBER -#define HSION_BITNUMBER RCC_HSION_BIT_NUMBER -#define HSEON_BitNumber RCC_HSEON_BIT_NUMBER -#define HSEON_BITNUMBER RCC_HSEON_BIT_NUMBER -#define MSION_BITNUMBER RCC_MSION_BIT_NUMBER -#define CSSON_BitNumber RCC_CSSON_BIT_NUMBER -#define CSSON_BITNUMBER RCC_CSSON_BIT_NUMBER -#define PLLON_BitNumber RCC_PLLON_BIT_NUMBER -#define PLLON_BITNUMBER RCC_PLLON_BIT_NUMBER -#define PLLI2SON_BitNumber RCC_PLLI2SON_BIT_NUMBER -#define I2SSRC_BitNumber RCC_I2SSRC_BIT_NUMBER -#define RTCEN_BitNumber RCC_RTCEN_BIT_NUMBER -#define RTCEN_BITNUMBER RCC_RTCEN_BIT_NUMBER -#define BDRST_BitNumber RCC_BDRST_BIT_NUMBER -#define BDRST_BITNUMBER RCC_BDRST_BIT_NUMBER -#define RTCRST_BITNUMBER RCC_RTCRST_BIT_NUMBER -#define LSION_BitNumber RCC_LSION_BIT_NUMBER -#define LSION_BITNUMBER RCC_LSION_BIT_NUMBER -#define LSEON_BitNumber RCC_LSEON_BIT_NUMBER -#define LSEON_BITNUMBER RCC_LSEON_BIT_NUMBER -#define LSEBYP_BITNUMBER RCC_LSEBYP_BIT_NUMBER -#define PLLSAION_BitNumber RCC_PLLSAION_BIT_NUMBER -#define TIMPRE_BitNumber RCC_TIMPRE_BIT_NUMBER -#define RMVF_BitNumber RCC_RMVF_BIT_NUMBER -#define RMVF_BITNUMBER RCC_RMVF_BIT_NUMBER -#define RCC_CR2_HSI14TRIM_BitNumber RCC_HSI14TRIM_BIT_NUMBER -#define CR_BYTE2_ADDRESS RCC_CR_BYTE2_ADDRESS -#define CIR_BYTE1_ADDRESS RCC_CIR_BYTE1_ADDRESS -#define CIR_BYTE2_ADDRESS RCC_CIR_BYTE2_ADDRESS -#define BDCR_BYTE0_ADDRESS RCC_BDCR_BYTE0_ADDRESS -#define DBP_TIMEOUT_VALUE RCC_DBP_TIMEOUT_VALUE -#define LSE_TIMEOUT_VALUE RCC_LSE_TIMEOUT_VALUE - -#define CR_HSION_BB RCC_CR_HSION_BB -#define CR_CSSON_BB RCC_CR_CSSON_BB -#define CR_PLLON_BB RCC_CR_PLLON_BB -#define CR_PLLI2SON_BB RCC_CR_PLLI2SON_BB -#define CR_MSION_BB RCC_CR_MSION_BB -#define CSR_LSION_BB RCC_CSR_LSION_BB -#define CSR_LSEON_BB RCC_CSR_LSEON_BB -#define CSR_LSEBYP_BB RCC_CSR_LSEBYP_BB -#define CSR_RTCEN_BB RCC_CSR_RTCEN_BB -#define CSR_RTCRST_BB RCC_CSR_RTCRST_BB -#define CFGR_I2SSRC_BB RCC_CFGR_I2SSRC_BB -#define BDCR_RTCEN_BB RCC_BDCR_RTCEN_BB -#define BDCR_BDRST_BB RCC_BDCR_BDRST_BB -#define CR_HSEON_BB RCC_CR_HSEON_BB -#define CSR_RMVF_BB RCC_CSR_RMVF_BB -#define CR_PLLSAION_BB RCC_CR_PLLSAION_BB -#define DCKCFGR_TIMPRE_BB RCC_DCKCFGR_TIMPRE_BB - -#define __HAL_RCC_CRS_ENABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_ENABLE -#define __HAL_RCC_CRS_DISABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_DISABLE -#define __HAL_RCC_CRS_ENABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_ENABLE -#define __HAL_RCC_CRS_DISABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_DISABLE -#define __HAL_RCC_CRS_CALCULATE_RELOADVALUE __HAL_RCC_CRS_RELOADVALUE_CALCULATE - -#define __HAL_RCC_GET_IT_SOURCE __HAL_RCC_GET_IT - -#define RCC_CRS_SYNCWARM RCC_CRS_SYNCWARN -#define RCC_CRS_TRIMOV RCC_CRS_TRIMOVF - -#define RCC_PERIPHCLK_CK48 RCC_PERIPHCLK_CLK48 -#define RCC_CK48CLKSOURCE_PLLQ RCC_CLK48CLKSOURCE_PLLQ -#define RCC_CK48CLKSOURCE_PLLSAIP RCC_CLK48CLKSOURCE_PLLSAIP -#define RCC_CK48CLKSOURCE_PLLI2SQ RCC_CLK48CLKSOURCE_PLLI2SQ -#define IS_RCC_CK48CLKSOURCE IS_RCC_CLK48CLKSOURCE -#define RCC_SDIOCLKSOURCE_CK48 RCC_SDIOCLKSOURCE_CLK48 - -#define __HAL_RCC_DFSDM_CLK_ENABLE __HAL_RCC_DFSDM1_CLK_ENABLE -#define __HAL_RCC_DFSDM_CLK_DISABLE __HAL_RCC_DFSDM1_CLK_DISABLE -#define __HAL_RCC_DFSDM_IS_CLK_ENABLED __HAL_RCC_DFSDM1_IS_CLK_ENABLED -#define __HAL_RCC_DFSDM_IS_CLK_DISABLED __HAL_RCC_DFSDM1_IS_CLK_DISABLED -#define __HAL_RCC_DFSDM_FORCE_RESET __HAL_RCC_DFSDM1_FORCE_RESET -#define __HAL_RCC_DFSDM_RELEASE_RESET __HAL_RCC_DFSDM1_RELEASE_RESET -#define __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE -#define __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE -#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_ENABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_DISABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_DISABLED -#define DfsdmClockSelection Dfsdm1ClockSelection -#define RCC_PERIPHCLK_DFSDM RCC_PERIPHCLK_DFSDM1 -#define RCC_DFSDMCLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_DFSDMCLKSOURCE_SYSCLK RCC_DFSDM1CLKSOURCE_SYSCLK -#define __HAL_RCC_DFSDM_CONFIG __HAL_RCC_DFSDM1_CONFIG -#define __HAL_RCC_GET_DFSDM_SOURCE __HAL_RCC_GET_DFSDM1_SOURCE -#define RCC_DFSDM1CLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_SWPMI1CLKSOURCE_PCLK RCC_SWPMI1CLKSOURCE_PCLK1 -#define RCC_LPTIM1CLKSOURCE_PCLK RCC_LPTIM1CLKSOURCE_PCLK1 -#define RCC_LPTIM2CLKSOURCE_PCLK RCC_LPTIM2CLKSOURCE_PCLK1 - -#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM1AUDIOCLKSOURCE_I2S1 -#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM1AUDIOCLKSOURCE_I2S2 -#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM2AUDIOCLKSOURCE_I2S1 -#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM2AUDIOCLKSOURCE_I2S2 -#define RCC_DFSDM1CLKSOURCE_APB2 RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_DFSDM2CLKSOURCE_APB2 RCC_DFSDM2CLKSOURCE_PCLK2 -#define RCC_FMPI2C1CLKSOURCE_APB RCC_FMPI2C1CLKSOURCE_PCLK1 -#if defined(STM32U5) -#define MSIKPLLModeSEL RCC_MSIKPLL_MODE_SEL -#define MSISPLLModeSEL RCC_MSISPLL_MODE_SEL -#define __HAL_RCC_AHB21_CLK_DISABLE __HAL_RCC_AHB2_1_CLK_DISABLE -#define __HAL_RCC_AHB22_CLK_DISABLE __HAL_RCC_AHB2_2_CLK_DISABLE -#define __HAL_RCC_AHB1_CLK_Disable_Clear __HAL_RCC_AHB1_CLK_ENABLE -#define __HAL_RCC_AHB21_CLK_Disable_Clear __HAL_RCC_AHB2_1_CLK_ENABLE -#define __HAL_RCC_AHB22_CLK_Disable_Clear __HAL_RCC_AHB2_2_CLK_ENABLE -#define __HAL_RCC_AHB3_CLK_Disable_Clear __HAL_RCC_AHB3_CLK_ENABLE -#define __HAL_RCC_APB1_CLK_Disable_Clear __HAL_RCC_APB1_CLK_ENABLE -#define __HAL_RCC_APB2_CLK_Disable_Clear __HAL_RCC_APB2_CLK_ENABLE -#define __HAL_RCC_APB3_CLK_Disable_Clear __HAL_RCC_APB3_CLK_ENABLE -#define IS_RCC_MSIPLLModeSelection IS_RCC_MSIPLLMODE_SELECT -#endif -/** - * @} - */ - -/** @defgroup HAL_RNG_Aliased_Macros HAL RNG Aliased Macros maintained for legacy purpose - * @{ - */ -#define HAL_RNG_ReadyCallback(__HANDLE__) HAL_RNG_ReadyDataCallback((__HANDLE__), uint32_t random32bit) - -/** - * @} - */ - -/** @defgroup HAL_RTC_Aliased_Macros HAL RTC Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined (STM32G0) || defined (STM32L5) || defined (STM32L412xx) || defined (STM32L422xx) || defined (STM32L4P5xx) || defined (STM32L4Q5xx) || defined (STM32G4) || defined (STM32WL) || defined (STM32U5) -#else -#define __HAL_RTC_CLEAR_FLAG __HAL_RTC_EXTI_CLEAR_FLAG -#endif -#define __HAL_RTC_DISABLE_IT __HAL_RTC_EXTI_DISABLE_IT -#define __HAL_RTC_ENABLE_IT __HAL_RTC_EXTI_ENABLE_IT - -#if defined (STM32F1) -#define __HAL_RTC_EXTI_CLEAR_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() - -#define __HAL_RTC_EXTI_ENABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_ENABLE_IT() - -#define __HAL_RTC_EXTI_DISABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_DISABLE_IT() - -#define __HAL_RTC_EXTI_GET_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GET_FLAG() - -#define __HAL_RTC_EXTI_GENERATE_SWIT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() -#else -#define __HAL_RTC_EXTI_CLEAR_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG())) -#define __HAL_RTC_EXTI_ENABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_ENABLE_IT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT())) -#define __HAL_RTC_EXTI_DISABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_DISABLE_IT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_IT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_IT())) -#define __HAL_RTC_EXTI_GET_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GET_FLAG() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GET_FLAG() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG())) -#define __HAL_RTC_EXTI_GENERATE_SWIT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GENERATE_SWIT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT())) -#endif /* STM32F1 */ - -#define IS_ALARM IS_RTC_ALARM -#define IS_ALARM_MASK IS_RTC_ALARM_MASK -#define IS_TAMPER IS_RTC_TAMPER -#define IS_TAMPER_ERASE_MODE IS_RTC_TAMPER_ERASE_MODE -#define IS_TAMPER_FILTER IS_RTC_TAMPER_FILTER -#define IS_TAMPER_INTERRUPT IS_RTC_TAMPER_INTERRUPT -#define IS_TAMPER_MASKFLAG_STATE IS_RTC_TAMPER_MASKFLAG_STATE -#define IS_TAMPER_PRECHARGE_DURATION IS_RTC_TAMPER_PRECHARGE_DURATION -#define IS_TAMPER_PULLUP_STATE IS_RTC_TAMPER_PULLUP_STATE -#define IS_TAMPER_SAMPLING_FREQ IS_RTC_TAMPER_SAMPLING_FREQ -#define IS_TAMPER_TIMESTAMPONTAMPER_DETECTION IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION -#define IS_TAMPER_TRIGGER IS_RTC_TAMPER_TRIGGER -#define IS_WAKEUP_CLOCK IS_RTC_WAKEUP_CLOCK -#define IS_WAKEUP_COUNTER IS_RTC_WAKEUP_COUNTER - -#define __RTC_WRITEPROTECTION_ENABLE __HAL_RTC_WRITEPROTECTION_ENABLE -#define __RTC_WRITEPROTECTION_DISABLE __HAL_RTC_WRITEPROTECTION_DISABLE - -/** - * @} - */ - -/** @defgroup HAL_SD_Aliased_Macros HAL SD/MMC Aliased Macros maintained for legacy purpose - * @{ - */ - -#define SD_OCR_CID_CSD_OVERWRIETE SD_OCR_CID_CSD_OVERWRITE -#define SD_CMD_SD_APP_STAUS SD_CMD_SD_APP_STATUS - -#if !defined(STM32F1) && !defined(STM32F2) && !defined(STM32F4) && !defined(STM32F7) && !defined(STM32L1) -#define eMMC_HIGH_VOLTAGE_RANGE EMMC_HIGH_VOLTAGE_RANGE -#define eMMC_DUAL_VOLTAGE_RANGE EMMC_DUAL_VOLTAGE_RANGE -#define eMMC_LOW_VOLTAGE_RANGE EMMC_LOW_VOLTAGE_RANGE - -#define SDMMC_NSpeed_CLK_DIV SDMMC_NSPEED_CLK_DIV -#define SDMMC_HSpeed_CLK_DIV SDMMC_HSPEED_CLK_DIV -#endif - -#if defined(STM32F4) || defined(STM32F2) -#define SD_SDMMC_DISABLED SD_SDIO_DISABLED -#define SD_SDMMC_FUNCTION_BUSY SD_SDIO_FUNCTION_BUSY -#define SD_SDMMC_FUNCTION_FAILED SD_SDIO_FUNCTION_FAILED -#define SD_SDMMC_UNKNOWN_FUNCTION SD_SDIO_UNKNOWN_FUNCTION -#define SD_CMD_SDMMC_SEN_OP_COND SD_CMD_SDIO_SEN_OP_COND -#define SD_CMD_SDMMC_RW_DIRECT SD_CMD_SDIO_RW_DIRECT -#define SD_CMD_SDMMC_RW_EXTENDED SD_CMD_SDIO_RW_EXTENDED -#define __HAL_SD_SDMMC_ENABLE __HAL_SD_SDIO_ENABLE -#define __HAL_SD_SDMMC_DISABLE __HAL_SD_SDIO_DISABLE -#define __HAL_SD_SDMMC_DMA_ENABLE __HAL_SD_SDIO_DMA_ENABLE -#define __HAL_SD_SDMMC_DMA_DISABLE __HAL_SD_SDIO_DMA_DISABL -#define __HAL_SD_SDMMC_ENABLE_IT __HAL_SD_SDIO_ENABLE_IT -#define __HAL_SD_SDMMC_DISABLE_IT __HAL_SD_SDIO_DISABLE_IT -#define __HAL_SD_SDMMC_GET_FLAG __HAL_SD_SDIO_GET_FLAG -#define __HAL_SD_SDMMC_CLEAR_FLAG __HAL_SD_SDIO_CLEAR_FLAG -#define __HAL_SD_SDMMC_GET_IT __HAL_SD_SDIO_GET_IT -#define __HAL_SD_SDMMC_CLEAR_IT __HAL_SD_SDIO_CLEAR_IT -#define SDMMC_STATIC_FLAGS SDIO_STATIC_FLAGS -#define SDMMC_CMD0TIMEOUT SDIO_CMD0TIMEOUT -#define SD_SDMMC_SEND_IF_COND SD_SDIO_SEND_IF_COND -/* alias CMSIS */ -#define SDMMC1_IRQn SDIO_IRQn -#define SDMMC1_IRQHandler SDIO_IRQHandler -#endif - -#if defined(STM32F7) || defined(STM32L4) -#define SD_SDIO_DISABLED SD_SDMMC_DISABLED -#define SD_SDIO_FUNCTION_BUSY SD_SDMMC_FUNCTION_BUSY -#define SD_SDIO_FUNCTION_FAILED SD_SDMMC_FUNCTION_FAILED -#define SD_SDIO_UNKNOWN_FUNCTION SD_SDMMC_UNKNOWN_FUNCTION -#define SD_CMD_SDIO_SEN_OP_COND SD_CMD_SDMMC_SEN_OP_COND -#define SD_CMD_SDIO_RW_DIRECT SD_CMD_SDMMC_RW_DIRECT -#define SD_CMD_SDIO_RW_EXTENDED SD_CMD_SDMMC_RW_EXTENDED -#define __HAL_SD_SDIO_ENABLE __HAL_SD_SDMMC_ENABLE -#define __HAL_SD_SDIO_DISABLE __HAL_SD_SDMMC_DISABLE -#define __HAL_SD_SDIO_DMA_ENABLE __HAL_SD_SDMMC_DMA_ENABLE -#define __HAL_SD_SDIO_DMA_DISABL __HAL_SD_SDMMC_DMA_DISABLE -#define __HAL_SD_SDIO_ENABLE_IT __HAL_SD_SDMMC_ENABLE_IT -#define __HAL_SD_SDIO_DISABLE_IT __HAL_SD_SDMMC_DISABLE_IT -#define __HAL_SD_SDIO_GET_FLAG __HAL_SD_SDMMC_GET_FLAG -#define __HAL_SD_SDIO_CLEAR_FLAG __HAL_SD_SDMMC_CLEAR_FLAG -#define __HAL_SD_SDIO_GET_IT __HAL_SD_SDMMC_GET_IT -#define __HAL_SD_SDIO_CLEAR_IT __HAL_SD_SDMMC_CLEAR_IT -#define SDIO_STATIC_FLAGS SDMMC_STATIC_FLAGS -#define SDIO_CMD0TIMEOUT SDMMC_CMD0TIMEOUT -#define SD_SDIO_SEND_IF_COND SD_SDMMC_SEND_IF_COND -/* alias CMSIS for compatibilities */ -#define SDIO_IRQn SDMMC1_IRQn -#define SDIO_IRQHandler SDMMC1_IRQHandler -#endif - -#if defined(STM32F7) || defined(STM32F4) || defined(STM32F2) || defined(STM32L4) || defined(STM32H7) -#define HAL_SD_CardCIDTypedef HAL_SD_CardCIDTypeDef -#define HAL_SD_CardCSDTypedef HAL_SD_CardCSDTypeDef -#define HAL_SD_CardStatusTypedef HAL_SD_CardStatusTypeDef -#define HAL_SD_CardStateTypedef HAL_SD_CardStateTypeDef -#endif - -#if defined(STM32H7) || defined(STM32L5) -#define HAL_MMCEx_Read_DMADoubleBuffer0CpltCallback HAL_MMCEx_Read_DMADoubleBuf0CpltCallback -#define HAL_MMCEx_Read_DMADoubleBuffer1CpltCallback HAL_MMCEx_Read_DMADoubleBuf1CpltCallback -#define HAL_MMCEx_Write_DMADoubleBuffer0CpltCallback HAL_MMCEx_Write_DMADoubleBuf0CpltCallback -#define HAL_MMCEx_Write_DMADoubleBuffer1CpltCallback HAL_MMCEx_Write_DMADoubleBuf1CpltCallback -#define HAL_SDEx_Read_DMADoubleBuffer0CpltCallback HAL_SDEx_Read_DMADoubleBuf0CpltCallback -#define HAL_SDEx_Read_DMADoubleBuffer1CpltCallback HAL_SDEx_Read_DMADoubleBuf1CpltCallback -#define HAL_SDEx_Write_DMADoubleBuffer0CpltCallback HAL_SDEx_Write_DMADoubleBuf0CpltCallback -#define HAL_SDEx_Write_DMADoubleBuffer1CpltCallback HAL_SDEx_Write_DMADoubleBuf1CpltCallback -#define HAL_SD_DriveTransciver_1_8V_Callback HAL_SD_DriveTransceiver_1_8V_Callback -#endif -/** - * @} - */ - -/** @defgroup HAL_SMARTCARD_Aliased_Macros HAL SMARTCARD Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __SMARTCARD_ENABLE_IT __HAL_SMARTCARD_ENABLE_IT -#define __SMARTCARD_DISABLE_IT __HAL_SMARTCARD_DISABLE_IT -#define __SMARTCARD_ENABLE __HAL_SMARTCARD_ENABLE -#define __SMARTCARD_DISABLE __HAL_SMARTCARD_DISABLE -#define __SMARTCARD_DMA_REQUEST_ENABLE __HAL_SMARTCARD_DMA_REQUEST_ENABLE -#define __SMARTCARD_DMA_REQUEST_DISABLE __HAL_SMARTCARD_DMA_REQUEST_DISABLE - -#define __HAL_SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE -#define __SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE - -#define IS_SMARTCARD_ONEBIT_SAMPLING IS_SMARTCARD_ONE_BIT_SAMPLE - -/** - * @} - */ - -/** @defgroup HAL_SMBUS_Aliased_Macros HAL SMBUS Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_SMBUS_RESET_CR1 SMBUS_RESET_CR1 -#define __HAL_SMBUS_RESET_CR2 SMBUS_RESET_CR2 -#define __HAL_SMBUS_GENERATE_START SMBUS_GENERATE_START -#define __HAL_SMBUS_GET_ADDR_MATCH SMBUS_GET_ADDR_MATCH -#define __HAL_SMBUS_GET_DIR SMBUS_GET_DIR -#define __HAL_SMBUS_GET_STOP_MODE SMBUS_GET_STOP_MODE -#define __HAL_SMBUS_GET_PEC_MODE SMBUS_GET_PEC_MODE -#define __HAL_SMBUS_GET_ALERT_ENABLED SMBUS_GET_ALERT_ENABLED -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Macros HAL SPI Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_SPI_1LINE_TX SPI_1LINE_TX -#define __HAL_SPI_1LINE_RX SPI_1LINE_RX -#define __HAL_SPI_RESET_CRC SPI_RESET_CRC - -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Macros HAL UART Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE -#define __HAL_UART_MASK_COMPUTATION UART_MASK_COMPUTATION -#define __UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE -#define __UART_MASK_COMPUTATION UART_MASK_COMPUTATION - -#define IS_UART_WAKEUPMETHODE IS_UART_WAKEUPMETHOD - -#define IS_UART_ONEBIT_SAMPLE IS_UART_ONE_BIT_SAMPLE -#define IS_UART_ONEBIT_SAMPLING IS_UART_ONE_BIT_SAMPLE - -/** - * @} - */ - - -/** @defgroup HAL_USART_Aliased_Macros HAL USART Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __USART_ENABLE_IT __HAL_USART_ENABLE_IT -#define __USART_DISABLE_IT __HAL_USART_DISABLE_IT -#define __USART_ENABLE __HAL_USART_ENABLE -#define __USART_DISABLE __HAL_USART_DISABLE - -#define __HAL_USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE -#define __USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE - -#if defined(STM32F0) || defined(STM32F3) || defined(STM32F7) -#define USART_OVERSAMPLING_16 0x00000000U -#define USART_OVERSAMPLING_8 USART_CR1_OVER8 - -#define IS_USART_OVERSAMPLING(__SAMPLING__) (((__SAMPLING__) == USART_OVERSAMPLING_16) || \ - ((__SAMPLING__) == USART_OVERSAMPLING_8)) -#endif /* STM32F0 || STM32F3 || STM32F7 */ -/** - * @} - */ - -/** @defgroup HAL_USB_Aliased_Macros HAL USB Aliased Macros maintained for legacy purpose - * @{ - */ -#define USB_EXTI_LINE_WAKEUP USB_WAKEUP_EXTI_LINE - -#define USB_FS_EXTI_TRIGGER_RISING_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_EDGE -#define USB_FS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_FS_WAKEUP_EXTI_FALLING_EDGE -#define USB_FS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_FALLING_EDGE -#define USB_FS_EXTI_LINE_WAKEUP USB_OTG_FS_WAKEUP_EXTI_LINE - -#define USB_HS_EXTI_TRIGGER_RISING_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_EDGE -#define USB_HS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_HS_WAKEUP_EXTI_FALLING_EDGE -#define USB_HS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_FALLING_EDGE -#define USB_HS_EXTI_LINE_WAKEUP USB_OTG_HS_WAKEUP_EXTI_LINE - -#define __HAL_USB_EXTI_ENABLE_IT __HAL_USB_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_EXTI_DISABLE_IT __HAL_USB_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_EXTI_GET_FLAG __HAL_USB_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_EXTI_CLEAR_FLAG __HAL_USB_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_EXTI_SET_RISING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_EXTI_SET_FALLING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE - -#define __HAL_USB_FS_EXTI_ENABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_FS_EXTI_DISABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_FS_EXTI_GET_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_FS_EXTI_CLEAR_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_FS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_FS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_FS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE -#define __HAL_USB_FS_EXTI_GENERATE_SWIT __HAL_USB_OTG_FS_WAKEUP_EXTI_GENERATE_SWIT - -#define __HAL_USB_HS_EXTI_ENABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_HS_EXTI_DISABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_HS_EXTI_GET_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_HS_EXTI_CLEAR_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_HS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_HS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_HS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE -#define __HAL_USB_HS_EXTI_GENERATE_SWIT __HAL_USB_OTG_HS_WAKEUP_EXTI_GENERATE_SWIT - -#define HAL_PCD_ActiveRemoteWakeup HAL_PCD_ActivateRemoteWakeup -#define HAL_PCD_DeActiveRemoteWakeup HAL_PCD_DeActivateRemoteWakeup - -#define HAL_PCD_SetTxFiFo HAL_PCDEx_SetTxFiFo -#define HAL_PCD_SetRxFiFo HAL_PCDEx_SetRxFiFo -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Macros HAL TIM Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_TIM_SetICPrescalerValue TIM_SET_ICPRESCALERVALUE -#define __HAL_TIM_ResetICPrescalerValue TIM_RESET_ICPRESCALERVALUE - -#define TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE -#define TIM_GET_CLEAR_IT __HAL_TIM_CLEAR_IT - -#define __HAL_TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE - -#define __HAL_TIM_DIRECTION_STATUS __HAL_TIM_IS_TIM_COUNTING_DOWN -#define __HAL_TIM_PRESCALER __HAL_TIM_SET_PRESCALER -#define __HAL_TIM_SetCounter __HAL_TIM_SET_COUNTER -#define __HAL_TIM_GetCounter __HAL_TIM_GET_COUNTER -#define __HAL_TIM_SetAutoreload __HAL_TIM_SET_AUTORELOAD -#define __HAL_TIM_GetAutoreload __HAL_TIM_GET_AUTORELOAD -#define __HAL_TIM_SetClockDivision __HAL_TIM_SET_CLOCKDIVISION -#define __HAL_TIM_GetClockDivision __HAL_TIM_GET_CLOCKDIVISION -#define __HAL_TIM_SetICPrescaler __HAL_TIM_SET_ICPRESCALER -#define __HAL_TIM_GetICPrescaler __HAL_TIM_GET_ICPRESCALER -#define __HAL_TIM_SetCompare __HAL_TIM_SET_COMPARE -#define __HAL_TIM_GetCompare __HAL_TIM_GET_COMPARE - -#define TIM_BREAKINPUTSOURCE_DFSDM TIM_BREAKINPUTSOURCE_DFSDM1 -/** - * @} - */ - -/** @defgroup HAL_ETH_Aliased_Macros HAL ETH Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_ETH_EXTI_ENABLE_IT __HAL_ETH_WAKEUP_EXTI_ENABLE_IT -#define __HAL_ETH_EXTI_DISABLE_IT __HAL_ETH_WAKEUP_EXTI_DISABLE_IT -#define __HAL_ETH_EXTI_GET_FLAG __HAL_ETH_WAKEUP_EXTI_GET_FLAG -#define __HAL_ETH_EXTI_CLEAR_FLAG __HAL_ETH_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_ETH_EXTI_SET_RISING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_RISING_EDGE_TRIGGER -#define __HAL_ETH_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLING_EDGE_TRIGGER -#define __HAL_ETH_EXTI_SET_FALLINGRISING_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLINGRISING_TRIGGER - -#define ETH_PROMISCIOUSMODE_ENABLE ETH_PROMISCUOUS_MODE_ENABLE -#define ETH_PROMISCIOUSMODE_DISABLE ETH_PROMISCUOUS_MODE_DISABLE -#define IS_ETH_PROMISCIOUS_MODE IS_ETH_PROMISCUOUS_MODE -/** - * @} - */ - -/** @defgroup HAL_LTDC_Aliased_Macros HAL LTDC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_LTDC_LAYER LTDC_LAYER -#define __HAL_LTDC_RELOAD_CONFIG __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG -/** - * @} - */ - -/** @defgroup HAL_SAI_Aliased_Macros HAL SAI Aliased Macros maintained for legacy purpose - * @{ - */ -#define SAI_OUTPUTDRIVE_DISABLED SAI_OUTPUTDRIVE_DISABLE -#define SAI_OUTPUTDRIVE_ENABLED SAI_OUTPUTDRIVE_ENABLE -#define SAI_MASTERDIVIDER_ENABLED SAI_MASTERDIVIDER_ENABLE -#define SAI_MASTERDIVIDER_DISABLED SAI_MASTERDIVIDER_DISABLE -#define SAI_STREOMODE SAI_STEREOMODE -#define SAI_FIFOStatus_Empty SAI_FIFOSTATUS_EMPTY -#define SAI_FIFOStatus_Less1QuarterFull SAI_FIFOSTATUS_LESS1QUARTERFULL -#define SAI_FIFOStatus_1QuarterFull SAI_FIFOSTATUS_1QUARTERFULL -#define SAI_FIFOStatus_HalfFull SAI_FIFOSTATUS_HALFFULL -#define SAI_FIFOStatus_3QuartersFull SAI_FIFOSTATUS_3QUARTERFULL -#define SAI_FIFOStatus_Full SAI_FIFOSTATUS_FULL -#define IS_SAI_BLOCK_MONO_STREO_MODE IS_SAI_BLOCK_MONO_STEREO_MODE -#define SAI_SYNCHRONOUS_EXT SAI_SYNCHRONOUS_EXT_SAI1 -#define SAI_SYNCEXT_IN_ENABLE SAI_SYNCEXT_OUTBLOCKA_ENABLE -/** - * @} - */ - -/** @defgroup HAL_SPDIFRX_Aliased_Macros HAL SPDIFRX Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined(STM32H7) -#define HAL_SPDIFRX_ReceiveControlFlow HAL_SPDIFRX_ReceiveCtrlFlow -#define HAL_SPDIFRX_ReceiveControlFlow_IT HAL_SPDIFRX_ReceiveCtrlFlow_IT -#define HAL_SPDIFRX_ReceiveControlFlow_DMA HAL_SPDIFRX_ReceiveCtrlFlow_DMA -#endif -/** - * @} - */ - -/** @defgroup HAL_HRTIM_Aliased_Functions HAL HRTIM Aliased Functions maintained for legacy purpose - * @{ - */ -#if defined (STM32H7) || defined (STM32G4) || defined (STM32F3) -#define HAL_HRTIM_WaveformCounterStart_IT HAL_HRTIM_WaveformCountStart_IT -#define HAL_HRTIM_WaveformCounterStart_DMA HAL_HRTIM_WaveformCountStart_DMA -#define HAL_HRTIM_WaveformCounterStart HAL_HRTIM_WaveformCountStart -#define HAL_HRTIM_WaveformCounterStop_IT HAL_HRTIM_WaveformCountStop_IT -#define HAL_HRTIM_WaveformCounterStop_DMA HAL_HRTIM_WaveformCountStop_DMA -#define HAL_HRTIM_WaveformCounterStop HAL_HRTIM_WaveformCountStop -#endif -/** - * @} - */ - -/** @defgroup HAL_QSPI_Aliased_Macros HAL QSPI Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined (STM32L4) || defined (STM32F4) || defined (STM32F7) || defined(STM32H7) -#define HAL_QPSI_TIMEOUT_DEFAULT_VALUE HAL_QSPI_TIMEOUT_DEFAULT_VALUE -#endif /* STM32L4 || STM32F4 || STM32F7 */ -/** - * @} - */ - -/** @defgroup HAL_PPP_Aliased_Macros HAL PPP Aliased Macros maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32_HAL_LEGACY */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32f4xx_hal_can_legacy.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32f4xx_hal_can_legacy.h deleted file mode 100644 index aacf0f0727d2031..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32f4xx_hal_can_legacy.h +++ /dev/null @@ -1,785 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_can_legacy.h - * @author MCD Application Team - * @brief Header file of CAN HAL module. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2017 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 __STM32F4xx_HAL_CAN_LEGACY_H -#define __STM32F4xx_HAL_CAN_LEGACY_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CAN - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CAN_Exported_Types CAN Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_CAN_STATE_RESET = 0x00U, /*!< CAN not yet initialized or disabled */ - HAL_CAN_STATE_READY = 0x01U, /*!< CAN initialized and ready for use */ - HAL_CAN_STATE_BUSY = 0x02U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_TX = 0x12U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_RX0 = 0x22U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_RX1 = 0x32U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_TX_RX0 = 0x42U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_TX_RX1 = 0x52U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_RX0_RX1 = 0x62U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_TX_RX0_RX1 = 0x72U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_TIMEOUT = 0x03U, /*!< CAN in Timeout state */ - HAL_CAN_STATE_ERROR = 0x04U /*!< CAN error state */ - -}HAL_CAN_StateTypeDef; - -/** - * @brief CAN init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the length of a time quantum. - This parameter must be a number between Min_Data = 1 and Max_Data = 1024 */ - - uint32_t Mode; /*!< Specifies the CAN operating mode. - This parameter can be a value of @ref CAN_operating_mode */ - - uint32_t SJW; /*!< Specifies the maximum number of time quanta - the CAN hardware is allowed to lengthen or - shorten a bit to perform resynchronization. - This parameter can be a value of @ref CAN_synchronisation_jump_width */ - - uint32_t BS1; /*!< Specifies the number of time quanta in Bit Segment 1. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */ - - uint32_t BS2; /*!< Specifies the number of time quanta in Bit Segment 2. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ - - uint32_t TTCM; /*!< Enable or disable the time triggered communication mode. - This parameter can be set to ENABLE or DISABLE. */ - - uint32_t ABOM; /*!< Enable or disable the automatic bus-off management. - This parameter can be set to ENABLE or DISABLE */ - - uint32_t AWUM; /*!< Enable or disable the automatic wake-up mode. - This parameter can be set to ENABLE or DISABLE */ - - uint32_t NART; /*!< Enable or disable the non-automatic retransmission mode. - This parameter can be set to ENABLE or DISABLE */ - - uint32_t RFLM; /*!< Enable or disable the receive FIFO Locked mode. - This parameter can be set to ENABLE or DISABLE */ - - uint32_t TXFP; /*!< Enable or disable the transmit FIFO priority. - This parameter can be set to ENABLE or DISABLE */ -}CAN_InitTypeDef; - -/** - * @brief CAN filter configuration structure definition - */ -typedef struct -{ - uint32_t FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit - configuration, first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit - configuration, second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, - according to the mode (MSBs for a 32-bit configuration, - first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, - according to the mode (LSBs for a 32-bit configuration, - second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter. - This parameter can be a value of @ref CAN_filter_FIFO */ - - uint32_t FilterNumber; /*!< Specifies the filter which will be initialized. - This parameter must be a number between Min_Data = 0 and Max_Data = 27 */ - - uint32_t FilterMode; /*!< Specifies the filter mode to be initialized. - This parameter can be a value of @ref CAN_filter_mode */ - - uint32_t FilterScale; /*!< Specifies the filter scale. - This parameter can be a value of @ref CAN_filter_scale */ - - uint32_t FilterActivation; /*!< Enable or disable the filter. - This parameter can be set to ENABLE or DISABLE. */ - - uint32_t BankNumber; /*!< Select the start slave bank filter. - This parameter must be a number between Min_Data = 0 and Max_Data = 28 */ - -}CAN_FilterConfTypeDef; - -/** - * @brief CAN Tx message structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_Identifier_Type */ - - uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 8 */ - - uint8_t Data[8]; /*!< Contains the data to be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF */ - -}CanTxMsgTypeDef; - -/** - * @brief CAN Rx message structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be received. - This parameter can be a value of @ref CAN_Identifier_Type */ - - uint32_t RTR; /*!< Specifies the type of frame for the received message. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be received. - This parameter must be a number between Min_Data = 0 and Max_Data = 8 */ - - uint8_t Data[8]; /*!< Contains the data to be received. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF */ - - uint32_t FMI; /*!< Specifies the index of the filter the message stored in the mailbox passes through. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF */ - - uint32_t FIFONumber; /*!< Specifies the receive FIFO number. - This parameter can be CAN_FIFO0 or CAN_FIFO1 */ - -}CanRxMsgTypeDef; - -/** - * @brief CAN handle Structure definition - */ -typedef struct -{ - CAN_TypeDef *Instance; /*!< Register base address */ - - CAN_InitTypeDef Init; /*!< CAN required parameters */ - - CanTxMsgTypeDef* pTxMsg; /*!< Pointer to transmit structure */ - - CanRxMsgTypeDef* pRxMsg; /*!< Pointer to reception structure for RX FIFO0 msg */ - - CanRxMsgTypeDef* pRx1Msg; /*!< Pointer to reception structure for RX FIFO1 msg */ - - __IO HAL_CAN_StateTypeDef State; /*!< CAN communication state */ - - HAL_LockTypeDef Lock; /*!< CAN locking object */ - - __IO uint32_t ErrorCode; /*!< CAN Error code */ - -}CAN_HandleTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CAN_Exported_Constants CAN Exported Constants - * @{ - */ - -/** @defgroup CAN_Error_Code CAN Error Code - * @{ - */ -#define HAL_CAN_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_CAN_ERROR_EWG 0x00000001U /*!< EWG error */ -#define HAL_CAN_ERROR_EPV 0x00000002U /*!< EPV error */ -#define HAL_CAN_ERROR_BOF 0x00000004U /*!< BOF error */ -#define HAL_CAN_ERROR_STF 0x00000008U /*!< Stuff error */ -#define HAL_CAN_ERROR_FOR 0x00000010U /*!< Form error */ -#define HAL_CAN_ERROR_ACK 0x00000020U /*!< Acknowledgment error */ -#define HAL_CAN_ERROR_BR 0x00000040U /*!< Bit recessive */ -#define HAL_CAN_ERROR_BD 0x00000080U /*!< LEC dominant */ -#define HAL_CAN_ERROR_CRC 0x00000100U /*!< LEC transfer error */ -#define HAL_CAN_ERROR_FOV0 0x00000200U /*!< FIFO0 overrun error */ -#define HAL_CAN_ERROR_FOV1 0x00000400U /*!< FIFO1 overrun error */ -#define HAL_CAN_ERROR_TXFAIL 0x00000800U /*!< Transmit failure */ -/** - * @} - */ - -/** @defgroup CAN_InitStatus CAN InitStatus - * @{ - */ -#define CAN_INITSTATUS_FAILED ((uint8_t)0x00) /*!< CAN initialization failed */ -#define CAN_INITSTATUS_SUCCESS ((uint8_t)0x01) /*!< CAN initialization OK */ -/** - * @} - */ - -/** @defgroup CAN_operating_mode CAN Operating Mode - * @{ - */ -#define CAN_MODE_NORMAL 0x00000000U /*!< Normal mode */ -#define CAN_MODE_LOOPBACK ((uint32_t)CAN_BTR_LBKM) /*!< Loopback mode */ -#define CAN_MODE_SILENT ((uint32_t)CAN_BTR_SILM) /*!< Silent mode */ -#define CAN_MODE_SILENT_LOOPBACK ((uint32_t)(CAN_BTR_LBKM | CAN_BTR_SILM)) /*!< Loopback combined with silent mode */ -/** - * @} - */ - -/** @defgroup CAN_synchronisation_jump_width CAN Synchronisation Jump Width - * @{ - */ -#define CAN_SJW_1TQ 0x00000000U /*!< 1 time quantum */ -#define CAN_SJW_2TQ ((uint32_t)CAN_BTR_SJW_0) /*!< 2 time quantum */ -#define CAN_SJW_3TQ ((uint32_t)CAN_BTR_SJW_1) /*!< 3 time quantum */ -#define CAN_SJW_4TQ ((uint32_t)CAN_BTR_SJW) /*!< 4 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_1 CAN Time Quantum in bit segment 1 - * @{ - */ -#define CAN_BS1_1TQ 0x00000000U /*!< 1 time quantum */ -#define CAN_BS1_2TQ ((uint32_t)CAN_BTR_TS1_0) /*!< 2 time quantum */ -#define CAN_BS1_3TQ ((uint32_t)CAN_BTR_TS1_1) /*!< 3 time quantum */ -#define CAN_BS1_4TQ ((uint32_t)(CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 4 time quantum */ -#define CAN_BS1_5TQ ((uint32_t)CAN_BTR_TS1_2) /*!< 5 time quantum */ -#define CAN_BS1_6TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 6 time quantum */ -#define CAN_BS1_7TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 7 time quantum */ -#define CAN_BS1_8TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 8 time quantum */ -#define CAN_BS1_9TQ ((uint32_t)CAN_BTR_TS1_3) /*!< 9 time quantum */ -#define CAN_BS1_10TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_0)) /*!< 10 time quantum */ -#define CAN_BS1_11TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1)) /*!< 11 time quantum */ -#define CAN_BS1_12TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 12 time quantum */ -#define CAN_BS1_13TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2)) /*!< 13 time quantum */ -#define CAN_BS1_14TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 14 time quantum */ -#define CAN_BS1_15TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 15 time quantum */ -#define CAN_BS1_16TQ ((uint32_t)CAN_BTR_TS1) /*!< 16 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_2 CAN Time Quantum in bit segment 2 - * @{ - */ -#define CAN_BS2_1TQ 0x00000000U /*!< 1 time quantum */ -#define CAN_BS2_2TQ ((uint32_t)CAN_BTR_TS2_0) /*!< 2 time quantum */ -#define CAN_BS2_3TQ ((uint32_t)CAN_BTR_TS2_1) /*!< 3 time quantum */ -#define CAN_BS2_4TQ ((uint32_t)(CAN_BTR_TS2_1 | CAN_BTR_TS2_0)) /*!< 4 time quantum */ -#define CAN_BS2_5TQ ((uint32_t)CAN_BTR_TS2_2) /*!< 5 time quantum */ -#define CAN_BS2_6TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_0)) /*!< 6 time quantum */ -#define CAN_BS2_7TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_1)) /*!< 7 time quantum */ -#define CAN_BS2_8TQ ((uint32_t)CAN_BTR_TS2) /*!< 8 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_filter_mode CAN Filter Mode - * @{ - */ -#define CAN_FILTERMODE_IDMASK ((uint8_t)0x00) /*!< Identifier mask mode */ -#define CAN_FILTERMODE_IDLIST ((uint8_t)0x01) /*!< Identifier list mode */ -/** - * @} - */ - -/** @defgroup CAN_filter_scale CAN Filter Scale - * @{ - */ -#define CAN_FILTERSCALE_16BIT ((uint8_t)0x00) /*!< Two 16-bit filters */ -#define CAN_FILTERSCALE_32BIT ((uint8_t)0x01) /*!< One 32-bit filter */ -/** - * @} - */ - -/** @defgroup CAN_filter_FIFO CAN Filter FIFO - * @{ - */ -#define CAN_FILTER_FIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */ -#define CAN_FILTER_FIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */ -/** - * @} - */ - -/** @defgroup CAN_Identifier_Type CAN Identifier Type - * @{ - */ -#define CAN_ID_STD 0x00000000U /*!< Standard Id */ -#define CAN_ID_EXT 0x00000004U /*!< Extended Id */ -/** - * @} - */ - -/** @defgroup CAN_remote_transmission_request CAN Remote Transmission Request - * @{ - */ -#define CAN_RTR_DATA 0x00000000U /*!< Data frame */ -#define CAN_RTR_REMOTE 0x00000002U /*!< Remote frame */ -/** - * @} - */ - -/** @defgroup CAN_receive_FIFO_number_constants CAN Receive FIFO Number Constants - * @{ - */ -#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO 0 used to receive */ -#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO 1 used to receive */ -/** - * @} - */ - -/** @defgroup CAN_flags CAN Flags - * @{ - */ -/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus() - and CAN_ClearFlag() functions. */ -/* If the flag is 0x1XXXXXXX, it means that it can only be used with - CAN_GetFlagStatus() function. */ - -/* Transmit Flags */ -#define CAN_FLAG_RQCP0 0x00000500U /*!< Request MailBox0 flag */ -#define CAN_FLAG_RQCP1 0x00000508U /*!< Request MailBox1 flag */ -#define CAN_FLAG_RQCP2 0x00000510U /*!< Request MailBox2 flag */ -#define CAN_FLAG_TXOK0 0x00000501U /*!< Transmission OK MailBox0 flag */ -#define CAN_FLAG_TXOK1 0x00000509U /*!< Transmission OK MailBox1 flag */ -#define CAN_FLAG_TXOK2 0x00000511U /*!< Transmission OK MailBox2 flag */ -#define CAN_FLAG_TME0 0x0000051AU /*!< Transmit mailbox 0 empty flag */ -#define CAN_FLAG_TME1 0x0000051BU /*!< Transmit mailbox 0 empty flag */ -#define CAN_FLAG_TME2 0x0000051CU /*!< Transmit mailbox 0 empty flag */ - -/* Receive Flags */ -#define CAN_FLAG_FF0 0x00000203U /*!< FIFO 0 Full flag */ -#define CAN_FLAG_FOV0 0x00000204U /*!< FIFO 0 Overrun flag */ - -#define CAN_FLAG_FF1 0x00000403U /*!< FIFO 1 Full flag */ -#define CAN_FLAG_FOV1 0x00000404U /*!< FIFO 1 Overrun flag */ - -/* Operating Mode Flags */ -#define CAN_FLAG_INAK 0x00000100U /*!< Initialization acknowledge flag */ -#define CAN_FLAG_SLAK 0x00000101U /*!< Sleep acknowledge flag */ -#define CAN_FLAG_ERRI 0x00000102U /*!< Error flag */ -#define CAN_FLAG_WKU 0x00000103U /*!< Wake up flag */ -#define CAN_FLAG_SLAKI 0x00000104U /*!< Sleep acknowledge flag */ - -/* @note When SLAK interrupt is disabled (SLKIE=0), no polling on SLAKI is possible. - In this case the SLAK bit can be polled.*/ - -/* Error Flags */ -#define CAN_FLAG_EWG 0x00000300U /*!< Error warning flag */ -#define CAN_FLAG_EPV 0x00000301U /*!< Error passive flag */ -#define CAN_FLAG_BOF 0x00000302U /*!< Bus-Off flag */ -/** - * @} - */ - -/** @defgroup CAN_Interrupts CAN Interrupts - * @{ - */ -#define CAN_IT_TME ((uint32_t)CAN_IER_TMEIE) /*!< Transmit mailbox empty interrupt */ - -/* Receive Interrupts */ -#define CAN_IT_FMP0 ((uint32_t)CAN_IER_FMPIE0) /*!< FIFO 0 message pending interrupt */ -#define CAN_IT_FF0 ((uint32_t)CAN_IER_FFIE0) /*!< FIFO 0 full interrupt */ -#define CAN_IT_FOV0 ((uint32_t)CAN_IER_FOVIE0) /*!< FIFO 0 overrun interrupt */ -#define CAN_IT_FMP1 ((uint32_t)CAN_IER_FMPIE1) /*!< FIFO 1 message pending interrupt */ -#define CAN_IT_FF1 ((uint32_t)CAN_IER_FFIE1) /*!< FIFO 1 full interrupt */ -#define CAN_IT_FOV1 ((uint32_t)CAN_IER_FOVIE1) /*!< FIFO 1 overrun interrupt */ - -/* Operating Mode Interrupts */ -#define CAN_IT_WKU ((uint32_t)CAN_IER_WKUIE) /*!< Wake-up interrupt */ -#define CAN_IT_SLK ((uint32_t)CAN_IER_SLKIE) /*!< Sleep acknowledge interrupt */ - -/* Error Interrupts */ -#define CAN_IT_EWG ((uint32_t)CAN_IER_EWGIE) /*!< Error warning interrupt */ -#define CAN_IT_EPV ((uint32_t)CAN_IER_EPVIE) /*!< Error passive interrupt */ -#define CAN_IT_BOF ((uint32_t)CAN_IER_BOFIE) /*!< Bus-off interrupt */ -#define CAN_IT_LEC ((uint32_t)CAN_IER_LECIE) /*!< Last error code interrupt */ -#define CAN_IT_ERR ((uint32_t)CAN_IER_ERRIE) /*!< Error Interrupt */ -/** - * @} - */ - -/** @defgroup CAN_Mailboxes_Definition CAN Mailboxes Definition - * @{ - */ -#define CAN_TXMAILBOX_0 ((uint8_t)0x00) -#define CAN_TXMAILBOX_1 ((uint8_t)0x01) -#define CAN_TXMAILBOX_2 ((uint8_t)0x02) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup CAN_Exported_Macros CAN Exported Macros - * @{ - */ - -/** @brief Reset CAN handle state - * @param __HANDLE__ specifies the CAN Handle. - * @retval None - */ -#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CAN_STATE_RESET) - -/** - * @brief Enable the specified CAN interrupts. - * @param __HANDLE__ CAN handle - * @param __INTERRUPT__ CAN Interrupt - * @retval None - */ -#define __HAL_CAN_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) |= (__INTERRUPT__)) - -/** - * @brief Disable the specified CAN interrupts. - * @param __HANDLE__ CAN handle - * @param __INTERRUPT__ CAN Interrupt - * @retval None - */ -#define __HAL_CAN_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) &= ~(__INTERRUPT__)) - -/** - * @brief Return the number of pending received messages. - * @param __HANDLE__ CAN handle - * @param __FIFONUMBER__ Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. - * @retval The number of pending message. - */ -#define __HAL_CAN_MSG_PENDING(__HANDLE__, __FIFONUMBER__) (((__FIFONUMBER__) == CAN_FIFO0)? \ -((uint8_t)((__HANDLE__)->Instance->RF0R&0x03U)) : ((uint8_t)((__HANDLE__)->Instance->RF1R & 0x03U))) - -/** @brief Check whether the specified CAN flag is set or not. - * @param __HANDLE__ CAN Handle - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg CAN_TSR_RQCP0: Request MailBox0 Flag - * @arg CAN_TSR_RQCP1: Request MailBox1 Flag - * @arg CAN_TSR_RQCP2: Request MailBox2 Flag - * @arg CAN_FLAG_TXOK0: Transmission OK MailBox0 Flag - * @arg CAN_FLAG_TXOK1: Transmission OK MailBox1 Flag - * @arg CAN_FLAG_TXOK2: Transmission OK MailBox2 Flag - * @arg CAN_FLAG_TME0: Transmit mailbox 0 empty Flag - * @arg CAN_FLAG_TME1: Transmit mailbox 1 empty Flag - * @arg CAN_FLAG_TME2: Transmit mailbox 2 empty Flag - * @arg CAN_FLAG_FMP0: FIFO 0 Message Pending Flag - * @arg CAN_FLAG_FF0: FIFO 0 Full Flag - * @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag - * @arg CAN_FLAG_FMP1: FIFO 1 Message Pending Flag - * @arg CAN_FLAG_FF1: FIFO 1 Full Flag - * @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag - * @arg CAN_FLAG_WKU: Wake up Flag - * @arg CAN_FLAG_SLAK: Sleep acknowledge Flag - * @arg CAN_FLAG_SLAKI: Sleep acknowledge Flag - * @arg CAN_FLAG_EWG: Error Warning Flag - * @arg CAN_FLAG_EPV: Error Passive Flag - * @arg CAN_FLAG_BOF: Bus-Off Flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_FLAG(__HANDLE__, __FLAG__) \ -((((__FLAG__) >> 8U) == 5U)? ((((__HANDLE__)->Instance->TSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? ((((__HANDLE__)->Instance->RF0R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? ((((__HANDLE__)->Instance->RF1R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 1U)? ((((__HANDLE__)->Instance->MSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - ((((__HANDLE__)->Instance->ESR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK)))) - -/** @brief Clear the specified CAN pending flag. - * @param __HANDLE__ CAN Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg CAN_TSR_RQCP0: Request MailBox0 Flag - * @arg CAN_TSR_RQCP1: Request MailBox1 Flag - * @arg CAN_TSR_RQCP2: Request MailBox2 Flag - * @arg CAN_FLAG_TXOK0: Transmission OK MailBox0 Flag - * @arg CAN_FLAG_TXOK1: Transmission OK MailBox1 Flag - * @arg CAN_FLAG_TXOK2: Transmission OK MailBox2 Flag - * @arg CAN_FLAG_TME0: Transmit mailbox 0 empty Flag - * @arg CAN_FLAG_TME1: Transmit mailbox 1 empty Flag - * @arg CAN_FLAG_TME2: Transmit mailbox 2 empty Flag - * @arg CAN_FLAG_FMP0: FIFO 0 Message Pending Flag - * @arg CAN_FLAG_FF0: FIFO 0 Full Flag - * @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag - * @arg CAN_FLAG_FMP1: FIFO 1 Message Pending Flag - * @arg CAN_FLAG_FF1: FIFO 1 Full Flag - * @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag - * @arg CAN_FLAG_WKU: Wake up Flag - * @arg CAN_FLAG_SLAK: Sleep acknowledge Flag - * @arg CAN_FLAG_SLAKI: Sleep acknowledge Flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_CAN_CLEAR_FLAG(__HANDLE__, __FLAG__) \ -((((__FLAG__) >> 8U) == 5U)? (((__HANDLE__)->Instance->TSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? (((__HANDLE__)->Instance->RF0R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? (((__HANDLE__)->Instance->RF1R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__HANDLE__)->Instance->MSR) = ((uint32_t)1U << ((__FLAG__) & CAN_FLAG_MASK)))) - -/** @brief Check if the specified CAN interrupt source is enabled or disabled. - * @param __HANDLE__ CAN Handle - * @param __INTERRUPT__ specifies the CAN interrupt source to check. - * This parameter can be one of the following values: - * @arg CAN_IT_TME: Transmit mailbox empty interrupt enable - * @arg CAN_IT_FMP0: FIFO0 message pending interrupt enable - * @arg CAN_IT_FMP1: FIFO1 message pending interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IER & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** - * @brief Check the transmission status of a CAN Frame. - * @param __HANDLE__ CAN Handle - * @param __TRANSMITMAILBOX__ the number of the mailbox that is used for transmission. - * @retval The new status of transmission (TRUE or FALSE). - */ -#define __HAL_CAN_TRANSMIT_STATUS(__HANDLE__, __TRANSMITMAILBOX__)\ -(((__TRANSMITMAILBOX__) == CAN_TXMAILBOX_0)? ((((__HANDLE__)->Instance->TSR) & (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0)) == (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0)) :\ - ((__TRANSMITMAILBOX__) == CAN_TXMAILBOX_1)? ((((__HANDLE__)->Instance->TSR) & (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1)) == (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1)) :\ - ((((__HANDLE__)->Instance->TSR) & (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2)) == (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2))) - -/** - * @brief Release the specified receive FIFO. - * @param __HANDLE__ CAN handle - * @param __FIFONUMBER__ Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. - * @retval None - */ -#define __HAL_CAN_FIFO_RELEASE(__HANDLE__, __FIFONUMBER__) (((__FIFONUMBER__) == CAN_FIFO0)? \ -((__HANDLE__)->Instance->RF0R = CAN_RF0R_RFOM0) : ((__HANDLE__)->Instance->RF1R = CAN_RF1R_RFOM1)) - -/** - * @brief Cancel a transmit request. - * @param __HANDLE__ CAN Handle - * @param __TRANSMITMAILBOX__ the number of the mailbox that is used for transmission. - * @retval None - */ -#define __HAL_CAN_CANCEL_TRANSMIT(__HANDLE__, __TRANSMITMAILBOX__)\ -(((__TRANSMITMAILBOX__) == CAN_TXMAILBOX_0)? ((__HANDLE__)->Instance->TSR = CAN_TSR_ABRQ0) :\ - ((__TRANSMITMAILBOX__) == CAN_TXMAILBOX_1)? ((__HANDLE__)->Instance->TSR = CAN_TSR_ABRQ1) :\ - ((__HANDLE__)->Instance->TSR = CAN_TSR_ABRQ2)) - -/** - * @brief Enable or disable the DBG Freeze for CAN. - * @param __HANDLE__ CAN Handle - * @param __NEWSTATE__ new state of the CAN peripheral. - * This parameter can be: ENABLE (CAN reception/transmission is frozen - * during debug. Reception FIFOs can still be accessed/controlled normally) - * or DISABLE (CAN is working during debug). - * @retval None - */ -#define __HAL_CAN_DBG_FREEZE(__HANDLE__, __NEWSTATE__) (((__NEWSTATE__) == ENABLE)? \ -((__HANDLE__)->Instance->MCR |= CAN_MCR_DBF) : ((__HANDLE__)->Instance->MCR &= ~CAN_MCR_DBF)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CAN_Exported_Functions - * @{ - */ - -/** @addtogroup CAN_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ***********************************/ -HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef* hcan); -HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef* hcan, CAN_FilterConfTypeDef* sFilterConfig); -HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef* hcan); -void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan); -void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan); -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ******************************************************/ -HAL_StatusTypeDef HAL_CAN_Transmit(CAN_HandleTypeDef *hcan, uint32_t Timeout); -HAL_StatusTypeDef HAL_CAN_Transmit_IT(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_Receive(CAN_HandleTypeDef *hcan, uint8_t FIFONumber, uint32_t Timeout); -HAL_StatusTypeDef HAL_CAN_Receive_IT(CAN_HandleTypeDef *hcan, uint8_t FIFONumber); -HAL_StatusTypeDef HAL_CAN_Sleep(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan); -void HAL_CAN_IRQHandler(CAN_HandleTypeDef* hcan); -void HAL_CAN_TxCpltCallback(CAN_HandleTypeDef* hcan); -void HAL_CAN_RxCpltCallback(CAN_HandleTypeDef* hcan); -void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan); -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ***************************************************/ -uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan); -HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef* hcan); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CAN_Private_Types CAN Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Variables CAN Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Constants CAN Private Constants - * @{ - */ -#define CAN_TXSTATUS_NOMAILBOX ((uint8_t)0x04) /*!< CAN cell did not provide CAN_TxStatus_NoMailBox */ -#define CAN_FLAG_MASK 0x000000FFU -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CAN_Private_Macros CAN Private Macros - * @{ - */ -#define IS_CAN_MODE(MODE) (((MODE) == CAN_MODE_NORMAL) || \ - ((MODE) == CAN_MODE_LOOPBACK)|| \ - ((MODE) == CAN_MODE_SILENT) || \ - ((MODE) == CAN_MODE_SILENT_LOOPBACK)) -#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1TQ) || ((SJW) == CAN_SJW_2TQ)|| \ - ((SJW) == CAN_SJW_3TQ) || ((SJW) == CAN_SJW_4TQ)) -#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16TQ) -#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8TQ) -#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1U) && ((PRESCALER) <= 1024U)) -#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27U) -#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FILTERMODE_IDMASK) || \ - ((MODE) == CAN_FILTERMODE_IDLIST)) -#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FILTERSCALE_16BIT) || \ - ((SCALE) == CAN_FILTERSCALE_32BIT)) -#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FILTER_FIFO0) || \ - ((FIFO) == CAN_FILTER_FIFO1)) -#define IS_CAN_BANKNUMBER(BANKNUMBER) ((BANKNUMBER) <= 28U) - -#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02)) -#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FFU)) -#define IS_CAN_EXTID(EXTID) ((EXTID) <= 0x1FFFFFFFU) -#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08)) - -#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || \ - ((IDTYPE) == CAN_ID_EXT)) -#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE)) -#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Functions CAN Private Functions - * @{ - */ - -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CAN_LEGACY_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32_assert_template.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32_assert_template.h deleted file mode 100644 index 4711b65d8f92aad..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32_assert_template.h +++ /dev/null @@ -1,57 +0,0 @@ -/** - ****************************************************************************** - * @file stm32_assert.h - * @author MCD Application Team - * @brief STM32 assert template file. - * This file should be copied to the application folder and renamed - * to stm32_assert.h. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32_ASSERT_H -#define __STM32_ASSERT_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Includes ------------------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); -#else - #define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32_ASSERT_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h deleted file mode 100644 index 209864d5302a9a4..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h +++ /dev/null @@ -1,298 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal.h - * @author MCD Application Team - * @brief This file contains all the functions prototypes for the HAL - * module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_H -#define __STM32F4xx_HAL_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_conf.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup HAL - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup HAL_Exported_Constants HAL Exported Constants - * @{ - */ - -/** @defgroup HAL_TICK_FREQ Tick Frequency - * @{ - */ -typedef enum -{ - HAL_TICK_FREQ_10HZ = 100U, - HAL_TICK_FREQ_100HZ = 10U, - HAL_TICK_FREQ_1KHZ = 1U, - HAL_TICK_FREQ_DEFAULT = HAL_TICK_FREQ_1KHZ -} HAL_TickFreqTypeDef; -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup HAL_Exported_Macros HAL Exported Macros - * @{ - */ - -/** @brief Freeze/Unfreeze Peripherals in Debug mode - */ -#define __HAL_DBGMCU_FREEZE_TIM2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM2_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM3() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM3_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM4() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM4_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM5() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM5_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM6() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM6_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM7() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM7_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM12() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM12_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM13() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM13_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM14() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM14_STOP)) -#define __HAL_DBGMCU_FREEZE_RTC() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_RTC_STOP)) -#define __HAL_DBGMCU_FREEZE_WWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_WWDG_STOP)) -#define __HAL_DBGMCU_FREEZE_IWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_IWDG_STOP)) -#define __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_CAN1() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN1_STOP)) -#define __HAL_DBGMCU_FREEZE_CAN2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN2_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM1() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM1_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM8() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM8_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM9() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM9_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM10() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM10_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM11() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM11_STOP)) - -#define __HAL_DBGMCU_UNFREEZE_TIM2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM2_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM3() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM3_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM4() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM4_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM5() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM5_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM6() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM6_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM7() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM7_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM12() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM12_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM13() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM13_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM14() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM14_STOP)) -#define __HAL_DBGMCU_UNFREEZE_RTC() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_RTC_STOP)) -#define __HAL_DBGMCU_UNFREEZE_WWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_WWDG_STOP)) -#define __HAL_DBGMCU_UNFREEZE_IWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_IWDG_STOP)) -#define __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_CAN1() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN1_STOP)) -#define __HAL_DBGMCU_UNFREEZE_CAN2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN2_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM1() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM1_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM8() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM8_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM9() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM9_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM10() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM10_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM11() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM11_STOP)) - -/** @brief Main Flash memory mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FLASH() (SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE)) - -/** @brief System Flash memory mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= SYSCFG_MEMRMP_MEM_MODE_0;\ - }while(0); - -/** @brief Embedded SRAM mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_SRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_0 | SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -/** @brief FSMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FSMC() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -/** @brief FMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FMC() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); - -/** @brief FMC/SDRAM Bank 1 and 2 mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_2);\ - }while(0); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup Cortex_Lockup_Enable Cortex Lockup Enable - * @{ - */ -/** @brief SYSCFG Break Lockup lock - * Enables and locks the connection of Cortex-M4 LOCKUP (Hardfault) output to TIM1/8 input - * @note The selected configuration is locked and can be unlocked by system reset - */ -#define __HAL_SYSCFG_BREAK_PVD_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_PVD_LOCK); \ - SYSCFG->CFGR2 |= SYSCFG_CFGR2_PVD_LOCK; \ - }while(0) -/** - * @} - */ - -/** @defgroup PVD_Lock_Enable PVD Lock - * @{ - */ -/** @brief SYSCFG Break PVD lock - * Enables and locks the PVD connection with Timer1/8 Break Input, , as well as the PVDE and PLS[2:0] in the PWR_CR register - * @note The selected configuration is locked and can be unlocked by system reset - */ -#define __HAL_SYSCFG_BREAK_LOCKUP_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_LOCKUP_LOCK); \ - SYSCFG->CFGR2 |= SYSCFG_CFGR2_LOCKUP_LOCK; \ - }while(0) -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup HAL_Private_Macros HAL Private Macros - * @{ - */ -#define IS_TICKFREQ(FREQ) (((FREQ) == HAL_TICK_FREQ_10HZ) || \ - ((FREQ) == HAL_TICK_FREQ_100HZ) || \ - ((FREQ) == HAL_TICK_FREQ_1KHZ)) -/** - * @} - */ - -/* Exported variables --------------------------------------------------------*/ - -/** @addtogroup HAL_Exported_Variables - * @{ - */ -extern __IO uint32_t uwTick; -extern uint32_t uwTickPrio; -extern HAL_TickFreqTypeDef uwTickFreq; -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup HAL_Exported_Functions - * @{ - */ -/** @addtogroup HAL_Exported_Functions_Group1 - * @{ - */ -/* Initialization and Configuration functions ******************************/ -HAL_StatusTypeDef HAL_Init(void); -HAL_StatusTypeDef HAL_DeInit(void); -void HAL_MspInit(void); -void HAL_MspDeInit(void); -HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority); -/** - * @} - */ - -/** @addtogroup HAL_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ************************************************/ -void HAL_IncTick(void); -void HAL_Delay(uint32_t Delay); -uint32_t HAL_GetTick(void); -uint32_t HAL_GetTickPrio(void); -HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq); -HAL_TickFreqTypeDef HAL_GetTickFreq(void); -void HAL_SuspendTick(void); -void HAL_ResumeTick(void); -uint32_t HAL_GetHalVersion(void); -uint32_t HAL_GetREVID(void); -uint32_t HAL_GetDEVID(void); -void HAL_DBGMCU_EnableDBGSleepMode(void); -void HAL_DBGMCU_DisableDBGSleepMode(void); -void HAL_DBGMCU_EnableDBGStopMode(void); -void HAL_DBGMCU_DisableDBGStopMode(void); -void HAL_DBGMCU_EnableDBGStandbyMode(void); -void HAL_DBGMCU_DisableDBGStandbyMode(void); -void HAL_EnableCompensationCell(void); -void HAL_DisableCompensationCell(void); -uint32_t HAL_GetUIDw0(void); -uint32_t HAL_GetUIDw1(void); -uint32_t HAL_GetUIDw2(void); -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -void HAL_EnableMemorySwappingBank(void); -void HAL_DisableMemorySwappingBank(void); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup HAL_Private_Variables HAL Private Variables - * @{ - */ -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup HAL_Private_Constants HAL Private Constants - * @{ - */ -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h deleted file mode 100644 index a041e76965c12b5..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h +++ /dev/null @@ -1,900 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_adc.h - * @author MCD Application Team - * @brief Header file containing functions prototypes of ADC HAL library. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_ADC_H -#define __STM32F4xx_ADC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/* Include low level driver */ -#include "stm32f4xx_ll_adc.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup ADC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup ADC_Exported_Types ADC Exported Types - * @{ - */ - -/** - * @brief Structure definition of ADC and regular group initialization - * @note Parameters of this structure are shared within 2 scopes: - * - Scope entire ADC (affects regular and injected groups): ClockPrescaler, Resolution, ScanConvMode, DataAlign, ScanConvMode, EOCSelection, LowPowerAutoWait, LowPowerAutoPowerOff, ChannelsBank. - * - Scope regular group: ContinuousConvMode, NbrOfConversion, DiscontinuousConvMode, NbrOfDiscConversion, ExternalTrigConvEdge, ExternalTrigConv. - * @note The setting of these parameters with function HAL_ADC_Init() is conditioned to ADC state. - * ADC state can be either: - * - For all parameters: ADC disabled - * - For all parameters except 'Resolution', 'ScanConvMode', 'DiscontinuousConvMode', 'NbrOfDiscConversion' : ADC enabled without conversion on going on regular group. - * - For parameters 'ExternalTrigConv' and 'ExternalTrigConvEdge': ADC enabled, even with conversion on going. - * If ADC is not in the appropriate state to modify some parameters, these parameters setting is bypassed - * without error reporting (as it can be the expected behaviour in case of intended action to update another parameter (which fulfills the ADC state condition) on the fly). - */ -typedef struct -{ - uint32_t ClockPrescaler; /*!< Select ADC clock prescaler. The clock is common for - all the ADCs. - This parameter can be a value of @ref ADC_ClockPrescaler */ - uint32_t Resolution; /*!< Configures the ADC resolution. - This parameter can be a value of @ref ADC_Resolution */ - uint32_t DataAlign; /*!< Specifies ADC data alignment to right (MSB on register bit 11 and LSB on register bit 0) (default setting) - or to left (if regular group: MSB on register bit 15 and LSB on register bit 4, if injected group (MSB kept as signed value due to potential negative value after offset application): MSB on register bit 14 and LSB on register bit 3). - This parameter can be a value of @ref ADC_Data_align */ - uint32_t ScanConvMode; /*!< Configures the sequencer of regular and injected groups. - This parameter can be associated to parameter 'DiscontinuousConvMode' to have main sequence subdivided in successive parts. - If disabled: Conversion is performed in single mode (one channel converted, the one defined in rank 1). - Parameters 'NbrOfConversion' and 'InjectedNbrOfConversion' are discarded (equivalent to set to 1). - If enabled: Conversions are performed in sequence mode (multiple ranks defined by 'NbrOfConversion'/'InjectedNbrOfConversion' and each channel rank). - Scan direction is upward: from rank1 to rank 'n'. - This parameter can be set to ENABLE or DISABLE */ - uint32_t EOCSelection; /*!< Specifies what EOC (End Of Conversion) flag is used for conversion by polling and interruption: end of conversion of each rank or complete sequence. - This parameter can be a value of @ref ADC_EOCSelection. - Note: For injected group, end of conversion (flag&IT) is raised only at the end of the sequence. - Therefore, if end of conversion is set to end of each conversion, injected group should not be used with interruption (HAL_ADCEx_InjectedStart_IT) - or polling (HAL_ADCEx_InjectedStart and HAL_ADCEx_InjectedPollForConversion). By the way, polling is still possible since driver will use an estimated timing for end of injected conversion. - Note: If overrun feature is intended to be used, use ADC in mode 'interruption' (function HAL_ADC_Start_IT() ) with parameter EOCSelection set to end of each conversion or in mode 'transfer by DMA' (function HAL_ADC_Start_DMA()). - If overrun feature is intended to be bypassed, use ADC in mode 'polling' or 'interruption' with parameter EOCSelection must be set to end of sequence */ - FunctionalState ContinuousConvMode; /*!< Specifies whether the conversion is performed in single mode (one conversion) or continuous mode for regular group, - after the selected trigger occurred (software start or external trigger). - This parameter can be set to ENABLE or DISABLE. */ - uint32_t NbrOfConversion; /*!< Specifies the number of ranks that will be converted within the regular group sequencer. - To use regular group sequencer and convert several ranks, parameter 'ScanConvMode' must be enabled. - This parameter must be a number between Min_Data = 1 and Max_Data = 16. */ - FunctionalState DiscontinuousConvMode; /*!< Specifies whether the conversions sequence of regular group is performed in Complete-sequence/Discontinuous-sequence (main sequence subdivided in successive parts). - Discontinuous mode is used only if sequencer is enabled (parameter 'ScanConvMode'). If sequencer is disabled, this parameter is discarded. - Discontinuous mode can be enabled only if continuous mode is disabled. If continuous mode is enabled, this parameter setting is discarded. - This parameter can be set to ENABLE or DISABLE. */ - uint32_t NbrOfDiscConversion; /*!< Specifies the number of discontinuous conversions in which the main sequence of regular group (parameter NbrOfConversion) will be subdivided. - If parameter 'DiscontinuousConvMode' is disabled, this parameter is discarded. - This parameter must be a number between Min_Data = 1 and Max_Data = 8. */ - uint32_t ExternalTrigConv; /*!< Selects the external event used to trigger the conversion start of regular group. - If set to ADC_SOFTWARE_START, external triggers are disabled. - If set to external trigger source, triggering is on event rising edge by default. - This parameter can be a value of @ref ADC_External_trigger_Source_Regular */ - uint32_t ExternalTrigConvEdge; /*!< Selects the external trigger edge of regular group. - If trigger is set to ADC_SOFTWARE_START, this parameter is discarded. - This parameter can be a value of @ref ADC_External_trigger_edge_Regular */ - FunctionalState DMAContinuousRequests; /*!< Specifies whether the DMA requests are performed in one shot mode (DMA transfer stop when number of conversions is reached) - or in Continuous mode (DMA transfer unlimited, whatever number of conversions). - Note: In continuous mode, DMA must be configured in circular mode. Otherwise an overrun will be triggered when DMA buffer maximum pointer is reached. - Note: This parameter must be modified when no conversion is on going on both regular and injected groups (ADC disabled, or ADC enabled without continuous mode or external trigger that could launch a conversion). - This parameter can be set to ENABLE or DISABLE. */ -}ADC_InitTypeDef; - - - -/** - * @brief Structure definition of ADC channel for regular group - * @note The setting of these parameters with function HAL_ADC_ConfigChannel() is conditioned to ADC state. - * ADC can be either disabled or enabled without conversion on going on regular group. - */ -typedef struct -{ - uint32_t Channel; /*!< Specifies the channel to configure into ADC regular group. - This parameter can be a value of @ref ADC_channels */ - uint32_t Rank; /*!< Specifies the rank in the regular group sequencer. - This parameter must be a number between Min_Data = 1 and Max_Data = 16 */ - uint32_t SamplingTime; /*!< Sampling time value to be set for the selected channel. - Unit: ADC clock cycles - Conversion time is the addition of sampling time and processing time (12 ADC clock cycles at ADC resolution 12 bits, 11 cycles at 10 bits, 9 cycles at 8 bits, 7 cycles at 6 bits). - This parameter can be a value of @ref ADC_sampling_times - Caution: This parameter updates the parameter property of the channel, that can be used into regular and/or injected groups. - If this same channel has been previously configured in the other group (regular/injected), it will be updated to last setting. - Note: In case of usage of internal measurement channels (VrefInt/Vbat/TempSensor), - sampling time constraints must be respected (sampling time can be adjusted in function of ADC clock frequency and sampling time setting) - Refer to device datasheet for timings values, parameters TS_vrefint, TS_temp (values rough order: 4us min). */ - uint32_t Offset; /*!< Reserved for future use, can be set to 0 */ -}ADC_ChannelConfTypeDef; - -/** - * @brief ADC Configuration multi-mode structure definition - */ -typedef struct -{ - uint32_t WatchdogMode; /*!< Configures the ADC analog watchdog mode. - This parameter can be a value of @ref ADC_analog_watchdog_selection */ - uint32_t HighThreshold; /*!< Configures the ADC analog watchdog High threshold value. - This parameter must be a 12-bit value. */ - uint32_t LowThreshold; /*!< Configures the ADC analog watchdog High threshold value. - This parameter must be a 12-bit value. */ - uint32_t Channel; /*!< Configures ADC channel for the analog watchdog. - This parameter has an effect only if watchdog mode is configured on single channel - This parameter can be a value of @ref ADC_channels */ - FunctionalState ITMode; /*!< Specifies whether the analog watchdog is configured - is interrupt mode or in polling mode. - This parameter can be set to ENABLE or DISABLE */ - uint32_t WatchdogNumber; /*!< Reserved for future use, can be set to 0 */ -}ADC_AnalogWDGConfTypeDef; - -/** - * @brief HAL ADC state machine: ADC states definition (bitfields) - */ -/* States of ADC global scope */ -#define HAL_ADC_STATE_RESET 0x00000000U /*!< ADC not yet initialized or disabled */ -#define HAL_ADC_STATE_READY 0x00000001U /*!< ADC peripheral ready for use */ -#define HAL_ADC_STATE_BUSY_INTERNAL 0x00000002U /*!< ADC is busy to internal process (initialization, calibration) */ -#define HAL_ADC_STATE_TIMEOUT 0x00000004U /*!< TimeOut occurrence */ - -/* States of ADC errors */ -#define HAL_ADC_STATE_ERROR_INTERNAL 0x00000010U /*!< Internal error occurrence */ -#define HAL_ADC_STATE_ERROR_CONFIG 0x00000020U /*!< Configuration error occurrence */ -#define HAL_ADC_STATE_ERROR_DMA 0x00000040U /*!< DMA error occurrence */ - -/* States of ADC group regular */ -#define HAL_ADC_STATE_REG_BUSY 0x00000100U /*!< A conversion on group regular is ongoing or can occur (either by continuous mode, - external trigger, low power auto power-on (if feature available), multimode ADC master control (if feature available)) */ -#define HAL_ADC_STATE_REG_EOC 0x00000200U /*!< Conversion data available on group regular */ -#define HAL_ADC_STATE_REG_OVR 0x00000400U /*!< Overrun occurrence */ - -/* States of ADC group injected */ -#define HAL_ADC_STATE_INJ_BUSY 0x00001000U /*!< A conversion on group injected is ongoing or can occur (either by auto-injection mode, - external trigger, low power auto power-on (if feature available), multimode ADC master control (if feature available)) */ -#define HAL_ADC_STATE_INJ_EOC 0x00002000U /*!< Conversion data available on group injected */ - -/* States of ADC analog watchdogs */ -#define HAL_ADC_STATE_AWD1 0x00010000U /*!< Out-of-window occurrence of analog watchdog 1 */ -#define HAL_ADC_STATE_AWD2 0x00020000U /*!< Not available on STM32F4 device: Out-of-window occurrence of analog watchdog 2 */ -#define HAL_ADC_STATE_AWD3 0x00040000U /*!< Not available on STM32F4 device: Out-of-window occurrence of analog watchdog 3 */ - -/* States of ADC multi-mode */ -#define HAL_ADC_STATE_MULTIMODE_SLAVE 0x00100000U /*!< Not available on STM32F4 device: ADC in multimode slave state, controlled by another ADC master ( */ - - -/** - * @brief ADC handle Structure definition - */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -typedef struct __ADC_HandleTypeDef -#else -typedef struct -#endif -{ - ADC_TypeDef *Instance; /*!< Register base address */ - - ADC_InitTypeDef Init; /*!< ADC required parameters */ - - __IO uint32_t NbrOfCurrentConversionRank; /*!< ADC number of current conversion rank */ - - DMA_HandleTypeDef *DMA_Handle; /*!< Pointer DMA Handler */ - - HAL_LockTypeDef Lock; /*!< ADC locking object */ - - __IO uint32_t State; /*!< ADC communication state */ - - __IO uint32_t ErrorCode; /*!< ADC Error code */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - void (* ConvCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC conversion complete callback */ - void (* ConvHalfCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC conversion DMA half-transfer callback */ - void (* LevelOutOfWindowCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC analog watchdog 1 callback */ - void (* ErrorCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC error callback */ - void (* InjectedConvCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC group injected conversion complete callback */ - void (* MspInitCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC Msp Init callback */ - void (* MspDeInitCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC Msp DeInit callback */ -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ -}ADC_HandleTypeDef; - -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL ADC Callback ID enumeration definition - */ -typedef enum -{ - HAL_ADC_CONVERSION_COMPLETE_CB_ID = 0x00U, /*!< ADC conversion complete callback ID */ - HAL_ADC_CONVERSION_HALF_CB_ID = 0x01U, /*!< ADC conversion DMA half-transfer callback ID */ - HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID = 0x02U, /*!< ADC analog watchdog 1 callback ID */ - HAL_ADC_ERROR_CB_ID = 0x03U, /*!< ADC error callback ID */ - HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID = 0x04U, /*!< ADC group injected conversion complete callback ID */ - HAL_ADC_MSPINIT_CB_ID = 0x05U, /*!< ADC Msp Init callback ID */ - HAL_ADC_MSPDEINIT_CB_ID = 0x06U /*!< ADC Msp DeInit callback ID */ -} HAL_ADC_CallbackIDTypeDef; - -/** - * @brief HAL ADC Callback pointer definition - */ -typedef void (*pADC_CallbackTypeDef)(ADC_HandleTypeDef *hadc); /*!< pointer to a ADC callback function */ - -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup ADC_Exported_Constants ADC Exported Constants - * @{ - */ - -/** @defgroup ADC_Error_Code ADC Error Code - * @{ - */ -#define HAL_ADC_ERROR_NONE 0x00U /*!< No error */ -#define HAL_ADC_ERROR_INTERNAL 0x01U /*!< ADC IP internal error: if problem of clocking, - enable/disable, erroneous state */ -#define HAL_ADC_ERROR_OVR 0x02U /*!< Overrun error */ -#define HAL_ADC_ERROR_DMA 0x04U /*!< DMA transfer error */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -#define HAL_ADC_ERROR_INVALID_CALLBACK (0x10U) /*!< Invalid Callback error */ -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ -/** - * @} - */ - - -/** @defgroup ADC_ClockPrescaler ADC Clock Prescaler - * @{ - */ -#define ADC_CLOCK_SYNC_PCLK_DIV2 0x00000000U -#define ADC_CLOCK_SYNC_PCLK_DIV4 ((uint32_t)ADC_CCR_ADCPRE_0) -#define ADC_CLOCK_SYNC_PCLK_DIV6 ((uint32_t)ADC_CCR_ADCPRE_1) -#define ADC_CLOCK_SYNC_PCLK_DIV8 ((uint32_t)ADC_CCR_ADCPRE) -/** - * @} - */ - -/** @defgroup ADC_delay_between_2_sampling_phases ADC Delay Between 2 Sampling Phases - * @{ - */ -#define ADC_TWOSAMPLINGDELAY_5CYCLES 0x00000000U -#define ADC_TWOSAMPLINGDELAY_6CYCLES ((uint32_t)ADC_CCR_DELAY_0) -#define ADC_TWOSAMPLINGDELAY_7CYCLES ((uint32_t)ADC_CCR_DELAY_1) -#define ADC_TWOSAMPLINGDELAY_8CYCLES ((uint32_t)(ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_9CYCLES ((uint32_t)ADC_CCR_DELAY_2) -#define ADC_TWOSAMPLINGDELAY_10CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_11CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1)) -#define ADC_TWOSAMPLINGDELAY_12CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_13CYCLES ((uint32_t)ADC_CCR_DELAY_3) -#define ADC_TWOSAMPLINGDELAY_14CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_15CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1)) -#define ADC_TWOSAMPLINGDELAY_16CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_17CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2)) -#define ADC_TWOSAMPLINGDELAY_18CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_19CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1)) -#define ADC_TWOSAMPLINGDELAY_20CYCLES ((uint32_t)ADC_CCR_DELAY) -/** - * @} - */ - -/** @defgroup ADC_Resolution ADC Resolution - * @{ - */ -#define ADC_RESOLUTION_12B 0x00000000U -#define ADC_RESOLUTION_10B ((uint32_t)ADC_CR1_RES_0) -#define ADC_RESOLUTION_8B ((uint32_t)ADC_CR1_RES_1) -#define ADC_RESOLUTION_6B ((uint32_t)ADC_CR1_RES) -/** - * @} - */ - -/** @defgroup ADC_External_trigger_edge_Regular ADC External Trigger Edge Regular - * @{ - */ -#define ADC_EXTERNALTRIGCONVEDGE_NONE 0x00000000U -#define ADC_EXTERNALTRIGCONVEDGE_RISING ((uint32_t)ADC_CR2_EXTEN_0) -#define ADC_EXTERNALTRIGCONVEDGE_FALLING ((uint32_t)ADC_CR2_EXTEN_1) -#define ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING ((uint32_t)ADC_CR2_EXTEN) -/** - * @} - */ - -/** @defgroup ADC_External_trigger_Source_Regular ADC External Trigger Source Regular - * @{ - */ -/* Note: Parameter ADC_SOFTWARE_START is a software parameter used for */ -/* compatibility with other STM32 devices. */ -#define ADC_EXTERNALTRIGCONV_T1_CC1 0x00000000U -#define ADC_EXTERNALTRIGCONV_T1_CC2 ((uint32_t)ADC_CR2_EXTSEL_0) -#define ADC_EXTERNALTRIGCONV_T1_CC3 ((uint32_t)ADC_CR2_EXTSEL_1) -#define ADC_EXTERNALTRIGCONV_T2_CC2 ((uint32_t)(ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T2_CC3 ((uint32_t)ADC_CR2_EXTSEL_2) -#define ADC_EXTERNALTRIGCONV_T2_CC4 ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T2_TRGO ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1)) -#define ADC_EXTERNALTRIGCONV_T3_CC1 ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T3_TRGO ((uint32_t)ADC_CR2_EXTSEL_3) -#define ADC_EXTERNALTRIGCONV_T4_CC4 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T5_CC1 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1)) -#define ADC_EXTERNALTRIGCONV_T5_CC2 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T5_CC3 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2)) -#define ADC_EXTERNALTRIGCONV_T8_CC1 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T8_TRGO ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1)) -#define ADC_EXTERNALTRIGCONV_Ext_IT11 ((uint32_t)ADC_CR2_EXTSEL) -#define ADC_SOFTWARE_START ((uint32_t)ADC_CR2_EXTSEL + 1U) -/** - * @} - */ - -/** @defgroup ADC_Data_align ADC Data Align - * @{ - */ -#define ADC_DATAALIGN_RIGHT 0x00000000U -#define ADC_DATAALIGN_LEFT ((uint32_t)ADC_CR2_ALIGN) -/** - * @} - */ - -/** @defgroup ADC_channels ADC Common Channels - * @{ - */ -#define ADC_CHANNEL_0 0x00000000U -#define ADC_CHANNEL_1 ((uint32_t)ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_2 ((uint32_t)ADC_CR1_AWDCH_1) -#define ADC_CHANNEL_3 ((uint32_t)(ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_4 ((uint32_t)ADC_CR1_AWDCH_2) -#define ADC_CHANNEL_5 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_6 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1)) -#define ADC_CHANNEL_7 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_8 ((uint32_t)ADC_CR1_AWDCH_3) -#define ADC_CHANNEL_9 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_10 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1)) -#define ADC_CHANNEL_11 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_12 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2)) -#define ADC_CHANNEL_13 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_14 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1)) -#define ADC_CHANNEL_15 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_16 ((uint32_t)ADC_CR1_AWDCH_4) -#define ADC_CHANNEL_17 ((uint32_t)(ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_18 ((uint32_t)(ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_1)) - -#define ADC_CHANNEL_VREFINT ((uint32_t)ADC_CHANNEL_17) -#define ADC_CHANNEL_VBAT ((uint32_t)ADC_CHANNEL_18) -/** - * @} - */ - -/** @defgroup ADC_sampling_times ADC Sampling Times - * @{ - */ -#define ADC_SAMPLETIME_3CYCLES 0x00000000U -#define ADC_SAMPLETIME_15CYCLES ((uint32_t)ADC_SMPR1_SMP10_0) -#define ADC_SAMPLETIME_28CYCLES ((uint32_t)ADC_SMPR1_SMP10_1) -#define ADC_SAMPLETIME_56CYCLES ((uint32_t)(ADC_SMPR1_SMP10_1 | ADC_SMPR1_SMP10_0)) -#define ADC_SAMPLETIME_84CYCLES ((uint32_t)ADC_SMPR1_SMP10_2) -#define ADC_SAMPLETIME_112CYCLES ((uint32_t)(ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_0)) -#define ADC_SAMPLETIME_144CYCLES ((uint32_t)(ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_1)) -#define ADC_SAMPLETIME_480CYCLES ((uint32_t)ADC_SMPR1_SMP10) -/** - * @} - */ - - /** @defgroup ADC_EOCSelection ADC EOC Selection - * @{ - */ -#define ADC_EOC_SEQ_CONV 0x00000000U -#define ADC_EOC_SINGLE_CONV 0x00000001U -#define ADC_EOC_SINGLE_SEQ_CONV 0x00000002U /*!< reserved for future use */ -/** - * @} - */ - -/** @defgroup ADC_Event_type ADC Event Type - * @{ - */ -#define ADC_AWD_EVENT ((uint32_t)ADC_FLAG_AWD) -#define ADC_OVR_EVENT ((uint32_t)ADC_FLAG_OVR) -/** - * @} - */ - -/** @defgroup ADC_analog_watchdog_selection ADC Analog Watchdog Selection - * @{ - */ -#define ADC_ANALOGWATCHDOG_SINGLE_REG ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_AWDEN)) -#define ADC_ANALOGWATCHDOG_SINGLE_INJEC ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_JAWDEN)) -#define ADC_ANALOGWATCHDOG_SINGLE_REGINJEC ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_AWDEN | ADC_CR1_JAWDEN)) -#define ADC_ANALOGWATCHDOG_ALL_REG ((uint32_t)ADC_CR1_AWDEN) -#define ADC_ANALOGWATCHDOG_ALL_INJEC ((uint32_t)ADC_CR1_JAWDEN) -#define ADC_ANALOGWATCHDOG_ALL_REGINJEC ((uint32_t)(ADC_CR1_AWDEN | ADC_CR1_JAWDEN)) -#define ADC_ANALOGWATCHDOG_NONE 0x00000000U -/** - * @} - */ - -/** @defgroup ADC_interrupts_definition ADC Interrupts Definition - * @{ - */ -#define ADC_IT_EOC ((uint32_t)ADC_CR1_EOCIE) -#define ADC_IT_AWD ((uint32_t)ADC_CR1_AWDIE) -#define ADC_IT_JEOC ((uint32_t)ADC_CR1_JEOCIE) -#define ADC_IT_OVR ((uint32_t)ADC_CR1_OVRIE) -/** - * @} - */ - -/** @defgroup ADC_flags_definition ADC Flags Definition - * @{ - */ -#define ADC_FLAG_AWD ((uint32_t)ADC_SR_AWD) -#define ADC_FLAG_EOC ((uint32_t)ADC_SR_EOC) -#define ADC_FLAG_JEOC ((uint32_t)ADC_SR_JEOC) -#define ADC_FLAG_JSTRT ((uint32_t)ADC_SR_JSTRT) -#define ADC_FLAG_STRT ((uint32_t)ADC_SR_STRT) -#define ADC_FLAG_OVR ((uint32_t)ADC_SR_OVR) -/** - * @} - */ - -/** @defgroup ADC_channels_type ADC Channels Type - * @{ - */ -#define ADC_ALL_CHANNELS 0x00000001U -#define ADC_REGULAR_CHANNELS 0x00000002U /*!< reserved for future use */ -#define ADC_INJECTED_CHANNELS 0x00000003U /*!< reserved for future use */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup ADC_Exported_Macros ADC Exported Macros - * @{ - */ - -/** @brief Reset ADC handle state - * @param __HANDLE__ ADC handle - * @retval None - */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) \ - do{ \ - (__HANDLE__)->State = HAL_ADC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) \ - ((__HANDLE__)->State = HAL_ADC_STATE_RESET) -#endif - -/** - * @brief Enable the ADC peripheral. - * @param __HANDLE__ ADC handle - * @retval None - */ -#define __HAL_ADC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR2 |= ADC_CR2_ADON) - -/** - * @brief Disable the ADC peripheral. - * @param __HANDLE__ ADC handle - * @retval None - */ -#define __HAL_ADC_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= ~ADC_CR2_ADON) - -/** - * @brief Enable the ADC end of conversion interrupt. - * @param __HANDLE__ specifies the ADC Handle. - * @param __INTERRUPT__ ADC Interrupt. - * @retval None - */ -#define __HAL_ADC_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1) |= (__INTERRUPT__)) - -/** - * @brief Disable the ADC end of conversion interrupt. - * @param __HANDLE__ specifies the ADC Handle. - * @param __INTERRUPT__ ADC interrupt. - * @retval None - */ -#define __HAL_ADC_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1) &= ~(__INTERRUPT__)) - -/** @brief Check if the specified ADC interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the ADC Handle. - * @param __INTERRUPT__ specifies the ADC interrupt source to check. - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_ADC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1 & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @brief Clear the ADC's pending flags. - * @param __HANDLE__ specifies the ADC Handle. - * @param __FLAG__ ADC flag. - * @retval None - */ -#define __HAL_ADC_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = ~(__FLAG__)) - -/** - * @brief Get the selected ADC's flag status. - * @param __HANDLE__ specifies the ADC Handle. - * @param __FLAG__ ADC flag. - * @retval None - */ -#define __HAL_ADC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** - * @} - */ - -/* Include ADC HAL Extension module */ -#include "stm32f4xx_hal_adc_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup ADC_Exported_Functions - * @{ - */ - -/** @addtogroup ADC_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ***********************************/ -HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef *hadc); -void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc); -void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc); - -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_ADC_RegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID, pADC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup ADC_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ******************************************************/ -HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout); - -HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef* hadc, uint32_t EventType, uint32_t Timeout); - -HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef* hadc); - -void HAL_ADC_IRQHandler(ADC_HandleTypeDef* hadc); - -HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length); -HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef* hadc); - -uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef* hadc); - -void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc); -void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc); -void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef* hadc); -void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc); -/** - * @} - */ - -/** @addtogroup ADC_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions *************************************************/ -HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef* hadc, ADC_ChannelConfTypeDef* sConfig); -HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef* hadc, ADC_AnalogWDGConfTypeDef* AnalogWDGConfig); -/** - * @} - */ - -/** @addtogroup ADC_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State functions ***************************************************/ -uint32_t HAL_ADC_GetState(ADC_HandleTypeDef* hadc); -uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup ADC_Private_Constants ADC Private Constants - * @{ - */ -/* Delay for ADC stabilization time. */ -/* Maximum delay is 1us (refer to device datasheet, parameter tSTAB). */ -/* Unit: us */ -#define ADC_STAB_DELAY_US 3U -/* Delay for temperature sensor stabilization time. */ -/* Maximum delay is 10us (refer to device datasheet, parameter tSTART). */ -/* Unit: us */ -#define ADC_TEMPSENSOR_DELAY_US 10U -/** - * @} - */ - -/* Private macro ------------------------------------------------------------*/ - -/** @defgroup ADC_Private_Macros ADC Private Macros - * @{ - */ -/* Macro reserved for internal HAL driver usage, not intended to be used in - code of final user */ - -/** - * @brief Verification of ADC state: enabled or disabled - * @param __HANDLE__ ADC handle - * @retval SET (ADC enabled) or RESET (ADC disabled) - */ -#define ADC_IS_ENABLE(__HANDLE__) \ - ((( ((__HANDLE__)->Instance->SR & ADC_SR_ADONS) == ADC_SR_ADONS ) \ - ) ? SET : RESET) - -/** - * @brief Test if conversion trigger of regular group is software start - * or external trigger. - * @param __HANDLE__ ADC handle - * @retval SET (software start) or RESET (external trigger) - */ -#define ADC_IS_SOFTWARE_START_REGULAR(__HANDLE__) \ - (((__HANDLE__)->Instance->CR2 & ADC_CR2_EXTEN) == RESET) - -/** - * @brief Test if conversion trigger of injected group is software start - * or external trigger. - * @param __HANDLE__ ADC handle - * @retval SET (software start) or RESET (external trigger) - */ -#define ADC_IS_SOFTWARE_START_INJECTED(__HANDLE__) \ - (((__HANDLE__)->Instance->CR2 & ADC_CR2_JEXTEN) == RESET) - -/** - * @brief Simultaneously clears and sets specific bits of the handle State - * @note: ADC_STATE_CLR_SET() macro is merely aliased to generic macro MODIFY_REG(), - * the first parameter is the ADC handle State, the second parameter is the - * bit field to clear, the third and last parameter is the bit field to set. - * @retval None - */ -#define ADC_STATE_CLR_SET MODIFY_REG - -/** - * @brief Clear ADC error code (set it to error code: "no error") - * @param __HANDLE__ ADC handle - * @retval None - */ -#define ADC_CLEAR_ERRORCODE(__HANDLE__) \ - ((__HANDLE__)->ErrorCode = HAL_ADC_ERROR_NONE) - - -#define IS_ADC_CLOCKPRESCALER(ADC_CLOCK) (((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV2) || \ - ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV4) || \ - ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV6) || \ - ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV8)) -#define IS_ADC_SAMPLING_DELAY(DELAY) (((DELAY) == ADC_TWOSAMPLINGDELAY_5CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_6CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_7CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_8CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_9CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_10CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_11CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_12CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_13CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_14CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_15CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_16CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_17CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_18CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_19CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_20CYCLES)) -#define IS_ADC_RESOLUTION(RESOLUTION) (((RESOLUTION) == ADC_RESOLUTION_12B) || \ - ((RESOLUTION) == ADC_RESOLUTION_10B) || \ - ((RESOLUTION) == ADC_RESOLUTION_8B) || \ - ((RESOLUTION) == ADC_RESOLUTION_6B)) -#define IS_ADC_EXT_TRIG_EDGE(EDGE) (((EDGE) == ADC_EXTERNALTRIGCONVEDGE_NONE) || \ - ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_RISING) || \ - ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_FALLING) || \ - ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING)) -#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC1) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC2) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC3) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC2) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC3) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC4) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_TRGO) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T3_CC1) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T3_TRGO) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T4_CC4) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC1) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC2) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC3) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T8_CC1) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T8_TRGO) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_Ext_IT11)|| \ - ((REGTRIG) == ADC_SOFTWARE_START)) -#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DATAALIGN_RIGHT) || \ - ((ALIGN) == ADC_DATAALIGN_LEFT)) -#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SAMPLETIME_3CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_15CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_28CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_56CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_84CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_112CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_144CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_480CYCLES)) -#define IS_ADC_EOCSelection(EOCSelection) (((EOCSelection) == ADC_EOC_SINGLE_CONV) || \ - ((EOCSelection) == ADC_EOC_SEQ_CONV) || \ - ((EOCSelection) == ADC_EOC_SINGLE_SEQ_CONV)) -#define IS_ADC_EVENT_TYPE(EVENT) (((EVENT) == ADC_AWD_EVENT) || \ - ((EVENT) == ADC_OVR_EVENT)) -#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_REG) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_INJEC) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_REGINJEC) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_REG) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_INJEC) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_REGINJEC) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_NONE)) -#define IS_ADC_CHANNELS_TYPE(CHANNEL_TYPE) (((CHANNEL_TYPE) == ADC_ALL_CHANNELS) || \ - ((CHANNEL_TYPE) == ADC_REGULAR_CHANNELS) || \ - ((CHANNEL_TYPE) == ADC_INJECTED_CHANNELS)) -#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFFU) - -#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 1U) && ((LENGTH) <= 16U)) -#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 1U) && ((RANK) <= (16U))) -#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 1U) && ((NUMBER) <= 8U)) -#define IS_ADC_RANGE(RESOLUTION, ADC_VALUE) \ - ((((RESOLUTION) == ADC_RESOLUTION_12B) && ((ADC_VALUE) <= 0x0FFFU)) || \ - (((RESOLUTION) == ADC_RESOLUTION_10B) && ((ADC_VALUE) <= 0x03FFU)) || \ - (((RESOLUTION) == ADC_RESOLUTION_8B) && ((ADC_VALUE) <= 0x00FFU)) || \ - (((RESOLUTION) == ADC_RESOLUTION_6B) && ((ADC_VALUE) <= 0x003FU))) - -/** - * @brief Set ADC Regular channel sequence length. - * @param _NbrOfConversion_ Regular channel sequence length. - * @retval None - */ -#define ADC_SQR1(_NbrOfConversion_) (((_NbrOfConversion_) - (uint8_t)1U) << 20U) - -/** - * @brief Set the ADC's sample time for channel numbers between 10 and 18. - * @param _SAMPLETIME_ Sample time parameter. - * @param _CHANNELNB_ Channel number. - * @retval None - */ -#define ADC_SMPR1(_SAMPLETIME_, _CHANNELNB_) ((_SAMPLETIME_) << (3U * (((uint32_t)((uint16_t)(_CHANNELNB_))) - 10U))) - -/** - * @brief Set the ADC's sample time for channel numbers between 0 and 9. - * @param _SAMPLETIME_ Sample time parameter. - * @param _CHANNELNB_ Channel number. - * @retval None - */ -#define ADC_SMPR2(_SAMPLETIME_, _CHANNELNB_) ((_SAMPLETIME_) << (3U * ((uint32_t)((uint16_t)(_CHANNELNB_))))) - -/** - * @brief Set the selected regular channel rank for rank between 1 and 6. - * @param _CHANNELNB_ Channel number. - * @param _RANKNB_ Rank number. - * @retval None - */ -#define ADC_SQR3_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 1U))) - -/** - * @brief Set the selected regular channel rank for rank between 7 and 12. - * @param _CHANNELNB_ Channel number. - * @param _RANKNB_ Rank number. - * @retval None - */ -#define ADC_SQR2_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 7U))) - -/** - * @brief Set the selected regular channel rank for rank between 13 and 16. - * @param _CHANNELNB_ Channel number. - * @param _RANKNB_ Rank number. - * @retval None - */ -#define ADC_SQR1_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 13U))) - -/** - * @brief Enable ADC continuous conversion mode. - * @param _CONTINUOUS_MODE_ Continuous mode. - * @retval None - */ -#define ADC_CR2_CONTINUOUS(_CONTINUOUS_MODE_) ((_CONTINUOUS_MODE_) << 1U) - -/** - * @brief Configures the number of discontinuous conversions for the regular group channels. - * @param _NBR_DISCONTINUOUSCONV_ Number of discontinuous conversions. - * @retval None - */ -#define ADC_CR1_DISCONTINUOUS(_NBR_DISCONTINUOUSCONV_) (((_NBR_DISCONTINUOUSCONV_) - 1U) << ADC_CR1_DISCNUM_Pos) - -/** - * @brief Enable ADC scan mode. - * @param _SCANCONV_MODE_ Scan conversion mode. - * @retval None - */ -#define ADC_CR1_SCANCONV(_SCANCONV_MODE_) ((_SCANCONV_MODE_) << 8U) - -/** - * @brief Enable the ADC end of conversion selection. - * @param _EOCSelection_MODE_ End of conversion selection mode. - * @retval None - */ -#define ADC_CR2_EOCSelection(_EOCSelection_MODE_) ((_EOCSelection_MODE_) << 10U) - -/** - * @brief Enable the ADC DMA continuous request. - * @param _DMAContReq_MODE_ DMA continuous request mode. - * @retval None - */ -#define ADC_CR2_DMAContReq(_DMAContReq_MODE_) ((_DMAContReq_MODE_) << 9U) - -/** - * @brief Return resolution bits in CR1 register. - * @param __HANDLE__ ADC handle - * @retval None - */ -#define ADC_GET_RESOLUTION(__HANDLE__) (((__HANDLE__)->Instance->CR1) & ADC_CR1_RES) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup ADC_Private_Functions ADC Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F4xx_ADC_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h deleted file mode 100644 index b0cdd2abd358933..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h +++ /dev/null @@ -1,409 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_adc_ex.h - * @author MCD Application Team - * @brief Header file of ADC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_ADC_EX_H -#define __STM32F4xx_ADC_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup ADCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup ADCEx_Exported_Types ADC Exported Types - * @{ - */ - -/** - * @brief ADC Configuration injected Channel structure definition - * @note Parameters of this structure are shared within 2 scopes: - * - Scope channel: InjectedChannel, InjectedRank, InjectedSamplingTime, InjectedOffset - * - Scope injected group (affects all channels of injected group): InjectedNbrOfConversion, InjectedDiscontinuousConvMode, - * AutoInjectedConv, ExternalTrigInjecConvEdge, ExternalTrigInjecConv. - * @note The setting of these parameters with function HAL_ADCEx_InjectedConfigChannel() is conditioned to ADC state. - * ADC state can be either: - * - For all parameters: ADC disabled - * - For all except parameters 'InjectedDiscontinuousConvMode' and 'AutoInjectedConv': ADC enabled without conversion on going on injected group. - * - For parameters 'ExternalTrigInjecConv' and 'ExternalTrigInjecConvEdge': ADC enabled, even with conversion on going on injected group. - */ -typedef struct -{ - uint32_t InjectedChannel; /*!< Selection of ADC channel to configure - This parameter can be a value of @ref ADC_channels - Note: Depending on devices, some channels may not be available on package pins. Refer to device datasheet for channels availability. */ - uint32_t InjectedRank; /*!< Rank in the injected group sequencer - This parameter must be a value of @ref ADCEx_injected_rank - Note: In case of need to disable a channel or change order of conversion sequencer, rank containing a previous channel setting can be overwritten by the new channel setting (or parameter number of conversions can be adjusted) */ - uint32_t InjectedSamplingTime; /*!< Sampling time value to be set for the selected channel. - Unit: ADC clock cycles - Conversion time is the addition of sampling time and processing time (12 ADC clock cycles at ADC resolution 12 bits, 11 cycles at 10 bits, 9 cycles at 8 bits, 7 cycles at 6 bits). - This parameter can be a value of @ref ADC_sampling_times - Caution: This parameter updates the parameter property of the channel, that can be used into regular and/or injected groups. - If this same channel has been previously configured in the other group (regular/injected), it will be updated to last setting. - Note: In case of usage of internal measurement channels (VrefInt/Vbat/TempSensor), - sampling time constraints must be respected (sampling time can be adjusted in function of ADC clock frequency and sampling time setting) - Refer to device datasheet for timings values, parameters TS_vrefint, TS_temp (values rough order: 4us min). */ - uint32_t InjectedOffset; /*!< Defines the offset to be subtracted from the raw converted data (for channels set on injected group only). - Offset value must be a positive number. - Depending of ADC resolution selected (12, 10, 8 or 6 bits), - this parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF, 0x3FF, 0xFF or 0x3F respectively. */ - uint32_t InjectedNbrOfConversion; /*!< Specifies the number of ranks that will be converted within the injected group sequencer. - To use the injected group sequencer and convert several ranks, parameter 'ScanConvMode' must be enabled. - This parameter must be a number between Min_Data = 1 and Max_Data = 4. - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ - FunctionalState InjectedDiscontinuousConvMode; /*!< Specifies whether the conversions sequence of injected group is performed in Complete-sequence/Discontinuous-sequence (main sequence subdivided in successive parts). - Discontinuous mode is used only if sequencer is enabled (parameter 'ScanConvMode'). If sequencer is disabled, this parameter is discarded. - Discontinuous mode can be enabled only if continuous mode is disabled. If continuous mode is enabled, this parameter setting is discarded. - This parameter can be set to ENABLE or DISABLE. - Note: For injected group, number of discontinuous ranks increment is fixed to one-by-one. - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ - FunctionalState AutoInjectedConv; /*!< Enables or disables the selected ADC automatic injected group conversion after regular one - This parameter can be set to ENABLE or DISABLE. - Note: To use Automatic injected conversion, discontinuous mode must be disabled ('DiscontinuousConvMode' and 'InjectedDiscontinuousConvMode' set to DISABLE) - Note: To use Automatic injected conversion, injected group external triggers must be disabled ('ExternalTrigInjecConv' set to ADC_SOFTWARE_START) - Note: In case of DMA used with regular group: if DMA configured in normal mode (single shot) JAUTO will be stopped upon DMA transfer complete. - To maintain JAUTO always enabled, DMA must be configured in circular mode. - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ - uint32_t ExternalTrigInjecConv; /*!< Selects the external event used to trigger the conversion start of injected group. - If set to ADC_INJECTED_SOFTWARE_START, external triggers are disabled. - If set to external trigger source, triggering is on event rising edge. - This parameter can be a value of @ref ADCEx_External_trigger_Source_Injected - Note: This parameter must be modified when ADC is disabled (before ADC start conversion or after ADC stop conversion). - If ADC is enabled, this parameter setting is bypassed without error reporting (as it can be the expected behaviour in case of another parameter update on the fly) - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ - uint32_t ExternalTrigInjecConvEdge; /*!< Selects the external trigger edge of injected group. - This parameter can be a value of @ref ADCEx_External_trigger_edge_Injected. - If trigger is set to ADC_INJECTED_SOFTWARE_START, this parameter is discarded. - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ -}ADC_InjectionConfTypeDef; - -/** - * @brief ADC Configuration multi-mode structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Configures the ADC to operate in independent or multi mode. - This parameter can be a value of @ref ADCEx_Common_mode */ - uint32_t DMAAccessMode; /*!< Configures the Direct memory access mode for multi ADC mode. - This parameter can be a value of @ref ADCEx_Direct_memory_access_mode_for_multi_mode */ - uint32_t TwoSamplingDelay; /*!< Configures the Delay between 2 sampling phases. - This parameter can be a value of @ref ADC_delay_between_2_sampling_phases */ -}ADC_MultiModeTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup ADCEx_Exported_Constants ADC Exported Constants - * @{ - */ - -/** @defgroup ADCEx_Common_mode ADC Common Mode - * @{ - */ -#define ADC_MODE_INDEPENDENT 0x00000000U -#define ADC_DUALMODE_REGSIMULT_INJECSIMULT ((uint32_t)ADC_CCR_MULTI_0) -#define ADC_DUALMODE_REGSIMULT_ALTERTRIG ((uint32_t)ADC_CCR_MULTI_1) -#define ADC_DUALMODE_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0)) -#define ADC_DUALMODE_REGSIMULT ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1)) -#define ADC_DUALMODE_INTERL ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0)) -#define ADC_DUALMODE_ALTERTRIG ((uint32_t)(ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0)) -#define ADC_TRIPLEMODE_REGSIMULT_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0)) -#define ADC_TRIPLEMODE_REGSIMULT_AlterTrig ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_1)) -#define ADC_TRIPLEMODE_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0)) -#define ADC_TRIPLEMODE_REGSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1)) -#define ADC_TRIPLEMODE_INTERL ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0)) -#define ADC_TRIPLEMODE_ALTERTRIG ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0)) -/** - * @} - */ - -/** @defgroup ADCEx_Direct_memory_access_mode_for_multi_mode ADC Direct Memory Access Mode For Multi Mode - * @{ - */ -#define ADC_DMAACCESSMODE_DISABLED 0x00000000U /*!< DMA mode disabled */ -#define ADC_DMAACCESSMODE_1 ((uint32_t)ADC_CCR_DMA_0) /*!< DMA mode 1 enabled (2 / 3 half-words one by one - 1 then 2 then 3)*/ -#define ADC_DMAACCESSMODE_2 ((uint32_t)ADC_CCR_DMA_1) /*!< DMA mode 2 enabled (2 / 3 half-words by pairs - 2&1 then 1&3 then 3&2)*/ -#define ADC_DMAACCESSMODE_3 ((uint32_t)ADC_CCR_DMA) /*!< DMA mode 3 enabled (2 / 3 bytes by pairs - 2&1 then 1&3 then 3&2) */ -/** - * @} - */ - -/** @defgroup ADCEx_External_trigger_edge_Injected ADC External Trigger Edge Injected - * @{ - */ -#define ADC_EXTERNALTRIGINJECCONVEDGE_NONE 0x00000000U -#define ADC_EXTERNALTRIGINJECCONVEDGE_RISING ((uint32_t)ADC_CR2_JEXTEN_0) -#define ADC_EXTERNALTRIGINJECCONVEDGE_FALLING ((uint32_t)ADC_CR2_JEXTEN_1) -#define ADC_EXTERNALTRIGINJECCONVEDGE_RISINGFALLING ((uint32_t)ADC_CR2_JEXTEN) -/** - * @} - */ - -/** @defgroup ADCEx_External_trigger_Source_Injected ADC External Trigger Source Injected - * @{ - */ -#define ADC_EXTERNALTRIGINJECCONV_T1_CC4 0x00000000U -#define ADC_EXTERNALTRIGINJECCONV_T1_TRGO ((uint32_t)ADC_CR2_JEXTSEL_0) -#define ADC_EXTERNALTRIGINJECCONV_T2_CC1 ((uint32_t)ADC_CR2_JEXTSEL_1) -#define ADC_EXTERNALTRIGINJECCONV_T2_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T3_CC2 ((uint32_t)ADC_CR2_JEXTSEL_2) -#define ADC_EXTERNALTRIGINJECCONV_T3_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T4_CC1 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1)) -#define ADC_EXTERNALTRIGINJECCONV_T4_CC2 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T4_CC3 ((uint32_t)ADC_CR2_JEXTSEL_3) -#define ADC_EXTERNALTRIGINJECCONV_T4_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T5_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1)) -#define ADC_EXTERNALTRIGINJECCONV_T5_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T8_CC2 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2)) -#define ADC_EXTERNALTRIGINJECCONV_T8_CC3 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T8_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1)) -#define ADC_EXTERNALTRIGINJECCONV_EXT_IT15 ((uint32_t)ADC_CR2_JEXTSEL) -#define ADC_INJECTED_SOFTWARE_START ((uint32_t)ADC_CR2_JEXTSEL + 1U) -/** - * @} - */ - -/** @defgroup ADCEx_injected_rank ADC Injected Rank - * @{ - */ -#define ADC_INJECTED_RANK_1 0x00000001U -#define ADC_INJECTED_RANK_2 0x00000002U -#define ADC_INJECTED_RANK_3 0x00000003U -#define ADC_INJECTED_RANK_4 0x00000004U -/** - * @} - */ - -/** @defgroup ADCEx_channels ADC Specific Channels - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ - defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ - defined(STM32F412Cx) -#define ADC_CHANNEL_TEMPSENSOR ((uint32_t)ADC_CHANNEL_16) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx || STM32F412Zx || - STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F411xE) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT 0x10000000U /* Dummy bit for driver internal usage, not used in ADC channel setting registers CR1 or SQRx */ -#define ADC_CHANNEL_TEMPSENSOR ((uint32_t)ADC_CHANNEL_18 | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) -#endif /* STM32F411xE || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup ADC_Exported_Macros ADC Exported Macros - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) -/** - * @brief Disable internal path of ADC channel Vbat - * @note Use case of this macro: - * On devices STM32F42x and STM32F43x, ADC internal channels - * Vbat and VrefInt share the same internal path, only - * one of them can be enabled.This macro is to be used when ADC - * channels Vbat and VrefInt are selected, and must be called - * before starting conversion of ADC channel VrefInt in order - * to disable ADC channel Vbat. - * @retval None - */ -#define __HAL_ADC_PATH_INTERNAL_VBAT_DISABLE() (ADC->CCR &= ~(ADC_CCR_VBATE)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup ADCEx_Exported_Functions - * @{ - */ - -/** @addtogroup ADCEx_Exported_Functions_Group1 - * @{ - */ - -/* I/O operation functions ******************************************************/ -HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout); -HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc); -uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank); -HAL_StatusTypeDef HAL_ADCEx_MultiModeStart_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length); -HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc); -uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc); -void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc); - -/* Peripheral Control functions *************************************************/ -HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc,ADC_InjectionConfTypeDef* sConfigInjected); -HAL_StatusTypeDef HAL_ADCEx_MultiModeConfigChannel(ADC_HandleTypeDef* hadc, ADC_MultiModeTypeDef* multimode); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup ADCEx_Private_Constants ADC Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup ADCEx_Private_Macros ADC Private Macros - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ - defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ - defined(STM32F412Cx) -#define IS_ADC_CHANNEL(CHANNEL) ((CHANNEL) <= ADC_CHANNEL_18) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || - STM32F410xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F411xE) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || \ - defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) -#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) <= ADC_CHANNEL_18) || \ - ((CHANNEL) == ADC_CHANNEL_TEMPSENSOR)) -#endif /* STM32F411xE || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#define IS_ADC_MODE(MODE) (((MODE) == ADC_MODE_INDEPENDENT) || \ - ((MODE) == ADC_DUALMODE_REGSIMULT_INJECSIMULT) || \ - ((MODE) == ADC_DUALMODE_REGSIMULT_ALTERTRIG) || \ - ((MODE) == ADC_DUALMODE_INJECSIMULT) || \ - ((MODE) == ADC_DUALMODE_REGSIMULT) || \ - ((MODE) == ADC_DUALMODE_INTERL) || \ - ((MODE) == ADC_DUALMODE_ALTERTRIG) || \ - ((MODE) == ADC_TRIPLEMODE_REGSIMULT_INJECSIMULT) || \ - ((MODE) == ADC_TRIPLEMODE_REGSIMULT_AlterTrig) || \ - ((MODE) == ADC_TRIPLEMODE_INJECSIMULT) || \ - ((MODE) == ADC_TRIPLEMODE_REGSIMULT) || \ - ((MODE) == ADC_TRIPLEMODE_INTERL) || \ - ((MODE) == ADC_TRIPLEMODE_ALTERTRIG)) -#define IS_ADC_DMA_ACCESS_MODE(MODE) (((MODE) == ADC_DMAACCESSMODE_DISABLED) || \ - ((MODE) == ADC_DMAACCESSMODE_1) || \ - ((MODE) == ADC_DMAACCESSMODE_2) || \ - ((MODE) == ADC_DMAACCESSMODE_3)) -#define IS_ADC_EXT_INJEC_TRIG_EDGE(EDGE) (((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_NONE) || \ - ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_RISING) || \ - ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_FALLING) || \ - ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_RISINGFALLING)) -#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T1_CC4) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T1_TRGO) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T2_CC1) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T2_TRGO) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T3_CC2) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T3_CC4) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC1) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC2) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC3) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_TRGO) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T5_CC4) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T5_TRGO) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC2) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC3) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC4) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_EXT_IT15)|| \ - ((INJTRIG) == ADC_INJECTED_SOFTWARE_START)) -#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 1U) && ((LENGTH) <= 4U)) -#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 1U) && ((RANK) <= 4U)) - -/** - * @brief Set the selected injected Channel rank. - * @param _CHANNELNB_ Channel number. - * @param _RANKNB_ Rank number. - * @param _JSQR_JL_ Sequence length. - * @retval None - */ -#define ADC_JSQR(_CHANNELNB_, _RANKNB_, _JSQR_JL_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * (uint8_t)(((_RANKNB_) + 3U) - (_JSQR_JL_)))) - -/** - * @brief Defines if the selected ADC is within ADC common register ADC123 or ADC1 - * if available (ADC2, ADC3 availability depends on STM32 product) - * @param __HANDLE__ ADC handle - * @retval Common control register ADC123 or ADC1 - */ -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F429xx) || defined(STM32F437xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define ADC_COMMON_REGISTER(__HANDLE__) ADC123_COMMON -#else -#define ADC_COMMON_REGISTER(__HANDLE__) ADC1_COMMON -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx || STM32F427xx || STM32F429xx || STM32F437xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup ADCEx_Private_Functions ADC Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F4xx_ADC_EX_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h deleted file mode 100644 index 062abd69250be73..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h +++ /dev/null @@ -1,848 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_can.h - * @author MCD Application Team - * @brief Header file of CAN HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_CAN_H -#define STM32F4xx_HAL_CAN_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (CAN1) -/** @addtogroup CAN - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CAN_Exported_Types CAN Exported Types - * @{ - */ -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_CAN_STATE_RESET = 0x00U, /*!< CAN not yet initialized or disabled */ - HAL_CAN_STATE_READY = 0x01U, /*!< CAN initialized and ready for use */ - HAL_CAN_STATE_LISTENING = 0x02U, /*!< CAN receive process is ongoing */ - HAL_CAN_STATE_SLEEP_PENDING = 0x03U, /*!< CAN sleep request is pending */ - HAL_CAN_STATE_SLEEP_ACTIVE = 0x04U, /*!< CAN sleep mode is active */ - HAL_CAN_STATE_ERROR = 0x05U /*!< CAN error state */ - -} HAL_CAN_StateTypeDef; - -/** - * @brief CAN init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the length of a time quantum. - This parameter must be a number between Min_Data = 1 and Max_Data = 1024. */ - - uint32_t Mode; /*!< Specifies the CAN operating mode. - This parameter can be a value of @ref CAN_operating_mode */ - - uint32_t SyncJumpWidth; /*!< Specifies the maximum number of time quanta the CAN hardware - is allowed to lengthen or shorten a bit to perform resynchronization. - This parameter can be a value of @ref CAN_synchronisation_jump_width */ - - uint32_t TimeSeg1; /*!< Specifies the number of time quanta in Bit Segment 1. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */ - - uint32_t TimeSeg2; /*!< Specifies the number of time quanta in Bit Segment 2. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ - - FunctionalState TimeTriggeredMode; /*!< Enable or disable the time triggered communication mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoBusOff; /*!< Enable or disable the automatic bus-off management. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoWakeUp; /*!< Enable or disable the automatic wake-up mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoRetransmission; /*!< Enable or disable the non-automatic retransmission mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState ReceiveFifoLocked; /*!< Enable or disable the Receive FIFO Locked mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState TransmitFifoPriority;/*!< Enable or disable the transmit FIFO priority. - This parameter can be set to ENABLE or DISABLE. */ - -} CAN_InitTypeDef; - -/** - * @brief CAN filter configuration structure definition - */ -typedef struct -{ - uint32_t FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit - configuration, first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit - configuration, second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, - according to the mode (MSBs for a 32-bit configuration, - first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, - according to the mode (LSBs for a 32-bit configuration, - second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1U) which will be assigned to the filter. - This parameter can be a value of @ref CAN_filter_FIFO */ - - uint32_t FilterBank; /*!< Specifies the filter bank which will be initialized. - For single CAN instance(14 dedicated filter banks), - this parameter must be a number between Min_Data = 0 and Max_Data = 13. - For dual CAN instances(28 filter banks shared), - this parameter must be a number between Min_Data = 0 and Max_Data = 27. */ - - uint32_t FilterMode; /*!< Specifies the filter mode to be initialized. - This parameter can be a value of @ref CAN_filter_mode */ - - uint32_t FilterScale; /*!< Specifies the filter scale. - This parameter can be a value of @ref CAN_filter_scale */ - - uint32_t FilterActivation; /*!< Enable or disable the filter. - This parameter can be a value of @ref CAN_filter_activation */ - - uint32_t SlaveStartFilterBank; /*!< Select the start filter bank for the slave CAN instance. - For single CAN instances, this parameter is meaningless. - For dual CAN instances, all filter banks with lower index are assigned to master - CAN instance, whereas all filter banks with greater index are assigned to slave - CAN instance. - This parameter must be a number between Min_Data = 0 and Max_Data = 27. */ - -} CAN_FilterTypeDef; - -/** - * @brief CAN Tx message header structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF. */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF. */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_identifier_type */ - - uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 8. */ - - FunctionalState TransmitGlobalTime; /*!< Specifies whether the timestamp counter value captured on start - of frame transmission, is sent in DATA6 and DATA7 replacing pData[6] and pData[7]. - @note: Time Triggered Communication Mode must be enabled. - @note: DLC must be programmed as 8 bytes, in order these 2 bytes are sent. - This parameter can be set to ENABLE or DISABLE. */ - -} CAN_TxHeaderTypeDef; - -/** - * @brief CAN Rx message header structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF. */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF. */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_identifier_type */ - - uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 8. */ - - uint32_t Timestamp; /*!< Specifies the timestamp counter value captured on start of frame reception. - @note: Time Triggered Communication Mode must be enabled. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFFFF. */ - - uint32_t FilterMatchIndex; /*!< Specifies the index of matching acceptance filter element. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF. */ - -} CAN_RxHeaderTypeDef; - -/** - * @brief CAN handle Structure definition - */ -typedef struct __CAN_HandleTypeDef -{ - CAN_TypeDef *Instance; /*!< Register base address */ - - CAN_InitTypeDef Init; /*!< CAN required parameters */ - - __IO HAL_CAN_StateTypeDef State; /*!< CAN communication state */ - - __IO uint32_t ErrorCode; /*!< CAN Error code. - This parameter can be a value of @ref CAN_Error_Code */ - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - void (* TxMailbox0CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 0 complete callback */ - void (* TxMailbox1CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 1 complete callback */ - void (* TxMailbox2CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 2 complete callback */ - void (* TxMailbox0AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 0 abort callback */ - void (* TxMailbox1AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 1 abort callback */ - void (* TxMailbox2AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 2 abort callback */ - void (* RxFifo0MsgPendingCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 0 msg pending callback */ - void (* RxFifo0FullCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 0 full callback */ - void (* RxFifo1MsgPendingCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 1 msg pending callback */ - void (* RxFifo1FullCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 1 full callback */ - void (* SleepCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Sleep callback */ - void (* WakeUpFromRxMsgCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Wake Up from Rx msg callback */ - void (* ErrorCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Error callback */ - - void (* MspInitCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Msp Init callback */ - void (* MspDeInitCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Msp DeInit callback */ - -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ -} CAN_HandleTypeDef; - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -/** - * @brief HAL CAN common Callback ID enumeration definition - */ -typedef enum -{ - HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID = 0x00U, /*!< CAN Tx Mailbox 0 complete callback ID */ - HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID = 0x01U, /*!< CAN Tx Mailbox 1 complete callback ID */ - HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID = 0x02U, /*!< CAN Tx Mailbox 2 complete callback ID */ - HAL_CAN_TX_MAILBOX0_ABORT_CB_ID = 0x03U, /*!< CAN Tx Mailbox 0 abort callback ID */ - HAL_CAN_TX_MAILBOX1_ABORT_CB_ID = 0x04U, /*!< CAN Tx Mailbox 1 abort callback ID */ - HAL_CAN_TX_MAILBOX2_ABORT_CB_ID = 0x05U, /*!< CAN Tx Mailbox 2 abort callback ID */ - HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID = 0x06U, /*!< CAN Rx FIFO 0 message pending callback ID */ - HAL_CAN_RX_FIFO0_FULL_CB_ID = 0x07U, /*!< CAN Rx FIFO 0 full callback ID */ - HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID = 0x08U, /*!< CAN Rx FIFO 1 message pending callback ID */ - HAL_CAN_RX_FIFO1_FULL_CB_ID = 0x09U, /*!< CAN Rx FIFO 1 full callback ID */ - HAL_CAN_SLEEP_CB_ID = 0x0AU, /*!< CAN Sleep callback ID */ - HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID = 0x0BU, /*!< CAN Wake Up from Rx msg callback ID */ - HAL_CAN_ERROR_CB_ID = 0x0CU, /*!< CAN Error callback ID */ - - HAL_CAN_MSPINIT_CB_ID = 0x0DU, /*!< CAN MspInit callback ID */ - HAL_CAN_MSPDEINIT_CB_ID = 0x0EU, /*!< CAN MspDeInit callback ID */ - -} HAL_CAN_CallbackIDTypeDef; - -/** - * @brief HAL CAN Callback pointer definition - */ -typedef void (*pCAN_CallbackTypeDef)(CAN_HandleTypeDef *hcan); /*!< pointer to a CAN callback function */ - -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup CAN_Exported_Constants CAN Exported Constants - * @{ - */ - -/** @defgroup CAN_Error_Code CAN Error Code - * @{ - */ -#define HAL_CAN_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_CAN_ERROR_EWG (0x00000001U) /*!< Protocol Error Warning */ -#define HAL_CAN_ERROR_EPV (0x00000002U) /*!< Error Passive */ -#define HAL_CAN_ERROR_BOF (0x00000004U) /*!< Bus-off error */ -#define HAL_CAN_ERROR_STF (0x00000008U) /*!< Stuff error */ -#define HAL_CAN_ERROR_FOR (0x00000010U) /*!< Form error */ -#define HAL_CAN_ERROR_ACK (0x00000020U) /*!< Acknowledgment error */ -#define HAL_CAN_ERROR_BR (0x00000040U) /*!< Bit recessive error */ -#define HAL_CAN_ERROR_BD (0x00000080U) /*!< Bit dominant error */ -#define HAL_CAN_ERROR_CRC (0x00000100U) /*!< CRC error */ -#define HAL_CAN_ERROR_RX_FOV0 (0x00000200U) /*!< Rx FIFO0 overrun error */ -#define HAL_CAN_ERROR_RX_FOV1 (0x00000400U) /*!< Rx FIFO1 overrun error */ -#define HAL_CAN_ERROR_TX_ALST0 (0x00000800U) /*!< TxMailbox 0 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR0 (0x00001000U) /*!< TxMailbox 0 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TX_ALST1 (0x00002000U) /*!< TxMailbox 1 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR1 (0x00004000U) /*!< TxMailbox 1 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TX_ALST2 (0x00008000U) /*!< TxMailbox 2 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR2 (0x00010000U) /*!< TxMailbox 2 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TIMEOUT (0x00020000U) /*!< Timeout error */ -#define HAL_CAN_ERROR_NOT_INITIALIZED (0x00040000U) /*!< Peripheral not initialized */ -#define HAL_CAN_ERROR_NOT_READY (0x00080000U) /*!< Peripheral not ready */ -#define HAL_CAN_ERROR_NOT_STARTED (0x00100000U) /*!< Peripheral not started */ -#define HAL_CAN_ERROR_PARAM (0x00200000U) /*!< Parameter error */ - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -#define HAL_CAN_ERROR_INVALID_CALLBACK (0x00400000U) /*!< Invalid Callback error */ -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ -#define HAL_CAN_ERROR_INTERNAL (0x00800000U) /*!< Internal error */ - -/** - * @} - */ - -/** @defgroup CAN_InitStatus CAN InitStatus - * @{ - */ -#define CAN_INITSTATUS_FAILED (0x00000000U) /*!< CAN initialization failed */ -#define CAN_INITSTATUS_SUCCESS (0x00000001U) /*!< CAN initialization OK */ -/** - * @} - */ - -/** @defgroup CAN_operating_mode CAN Operating Mode - * @{ - */ -#define CAN_MODE_NORMAL (0x00000000U) /*!< Normal mode */ -#define CAN_MODE_LOOPBACK ((uint32_t)CAN_BTR_LBKM) /*!< Loopback mode */ -#define CAN_MODE_SILENT ((uint32_t)CAN_BTR_SILM) /*!< Silent mode */ -#define CAN_MODE_SILENT_LOOPBACK ((uint32_t)(CAN_BTR_LBKM | CAN_BTR_SILM)) /*!< Loopback combined with silent mode */ -/** - * @} - */ - - -/** @defgroup CAN_synchronisation_jump_width CAN Synchronization Jump Width - * @{ - */ -#define CAN_SJW_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_SJW_2TQ ((uint32_t)CAN_BTR_SJW_0) /*!< 2 time quantum */ -#define CAN_SJW_3TQ ((uint32_t)CAN_BTR_SJW_1) /*!< 3 time quantum */ -#define CAN_SJW_4TQ ((uint32_t)CAN_BTR_SJW) /*!< 4 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_1 CAN Time Quantum in Bit Segment 1 - * @{ - */ -#define CAN_BS1_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_BS1_2TQ ((uint32_t)CAN_BTR_TS1_0) /*!< 2 time quantum */ -#define CAN_BS1_3TQ ((uint32_t)CAN_BTR_TS1_1) /*!< 3 time quantum */ -#define CAN_BS1_4TQ ((uint32_t)(CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 4 time quantum */ -#define CAN_BS1_5TQ ((uint32_t)CAN_BTR_TS1_2) /*!< 5 time quantum */ -#define CAN_BS1_6TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 6 time quantum */ -#define CAN_BS1_7TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 7 time quantum */ -#define CAN_BS1_8TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 8 time quantum */ -#define CAN_BS1_9TQ ((uint32_t)CAN_BTR_TS1_3) /*!< 9 time quantum */ -#define CAN_BS1_10TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_0)) /*!< 10 time quantum */ -#define CAN_BS1_11TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1)) /*!< 11 time quantum */ -#define CAN_BS1_12TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 12 time quantum */ -#define CAN_BS1_13TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2)) /*!< 13 time quantum */ -#define CAN_BS1_14TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 14 time quantum */ -#define CAN_BS1_15TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 15 time quantum */ -#define CAN_BS1_16TQ ((uint32_t)CAN_BTR_TS1) /*!< 16 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_2 CAN Time Quantum in Bit Segment 2 - * @{ - */ -#define CAN_BS2_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_BS2_2TQ ((uint32_t)CAN_BTR_TS2_0) /*!< 2 time quantum */ -#define CAN_BS2_3TQ ((uint32_t)CAN_BTR_TS2_1) /*!< 3 time quantum */ -#define CAN_BS2_4TQ ((uint32_t)(CAN_BTR_TS2_1 | CAN_BTR_TS2_0)) /*!< 4 time quantum */ -#define CAN_BS2_5TQ ((uint32_t)CAN_BTR_TS2_2) /*!< 5 time quantum */ -#define CAN_BS2_6TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_0)) /*!< 6 time quantum */ -#define CAN_BS2_7TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_1)) /*!< 7 time quantum */ -#define CAN_BS2_8TQ ((uint32_t)CAN_BTR_TS2) /*!< 8 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_filter_mode CAN Filter Mode - * @{ - */ -#define CAN_FILTERMODE_IDMASK (0x00000000U) /*!< Identifier mask mode */ -#define CAN_FILTERMODE_IDLIST (0x00000001U) /*!< Identifier list mode */ -/** - * @} - */ - -/** @defgroup CAN_filter_scale CAN Filter Scale - * @{ - */ -#define CAN_FILTERSCALE_16BIT (0x00000000U) /*!< Two 16-bit filters */ -#define CAN_FILTERSCALE_32BIT (0x00000001U) /*!< One 32-bit filter */ -/** - * @} - */ - -/** @defgroup CAN_filter_activation CAN Filter Activation - * @{ - */ -#define CAN_FILTER_DISABLE (0x00000000U) /*!< Disable filter */ -#define CAN_FILTER_ENABLE (0x00000001U) /*!< Enable filter */ -/** - * @} - */ - -/** @defgroup CAN_filter_FIFO CAN Filter FIFO - * @{ - */ -#define CAN_FILTER_FIFO0 (0x00000000U) /*!< Filter FIFO 0 assignment for filter x */ -#define CAN_FILTER_FIFO1 (0x00000001U) /*!< Filter FIFO 1 assignment for filter x */ -/** - * @} - */ - -/** @defgroup CAN_identifier_type CAN Identifier Type - * @{ - */ -#define CAN_ID_STD (0x00000000U) /*!< Standard Id */ -#define CAN_ID_EXT (0x00000004U) /*!< Extended Id */ -/** - * @} - */ - -/** @defgroup CAN_remote_transmission_request CAN Remote Transmission Request - * @{ - */ -#define CAN_RTR_DATA (0x00000000U) /*!< Data frame */ -#define CAN_RTR_REMOTE (0x00000002U) /*!< Remote frame */ -/** - * @} - */ - -/** @defgroup CAN_receive_FIFO_number CAN Receive FIFO Number - * @{ - */ -#define CAN_RX_FIFO0 (0x00000000U) /*!< CAN receive FIFO 0 */ -#define CAN_RX_FIFO1 (0x00000001U) /*!< CAN receive FIFO 1 */ -/** - * @} - */ - -/** @defgroup CAN_Tx_Mailboxes CAN Tx Mailboxes - * @{ - */ -#define CAN_TX_MAILBOX0 (0x00000001U) /*!< Tx Mailbox 0 */ -#define CAN_TX_MAILBOX1 (0x00000002U) /*!< Tx Mailbox 1 */ -#define CAN_TX_MAILBOX2 (0x00000004U) /*!< Tx Mailbox 2 */ -/** - * @} - */ - -/** @defgroup CAN_flags CAN Flags - * @{ - */ -/* Transmit Flags */ -#define CAN_FLAG_RQCP0 (0x00000500U) /*!< Request complete MailBox 0 flag */ -#define CAN_FLAG_TXOK0 (0x00000501U) /*!< Transmission OK MailBox 0 flag */ -#define CAN_FLAG_ALST0 (0x00000502U) /*!< Arbitration Lost MailBox 0 flag */ -#define CAN_FLAG_TERR0 (0x00000503U) /*!< Transmission error MailBox 0 flag */ -#define CAN_FLAG_RQCP1 (0x00000508U) /*!< Request complete MailBox1 flag */ -#define CAN_FLAG_TXOK1 (0x00000509U) /*!< Transmission OK MailBox 1 flag */ -#define CAN_FLAG_ALST1 (0x0000050AU) /*!< Arbitration Lost MailBox 1 flag */ -#define CAN_FLAG_TERR1 (0x0000050BU) /*!< Transmission error MailBox 1 flag */ -#define CAN_FLAG_RQCP2 (0x00000510U) /*!< Request complete MailBox2 flag */ -#define CAN_FLAG_TXOK2 (0x00000511U) /*!< Transmission OK MailBox 2 flag */ -#define CAN_FLAG_ALST2 (0x00000512U) /*!< Arbitration Lost MailBox 2 flag */ -#define CAN_FLAG_TERR2 (0x00000513U) /*!< Transmission error MailBox 2 flag */ -#define CAN_FLAG_TME0 (0x0000051AU) /*!< Transmit mailbox 0 empty flag */ -#define CAN_FLAG_TME1 (0x0000051BU) /*!< Transmit mailbox 1 empty flag */ -#define CAN_FLAG_TME2 (0x0000051CU) /*!< Transmit mailbox 2 empty flag */ -#define CAN_FLAG_LOW0 (0x0000051DU) /*!< Lowest priority mailbox 0 flag */ -#define CAN_FLAG_LOW1 (0x0000051EU) /*!< Lowest priority mailbox 1 flag */ -#define CAN_FLAG_LOW2 (0x0000051FU) /*!< Lowest priority mailbox 2 flag */ - -/* Receive Flags */ -#define CAN_FLAG_FF0 (0x00000203U) /*!< RX FIFO 0 Full flag */ -#define CAN_FLAG_FOV0 (0x00000204U) /*!< RX FIFO 0 Overrun flag */ -#define CAN_FLAG_FF1 (0x00000403U) /*!< RX FIFO 1 Full flag */ -#define CAN_FLAG_FOV1 (0x00000404U) /*!< RX FIFO 1 Overrun flag */ - -/* Operating Mode Flags */ -#define CAN_FLAG_INAK (0x00000100U) /*!< Initialization acknowledge flag */ -#define CAN_FLAG_SLAK (0x00000101U) /*!< Sleep acknowledge flag */ -#define CAN_FLAG_ERRI (0x00000102U) /*!< Error flag */ -#define CAN_FLAG_WKU (0x00000103U) /*!< Wake up interrupt flag */ -#define CAN_FLAG_SLAKI (0x00000104U) /*!< Sleep acknowledge interrupt flag */ - -/* Error Flags */ -#define CAN_FLAG_EWG (0x00000300U) /*!< Error warning flag */ -#define CAN_FLAG_EPV (0x00000301U) /*!< Error passive flag */ -#define CAN_FLAG_BOF (0x00000302U) /*!< Bus-Off flag */ -/** - * @} - */ - - -/** @defgroup CAN_Interrupts CAN Interrupts - * @{ - */ -/* Transmit Interrupt */ -#define CAN_IT_TX_MAILBOX_EMPTY ((uint32_t)CAN_IER_TMEIE) /*!< Transmit mailbox empty interrupt */ - -/* Receive Interrupts */ -#define CAN_IT_RX_FIFO0_MSG_PENDING ((uint32_t)CAN_IER_FMPIE0) /*!< FIFO 0 message pending interrupt */ -#define CAN_IT_RX_FIFO0_FULL ((uint32_t)CAN_IER_FFIE0) /*!< FIFO 0 full interrupt */ -#define CAN_IT_RX_FIFO0_OVERRUN ((uint32_t)CAN_IER_FOVIE0) /*!< FIFO 0 overrun interrupt */ -#define CAN_IT_RX_FIFO1_MSG_PENDING ((uint32_t)CAN_IER_FMPIE1) /*!< FIFO 1 message pending interrupt */ -#define CAN_IT_RX_FIFO1_FULL ((uint32_t)CAN_IER_FFIE1) /*!< FIFO 1 full interrupt */ -#define CAN_IT_RX_FIFO1_OVERRUN ((uint32_t)CAN_IER_FOVIE1) /*!< FIFO 1 overrun interrupt */ - -/* Operating Mode Interrupts */ -#define CAN_IT_WAKEUP ((uint32_t)CAN_IER_WKUIE) /*!< Wake-up interrupt */ -#define CAN_IT_SLEEP_ACK ((uint32_t)CAN_IER_SLKIE) /*!< Sleep acknowledge interrupt */ - -/* Error Interrupts */ -#define CAN_IT_ERROR_WARNING ((uint32_t)CAN_IER_EWGIE) /*!< Error warning interrupt */ -#define CAN_IT_ERROR_PASSIVE ((uint32_t)CAN_IER_EPVIE) /*!< Error passive interrupt */ -#define CAN_IT_BUSOFF ((uint32_t)CAN_IER_BOFIE) /*!< Bus-off interrupt */ -#define CAN_IT_LAST_ERROR_CODE ((uint32_t)CAN_IER_LECIE) /*!< Last error code interrupt */ -#define CAN_IT_ERROR ((uint32_t)CAN_IER_ERRIE) /*!< Error Interrupt */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CAN_Exported_Macros CAN Exported Macros - * @{ - */ - -/** @brief Reset CAN handle state - * @param __HANDLE__ CAN handle. - * @retval None - */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_CAN_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CAN_STATE_RESET) -#endif /*USE_HAL_CAN_REGISTER_CALLBACKS */ - -/** - * @brief Enable the specified CAN interrupts. - * @param __HANDLE__ CAN handle. - * @param __INTERRUPT__ CAN Interrupt sources to enable. - * This parameter can be any combination of @arg CAN_Interrupts - * @retval None - */ -#define __HAL_CAN_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) |= (__INTERRUPT__)) - -/** - * @brief Disable the specified CAN interrupts. - * @param __HANDLE__ CAN handle. - * @param __INTERRUPT__ CAN Interrupt sources to disable. - * This parameter can be any combination of @arg CAN_Interrupts - * @retval None - */ -#define __HAL_CAN_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) &= ~(__INTERRUPT__)) - -/** @brief Check if the specified CAN interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the CAN Handle. - * @param __INTERRUPT__ specifies the CAN interrupt source to check. - * This parameter can be a value of @arg CAN_Interrupts - * @retval The state of __IT__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) & (__INTERRUPT__)) - -/** @brief Check whether the specified CAN flag is set or not. - * @param __HANDLE__ specifies the CAN Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of @arg CAN_flags - * @retval The state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_FLAG(__HANDLE__, __FLAG__) \ - ((((__FLAG__) >> 8U) == 5U)? ((((__HANDLE__)->Instance->TSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? ((((__HANDLE__)->Instance->RF0R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? ((((__HANDLE__)->Instance->RF1R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 1U)? ((((__HANDLE__)->Instance->MSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 3U)? ((((__HANDLE__)->Instance->ESR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): 0U) - -/** @brief Clear the specified CAN pending flag. - * @param __HANDLE__ specifies the CAN Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg CAN_FLAG_RQCP0: Request complete MailBox 0 Flag - * @arg CAN_FLAG_TXOK0: Transmission OK MailBox 0 Flag - * @arg CAN_FLAG_ALST0: Arbitration Lost MailBox 0 Flag - * @arg CAN_FLAG_TERR0: Transmission error MailBox 0 Flag - * @arg CAN_FLAG_RQCP1: Request complete MailBox 1 Flag - * @arg CAN_FLAG_TXOK1: Transmission OK MailBox 1 Flag - * @arg CAN_FLAG_ALST1: Arbitration Lost MailBox 1 Flag - * @arg CAN_FLAG_TERR1: Transmission error MailBox 1 Flag - * @arg CAN_FLAG_RQCP2: Request complete MailBox 2 Flag - * @arg CAN_FLAG_TXOK2: Transmission OK MailBox 2 Flag - * @arg CAN_FLAG_ALST2: Arbitration Lost MailBox 2 Flag - * @arg CAN_FLAG_TERR2: Transmission error MailBox 2 Flag - * @arg CAN_FLAG_FF0: RX FIFO 0 Full Flag - * @arg CAN_FLAG_FOV0: RX FIFO 0 Overrun Flag - * @arg CAN_FLAG_FF1: RX FIFO 1 Full Flag - * @arg CAN_FLAG_FOV1: RX FIFO 1 Overrun Flag - * @arg CAN_FLAG_WKUI: Wake up Interrupt Flag - * @arg CAN_FLAG_SLAKI: Sleep acknowledge Interrupt Flag - * @retval None - */ -#define __HAL_CAN_CLEAR_FLAG(__HANDLE__, __FLAG__) \ - ((((__FLAG__) >> 8U) == 5U)? (((__HANDLE__)->Instance->TSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? (((__HANDLE__)->Instance->RF0R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? (((__HANDLE__)->Instance->RF1R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 1U)? (((__HANDLE__)->Instance->MSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): 0U) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CAN_Exported_Functions CAN Exported Functions - * @{ - */ - -/** @addtogroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * @{ - */ - -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef *hcan); -void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan); -void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan); - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_CAN_RegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID, void (* pCallback)(CAN_HandleTypeDef *_hcan)); -HAL_StatusTypeDef HAL_CAN_UnRegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID); - -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group2 Configuration functions - * @brief Configuration functions - * @{ - */ - -/* Configuration functions ****************************************************/ -HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef *hcan, CAN_FilterTypeDef *sFilterConfig); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group3 Control functions - * @brief Control functions - * @{ - */ - -/* Control functions **********************************************************/ -HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_Stop(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_RequestSleep(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_IsSleepActive(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_AddTxMessage(CAN_HandleTypeDef *hcan, CAN_TxHeaderTypeDef *pHeader, uint8_t aData[], uint32_t *pTxMailbox); -HAL_StatusTypeDef HAL_CAN_AbortTxRequest(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes); -uint32_t HAL_CAN_GetTxMailboxesFreeLevel(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_IsTxMessagePending(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes); -uint32_t HAL_CAN_GetTxTimestamp(CAN_HandleTypeDef *hcan, uint32_t TxMailbox); -HAL_StatusTypeDef HAL_CAN_GetRxMessage(CAN_HandleTypeDef *hcan, uint32_t RxFifo, CAN_RxHeaderTypeDef *pHeader, uint8_t aData[]); -uint32_t HAL_CAN_GetRxFifoFillLevel(CAN_HandleTypeDef *hcan, uint32_t RxFifo); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group4 Interrupts management - * @brief Interrupts management - * @{ - */ -/* Interrupts management ******************************************************/ -HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *hcan, uint32_t ActiveITs); -HAL_StatusTypeDef HAL_CAN_DeactivateNotification(CAN_HandleTypeDef *hcan, uint32_t InactiveITs); -void HAL_CAN_IRQHandler(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group5 Callback functions - * @brief Callback functions - * @{ - */ -/* Callbacks functions ********************************************************/ - -void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group6 Peripheral State and Error functions - * @brief CAN Peripheral State functions - * @{ - */ -/* Peripheral State and Error functions ***************************************/ -HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_ResetError(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CAN_Private_Types CAN Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Variables CAN Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Constants CAN Private Constants - * @{ - */ -#define CAN_FLAG_MASK (0x000000FFU) -/** - * @} - */ - -/* Private Macros -----------------------------------------------------------*/ -/** @defgroup CAN_Private_Macros CAN Private Macros - * @{ - */ - -#define IS_CAN_MODE(MODE) (((MODE) == CAN_MODE_NORMAL) || \ - ((MODE) == CAN_MODE_LOOPBACK)|| \ - ((MODE) == CAN_MODE_SILENT) || \ - ((MODE) == CAN_MODE_SILENT_LOOPBACK)) -#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1TQ) || ((SJW) == CAN_SJW_2TQ) || \ - ((SJW) == CAN_SJW_3TQ) || ((SJW) == CAN_SJW_4TQ)) -#define IS_CAN_BS1(BS1) (((BS1) == CAN_BS1_1TQ) || ((BS1) == CAN_BS1_2TQ) || \ - ((BS1) == CAN_BS1_3TQ) || ((BS1) == CAN_BS1_4TQ) || \ - ((BS1) == CAN_BS1_5TQ) || ((BS1) == CAN_BS1_6TQ) || \ - ((BS1) == CAN_BS1_7TQ) || ((BS1) == CAN_BS1_8TQ) || \ - ((BS1) == CAN_BS1_9TQ) || ((BS1) == CAN_BS1_10TQ)|| \ - ((BS1) == CAN_BS1_11TQ)|| ((BS1) == CAN_BS1_12TQ)|| \ - ((BS1) == CAN_BS1_13TQ)|| ((BS1) == CAN_BS1_14TQ)|| \ - ((BS1) == CAN_BS1_15TQ)|| ((BS1) == CAN_BS1_16TQ)) -#define IS_CAN_BS2(BS2) (((BS2) == CAN_BS2_1TQ) || ((BS2) == CAN_BS2_2TQ) || \ - ((BS2) == CAN_BS2_3TQ) || ((BS2) == CAN_BS2_4TQ) || \ - ((BS2) == CAN_BS2_5TQ) || ((BS2) == CAN_BS2_6TQ) || \ - ((BS2) == CAN_BS2_7TQ) || ((BS2) == CAN_BS2_8TQ)) -#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1U) && ((PRESCALER) <= 1024U)) -#define IS_CAN_FILTER_ID_HALFWORD(HALFWORD) ((HALFWORD) <= 0xFFFFU) -#define IS_CAN_FILTER_BANK_DUAL(BANK) ((BANK) <= 27U) -#define IS_CAN_FILTER_BANK_SINGLE(BANK) ((BANK) <= 13U) -#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FILTERMODE_IDMASK) || \ - ((MODE) == CAN_FILTERMODE_IDLIST)) -#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FILTERSCALE_16BIT) || \ - ((SCALE) == CAN_FILTERSCALE_32BIT)) -#define IS_CAN_FILTER_ACTIVATION(ACTIVATION) (((ACTIVATION) == CAN_FILTER_DISABLE) || \ - ((ACTIVATION) == CAN_FILTER_ENABLE)) -#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FILTER_FIFO0) || \ - ((FIFO) == CAN_FILTER_FIFO1)) -#define IS_CAN_TX_MAILBOX(TRANSMITMAILBOX) (((TRANSMITMAILBOX) == CAN_TX_MAILBOX0 ) || \ - ((TRANSMITMAILBOX) == CAN_TX_MAILBOX1 ) || \ - ((TRANSMITMAILBOX) == CAN_TX_MAILBOX2 )) -#define IS_CAN_TX_MAILBOX_LIST(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= (CAN_TX_MAILBOX0 | CAN_TX_MAILBOX1 | CAN_TX_MAILBOX2)) -#define IS_CAN_STDID(STDID) ((STDID) <= 0x7FFU) -#define IS_CAN_EXTID(EXTID) ((EXTID) <= 0x1FFFFFFFU) -#define IS_CAN_DLC(DLC) ((DLC) <= 8U) -#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || \ - ((IDTYPE) == CAN_ID_EXT)) -#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE)) -#define IS_CAN_RX_FIFO(FIFO) (((FIFO) == CAN_RX_FIFO0) || ((FIFO) == CAN_RX_FIFO1)) -#define IS_CAN_IT(IT) ((IT) <= (CAN_IT_TX_MAILBOX_EMPTY | CAN_IT_RX_FIFO0_MSG_PENDING | \ - CAN_IT_RX_FIFO0_FULL | CAN_IT_RX_FIFO0_OVERRUN | \ - CAN_IT_RX_FIFO1_MSG_PENDING | CAN_IT_RX_FIFO1_FULL | \ - CAN_IT_RX_FIFO1_OVERRUN | CAN_IT_WAKEUP | \ - CAN_IT_SLEEP_ACK | CAN_IT_ERROR_WARNING | \ - CAN_IT_ERROR_PASSIVE | CAN_IT_BUSOFF | \ - CAN_IT_LAST_ERROR_CODE | CAN_IT_ERROR)) - -/** - * @} - */ -/* End of private macros -----------------------------------------------------*/ - -/** - * @} - */ - - -#endif /* CAN1 */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_CAN_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cec.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cec.h deleted file mode 100644 index 90415773694bf09..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cec.h +++ /dev/null @@ -1,794 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cec.h - * @author MCD Application Team - * @brief Header file of CEC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_CEC_H -#define STM32F4xx_HAL_CEC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (CEC) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CEC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CEC_Exported_Types CEC Exported Types - * @{ - */ - -/** - * @brief CEC Init Structure definition - */ -typedef struct -{ - uint32_t SignalFreeTime; /*!< Set SFT field, specifies the Signal Free Time. - It can be one of @ref CEC_Signal_Free_Time - and belongs to the set {0,...,7} where - 0x0 is the default configuration - else means 0.5 + (SignalFreeTime - 1) nominal data bit periods */ - - uint32_t Tolerance; /*!< Set RXTOL bit, specifies the tolerance accepted on the received waveforms, - it can be a value of @ref CEC_Tolerance : it is either CEC_STANDARD_TOLERANCE - or CEC_EXTENDED_TOLERANCE */ - - uint32_t BRERxStop; /*!< Set BRESTP bit @ref CEC_BRERxStop : specifies whether or not a Bit Rising Error stops the reception. - CEC_NO_RX_STOP_ON_BRE: reception is not stopped. - CEC_RX_STOP_ON_BRE: reception is stopped. */ - - uint32_t BREErrorBitGen; /*!< Set BREGEN bit @ref CEC_BREErrorBitGen : specifies whether or not an Error-Bit is generated on the - CEC line upon Bit Rising Error detection. - CEC_BRE_ERRORBIT_NO_GENERATION: no error-bit generation. - CEC_BRE_ERRORBIT_GENERATION: error-bit generation if BRESTP is set. */ - - uint32_t LBPEErrorBitGen; /*!< Set LBPEGEN bit @ref CEC_LBPEErrorBitGen : specifies whether or not an Error-Bit is generated on the - CEC line upon Long Bit Period Error detection. - CEC_LBPE_ERRORBIT_NO_GENERATION: no error-bit generation. - CEC_LBPE_ERRORBIT_GENERATION: error-bit generation. */ - - uint32_t BroadcastMsgNoErrorBitGen; /*!< Set BRDNOGEN bit @ref CEC_BroadCastMsgErrorBitGen : allows to avoid an Error-Bit generation on the CEC line - upon an error detected on a broadcast message. - - It supersedes BREGEN and LBPEGEN bits for a broadcast message error handling. It can take two values: - - 1) CEC_BROADCASTERROR_ERRORBIT_GENERATION. - a) BRE detection: error-bit generation on the CEC line if BRESTP=CEC_RX_STOP_ON_BRE - and BREGEN=CEC_BRE_ERRORBIT_NO_GENERATION. - b) LBPE detection: error-bit generation on the CEC line - if LBPGEN=CEC_LBPE_ERRORBIT_NO_GENERATION. - - 2) CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION. - no error-bit generation in case neither a) nor b) are satisfied. Additionally, - there is no error-bit generation in case of Short Bit Period Error detection in - a broadcast message while LSTN bit is set. */ - - uint32_t SignalFreeTimeOption; /*!< Set SFTOP bit @ref CEC_SFT_Option : specifies when SFT timer starts. - CEC_SFT_START_ON_TXSOM SFT: timer starts when TXSOM is set by software. - CEC_SFT_START_ON_TX_RX_END: SFT timer starts automatically at the end of message transmission/reception. */ - - uint32_t ListenMode; /*!< Set LSTN bit @ref CEC_Listening_Mode : specifies device listening mode. It can take two values: - - CEC_REDUCED_LISTENING_MODE: CEC peripheral receives only message addressed to its - own address (OAR). Messages addressed to different destination are ignored. - Broadcast messages are always received. - - CEC_FULL_LISTENING_MODE: CEC peripheral receives messages addressed to its own - address (OAR) with positive acknowledge. Messages addressed to different destination - are received, but without interfering with the CEC bus: no acknowledge sent. */ - - uint16_t OwnAddress; /*!< Own addresses configuration - This parameter can be a value of @ref CEC_OWN_ADDRESS */ - - uint8_t *RxBuffer; /*!< CEC Rx buffer pointeur */ - - -} CEC_InitTypeDef; - -/** - * @brief HAL CEC State definition - * @note HAL CEC State value is a combination of 2 different substates: gState and RxState (see @ref CEC_State_Definition). - * - gState contains CEC state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7 (not used) - * x : Should be set to 0 - * b6 Error information - * 0 : No Error - * 1 : Error - * b5 CEC peripheral initialization status - * 0 : Reset (peripheral not initialized) - * 1 : Init done (peripheral initialized. HAL CEC Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (peripheral busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 CEC peripheral initialization status - * 0 : Reset (peripheral not initialized) - * 1 : Init done (peripheral initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef uint32_t HAL_CEC_StateTypeDef; - -/** - * @brief CEC handle Structure definition - */ -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -typedef struct __CEC_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -{ - CEC_TypeDef *Instance; /*!< CEC registers base address */ - - CEC_InitTypeDef Init; /*!< CEC communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to CEC Tx transfer Buffer */ - - uint16_t TxXferCount; /*!< CEC Tx Transfer Counter */ - - uint16_t RxXferSize; /*!< CEC Rx Transfer size, 0: header received only */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - HAL_CEC_StateTypeDef gState; /*!< CEC state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_CEC_StateTypeDef */ - - HAL_CEC_StateTypeDef RxState; /*!< CEC state information related to Rx operations. - This parameter can be a value of @ref HAL_CEC_StateTypeDef */ - - uint32_t ErrorCode; /*!< For errors handling purposes, copy of ISR register - in case error is reported */ - -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) - void (* TxCpltCallback)(struct __CEC_HandleTypeDef - *hcec); /*!< CEC Tx Transfer completed callback */ - void (* RxCpltCallback)(struct __CEC_HandleTypeDef *hcec, - uint32_t RxFrameSize); /*!< CEC Rx Transfer completed callback */ - void (* ErrorCallback)(struct __CEC_HandleTypeDef *hcec); /*!< CEC error callback */ - - void (* MspInitCallback)(struct __CEC_HandleTypeDef *hcec); /*!< CEC Msp Init callback */ - void (* MspDeInitCallback)(struct __CEC_HandleTypeDef *hcec); /*!< CEC Msp DeInit callback */ - -#endif /* (USE_HAL_CEC_REGISTER_CALLBACKS) */ -} CEC_HandleTypeDef; - -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL CEC Callback ID enumeration definition - */ -typedef enum -{ - HAL_CEC_TX_CPLT_CB_ID = 0x00U, /*!< CEC Tx Transfer completed callback ID */ - HAL_CEC_RX_CPLT_CB_ID = 0x01U, /*!< CEC Rx Transfer completed callback ID */ - HAL_CEC_ERROR_CB_ID = 0x02U, /*!< CEC error callback ID */ - HAL_CEC_MSPINIT_CB_ID = 0x03U, /*!< CEC Msp Init callback ID */ - HAL_CEC_MSPDEINIT_CB_ID = 0x04U /*!< CEC Msp DeInit callback ID */ -} HAL_CEC_CallbackIDTypeDef; - -/** - * @brief HAL CEC Callback pointer definition - */ -typedef void (*pCEC_CallbackTypeDef)(CEC_HandleTypeDef *hcec); /*!< pointer to an CEC callback function */ -typedef void (*pCEC_RxCallbackTypeDef)(CEC_HandleTypeDef *hcec, - uint32_t RxFrameSize); /*!< pointer to an Rx Transfer completed callback function */ -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CEC_Exported_Constants CEC Exported Constants - * @{ - */ -/** @defgroup CEC_State_Definition CEC State Code Definition - * @{ - */ -#define HAL_CEC_STATE_RESET ((uint32_t)0x00000000) /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ -#define HAL_CEC_STATE_READY ((uint32_t)0x00000020) /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ -#define HAL_CEC_STATE_BUSY ((uint32_t)0x00000024) /*!< an internal process is ongoing - Value is allowed for gState only */ -#define HAL_CEC_STATE_BUSY_RX ((uint32_t)0x00000022) /*!< Data Reception process is ongoing - Value is allowed for RxState only */ -#define HAL_CEC_STATE_BUSY_TX ((uint32_t)0x00000021) /*!< Data Transmission process is ongoing - Value is allowed for gState only */ -#define HAL_CEC_STATE_BUSY_RX_TX ((uint32_t)0x00000023) /*!< an internal process is ongoing - Value is allowed for gState only */ -#define HAL_CEC_STATE_ERROR ((uint32_t)0x00000050) /*!< Error Value is allowed for gState only */ -/** - * @} - */ -/** @defgroup CEC_Error_Code CEC Error Code - * @{ - */ -#define HAL_CEC_ERROR_NONE (uint32_t) 0x0000U /*!< no error */ -#define HAL_CEC_ERROR_RXOVR CEC_ISR_RXOVR /*!< CEC Rx-Overrun */ -#define HAL_CEC_ERROR_BRE CEC_ISR_BRE /*!< CEC Rx Bit Rising Error */ -#define HAL_CEC_ERROR_SBPE CEC_ISR_SBPE /*!< CEC Rx Short Bit period Error */ -#define HAL_CEC_ERROR_LBPE CEC_ISR_LBPE /*!< CEC Rx Long Bit period Error */ -#define HAL_CEC_ERROR_RXACKE CEC_ISR_RXACKE /*!< CEC Rx Missing Acknowledge */ -#define HAL_CEC_ERROR_ARBLST CEC_ISR_ARBLST /*!< CEC Arbitration Lost */ -#define HAL_CEC_ERROR_TXUDR CEC_ISR_TXUDR /*!< CEC Tx-Buffer Underrun */ -#define HAL_CEC_ERROR_TXERR CEC_ISR_TXERR /*!< CEC Tx-Error */ -#define HAL_CEC_ERROR_TXACKE CEC_ISR_TXACKE /*!< CEC Tx Missing Acknowledge */ -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -#define HAL_CEC_ERROR_INVALID_CALLBACK ((uint32_t)0x00002000U) /*!< Invalid Callback Error */ -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup CEC_Signal_Free_Time CEC Signal Free Time setting parameter - * @{ - */ -#define CEC_DEFAULT_SFT ((uint32_t)0x00000000U) -#define CEC_0_5_BITPERIOD_SFT ((uint32_t)0x00000001U) -#define CEC_1_5_BITPERIOD_SFT ((uint32_t)0x00000002U) -#define CEC_2_5_BITPERIOD_SFT ((uint32_t)0x00000003U) -#define CEC_3_5_BITPERIOD_SFT ((uint32_t)0x00000004U) -#define CEC_4_5_BITPERIOD_SFT ((uint32_t)0x00000005U) -#define CEC_5_5_BITPERIOD_SFT ((uint32_t)0x00000006U) -#define CEC_6_5_BITPERIOD_SFT ((uint32_t)0x00000007U) -/** - * @} - */ - -/** @defgroup CEC_Tolerance CEC Receiver Tolerance - * @{ - */ -#define CEC_STANDARD_TOLERANCE ((uint32_t)0x00000000U) -#define CEC_EXTENDED_TOLERANCE ((uint32_t)CEC_CFGR_RXTOL) -/** - * @} - */ - -/** @defgroup CEC_BRERxStop CEC Reception Stop on Error - * @{ - */ -#define CEC_NO_RX_STOP_ON_BRE ((uint32_t)0x00000000U) -#define CEC_RX_STOP_ON_BRE ((uint32_t)CEC_CFGR_BRESTP) -/** - * @} - */ - -/** @defgroup CEC_BREErrorBitGen CEC Error Bit Generation if Bit Rise Error reported - * @{ - */ -#define CEC_BRE_ERRORBIT_NO_GENERATION ((uint32_t)0x00000000U) -#define CEC_BRE_ERRORBIT_GENERATION ((uint32_t)CEC_CFGR_BREGEN) -/** - * @} - */ - -/** @defgroup CEC_LBPEErrorBitGen CEC Error Bit Generation if Long Bit Period Error reported - * @{ - */ -#define CEC_LBPE_ERRORBIT_NO_GENERATION ((uint32_t)0x00000000U) -#define CEC_LBPE_ERRORBIT_GENERATION ((uint32_t)CEC_CFGR_LBPEGEN) -/** - * @} - */ - -/** @defgroup CEC_BroadCastMsgErrorBitGen CEC Error Bit Generation on Broadcast message - * @{ - */ -#define CEC_BROADCASTERROR_ERRORBIT_GENERATION ((uint32_t)0x00000000U) -#define CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION ((uint32_t)CEC_CFGR_BRDNOGEN) -/** - * @} - */ - -/** @defgroup CEC_SFT_Option CEC Signal Free Time start option - * @{ - */ -#define CEC_SFT_START_ON_TXSOM ((uint32_t)0x00000000U) -#define CEC_SFT_START_ON_TX_RX_END ((uint32_t)CEC_CFGR_SFTOPT) -/** - * @} - */ - -/** @defgroup CEC_Listening_Mode CEC Listening mode option - * @{ - */ -#define CEC_REDUCED_LISTENING_MODE ((uint32_t)0x00000000U) -#define CEC_FULL_LISTENING_MODE ((uint32_t)CEC_CFGR_LSTN) -/** - * @} - */ - -/** @defgroup CEC_OAR_Position CEC Device Own Address position in CEC CFGR register - * @{ - */ -#define CEC_CFGR_OAR_LSB_POS ((uint32_t) 16U) -/** - * @} - */ - -/** @defgroup CEC_Initiator_Position CEC Initiator logical address position in message header - * @{ - */ -#define CEC_INITIATOR_LSB_POS ((uint32_t) 4U) -/** - * @} - */ - -/** @defgroup CEC_OWN_ADDRESS CEC Own Address - * @{ - */ -#define CEC_OWN_ADDRESS_NONE ((uint16_t) 0x0000U) /* Reset value */ -#define CEC_OWN_ADDRESS_0 ((uint16_t) 0x0001U) /* Logical Address 0 */ -#define CEC_OWN_ADDRESS_1 ((uint16_t) 0x0002U) /* Logical Address 1 */ -#define CEC_OWN_ADDRESS_2 ((uint16_t) 0x0004U) /* Logical Address 2 */ -#define CEC_OWN_ADDRESS_3 ((uint16_t) 0x0008U) /* Logical Address 3 */ -#define CEC_OWN_ADDRESS_4 ((uint16_t) 0x0010U) /* Logical Address 4 */ -#define CEC_OWN_ADDRESS_5 ((uint16_t) 0x0020U) /* Logical Address 5 */ -#define CEC_OWN_ADDRESS_6 ((uint16_t) 0x0040U) /* Logical Address 6 */ -#define CEC_OWN_ADDRESS_7 ((uint16_t) 0x0080U) /* Logical Address 7 */ -#define CEC_OWN_ADDRESS_8 ((uint16_t) 0x0100U) /* Logical Address 9 */ -#define CEC_OWN_ADDRESS_9 ((uint16_t) 0x0200U) /* Logical Address 10 */ -#define CEC_OWN_ADDRESS_10 ((uint16_t) 0x0400U) /* Logical Address 11 */ -#define CEC_OWN_ADDRESS_11 ((uint16_t) 0x0800U) /* Logical Address 12 */ -#define CEC_OWN_ADDRESS_12 ((uint16_t) 0x1000U) /* Logical Address 13 */ -#define CEC_OWN_ADDRESS_13 ((uint16_t) 0x2000U) /* Logical Address 14 */ -#define CEC_OWN_ADDRESS_14 ((uint16_t) 0x4000U) /* Logical Address 15 */ -/** - * @} - */ - -/** @defgroup CEC_Interrupts_Definitions CEC Interrupts definition - * @{ - */ -#define CEC_IT_TXACKE CEC_IER_TXACKEIE -#define CEC_IT_TXERR CEC_IER_TXERRIE -#define CEC_IT_TXUDR CEC_IER_TXUDRIE -#define CEC_IT_TXEND CEC_IER_TXENDIE -#define CEC_IT_TXBR CEC_IER_TXBRIE -#define CEC_IT_ARBLST CEC_IER_ARBLSTIE -#define CEC_IT_RXACKE CEC_IER_RXACKEIE -#define CEC_IT_LBPE CEC_IER_LBPEIE -#define CEC_IT_SBPE CEC_IER_SBPEIE -#define CEC_IT_BRE CEC_IER_BREIE -#define CEC_IT_RXOVR CEC_IER_RXOVRIE -#define CEC_IT_RXEND CEC_IER_RXENDIE -#define CEC_IT_RXBR CEC_IER_RXBRIE -/** - * @} - */ - -/** @defgroup CEC_Flags_Definitions CEC Flags definition - * @{ - */ -#define CEC_FLAG_TXACKE CEC_ISR_TXACKE -#define CEC_FLAG_TXERR CEC_ISR_TXERR -#define CEC_FLAG_TXUDR CEC_ISR_TXUDR -#define CEC_FLAG_TXEND CEC_ISR_TXEND -#define CEC_FLAG_TXBR CEC_ISR_TXBR -#define CEC_FLAG_ARBLST CEC_ISR_ARBLST -#define CEC_FLAG_RXACKE CEC_ISR_RXACKE -#define CEC_FLAG_LBPE CEC_ISR_LBPE -#define CEC_FLAG_SBPE CEC_ISR_SBPE -#define CEC_FLAG_BRE CEC_ISR_BRE -#define CEC_FLAG_RXOVR CEC_ISR_RXOVR -#define CEC_FLAG_RXEND CEC_ISR_RXEND -#define CEC_FLAG_RXBR CEC_ISR_RXBR -/** - * @} - */ - -/** @defgroup CEC_ALL_ERROR CEC all RX or TX errors flags - * @{ - */ -#define CEC_ISR_ALL_ERROR ((uint32_t)CEC_ISR_RXOVR|CEC_ISR_BRE|CEC_ISR_SBPE|CEC_ISR_LBPE|CEC_ISR_RXACKE|\ - CEC_ISR_ARBLST|CEC_ISR_TXUDR|CEC_ISR_TXERR|CEC_ISR_TXACKE) -/** - * @} - */ - -/** @defgroup CEC_IER_ALL_RX CEC all RX errors interrupts enabling flag - * @{ - */ -#define CEC_IER_RX_ALL_ERR ((uint32_t)CEC_IER_RXACKEIE|CEC_IER_LBPEIE|CEC_IER_SBPEIE|CEC_IER_BREIE|CEC_IER_RXOVRIE) -/** - * @} - */ - -/** @defgroup CEC_IER_ALL_TX CEC all TX errors interrupts enabling flag - * @{ - */ -#define CEC_IER_TX_ALL_ERR ((uint32_t)CEC_IER_TXACKEIE|CEC_IER_TXERRIE|CEC_IER_TXUDRIE|CEC_IER_ARBLSTIE) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CEC_Exported_Macros CEC Exported Macros - * @{ - */ - -/** @brief Reset CEC handle gstate & RxState - * @param __HANDLE__ CEC handle. - * @retval None - */ -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -#define __HAL_CEC_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_CEC_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_CEC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_CEC_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_CEC_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_CEC_STATE_RESET; \ - } while(0) -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -/** @brief Checks whether or not the specified CEC interrupt flag is set. - * @param __HANDLE__ specifies the CEC Handle. - * @param __FLAG__ specifies the flag to check. - * @arg CEC_FLAG_TXACKE: Tx Missing acknowledge Error - * @arg CEC_FLAG_TXERR: Tx Error. - * @arg CEC_FLAG_TXUDR: Tx-Buffer Underrun. - * @arg CEC_FLAG_TXEND: End of transmission (successful transmission of the last byte). - * @arg CEC_FLAG_TXBR: Tx-Byte Request. - * @arg CEC_FLAG_ARBLST: Arbitration Lost - * @arg CEC_FLAG_RXACKE: Rx-Missing Acknowledge - * @arg CEC_FLAG_LBPE: Rx Long period Error - * @arg CEC_FLAG_SBPE: Rx Short period Error - * @arg CEC_FLAG_BRE: Rx Bit Rising Error - * @arg CEC_FLAG_RXOVR: Rx Overrun. - * @arg CEC_FLAG_RXEND: End Of Reception. - * @arg CEC_FLAG_RXBR: Rx-Byte Received. - * @retval ITStatus - */ -#define __HAL_CEC_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR & (__FLAG__)) - -/** @brief Clears the interrupt or status flag when raised (write at 1) - * @param __HANDLE__ specifies the CEC Handle. - * @param __FLAG__ specifies the interrupt/status flag to clear. - * This parameter can be one of the following values: - * @arg CEC_FLAG_TXACKE: Tx Missing acknowledge Error - * @arg CEC_FLAG_TXERR: Tx Error. - * @arg CEC_FLAG_TXUDR: Tx-Buffer Underrun. - * @arg CEC_FLAG_TXEND: End of transmission (successful transmission of the last byte). - * @arg CEC_FLAG_TXBR: Tx-Byte Request. - * @arg CEC_FLAG_ARBLST: Arbitration Lost - * @arg CEC_FLAG_RXACKE: Rx-Missing Acknowledge - * @arg CEC_FLAG_LBPE: Rx Long period Error - * @arg CEC_FLAG_SBPE: Rx Short period Error - * @arg CEC_FLAG_BRE: Rx Bit Rising Error - * @arg CEC_FLAG_RXOVR: Rx Overrun. - * @arg CEC_FLAG_RXEND: End Of Reception. - * @arg CEC_FLAG_RXBR: Rx-Byte Received. - * @retval none - */ -#define __HAL_CEC_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR |= (__FLAG__)) - -/** @brief Enables the specified CEC interrupt. - * @param __HANDLE__ specifies the CEC Handle. - * @param __INTERRUPT__ specifies the CEC interrupt to enable. - * This parameter can be one of the following values: - * @arg CEC_IT_TXACKE: Tx Missing acknowledge Error IT Enable - * @arg CEC_IT_TXERR: Tx Error IT Enable - * @arg CEC_IT_TXUDR: Tx-Buffer Underrun IT Enable - * @arg CEC_IT_TXEND: End of transmission IT Enable - * @arg CEC_IT_TXBR: Tx-Byte Request IT Enable - * @arg CEC_IT_ARBLST: Arbitration Lost IT Enable - * @arg CEC_IT_RXACKE: Rx-Missing Acknowledge IT Enable - * @arg CEC_IT_LBPE: Rx Long period Error IT Enable - * @arg CEC_IT_SBPE: Rx Short period Error IT Enable - * @arg CEC_IT_BRE: Rx Bit Rising Error IT Enable - * @arg CEC_IT_RXOVR: Rx Overrun IT Enable - * @arg CEC_IT_RXEND: End Of Reception IT Enable - * @arg CEC_IT_RXBR: Rx-Byte Received IT Enable - * @retval none - */ -#define __HAL_CEC_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__)) - -/** @brief Disables the specified CEC interrupt. - * @param __HANDLE__ specifies the CEC Handle. - * @param __INTERRUPT__ specifies the CEC interrupt to disable. - * This parameter can be one of the following values: - * @arg CEC_IT_TXACKE: Tx Missing acknowledge Error IT Enable - * @arg CEC_IT_TXERR: Tx Error IT Enable - * @arg CEC_IT_TXUDR: Tx-Buffer Underrun IT Enable - * @arg CEC_IT_TXEND: End of transmission IT Enable - * @arg CEC_IT_TXBR: Tx-Byte Request IT Enable - * @arg CEC_IT_ARBLST: Arbitration Lost IT Enable - * @arg CEC_IT_RXACKE: Rx-Missing Acknowledge IT Enable - * @arg CEC_IT_LBPE: Rx Long period Error IT Enable - * @arg CEC_IT_SBPE: Rx Short period Error IT Enable - * @arg CEC_IT_BRE: Rx Bit Rising Error IT Enable - * @arg CEC_IT_RXOVR: Rx Overrun IT Enable - * @arg CEC_IT_RXEND: End Of Reception IT Enable - * @arg CEC_IT_RXBR: Rx-Byte Received IT Enable - * @retval none - */ -#define __HAL_CEC_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= (~(__INTERRUPT__))) - -/** @brief Checks whether or not the specified CEC interrupt is enabled. - * @param __HANDLE__ specifies the CEC Handle. - * @param __INTERRUPT__ specifies the CEC interrupt to check. - * This parameter can be one of the following values: - * @arg CEC_IT_TXACKE: Tx Missing acknowledge Error IT Enable - * @arg CEC_IT_TXERR: Tx Error IT Enable - * @arg CEC_IT_TXUDR: Tx-Buffer Underrun IT Enable - * @arg CEC_IT_TXEND: End of transmission IT Enable - * @arg CEC_IT_TXBR: Tx-Byte Request IT Enable - * @arg CEC_IT_ARBLST: Arbitration Lost IT Enable - * @arg CEC_IT_RXACKE: Rx-Missing Acknowledge IT Enable - * @arg CEC_IT_LBPE: Rx Long period Error IT Enable - * @arg CEC_IT_SBPE: Rx Short period Error IT Enable - * @arg CEC_IT_BRE: Rx Bit Rising Error IT Enable - * @arg CEC_IT_RXOVR: Rx Overrun IT Enable - * @arg CEC_IT_RXEND: End Of Reception IT Enable - * @arg CEC_IT_RXBR: Rx-Byte Received IT Enable - * @retval FlagStatus - */ -#define __HAL_CEC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER & (__INTERRUPT__)) - -/** @brief Enables the CEC device - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - */ -#define __HAL_CEC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= CEC_CR_CECEN) - -/** @brief Disables the CEC device - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - */ -#define __HAL_CEC_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~CEC_CR_CECEN) - -/** @brief Set Transmission Start flag - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - */ -#define __HAL_CEC_FIRST_BYTE_TX_SET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CEC_CR_TXSOM) - -/** @brief Set Transmission End flag - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - * If the CEC message consists of only one byte, TXEOM must be set before of TXSOM. - */ -#define __HAL_CEC_LAST_BYTE_TX_SET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CEC_CR_TXEOM) - -/** @brief Get Transmission Start flag - * @param __HANDLE__ specifies the CEC Handle. - * @retval FlagStatus - */ -#define __HAL_CEC_GET_TRANSMISSION_START_FLAG(__HANDLE__) ((__HANDLE__)->Instance->CR & CEC_CR_TXSOM) - -/** @brief Get Transmission End flag - * @param __HANDLE__ specifies the CEC Handle. - * @retval FlagStatus - */ -#define __HAL_CEC_GET_TRANSMISSION_END_FLAG(__HANDLE__) ((__HANDLE__)->Instance->CR & CEC_CR_TXEOM) - -/** @brief Clear OAR register - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - */ -#define __HAL_CEC_CLEAR_OAR(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CFGR, CEC_CFGR_OAR) - -/** @brief Set OAR register (without resetting previously set address in case of multi-address mode) - * To reset OAR, __HAL_CEC_CLEAR_OAR() needs to be called beforehand - * @param __HANDLE__ specifies the CEC Handle. - * @param __ADDRESS__ Own Address value (CEC logical address is identified by bit position) - * @retval none - */ -#define __HAL_CEC_SET_OAR(__HANDLE__,__ADDRESS__) SET_BIT((__HANDLE__)->Instance->CFGR, (__ADDRESS__)<< CEC_CFGR_OAR_LSB_POS) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CEC_Exported_Functions - * @{ - */ - -/** @addtogroup CEC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions ****************************/ -HAL_StatusTypeDef HAL_CEC_Init(CEC_HandleTypeDef *hcec); -HAL_StatusTypeDef HAL_CEC_DeInit(CEC_HandleTypeDef *hcec); -HAL_StatusTypeDef HAL_CEC_SetDeviceAddress(CEC_HandleTypeDef *hcec, uint16_t CEC_OwnAddress); -void HAL_CEC_MspInit(CEC_HandleTypeDef *hcec); -void HAL_CEC_MspDeInit(CEC_HandleTypeDef *hcec); - -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_CEC_RegisterCallback(CEC_HandleTypeDef *hcec, HAL_CEC_CallbackIDTypeDef CallbackID, - pCEC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_CEC_UnRegisterCallback(CEC_HandleTypeDef *hcec, HAL_CEC_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_CEC_RegisterRxCpltCallback(CEC_HandleTypeDef *hcec, pCEC_RxCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_CEC_UnRegisterRxCpltCallback(CEC_HandleTypeDef *hcec); -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup CEC_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -HAL_StatusTypeDef HAL_CEC_Transmit_IT(CEC_HandleTypeDef *hcec, uint8_t InitiatorAddress, uint8_t DestinationAddress, - uint8_t *pData, uint32_t Size); -uint32_t HAL_CEC_GetLastReceivedFrameSize(CEC_HandleTypeDef *hcec); -void HAL_CEC_ChangeRxBuffer(CEC_HandleTypeDef *hcec, uint8_t *Rxbuffer); -void HAL_CEC_IRQHandler(CEC_HandleTypeDef *hcec); -void HAL_CEC_TxCpltCallback(CEC_HandleTypeDef *hcec); -void HAL_CEC_RxCpltCallback(CEC_HandleTypeDef *hcec, uint32_t RxFrameSize); -void HAL_CEC_ErrorCallback(CEC_HandleTypeDef *hcec); -/** - * @} - */ - -/** @addtogroup CEC_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_CEC_StateTypeDef HAL_CEC_GetState(CEC_HandleTypeDef *hcec); -uint32_t HAL_CEC_GetError(CEC_HandleTypeDef *hcec); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CEC_Private_Types CEC Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CEC_Private_Variables CEC Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CEC_Private_Constants CEC Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CEC_Private_Macros CEC Private Macros - * @{ - */ - -#define IS_CEC_SIGNALFREETIME(__SFT__) ((__SFT__) <= CEC_CFGR_SFT) - -#define IS_CEC_TOLERANCE(__RXTOL__) (((__RXTOL__) == CEC_STANDARD_TOLERANCE) || \ - ((__RXTOL__) == CEC_EXTENDED_TOLERANCE)) - -#define IS_CEC_BRERXSTOP(__BRERXSTOP__) (((__BRERXSTOP__) == CEC_NO_RX_STOP_ON_BRE) || \ - ((__BRERXSTOP__) == CEC_RX_STOP_ON_BRE)) - -#define IS_CEC_BREERRORBITGEN(__ERRORBITGEN__) (((__ERRORBITGEN__) == CEC_BRE_ERRORBIT_NO_GENERATION) || \ - ((__ERRORBITGEN__) == CEC_BRE_ERRORBIT_GENERATION)) - -#define IS_CEC_LBPEERRORBITGEN(__ERRORBITGEN__) (((__ERRORBITGEN__) == CEC_LBPE_ERRORBIT_NO_GENERATION) || \ - ((__ERRORBITGEN__) == CEC_LBPE_ERRORBIT_GENERATION)) - -#define IS_CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION(__ERRORBITGEN__) (((__ERRORBITGEN__) == CEC_BROADCASTERROR_ERRORBIT_GENERATION) || \ - ((__ERRORBITGEN__) == CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION)) - -#define IS_CEC_SFTOP(__SFTOP__) (((__SFTOP__) == CEC_SFT_START_ON_TXSOM) || \ - ((__SFTOP__) == CEC_SFT_START_ON_TX_RX_END)) - -#define IS_CEC_LISTENING_MODE(__MODE__) (((__MODE__) == CEC_REDUCED_LISTENING_MODE) || \ - ((__MODE__) == CEC_FULL_LISTENING_MODE)) - -/** @brief Check CEC message size. - * The message size is the payload size: without counting the header, - * it varies from 0 byte (ping operation, one header only, no payload) to - * 15 bytes (1 opcode and up to 14 operands following the header). - * @param __SIZE__ CEC message size. - * @retval Test result (TRUE or FALSE). - */ -#define IS_CEC_MSGSIZE(__SIZE__) ((__SIZE__) <= 0x10U) - -/** @brief Check CEC device Own Address Register (OAR) setting. - * OAR address is written in a 15-bit field within CEC_CFGR register. - * @param __ADDRESS__ CEC own address. - * @retval Test result (TRUE or FALSE). - */ -#define IS_CEC_OWN_ADDRESS(__ADDRESS__) ((__ADDRESS__) <= 0x7FFFU) - -/** @brief Check CEC initiator or destination logical address setting. - * Initiator and destination addresses are coded over 4 bits. - * @param __ADDRESS__ CEC initiator or logical address. - * @retval Test result (TRUE or FALSE). - */ -#define IS_CEC_ADDRESS(__ADDRESS__) ((__ADDRESS__) <= 0xFU) -/** - * @} - */ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup CEC_Private_Functions CEC Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* CEC */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xxHAL_CEC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_conf_template.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_conf_template.h deleted file mode 100644 index afa2f56876885c1..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_conf_template.h +++ /dev/null @@ -1,501 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_conf_template.h - * @author MCD Application Team - * @brief HAL configuration template file. - * This file should be copied to the application folder and renamed - * to stm32f4xx_hal_conf.h. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CONF_H -#define __STM32F4xx_HAL_CONF_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* ########################## Module Selection ############################## */ -/** - * @brief This is the list of modules to be used in the HAL driver - */ -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -#define HAL_CAN_MODULE_ENABLED -/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ -#define HAL_CRC_MODULE_ENABLED -#define HAL_CEC_MODULE_ENABLED -#define HAL_CRYP_MODULE_ENABLED -#define HAL_DAC_MODULE_ENABLED -#define HAL_DCMI_MODULE_ENABLED -#define HAL_DMA_MODULE_ENABLED -#define HAL_DMA2D_MODULE_ENABLED -#define HAL_ETH_MODULE_ENABLED -#define HAL_FLASH_MODULE_ENABLED -#define HAL_NAND_MODULE_ENABLED -#define HAL_NOR_MODULE_ENABLED -#define HAL_PCCARD_MODULE_ENABLED -#define HAL_SRAM_MODULE_ENABLED -#define HAL_SDRAM_MODULE_ENABLED -#define HAL_HASH_MODULE_ENABLED -#define HAL_GPIO_MODULE_ENABLED -#define HAL_EXTI_MODULE_ENABLED -#define HAL_I2C_MODULE_ENABLED -#define HAL_SMBUS_MODULE_ENABLED -#define HAL_I2S_MODULE_ENABLED -#define HAL_IWDG_MODULE_ENABLED -#define HAL_LTDC_MODULE_ENABLED -#define HAL_DSI_MODULE_ENABLED -#define HAL_PWR_MODULE_ENABLED -#define HAL_QSPI_MODULE_ENABLED -#define HAL_RCC_MODULE_ENABLED -#define HAL_RNG_MODULE_ENABLED -#define HAL_RTC_MODULE_ENABLED -#define HAL_SAI_MODULE_ENABLED -#define HAL_SD_MODULE_ENABLED -#define HAL_SPI_MODULE_ENABLED -#define HAL_TIM_MODULE_ENABLED -#define HAL_UART_MODULE_ENABLED -#define HAL_USART_MODULE_ENABLED -#define HAL_IRDA_MODULE_ENABLED -#define HAL_SMARTCARD_MODULE_ENABLED -#define HAL_WWDG_MODULE_ENABLED -#define HAL_CORTEX_MODULE_ENABLED -#define HAL_PCD_MODULE_ENABLED -#define HAL_HCD_MODULE_ENABLED -#define HAL_FMPI2C_MODULE_ENABLED -#define HAL_FMPSMBUS_MODULE_ENABLED -#define HAL_SPDIFRX_MODULE_ENABLED -#define HAL_DFSDM_MODULE_ENABLED -#define HAL_LPTIM_MODULE_ENABLED -#define HAL_MMC_MODULE_ENABLED - -/* ########################## HSE/HSI Values adaptation ##################### */ -/** - * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSE is used as system clock source, directly or through the PLL). - */ -#if !defined (HSE_VALUE) - #define HSE_VALUE 25000000U /*!< Value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSE_STARTUP_TIMEOUT) - #define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ -#endif /* HSE_STARTUP_TIMEOUT */ - -/** - * @brief Internal High Speed oscillator (HSI) value. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSI is used as system clock source, directly or through the PLL). - */ -#if !defined (HSI_VALUE) - #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */ -#endif /* HSI_VALUE */ - -/** - * @brief Internal Low Speed oscillator (LSI) value. - */ -#if !defined (LSI_VALUE) - #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */ -#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz - The real value may vary depending on the variations - in voltage and temperature. */ -/** - * @brief External Low Speed oscillator (LSE) value. - */ -#if !defined (LSE_VALUE) - #define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ -#endif /* LSE_VALUE */ - -#if !defined (LSE_STARTUP_TIMEOUT) - #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ -#endif /* LSE_STARTUP_TIMEOUT */ - -/** - * @brief External clock source for I2S peripheral - * This value is used by the I2S HAL module to compute the I2S clock source - * frequency, this source is inserted directly through I2S_CKIN pad. - */ -#if !defined (EXTERNAL_CLOCK_VALUE) - #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/ -#endif /* EXTERNAL_CLOCK_VALUE */ - -/* Tip: To avoid modifying this file each time you need to use different HSE, - === you can define the HSE value in your toolchain compiler preprocessor. */ - -/* ########################### System Configuration ######################### */ -/** - * @brief This is the HAL system configuration section - */ -#define VDD_VALUE 3300U /*!< Value of VDD in mv */ -#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */ -#define USE_RTOS 0U -#define PREFETCH_ENABLE 1U -#define INSTRUCTION_CACHE_ENABLE 1U -#define DATA_CACHE_ENABLE 1U - -#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ -#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ -#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ -#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ -#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ -#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ -#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ -#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ -#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ -#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ -#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ -#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ -#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ -#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ -#define USE_HAL_FMPSMBUS_REGISTER_CALLBACKS 0U /* FMPSMBUS register callback disabled */ -#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ -#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ -#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ -#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ -#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ -#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ -#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ -#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ -#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ -#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ -#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ -#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ -#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ -#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ -#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ -#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ -#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ -#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ -#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ -#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ -#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ -#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ -#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ -#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ - -/* ########################## Assert Selection ############################## */ -/** - * @brief Uncomment the line below to expanse the "assert_param" macro in the - * HAL drivers code - */ -/* #define USE_FULL_ASSERT 1U */ - -/* ################## Ethernet peripheral configuration ##################### */ - -/* Section 1 : Ethernet peripheral configuration */ - -/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ -#define MAC_ADDR0 2U -#define MAC_ADDR1 0U -#define MAC_ADDR2 0U -#define MAC_ADDR3 0U -#define MAC_ADDR4 0U -#define MAC_ADDR5 0U - -/* Definition of the Ethernet driver buffers size and count */ -#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ -#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ -#define ETH_RXBUFNB 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ -#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ - -/* Section 2: PHY configuration section */ - -/* DP83848 PHY Address*/ -#define DP83848_PHY_ADDRESS 0x01U -/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ -#define PHY_RESET_DELAY 0x000000FFU -/* PHY Configuration delay */ -#define PHY_CONFIG_DELAY 0x00000FFFU - -#define PHY_READ_TO 0x0000FFFFU -#define PHY_WRITE_TO 0x0000FFFFU - -/* Section 3: Common PHY Registers */ - -#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */ -#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */ - -#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ -#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ -#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ -#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ -#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ -#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ -#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ -#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ -#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ -#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ - -#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ -#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ -#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ - -/* Section 4: Extended PHY Registers */ - -#define PHY_SR ((uint16_t)0x0010) /*!< PHY status register Offset */ -#define PHY_MICR ((uint16_t)0x0011) /*!< MII Interrupt Control Register */ -#define PHY_MISR ((uint16_t)0x0012) /*!< MII Interrupt Status and Misc. Control Register */ - -#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */ -#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */ -#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */ - -#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */ -#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */ - -#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */ -#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */ - -/* ################## SPI peripheral configuration ########################## */ - -/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver -* Activated: CRC code is present inside driver -* Deactivated: CRC code cleaned from driver -*/ - -#define USE_SPI_CRC 1U - -/* Includes ------------------------------------------------------------------*/ -/** - * @brief Include module's header file - */ - -#ifdef HAL_RCC_MODULE_ENABLED - #include "stm32f4xx_hal_rcc.h" -#endif /* HAL_RCC_MODULE_ENABLED */ - -#ifdef HAL_GPIO_MODULE_ENABLED - #include "stm32f4xx_hal_gpio.h" -#endif /* HAL_GPIO_MODULE_ENABLED */ - -#ifdef HAL_EXTI_MODULE_ENABLED - #include "stm32f4xx_hal_exti.h" -#endif /* HAL_EXTI_MODULE_ENABLED */ - -#ifdef HAL_DMA_MODULE_ENABLED - #include "stm32f4xx_hal_dma.h" -#endif /* HAL_DMA_MODULE_ENABLED */ - -#ifdef HAL_CORTEX_MODULE_ENABLED - #include "stm32f4xx_hal_cortex.h" -#endif /* HAL_CORTEX_MODULE_ENABLED */ - -#ifdef HAL_ADC_MODULE_ENABLED - #include "stm32f4xx_hal_adc.h" -#endif /* HAL_ADC_MODULE_ENABLED */ - -#ifdef HAL_CAN_MODULE_ENABLED - #include "stm32f4xx_hal_can.h" -#endif /* HAL_CAN_MODULE_ENABLED */ - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - #include "stm32f4xx_hal_can_legacy.h" -#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ - -#ifdef HAL_CRC_MODULE_ENABLED - #include "stm32f4xx_hal_crc.h" -#endif /* HAL_CRC_MODULE_ENABLED */ - -#ifdef HAL_CRYP_MODULE_ENABLED - #include "stm32f4xx_hal_cryp.h" -#endif /* HAL_CRYP_MODULE_ENABLED */ - -#ifdef HAL_DMA2D_MODULE_ENABLED - #include "stm32f4xx_hal_dma2d.h" -#endif /* HAL_DMA2D_MODULE_ENABLED */ - -#ifdef HAL_DAC_MODULE_ENABLED - #include "stm32f4xx_hal_dac.h" -#endif /* HAL_DAC_MODULE_ENABLED */ - -#ifdef HAL_DCMI_MODULE_ENABLED - #include "stm32f4xx_hal_dcmi.h" -#endif /* HAL_DCMI_MODULE_ENABLED */ - -#ifdef HAL_ETH_MODULE_ENABLED - #include "stm32f4xx_hal_eth.h" -#endif /* HAL_ETH_MODULE_ENABLED */ - -#ifdef HAL_FLASH_MODULE_ENABLED - #include "stm32f4xx_hal_flash.h" -#endif /* HAL_FLASH_MODULE_ENABLED */ - -#ifdef HAL_SRAM_MODULE_ENABLED - #include "stm32f4xx_hal_sram.h" -#endif /* HAL_SRAM_MODULE_ENABLED */ - -#ifdef HAL_NOR_MODULE_ENABLED - #include "stm32f4xx_hal_nor.h" -#endif /* HAL_NOR_MODULE_ENABLED */ - -#ifdef HAL_NAND_MODULE_ENABLED - #include "stm32f4xx_hal_nand.h" -#endif /* HAL_NAND_MODULE_ENABLED */ - -#ifdef HAL_PCCARD_MODULE_ENABLED - #include "stm32f4xx_hal_pccard.h" -#endif /* HAL_PCCARD_MODULE_ENABLED */ - -#ifdef HAL_SDRAM_MODULE_ENABLED - #include "stm32f4xx_hal_sdram.h" -#endif /* HAL_SDRAM_MODULE_ENABLED */ - -#ifdef HAL_HASH_MODULE_ENABLED - #include "stm32f4xx_hal_hash.h" -#endif /* HAL_HASH_MODULE_ENABLED */ - -#ifdef HAL_I2C_MODULE_ENABLED - #include "stm32f4xx_hal_i2c.h" -#endif /* HAL_I2C_MODULE_ENABLED */ - -#ifdef HAL_SMBUS_MODULE_ENABLED - #include "stm32f4xx_hal_smbus.h" -#endif /* HAL_SMBUS_MODULE_ENABLED */ - -#ifdef HAL_I2S_MODULE_ENABLED - #include "stm32f4xx_hal_i2s.h" -#endif /* HAL_I2S_MODULE_ENABLED */ - -#ifdef HAL_IWDG_MODULE_ENABLED - #include "stm32f4xx_hal_iwdg.h" -#endif /* HAL_IWDG_MODULE_ENABLED */ - -#ifdef HAL_LTDC_MODULE_ENABLED - #include "stm32f4xx_hal_ltdc.h" -#endif /* HAL_LTDC_MODULE_ENABLED */ - -#ifdef HAL_PWR_MODULE_ENABLED - #include "stm32f4xx_hal_pwr.h" -#endif /* HAL_PWR_MODULE_ENABLED */ - -#ifdef HAL_RNG_MODULE_ENABLED - #include "stm32f4xx_hal_rng.h" -#endif /* HAL_RNG_MODULE_ENABLED */ - -#ifdef HAL_RTC_MODULE_ENABLED - #include "stm32f4xx_hal_rtc.h" -#endif /* HAL_RTC_MODULE_ENABLED */ - -#ifdef HAL_SAI_MODULE_ENABLED - #include "stm32f4xx_hal_sai.h" -#endif /* HAL_SAI_MODULE_ENABLED */ - -#ifdef HAL_SD_MODULE_ENABLED - #include "stm32f4xx_hal_sd.h" -#endif /* HAL_SD_MODULE_ENABLED */ - -#ifdef HAL_SPI_MODULE_ENABLED - #include "stm32f4xx_hal_spi.h" -#endif /* HAL_SPI_MODULE_ENABLED */ - -#ifdef HAL_TIM_MODULE_ENABLED - #include "stm32f4xx_hal_tim.h" -#endif /* HAL_TIM_MODULE_ENABLED */ - -#ifdef HAL_UART_MODULE_ENABLED - #include "stm32f4xx_hal_uart.h" -#endif /* HAL_UART_MODULE_ENABLED */ - -#ifdef HAL_USART_MODULE_ENABLED - #include "stm32f4xx_hal_usart.h" -#endif /* HAL_USART_MODULE_ENABLED */ - -#ifdef HAL_IRDA_MODULE_ENABLED - #include "stm32f4xx_hal_irda.h" -#endif /* HAL_IRDA_MODULE_ENABLED */ - -#ifdef HAL_SMARTCARD_MODULE_ENABLED - #include "stm32f4xx_hal_smartcard.h" -#endif /* HAL_SMARTCARD_MODULE_ENABLED */ - -#ifdef HAL_WWDG_MODULE_ENABLED - #include "stm32f4xx_hal_wwdg.h" -#endif /* HAL_WWDG_MODULE_ENABLED */ - -#ifdef HAL_PCD_MODULE_ENABLED - #include "stm32f4xx_hal_pcd.h" -#endif /* HAL_PCD_MODULE_ENABLED */ - -#ifdef HAL_HCD_MODULE_ENABLED - #include "stm32f4xx_hal_hcd.h" -#endif /* HAL_HCD_MODULE_ENABLED */ - -#ifdef HAL_DSI_MODULE_ENABLED - #include "stm32f4xx_hal_dsi.h" -#endif /* HAL_DSI_MODULE_ENABLED */ - -#ifdef HAL_QSPI_MODULE_ENABLED - #include "stm32f4xx_hal_qspi.h" -#endif /* HAL_QSPI_MODULE_ENABLED */ - -#ifdef HAL_CEC_MODULE_ENABLED - #include "stm32f4xx_hal_cec.h" -#endif /* HAL_CEC_MODULE_ENABLED */ - -#ifdef HAL_FMPI2C_MODULE_ENABLED - #include "stm32f4xx_hal_fmpi2c.h" -#endif /* HAL_FMPI2C_MODULE_ENABLED */ - -#ifdef HAL_FMPSMBUS_MODULE_ENABLED - #include "stm32f4xx_hal_fmpsmbus.h" -#endif /* HAL_FMPSMBUS_MODULE_ENABLED */ - -#ifdef HAL_SPDIFRX_MODULE_ENABLED - #include "stm32f4xx_hal_spdifrx.h" -#endif /* HAL_SPDIFRX_MODULE_ENABLED */ - -#ifdef HAL_DFSDM_MODULE_ENABLED - #include "stm32f4xx_hal_dfsdm.h" -#endif /* HAL_DFSDM_MODULE_ENABLED */ - -#ifdef HAL_LPTIM_MODULE_ENABLED - #include "stm32f4xx_hal_lptim.h" -#endif /* HAL_LPTIM_MODULE_ENABLED */ - -#ifdef HAL_MMC_MODULE_ENABLED - #include "stm32f4xx_hal_mmc.h" -#endif /* HAL_MMC_MODULE_ENABLED */ - -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); -#else - #define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CONF_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h deleted file mode 100644 index 95218cfbbc30069..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h +++ /dev/null @@ -1,410 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cortex.h - * @author MCD Application Team - * @brief Header file of CORTEX HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CORTEX_H -#define __STM32F4xx_HAL_CORTEX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CORTEX - * @{ - */ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CORTEX_Exported_Types Cortex Exported Types - * @{ - */ - -#if (__MPU_PRESENT == 1U) -/** @defgroup CORTEX_MPU_Region_Initialization_Structure_definition MPU Region Initialization Structure Definition - * @brief MPU Region initialization structure - * @{ - */ -typedef struct -{ - uint8_t Enable; /*!< Specifies the status of the region. - This parameter can be a value of @ref CORTEX_MPU_Region_Enable */ - uint8_t Number; /*!< Specifies the number of the region to protect. - This parameter can be a value of @ref CORTEX_MPU_Region_Number */ - uint32_t BaseAddress; /*!< Specifies the base address of the region to protect. */ - uint8_t Size; /*!< Specifies the size of the region to protect. - This parameter can be a value of @ref CORTEX_MPU_Region_Size */ - uint8_t SubRegionDisable; /*!< Specifies the number of the subregion protection to disable. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF */ - uint8_t TypeExtField; /*!< Specifies the TEX field level. - This parameter can be a value of @ref CORTEX_MPU_TEX_Levels */ - uint8_t AccessPermission; /*!< Specifies the region access permission type. - This parameter can be a value of @ref CORTEX_MPU_Region_Permission_Attributes */ - uint8_t DisableExec; /*!< Specifies the instruction access status. - This parameter can be a value of @ref CORTEX_MPU_Instruction_Access */ - uint8_t IsShareable; /*!< Specifies the shareability status of the protected region. - This parameter can be a value of @ref CORTEX_MPU_Access_Shareable */ - uint8_t IsCacheable; /*!< Specifies the cacheable status of the region protected. - This parameter can be a value of @ref CORTEX_MPU_Access_Cacheable */ - uint8_t IsBufferable; /*!< Specifies the bufferable status of the protected region. - This parameter can be a value of @ref CORTEX_MPU_Access_Bufferable */ -}MPU_Region_InitTypeDef; -/** - * @} - */ -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup CORTEX_Exported_Constants CORTEX Exported Constants - * @{ - */ - -/** @defgroup CORTEX_Preemption_Priority_Group CORTEX Preemption Priority Group - * @{ - */ -#define NVIC_PRIORITYGROUP_0 0x00000007U /*!< 0 bits for pre-emption priority - 4 bits for subpriority */ -#define NVIC_PRIORITYGROUP_1 0x00000006U /*!< 1 bits for pre-emption priority - 3 bits for subpriority */ -#define NVIC_PRIORITYGROUP_2 0x00000005U /*!< 2 bits for pre-emption priority - 2 bits for subpriority */ -#define NVIC_PRIORITYGROUP_3 0x00000004U /*!< 3 bits for pre-emption priority - 1 bits for subpriority */ -#define NVIC_PRIORITYGROUP_4 0x00000003U /*!< 4 bits for pre-emption priority - 0 bits for subpriority */ -/** - * @} - */ - -/** @defgroup CORTEX_SysTick_clock_source CORTEX _SysTick clock source - * @{ - */ -#define SYSTICK_CLKSOURCE_HCLK_DIV8 0x00000000U -#define SYSTICK_CLKSOURCE_HCLK 0x00000004U - -/** - * @} - */ - -#if (__MPU_PRESENT == 1) -/** @defgroup CORTEX_MPU_HFNMI_PRIVDEF_Control MPU HFNMI and PRIVILEGED Access control - * @{ - */ -#define MPU_HFNMI_PRIVDEF_NONE 0x00000000U -#define MPU_HARDFAULT_NMI MPU_CTRL_HFNMIENA_Msk -#define MPU_PRIVILEGED_DEFAULT MPU_CTRL_PRIVDEFENA_Msk -#define MPU_HFNMI_PRIVDEF (MPU_CTRL_HFNMIENA_Msk | MPU_CTRL_PRIVDEFENA_Msk) - -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Enable CORTEX MPU Region Enable - * @{ - */ -#define MPU_REGION_ENABLE ((uint8_t)0x01) -#define MPU_REGION_DISABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Instruction_Access CORTEX MPU Instruction Access - * @{ - */ -#define MPU_INSTRUCTION_ACCESS_ENABLE ((uint8_t)0x00) -#define MPU_INSTRUCTION_ACCESS_DISABLE ((uint8_t)0x01) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Shareable CORTEX MPU Instruction Access Shareable - * @{ - */ -#define MPU_ACCESS_SHAREABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_SHAREABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Cacheable CORTEX MPU Instruction Access Cacheable - * @{ - */ -#define MPU_ACCESS_CACHEABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_CACHEABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Bufferable CORTEX MPU Instruction Access Bufferable - * @{ - */ -#define MPU_ACCESS_BUFFERABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_BUFFERABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_TEX_Levels MPU TEX Levels - * @{ - */ -#define MPU_TEX_LEVEL0 ((uint8_t)0x00) -#define MPU_TEX_LEVEL1 ((uint8_t)0x01) -#define MPU_TEX_LEVEL2 ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Size CORTEX MPU Region Size - * @{ - */ -#define MPU_REGION_SIZE_32B ((uint8_t)0x04) -#define MPU_REGION_SIZE_64B ((uint8_t)0x05) -#define MPU_REGION_SIZE_128B ((uint8_t)0x06) -#define MPU_REGION_SIZE_256B ((uint8_t)0x07) -#define MPU_REGION_SIZE_512B ((uint8_t)0x08) -#define MPU_REGION_SIZE_1KB ((uint8_t)0x09) -#define MPU_REGION_SIZE_2KB ((uint8_t)0x0A) -#define MPU_REGION_SIZE_4KB ((uint8_t)0x0B) -#define MPU_REGION_SIZE_8KB ((uint8_t)0x0C) -#define MPU_REGION_SIZE_16KB ((uint8_t)0x0D) -#define MPU_REGION_SIZE_32KB ((uint8_t)0x0E) -#define MPU_REGION_SIZE_64KB ((uint8_t)0x0F) -#define MPU_REGION_SIZE_128KB ((uint8_t)0x10) -#define MPU_REGION_SIZE_256KB ((uint8_t)0x11) -#define MPU_REGION_SIZE_512KB ((uint8_t)0x12) -#define MPU_REGION_SIZE_1MB ((uint8_t)0x13) -#define MPU_REGION_SIZE_2MB ((uint8_t)0x14) -#define MPU_REGION_SIZE_4MB ((uint8_t)0x15) -#define MPU_REGION_SIZE_8MB ((uint8_t)0x16) -#define MPU_REGION_SIZE_16MB ((uint8_t)0x17) -#define MPU_REGION_SIZE_32MB ((uint8_t)0x18) -#define MPU_REGION_SIZE_64MB ((uint8_t)0x19) -#define MPU_REGION_SIZE_128MB ((uint8_t)0x1A) -#define MPU_REGION_SIZE_256MB ((uint8_t)0x1B) -#define MPU_REGION_SIZE_512MB ((uint8_t)0x1C) -#define MPU_REGION_SIZE_1GB ((uint8_t)0x1D) -#define MPU_REGION_SIZE_2GB ((uint8_t)0x1E) -#define MPU_REGION_SIZE_4GB ((uint8_t)0x1F) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Permission_Attributes CORTEX MPU Region Permission Attributes - * @{ - */ -#define MPU_REGION_NO_ACCESS ((uint8_t)0x00) -#define MPU_REGION_PRIV_RW ((uint8_t)0x01) -#define MPU_REGION_PRIV_RW_URO ((uint8_t)0x02) -#define MPU_REGION_FULL_ACCESS ((uint8_t)0x03) -#define MPU_REGION_PRIV_RO ((uint8_t)0x05) -#define MPU_REGION_PRIV_RO_URO ((uint8_t)0x06) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Number CORTEX MPU Region Number - * @{ - */ -#define MPU_REGION_NUMBER0 ((uint8_t)0x00) -#define MPU_REGION_NUMBER1 ((uint8_t)0x01) -#define MPU_REGION_NUMBER2 ((uint8_t)0x02) -#define MPU_REGION_NUMBER3 ((uint8_t)0x03) -#define MPU_REGION_NUMBER4 ((uint8_t)0x04) -#define MPU_REGION_NUMBER5 ((uint8_t)0x05) -#define MPU_REGION_NUMBER6 ((uint8_t)0x06) -#define MPU_REGION_NUMBER7 ((uint8_t)0x07) -/** - * @} - */ -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - - -/* Exported Macros -----------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CORTEX_Exported_Functions - * @{ - */ - -/** @addtogroup CORTEX_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup); -void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority); -void HAL_NVIC_EnableIRQ(IRQn_Type IRQn); -void HAL_NVIC_DisableIRQ(IRQn_Type IRQn); -void HAL_NVIC_SystemReset(void); -uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb); -/** - * @} - */ - -/** @addtogroup CORTEX_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -uint32_t HAL_NVIC_GetPriorityGrouping(void); -void HAL_NVIC_GetPriority(IRQn_Type IRQn, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority); -uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn); -void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn); -void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn); -uint32_t HAL_NVIC_GetActive(IRQn_Type IRQn); -void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource); -void HAL_SYSTICK_IRQHandler(void); -void HAL_SYSTICK_Callback(void); - -#if (__MPU_PRESENT == 1U) -void HAL_MPU_Enable(uint32_t MPU_Control); -void HAL_MPU_Disable(void); -void HAL_MPU_ConfigRegion(MPU_Region_InitTypeDef *MPU_Init); -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CORTEX_Private_Macros CORTEX Private Macros - * @{ - */ -#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PRIORITYGROUP_0) || \ - ((GROUP) == NVIC_PRIORITYGROUP_1) || \ - ((GROUP) == NVIC_PRIORITYGROUP_2) || \ - ((GROUP) == NVIC_PRIORITYGROUP_3) || \ - ((GROUP) == NVIC_PRIORITYGROUP_4)) - -#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10U) - -#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10U) - -#define IS_NVIC_DEVICE_IRQ(IRQ) ((IRQ) >= (IRQn_Type)0x00U) - -#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SYSTICK_CLKSOURCE_HCLK) || \ - ((SOURCE) == SYSTICK_CLKSOURCE_HCLK_DIV8)) - -#if (__MPU_PRESENT == 1U) -#define IS_MPU_REGION_ENABLE(STATE) (((STATE) == MPU_REGION_ENABLE) || \ - ((STATE) == MPU_REGION_DISABLE)) - -#define IS_MPU_INSTRUCTION_ACCESS(STATE) (((STATE) == MPU_INSTRUCTION_ACCESS_ENABLE) || \ - ((STATE) == MPU_INSTRUCTION_ACCESS_DISABLE)) - -#define IS_MPU_ACCESS_SHAREABLE(STATE) (((STATE) == MPU_ACCESS_SHAREABLE) || \ - ((STATE) == MPU_ACCESS_NOT_SHAREABLE)) - -#define IS_MPU_ACCESS_CACHEABLE(STATE) (((STATE) == MPU_ACCESS_CACHEABLE) || \ - ((STATE) == MPU_ACCESS_NOT_CACHEABLE)) - -#define IS_MPU_ACCESS_BUFFERABLE(STATE) (((STATE) == MPU_ACCESS_BUFFERABLE) || \ - ((STATE) == MPU_ACCESS_NOT_BUFFERABLE)) - -#define IS_MPU_TEX_LEVEL(TYPE) (((TYPE) == MPU_TEX_LEVEL0) || \ - ((TYPE) == MPU_TEX_LEVEL1) || \ - ((TYPE) == MPU_TEX_LEVEL2)) - -#define IS_MPU_REGION_PERMISSION_ATTRIBUTE(TYPE) (((TYPE) == MPU_REGION_NO_ACCESS) || \ - ((TYPE) == MPU_REGION_PRIV_RW) || \ - ((TYPE) == MPU_REGION_PRIV_RW_URO) || \ - ((TYPE) == MPU_REGION_FULL_ACCESS) || \ - ((TYPE) == MPU_REGION_PRIV_RO) || \ - ((TYPE) == MPU_REGION_PRIV_RO_URO)) - -#define IS_MPU_REGION_NUMBER(NUMBER) (((NUMBER) == MPU_REGION_NUMBER0) || \ - ((NUMBER) == MPU_REGION_NUMBER1) || \ - ((NUMBER) == MPU_REGION_NUMBER2) || \ - ((NUMBER) == MPU_REGION_NUMBER3) || \ - ((NUMBER) == MPU_REGION_NUMBER4) || \ - ((NUMBER) == MPU_REGION_NUMBER5) || \ - ((NUMBER) == MPU_REGION_NUMBER6) || \ - ((NUMBER) == MPU_REGION_NUMBER7)) - -#define IS_MPU_REGION_SIZE(SIZE) (((SIZE) == MPU_REGION_SIZE_32B) || \ - ((SIZE) == MPU_REGION_SIZE_64B) || \ - ((SIZE) == MPU_REGION_SIZE_128B) || \ - ((SIZE) == MPU_REGION_SIZE_256B) || \ - ((SIZE) == MPU_REGION_SIZE_512B) || \ - ((SIZE) == MPU_REGION_SIZE_1KB) || \ - ((SIZE) == MPU_REGION_SIZE_2KB) || \ - ((SIZE) == MPU_REGION_SIZE_4KB) || \ - ((SIZE) == MPU_REGION_SIZE_8KB) || \ - ((SIZE) == MPU_REGION_SIZE_16KB) || \ - ((SIZE) == MPU_REGION_SIZE_32KB) || \ - ((SIZE) == MPU_REGION_SIZE_64KB) || \ - ((SIZE) == MPU_REGION_SIZE_128KB) || \ - ((SIZE) == MPU_REGION_SIZE_256KB) || \ - ((SIZE) == MPU_REGION_SIZE_512KB) || \ - ((SIZE) == MPU_REGION_SIZE_1MB) || \ - ((SIZE) == MPU_REGION_SIZE_2MB) || \ - ((SIZE) == MPU_REGION_SIZE_4MB) || \ - ((SIZE) == MPU_REGION_SIZE_8MB) || \ - ((SIZE) == MPU_REGION_SIZE_16MB) || \ - ((SIZE) == MPU_REGION_SIZE_32MB) || \ - ((SIZE) == MPU_REGION_SIZE_64MB) || \ - ((SIZE) == MPU_REGION_SIZE_128MB) || \ - ((SIZE) == MPU_REGION_SIZE_256MB) || \ - ((SIZE) == MPU_REGION_SIZE_512MB) || \ - ((SIZE) == MPU_REGION_SIZE_1GB) || \ - ((SIZE) == MPU_REGION_SIZE_2GB) || \ - ((SIZE) == MPU_REGION_SIZE_4GB)) - -#define IS_MPU_SUB_REGION_DISABLE(SUBREGION) ((SUBREGION) < (uint16_t)0x00FF) -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CORTEX_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h deleted file mode 100644 index bbd58a581ae0b7d..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h +++ /dev/null @@ -1,184 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_crc.h - * @author MCD Application Team - * @brief Header file of CRC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_CRC_H -#define STM32F4xx_HAL_CRC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CRC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CRC_Exported_Types CRC Exported Types - * @{ - */ - -/** - * @brief CRC HAL State Structure definition - */ -typedef enum -{ - HAL_CRC_STATE_RESET = 0x00U, /*!< CRC not yet initialized or disabled */ - HAL_CRC_STATE_READY = 0x01U, /*!< CRC initialized and ready for use */ - HAL_CRC_STATE_BUSY = 0x02U, /*!< CRC internal process is ongoing */ - HAL_CRC_STATE_TIMEOUT = 0x03U, /*!< CRC timeout state */ - HAL_CRC_STATE_ERROR = 0x04U /*!< CRC error state */ -} HAL_CRC_StateTypeDef; - - -/** - * @brief CRC Handle Structure definition - */ -typedef struct -{ - CRC_TypeDef *Instance; /*!< Register base address */ - - HAL_LockTypeDef Lock; /*!< CRC Locking object */ - - __IO HAL_CRC_StateTypeDef State; /*!< CRC communication state */ - -} CRC_HandleTypeDef; -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CRC_Exported_Constants CRC Exported Constants - * @{ - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CRC_Exported_Macros CRC Exported Macros - * @{ - */ - -/** @brief Reset CRC handle state. - * @param __HANDLE__ CRC handle. - * @retval None - */ -#define __HAL_CRC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CRC_STATE_RESET) - -/** - * @brief Reset CRC Data Register. - * @param __HANDLE__ CRC handle - * @retval None - */ -#define __HAL_CRC_DR_RESET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRC_CR_RESET) - -/** - * @brief Store data in the Independent Data (ID) register. - * @param __HANDLE__ CRC handle - * @param __VALUE__ Value to be stored in the ID register - * @note Refer to the Reference Manual to get the authorized __VALUE__ length in bits - * @retval None - */ -#define __HAL_CRC_SET_IDR(__HANDLE__, __VALUE__) (WRITE_REG((__HANDLE__)->Instance->IDR, (__VALUE__))) - -/** - * @brief Return the data stored in the Independent Data (ID) register. - * @param __HANDLE__ CRC handle - * @note Refer to the Reference Manual to get the authorized __VALUE__ length in bits - * @retval Value of the ID register - */ -#define __HAL_CRC_GET_IDR(__HANDLE__) (((__HANDLE__)->Instance->IDR) & CRC_IDR_IDR) -/** - * @} - */ - - -/* Private macros --------------------------------------------------------*/ -/** @defgroup CRC_Private_Macros CRC Private Macros - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CRC_Exported_Functions CRC Exported Functions - * @{ - */ - -/* Initialization and de-initialization functions ****************************/ -/** @defgroup CRC_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc); -HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc); -void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc); -void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc); -/** - * @} - */ - -/* Peripheral Control functions ***********************************************/ -/** @defgroup CRC_Exported_Functions_Group2 Peripheral Control functions - * @{ - */ -uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength); -uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength); -/** - * @} - */ - -/* Peripheral State and Error functions ***************************************/ -/** @defgroup CRC_Exported_Functions_Group3 Peripheral State functions - * @{ - */ -HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_CRC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp.h deleted file mode 100644 index 8596fe7d21effcf..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp.h +++ /dev/null @@ -1,685 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cryp.h - * @author MCD Application Team - * @brief Header file of CRYP HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CRYP_H -#define __STM32F4xx_HAL_CRYP_H - -#ifdef __cplusplus -extern "C" { -#endif - - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (AES) || defined (CRYP) -/** @addtogroup CRYP - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup CRYP_Exported_Types CRYP Exported Types - * @{ - */ - -/** - * @brief CRYP Init Structure definition - */ - -typedef struct -{ - uint32_t DataType; /*!< 32-bit data, 16-bit data, 8-bit data or 1-bit string. - This parameter can be a value of @ref CRYP_Data_Type */ - uint32_t KeySize; /*!< Used only in AES mode : 128, 192 or 256 bit key length in CRYP1. - 128 or 256 bit key length in TinyAES This parameter can be a value of @ref CRYP_Key_Size */ - uint32_t *pKey; /*!< The key used for encryption/decryption */ - uint32_t *pInitVect; /*!< The initialization vector used also as initialization - counter in CTR mode */ - uint32_t Algorithm; /*!< DES/ TDES Algorithm ECB/CBC - AES Algorithm ECB/CBC/CTR/GCM or CCM - This parameter can be a value of @ref CRYP_Algorithm_Mode */ - uint32_t *Header; /*!< used only in AES GCM and CCM Algorithm for authentication, - GCM : also known as Additional Authentication Data - CCM : named B1 composed of the associated data length and Associated Data. */ - uint32_t HeaderSize; /*!< The size of header buffer in word */ - uint32_t *B0; /*!< B0 is first authentication block used only in AES CCM mode */ - uint32_t DataWidthUnit; /*!< Data With Unit, this parameter can be value of @ref CRYP_Data_Width_Unit*/ - uint32_t HeaderWidthUnit; /*!< Header Width Unit, this parameter can be value of @ref CRYP_Header_Width_Unit*/ - uint32_t KeyIVConfigSkip; /*!< CRYP peripheral Key and IV configuration skip, to config Key and Initialization - Vector only once and to skip configuration for consecutive processings. - This parameter can be a value of @ref CRYP_Configuration_Skip */ - -} CRYP_ConfigTypeDef; - - -/** - * @brief CRYP State Structure definition - */ - -typedef enum -{ - HAL_CRYP_STATE_RESET = 0x00U, /*!< CRYP not yet initialized or disabled */ - HAL_CRYP_STATE_READY = 0x01U, /*!< CRYP initialized and ready for use */ - HAL_CRYP_STATE_BUSY = 0x02U /*!< CRYP BUSY, internal processing is ongoing */ -} HAL_CRYP_STATETypeDef; - - -/** - * @brief CRYP handle Structure definition - */ - -typedef struct __CRYP_HandleTypeDef -{ -#if defined (CRYP) - CRYP_TypeDef *Instance; /*!< CRYP registers base address */ -#else /* AES*/ - AES_TypeDef *Instance; /*!< AES Register base address */ -#endif /* End AES or CRYP */ - - CRYP_ConfigTypeDef Init; /*!< CRYP required parameters */ - - FunctionalState AutoKeyDerivation; /*!< Used only in TinyAES to allows to bypass or not key write-up before decryption. - This parameter can be a value of ENABLE/DISABLE */ - - uint32_t *pCrypInBuffPtr; /*!< Pointer to CRYP processing (encryption, decryption,...) buffer */ - - uint32_t *pCrypOutBuffPtr; /*!< Pointer to CRYP processing (encryption, decryption,...) buffer */ - - __IO uint16_t CrypHeaderCount; /*!< Counter of header data */ - - __IO uint16_t CrypInCount; /*!< Counter of input data */ - - __IO uint16_t CrypOutCount; /*!< Counter of output data */ - - uint16_t Size; /*!< length of input data in word */ - - uint32_t Phase; /*!< CRYP peripheral phase */ - - DMA_HandleTypeDef *hdmain; /*!< CRYP In DMA handle parameters */ - - DMA_HandleTypeDef *hdmaout; /*!< CRYP Out DMA handle parameters */ - - HAL_LockTypeDef Lock; /*!< CRYP locking object */ - - __IO HAL_CRYP_STATETypeDef State; /*!< CRYP peripheral state */ - - __IO uint32_t ErrorCode; /*!< CRYP peripheral error code */ - - uint32_t KeyIVConfig; /*!< CRYP peripheral Key and IV configuration flag, used when - configuration can be skipped */ - - uint32_t SizesSum; /*!< Sum of successive payloads lengths (in bytes), stored - for a single signature computation after several - messages processing */ - -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - void (*InCpltCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Input FIFO transfer completed callback */ - void (*OutCpltCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Output FIFO transfer completed callback */ - void (*ErrorCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Error callback */ - - void (* MspInitCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Msp Init callback */ - void (* MspDeInitCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Msp DeInit callback */ - -#endif /* (USE_HAL_CRYP_REGISTER_CALLBACKS) */ -} CRYP_HandleTypeDef; - - -/** - * @} - */ - -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -/** @defgroup HAL_CRYP_Callback_ID_enumeration_definition HAL CRYP Callback ID enumeration definition - * @brief HAL CRYP Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_CRYP_INPUT_COMPLETE_CB_ID = 0x01U, /*!< CRYP Input FIFO transfer completed callback ID */ - HAL_CRYP_OUTPUT_COMPLETE_CB_ID = 0x02U, /*!< CRYP Output FIFO transfer completed callback ID */ - HAL_CRYP_ERROR_CB_ID = 0x03U, /*!< CRYP Error callback ID */ - - HAL_CRYP_MSPINIT_CB_ID = 0x04U, /*!< CRYP MspInit callback ID */ - HAL_CRYP_MSPDEINIT_CB_ID = 0x05U /*!< CRYP MspDeInit callback ID */ - -} HAL_CRYP_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup HAL_CRYP_Callback_pointer_definition HAL CRYP Callback pointer definition - * @brief HAL CRYP Callback pointer definition - * @{ - */ - -typedef void (*pCRYP_CallbackTypeDef)(CRYP_HandleTypeDef *hcryp); /*!< pointer to a common CRYP callback function */ - -/** - * @} - */ - -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CRYP_Exported_Constants CRYP Exported Constants - * @{ - */ - -/** @defgroup CRYP_Error_Definition CRYP Error Definition - * @{ - */ -#define HAL_CRYP_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_CRYP_ERROR_WRITE 0x00000001U /*!< Write error */ -#define HAL_CRYP_ERROR_READ 0x00000002U /*!< Read error */ -#define HAL_CRYP_ERROR_DMA 0x00000004U /*!< DMA error */ -#define HAL_CRYP_ERROR_BUSY 0x00000008U /*!< Busy flag error */ -#define HAL_CRYP_ERROR_TIMEOUT 0x00000010U /*!< Timeout error */ -#define HAL_CRYP_ERROR_NOT_SUPPORTED 0x00000020U /*!< Not supported mode */ -#define HAL_CRYP_ERROR_AUTH_TAG_SEQUENCE 0x00000040U /*!< Sequence are not respected only for GCM or CCM */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -#define HAL_CRYP_ERROR_INVALID_CALLBACK ((uint32_t)0x00000080U) /*!< Invalid Callback error */ -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup CRYP_Data_Width_Unit CRYP Data Width Unit - * @{ - */ - -#define CRYP_DATAWIDTHUNIT_WORD 0x00000000U /*!< By default, size unit is word */ -#define CRYP_DATAWIDTHUNIT_BYTE 0x00000001U /*!< By default, size unit is word */ - -/** - * @} - */ - -/** @defgroup CRYP_Header_Width_Unit CRYP Header Width Unit - * @{ - */ - -#define CRYP_HEADERWIDTHUNIT_WORD 0x00000000U /*!< By default, header size unit is word */ -#define CRYP_HEADERWIDTHUNIT_BYTE 0x00000001U /*!< By default, header size unit is byte */ - -/** - * @} - */ - -/** @defgroup CRYP_Algorithm_Mode CRYP Algorithm Mode - * @{ - */ -#if defined(CRYP) - -#define CRYP_DES_ECB CRYP_CR_ALGOMODE_DES_ECB -#define CRYP_DES_CBC CRYP_CR_ALGOMODE_DES_CBC -#define CRYP_TDES_ECB CRYP_CR_ALGOMODE_TDES_ECB -#define CRYP_TDES_CBC CRYP_CR_ALGOMODE_TDES_CBC -#define CRYP_AES_ECB CRYP_CR_ALGOMODE_AES_ECB -#define CRYP_AES_CBC CRYP_CR_ALGOMODE_AES_CBC -#define CRYP_AES_CTR CRYP_CR_ALGOMODE_AES_CTR -#if defined (CRYP_CR_ALGOMODE_AES_GCM) -#define CRYP_AES_GCM CRYP_CR_ALGOMODE_AES_GCM -#define CRYP_AES_CCM CRYP_CR_ALGOMODE_AES_CCM -#endif /* GCM CCM defined*/ -#else /* AES*/ -#define CRYP_AES_ECB 0x00000000U /*!< Electronic codebook chaining algorithm */ -#define CRYP_AES_CBC AES_CR_CHMOD_0 /*!< Cipher block chaining algorithm */ -#define CRYP_AES_CTR AES_CR_CHMOD_1 /*!< Counter mode chaining algorithm */ -#define CRYP_AES_GCM_GMAC (AES_CR_CHMOD_0 | AES_CR_CHMOD_1) /*!< Galois counter mode - Galois message authentication code */ -#define CRYP_AES_CCM AES_CR_CHMOD_2 /*!< Counter with Cipher Mode */ -#endif /* End AES or CRYP */ - -/** - * @} - */ - -/** @defgroup CRYP_Key_Size CRYP Key Size - * @{ - */ -#if defined(CRYP) -#define CRYP_KEYSIZE_128B 0x00000000U -#define CRYP_KEYSIZE_192B CRYP_CR_KEYSIZE_0 -#define CRYP_KEYSIZE_256B CRYP_CR_KEYSIZE_1 -#else /* AES*/ -#define CRYP_KEYSIZE_128B 0x00000000U /*!< 128-bit long key */ -#define CRYP_KEYSIZE_256B AES_CR_KEYSIZE /*!< 256-bit long key */ -#endif /* End AES or CRYP */ -/** - * @} - */ - -/** @defgroup CRYP_Data_Type CRYP Data Type - * @{ - */ -#if defined(CRYP) -#define CRYP_DATATYPE_32B 0x00000000U -#define CRYP_DATATYPE_16B CRYP_CR_DATATYPE_0 -#define CRYP_DATATYPE_8B CRYP_CR_DATATYPE_1 -#define CRYP_DATATYPE_1B CRYP_CR_DATATYPE -#else /* AES*/ -#define CRYP_DATATYPE_32B 0x00000000U /*!< 32-bit data type (no swapping) */ -#define CRYP_DATATYPE_16B AES_CR_DATATYPE_0 /*!< 16-bit data type (half-word swapping) */ -#define CRYP_DATATYPE_8B AES_CR_DATATYPE_1 /*!< 8-bit data type (byte swapping) */ -#define CRYP_DATATYPE_1B AES_CR_DATATYPE /*!< 1-bit data type (bit swapping) */ -#endif /* End AES or CRYP */ - -/** - * @} - */ - -/** @defgroup CRYP_Interrupt CRYP Interrupt - * @{ - */ -#if defined (CRYP) -#define CRYP_IT_INI CRYP_IMSCR_INIM /*!< Input FIFO Interrupt */ -#define CRYP_IT_OUTI CRYP_IMSCR_OUTIM /*!< Output FIFO Interrupt */ -#else /* AES*/ -#define CRYP_IT_CCFIE AES_CR_CCFIE /*!< Computation Complete interrupt enable */ -#define CRYP_IT_ERRIE AES_CR_ERRIE /*!< Error interrupt enable */ -#define CRYP_IT_WRERR AES_SR_WRERR /*!< Write Error */ -#define CRYP_IT_RDERR AES_SR_RDERR /*!< Read Error */ -#define CRYP_IT_CCF AES_SR_CCF /*!< Computation completed */ -#endif /* End AES or CRYP */ - -/** - * @} - */ - -/** @defgroup CRYP_Flags CRYP Flags - * @{ - */ -#if defined (CRYP) -/* Flags in the SR register */ -#define CRYP_FLAG_IFEM CRYP_SR_IFEM /*!< Input FIFO is empty */ -#define CRYP_FLAG_IFNF CRYP_SR_IFNF /*!< Input FIFO is not Full */ -#define CRYP_FLAG_OFNE CRYP_SR_OFNE /*!< Output FIFO is not empty */ -#define CRYP_FLAG_OFFU CRYP_SR_OFFU /*!< Output FIFO is Full */ -#define CRYP_FLAG_BUSY CRYP_SR_BUSY /*!< The CRYP core is currently processing a block of data - or a key preparation (for AES decryption). */ -/* Flags in the RISR register */ -#define CRYP_FLAG_OUTRIS 0x01000002U /*!< Output FIFO service raw interrupt status */ -#define CRYP_FLAG_INRIS 0x01000001U /*!< Input FIFO service raw interrupt status*/ -#else /* AES*/ -/* status flags */ -#define CRYP_FLAG_BUSY AES_SR_BUSY /*!< GCM process suspension forbidden */ -#define CRYP_FLAG_WRERR AES_SR_WRERR /*!< Write Error */ -#define CRYP_FLAG_RDERR AES_SR_RDERR /*!< Read error */ -#define CRYP_FLAG_CCF AES_SR_CCF /*!< Computation completed */ -/* clearing flags */ -#define CRYP_CCF_CLEAR AES_CR_CCFC /*!< Computation Complete Flag Clear */ -#define CRYP_ERR_CLEAR AES_CR_ERRC /*!< Error Flag Clear */ -#endif /* End AES or CRYP */ - -/** - * @} - */ - -/** @defgroup CRYP_Configuration_Skip CRYP Key and IV Configuration Skip Mode - * @{ - */ - -#define CRYP_KEYIVCONFIG_ALWAYS 0x00000000U /*!< Peripheral Key and IV configuration to do systematically */ -#define CRYP_KEYIVCONFIG_ONCE 0x00000001U /*!< Peripheral Key and IV configuration to do only once */ - -/** - * @} - */ - - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CRYP_Exported_Macros CRYP Exported Macros - * @{ - */ - -/** @brief Reset CRYP handle state - * @param __HANDLE__ specifies the CRYP handle. - * @retval None - */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -#define __HAL_CRYP_RESET_HANDLE_STATE(__HANDLE__) do{\ - (__HANDLE__)->State = HAL_CRYP_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL;\ - (__HANDLE__)->MspDeInitCallback = NULL;\ - }while(0) -#else -#define __HAL_CRYP_RESET_HANDLE_STATE(__HANDLE__) ( (__HANDLE__)->State = HAL_CRYP_STATE_RESET) -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - -/** - * @brief Enable/Disable the CRYP peripheral. - * @param __HANDLE__: specifies the CRYP handle. - * @retval None - */ -#if defined(CRYP) -#define __HAL_CRYP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRYP_CR_CRYPEN) -#define __HAL_CRYP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~CRYP_CR_CRYPEN) -#else /* AES*/ -#define __HAL_CRYP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= AES_CR_EN) -#define __HAL_CRYP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~AES_CR_EN) -#endif /* End AES or CRYP */ - -/** @brief Check whether the specified CRYP status flag is set or not. - * @param __FLAG__: specifies the flag to check. - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_FLAG_BUSY GCM process suspension forbidden - * @arg @ref CRYP_IT_WRERR Write Error - * @arg @ref CRYP_IT_RDERR Read Error - * @arg @ref CRYP_IT_CCF Computation Complete - * This parameter can be one of the following values for CRYP: - * @arg CRYP_FLAG_BUSY: The CRYP core is currently processing a block of data - * or a key preparation (for AES decryption). - * @arg CRYP_FLAG_IFEM: Input FIFO is empty - * @arg CRYP_FLAG_IFNF: Input FIFO is not full - * @arg CRYP_FLAG_INRIS: Input FIFO service raw interrupt is pending - * @arg CRYP_FLAG_OFNE: Output FIFO is not empty - * @arg CRYP_FLAG_OFFU: Output FIFO is full - * @arg CRYP_FLAG_OUTRIS: Input FIFO service raw interrupt is pending - * @retval The state of __FLAG__ (TRUE or FALSE). - */ -#define CRYP_FLAG_MASK 0x0000001FU -#if defined(CRYP) -#define __HAL_CRYP_GET_FLAG(__HANDLE__, __FLAG__) ((((uint8_t)((__FLAG__) >> 24)) == 0x01U)?((((__HANDLE__)->Instance->RISR) & ((__FLAG__) & CRYP_FLAG_MASK)) == ((__FLAG__) & CRYP_FLAG_MASK)): \ - ((((__HANDLE__)->Instance->RISR) & ((__FLAG__) & CRYP_FLAG_MASK)) == ((__FLAG__) & CRYP_FLAG_MASK))) -#else /* AES*/ -#define __HAL_CRYP_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) -#endif /* End AES or CRYP */ - -/** @brief Clear the CRYP pending status flag. - * @param __FLAG__: specifies the flag to clear. - * This parameter can be one of the following values: - * @arg @ref CRYP_ERR_CLEAR Read (RDERR) or Write Error (WRERR) Flag Clear - * @arg @ref CRYP_CCF_CLEAR Computation Complete Flag (CCF) Clear - * @param __HANDLE__: specifies the CRYP handle. - * @retval None - */ - -#if defined(AES) -#define __HAL_CRYP_CLEAR_FLAG(__HANDLE__, __FLAG__) SET_BIT((__HANDLE__)->Instance->CR, (__FLAG__)) - - -/** @brief Check whether the specified CRYP interrupt source is enabled or not. - * @param __INTERRUPT__: CRYP interrupt source to check - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_IT_ERRIE Error interrupt (used for RDERR and WRERR) - * @arg @ref CRYP_IT_CCFIE Computation Complete interrupt - * @param __HANDLE__: specifies the CRYP handle. - * @retval State of interruption (TRUE or FALSE). - */ - -#define __HAL_CRYP_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR\ - & (__INTERRUPT__)) == (__INTERRUPT__)) - -#endif /* AES */ - -/** @brief Check whether the specified CRYP interrupt is set or not. - * @param __INTERRUPT__: specifies the interrupt to check. - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_IT_WRERR Write Error - * @arg @ref CRYP_IT_RDERR Read Error - * @arg @ref CRYP_IT_CCF Computation Complete - * This parameter can be one of the following values for CRYP: - * @arg CRYP_IT_INI: Input FIFO service masked interrupt status - * @arg CRYP_IT_OUTI: Output FIFO service masked interrupt status - * @param __HANDLE__: specifies the CRYP handle. - * @retval The state of __INTERRUPT__ (TRUE or FALSE). - */ -#if defined(CRYP) -#define __HAL_CRYP_GET_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->MISR\ - & (__INTERRUPT__)) == (__INTERRUPT__)) -#else /* AES*/ -#define __HAL_CRYP_GET_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->SR & (__INTERRUPT__)) == (__INTERRUPT__)) -#endif /* End AES or CRYP */ - -/** - * @brief Enable the CRYP interrupt. - * @param __INTERRUPT__: CRYP Interrupt. - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_IT_ERRIE Error interrupt (used for RDERR and WRERR) - * @arg @ref CRYP_IT_CCFIE Computation Complete interrupt - * This parameter can be one of the following values for CRYP: - * @ CRYP_IT_INI : Input FIFO service interrupt mask. - * @ CRYP_IT_OUTI : Output FIFO service interrupt mask.CRYP interrupt. - * @param __HANDLE__: specifies the CRYP handle. - * @retval None - */ -#if defined(CRYP) -#define __HAL_CRYP_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IMSCR) |= (__INTERRUPT__)) -#else /* AES*/ -#define __HAL_CRYP_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) |= (__INTERRUPT__)) -#endif /* End AES or CRYP */ - -/** - * @brief Disable the CRYP interrupt. - * @param __INTERRUPT__: CRYP Interrupt. - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_IT_ERRIE Error interrupt (used for RDERR and WRERR) - * @arg @ref CRYP_IT_CCFIE Computation Complete interrupt - * This parameter can be one of the following values for CRYP: - * @ CRYP_IT_INI : Input FIFO service interrupt mask. - * @ CRYP_IT_OUTI : Output FIFO service interrupt mask.CRYP interrupt. - * @param __HANDLE__: specifies the CRYP handle. - * @retval None - */ -#if defined(CRYP) -#define __HAL_CRYP_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IMSCR) &= ~(__INTERRUPT__)) -#else /* AES*/ -#define __HAL_CRYP_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) &= ~(__INTERRUPT__)) -#endif /* End AES or CRYP */ - -/** - * @} - */ -#if defined (CRYP_CR_ALGOMODE_AES_GCM)|| defined (AES) -/* Include CRYP HAL Extended module */ -#include "stm32f4xx_hal_cryp_ex.h" -#endif /* AES or GCM CCM defined*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CRYP_Exported_Functions CRYP Exported Functions - * @{ - */ - -/** @addtogroup CRYP_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_CRYP_Init(CRYP_HandleTypeDef *hcryp); -HAL_StatusTypeDef HAL_CRYP_DeInit(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_MspInit(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_MspDeInit(CRYP_HandleTypeDef *hcryp); -HAL_StatusTypeDef HAL_CRYP_SetConfig(CRYP_HandleTypeDef *hcryp, CRYP_ConfigTypeDef *pConf); -HAL_StatusTypeDef HAL_CRYP_GetConfig(CRYP_HandleTypeDef *hcryp, CRYP_ConfigTypeDef *pConf); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_CRYP_RegisterCallback(CRYP_HandleTypeDef *hcryp, HAL_CRYP_CallbackIDTypeDef CallbackID, - pCRYP_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_CRYP_UnRegisterCallback(CRYP_HandleTypeDef *hcryp, HAL_CRYP_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup CRYP_Exported_Functions_Group2 - * @{ - */ - -/* encryption/decryption ***********************************/ -HAL_StatusTypeDef HAL_CRYP_Encrypt(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output, - uint32_t Timeout); -HAL_StatusTypeDef HAL_CRYP_Decrypt(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output, - uint32_t Timeout); -HAL_StatusTypeDef HAL_CRYP_Encrypt_IT(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output); -HAL_StatusTypeDef HAL_CRYP_Decrypt_IT(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output); -HAL_StatusTypeDef HAL_CRYP_Encrypt_DMA(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output); -HAL_StatusTypeDef HAL_CRYP_Decrypt_DMA(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output); - -/** - * @} - */ - - -/** @addtogroup CRYP_Exported_Functions_Group3 - * @{ - */ -/* Interrupt Handler functions **********************************************/ -void HAL_CRYP_IRQHandler(CRYP_HandleTypeDef *hcryp); -HAL_CRYP_STATETypeDef HAL_CRYP_GetState(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_InCpltCallback(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_OutCpltCallback(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_ErrorCallback(CRYP_HandleTypeDef *hcryp); -uint32_t HAL_CRYP_GetError(CRYP_HandleTypeDef *hcryp); - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros --------------------------------------------------------*/ -/** @defgroup CRYP_Private_Macros CRYP Private Macros - * @{ - */ - -/** @defgroup CRYP_IS_CRYP_Definitions CRYP Private macros to check input parameters - * @{ - */ -#if defined(CRYP) -#if defined (CRYP_CR_ALGOMODE_AES_GCM) -#define IS_CRYP_ALGORITHM(ALGORITHM) (((ALGORITHM) == CRYP_DES_ECB) || \ - ((ALGORITHM) == CRYP_DES_CBC) || \ - ((ALGORITHM) == CRYP_TDES_ECB) || \ - ((ALGORITHM) == CRYP_TDES_CBC) || \ - ((ALGORITHM) == CRYP_AES_ECB) || \ - ((ALGORITHM) == CRYP_AES_CBC) || \ - ((ALGORITHM) == CRYP_AES_CTR) || \ - ((ALGORITHM) == CRYP_AES_GCM) || \ - ((ALGORITHM) == CRYP_AES_CCM)) -#else /*NO GCM CCM */ -#define IS_CRYP_ALGORITHM(ALGORITHM) (((ALGORITHM) == CRYP_DES_ECB) || \ - ((ALGORITHM) == CRYP_DES_CBC) || \ - ((ALGORITHM) == CRYP_TDES_ECB) || \ - ((ALGORITHM) == CRYP_TDES_CBC) || \ - ((ALGORITHM) == CRYP_AES_ECB) || \ - ((ALGORITHM) == CRYP_AES_CBC) || \ - ((ALGORITHM) == CRYP_AES_CTR)) -#endif /* GCM CCM defined*/ -#define IS_CRYP_KEYSIZE(KEYSIZE)(((KEYSIZE) == CRYP_KEYSIZE_128B) || \ - ((KEYSIZE) == CRYP_KEYSIZE_192B) || \ - ((KEYSIZE) == CRYP_KEYSIZE_256B)) -#else /* AES*/ -#define IS_CRYP_ALGORITHM(ALGORITHM) (((ALGORITHM) == CRYP_AES_ECB) || \ - ((ALGORITHM) == CRYP_AES_CBC) || \ - ((ALGORITHM) == CRYP_AES_CTR) || \ - ((ALGORITHM) == CRYP_AES_GCM_GMAC)|| \ - ((ALGORITHM) == CRYP_AES_CCM)) - - -#define IS_CRYP_KEYSIZE(KEYSIZE)(((KEYSIZE) == CRYP_KEYSIZE_128B) || \ - ((KEYSIZE) == CRYP_KEYSIZE_256B)) -#endif /* End AES or CRYP */ - -#define IS_CRYP_DATATYPE(DATATYPE)(((DATATYPE) == CRYP_DATATYPE_32B) || \ - ((DATATYPE) == CRYP_DATATYPE_16B) || \ - ((DATATYPE) == CRYP_DATATYPE_8B) || \ - ((DATATYPE) == CRYP_DATATYPE_1B)) - -#define IS_CRYP_INIT(CONFIG)(((CONFIG) == CRYP_KEYIVCONFIG_ALWAYS) || \ - ((CONFIG) == CRYP_KEYIVCONFIG_ONCE)) -/** - * @} - */ - -/** - * @} - */ - - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CRYP_Private_Constants CRYP Private Constants - * @{ - */ - -/** - * @} - */ -/* Private defines -----------------------------------------------------------*/ -/** @defgroup CRYP_Private_Defines CRYP Private Defines - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CRYP_Private_Variables CRYP Private Variables - * @{ - */ - -/** - * @} - */ -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup CRYP_Private_Functions_Prototypes CRYP Private Functions Prototypes - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup CRYP_Private_Functions CRYP Private Functions - * @{ - */ - -/** - * @} - */ - - -/** - * @} - */ - - -/** - * @} - */ -#endif /* TinyAES or CRYP*/ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CRYP_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp_ex.h deleted file mode 100644 index 251e94b1daac854..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp_ex.h +++ /dev/null @@ -1,144 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cryp_ex.h - * @author MCD Application Team - * @brief Header file of CRYP HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CRYP_EX_H -#define __STM32F4xx_HAL_CRYP_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CRYPEx - * @{ - */ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CRYPEx_Exported_Types CRYPEx Exported types - * @{ - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CRYPEx_Exported_Constants CRYPEx Exported constants - * @{ - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Types CRYPEx Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Variables CRYPEx Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Constants CRYPEx Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Macros CRYPEx Private Macros - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Functions CRYPEx Private Functions - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CRYPEx_Exported_Functions CRYPEx Exported Functions - * @{ - */ -#if defined (CRYP) || defined (AES) -/** @addtogroup CRYPEx_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_CRYPEx_AESGCM_GenerateAuthTAG(CRYP_HandleTypeDef *hcryp, uint32_t *AuthTag, uint32_t Timeout); -HAL_StatusTypeDef HAL_CRYPEx_AESCCM_GenerateAuthTAG(CRYP_HandleTypeDef *hcryp, uint32_t *AuthTag, uint32_t Timeout); -/** - * @} - */ -#endif /* CRYP||AES */ - -#if defined (AES) -/** @addtogroup CRYPEx_Exported_Functions_Group2 - * @{ - */ -void HAL_CRYPEx_EnableAutoKeyDerivation(CRYP_HandleTypeDef *hcryp); -void HAL_CRYPEx_DisableAutoKeyDerivation(CRYP_HandleTypeDef *hcryp); -/** - * @} - */ -#endif /* AES */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CRYP_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac.h deleted file mode 100644 index abd85449b6ae6fa..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac.h +++ /dev/null @@ -1,482 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dac.h - * @author MCD Application Team - * @brief Header file of DAC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_DAC_H -#define STM32F4xx_HAL_DAC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(DAC) - -/** @addtogroup DAC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup DAC_Exported_Types DAC Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_DAC_STATE_RESET = 0x00U, /*!< DAC not yet initialized or disabled */ - HAL_DAC_STATE_READY = 0x01U, /*!< DAC initialized and ready for use */ - HAL_DAC_STATE_BUSY = 0x02U, /*!< DAC internal processing is ongoing */ - HAL_DAC_STATE_TIMEOUT = 0x03U, /*!< DAC timeout state */ - HAL_DAC_STATE_ERROR = 0x04U /*!< DAC error state */ - -} HAL_DAC_StateTypeDef; - -/** - * @brief DAC handle Structure definition - */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -typedef struct __DAC_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ -{ - DAC_TypeDef *Instance; /*!< Register base address */ - - __IO HAL_DAC_StateTypeDef State; /*!< DAC communication state */ - - HAL_LockTypeDef Lock; /*!< DAC locking object */ - - DMA_HandleTypeDef *DMA_Handle1; /*!< Pointer DMA handler for channel 1 */ - - DMA_HandleTypeDef *DMA_Handle2; /*!< Pointer DMA handler for channel 2 */ - - __IO uint32_t ErrorCode; /*!< DAC Error code */ - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - void (* ConvCpltCallbackCh1) (struct __DAC_HandleTypeDef *hdac); - void (* ConvHalfCpltCallbackCh1) (struct __DAC_HandleTypeDef *hdac); - void (* ErrorCallbackCh1) (struct __DAC_HandleTypeDef *hdac); - void (* DMAUnderrunCallbackCh1) (struct __DAC_HandleTypeDef *hdac); -#if defined(DAC_CHANNEL2_SUPPORT) - void (* ConvCpltCallbackCh2) (struct __DAC_HandleTypeDef *hdac); - void (* ConvHalfCpltCallbackCh2) (struct __DAC_HandleTypeDef *hdac); - void (* ErrorCallbackCh2) (struct __DAC_HandleTypeDef *hdac); - void (* DMAUnderrunCallbackCh2) (struct __DAC_HandleTypeDef *hdac); -#endif /* DAC_CHANNEL2_SUPPORT */ - - void (* MspInitCallback) (struct __DAC_HandleTypeDef *hdac); - void (* MspDeInitCallback) (struct __DAC_HandleTypeDef *hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -} DAC_HandleTypeDef; - -/** - * @brief DAC Configuration regular Channel structure definition - */ -typedef struct -{ - uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel. - This parameter can be a value of @ref DAC_trigger_selection */ - - uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled. - This parameter can be a value of @ref DAC_output_buffer */ - -} DAC_ChannelConfTypeDef; - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL DAC Callback ID enumeration definition - */ -typedef enum -{ - HAL_DAC_CH1_COMPLETE_CB_ID = 0x00U, /*!< DAC CH1 Complete Callback ID */ - HAL_DAC_CH1_HALF_COMPLETE_CB_ID = 0x01U, /*!< DAC CH1 half Complete Callback ID */ - HAL_DAC_CH1_ERROR_ID = 0x02U, /*!< DAC CH1 error Callback ID */ - HAL_DAC_CH1_UNDERRUN_CB_ID = 0x03U, /*!< DAC CH1 underrun Callback ID */ -#if defined(DAC_CHANNEL2_SUPPORT) - HAL_DAC_CH2_COMPLETE_CB_ID = 0x04U, /*!< DAC CH2 Complete Callback ID */ - HAL_DAC_CH2_HALF_COMPLETE_CB_ID = 0x05U, /*!< DAC CH2 half Complete Callback ID */ - HAL_DAC_CH2_ERROR_ID = 0x06U, /*!< DAC CH2 error Callback ID */ - HAL_DAC_CH2_UNDERRUN_CB_ID = 0x07U, /*!< DAC CH2 underrun Callback ID */ -#endif /* DAC_CHANNEL2_SUPPORT */ - HAL_DAC_MSPINIT_CB_ID = 0x08U, /*!< DAC MspInit Callback ID */ - HAL_DAC_MSPDEINIT_CB_ID = 0x09U, /*!< DAC MspDeInit Callback ID */ - HAL_DAC_ALL_CB_ID = 0x0AU /*!< DAC All ID */ -} HAL_DAC_CallbackIDTypeDef; - -/** - * @brief HAL DAC Callback pointer definition - */ -typedef void (*pDAC_CallbackTypeDef)(DAC_HandleTypeDef *hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup DAC_Exported_Constants DAC Exported Constants - * @{ - */ - -/** @defgroup DAC_Error_Code DAC Error Code - * @{ - */ -#define HAL_DAC_ERROR_NONE 0x00U /*!< No error */ -#define HAL_DAC_ERROR_DMAUNDERRUNCH1 0x01U /*!< DAC channel1 DMA underrun error */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define HAL_DAC_ERROR_DMAUNDERRUNCH2 0x02U /*!< DAC channel2 DMA underrun error */ -#endif /* DAC_CHANNEL2_SUPPORT */ -#define HAL_DAC_ERROR_DMA 0x04U /*!< DMA error */ -#define HAL_DAC_ERROR_TIMEOUT 0x08U /*!< Timeout error */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -#define HAL_DAC_ERROR_INVALID_CALLBACK 0x10U /*!< Invalid callback error */ -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup DAC_trigger_selection DAC trigger selection - * @{ - */ -#define DAC_TRIGGER_NONE 0x00000000UL /*!< Conversion is automatic once the DAC1_DHRxxxx register has been loaded, and not by external trigger */ -#define DAC_TRIGGER_T2_TRGO (DAC_CR_TSEL1_2 | DAC_CR_TEN1) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_T4_TRGO (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_0 | DAC_CR_TEN1) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_T5_TRGO ( DAC_CR_TSEL1_1 | DAC_CR_TSEL1_0 | DAC_CR_TEN1) /*!< TIM3 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_T6_TRGO ( DAC_CR_TEN1) /*!< Conversion started by software trigger for DAC channel */ -#define DAC_TRIGGER_T7_TRGO ( DAC_CR_TSEL1_1 | DAC_CR_TEN1) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_T8_TRGO ( DAC_CR_TSEL1_0 | DAC_CR_TEN1) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_EXT_IT9 (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_1 | DAC_CR_TEN1) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_SOFTWARE (DAC_CR_TSEL1 | DAC_CR_TEN1) /*!< Conversion started by software trigger for DAC channel */ - -/** - * @} - */ - -/** @defgroup DAC_output_buffer DAC output buffer - * @{ - */ -#define DAC_OUTPUTBUFFER_ENABLE 0x00000000U -#define DAC_OUTPUTBUFFER_DISABLE (DAC_CR_BOFF1) - -/** - * @} - */ - -/** @defgroup DAC_Channel_selection DAC Channel selection - * @{ - */ -#define DAC_CHANNEL_1 0x00000000U -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_CHANNEL_2 0x00000010U -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** @defgroup DAC_data_alignment DAC data alignment - * @{ - */ -#define DAC_ALIGN_12B_R 0x00000000U -#define DAC_ALIGN_12B_L 0x00000004U -#define DAC_ALIGN_8B_R 0x00000008U - -/** - * @} - */ - -/** @defgroup DAC_flags_definition DAC flags definition - * @{ - */ -#define DAC_FLAG_DMAUDR1 (DAC_SR_DMAUDR1) -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_FLAG_DMAUDR2 (DAC_SR_DMAUDR2) -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -/** @defgroup DAC_IT_definition DAC IT definition - * @{ - */ -#define DAC_IT_DMAUDR1 (DAC_SR_DMAUDR1) -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_IT_DMAUDR2 (DAC_SR_DMAUDR2) -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/** @defgroup DAC_Exported_Macros DAC Exported Macros - * @{ - */ - -/** @brief Reset DAC handle state. - * @param __HANDLE__ specifies the DAC handle. - * @retval None - */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -#define __HAL_DAC_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_DAC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_DAC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DAC_STATE_RESET) -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** @brief Enable the DAC channel. - * @param __HANDLE__ specifies the DAC handle. - * @param __DAC_Channel__ specifies the DAC channel - * @retval None - */ -#define __HAL_DAC_ENABLE(__HANDLE__, __DAC_Channel__) \ - ((__HANDLE__)->Instance->CR |= (DAC_CR_EN1 << ((__DAC_Channel__) & 0x10UL))) - -/** @brief Disable the DAC channel. - * @param __HANDLE__ specifies the DAC handle - * @param __DAC_Channel__ specifies the DAC channel. - * @retval None - */ -#define __HAL_DAC_DISABLE(__HANDLE__, __DAC_Channel__) \ - ((__HANDLE__)->Instance->CR &= ~(DAC_CR_EN1 << ((__DAC_Channel__) & 0x10UL))) - -/** @brief Set DHR12R1 alignment. - * @param __ALIGNMENT__ specifies the DAC alignment - * @retval None - */ -#define DAC_DHR12R1_ALIGNMENT(__ALIGNMENT__) (0x00000008UL + (__ALIGNMENT__)) - -#if defined(DAC_CHANNEL2_SUPPORT) -/** @brief Set DHR12R2 alignment. - * @param __ALIGNMENT__ specifies the DAC alignment - * @retval None - */ -#define DAC_DHR12R2_ALIGNMENT(__ALIGNMENT__) (0x00000014UL + (__ALIGNMENT__)) -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** @brief Set DHR12RD alignment. - * @param __ALIGNMENT__ specifies the DAC alignment - * @retval None - */ -#define DAC_DHR12RD_ALIGNMENT(__ALIGNMENT__) (0x00000020UL + (__ALIGNMENT__)) - -/** @brief Enable the DAC interrupt. - * @param __HANDLE__ specifies the DAC handle - * @param __INTERRUPT__ specifies the DAC interrupt. - * This parameter can be any combination of the following values: - * @arg DAC_IT_DMAUDR1 DAC channel 1 DMA underrun interrupt - * @arg DAC_IT_DMAUDR2 DAC channel 2 DMA underrun interrupt - * @retval None - */ -#define __HAL_DAC_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) |= (__INTERRUPT__)) - -/** @brief Disable the DAC interrupt. - * @param __HANDLE__ specifies the DAC handle - * @param __INTERRUPT__ specifies the DAC interrupt. - * This parameter can be any combination of the following values: - * @arg DAC_IT_DMAUDR1 DAC channel 1 DMA underrun interrupt - * @arg DAC_IT_DMAUDR2 DAC channel 2 DMA underrun interrupt - * @retval None - */ -#define __HAL_DAC_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) &= ~(__INTERRUPT__)) - -/** @brief Check whether the specified DAC interrupt source is enabled or not. - * @param __HANDLE__ DAC handle - * @param __INTERRUPT__ DAC interrupt source to check - * This parameter can be any combination of the following values: - * @arg DAC_IT_DMAUDR1 DAC channel 1 DMA underrun interrupt - * @arg DAC_IT_DMAUDR2 DAC channel 2 DMA underrun interrupt - * @retval State of interruption (SET or RESET) - */ -#define __HAL_DAC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR\ - & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** @brief Get the selected DAC's flag status. - * @param __HANDLE__ specifies the DAC handle. - * @param __FLAG__ specifies the DAC flag to get. - * This parameter can be any combination of the following values: - * @arg DAC_FLAG_DMAUDR1 DAC channel 1 DMA underrun flag - * @arg DAC_FLAG_DMAUDR2 DAC channel 2 DMA underrun flag - * @retval None - */ -#define __HAL_DAC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the DAC's flag. - * @param __HANDLE__ specifies the DAC handle. - * @param __FLAG__ specifies the DAC flag to clear. - * This parameter can be any combination of the following values: - * @arg DAC_FLAG_DMAUDR1 DAC channel 1 DMA underrun flag - * @arg DAC_FLAG_DMAUDR2 DAC channel 2 DMA underrun flag - * @retval None - */ -#define __HAL_DAC_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = (__FLAG__)) - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ - -/** @defgroup DAC_Private_Macros DAC Private Macros - * @{ - */ -#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OUTPUTBUFFER_ENABLE) || \ - ((STATE) == DAC_OUTPUTBUFFER_DISABLE)) - -#if defined(DAC_CHANNEL2_SUPPORT) -#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_CHANNEL_1) || \ - ((CHANNEL) == DAC_CHANNEL_2)) -#else -#define IS_DAC_CHANNEL(CHANNEL) ((CHANNEL) == DAC_CHANNEL_1) -#endif /* DAC_CHANNEL2_SUPPORT */ - -#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_ALIGN_12B_R) || \ - ((ALIGN) == DAC_ALIGN_12B_L) || \ - ((ALIGN) == DAC_ALIGN_8B_R)) - -#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0UL) - -/** - * @} - */ - -/* Include DAC HAL Extended module */ -#include "stm32f4xx_hal_dac_ex.h" - -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup DAC_Exported_Functions - * @{ - */ - -/** @addtogroup DAC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_DAC_Init(DAC_HandleTypeDef *hdac); -HAL_StatusTypeDef HAL_DAC_DeInit(DAC_HandleTypeDef *hdac); -void HAL_DAC_MspInit(DAC_HandleTypeDef *hdac); -void HAL_DAC_MspDeInit(DAC_HandleTypeDef *hdac); - -/** - * @} - */ - -/** @addtogroup DAC_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -HAL_StatusTypeDef HAL_DAC_Start(DAC_HandleTypeDef *hdac, uint32_t Channel); -HAL_StatusTypeDef HAL_DAC_Stop(DAC_HandleTypeDef *hdac, uint32_t Channel); -HAL_StatusTypeDef HAL_DAC_Start_DMA(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t *pData, uint32_t Length, - uint32_t Alignment); -HAL_StatusTypeDef HAL_DAC_Stop_DMA(DAC_HandleTypeDef *hdac, uint32_t Channel); -void HAL_DAC_IRQHandler(DAC_HandleTypeDef *hdac); -HAL_StatusTypeDef HAL_DAC_SetValue(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Alignment, uint32_t Data); - -void HAL_DAC_ConvCpltCallbackCh1(DAC_HandleTypeDef *hdac); -void HAL_DAC_ConvHalfCpltCallbackCh1(DAC_HandleTypeDef *hdac); -void HAL_DAC_ErrorCallbackCh1(DAC_HandleTypeDef *hdac); -void HAL_DAC_DMAUnderrunCallbackCh1(DAC_HandleTypeDef *hdac); - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -/* DAC callback registering/unregistering */ -HAL_StatusTypeDef HAL_DAC_RegisterCallback(DAC_HandleTypeDef *hdac, HAL_DAC_CallbackIDTypeDef CallbackID, - pDAC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DAC_UnRegisterCallback(DAC_HandleTypeDef *hdac, HAL_DAC_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup DAC_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -uint32_t HAL_DAC_GetValue(DAC_HandleTypeDef *hdac, uint32_t Channel); -HAL_StatusTypeDef HAL_DAC_ConfigChannel(DAC_HandleTypeDef *hdac, DAC_ChannelConfTypeDef *sConfig, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup DAC_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State and Error functions ***************************************/ -HAL_DAC_StateTypeDef HAL_DAC_GetState(DAC_HandleTypeDef *hdac); -uint32_t HAL_DAC_GetError(DAC_HandleTypeDef *hdac); - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup DAC_Private_Functions DAC Private Functions - * @{ - */ -void DAC_DMAConvCpltCh1(DMA_HandleTypeDef *hdma); -void DAC_DMAErrorCh1(DMA_HandleTypeDef *hdma); -void DAC_DMAHalfConvCpltCh1(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_DAC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac_ex.h deleted file mode 100644 index 03159d4fe5f6257..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac_ex.h +++ /dev/null @@ -1,207 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dac_ex.h - * @author MCD Application Team - * @brief Header file of DAC HAL Extended module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_DAC_EX_H -#define STM32F4xx_HAL_DAC_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(DAC) - -/** @addtogroup DACEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL State structures definition - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup DACEx_Exported_Constants DACEx Exported Constants - * @{ - */ - -/** @defgroup DACEx_lfsrunmask_triangleamplitude DACEx lfsrunmask triangle amplitude - * @{ - */ -#define DAC_LFSRUNMASK_BIT0 0x00000000UL /*!< Unmask DAC channel LFSR bit0 for noise wave generation */ -#define DAC_LFSRUNMASK_BITS1_0 ( DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS2_0 ( DAC_CR_MAMP1_1 ) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS3_0 ( DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS4_0 ( DAC_CR_MAMP1_2 ) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS5_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS6_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 ) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS7_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS8_0 (DAC_CR_MAMP1_3 ) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS9_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS10_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 ) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS11_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */ -#define DAC_TRIANGLEAMPLITUDE_1 0x00000000UL /*!< Select max triangle amplitude of 1 */ -#define DAC_TRIANGLEAMPLITUDE_3 ( DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 3 */ -#define DAC_TRIANGLEAMPLITUDE_7 ( DAC_CR_MAMP1_1 ) /*!< Select max triangle amplitude of 7 */ -#define DAC_TRIANGLEAMPLITUDE_15 ( DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 15 */ -#define DAC_TRIANGLEAMPLITUDE_31 ( DAC_CR_MAMP1_2 ) /*!< Select max triangle amplitude of 31 */ -#define DAC_TRIANGLEAMPLITUDE_63 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 63 */ -#define DAC_TRIANGLEAMPLITUDE_127 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 ) /*!< Select max triangle amplitude of 127 */ -#define DAC_TRIANGLEAMPLITUDE_255 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 255 */ -#define DAC_TRIANGLEAMPLITUDE_511 (DAC_CR_MAMP1_3 ) /*!< Select max triangle amplitude of 511 */ -#define DAC_TRIANGLEAMPLITUDE_1023 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 1023 */ -#define DAC_TRIANGLEAMPLITUDE_2047 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 ) /*!< Select max triangle amplitude of 2047 */ -#define DAC_TRIANGLEAMPLITUDE_4095 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 4095 */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - - -/* Private macro -------------------------------------------------------------*/ - -/** @defgroup DACEx_Private_Macros DACEx Private Macros - * @{ - */ -#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_TRIGGER_NONE) || \ - ((TRIGGER) == DAC_TRIGGER_T2_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T8_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T7_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T5_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T6_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T4_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_EXT_IT9) || \ - ((TRIGGER) == DAC_TRIGGER_SOFTWARE)) - -#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUNMASK_BIT0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS1_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS2_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS3_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS4_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS5_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS6_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS7_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS8_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS9_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS10_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS11_0) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_1) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_3) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_7) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_15) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_31) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_63) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_127) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_255) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_511) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_1023) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_2047) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_4095)) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/* Extended features functions ***********************************************/ - -/** @addtogroup DACEx_Exported_Functions - * @{ - */ - -/** @addtogroup DACEx_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ - -HAL_StatusTypeDef HAL_DACEx_TriangleWaveGenerate(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Amplitude); -HAL_StatusTypeDef HAL_DACEx_NoiseWaveGenerate(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Amplitude); - -#if defined(DAC_CHANNEL2_SUPPORT) -#endif -HAL_StatusTypeDef HAL_DACEx_DualStart(DAC_HandleTypeDef *hdac); -HAL_StatusTypeDef HAL_DACEx_DualStop(DAC_HandleTypeDef *hdac); -HAL_StatusTypeDef HAL_DACEx_DualSetValue(DAC_HandleTypeDef *hdac, uint32_t Alignment, uint32_t Data1, uint32_t Data2); -uint32_t HAL_DACEx_DualGetValue(DAC_HandleTypeDef *hdac); - -#if defined(DAC_CHANNEL2_SUPPORT) -#endif -void HAL_DACEx_ConvCpltCallbackCh2(DAC_HandleTypeDef *hdac); -void HAL_DACEx_ConvHalfCpltCallbackCh2(DAC_HandleTypeDef *hdac); -void HAL_DACEx_ErrorCallbackCh2(DAC_HandleTypeDef *hdac); -void HAL_DACEx_DMAUnderrunCallbackCh2(DAC_HandleTypeDef *hdac); - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup DACEx_Private_Functions - * @{ - */ -#if defined(DAC_CHANNEL2_SUPPORT) -/* DAC_DMAConvCpltCh2 / DAC_DMAErrorCh2 / DAC_DMAHalfConvCpltCh2 */ -/* are called by HAL_DAC_Start_DMA */ -void DAC_DMAConvCpltCh2(DMA_HandleTypeDef *hdma); -void DAC_DMAErrorCh2(DMA_HandleTypeDef *hdma); -void DAC_DMAHalfConvCpltCh2(DMA_HandleTypeDef *hdma); -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_DAC_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi.h deleted file mode 100644 index 2a9edb6c47f28cd..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi.h +++ /dev/null @@ -1,567 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dcmi.h - * @author MCD Application Team - * @brief Header file of DCMI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DCMI_H -#define __STM32F4xx_HAL_DCMI_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/* Include DCMI HAL Extended module */ -/* (include on top of file since DCMI structures are defined in extended file) */ -#include "stm32f4xx_hal_dcmi_ex.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DCMI DCMI - * @brief DCMI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DCMI_Exported_Types DCMI Exported Types - * @{ - */ -/** - * @brief DCMI Embedded Synchronisation CODE Init structure definition - */ -typedef struct -{ - uint8_t FrameStartUnmask; /*!< Specifies the frame start delimiter unmask. */ - uint8_t LineStartUnmask; /*!< Specifies the line start delimiter unmask. */ - uint8_t LineEndUnmask; /*!< Specifies the line end delimiter unmask. */ - uint8_t FrameEndUnmask; /*!< Specifies the frame end delimiter unmask. */ -}DCMI_SyncUnmaskTypeDef; -/** - * @brief HAL DCMI State structures definition - */ -typedef enum -{ - HAL_DCMI_STATE_RESET = 0x00U, /*!< DCMI not yet initialized or disabled */ - HAL_DCMI_STATE_READY = 0x01U, /*!< DCMI initialized and ready for use */ - HAL_DCMI_STATE_BUSY = 0x02U, /*!< DCMI internal processing is ongoing */ - HAL_DCMI_STATE_TIMEOUT = 0x03U, /*!< DCMI timeout state */ - HAL_DCMI_STATE_ERROR = 0x04U, /*!< DCMI error state */ - HAL_DCMI_STATE_SUSPENDED = 0x05U /*!< DCMI suspend state */ -}HAL_DCMI_StateTypeDef; - -/** - * @brief DCMI handle Structure definition - */ -typedef struct __DCMI_HandleTypeDef -{ - DCMI_TypeDef *Instance; /*!< DCMI Register base address */ - - DCMI_InitTypeDef Init; /*!< DCMI parameters */ - - HAL_LockTypeDef Lock; /*!< DCMI locking object */ - - __IO HAL_DCMI_StateTypeDef State; /*!< DCMI state */ - - __IO uint32_t XferCount; /*!< DMA transfer counter */ - - __IO uint32_t XferSize; /*!< DMA transfer size */ - - uint32_t XferTransferNumber; /*!< DMA transfer number */ - - uint32_t pBuffPtr; /*!< Pointer to DMA output buffer */ - - DMA_HandleTypeDef *DMA_Handle; /*!< Pointer to the DMA handler */ - - __IO uint32_t ErrorCode; /*!< DCMI Error code */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - void (* FrameEventCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Frame Event Callback */ - void (* VsyncEventCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Vsync Event Callback */ - void (* LineEventCallback ) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Line Event Callback */ - void (* ErrorCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Error Callback */ - void (* MspInitCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Msp Init callback */ - void (* MspDeInitCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Msp DeInit callback */ -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ -}DCMI_HandleTypeDef; - -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) -typedef enum -{ - HAL_DCMI_FRAME_EVENT_CB_ID = 0x00U, /*!< DCMI Frame Event Callback ID */ - HAL_DCMI_VSYNC_EVENT_CB_ID = 0x01U, /*!< DCMI Vsync Event Callback ID */ - HAL_DCMI_LINE_EVENT_CB_ID = 0x02U, /*!< DCMI Line Event Callback ID */ - HAL_DCMI_ERROR_CB_ID = 0x03U, /*!< DCMI Error Callback ID */ - HAL_DCMI_MSPINIT_CB_ID = 0x04U, /*!< DCMI MspInit callback ID */ - HAL_DCMI_MSPDEINIT_CB_ID = 0x05U /*!< DCMI MspDeInit callback ID */ - -}HAL_DCMI_CallbackIDTypeDef; - -typedef void (*pDCMI_CallbackTypeDef)(DCMI_HandleTypeDef *hdcmi); -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ - - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DCMI_Exported_Constants DCMI Exported Constants - * @{ - */ - -/** @defgroup DCMI_Error_Code DCMI Error Code - * @{ - */ -#define HAL_DCMI_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_DCMI_ERROR_OVR 0x00000001U /*!< Overrun error */ -#define HAL_DCMI_ERROR_SYNC 0x00000002U /*!< Synchronization error */ -#define HAL_DCMI_ERROR_TIMEOUT 0x00000020U /*!< Timeout error */ -#define HAL_DCMI_ERROR_DMA 0x00000040U /*!< DMA error */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) -#define HAL_DCMI_ERROR_INVALID_CALLBACK ((uint32_t)0x00000080U) /*!< Invalid callback error */ -#endif -/** - * @} - */ - -/** @defgroup DCMI_Capture_Mode DCMI Capture Mode - * @{ - */ -#define DCMI_MODE_CONTINUOUS 0x00000000U /*!< The received data are transferred continuously - into the destination memory through the DMA */ -#define DCMI_MODE_SNAPSHOT ((uint32_t)DCMI_CR_CM) /*!< Once activated, the interface waits for the start of - frame and then transfers a single frame through the DMA */ -/** - * @} - */ - -/** @defgroup DCMI_Synchronization_Mode DCMI Synchronization Mode - * @{ - */ -#define DCMI_SYNCHRO_HARDWARE 0x00000000U /*!< Hardware synchronization data capture (frame/line start/stop) - is synchronized with the HSYNC/VSYNC signals */ -#define DCMI_SYNCHRO_EMBEDDED ((uint32_t)DCMI_CR_ESS) /*!< Embedded synchronization data capture is synchronized with - synchronization codes embedded in the data flow */ - -/** - * @} - */ - -/** @defgroup DCMI_PIXCK_Polarity DCMI PIXCK Polarity - * @{ - */ -#define DCMI_PCKPOLARITY_FALLING 0x00000000U /*!< Pixel clock active on Falling edge */ -#define DCMI_PCKPOLARITY_RISING ((uint32_t)DCMI_CR_PCKPOL) /*!< Pixel clock active on Rising edge */ - -/** - * @} - */ - -/** @defgroup DCMI_VSYNC_Polarity DCMI VSYNC Polarity - * @{ - */ -#define DCMI_VSPOLARITY_LOW 0x00000000U /*!< Vertical synchronization active Low */ -#define DCMI_VSPOLARITY_HIGH ((uint32_t)DCMI_CR_VSPOL) /*!< Vertical synchronization active High */ - -/** - * @} - */ - -/** @defgroup DCMI_HSYNC_Polarity DCMI HSYNC Polarity - * @{ - */ -#define DCMI_HSPOLARITY_LOW 0x00000000U /*!< Horizontal synchronization active Low */ -#define DCMI_HSPOLARITY_HIGH ((uint32_t)DCMI_CR_HSPOL) /*!< Horizontal synchronization active High */ - -/** - * @} - */ - -/** @defgroup DCMI_MODE_JPEG DCMI MODE JPEG - * @{ - */ -#define DCMI_JPEG_DISABLE 0x00000000U /*!< Mode JPEG Disabled */ -#define DCMI_JPEG_ENABLE ((uint32_t)DCMI_CR_JPEG) /*!< Mode JPEG Enabled */ - -/** - * @} - */ - -/** @defgroup DCMI_Capture_Rate DCMI Capture Rate - * @{ - */ -#define DCMI_CR_ALL_FRAME 0x00000000U /*!< All frames are captured */ -#define DCMI_CR_ALTERNATE_2_FRAME ((uint32_t)DCMI_CR_FCRC_0) /*!< Every alternate frame captured */ -#define DCMI_CR_ALTERNATE_4_FRAME ((uint32_t)DCMI_CR_FCRC_1) /*!< One frame in 4 frames captured */ - -/** - * @} - */ - -/** @defgroup DCMI_Extended_Data_Mode DCMI Extended Data Mode - * @{ - */ -#define DCMI_EXTEND_DATA_8B 0x00000000U /*!< Interface captures 8-bit data on every pixel clock */ -#define DCMI_EXTEND_DATA_10B ((uint32_t)DCMI_CR_EDM_0) /*!< Interface captures 10-bit data on every pixel clock */ -#define DCMI_EXTEND_DATA_12B ((uint32_t)DCMI_CR_EDM_1) /*!< Interface captures 12-bit data on every pixel clock */ -#define DCMI_EXTEND_DATA_14B ((uint32_t)(DCMI_CR_EDM_0 | DCMI_CR_EDM_1)) /*!< Interface captures 14-bit data on every pixel clock */ - -/** - * @} - */ - -/** @defgroup DCMI_Window_Coordinate DCMI Window Coordinate - * @{ - */ -#define DCMI_WINDOW_COORDINATE 0x3FFFU /*!< Window coordinate */ - -/** - * @} - */ - -/** @defgroup DCMI_Window_Height DCMI Window Height - * @{ - */ -#define DCMI_WINDOW_HEIGHT 0x1FFFU /*!< Window Height */ - -/** - * @} - */ - -/** @defgroup DCMI_Window_Vertical_Line DCMI Window Vertical Line - * @{ - */ -#define DCMI_POSITION_CWSIZE_VLINE (uint32_t)DCMI_CWSIZE_VLINE_Pos /*!< Required left shift to set crop window vertical line count */ -#define DCMI_POSITION_CWSTRT_VST (uint32_t)DCMI_CWSTRT_VST_Pos /*!< Required left shift to set crop window vertical start line count */ - -/** - * @} - */ - -/** @defgroup DCMI_interrupt_sources DCMI interrupt sources - * @{ - */ -#define DCMI_IT_FRAME ((uint32_t)DCMI_IER_FRAME_IE) /*!< Capture complete interrupt */ -#define DCMI_IT_OVR ((uint32_t)DCMI_IER_OVR_IE) /*!< Overrun interrupt */ -#define DCMI_IT_ERR ((uint32_t)DCMI_IER_ERR_IE) /*!< Synchronization error interrupt */ -#define DCMI_IT_VSYNC ((uint32_t)DCMI_IER_VSYNC_IE) /*!< VSYNC interrupt */ -#define DCMI_IT_LINE ((uint32_t)DCMI_IER_LINE_IE) /*!< Line interrupt */ -/** - * @} - */ - -/** @defgroup DCMI_Flags DCMI Flags - * @{ - */ - -/** - * @brief DCMI SR register - */ -#define DCMI_FLAG_HSYNC ((uint32_t)DCMI_SR_INDEX|DCMI_SR_HSYNC) /*!< HSYNC pin state (active line / synchronization between lines) */ -#define DCMI_FLAG_VSYNC ((uint32_t)DCMI_SR_INDEX|DCMI_SR_VSYNC) /*!< VSYNC pin state (active frame / synchronization between frames) */ -#define DCMI_FLAG_FNE ((uint32_t)DCMI_SR_INDEX|DCMI_SR_FNE) /*!< FIFO not empty flag */ -/** - * @brief DCMI RIS register - */ -#define DCMI_FLAG_FRAMERI ((uint32_t)DCMI_RISR_FRAME_RIS) /*!< Frame capture complete interrupt flag */ -#define DCMI_FLAG_OVRRI ((uint32_t)DCMI_RISR_OVR_RIS) /*!< Overrun interrupt flag */ -#define DCMI_FLAG_ERRRI ((uint32_t)DCMI_RISR_ERR_RIS) /*!< Synchronization error interrupt flag */ -#define DCMI_FLAG_VSYNCRI ((uint32_t)DCMI_RISR_VSYNC_RIS) /*!< VSYNC interrupt flag */ -#define DCMI_FLAG_LINERI ((uint32_t)DCMI_RISR_LINE_RIS) /*!< Line interrupt flag */ -/** - * @brief DCMI MIS register - */ -#define DCMI_FLAG_FRAMEMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_FRAME_MIS) /*!< DCMI Frame capture complete masked interrupt status */ -#define DCMI_FLAG_OVRMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_OVR_MIS ) /*!< DCMI Overrun masked interrupt status */ -#define DCMI_FLAG_ERRMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_ERR_MIS ) /*!< DCMI Synchronization error masked interrupt status */ -#define DCMI_FLAG_VSYNCMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_VSYNC_MIS) /*!< DCMI VSYNC masked interrupt status */ -#define DCMI_FLAG_LINEMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_LINE_MIS ) /*!< DCMI Line masked interrupt status */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DCMI_Exported_Macros DCMI Exported Macros - * @{ - */ - -/** @brief Reset DCMI handle state - * @param __HANDLE__ specifies the DCMI handle. - * @retval None - */ -#define __HAL_DCMI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DCMI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) - -/** - * @brief Enable the DCMI. - * @param __HANDLE__ DCMI handle - * @retval None - */ -#define __HAL_DCMI_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= DCMI_CR_ENABLE) - -/** - * @brief Disable the DCMI. - * @param __HANDLE__ DCMI handle - * @retval None - */ -#define __HAL_DCMI_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(DCMI_CR_ENABLE)) - -/* Interrupt & Flag management */ -/** - * @brief Get the DCMI pending flag. - * @param __HANDLE__ DCMI handle - * @param __FLAG__ Get the specified flag. - * This parameter can be one of the following values (no combination allowed) - * @arg DCMI_FLAG_HSYNC: HSYNC pin state (active line / synchronization between lines) - * @arg DCMI_FLAG_VSYNC: VSYNC pin state (active frame / synchronization between frames) - * @arg DCMI_FLAG_FNE: FIFO empty flag - * @arg DCMI_FLAG_FRAMERI: Frame capture complete flag mask - * @arg DCMI_FLAG_OVRRI: Overrun flag mask - * @arg DCMI_FLAG_ERRRI: Synchronization error flag mask - * @arg DCMI_FLAG_VSYNCRI: VSYNC flag mask - * @arg DCMI_FLAG_LINERI: Line flag mask - * @arg DCMI_FLAG_FRAMEMI: DCMI Capture complete masked interrupt status - * @arg DCMI_FLAG_OVRMI: DCMI Overrun masked interrupt status - * @arg DCMI_FLAG_ERRMI: DCMI Synchronization error masked interrupt status - * @arg DCMI_FLAG_VSYNCMI: DCMI VSYNC masked interrupt status - * @arg DCMI_FLAG_LINEMI: DCMI Line masked interrupt status - * @retval The state of FLAG. - */ -#define __HAL_DCMI_GET_FLAG(__HANDLE__, __FLAG__)\ -((((__FLAG__) & (DCMI_SR_INDEX|DCMI_MIS_INDEX)) == 0x0U)? ((__HANDLE__)->Instance->RISR & (__FLAG__)) :\ - (((__FLAG__) & DCMI_SR_INDEX) == 0x0U)? ((__HANDLE__)->Instance->MISR & (__FLAG__)) : ((__HANDLE__)->Instance->SR & (__FLAG__))) - -/** - * @brief Clear the DCMI pending flags. - * @param __HANDLE__ DCMI handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DCMI_FLAG_FRAMERI: Frame capture complete flag mask - * @arg DCMI_FLAG_OVRRI: Overrun flag mask - * @arg DCMI_FLAG_ERRRI: Synchronization error flag mask - * @arg DCMI_FLAG_VSYNCRI: VSYNC flag mask - * @arg DCMI_FLAG_LINERI: Line flag mask - * @retval None - */ -#define __HAL_DCMI_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__)) - -/** - * @brief Enable the specified DCMI interrupts. - * @param __HANDLE__ DCMI handle - * @param __INTERRUPT__ specifies the DCMI interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask - * @arg DCMI_IT_OVR: Overrun interrupt mask - * @arg DCMI_IT_ERR: Synchronization error interrupt mask - * @arg DCMI_IT_VSYNC: VSYNC interrupt mask - * @arg DCMI_IT_LINE: Line interrupt mask - * @retval None - */ -#define __HAL_DCMI_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__)) - -/** - * @brief Disable the specified DCMI interrupts. - * @param __HANDLE__ DCMI handle - * @param __INTERRUPT__ specifies the DCMI interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask - * @arg DCMI_IT_OVR: Overrun interrupt mask - * @arg DCMI_IT_ERR: Synchronization error interrupt mask - * @arg DCMI_IT_VSYNC: VSYNC interrupt mask - * @arg DCMI_IT_LINE: Line interrupt mask - * @retval None - */ -#define __HAL_DCMI_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified DCMI interrupt has occurred or not. - * @param __HANDLE__ DCMI handle - * @param __INTERRUPT__ specifies the DCMI interrupt source to check. - * This parameter can be one of the following values: - * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask - * @arg DCMI_IT_OVR: Overrun interrupt mask - * @arg DCMI_IT_ERR: Synchronization error interrupt mask - * @arg DCMI_IT_VSYNC: VSYNC interrupt mask - * @arg DCMI_IT_LINE: Line interrupt mask - * @retval The state of INTERRUPT. - */ -#define __HAL_DCMI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MISR & (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DCMI_Exported_Functions DCMI Exported Functions - * @{ - */ - -/** @addtogroup DCMI_Exported_Functions_Group1 Initialization and Configuration functions - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_DCMI_Init(DCMI_HandleTypeDef *hdcmi); -HAL_StatusTypeDef HAL_DCMI_DeInit(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_MspInit(DCMI_HandleTypeDef* hdcmi); -void HAL_DCMI_MspDeInit(DCMI_HandleTypeDef* hdcmi); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_DCMI_RegisterCallback(DCMI_HandleTypeDef *hdcmi, HAL_DCMI_CallbackIDTypeDef CallbackID, pDCMI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DCMI_UnRegisterCallback(DCMI_HandleTypeDef *hdcmi, HAL_DCMI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup DCMI_Exported_Functions_Group2 IO operation functions - * @{ - */ -/* IO operation functions *****************************************************/ -HAL_StatusTypeDef HAL_DCMI_Start_DMA(DCMI_HandleTypeDef* hdcmi, uint32_t DCMI_Mode, uint32_t pData, uint32_t Length); -HAL_StatusTypeDef HAL_DCMI_Stop(DCMI_HandleTypeDef* hdcmi); -HAL_StatusTypeDef HAL_DCMI_Suspend(DCMI_HandleTypeDef* hdcmi); -HAL_StatusTypeDef HAL_DCMI_Resume(DCMI_HandleTypeDef* hdcmi); -void HAL_DCMI_ErrorCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_LineEventCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_FrameEventCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_VsyncEventCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_VsyncCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_HsyncCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_IRQHandler(DCMI_HandleTypeDef *hdcmi); -/** - * @} - */ - -/** @addtogroup DCMI_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -/* Peripheral Control functions ***********************************************/ -HAL_StatusTypeDef HAL_DCMI_ConfigCrop(DCMI_HandleTypeDef *hdcmi, uint32_t X0, uint32_t Y0, uint32_t XSize, uint32_t YSize); -HAL_StatusTypeDef HAL_DCMI_EnableCrop(DCMI_HandleTypeDef *hdcmi); -HAL_StatusTypeDef HAL_DCMI_DisableCrop(DCMI_HandleTypeDef *hdcmi); -HAL_StatusTypeDef HAL_DCMI_ConfigSyncUnmask(DCMI_HandleTypeDef *hdcmi, DCMI_SyncUnmaskTypeDef *SyncUnmask); -/** - * @} - */ - -/** @addtogroup DCMI_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -/* Peripheral State functions *************************************************/ -HAL_DCMI_StateTypeDef HAL_DCMI_GetState(DCMI_HandleTypeDef *hdcmi); -uint32_t HAL_DCMI_GetError(DCMI_HandleTypeDef *hdcmi); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DCMI_Private_Constants DCMI Private Constants - * @{ - */ -#define DCMI_MIS_INDEX 0x1000U /*!< DCMI MIS register index */ -#define DCMI_SR_INDEX 0x2000U /*!< DCMI SR register index */ -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/** @defgroup DCMI_Private_Macros DCMI Private Macros - * @{ - */ -#define IS_DCMI_CAPTURE_MODE(MODE)(((MODE) == DCMI_MODE_CONTINUOUS) || \ - ((MODE) == DCMI_MODE_SNAPSHOT)) - -#define IS_DCMI_SYNCHRO(MODE)(((MODE) == DCMI_SYNCHRO_HARDWARE) || \ - ((MODE) == DCMI_SYNCHRO_EMBEDDED)) - -#define IS_DCMI_PCKPOLARITY(POLARITY)(((POLARITY) == DCMI_PCKPOLARITY_FALLING) || \ - ((POLARITY) == DCMI_PCKPOLARITY_RISING)) - -#define IS_DCMI_VSPOLARITY(POLARITY)(((POLARITY) == DCMI_VSPOLARITY_LOW) || \ - ((POLARITY) == DCMI_VSPOLARITY_HIGH)) - -#define IS_DCMI_HSPOLARITY(POLARITY)(((POLARITY) == DCMI_HSPOLARITY_LOW) || \ - ((POLARITY) == DCMI_HSPOLARITY_HIGH)) - -#define IS_DCMI_MODE_JPEG(JPEG_MODE)(((JPEG_MODE) == DCMI_JPEG_DISABLE) || \ - ((JPEG_MODE) == DCMI_JPEG_ENABLE)) - -#define IS_DCMI_CAPTURE_RATE(RATE) (((RATE) == DCMI_CR_ALL_FRAME) || \ - ((RATE) == DCMI_CR_ALTERNATE_2_FRAME) || \ - ((RATE) == DCMI_CR_ALTERNATE_4_FRAME)) - -#define IS_DCMI_EXTENDED_DATA(DATA)(((DATA) == DCMI_EXTEND_DATA_8B) || \ - ((DATA) == DCMI_EXTEND_DATA_10B) || \ - ((DATA) == DCMI_EXTEND_DATA_12B) || \ - ((DATA) == DCMI_EXTEND_DATA_14B)) - -#define IS_DCMI_WINDOW_COORDINATE(COORDINATE) ((COORDINATE) <= DCMI_WINDOW_COORDINATE) - -#define IS_DCMI_WINDOW_HEIGHT(HEIGHT) ((HEIGHT) <= DCMI_WINDOW_HEIGHT) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup DCMI_Private_Functions DCMI Private Functions - * @{ - */ - -/** - * @} - */ - -#endif /* STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ - STM32F479xx */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DCMI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi_ex.h deleted file mode 100644 index 9bc942dea819922..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi_ex.h +++ /dev/null @@ -1,212 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dcmi_ex.h - * @author MCD Application Team - * @brief Header file of DCMI Extension HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DCMI_EX_H -#define __STM32F4xx_HAL_DCMI_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DCMIEx - * @brief DCMI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DCMIEx_Exported_Types DCMI Extended Exported Types - * @{ - */ -/** - * @brief DCMIEx Embedded Synchronisation CODE Init structure definition - */ -typedef struct -{ - uint8_t FrameStartCode; /*!< Specifies the code of the frame start delimiter. */ - uint8_t LineStartCode; /*!< Specifies the code of the line start delimiter. */ - uint8_t LineEndCode; /*!< Specifies the code of the line end delimiter. */ - uint8_t FrameEndCode; /*!< Specifies the code of the frame end delimiter. */ -}DCMI_CodesInitTypeDef; - -/** - * @brief DCMI Init structure definition - */ -typedef struct -{ - uint32_t SynchroMode; /*!< Specifies the Synchronization Mode: Hardware or Embedded. - This parameter can be a value of @ref DCMI_Synchronization_Mode */ - - uint32_t PCKPolarity; /*!< Specifies the Pixel clock polarity: Falling or Rising. - This parameter can be a value of @ref DCMI_PIXCK_Polarity */ - - uint32_t VSPolarity; /*!< Specifies the Vertical synchronization polarity: High or Low. - This parameter can be a value of @ref DCMI_VSYNC_Polarity */ - - uint32_t HSPolarity; /*!< Specifies the Horizontal synchronization polarity: High or Low. - This parameter can be a value of @ref DCMI_HSYNC_Polarity */ - - uint32_t CaptureRate; /*!< Specifies the frequency of frame capture: All, 1/2 or 1/4. - This parameter can be a value of @ref DCMI_Capture_Rate */ - - uint32_t ExtendedDataMode; /*!< Specifies the data width: 8-bit, 10-bit, 12-bit or 14-bit. - This parameter can be a value of @ref DCMI_Extended_Data_Mode */ - - DCMI_CodesInitTypeDef SyncroCode; /*!< Specifies the code of the frame start delimiter. */ - - uint32_t JPEGMode; /*!< Enable or Disable the JPEG mode - This parameter can be a value of @ref DCMI_MODE_JPEG */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - uint32_t ByteSelectMode; /*!< Specifies the data to be captured by the interface - This parameter can be a value of @ref DCMIEx_Byte_Select_Mode */ - - uint32_t ByteSelectStart; /*!< Specifies if the data to be captured by the interface is even or odd - This parameter can be a value of @ref DCMIEx_Byte_Select_Start */ - - uint32_t LineSelectMode; /*!< Specifies the line of data to be captured by the interface - This parameter can be a value of @ref DCMIEx_Line_Select_Mode */ - - uint32_t LineSelectStart; /*!< Specifies if the line of data to be captured by the interface is even or odd - This parameter can be a value of @ref DCMIEx_Line_Select_Start */ - -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ -}DCMI_InitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup DCMIEx_Exported_Constants DCMI Exported Constants - * @{ - */ - -/** @defgroup DCMIEx_Byte_Select_Mode DCMI Byte Select Mode - * @{ - */ -#define DCMI_BSM_ALL 0x00000000U /*!< Interface captures all received data */ -#define DCMI_BSM_OTHER ((uint32_t)DCMI_CR_BSM_0) /*!< Interface captures every other byte from the received data */ -#define DCMI_BSM_ALTERNATE_4 ((uint32_t)DCMI_CR_BSM_1) /*!< Interface captures one byte out of four */ -#define DCMI_BSM_ALTERNATE_2 ((uint32_t)(DCMI_CR_BSM_0 | DCMI_CR_BSM_1)) /*!< Interface captures two bytes out of four */ - -/** - * @} - */ - -/** @defgroup DCMIEx_Byte_Select_Start DCMI Byte Select Start - * @{ - */ -#define DCMI_OEBS_ODD 0x00000000U /*!< Interface captures first data from the frame/line start, second one being dropped */ -#define DCMI_OEBS_EVEN ((uint32_t)DCMI_CR_OEBS) /*!< Interface captures second data from the frame/line start, first one being dropped */ - -/** - * @} - */ - -/** @defgroup DCMIEx_Line_Select_Mode DCMI Line Select Mode - * @{ - */ -#define DCMI_LSM_ALL 0x00000000U /*!< Interface captures all received lines */ -#define DCMI_LSM_ALTERNATE_2 ((uint32_t)DCMI_CR_LSM) /*!< Interface captures one line out of two */ - -/** - * @} - */ - -/** @defgroup DCMIEx_Line_Select_Start DCMI Line Select Start - * @{ - */ -#define DCMI_OELS_ODD 0x00000000U /*!< Interface captures first line from the frame start, second one being dropped */ -#define DCMI_OELS_EVEN ((uint32_t)DCMI_CR_OELS) /*!< Interface captures second line from the frame start, first one being dropped */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -#define DCMI_POSITION_ESCR_LSC (uint32_t)DCMI_ESCR_LSC_Pos /*!< Required left shift to set line start delimiter */ -#define DCMI_POSITION_ESCR_LEC (uint32_t)DCMI_ESCR_LEC_Pos /*!< Required left shift to set line end delimiter */ -#define DCMI_POSITION_ESCR_FEC (uint32_t)DCMI_ESCR_FEC_Pos /*!< Required left shift to set frame end delimiter */ - -/* Private macro -------------------------------------------------------------*/ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup DCMIEx_Private_Macros DCMI Extended Private Macros - * @{ - */ -#define IS_DCMI_BYTE_SELECT_MODE(MODE)(((MODE) == DCMI_BSM_ALL) || \ - ((MODE) == DCMI_BSM_OTHER) || \ - ((MODE) == DCMI_BSM_ALTERNATE_4) || \ - ((MODE) == DCMI_BSM_ALTERNATE_2)) - -#define IS_DCMI_BYTE_SELECT_START(POLARITY)(((POLARITY) == DCMI_OEBS_ODD) || \ - ((POLARITY) == DCMI_OEBS_EVEN)) - -#define IS_DCMI_LINE_SELECT_MODE(MODE)(((MODE) == DCMI_LSM_ALL) || \ - ((MODE) == DCMI_LSM_ALTERNATE_2)) - -#define IS_DCMI_LINE_SELECT_START(POLARITY)(((POLARITY) == DCMI_OELS_ODD) || \ - ((POLARITY) == DCMI_OELS_EVEN)) -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -#endif /* STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ - STM32F479xx */ - - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DCMI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h deleted file mode 100644 index 975f70bd4b2ddcf..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h +++ /dev/null @@ -1,211 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_def.h - * @author MCD Application Team - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DEF -#define __STM32F4xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.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 UNUSED(X) (void)X /* To avoid gcc/g++ warnings */ - -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) == (BIT)) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ - (__DMA_HANDLE__).Parent = (__HANDLE__); \ - } while(0U) - -/** @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 == 1U) - /* 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 (0U) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0U) -#endif /* USE_RTOS */ - -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif - #ifndef __packed - #define __packed __attribute__((packed)) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #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 (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* 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 V5*/ -#define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - - -/** - * @brief __RAM_FUNC definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) -/* ARM Compiler V4/V5 and V6 - -------------------------- - RAM functions are defined using the toolchain options. - Functions that are executed in RAM should reside in a separate source module. - Using the 'Options for File' dialog you can simply change the 'Code / Const' - area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the 'Options for Target' - dialog. -*/ -#define __RAM_FUNC - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- - RAM functions are defined using a specific toolchain keyword "__ramfunc". -*/ -#define __RAM_FUNC __ramfunc - -#elif defined ( __GNUC__ ) -/* GNU Compiler - ------------ - RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". -*/ -#define __RAM_FUNC __attribute__((section(".RamFunc"))) - -#endif - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ ) -/* ARM V4/V5 and V6 & GNU Compiler - ------------------------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* ___STM32F4xx_HAL_DEF */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dfsdm.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dfsdm.h deleted file mode 100644 index 09c6551e60384ea..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dfsdm.h +++ /dev/null @@ -1,1144 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dfsdm.h - * @author MCD Application Team - * @brief Header file of DFSDM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DFSDM_H -#define __STM32F4xx_HAL_DFSDM_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DFSDM - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DFSDM_Exported_Types DFSDM Exported Types - * @{ - */ - -/** - * @brief HAL DFSDM Channel states definition - */ -typedef enum -{ - HAL_DFSDM_CHANNEL_STATE_RESET = 0x00U, /*!< DFSDM channel not initialized */ - HAL_DFSDM_CHANNEL_STATE_READY = 0x01U, /*!< DFSDM channel initialized and ready for use */ - HAL_DFSDM_CHANNEL_STATE_ERROR = 0xFFU /*!< DFSDM channel state error */ -}HAL_DFSDM_Channel_StateTypeDef; - -/** - * @brief DFSDM channel output clock structure definition - */ -typedef struct -{ - FunctionalState Activation; /*!< Output clock enable/disable */ - uint32_t Selection; /*!< Output clock is system clock or audio clock. - This parameter can be a value of @ref DFSDM_Channel_OuputClock */ - uint32_t Divider; /*!< Output clock divider. - This parameter must be a number between Min_Data = 2 and Max_Data = 256 */ -}DFSDM_Channel_OutputClockTypeDef; - -/** - * @brief DFSDM channel input structure definition - */ -typedef struct -{ - uint32_t Multiplexer; /*!< Input is external serial inputs or internal register. - This parameter can be a value of @ref DFSDM_Channel_InputMultiplexer */ - uint32_t DataPacking; /*!< Standard, interleaved or dual mode for internal register. - This parameter can be a value of @ref DFSDM_Channel_DataPacking */ - uint32_t Pins; /*!< Input pins are taken from same or following channel. - This parameter can be a value of @ref DFSDM_Channel_InputPins */ -}DFSDM_Channel_InputTypeDef; - -/** - * @brief DFSDM channel serial interface structure definition - */ -typedef struct -{ - uint32_t Type; /*!< SPI or Manchester modes. - This parameter can be a value of @ref DFSDM_Channel_SerialInterfaceType */ - uint32_t SpiClock; /*!< SPI clock select (external or internal with different sampling point). - This parameter can be a value of @ref DFSDM_Channel_SpiClock */ -}DFSDM_Channel_SerialInterfaceTypeDef; - -/** - * @brief DFSDM channel analog watchdog structure definition - */ -typedef struct -{ - uint32_t FilterOrder; /*!< Analog watchdog Sinc filter order. - This parameter can be a value of @ref DFSDM_Channel_AwdFilterOrder */ - uint32_t Oversampling; /*!< Analog watchdog filter oversampling ratio. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 */ -}DFSDM_Channel_AwdTypeDef; - -/** - * @brief DFSDM channel init structure definition - */ -typedef struct -{ - DFSDM_Channel_OutputClockTypeDef OutputClock; /*!< DFSDM channel output clock parameters */ - DFSDM_Channel_InputTypeDef Input; /*!< DFSDM channel input parameters */ - DFSDM_Channel_SerialInterfaceTypeDef SerialInterface; /*!< DFSDM channel serial interface parameters */ - DFSDM_Channel_AwdTypeDef Awd; /*!< DFSDM channel analog watchdog parameters */ - int32_t Offset; /*!< DFSDM channel offset. - This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */ - uint32_t RightBitShift; /*!< DFSDM channel right bit shift. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */ -}DFSDM_Channel_InitTypeDef; - -/** - * @brief DFSDM channel handle structure definition - */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -typedef struct __DFSDM_Channel_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */ -{ - DFSDM_Channel_TypeDef *Instance; /*!< DFSDM channel instance */ - DFSDM_Channel_InitTypeDef Init; /*!< DFSDM channel init parameters */ - HAL_DFSDM_Channel_StateTypeDef State; /*!< DFSDM channel state */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - void (*CkabCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel clock absence detection callback */ - void (*ScdCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel short circuit detection callback */ - void (*MspInitCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel MSP init callback */ - void (*MspDeInitCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel MSP de-init callback */ -#endif -}DFSDM_Channel_HandleTypeDef; - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/** - * @brief DFSDM channel callback ID enumeration definition - */ -typedef enum -{ - HAL_DFSDM_CHANNEL_CKAB_CB_ID = 0x00U, /*!< DFSDM channel clock absence detection callback ID */ - HAL_DFSDM_CHANNEL_SCD_CB_ID = 0x01U, /*!< DFSDM channel short circuit detection callback ID */ - HAL_DFSDM_CHANNEL_MSPINIT_CB_ID = 0x02U, /*!< DFSDM channel MSP init callback ID */ - HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID = 0x03U /*!< DFSDM channel MSP de-init callback ID */ -}HAL_DFSDM_Channel_CallbackIDTypeDef; - -/** - * @brief DFSDM channel callback pointer definition - */ -typedef void (*pDFSDM_Channel_CallbackTypeDef)(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -#endif -/** - * @brief HAL DFSDM Filter states definition - */ -typedef enum -{ - HAL_DFSDM_FILTER_STATE_RESET = 0x00U, /*!< DFSDM filter not initialized */ - HAL_DFSDM_FILTER_STATE_READY = 0x01U, /*!< DFSDM filter initialized and ready for use */ - HAL_DFSDM_FILTER_STATE_REG = 0x02U, /*!< DFSDM filter regular conversion in progress */ - HAL_DFSDM_FILTER_STATE_INJ = 0x03U, /*!< DFSDM filter injected conversion in progress */ - HAL_DFSDM_FILTER_STATE_REG_INJ = 0x04U, /*!< DFSDM filter regular and injected conversions in progress */ - HAL_DFSDM_FILTER_STATE_ERROR = 0xFFU /*!< DFSDM filter state error */ -}HAL_DFSDM_Filter_StateTypeDef; - -/** - * @brief DFSDM filter regular conversion parameters structure definition - */ -typedef struct -{ - uint32_t Trigger; /*!< Trigger used to start regular conversion: software or synchronous. - This parameter can be a value of @ref DFSDM_Filter_Trigger */ - FunctionalState FastMode; /*!< Enable/disable fast mode for regular conversion */ - FunctionalState DmaMode; /*!< Enable/disable DMA for regular conversion */ -}DFSDM_Filter_RegularParamTypeDef; - -/** - * @brief DFSDM filter injected conversion parameters structure definition - */ -typedef struct -{ - uint32_t Trigger; /*!< Trigger used to start injected conversion: software, external or synchronous. - This parameter can be a value of @ref DFSDM_Filter_Trigger */ - FunctionalState ScanMode; /*!< Enable/disable scanning mode for injected conversion */ - FunctionalState DmaMode; /*!< Enable/disable DMA for injected conversion */ - uint32_t ExtTrigger; /*!< External trigger. - This parameter can be a value of @ref DFSDM_Filter_ExtTrigger */ - uint32_t ExtTriggerEdge; /*!< External trigger edge: rising, falling or both. - This parameter can be a value of @ref DFSDM_Filter_ExtTriggerEdge */ -}DFSDM_Filter_InjectedParamTypeDef; - -/** - * @brief DFSDM filter parameters structure definition - */ -typedef struct -{ - uint32_t SincOrder; /*!< Sinc filter order. - This parameter can be a value of @ref DFSDM_Filter_SincOrder */ - uint32_t Oversampling; /*!< Filter oversampling ratio. - This parameter must be a number between Min_Data = 1 and Max_Data = 1024 */ - uint32_t IntOversampling; /*!< Integrator oversampling ratio. - This parameter must be a number between Min_Data = 1 and Max_Data = 256 */ -}DFSDM_Filter_FilterParamTypeDef; - -/** - * @brief DFSDM filter init structure definition - */ -typedef struct -{ - DFSDM_Filter_RegularParamTypeDef RegularParam; /*!< DFSDM regular conversion parameters */ - DFSDM_Filter_InjectedParamTypeDef InjectedParam; /*!< DFSDM injected conversion parameters */ - DFSDM_Filter_FilterParamTypeDef FilterParam; /*!< DFSDM filter parameters */ -}DFSDM_Filter_InitTypeDef; - -/** - * @brief DFSDM filter handle structure definition - */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -typedef struct __DFSDM_Filter_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */ -{ - DFSDM_Filter_TypeDef *Instance; /*!< DFSDM filter instance */ - DFSDM_Filter_InitTypeDef Init; /*!< DFSDM filter init parameters */ - DMA_HandleTypeDef *hdmaReg; /*!< Pointer on DMA handler for regular conversions */ - DMA_HandleTypeDef *hdmaInj; /*!< Pointer on DMA handler for injected conversions */ - uint32_t RegularContMode; /*!< Regular conversion continuous mode */ - uint32_t RegularTrigger; /*!< Trigger used for regular conversion */ - uint32_t InjectedTrigger; /*!< Trigger used for injected conversion */ - uint32_t ExtTriggerEdge; /*!< Rising, falling or both edges selected */ - FunctionalState InjectedScanMode; /*!< Injected scanning mode */ - uint32_t InjectedChannelsNbr; /*!< Number of channels in injected sequence */ - uint32_t InjConvRemaining; /*!< Injected conversions remaining */ - HAL_DFSDM_Filter_StateTypeDef State; /*!< DFSDM filter state */ - uint32_t ErrorCode; /*!< DFSDM filter error code */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - void (*AwdCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel, uint32_t Threshold); /*!< DFSDM filter analog watchdog callback */ - void (*RegConvCpltCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter regular conversion complete callback */ - void (*RegConvHalfCpltCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter half regular conversion complete callback */ - void (*InjConvCpltCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter injected conversion complete callback */ - void (*InjConvHalfCpltCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter half injected conversion complete callback */ - void (*ErrorCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter error callback */ - void (*MspInitCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter MSP init callback */ - void (*MspDeInitCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter MSP de-init callback */ -#endif -}DFSDM_Filter_HandleTypeDef; - -/** - * @brief DFSDM filter analog watchdog parameters structure definition - */ -typedef struct -{ - uint32_t DataSource; /*!< Values from digital filter or from channel watchdog filter. - This parameter can be a value of @ref DFSDM_Filter_AwdDataSource */ - uint32_t Channel; /*!< Analog watchdog channel selection. - This parameter can be a values combination of @ref DFSDM_Channel_Selection */ - int32_t HighThreshold; /*!< High threshold for the analog watchdog. - This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */ - int32_t LowThreshold; /*!< Low threshold for the analog watchdog. - This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */ - uint32_t HighBreakSignal; /*!< Break signal assigned to analog watchdog high threshold event. - This parameter can be a values combination of @ref DFSDM_BreakSignals */ - uint32_t LowBreakSignal; /*!< Break signal assigned to analog watchdog low threshold event. - This parameter can be a values combination of @ref DFSDM_BreakSignals */ -}DFSDM_Filter_AwdParamTypeDef; - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/** - * @brief DFSDM filter callback ID enumeration definition - */ -typedef enum -{ - HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID = 0x00U, /*!< DFSDM filter regular conversion complete callback ID */ - HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID = 0x01U, /*!< DFSDM filter half regular conversion complete callback ID */ - HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID = 0x02U, /*!< DFSDM filter injected conversion complete callback ID */ - HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID = 0x03U, /*!< DFSDM filter half injected conversion complete callback ID */ - HAL_DFSDM_FILTER_ERROR_CB_ID = 0x04U, /*!< DFSDM filter error callback ID */ - HAL_DFSDM_FILTER_MSPINIT_CB_ID = 0x05U, /*!< DFSDM filter MSP init callback ID */ - HAL_DFSDM_FILTER_MSPDEINIT_CB_ID = 0x06U /*!< DFSDM filter MSP de-init callback ID */ -}HAL_DFSDM_Filter_CallbackIDTypeDef; - -/** - * @brief DFSDM filter callback pointer definition - */ -typedef void (*pDFSDM_Filter_CallbackTypeDef)(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -typedef void (*pDFSDM_Filter_AwdCallbackTypeDef)(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel, uint32_t Threshold); -#endif - -/** - * @} - */ -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** - * @brief Synchronization parameters structure definition for STM32F413xx/STM32F423xx devices - */ -typedef struct -{ - uint32_t DFSDM1ClockIn; /*!< Source selection for DFSDM1_Ckin. - This parameter can be a value of @ref DFSDM_1_CLOCKIN_SELECTION*/ - uint32_t DFSDM2ClockIn; /*!< Source selection for DFSDM2_Ckin. - This parameter can be a value of @ref DFSDM_2_CLOCKIN_SELECTION*/ - uint32_t DFSDM1ClockOut; /*!< Source selection for DFSDM1_Ckout. - This parameter can be a value of @ref DFSDM_1_CLOCKOUT_SELECTION*/ - uint32_t DFSDM2ClockOut; /*!< Source selection for DFSDM2_Ckout. - This parameter can be a value of @ref DFSDM_2_CLOCKOUT_SELECTION*/ - uint32_t DFSDM1BitClkDistribution; /*!< Distribution of the DFSDM1 bitstream clock gated by TIM4 OC1 or TIM4 OC2. - This parameter can be a value of @ref DFSDM_1_BIT_STREAM_DISTRIBUTION - @note The DFSDM2 audio gated by TIM4 OC2 can be injected on CKIN0 or CKIN2 - @note The DFSDM2 audio gated by TIM4 OC1 can be injected on CKIN1 or CKIN3 */ - uint32_t DFSDM2BitClkDistribution; /*!< Distribution of the DFSDM2 bitstream clock gated by TIM3 OC1 or TIM3 OC2 or TIM3 OC3 or TIM3 OC4. - This parameter can be a value of @ref DFSDM_2_BIT_STREAM_DISTRIBUTION - @note The DFSDM2 audio gated by TIM3 OC4 can be injected on CKIN0 or CKIN4 - @note The DFSDM2 audio gated by TIM3 OC3 can be injected on CKIN1 or CKIN5 - @note The DFSDM2 audio gated by TIM3 OC2 can be injected on CKIN2 or CKIN6 - @note The DFSDM2 audio gated by TIM3 OC1 can be injected on CKIN3 or CKIN7 */ - uint32_t DFSDM1DataDistribution; /*!< Source selection for DatIn0 and DatIn2 of DFSDM1. - This parameter can be a value of @ref DFSDM_1_DATA_DISTRIBUTION */ - uint32_t DFSDM2DataDistribution; /*!< Source selection for DatIn0, DatIn2, DatIn4 and DatIn6 of DFSDM2. - This parameter can be a value of @ref DFSDM_2_DATA_DISTRIBUTION */ -}DFSDM_MultiChannelConfigTypeDef; -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ -/** - * @} - */ - -/* End of exported types -----------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DFSDM_Exported_Constants DFSDM Exported Constants - * @{ - */ - -/** @defgroup DFSDM_Channel_OuputClock DFSDM channel output clock selection - * @{ - */ -#define DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM 0x00000000U /*!< Source for ouput clock is system clock */ -#define DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO DFSDM_CHCFGR1_CKOUTSRC /*!< Source for ouput clock is audio clock */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_InputMultiplexer DFSDM channel input multiplexer - * @{ - */ -#define DFSDM_CHANNEL_EXTERNAL_INPUTS 0x00000000U /*!< Data are taken from external inputs */ -#define DFSDM_CHANNEL_INTERNAL_REGISTER DFSDM_CHCFGR1_DATMPX_1 /*!< Data are taken from internal register */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_DataPacking DFSDM channel input data packing - * @{ - */ -#define DFSDM_CHANNEL_STANDARD_MODE 0x00000000U /*!< Standard data packing mode */ -#define DFSDM_CHANNEL_INTERLEAVED_MODE DFSDM_CHCFGR1_DATPACK_0 /*!< Interleaved data packing mode */ -#define DFSDM_CHANNEL_DUAL_MODE DFSDM_CHCFGR1_DATPACK_1 /*!< Dual data packing mode */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_InputPins DFSDM channel input pins - * @{ - */ -#define DFSDM_CHANNEL_SAME_CHANNEL_PINS 0x00000000U /*!< Input from pins on same channel */ -#define DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS DFSDM_CHCFGR1_CHINSEL /*!< Input from pins on following channel */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_SerialInterfaceType DFSDM channel serial interface type - * @{ - */ -#define DFSDM_CHANNEL_SPI_RISING 0x00000000U /*!< SPI with rising edge */ -#define DFSDM_CHANNEL_SPI_FALLING DFSDM_CHCFGR1_SITP_0 /*!< SPI with falling edge */ -#define DFSDM_CHANNEL_MANCHESTER_RISING DFSDM_CHCFGR1_SITP_1 /*!< Manchester with rising edge */ -#define DFSDM_CHANNEL_MANCHESTER_FALLING DFSDM_CHCFGR1_SITP /*!< Manchester with falling edge */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_SpiClock DFSDM channel SPI clock selection - * @{ - */ -#define DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL 0x00000000U /*!< External SPI clock */ -#define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL DFSDM_CHCFGR1_SPICKSEL_0 /*!< Internal SPI clock */ -#define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING DFSDM_CHCFGR1_SPICKSEL_1 /*!< Internal SPI clock divided by 2, falling edge */ -#define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING DFSDM_CHCFGR1_SPICKSEL /*!< Internal SPI clock divided by 2, rising edge */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_AwdFilterOrder DFSDM channel analog watchdog filter order - * @{ - */ -#define DFSDM_CHANNEL_FASTSINC_ORDER 0x00000000U /*!< FastSinc filter type */ -#define DFSDM_CHANNEL_SINC1_ORDER DFSDM_CHAWSCDR_AWFORD_0 /*!< Sinc 1 filter type */ -#define DFSDM_CHANNEL_SINC2_ORDER DFSDM_CHAWSCDR_AWFORD_1 /*!< Sinc 2 filter type */ -#define DFSDM_CHANNEL_SINC3_ORDER DFSDM_CHAWSCDR_AWFORD /*!< Sinc 3 filter type */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_Trigger DFSDM filter conversion trigger - * @{ - */ -#define DFSDM_FILTER_SW_TRIGGER 0x00000000U /*!< Software trigger */ -#define DFSDM_FILTER_SYNC_TRIGGER 0x00000001U /*!< Synchronous with DFSDM_FLT0 */ -#define DFSDM_FILTER_EXT_TRIGGER 0x00000002U /*!< External trigger (only for injected conversion) */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_ExtTrigger DFSDM filter external trigger - * @{ - */ -#if defined(STM32F413xx) || defined(STM32F423xx) -/* Trigger for stm32f413xx and STM32f423xx devices */ -#define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO 0x00000000U /*!< For All DFSDM1/2 filters */ -#define DFSDM_FILTER_EXT_TRIG_TIM3_TRGO DFSDM_FLTCR1_JEXTSEL_0 /*!< For All DFSDM1/2 filters */ -#define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO DFSDM_FLTCR1_JEXTSEL_1 /*!< For All DFSDM1/2 filters */ -#define DFSDM_FILTER_EXT_TRIG_TIM10_OC1 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0, 1 and 2 */ -#define DFSDM_FILTER_EXT_TRIG_TIM2_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM2 filter 3 */ -#define DFSDM_FILTER_EXT_TRIG_TIM4_TRGO DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0, 1 and 2 */ -#define DFSDM_FILTER_EXT_TRIG_TIM11_OC1 DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM2 filter 3 */ -#define DFSDM_FILTER_EXT_TRIG_TIM6_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0 and 1 */ -#define DFSDM_FILTER_EXT_TRIG_TIM7_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM2 filter 2 and 3*/ -#define DFSDM_FILTER_EXT_TRIG_EXTI11 (DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For All DFSDM1/2 filters */ -#define DFSDM_FILTER_EXT_TRIG_EXTI15 DFSDM_FLTCR1_JEXTSEL /*!< For All DFSDM1/2 filters */ -#else -/* Trigger for stm32f412xx devices */ -#define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO 0x00000000U /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM3_TRGO DFSDM_FLTCR1_JEXTSEL_0 /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO DFSDM_FLTCR1_JEXTSEL_1 /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM10_OC1 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM4_TRGO DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM6_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_EXTI11 (DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_EXTI15 DFSDM_FLTCR1_JEXTSEL /*!< For DFSDM1 filter 0 and 1*/ -#endif -/** - * @} - */ - -/** @defgroup DFSDM_Filter_ExtTriggerEdge DFSDM filter external trigger edge - * @{ - */ -#define DFSDM_FILTER_EXT_TRIG_RISING_EDGE DFSDM_FLTCR1_JEXTEN_0 /*!< External rising edge */ -#define DFSDM_FILTER_EXT_TRIG_FALLING_EDGE DFSDM_FLTCR1_JEXTEN_1 /*!< External falling edge */ -#define DFSDM_FILTER_EXT_TRIG_BOTH_EDGES DFSDM_FLTCR1_JEXTEN /*!< External rising and falling edges */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_SincOrder DFSDM filter sinc order - * @{ - */ -#define DFSDM_FILTER_FASTSINC_ORDER 0x00000000U /*!< FastSinc filter type */ -#define DFSDM_FILTER_SINC1_ORDER DFSDM_FLTFCR_FORD_0 /*!< Sinc 1 filter type */ -#define DFSDM_FILTER_SINC2_ORDER DFSDM_FLTFCR_FORD_1 /*!< Sinc 2 filter type */ -#define DFSDM_FILTER_SINC3_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_1) /*!< Sinc 3 filter type */ -#define DFSDM_FILTER_SINC4_ORDER DFSDM_FLTFCR_FORD_2 /*!< Sinc 4 filter type */ -#define DFSDM_FILTER_SINC5_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_2) /*!< Sinc 5 filter type */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_AwdDataSource DFSDM filter analog watchdog data source - * @{ - */ -#define DFSDM_FILTER_AWD_FILTER_DATA 0x00000000U /*!< From digital filter */ -#define DFSDM_FILTER_AWD_CHANNEL_DATA DFSDM_FLTCR1_AWFSEL /*!< From analog watchdog channel */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_ErrorCode DFSDM filter error code - * @{ - */ -#define DFSDM_FILTER_ERROR_NONE 0x00000000U /*!< No error */ -#define DFSDM_FILTER_ERROR_REGULAR_OVERRUN 0x00000001U /*!< Overrun occurs during regular conversion */ -#define DFSDM_FILTER_ERROR_INJECTED_OVERRUN 0x00000002U /*!< Overrun occurs during injected conversion */ -#define DFSDM_FILTER_ERROR_DMA 0x00000003U /*!< DMA error occurs */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -#define DFSDM_FILTER_ERROR_INVALID_CALLBACK 0x00000004U /*!< Invalid callback error occurs */ -#endif -/** - * @} - */ - -/** @defgroup DFSDM_BreakSignals DFSDM break signals - * @{ - */ -#define DFSDM_NO_BREAK_SIGNAL 0x00000000U /*!< No break signal */ -#define DFSDM_BREAK_SIGNAL_0 0x00000001U /*!< Break signal 0 */ -#define DFSDM_BREAK_SIGNAL_1 0x00000002U /*!< Break signal 1 */ -#define DFSDM_BREAK_SIGNAL_2 0x00000004U /*!< Break signal 2 */ -#define DFSDM_BREAK_SIGNAL_3 0x00000008U /*!< Break signal 3 */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_Selection DFSDM Channel Selection - * @{ - */ -/* DFSDM Channels ------------------------------------------------------------*/ -/* The DFSDM channels are defined as follows: - - in 16-bit LSB the channel mask is set - - in 16-bit MSB the channel number is set - e.g. for channel 3 definition: - - the channel mask is 0x00000008 (bit 3 is set) - - the channel number 3 is 0x00030000 - --> Consequently, channel 3 definition is 0x00000008 | 0x00030000 = 0x00030008 */ -#define DFSDM_CHANNEL_0 0x00000001U -#define DFSDM_CHANNEL_1 0x00010002U -#define DFSDM_CHANNEL_2 0x00020004U -#define DFSDM_CHANNEL_3 0x00030008U -#define DFSDM_CHANNEL_4 0x00040010U /* only for stmm32f413xx and stm32f423xx devices */ -#define DFSDM_CHANNEL_5 0x00050020U /* only for stmm32f413xx and stm32f423xx devices */ -#define DFSDM_CHANNEL_6 0x00060040U /* only for stmm32f413xx and stm32f423xx devices */ -#define DFSDM_CHANNEL_7 0x00070080U /* only for stmm32f413xx and stm32f423xx devices */ -/** - * @} - */ - -/** @defgroup DFSDM_ContinuousMode DFSDM Continuous Mode - * @{ - */ -#define DFSDM_CONTINUOUS_CONV_OFF 0x00000000U /*!< Conversion are not continuous */ -#define DFSDM_CONTINUOUS_CONV_ON 0x00000001U /*!< Conversion are continuous */ -/** - * @} - */ - -/** @defgroup DFSDM_AwdThreshold DFSDM analog watchdog threshold - * @{ - */ -#define DFSDM_AWD_HIGH_THRESHOLD 0x00000000U /*!< Analog watchdog high threshold */ -#define DFSDM_AWD_LOW_THRESHOLD 0x00000001U /*!< Analog watchdog low threshold */ -/** - * @} - */ - -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** @defgroup DFSDM_1_CLOCKOUT_SELECTION DFSDM1 ClockOut Selection - * @{ - */ -#define DFSDM1_CKOUT_DFSDM2_CKOUT 0x00000080U -#define DFSDM1_CKOUT_DFSDM1 0x00000000U -/** - * @} - */ - -/** @defgroup DFSDM_2_CLOCKOUT_SELECTION DFSDM2 ClockOut Selection - * @{ - */ -#define DFSDM2_CKOUT_DFSDM2_CKOUT 0x00040000U -#define DFSDM2_CKOUT_DFSDM2 0x00000000U -/** - * @} - */ - -/** @defgroup DFSDM_1_CLOCKIN_SELECTION DFSDM1 ClockIn Selection - * @{ - */ -#define DFSDM1_CKIN_DFSDM2_CKOUT 0x00000040U -#define DFSDM1_CKIN_PAD 0x00000000U -/** - * @} - */ - -/** @defgroup DFSDM_2_CLOCKIN_SELECTION DFSDM2 ClockIn Selection - * @{ - */ -#define DFSDM2_CKIN_DFSDM2_CKOUT 0x00020000U -#define DFSDM2_CKIN_PAD 0x00000000U -/** - * @} - */ - -/** @defgroup DFSDM_1_BIT_STREAM_DISTRIBUTION DFSDM1 Bit Stream Distribution - * @{ - */ -#define DFSDM1_T4_OC2_BITSTREAM_CKIN0 0x00000000U /* TIM4_OC2 to CLKIN0 */ -#define DFSDM1_T4_OC2_BITSTREAM_CKIN2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL /* TIM4_OC2 to CLKIN2 */ -#define DFSDM1_T4_OC1_BITSTREAM_CKIN3 SYSCFG_MCHDLYCR_DFSDM1CK13SEL /* TIM4_OC1 to CLKIN3 */ -#define DFSDM1_T4_OC1_BITSTREAM_CKIN1 0x00000000U /* TIM4_OC1 to CLKIN1 */ -/** - * @} - */ - -/** @defgroup DFSDM_2_BIT_STREAM_DISTRIBUTION DFSDM12 Bit Stream Distribution - * @{ - */ -#define DFSDM2_T3_OC4_BITSTREAM_CKIN0 0x00000000U /* TIM3_OC4 to CKIN0 */ -#define DFSDM2_T3_OC4_BITSTREAM_CKIN4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL /* TIM3_OC4 to CKIN4 */ -#define DFSDM2_T3_OC3_BITSTREAM_CKIN5 SYSCFG_MCHDLYCR_DFSDM2CK15SEL /* TIM3_OC3 to CKIN5 */ -#define DFSDM2_T3_OC3_BITSTREAM_CKIN1 0x00000000U /* TIM3_OC3 to CKIN1 */ -#define DFSDM2_T3_OC2_BITSTREAM_CKIN6 SYSCFG_MCHDLYCR_DFSDM2CK26SEL /* TIM3_OC2to CKIN6 */ -#define DFSDM2_T3_OC2_BITSTREAM_CKIN2 0x00000000U /* TIM3_OC2 to CKIN2 */ -#define DFSDM2_T3_OC1_BITSTREAM_CKIN3 0x00000000U /* TIM3_OC1 to CKIN3 */ -#define DFSDM2_T3_OC1_BITSTREAM_CKIN7 SYSCFG_MCHDLYCR_DFSDM2CK37SEL /* TIM3_OC1 to CKIN7 */ -/** - * @} - */ - -/** @defgroup DFSDM_1_DATA_DISTRIBUTION DFSDM1 Data Distribution - * @{ - */ -#define DFSDM1_DATIN0_TO_DATIN0_PAD 0x00000000U -#define DFSDM1_DATIN0_TO_DATIN1_PAD SYSCFG_MCHDLYCR_DFSDM1D0SEL -#define DFSDM1_DATIN2_TO_DATIN2_PAD 0x00000000U -#define DFSDM1_DATIN2_TO_DATIN3_PAD SYSCFG_MCHDLYCR_DFSDM1D2SEL -/** - * @} - */ - -/** @defgroup DFSDM_2_DATA_DISTRIBUTION DFSDM2 Data Distribution - * @{ - */ -#define DFSDM2_DATIN0_TO_DATIN0_PAD 0x00000000U -#define DFSDM2_DATIN0_TO_DATIN1_PAD SYSCFG_MCHDLYCR_DFSDM2D0SEL -#define DFSDM2_DATIN2_TO_DATIN2_PAD 0x00000000U -#define DFSDM2_DATIN2_TO_DATIN3_PAD SYSCFG_MCHDLYCR_DFSDM2D2SEL -#define DFSDM2_DATIN4_TO_DATIN4_PAD 0x00000000U -#define DFSDM2_DATIN4_TO_DATIN5_PAD SYSCFG_MCHDLYCR_DFSDM2D4SEL -#define DFSDM2_DATIN6_TO_DATIN6_PAD 0x00000000U -#define DFSDM2_DATIN6_TO_DATIN7_PAD SYSCFG_MCHDLYCR_DFSDM2D6SEL -/** - * @} - */ - -/** @defgroup HAL_MCHDLY_CLOCK HAL MCHDLY Clock enable - * @{ - */ -#define HAL_MCHDLY_CLOCK_DFSDM2 SYSCFG_MCHDLYCR_MCHDLY2EN -#define HAL_MCHDLY_CLOCK_DFSDM1 SYSCFG_MCHDLYCR_MCHDLY1EN -/** - * @} - */ - -/** @defgroup DFSDM_CLOCKIN_SOURCE DFSDM Clock In Source Selection - * @{ - */ -#define HAL_DFSDM2_CKIN_PAD 0x00040000U -#define HAL_DFSDM2_CKIN_DM SYSCFG_MCHDLYCR_DFSDM2CFG -#define HAL_DFSDM1_CKIN_PAD 0x00000000U -#define HAL_DFSDM1_CKIN_DM SYSCFG_MCHDLYCR_DFSDM1CFG -/** - * @} - */ - -/** @defgroup DFSDM_CLOCKOUT_SOURCE DFSDM Clock Source Selection - * @{ - */ -#define HAL_DFSDM2_CKOUT_DFSDM2 0x10000000U -#define HAL_DFSDM2_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM2CKOSEL -#define HAL_DFSDM1_CKOUT_DFSDM1 0x00000000U -#define HAL_DFSDM1_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM1CKOSEL -/** - * @} - */ - -/** @defgroup DFSDM_DATAIN0_SOURCE DFSDM Source Selection For DATAIN0 - * @{ - */ -#define HAL_DATAIN0_DFSDM2_PAD 0x10000000U -#define HAL_DATAIN0_DFSDM2_DATAIN1 SYSCFG_MCHDLYCR_DFSDM2D0SEL -#define HAL_DATAIN0_DFSDM1_PAD 0x00000000U -#define HAL_DATAIN0_DFSDM1_DATAIN1 SYSCFG_MCHDLYCR_DFSDM1D0SEL -/** - * @} - */ - -/** @defgroup DFSDM_DATAIN2_SOURCE DFSDM Source Selection For DATAIN2 - * @{ - */ -#define HAL_DATAIN2_DFSDM2_PAD 0x10000000U -#define HAL_DATAIN2_DFSDM2_DATAIN3 SYSCFG_MCHDLYCR_DFSDM2D2SEL -#define HAL_DATAIN2_DFSDM1_PAD 0x00000000U -#define HAL_DATAIN2_DFSDM1_DATAIN3 SYSCFG_MCHDLYCR_DFSDM1D2SEL -/** - * @} - */ - -/** @defgroup DFSDM_DATAIN4_SOURCE DFSDM Source Selection For DATAIN4 - * @{ - */ -#define HAL_DATAIN4_DFSDM2_PAD 0x00000000U -#define HAL_DATAIN4_DFSDM2_DATAIN5 SYSCFG_MCHDLYCR_DFSDM2D4SEL -/** - * @} - */ - -/** @defgroup DFSDM_DATAIN6_SOURCE DFSDM Source Selection For DATAIN6 - * @{ - */ -#define HAL_DATAIN6_DFSDM2_PAD 0x00000000U -#define HAL_DATAIN6_DFSDM2_DATAIN7 SYSCFG_MCHDLYCR_DFSDM2D6SEL -/** - * @} - */ - -/** @defgroup DFSDM1_CLKIN_SOURCE DFSDM1 Source Selection For CLKIN - * @{ - */ -#define HAL_DFSDM1_CLKIN0_TIM4OC2 0x01000000U -#define HAL_DFSDM1_CLKIN2_TIM4OC2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL -#define HAL_DFSDM1_CLKIN1_TIM4OC1 0x02000000U -#define HAL_DFSDM1_CLKIN3_TIM4OC1 SYSCFG_MCHDLYCR_DFSDM1CK13SEL -/** - * @} - */ - -/** @defgroup DFSDM2_CLKIN_SOURCE DFSDM2 Source Selection For CLKIN - * @{ - */ -#define HAL_DFSDM2_CLKIN0_TIM3OC4 0x04000000U -#define HAL_DFSDM2_CLKIN4_TIM3OC4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL -#define HAL_DFSDM2_CLKIN1_TIM3OC3 0x08000000U -#define HAL_DFSDM2_CLKIN5_TIM3OC3 SYSCFG_MCHDLYCR_DFSDM2CK15SEL -#define HAL_DFSDM2_CLKIN2_TIM3OC2 0x10000000U -#define HAL_DFSDM2_CLKIN6_TIM3OC2 SYSCFG_MCHDLYCR_DFSDM2CK26SEL -#define HAL_DFSDM2_CLKIN3_TIM3OC1 0x00000000U -#define HAL_DFSDM2_CLKIN7_TIM3OC1 SYSCFG_MCHDLYCR_DFSDM2CK37SEL -/** - * @} - */ - -#endif /* SYSCFG_MCHDLYCR_BSCKSEL*/ -/** - * @} - */ -/* End of exported constants -------------------------------------------------*/ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup DFSDM_Exported_Macros DFSDM Exported Macros - * @{ - */ - -/** @brief Reset DFSDM channel handle state. - * @param __HANDLE__ DFSDM channel handle. - * @retval None - */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -#define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET) -#endif - -/** @brief Reset DFSDM filter handle state. - * @param __HANDLE__ DFSDM filter handle. - * @retval None - */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -#define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET) -#endif - -/** - * @} - */ -/* End of exported macros ----------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DFSDM_Exported_Functions DFSDM Exported Functions - * @{ - */ - -/** @addtogroup DFSDM_Exported_Functions_Group1_Channel Channel initialization and de-initialization functions - * @{ - */ -/* Channel initialization and de-initialization functions *********************/ -HAL_StatusTypeDef HAL_DFSDM_ChannelInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -void HAL_DFSDM_ChannelMspInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -void HAL_DFSDM_ChannelMspDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/* Channel callbacks register/unregister functions ****************************/ -HAL_StatusTypeDef HAL_DFSDM_Channel_RegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID, - pDFSDM_Channel_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DFSDM_Channel_UnRegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID); -#endif -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group2_Channel Channel operation functions - * @{ - */ -/* Channel operation functions ************************************************/ -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); - -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Threshold, uint32_t BreakSignal); -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Threshold, uint32_t BreakSignal); -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); - -int16_t HAL_DFSDM_ChannelGetAwdValue(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelModifyOffset(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, int32_t Offset); - -HAL_StatusTypeDef HAL_DFSDM_ChannelPollForCkab(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Timeout); -HAL_StatusTypeDef HAL_DFSDM_ChannelPollForScd(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Timeout); - -void HAL_DFSDM_ChannelCkabCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -void HAL_DFSDM_ChannelScdCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group3_Channel Channel state function - * @{ - */ -/* Channel state function *****************************************************/ -HAL_DFSDM_Channel_StateTypeDef HAL_DFSDM_ChannelGetState(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group1_Filter Filter initialization and de-initialization functions - * @{ - */ -/* Filter initialization and de-initialization functions *********************/ -HAL_StatusTypeDef HAL_DFSDM_FilterInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterMspInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterMspDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/* Filter callbacks register/unregister functions ****************************/ -HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID, - pDFSDM_Filter_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID); -HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - pDFSDM_Filter_AwdCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -#endif -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group2_Filter Filter control functions - * @{ - */ -/* Filter control functions *********************/ -HAL_StatusTypeDef HAL_DFSDM_FilterConfigRegChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel, - uint32_t ContinuousMode); -HAL_StatusTypeDef HAL_DFSDM_FilterConfigInjChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel); -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group3_Filter Filter operation functions - * @{ - */ -/* Filter operation functions *********************/ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int32_t *pData, uint32_t Length); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int16_t *pData, uint32_t Length); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int32_t *pData, uint32_t Length); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int16_t *pData, uint32_t Length); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterAwdStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - DFSDM_Filter_AwdParamTypeDef* awdParam); -HAL_StatusTypeDef HAL_DFSDM_FilterAwdStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterExdStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel); -HAL_StatusTypeDef HAL_DFSDM_FilterExdStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); - -int32_t HAL_DFSDM_FilterGetRegularValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel); -int32_t HAL_DFSDM_FilterGetInjectedValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel); -int32_t HAL_DFSDM_FilterGetExdMaxValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel); -int32_t HAL_DFSDM_FilterGetExdMinValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel); -uint32_t HAL_DFSDM_FilterGetConvTimeValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); - -void HAL_DFSDM_IRQHandler(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); - -HAL_StatusTypeDef HAL_DFSDM_FilterPollForRegConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Timeout); -HAL_StatusTypeDef HAL_DFSDM_FilterPollForInjConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Timeout); - -void HAL_DFSDM_FilterRegConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterRegConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterInjConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterInjConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel, uint32_t Threshold); -void HAL_DFSDM_FilterErrorCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group4_Filter Filter state functions - * @{ - */ -/* Filter state functions *****************************************************/ -HAL_DFSDM_Filter_StateTypeDef HAL_DFSDM_FilterGetState(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -uint32_t HAL_DFSDM_FilterGetError(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -/** - * @} - */ -/** @addtogroup DFSDM_Exported_Functions_Group5_Filter MultiChannel operation functions - * @{ - */ -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -void HAL_DFSDM_ConfigMultiChannelDelay(DFSDM_MultiChannelConfigTypeDef* mchdlystruct); -void HAL_DFSDM_BitstreamClock_Start(void); -void HAL_DFSDM_BitstreamClock_Stop(void); -void HAL_DFSDM_DisableDelayClock(uint32_t MCHDLY); -void HAL_DFSDM_EnableDelayClock(uint32_t MCHDLY); -void HAL_DFSDM_ClockIn_SourceSelection(uint32_t source); -void HAL_DFSDM_ClockOut_SourceSelection(uint32_t source); -void HAL_DFSDM_DataIn0_SourceSelection(uint32_t source); -void HAL_DFSDM_DataIn2_SourceSelection(uint32_t source); -void HAL_DFSDM_DataIn4_SourceSelection(uint32_t source); -void HAL_DFSDM_DataIn6_SourceSelection(uint32_t source); -void HAL_DFSDM_BitStreamClkDistribution_Config(uint32_t source); -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ -/** - * @} - */ -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DFSDM_Private_Macros DFSDM Private Macros -* @{ -*/ -#define IS_DFSDM_CHANNEL_OUTPUT_CLOCK(CLOCK) (((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM) || \ - ((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO)) -#define IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(DIVIDER) ((2U <= (DIVIDER)) && ((DIVIDER) <= 256U)) -#define IS_DFSDM_CHANNEL_INPUT(INPUT) (((INPUT) == DFSDM_CHANNEL_EXTERNAL_INPUTS) || \ - ((INPUT) == DFSDM_CHANNEL_INTERNAL_REGISTER)) -#define IS_DFSDM_CHANNEL_DATA_PACKING(MODE) (((MODE) == DFSDM_CHANNEL_STANDARD_MODE) || \ - ((MODE) == DFSDM_CHANNEL_INTERLEAVED_MODE) || \ - ((MODE) == DFSDM_CHANNEL_DUAL_MODE)) -#define IS_DFSDM_CHANNEL_INPUT_PINS(PINS) (((PINS) == DFSDM_CHANNEL_SAME_CHANNEL_PINS) || \ - ((PINS) == DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS)) -#define IS_DFSDM_CHANNEL_SERIAL_INTERFACE_TYPE(MODE) (((MODE) == DFSDM_CHANNEL_SPI_RISING) || \ - ((MODE) == DFSDM_CHANNEL_SPI_FALLING) || \ - ((MODE) == DFSDM_CHANNEL_MANCHESTER_RISING) || \ - ((MODE) == DFSDM_CHANNEL_MANCHESTER_FALLING)) -#define IS_DFSDM_CHANNEL_SPI_CLOCK(TYPE) (((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL) || \ - ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL) || \ - ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING) || \ - ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING)) -#define IS_DFSDM_CHANNEL_FILTER_ORDER(ORDER) (((ORDER) == DFSDM_CHANNEL_FASTSINC_ORDER) || \ - ((ORDER) == DFSDM_CHANNEL_SINC1_ORDER) || \ - ((ORDER) == DFSDM_CHANNEL_SINC2_ORDER) || \ - ((ORDER) == DFSDM_CHANNEL_SINC3_ORDER)) -#define IS_DFSDM_CHANNEL_FILTER_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 32U)) -#define IS_DFSDM_CHANNEL_OFFSET(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607)) -#define IS_DFSDM_CHANNEL_RIGHT_BIT_SHIFT(VALUE) ((VALUE) <= 0x1FU) -#define IS_DFSDM_CHANNEL_SCD_THRESHOLD(VALUE) ((VALUE) <= 0xFFU) -#define IS_DFSDM_FILTER_REG_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \ - ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER)) -#define IS_DFSDM_FILTER_INJ_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \ - ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIGGER)) -#if defined (STM32F413xx) || defined (STM32F423xx) -#define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM10_OC1) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM2_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM11_OC1) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15)) -#define IS_DFSDM_DELAY_CLOCK(CLOCK) (((CLOCK) == HAL_MCHDLY_CLOCK_DFSDM2) || \ - ((CLOCK) == HAL_MCHDLY_CLOCK_DFSDM1)) -#else -#define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM10_OC1) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15)) -#endif -#define IS_DFSDM_FILTER_EXT_TRIG_EDGE(EDGE) (((EDGE) == DFSDM_FILTER_EXT_TRIG_RISING_EDGE) || \ - ((EDGE) == DFSDM_FILTER_EXT_TRIG_FALLING_EDGE) || \ - ((EDGE) == DFSDM_FILTER_EXT_TRIG_BOTH_EDGES)) -#define IS_DFSDM_FILTER_SINC_ORDER(ORDER) (((ORDER) == DFSDM_FILTER_FASTSINC_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC1_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC2_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC3_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC4_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC5_ORDER)) -#define IS_DFSDM_FILTER_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 1024U)) -#define IS_DFSDM_FILTER_INTEGRATOR_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 256U)) -#define IS_DFSDM_FILTER_AWD_DATA_SOURCE(DATA) (((DATA) == DFSDM_FILTER_AWD_FILTER_DATA) || \ - ((DATA) == DFSDM_FILTER_AWD_CHANNEL_DATA)) -#define IS_DFSDM_FILTER_AWD_THRESHOLD(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607)) -#define IS_DFSDM_BREAK_SIGNALS(VALUE) ((VALUE) <= 0x0FU) -#if defined(DFSDM2_Channel0) -#define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_CHANNEL_0) || \ - ((CHANNEL) == DFSDM_CHANNEL_1) || \ - ((CHANNEL) == DFSDM_CHANNEL_2) || \ - ((CHANNEL) == DFSDM_CHANNEL_3) || \ - ((CHANNEL) == DFSDM_CHANNEL_4) || \ - ((CHANNEL) == DFSDM_CHANNEL_5) || \ - ((CHANNEL) == DFSDM_CHANNEL_6) || \ - ((CHANNEL) == DFSDM_CHANNEL_7)) -#define IS_DFSDM_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) != 0U) && ((CHANNEL) <= 0x000F00FFU)) -#else -#define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_CHANNEL_0) || \ - ((CHANNEL) == DFSDM_CHANNEL_1) || \ - ((CHANNEL) == DFSDM_CHANNEL_2) || \ - ((CHANNEL) == DFSDM_CHANNEL_3)) -#define IS_DFSDM_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) != 0U) && ((CHANNEL) <= 0x0003000FU)) -#endif -#define IS_DFSDM_CONTINUOUS_MODE(MODE) (((MODE) == DFSDM_CONTINUOUS_CONV_OFF) || \ - ((MODE) == DFSDM_CONTINUOUS_CONV_ON)) -#if defined(DFSDM2_Channel0) -#define IS_DFSDM1_CHANNEL_INSTANCE(INSTANCE) (((INSTANCE) == DFSDM1_Channel0) || \ - ((INSTANCE) == DFSDM1_Channel1) || \ - ((INSTANCE) == DFSDM1_Channel2) || \ - ((INSTANCE) == DFSDM1_Channel3)) -#define IS_DFSDM1_FILTER_INSTANCE(INSTANCE) (((INSTANCE) == DFSDM1_Filter0) || \ - ((INSTANCE) == DFSDM1_Filter1)) -#endif /* DFSDM2_Channel0 */ - -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -#define IS_DFSDM_CLOCKIN_SELECTION(SELECTION) (((SELECTION) == HAL_DFSDM2_CKIN_PAD) || \ - ((SELECTION) == HAL_DFSDM2_CKIN_DM) || \ - ((SELECTION) == HAL_DFSDM1_CKIN_PAD) || \ - ((SELECTION) == HAL_DFSDM1_CKIN_DM)) -#define IS_DFSDM_CLOCKOUT_SELECTION(SELECTION) (((SELECTION) == HAL_DFSDM2_CKOUT_DFSDM2) || \ - ((SELECTION) == HAL_DFSDM2_CKOUT_M27) || \ - ((SELECTION) == HAL_DFSDM1_CKOUT_DFSDM1) || \ - ((SELECTION) == HAL_DFSDM1_CKOUT_M27)) -#define IS_DFSDM_DATAIN0_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN0_DFSDM2_PAD) || \ - ((SELECTION) == HAL_DATAIN0_DFSDM2_DATAIN1) || \ - ((SELECTION) == HAL_DATAIN0_DFSDM1_PAD) || \ - ((SELECTION) == HAL_DATAIN0_DFSDM1_DATAIN1)) -#define IS_DFSDM_DATAIN2_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN2_DFSDM2_PAD) || \ - ((SELECTION) == HAL_DATAIN2_DFSDM2_DATAIN3) || \ - ((SELECTION) == HAL_DATAIN2_DFSDM1_PAD) || \ - ((SELECTION) == HAL_DATAIN2_DFSDM1_DATAIN3)) -#define IS_DFSDM_DATAIN4_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN4_DFSDM2_PAD) || \ - ((SELECTION) == HAL_DATAIN4_DFSDM2_DATAIN5)) -#define IS_DFSDM_DATAIN6_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN6_DFSDM2_PAD) || \ - ((SELECTION) == HAL_DATAIN6_DFSDM2_DATAIN7)) -#define IS_DFSDM_BITSTREM_CLK_DISTRIBUTION(DISTRIBUTION) (((DISTRIBUTION) == HAL_DFSDM1_CLKIN0_TIM4OC2) || \ - ((DISTRIBUTION) == HAL_DFSDM1_CLKIN2_TIM4OC2) || \ - ((DISTRIBUTION) == HAL_DFSDM1_CLKIN1_TIM4OC1) || \ - ((DISTRIBUTION) == HAL_DFSDM1_CLKIN3_TIM4OC1) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN0_TIM3OC4) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN4_TIM3OC4) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN1_TIM3OC3)|| \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN5_TIM3OC3) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN2_TIM3OC2) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN6_TIM3OC2) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN3_TIM3OC1)|| \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN7_TIM3OC1)) -#define IS_DFSDM_DFSDM1_CLKOUT(CLKOUT) (((CLKOUT) == DFSDM1_CKOUT_DFSDM2_CKOUT) || \ - ((CLKOUT) == DFSDM1_CKOUT_DFSDM1)) -#define IS_DFSDM_DFSDM2_CLKOUT(CLKOUT) (((CLKOUT) == DFSDM2_CKOUT_DFSDM2_CKOUT) || \ - ((CLKOUT) == DFSDM2_CKOUT_DFSDM2)) -#define IS_DFSDM_DFSDM1_CLKIN(CLKIN) (((CLKIN) == DFSDM1_CKIN_DFSDM2_CKOUT) || \ - ((CLKIN) == DFSDM1_CKIN_PAD)) -#define IS_DFSDM_DFSDM2_CLKIN(CLKIN) (((CLKIN) == DFSDM2_CKIN_DFSDM2_CKOUT) || \ - ((CLKIN) == DFSDM2_CKIN_PAD)) -#define IS_DFSDM_DFSDM1_BIT_CLK(CLK) (((CLK) == DFSDM1_T4_OC2_BITSTREAM_CKIN0) || \ - ((CLK) == DFSDM1_T4_OC2_BITSTREAM_CKIN2) || \ - ((CLK) == DFSDM1_T4_OC1_BITSTREAM_CKIN3) || \ - ((CLK) == DFSDM1_T4_OC1_BITSTREAM_CKIN1) || \ - ((CLK) <= 0x30U)) - -#define IS_DFSDM_DFSDM2_BIT_CLK(CLK) (((CLK) == DFSDM2_T3_OC4_BITSTREAM_CKIN0) || \ - ((CLK) == DFSDM2_T3_OC4_BITSTREAM_CKIN4) || \ - ((CLK) == DFSDM2_T3_OC3_BITSTREAM_CKIN5) || \ - ((CLK) == DFSDM2_T3_OC3_BITSTREAM_CKIN1) || \ - ((CLK) == DFSDM2_T3_OC2_BITSTREAM_CKIN6) || \ - ((CLK) == DFSDM2_T3_OC2_BITSTREAM_CKIN2) || \ - ((CLK) == DFSDM2_T3_OC1_BITSTREAM_CKIN3) || \ - ((CLK) == DFSDM2_T3_OC1_BITSTREAM_CKIN7)|| \ - ((CLK) <= 0x1E000U)) - -#define IS_DFSDM_DFSDM1_DATA_DISTRIBUTION(DISTRIBUTION)(((DISTRIBUTION) == DFSDM1_DATIN0_TO_DATIN0_PAD )|| \ - ((DISTRIBUTION) == DFSDM1_DATIN0_TO_DATIN1_PAD) || \ - ((DISTRIBUTION) == DFSDM1_DATIN2_TO_DATIN2_PAD) || \ - ((DISTRIBUTION) == DFSDM1_DATIN2_TO_DATIN3_PAD)|| \ - ((DISTRIBUTION) <= 0xCU)) - -#define IS_DFSDM_DFSDM2_DATA_DISTRIBUTION(DISTRIBUTION)(((DISTRIBUTION) == DFSDM2_DATIN0_TO_DATIN0_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN0_TO_DATIN1_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN2_TO_DATIN2_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN2_TO_DATIN3_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN4_TO_DATIN4_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN4_TO_DATIN5_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN6_TO_DATIN6_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN6_TO_DATIN7_PAD)|| \ - ((DISTRIBUTION) <= 0x1D00U)) -#endif /* (SYSCFG_MCHDLYCR_BSCKSEL) */ -/** - * @} - */ -/* End of private macros -----------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DFSDM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h deleted file mode 100644 index 90dd292cc0ad34b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h +++ /dev/null @@ -1,804 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma.h - * @author MCD Application Team - * @brief Header file of DMA HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DMA_H -#define __STM32F4xx_HAL_DMA_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DMA - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Types DMA Exported Types - * @brief DMA Exported Types - * @{ - */ - -/** - * @brief DMA Configuration Structure definition - */ -typedef struct -{ - uint32_t Channel; /*!< Specifies the channel used for the specified stream. - This parameter can be a value of @ref DMA_Channel_selection */ - - uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral, - from memory to memory or from peripheral to memory. - This parameter can be a value of @ref DMA_Data_transfer_direction */ - - uint32_t PeriphInc; /*!< Specifies whether the Peripheral address register should be incremented or not. - This parameter can be a value of @ref DMA_Peripheral_incremented_mode */ - - uint32_t MemInc; /*!< Specifies whether the memory address register should be incremented or not. - This parameter can be a value of @ref DMA_Memory_incremented_mode */ - - uint32_t PeriphDataAlignment; /*!< Specifies the Peripheral data width. - This parameter can be a value of @ref DMA_Peripheral_data_size */ - - uint32_t MemDataAlignment; /*!< Specifies the Memory data width. - This parameter can be a value of @ref DMA_Memory_data_size */ - - uint32_t Mode; /*!< Specifies the operation mode of the DMAy Streamx. - This parameter can be a value of @ref DMA_mode - @note The circular buffer mode cannot be used if the memory-to-memory - data transfer is configured on the selected Stream */ - - uint32_t Priority; /*!< Specifies the software priority for the DMAy Streamx. - This parameter can be a value of @ref DMA_Priority_level */ - - uint32_t FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified stream. - This parameter can be a value of @ref DMA_FIFO_direct_mode - @note The Direct mode (FIFO mode disabled) cannot be used if the - memory-to-memory data transfer is configured on the selected stream */ - - uint32_t FIFOThreshold; /*!< Specifies the FIFO threshold level. - This parameter can be a value of @ref DMA_FIFO_threshold_level */ - - uint32_t MemBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_Memory_burst - @note The burst mode is possible only if the address Increment mode is enabled. */ - - uint32_t PeriphBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_Peripheral_burst - @note The burst mode is possible only if the address Increment mode is enabled. */ -}DMA_InitTypeDef; - - -/** - * @brief HAL DMA State structures definition - */ -typedef enum -{ - HAL_DMA_STATE_RESET = 0x00U, /*!< DMA not yet initialized or disabled */ - HAL_DMA_STATE_READY = 0x01U, /*!< DMA initialized and ready for use */ - HAL_DMA_STATE_BUSY = 0x02U, /*!< DMA process is ongoing */ - HAL_DMA_STATE_TIMEOUT = 0x03U, /*!< DMA timeout state */ - HAL_DMA_STATE_ERROR = 0x04U, /*!< DMA error state */ - HAL_DMA_STATE_ABORT = 0x05U, /*!< DMA Abort state */ -}HAL_DMA_StateTypeDef; - -/** - * @brief HAL DMA Error Code structure definition - */ -typedef enum -{ - HAL_DMA_FULL_TRANSFER = 0x00U, /*!< Full transfer */ - HAL_DMA_HALF_TRANSFER = 0x01U /*!< Half Transfer */ -}HAL_DMA_LevelCompleteTypeDef; - -/** - * @brief HAL DMA Error Code structure definition - */ -typedef enum -{ - HAL_DMA_XFER_CPLT_CB_ID = 0x00U, /*!< Full transfer */ - HAL_DMA_XFER_HALFCPLT_CB_ID = 0x01U, /*!< Half Transfer */ - HAL_DMA_XFER_M1CPLT_CB_ID = 0x02U, /*!< M1 Full Transfer */ - HAL_DMA_XFER_M1HALFCPLT_CB_ID = 0x03U, /*!< M1 Half Transfer */ - HAL_DMA_XFER_ERROR_CB_ID = 0x04U, /*!< Error */ - HAL_DMA_XFER_ABORT_CB_ID = 0x05U, /*!< Abort */ - HAL_DMA_XFER_ALL_CB_ID = 0x06U /*!< All */ -}HAL_DMA_CallbackIDTypeDef; - -/** - * @brief DMA handle Structure definition - */ -typedef struct __DMA_HandleTypeDef -{ - DMA_Stream_TypeDef *Instance; /*!< Register base address */ - - DMA_InitTypeDef Init; /*!< DMA communication parameters */ - - HAL_LockTypeDef Lock; /*!< DMA locking object */ - - __IO HAL_DMA_StateTypeDef State; /*!< DMA transfer state */ - - void *Parent; /*!< Parent object state */ - - void (* XferCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete callback */ - - void (* XferHalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA Half transfer complete callback */ - - void (* XferM1CpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete Memory1 callback */ - - void (* XferM1HalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer Half complete Memory1 callback */ - - void (* XferErrorCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer error callback */ - - void (* XferAbortCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer Abort callback */ - - __IO uint32_t ErrorCode; /*!< DMA Error code */ - - uint32_t StreamBaseAddress; /*!< DMA Stream Base Address */ - - uint32_t StreamIndex; /*!< DMA Stream Index */ - -}DMA_HandleTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Constants DMA Exported Constants - * @brief DMA Exported constants - * @{ - */ - -/** @defgroup DMA_Error_Code DMA Error Code - * @brief DMA Error Code - * @{ - */ -#define HAL_DMA_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_DMA_ERROR_TE 0x00000001U /*!< Transfer error */ -#define HAL_DMA_ERROR_FE 0x00000002U /*!< FIFO error */ -#define HAL_DMA_ERROR_DME 0x00000004U /*!< Direct Mode error */ -#define HAL_DMA_ERROR_TIMEOUT 0x00000020U /*!< Timeout error */ -#define HAL_DMA_ERROR_PARAM 0x00000040U /*!< Parameter error */ -#define HAL_DMA_ERROR_NO_XFER 0x00000080U /*!< Abort requested with no Xfer ongoing */ -#define HAL_DMA_ERROR_NOT_SUPPORTED 0x00000100U /*!< Not supported mode */ -/** - * @} - */ - -/** @defgroup DMA_Channel_selection DMA Channel selection - * @brief DMA channel selection - * @{ - */ -#define DMA_CHANNEL_0 0x00000000U /*!< DMA Channel 0 */ -#define DMA_CHANNEL_1 0x02000000U /*!< DMA Channel 1 */ -#define DMA_CHANNEL_2 0x04000000U /*!< DMA Channel 2 */ -#define DMA_CHANNEL_3 0x06000000U /*!< DMA Channel 3 */ -#define DMA_CHANNEL_4 0x08000000U /*!< DMA Channel 4 */ -#define DMA_CHANNEL_5 0x0A000000U /*!< DMA Channel 5 */ -#define DMA_CHANNEL_6 0x0C000000U /*!< DMA Channel 6 */ -#define DMA_CHANNEL_7 0x0E000000U /*!< DMA Channel 7 */ -#if defined (DMA_SxCR_CHSEL_3) -#define DMA_CHANNEL_8 0x10000000U /*!< DMA Channel 8 */ -#define DMA_CHANNEL_9 0x12000000U /*!< DMA Channel 9 */ -#define DMA_CHANNEL_10 0x14000000U /*!< DMA Channel 10 */ -#define DMA_CHANNEL_11 0x16000000U /*!< DMA Channel 11 */ -#define DMA_CHANNEL_12 0x18000000U /*!< DMA Channel 12 */ -#define DMA_CHANNEL_13 0x1A000000U /*!< DMA Channel 13 */ -#define DMA_CHANNEL_14 0x1C000000U /*!< DMA Channel 14 */ -#define DMA_CHANNEL_15 0x1E000000U /*!< DMA Channel 15 */ -#endif /* DMA_SxCR_CHSEL_3 */ -/** - * @} - */ - -/** @defgroup DMA_Data_transfer_direction DMA Data transfer direction - * @brief DMA data transfer direction - * @{ - */ -#define DMA_PERIPH_TO_MEMORY 0x00000000U /*!< Peripheral to memory direction */ -#define DMA_MEMORY_TO_PERIPH ((uint32_t)DMA_SxCR_DIR_0) /*!< Memory to peripheral direction */ -#define DMA_MEMORY_TO_MEMORY ((uint32_t)DMA_SxCR_DIR_1) /*!< Memory to memory direction */ -/** - * @} - */ - -/** @defgroup DMA_Peripheral_incremented_mode DMA Peripheral incremented mode - * @brief DMA peripheral incremented mode - * @{ - */ -#define DMA_PINC_ENABLE ((uint32_t)DMA_SxCR_PINC) /*!< Peripheral increment mode enable */ -#define DMA_PINC_DISABLE 0x00000000U /*!< Peripheral increment mode disable */ -/** - * @} - */ - -/** @defgroup DMA_Memory_incremented_mode DMA Memory incremented mode - * @brief DMA memory incremented mode - * @{ - */ -#define DMA_MINC_ENABLE ((uint32_t)DMA_SxCR_MINC) /*!< Memory increment mode enable */ -#define DMA_MINC_DISABLE 0x00000000U /*!< Memory increment mode disable */ -/** - * @} - */ - -/** @defgroup DMA_Peripheral_data_size DMA Peripheral data size - * @brief DMA peripheral data size - * @{ - */ -#define DMA_PDATAALIGN_BYTE 0x00000000U /*!< Peripheral data alignment: Byte */ -#define DMA_PDATAALIGN_HALFWORD ((uint32_t)DMA_SxCR_PSIZE_0) /*!< Peripheral data alignment: HalfWord */ -#define DMA_PDATAALIGN_WORD ((uint32_t)DMA_SxCR_PSIZE_1) /*!< Peripheral data alignment: Word */ -/** - * @} - */ - -/** @defgroup DMA_Memory_data_size DMA Memory data size - * @brief DMA memory data size - * @{ - */ -#define DMA_MDATAALIGN_BYTE 0x00000000U /*!< Memory data alignment: Byte */ -#define DMA_MDATAALIGN_HALFWORD ((uint32_t)DMA_SxCR_MSIZE_0) /*!< Memory data alignment: HalfWord */ -#define DMA_MDATAALIGN_WORD ((uint32_t)DMA_SxCR_MSIZE_1) /*!< Memory data alignment: Word */ -/** - * @} - */ - -/** @defgroup DMA_mode DMA mode - * @brief DMA mode - * @{ - */ -#define DMA_NORMAL 0x00000000U /*!< Normal mode */ -#define DMA_CIRCULAR ((uint32_t)DMA_SxCR_CIRC) /*!< Circular mode */ -#define DMA_PFCTRL ((uint32_t)DMA_SxCR_PFCTRL) /*!< Peripheral flow control mode */ -/** - * @} - */ - -/** @defgroup DMA_Priority_level DMA Priority level - * @brief DMA priority levels - * @{ - */ -#define DMA_PRIORITY_LOW 0x00000000U /*!< Priority level: Low */ -#define DMA_PRIORITY_MEDIUM ((uint32_t)DMA_SxCR_PL_0) /*!< Priority level: Medium */ -#define DMA_PRIORITY_HIGH ((uint32_t)DMA_SxCR_PL_1) /*!< Priority level: High */ -#define DMA_PRIORITY_VERY_HIGH ((uint32_t)DMA_SxCR_PL) /*!< Priority level: Very High */ -/** - * @} - */ - -/** @defgroup DMA_FIFO_direct_mode DMA FIFO direct mode - * @brief DMA FIFO direct mode - * @{ - */ -#define DMA_FIFOMODE_DISABLE 0x00000000U /*!< FIFO mode disable */ -#define DMA_FIFOMODE_ENABLE ((uint32_t)DMA_SxFCR_DMDIS) /*!< FIFO mode enable */ -/** - * @} - */ - -/** @defgroup DMA_FIFO_threshold_level DMA FIFO threshold level - * @brief DMA FIFO level - * @{ - */ -#define DMA_FIFO_THRESHOLD_1QUARTERFULL 0x00000000U /*!< FIFO threshold 1 quart full configuration */ -#define DMA_FIFO_THRESHOLD_HALFFULL ((uint32_t)DMA_SxFCR_FTH_0) /*!< FIFO threshold half full configuration */ -#define DMA_FIFO_THRESHOLD_3QUARTERSFULL ((uint32_t)DMA_SxFCR_FTH_1) /*!< FIFO threshold 3 quarts full configuration */ -#define DMA_FIFO_THRESHOLD_FULL ((uint32_t)DMA_SxFCR_FTH) /*!< FIFO threshold full configuration */ -/** - * @} - */ - -/** @defgroup DMA_Memory_burst DMA Memory burst - * @brief DMA memory burst - * @{ - */ -#define DMA_MBURST_SINGLE 0x00000000U -#define DMA_MBURST_INC4 ((uint32_t)DMA_SxCR_MBURST_0) -#define DMA_MBURST_INC8 ((uint32_t)DMA_SxCR_MBURST_1) -#define DMA_MBURST_INC16 ((uint32_t)DMA_SxCR_MBURST) -/** - * @} - */ - -/** @defgroup DMA_Peripheral_burst DMA Peripheral burst - * @brief DMA peripheral burst - * @{ - */ -#define DMA_PBURST_SINGLE 0x00000000U -#define DMA_PBURST_INC4 ((uint32_t)DMA_SxCR_PBURST_0) -#define DMA_PBURST_INC8 ((uint32_t)DMA_SxCR_PBURST_1) -#define DMA_PBURST_INC16 ((uint32_t)DMA_SxCR_PBURST) -/** - * @} - */ - -/** @defgroup DMA_interrupt_enable_definitions DMA interrupt enable definitions - * @brief DMA interrupts definition - * @{ - */ -#define DMA_IT_TC ((uint32_t)DMA_SxCR_TCIE) -#define DMA_IT_HT ((uint32_t)DMA_SxCR_HTIE) -#define DMA_IT_TE ((uint32_t)DMA_SxCR_TEIE) -#define DMA_IT_DME ((uint32_t)DMA_SxCR_DMEIE) -#define DMA_IT_FE 0x00000080U -/** - * @} - */ - -/** @defgroup DMA_flag_definitions DMA flag definitions - * @brief DMA flag definitions - * @{ - */ -#define DMA_FLAG_FEIF0_4 0x00000001U -#define DMA_FLAG_DMEIF0_4 0x00000004U -#define DMA_FLAG_TEIF0_4 0x00000008U -#define DMA_FLAG_HTIF0_4 0x00000010U -#define DMA_FLAG_TCIF0_4 0x00000020U -#define DMA_FLAG_FEIF1_5 0x00000040U -#define DMA_FLAG_DMEIF1_5 0x00000100U -#define DMA_FLAG_TEIF1_5 0x00000200U -#define DMA_FLAG_HTIF1_5 0x00000400U -#define DMA_FLAG_TCIF1_5 0x00000800U -#define DMA_FLAG_FEIF2_6 0x00010000U -#define DMA_FLAG_DMEIF2_6 0x00040000U -#define DMA_FLAG_TEIF2_6 0x00080000U -#define DMA_FLAG_HTIF2_6 0x00100000U -#define DMA_FLAG_TCIF2_6 0x00200000U -#define DMA_FLAG_FEIF3_7 0x00400000U -#define DMA_FLAG_DMEIF3_7 0x01000000U -#define DMA_FLAG_TEIF3_7 0x02000000U -#define DMA_FLAG_HTIF3_7 0x04000000U -#define DMA_FLAG_TCIF3_7 0x08000000U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/** @brief Reset DMA handle state - * @param __HANDLE__ specifies the DMA handle. - * @retval None - */ -#define __HAL_DMA_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DMA_STATE_RESET) - -/** - * @brief Return the current DMA Stream FIFO filled level. - * @param __HANDLE__ DMA handle - * @retval The FIFO filling state. - * - DMA_FIFOStatus_Less1QuarterFull: when FIFO is less than 1 quarter-full - * and not empty. - * - DMA_FIFOStatus_1QuarterFull: if more than 1 quarter-full. - * - DMA_FIFOStatus_HalfFull: if more than 1 half-full. - * - DMA_FIFOStatus_3QuartersFull: if more than 3 quarters-full. - * - DMA_FIFOStatus_Empty: when FIFO is empty - * - DMA_FIFOStatus_Full: when FIFO is full - */ -#define __HAL_DMA_GET_FS(__HANDLE__) (((__HANDLE__)->Instance->FCR & (DMA_SxFCR_FS))) - -/** - * @brief Enable the specified DMA Stream. - * @param __HANDLE__ DMA handle - * @retval None - */ -#define __HAL_DMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= DMA_SxCR_EN) - -/** - * @brief Disable the specified DMA Stream. - * @param __HANDLE__ DMA handle - * @retval None - */ -#define __HAL_DMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~DMA_SxCR_EN) - -/* Interrupt & Flag management */ - -/** - * @brief Return the current DMA Stream transfer complete flag. - * @param __HANDLE__ DMA handle - * @retval The specified transfer complete flag index. - */ -#define __HAL_DMA_GET_TC_FLAG_INDEX(__HANDLE__) \ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_TCIF2_6 :\ - DMA_FLAG_TCIF3_7) - -/** - * @brief Return the current DMA Stream half transfer complete flag. - * @param __HANDLE__ DMA handle - * @retval The specified half transfer complete flag index. - */ -#define __HAL_DMA_GET_HT_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_HTIF2_6 :\ - DMA_FLAG_HTIF3_7) - -/** - * @brief Return the current DMA Stream transfer error flag. - * @param __HANDLE__ DMA handle - * @retval The specified transfer error flag index. - */ -#define __HAL_DMA_GET_TE_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_TEIF2_6 :\ - DMA_FLAG_TEIF3_7) - -/** - * @brief Return the current DMA Stream FIFO error flag. - * @param __HANDLE__ DMA handle - * @retval The specified FIFO error flag index. - */ -#define __HAL_DMA_GET_FE_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_FEIF2_6 :\ - DMA_FLAG_FEIF3_7) - -/** - * @brief Return the current DMA Stream direct mode error flag. - * @param __HANDLE__ DMA handle - * @retval The specified direct mode error flag index. - */ -#define __HAL_DMA_GET_DME_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_DMEIF2_6 :\ - DMA_FLAG_DMEIF3_7) - -/** - * @brief Get the DMA Stream pending flags. - * @param __HANDLE__ DMA handle - * @param __FLAG__ Get the specified flag. - * This parameter can be any combination of the following values: - * @arg DMA_FLAG_TCIFx: Transfer complete flag. - * @arg DMA_FLAG_HTIFx: Half transfer complete flag. - * @arg DMA_FLAG_TEIFx: Transfer error flag. - * @arg DMA_FLAG_DMEIFx: Direct mode error flag. - * @arg DMA_FLAG_FEIFx: FIFO error flag. - * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Stream flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __HAL_DMA_GET_FLAG(__HANDLE__, __FLAG__)\ -(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA2_Stream3)? (DMA2->HISR & (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream7)? (DMA2->LISR & (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream3)? (DMA1->HISR & (__FLAG__)) : (DMA1->LISR & (__FLAG__))) - -/** - * @brief Clear the DMA Stream pending flags. - * @param __HANDLE__ DMA handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DMA_FLAG_TCIFx: Transfer complete flag. - * @arg DMA_FLAG_HTIFx: Half transfer complete flag. - * @arg DMA_FLAG_TEIFx: Transfer error flag. - * @arg DMA_FLAG_DMEIFx: Direct mode error flag. - * @arg DMA_FLAG_FEIFx: FIFO error flag. - * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Stream flag. - * @retval None - */ -#define __HAL_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) \ -(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA2_Stream3)? (DMA2->HIFCR = (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream7)? (DMA2->LIFCR = (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream3)? (DMA1->HIFCR = (__FLAG__)) : (DMA1->LIFCR = (__FLAG__))) - -/** - * @brief Enable the specified DMA Stream interrupts. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval None - */ -#define __HAL_DMA_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ -((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) : ((__HANDLE__)->Instance->FCR |= (__INTERRUPT__))) - -/** - * @brief Disable the specified DMA Stream interrupts. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval None - */ -#define __HAL_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ -((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) : ((__HANDLE__)->Instance->FCR &= ~(__INTERRUPT__))) - -/** - * @brief Check whether the specified DMA Stream interrupt is enabled or disabled. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt source to check. - * This parameter can be one of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval The state of DMA_IT. - */ -#define __HAL_DMA_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ - ((__HANDLE__)->Instance->CR & (__INTERRUPT__)) : \ - ((__HANDLE__)->Instance->FCR & (__INTERRUPT__))) - -/** - * @brief Writes the number of data units to be transferred on the DMA Stream. - * @param __HANDLE__ DMA handle - * @param __COUNTER__ Number of data units to be transferred (from 0 to 65535) - * Number of data items depends only on the Peripheral data format. - * - * @note If Peripheral data format is Bytes: number of data units is equal - * to total number of bytes to be transferred. - * - * @note If Peripheral data format is Half-Word: number of data units is - * equal to total number of bytes to be transferred / 2. - * - * @note If Peripheral data format is Word: number of data units is equal - * to total number of bytes to be transferred / 4. - * - * @retval The number of remaining data units in the current DMAy Streamx transfer. - */ -#define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->NDTR = (uint16_t)(__COUNTER__)) - -/** - * @brief Returns the number of remaining data units in the current DMAy Streamx transfer. - * @param __HANDLE__ DMA handle - * - * @retval The number of remaining data units in the current DMA Stream transfer. - */ -#define __HAL_DMA_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->NDTR) - - -/* Include DMA HAL Extension module */ -#include "stm32f4xx_hal_dma_ex.h" - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Functions DMA Exported Functions - * @brief DMA Exported functions - * @{ - */ - -/** @defgroup DMA_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** @defgroup DMA_Exported_Functions_Group2 I/O operation functions - * @brief I/O operation functions - * @{ - */ -HAL_StatusTypeDef HAL_DMA_Start (DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout); -void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_CleanCallbacks(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma)); -HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID); - -/** - * @} - */ - -/** @defgroup DMA_Exported_Functions_Group3 Peripheral State functions - * @brief Peripheral State functions - * @{ - */ -HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma); -uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma); -/** - * @} - */ -/** - * @} - */ -/* Private Constants -------------------------------------------------------------*/ -/** @defgroup DMA_Private_Constants DMA Private Constants - * @brief DMA private defines and constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DMA_Private_Macros DMA Private Macros - * @brief DMA private macros - * @{ - */ -#if defined (DMA_SxCR_CHSEL_3) -#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_CHANNEL_0) || \ - ((CHANNEL) == DMA_CHANNEL_1) || \ - ((CHANNEL) == DMA_CHANNEL_2) || \ - ((CHANNEL) == DMA_CHANNEL_3) || \ - ((CHANNEL) == DMA_CHANNEL_4) || \ - ((CHANNEL) == DMA_CHANNEL_5) || \ - ((CHANNEL) == DMA_CHANNEL_6) || \ - ((CHANNEL) == DMA_CHANNEL_7) || \ - ((CHANNEL) == DMA_CHANNEL_8) || \ - ((CHANNEL) == DMA_CHANNEL_9) || \ - ((CHANNEL) == DMA_CHANNEL_10)|| \ - ((CHANNEL) == DMA_CHANNEL_11)|| \ - ((CHANNEL) == DMA_CHANNEL_12)|| \ - ((CHANNEL) == DMA_CHANNEL_13)|| \ - ((CHANNEL) == DMA_CHANNEL_14)|| \ - ((CHANNEL) == DMA_CHANNEL_15)) -#else -#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_CHANNEL_0) || \ - ((CHANNEL) == DMA_CHANNEL_1) || \ - ((CHANNEL) == DMA_CHANNEL_2) || \ - ((CHANNEL) == DMA_CHANNEL_3) || \ - ((CHANNEL) == DMA_CHANNEL_4) || \ - ((CHANNEL) == DMA_CHANNEL_5) || \ - ((CHANNEL) == DMA_CHANNEL_6) || \ - ((CHANNEL) == DMA_CHANNEL_7)) -#endif /* DMA_SxCR_CHSEL_3 */ - -#define IS_DMA_DIRECTION(DIRECTION) (((DIRECTION) == DMA_PERIPH_TO_MEMORY ) || \ - ((DIRECTION) == DMA_MEMORY_TO_PERIPH) || \ - ((DIRECTION) == DMA_MEMORY_TO_MEMORY)) - -#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x01U) && ((SIZE) < 0x10000U)) - -#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PINC_ENABLE) || \ - ((STATE) == DMA_PINC_DISABLE)) - -#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MINC_ENABLE) || \ - ((STATE) == DMA_MINC_DISABLE)) - -#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PDATAALIGN_BYTE) || \ - ((SIZE) == DMA_PDATAALIGN_HALFWORD) || \ - ((SIZE) == DMA_PDATAALIGN_WORD)) - -#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MDATAALIGN_BYTE) || \ - ((SIZE) == DMA_MDATAALIGN_HALFWORD) || \ - ((SIZE) == DMA_MDATAALIGN_WORD )) - -#define IS_DMA_MODE(MODE) (((MODE) == DMA_NORMAL ) || \ - ((MODE) == DMA_CIRCULAR) || \ - ((MODE) == DMA_PFCTRL)) - -#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_PRIORITY_LOW ) || \ - ((PRIORITY) == DMA_PRIORITY_MEDIUM) || \ - ((PRIORITY) == DMA_PRIORITY_HIGH) || \ - ((PRIORITY) == DMA_PRIORITY_VERY_HIGH)) - -#define IS_DMA_FIFO_MODE_STATE(STATE) (((STATE) == DMA_FIFOMODE_DISABLE ) || \ - ((STATE) == DMA_FIFOMODE_ENABLE)) - -#define IS_DMA_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == DMA_FIFO_THRESHOLD_1QUARTERFULL ) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_HALFFULL) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_3QUARTERSFULL) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_FULL)) - -#define IS_DMA_MEMORY_BURST(BURST) (((BURST) == DMA_MBURST_SINGLE) || \ - ((BURST) == DMA_MBURST_INC4) || \ - ((BURST) == DMA_MBURST_INC8) || \ - ((BURST) == DMA_MBURST_INC16)) - -#define IS_DMA_PERIPHERAL_BURST(BURST) (((BURST) == DMA_PBURST_SINGLE) || \ - ((BURST) == DMA_PBURST_INC4) || \ - ((BURST) == DMA_PBURST_INC8) || \ - ((BURST) == DMA_PBURST_INC16)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DMA_Private_Functions DMA Private Functions - * @brief DMA private functions - * @{ - */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DMA_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma2d.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma2d.h deleted file mode 100644 index 158ed67d0e32c52..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma2d.h +++ /dev/null @@ -1,651 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma2d.h - * @author MCD Application Team - * @brief Header file of DMA2D HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_DMA2D_H -#define STM32F4xx_HAL_DMA2D_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (DMA2D) - -/** @addtogroup DMA2D DMA2D - * @brief DMA2D HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DMA2D_Exported_Types DMA2D Exported Types - * @{ - */ -#define MAX_DMA2D_LAYER 2U /*!< DMA2D maximum number of layers */ - -/** - * @brief DMA2D CLUT Structure definition - */ -typedef struct -{ - uint32_t *pCLUT; /*!< Configures the DMA2D CLUT memory address.*/ - - uint32_t CLUTColorMode; /*!< Configures the DMA2D CLUT color mode. - This parameter can be one value of @ref DMA2D_CLUT_CM. */ - - uint32_t Size; /*!< Configures the DMA2D CLUT size. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF.*/ -} DMA2D_CLUTCfgTypeDef; - -/** - * @brief DMA2D Init structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Configures the DMA2D transfer mode. - This parameter can be one value of @ref DMA2D_Mode. */ - - uint32_t ColorMode; /*!< Configures the color format of the output image. - This parameter can be one value of @ref DMA2D_Output_Color_Mode. */ - - uint32_t OutputOffset; /*!< Specifies the Offset value. - This parameter must be a number between - Min_Data = 0x0000 and Max_Data = 0x3FFF. */ - - - - -} DMA2D_InitTypeDef; - - -/** - * @brief DMA2D Layer structure definition - */ -typedef struct -{ - uint32_t InputOffset; /*!< Configures the DMA2D foreground or background offset. - This parameter must be a number between - Min_Data = 0x0000 and Max_Data = 0x3FFF. */ - - uint32_t InputColorMode; /*!< Configures the DMA2D foreground or background color mode. - This parameter can be one value of @ref DMA2D_Input_Color_Mode. */ - - uint32_t AlphaMode; /*!< Configures the DMA2D foreground or background alpha mode. - This parameter can be one value of @ref DMA2D_Alpha_Mode. */ - - uint32_t InputAlpha; /*!< Specifies the DMA2D foreground or background alpha value and color value - in case of A8 or A4 color mode. - This parameter must be a number between Min_Data = 0x00 - and Max_Data = 0xFF except for the color modes detailed below. - @note In case of A8 or A4 color mode (ARGB), - this parameter must be a number between - Min_Data = 0x00000000 and Max_Data = 0xFFFFFFFF where - - InputAlpha[24:31] is the alpha value ALPHA[0:7] - - InputAlpha[16:23] is the red value RED[0:7] - - InputAlpha[8:15] is the green value GREEN[0:7] - - InputAlpha[0:7] is the blue value BLUE[0:7]. */ - - -} DMA2D_LayerCfgTypeDef; - -/** - * @brief HAL DMA2D State structures definition - */ -typedef enum -{ - HAL_DMA2D_STATE_RESET = 0x00U, /*!< DMA2D not yet initialized or disabled */ - HAL_DMA2D_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_DMA2D_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */ - HAL_DMA2D_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_DMA2D_STATE_ERROR = 0x04U, /*!< DMA2D state error */ - HAL_DMA2D_STATE_SUSPEND = 0x05U /*!< DMA2D process is suspended */ -} HAL_DMA2D_StateTypeDef; - -/** - * @brief DMA2D handle Structure definition - */ -typedef struct __DMA2D_HandleTypeDef -{ - DMA2D_TypeDef *Instance; /*!< DMA2D register base address. */ - - DMA2D_InitTypeDef Init; /*!< DMA2D communication parameters. */ - - void (* XferCpltCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D transfer complete callback. */ - - void (* XferErrorCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D transfer error callback. */ - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) - void (* LineEventCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D line event callback. */ - - void (* CLUTLoadingCpltCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D CLUT loading completion callback */ - - void (* MspInitCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D Msp Init callback. */ - - void (* MspDeInitCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D Msp DeInit callback. */ - -#endif /* (USE_HAL_DMA2D_REGISTER_CALLBACKS) */ - - DMA2D_LayerCfgTypeDef LayerCfg[MAX_DMA2D_LAYER]; /*!< DMA2D Layers parameters */ - - HAL_LockTypeDef Lock; /*!< DMA2D lock. */ - - __IO HAL_DMA2D_StateTypeDef State; /*!< DMA2D transfer state. */ - - __IO uint32_t ErrorCode; /*!< DMA2D error code. */ -} DMA2D_HandleTypeDef; - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -/** - * @brief HAL DMA2D Callback pointer definition - */ -typedef void (*pDMA2D_CallbackTypeDef)(DMA2D_HandleTypeDef *hdma2d); /*!< Pointer to a DMA2D common callback function */ -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DMA2D_Exported_Constants DMA2D Exported Constants - * @{ - */ - -/** @defgroup DMA2D_Error_Code DMA2D Error Code - * @{ - */ -#define HAL_DMA2D_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_DMA2D_ERROR_TE 0x00000001U /*!< Transfer error */ -#define HAL_DMA2D_ERROR_CE 0x00000002U /*!< Configuration error */ -#define HAL_DMA2D_ERROR_CAE 0x00000004U /*!< CLUT access error */ -#define HAL_DMA2D_ERROR_TIMEOUT 0x00000020U /*!< Timeout error */ -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -#define HAL_DMA2D_ERROR_INVALID_CALLBACK 0x00000040U /*!< Invalid callback error */ -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup DMA2D_Mode DMA2D Mode - * @{ - */ -#define DMA2D_M2M 0x00000000U /*!< DMA2D memory to memory transfer mode */ -#define DMA2D_M2M_PFC DMA2D_CR_MODE_0 /*!< DMA2D memory to memory with pixel format conversion transfer mode */ -#define DMA2D_M2M_BLEND DMA2D_CR_MODE_1 /*!< DMA2D memory to memory with blending transfer mode */ -#define DMA2D_R2M DMA2D_CR_MODE /*!< DMA2D register to memory transfer mode */ -/** - * @} - */ - -/** @defgroup DMA2D_Output_Color_Mode DMA2D Output Color Mode - * @{ - */ -#define DMA2D_OUTPUT_ARGB8888 0x00000000U /*!< ARGB8888 DMA2D color mode */ -#define DMA2D_OUTPUT_RGB888 DMA2D_OPFCCR_CM_0 /*!< RGB888 DMA2D color mode */ -#define DMA2D_OUTPUT_RGB565 DMA2D_OPFCCR_CM_1 /*!< RGB565 DMA2D color mode */ -#define DMA2D_OUTPUT_ARGB1555 (DMA2D_OPFCCR_CM_0|DMA2D_OPFCCR_CM_1) /*!< ARGB1555 DMA2D color mode */ -#define DMA2D_OUTPUT_ARGB4444 DMA2D_OPFCCR_CM_2 /*!< ARGB4444 DMA2D color mode */ -/** - * @} - */ - -/** @defgroup DMA2D_Input_Color_Mode DMA2D Input Color Mode - * @{ - */ -#define DMA2D_INPUT_ARGB8888 0x00000000U /*!< ARGB8888 color mode */ -#define DMA2D_INPUT_RGB888 0x00000001U /*!< RGB888 color mode */ -#define DMA2D_INPUT_RGB565 0x00000002U /*!< RGB565 color mode */ -#define DMA2D_INPUT_ARGB1555 0x00000003U /*!< ARGB1555 color mode */ -#define DMA2D_INPUT_ARGB4444 0x00000004U /*!< ARGB4444 color mode */ -#define DMA2D_INPUT_L8 0x00000005U /*!< L8 color mode */ -#define DMA2D_INPUT_AL44 0x00000006U /*!< AL44 color mode */ -#define DMA2D_INPUT_AL88 0x00000007U /*!< AL88 color mode */ -#define DMA2D_INPUT_L4 0x00000008U /*!< L4 color mode */ -#define DMA2D_INPUT_A8 0x00000009U /*!< A8 color mode */ -#define DMA2D_INPUT_A4 0x0000000AU /*!< A4 color mode */ -/** - * @} - */ - -/** @defgroup DMA2D_Alpha_Mode DMA2D Alpha Mode - * @{ - */ -#define DMA2D_NO_MODIF_ALPHA 0x00000000U /*!< No modification of the alpha channel value */ -#define DMA2D_REPLACE_ALPHA 0x00000001U /*!< Replace original alpha channel value by programmed alpha value */ -#define DMA2D_COMBINE_ALPHA 0x00000002U /*!< Replace original alpha channel value by programmed alpha value - with original alpha channel value */ -/** - * @} - */ - - - - - - -/** @defgroup DMA2D_CLUT_CM DMA2D CLUT Color Mode - * @{ - */ -#define DMA2D_CCM_ARGB8888 0x00000000U /*!< ARGB8888 DMA2D CLUT color mode */ -#define DMA2D_CCM_RGB888 0x00000001U /*!< RGB888 DMA2D CLUT color mode */ -/** - * @} - */ - -/** @defgroup DMA2D_Interrupts DMA2D Interrupts - * @{ - */ -#define DMA2D_IT_CE DMA2D_CR_CEIE /*!< Configuration Error Interrupt */ -#define DMA2D_IT_CTC DMA2D_CR_CTCIE /*!< CLUT Transfer Complete Interrupt */ -#define DMA2D_IT_CAE DMA2D_CR_CAEIE /*!< CLUT Access Error Interrupt */ -#define DMA2D_IT_TW DMA2D_CR_TWIE /*!< Transfer Watermark Interrupt */ -#define DMA2D_IT_TC DMA2D_CR_TCIE /*!< Transfer Complete Interrupt */ -#define DMA2D_IT_TE DMA2D_CR_TEIE /*!< Transfer Error Interrupt */ -/** - * @} - */ - -/** @defgroup DMA2D_Flags DMA2D Flags - * @{ - */ -#define DMA2D_FLAG_CE DMA2D_ISR_CEIF /*!< Configuration Error Interrupt Flag */ -#define DMA2D_FLAG_CTC DMA2D_ISR_CTCIF /*!< CLUT Transfer Complete Interrupt Flag */ -#define DMA2D_FLAG_CAE DMA2D_ISR_CAEIF /*!< CLUT Access Error Interrupt Flag */ -#define DMA2D_FLAG_TW DMA2D_ISR_TWIF /*!< Transfer Watermark Interrupt Flag */ -#define DMA2D_FLAG_TC DMA2D_ISR_TCIF /*!< Transfer Complete Interrupt Flag */ -#define DMA2D_FLAG_TE DMA2D_ISR_TEIF /*!< Transfer Error Interrupt Flag */ -/** - * @} - */ - -/** @defgroup DMA2D_Aliases DMA2D API Aliases - * @{ - */ -#define HAL_DMA2D_DisableCLUT HAL_DMA2D_CLUTLoading_Abort /*!< Aliased to HAL_DMA2D_CLUTLoading_Abort - for compatibility with legacy code */ -/** - * @} - */ - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -/** - * @brief HAL DMA2D common Callback ID enumeration definition - */ -typedef enum -{ - HAL_DMA2D_MSPINIT_CB_ID = 0x00U, /*!< DMA2D MspInit callback ID */ - HAL_DMA2D_MSPDEINIT_CB_ID = 0x01U, /*!< DMA2D MspDeInit callback ID */ - HAL_DMA2D_TRANSFERCOMPLETE_CB_ID = 0x02U, /*!< DMA2D transfer complete callback ID */ - HAL_DMA2D_TRANSFERERROR_CB_ID = 0x03U, /*!< DMA2D transfer error callback ID */ - HAL_DMA2D_LINEEVENT_CB_ID = 0x04U, /*!< DMA2D line event callback ID */ - HAL_DMA2D_CLUTLOADINGCPLT_CB_ID = 0x05U, /*!< DMA2D CLUT loading completion callback ID */ -} HAL_DMA2D_CallbackIDTypeDef; -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - - -/** - * @} - */ -/* Exported macros ------------------------------------------------------------*/ -/** @defgroup DMA2D_Exported_Macros DMA2D Exported Macros - * @{ - */ - -/** @brief Reset DMA2D handle state - * @param __HANDLE__ specifies the DMA2D handle. - * @retval None - */ -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -#define __HAL_DMA2D_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DMA2D_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - }while(0) -#else -#define __HAL_DMA2D_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DMA2D_STATE_RESET) -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - - -/** - * @brief Enable the DMA2D. - * @param __HANDLE__ DMA2D handle - * @retval None. - */ -#define __HAL_DMA2D_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= DMA2D_CR_START) - - -/* Interrupt & Flag management */ -/** - * @brief Get the DMA2D pending flags. - * @param __HANDLE__ DMA2D handle - * @param __FLAG__ flag to check. - * This parameter can be any combination of the following values: - * @arg DMA2D_FLAG_CE: Configuration error flag - * @arg DMA2D_FLAG_CTC: CLUT transfer complete flag - * @arg DMA2D_FLAG_CAE: CLUT access error flag - * @arg DMA2D_FLAG_TW: Transfer Watermark flag - * @arg DMA2D_FLAG_TC: Transfer complete flag - * @arg DMA2D_FLAG_TE: Transfer error flag - * @retval The state of FLAG. - */ -#define __HAL_DMA2D_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR & (__FLAG__)) - -/** - * @brief Clear the DMA2D pending flags. - * @param __HANDLE__ DMA2D handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DMA2D_FLAG_CE: Configuration error flag - * @arg DMA2D_FLAG_CTC: CLUT transfer complete flag - * @arg DMA2D_FLAG_CAE: CLUT access error flag - * @arg DMA2D_FLAG_TW: Transfer Watermark flag - * @arg DMA2D_FLAG_TC: Transfer complete flag - * @arg DMA2D_FLAG_TE: Transfer error flag - * @retval None - */ -#define __HAL_DMA2D_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->IFCR = (__FLAG__)) - -/** - * @brief Enable the specified DMA2D interrupts. - * @param __HANDLE__ DMA2D handle - * @param __INTERRUPT__ specifies the DMA2D interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg DMA2D_IT_CE: Configuration error interrupt mask - * @arg DMA2D_IT_CTC: CLUT transfer complete interrupt mask - * @arg DMA2D_IT_CAE: CLUT access error interrupt mask - * @arg DMA2D_IT_TW: Transfer Watermark interrupt mask - * @arg DMA2D_IT_TC: Transfer complete interrupt mask - * @arg DMA2D_IT_TE: Transfer error interrupt mask - * @retval None - */ -#define __HAL_DMA2D_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the specified DMA2D interrupts. - * @param __HANDLE__ DMA2D handle - * @param __INTERRUPT__ specifies the DMA2D interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg DMA2D_IT_CE: Configuration error interrupt mask - * @arg DMA2D_IT_CTC: CLUT transfer complete interrupt mask - * @arg DMA2D_IT_CAE: CLUT access error interrupt mask - * @arg DMA2D_IT_TW: Transfer Watermark interrupt mask - * @arg DMA2D_IT_TC: Transfer complete interrupt mask - * @arg DMA2D_IT_TE: Transfer error interrupt mask - * @retval None - */ -#define __HAL_DMA2D_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified DMA2D interrupt source is enabled or not. - * @param __HANDLE__ DMA2D handle - * @param __INTERRUPT__ specifies the DMA2D interrupt source to check. - * This parameter can be one of the following values: - * @arg DMA2D_IT_CE: Configuration error interrupt mask - * @arg DMA2D_IT_CTC: CLUT transfer complete interrupt mask - * @arg DMA2D_IT_CAE: CLUT access error interrupt mask - * @arg DMA2D_IT_TW: Transfer Watermark interrupt mask - * @arg DMA2D_IT_TC: Transfer complete interrupt mask - * @arg DMA2D_IT_TE: Transfer error interrupt mask - * @retval The state of INTERRUPT source. - */ -#define __HAL_DMA2D_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR & (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DMA2D_Exported_Functions DMA2D Exported Functions - * @{ - */ - -/** @addtogroup DMA2D_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization and de-initialization functions *******************************/ -HAL_StatusTypeDef HAL_DMA2D_Init(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_DeInit(DMA2D_HandleTypeDef *hdma2d); -void HAL_DMA2D_MspInit(DMA2D_HandleTypeDef *hdma2d); -void HAL_DMA2D_MspDeInit(DMA2D_HandleTypeDef *hdma2d); -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_DMA2D_RegisterCallback(DMA2D_HandleTypeDef *hdma2d, HAL_DMA2D_CallbackIDTypeDef CallbackID, - pDMA2D_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DMA2D_UnRegisterCallback(DMA2D_HandleTypeDef *hdma2d, HAL_DMA2D_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - -/** - * @} - */ - - -/** @addtogroup DMA2D_Exported_Functions_Group2 IO operation functions - * @{ - */ - -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_DMA2D_Start(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, - uint32_t Height); -HAL_StatusTypeDef HAL_DMA2D_BlendingStart(DMA2D_HandleTypeDef *hdma2d, uint32_t SrcAddress1, uint32_t SrcAddress2, - uint32_t DstAddress, uint32_t Width, uint32_t Height); -HAL_StatusTypeDef HAL_DMA2D_Start_IT(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, - uint32_t Height); -HAL_StatusTypeDef HAL_DMA2D_BlendingStart_IT(DMA2D_HandleTypeDef *hdma2d, uint32_t SrcAddress1, uint32_t SrcAddress2, - uint32_t DstAddress, uint32_t Width, uint32_t Height); -HAL_StatusTypeDef HAL_DMA2D_Suspend(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_Resume(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_Abort(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_EnableCLUT(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTStartLoad(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef *CLUTCfg, - uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTStartLoad_IT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef *CLUTCfg, - uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoad(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoad_IT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Abort(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Suspend(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Resume(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_PollForTransfer(DMA2D_HandleTypeDef *hdma2d, uint32_t Timeout); -void HAL_DMA2D_IRQHandler(DMA2D_HandleTypeDef *hdma2d); -void HAL_DMA2D_LineEventCallback(DMA2D_HandleTypeDef *hdma2d); -void HAL_DMA2D_CLUTLoadingCpltCallback(DMA2D_HandleTypeDef *hdma2d); - -/** - * @} - */ - -/** @addtogroup DMA2D_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ - -/* Peripheral Control functions *************************************************/ -HAL_StatusTypeDef HAL_DMA2D_ConfigLayer(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_ConfigCLUT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_ProgramLineEvent(DMA2D_HandleTypeDef *hdma2d, uint32_t Line); -HAL_StatusTypeDef HAL_DMA2D_EnableDeadTime(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_DisableDeadTime(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_ConfigDeadTime(DMA2D_HandleTypeDef *hdma2d, uint8_t DeadTime); - -/** - * @} - */ - -/** @addtogroup DMA2D_Exported_Functions_Group4 Peripheral State and Error functions - * @{ - */ - -/* Peripheral State functions ***************************************************/ -HAL_DMA2D_StateTypeDef HAL_DMA2D_GetState(DMA2D_HandleTypeDef *hdma2d); -uint32_t HAL_DMA2D_GetError(DMA2D_HandleTypeDef *hdma2d); - -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ - -/** @addtogroup DMA2D_Private_Constants DMA2D Private Constants - * @{ - */ - -/** @defgroup DMA2D_Maximum_Line_WaterMark DMA2D Maximum Line Watermark - * @{ - */ -#define DMA2D_LINE_WATERMARK_MAX DMA2D_LWR_LW /*!< DMA2D maximum line watermark */ -/** - * @} - */ - -/** @defgroup DMA2D_Color_Value DMA2D Color Value - * @{ - */ -#define DMA2D_COLOR_VALUE 0x000000FFU /*!< Color value mask */ -/** - * @} - */ - -/** @defgroup DMA2D_Max_Layer DMA2D Maximum Number of Layers - * @{ - */ -#define DMA2D_MAX_LAYER 2U /*!< DMA2D maximum number of layers */ -/** - * @} - */ - -/** @defgroup DMA2D_Layers DMA2D Layers - * @{ - */ -#define DMA2D_BACKGROUND_LAYER 0x00000000U /*!< DMA2D Background Layer (layer 0) */ -#define DMA2D_FOREGROUND_LAYER 0x00000001U /*!< DMA2D Foreground Layer (layer 1) */ -/** - * @} - */ - -/** @defgroup DMA2D_Offset DMA2D Offset - * @{ - */ -#define DMA2D_OFFSET DMA2D_FGOR_LO /*!< maximum Line Offset */ -/** - * @} - */ - -/** @defgroup DMA2D_Size DMA2D Size - * @{ - */ -#define DMA2D_PIXEL (DMA2D_NLR_PL >> 16U) /*!< DMA2D maximum number of pixels per line */ -#define DMA2D_LINE DMA2D_NLR_NL /*!< DMA2D maximum number of lines */ -/** - * @} - */ - -/** @defgroup DMA2D_CLUT_Size DMA2D CLUT Size - * @{ - */ -#define DMA2D_CLUT_SIZE (DMA2D_FGPFCCR_CS >> 8U) /*!< DMA2D maximum CLUT size */ -/** - * @} - */ - -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DMA2D_Private_Macros DMA2D Private Macros - * @{ - */ -#define IS_DMA2D_LAYER(LAYER) (((LAYER) == DMA2D_BACKGROUND_LAYER)\ - || ((LAYER) == DMA2D_FOREGROUND_LAYER)) - -#define IS_DMA2D_MODE(MODE) (((MODE) == DMA2D_M2M) || ((MODE) == DMA2D_M2M_PFC) || \ - ((MODE) == DMA2D_M2M_BLEND) || ((MODE) == DMA2D_R2M)) - -#define IS_DMA2D_CMODE(MODE_ARGB) (((MODE_ARGB) == DMA2D_OUTPUT_ARGB8888) || \ - ((MODE_ARGB) == DMA2D_OUTPUT_RGB888) || \ - ((MODE_ARGB) == DMA2D_OUTPUT_RGB565) || \ - ((MODE_ARGB) == DMA2D_OUTPUT_ARGB1555) || \ - ((MODE_ARGB) == DMA2D_OUTPUT_ARGB4444)) - -#define IS_DMA2D_COLOR(COLOR) ((COLOR) <= DMA2D_COLOR_VALUE) -#define IS_DMA2D_LINE(LINE) ((LINE) <= DMA2D_LINE) -#define IS_DMA2D_PIXEL(PIXEL) ((PIXEL) <= DMA2D_PIXEL) -#define IS_DMA2D_OFFSET(OOFFSET) ((OOFFSET) <= DMA2D_OFFSET) - -#define IS_DMA2D_INPUT_COLOR_MODE(INPUT_CM) (((INPUT_CM) == DMA2D_INPUT_ARGB8888) || \ - ((INPUT_CM) == DMA2D_INPUT_RGB888) || \ - ((INPUT_CM) == DMA2D_INPUT_RGB565) || \ - ((INPUT_CM) == DMA2D_INPUT_ARGB1555) || \ - ((INPUT_CM) == DMA2D_INPUT_ARGB4444) || \ - ((INPUT_CM) == DMA2D_INPUT_L8) || \ - ((INPUT_CM) == DMA2D_INPUT_AL44) || \ - ((INPUT_CM) == DMA2D_INPUT_AL88) || \ - ((INPUT_CM) == DMA2D_INPUT_L4) || \ - ((INPUT_CM) == DMA2D_INPUT_A8) || \ - ((INPUT_CM) == DMA2D_INPUT_A4)) - -#define IS_DMA2D_ALPHA_MODE(AlphaMode) (((AlphaMode) == DMA2D_NO_MODIF_ALPHA) || \ - ((AlphaMode) == DMA2D_REPLACE_ALPHA) || \ - ((AlphaMode) == DMA2D_COMBINE_ALPHA)) - - - - - -#define IS_DMA2D_CLUT_CM(CLUT_CM) (((CLUT_CM) == DMA2D_CCM_ARGB8888) || ((CLUT_CM) == DMA2D_CCM_RGB888)) -#define IS_DMA2D_CLUT_SIZE(CLUT_SIZE) ((CLUT_SIZE) <= DMA2D_CLUT_SIZE) -#define IS_DMA2D_LINEWATERMARK(LineWatermark) ((LineWatermark) <= DMA2D_LINE_WATERMARK_MAX) -#define IS_DMA2D_IT(IT) (((IT) == DMA2D_IT_CTC) || ((IT) == DMA2D_IT_CAE) || \ - ((IT) == DMA2D_IT_TW) || ((IT) == DMA2D_IT_TC) || \ - ((IT) == DMA2D_IT_TE) || ((IT) == DMA2D_IT_CE)) -#define IS_DMA2D_GET_FLAG(FLAG) (((FLAG) == DMA2D_FLAG_CTC) || ((FLAG) == DMA2D_FLAG_CAE) || \ - ((FLAG) == DMA2D_FLAG_TW) || ((FLAG) == DMA2D_FLAG_TC) || \ - ((FLAG) == DMA2D_FLAG_TE) || ((FLAG) == DMA2D_FLAG_CE)) -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (DMA2D) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_DMA2D_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h deleted file mode 100644 index 2e60aff2ffe6bfd..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h +++ /dev/null @@ -1,104 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma_ex.h - * @author MCD Application Team - * @brief Header file of DMA HAL extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DMA_EX_H -#define __STM32F4xx_HAL_DMA_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DMAEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DMAEx_Exported_Types DMAEx Exported Types - * @brief DMAEx Exported types - * @{ - */ - -/** - * @brief HAL DMA Memory definition - */ -typedef enum -{ - MEMORY0 = 0x00U, /*!< Memory 0 */ - MEMORY1 = 0x01U /*!< Memory 1 */ -}HAL_DMA_MemoryTypeDef; - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DMAEx_Exported_Functions DMAEx Exported Functions - * @brief DMAEx Exported functions - * @{ - */ - -/** @defgroup DMAEx_Exported_Functions_Group1 Extended features functions - * @brief Extended features functions - * @{ - */ - -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory); - -/** - * @} - */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DMAEx_Private_Functions DMAEx Private Functions - * @brief DMAEx Private functions - * @{ - */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F4xx_HAL_DMA_EX_H*/ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dsi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dsi.h deleted file mode 100644 index 716dea17dafc2e0..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dsi.h +++ /dev/null @@ -1,1353 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dsi.h - * @author MCD Application Team - * @brief Header file of DSI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_DSI_H -#define STM32F4xx_HAL_DSI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(DSI) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup DSI DSI - * @brief DSI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** - * @brief DSI Init Structure definition - */ -typedef struct -{ - uint32_t AutomaticClockLaneControl; /*!< Automatic clock lane control - This parameter can be any value of @ref DSI_Automatic_Clk_Lane_Control */ - - uint32_t TXEscapeCkdiv; /*!< TX Escape clock division - The values 0 and 1 stop the TX_ESC clock generation */ - - uint32_t NumberOfLanes; /*!< Number of lanes - This parameter can be any value of @ref DSI_Number_Of_Lanes */ - -} DSI_InitTypeDef; - -/** - * @brief DSI PLL Clock structure definition - */ -typedef struct -{ - uint32_t PLLNDIV; /*!< PLL Loop Division Factor - This parameter must be a value between 10 and 125 */ - - uint32_t PLLIDF; /*!< PLL Input Division Factor - This parameter can be any value of @ref DSI_PLL_IDF */ - - uint32_t PLLODF; /*!< PLL Output Division Factor - This parameter can be any value of @ref DSI_PLL_ODF */ - -} DSI_PLLInitTypeDef; - -/** - * @brief DSI Video mode configuration - */ -typedef struct -{ - uint32_t VirtualChannelID; /*!< Virtual channel ID */ - - uint32_t ColorCoding; /*!< Color coding for LTDC interface - This parameter can be any value of @ref DSI_Color_Coding */ - - uint32_t LooselyPacked; /*!< Enable or disable loosely packed stream (needed only when using - 18-bit configuration). - This parameter can be any value of @ref DSI_LooselyPacked */ - - uint32_t Mode; /*!< Video mode type - This parameter can be any value of @ref DSI_Video_Mode_Type */ - - uint32_t PacketSize; /*!< Video packet size */ - - uint32_t NumberOfChunks; /*!< Number of chunks */ - - uint32_t NullPacketSize; /*!< Null packet size */ - - uint32_t HSPolarity; /*!< HSYNC pin polarity - This parameter can be any value of @ref DSI_HSYNC_Polarity */ - - uint32_t VSPolarity; /*!< VSYNC pin polarity - This parameter can be any value of @ref DSI_VSYNC_Active_Polarity */ - - uint32_t DEPolarity; /*!< Data Enable pin polarity - This parameter can be any value of @ref DSI_DATA_ENABLE_Polarity */ - - uint32_t HorizontalSyncActive; /*!< Horizontal synchronism active duration (in lane byte clock cycles) */ - - uint32_t HorizontalBackPorch; /*!< Horizontal back-porch duration (in lane byte clock cycles) */ - - uint32_t HorizontalLine; /*!< Horizontal line duration (in lane byte clock cycles) */ - - uint32_t VerticalSyncActive; /*!< Vertical synchronism active duration */ - - uint32_t VerticalBackPorch; /*!< Vertical back-porch duration */ - - uint32_t VerticalFrontPorch; /*!< Vertical front-porch duration */ - - uint32_t VerticalActive; /*!< Vertical active duration */ - - uint32_t LPCommandEnable; /*!< Low-power command enable - This parameter can be any value of @ref DSI_LP_Command */ - - uint32_t LPLargestPacketSize; /*!< The size, in bytes, of the low power largest packet that - can fit in a line during VSA, VBP and VFP regions */ - - uint32_t LPVACTLargestPacketSize; /*!< The size, in bytes, of the low power largest packet that - can fit in a line during VACT region */ - - uint32_t LPHorizontalFrontPorchEnable; /*!< Low-power horizontal front-porch enable - This parameter can be any value of @ref DSI_LP_HFP */ - - uint32_t LPHorizontalBackPorchEnable; /*!< Low-power horizontal back-porch enable - This parameter can be any value of @ref DSI_LP_HBP */ - - uint32_t LPVerticalActiveEnable; /*!< Low-power vertical active enable - This parameter can be any value of @ref DSI_LP_VACT */ - - uint32_t LPVerticalFrontPorchEnable; /*!< Low-power vertical front-porch enable - This parameter can be any value of @ref DSI_LP_VFP */ - - uint32_t LPVerticalBackPorchEnable; /*!< Low-power vertical back-porch enable - This parameter can be any value of @ref DSI_LP_VBP */ - - uint32_t LPVerticalSyncActiveEnable; /*!< Low-power vertical sync active enable - This parameter can be any value of @ref DSI_LP_VSYNC */ - - uint32_t FrameBTAAcknowledgeEnable; /*!< Frame bus-turn-around acknowledge enable - This parameter can be any value of @ref DSI_FBTA_acknowledge */ - -} DSI_VidCfgTypeDef; - -/** - * @brief DSI Adapted command mode configuration - */ -typedef struct -{ - uint32_t VirtualChannelID; /*!< Virtual channel ID */ - - uint32_t ColorCoding; /*!< Color coding for LTDC interface - This parameter can be any value of @ref DSI_Color_Coding */ - - uint32_t CommandSize; /*!< Maximum allowed size for an LTDC write memory command, measured in - pixels. This parameter can be any value between 0x00 and 0xFFFFU */ - - uint32_t TearingEffectSource; /*!< Tearing effect source - This parameter can be any value of @ref DSI_TearingEffectSource */ - - uint32_t TearingEffectPolarity; /*!< Tearing effect pin polarity - This parameter can be any value of @ref DSI_TearingEffectPolarity */ - - uint32_t HSPolarity; /*!< HSYNC pin polarity - This parameter can be any value of @ref DSI_HSYNC_Polarity */ - - uint32_t VSPolarity; /*!< VSYNC pin polarity - This parameter can be any value of @ref DSI_VSYNC_Active_Polarity */ - - uint32_t DEPolarity; /*!< Data Enable pin polarity - This parameter can be any value of @ref DSI_DATA_ENABLE_Polarity */ - - uint32_t VSyncPol; /*!< VSync edge on which the LTDC is halted - This parameter can be any value of @ref DSI_Vsync_Polarity */ - - uint32_t AutomaticRefresh; /*!< Automatic refresh mode - This parameter can be any value of @ref DSI_AutomaticRefresh */ - - uint32_t TEAcknowledgeRequest; /*!< Tearing Effect Acknowledge Request Enable - This parameter can be any value of @ref DSI_TE_AcknowledgeRequest */ - -} DSI_CmdCfgTypeDef; - -/** - * @brief DSI command transmission mode configuration - */ -typedef struct -{ - uint32_t LPGenShortWriteNoP; /*!< Generic Short Write Zero parameters Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortWriteNoP */ - - uint32_t LPGenShortWriteOneP; /*!< Generic Short Write One parameter Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortWriteOneP */ - - uint32_t LPGenShortWriteTwoP; /*!< Generic Short Write Two parameters Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortWriteTwoP */ - - uint32_t LPGenShortReadNoP; /*!< Generic Short Read Zero parameters Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortReadNoP */ - - uint32_t LPGenShortReadOneP; /*!< Generic Short Read One parameter Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortReadOneP */ - - uint32_t LPGenShortReadTwoP; /*!< Generic Short Read Two parameters Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortReadTwoP */ - - uint32_t LPGenLongWrite; /*!< Generic Long Write Transmission - This parameter can be any value of @ref DSI_LP_LPGenLongWrite */ - - uint32_t LPDcsShortWriteNoP; /*!< DCS Short Write Zero parameters Transmission - This parameter can be any value of @ref DSI_LP_LPDcsShortWriteNoP */ - - uint32_t LPDcsShortWriteOneP; /*!< DCS Short Write One parameter Transmission - This parameter can be any value of @ref DSI_LP_LPDcsShortWriteOneP */ - - uint32_t LPDcsShortReadNoP; /*!< DCS Short Read Zero parameters Transmission - This parameter can be any value of @ref DSI_LP_LPDcsShortReadNoP */ - - uint32_t LPDcsLongWrite; /*!< DCS Long Write Transmission - This parameter can be any value of @ref DSI_LP_LPDcsLongWrite */ - - uint32_t LPMaxReadPacket; /*!< Maximum Read Packet Size Transmission - This parameter can be any value of @ref DSI_LP_LPMaxReadPacket */ - - uint32_t AcknowledgeRequest; /*!< Acknowledge Request Enable - This parameter can be any value of @ref DSI_AcknowledgeRequest */ - -} DSI_LPCmdTypeDef; - -/** - * @brief DSI PHY Timings definition - */ -typedef struct -{ - uint32_t ClockLaneHS2LPTime; /*!< The maximum time that the D-PHY clock lane takes to go from high-speed - to low-power transmission */ - - uint32_t ClockLaneLP2HSTime; /*!< The maximum time that the D-PHY clock lane takes to go from low-power - to high-speed transmission */ - - uint32_t DataLaneHS2LPTime; /*!< The maximum time that the D-PHY data lanes takes to go from high-speed - to low-power transmission */ - - uint32_t DataLaneLP2HSTime; /*!< The maximum time that the D-PHY data lanes takes to go from low-power - to high-speed transmission */ - - uint32_t DataLaneMaxReadTime; /*!< The maximum time required to perform a read command */ - - uint32_t StopWaitTime; /*!< The minimum wait period to request a High-Speed transmission after the - Stop state */ - -} DSI_PHY_TimerTypeDef; - -/** - * @brief DSI HOST Timeouts definition - */ -typedef struct -{ - uint32_t TimeoutCkdiv; /*!< Time-out clock division */ - - uint32_t HighSpeedTransmissionTimeout; /*!< High-speed transmission time-out */ - - uint32_t LowPowerReceptionTimeout; /*!< Low-power reception time-out */ - - uint32_t HighSpeedReadTimeout; /*!< High-speed read time-out */ - - uint32_t LowPowerReadTimeout; /*!< Low-power read time-out */ - - uint32_t HighSpeedWriteTimeout; /*!< High-speed write time-out */ - - uint32_t HighSpeedWritePrespMode; /*!< High-speed write presp mode - This parameter can be any value of @ref DSI_HS_PrespMode */ - - uint32_t LowPowerWriteTimeout; /*!< Low-speed write time-out */ - - uint32_t BTATimeout; /*!< BTA time-out */ - -} DSI_HOST_TimeoutTypeDef; - -/** - * @brief DSI States Structure definition - */ -typedef enum -{ - HAL_DSI_STATE_RESET = 0x00U, - HAL_DSI_STATE_READY = 0x01U, - HAL_DSI_STATE_ERROR = 0x02U, - HAL_DSI_STATE_BUSY = 0x03U, - HAL_DSI_STATE_TIMEOUT = 0x04U -} HAL_DSI_StateTypeDef; - -/** - * @brief DSI Handle Structure definition - */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -typedef struct __DSI_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ -{ - DSI_TypeDef *Instance; /*!< Register base address */ - DSI_InitTypeDef Init; /*!< DSI required parameters */ - HAL_LockTypeDef Lock; /*!< DSI peripheral status */ - __IO HAL_DSI_StateTypeDef State; /*!< DSI communication state */ - __IO uint32_t ErrorCode; /*!< DSI Error code */ - uint32_t ErrorMsk; /*!< DSI Error monitoring mask */ - -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) - void (* TearingEffectCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI Tearing Effect Callback */ - void (* EndOfRefreshCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI End Of Refresh Callback */ - void (* ErrorCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI Error Callback */ - - void (* MspInitCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI Msp Init callback */ - void (* MspDeInitCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI Msp DeInit callback */ - -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - -} DSI_HandleTypeDef; - -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -/** - * @brief HAL DSI Callback ID enumeration definition - */ -typedef enum -{ - HAL_DSI_MSPINIT_CB_ID = 0x00U, /*!< DSI MspInit callback ID */ - HAL_DSI_MSPDEINIT_CB_ID = 0x01U, /*!< DSI MspDeInit callback ID */ - - HAL_DSI_TEARING_EFFECT_CB_ID = 0x02U, /*!< DSI Tearing Effect Callback ID */ - HAL_DSI_ENDOF_REFRESH_CB_ID = 0x03U, /*!< DSI End Of Refresh Callback ID */ - HAL_DSI_ERROR_CB_ID = 0x04U /*!< DSI Error Callback ID */ - -} HAL_DSI_CallbackIDTypeDef; - -/** - * @brief HAL DSI Callback pointer definition - */ -typedef void (*pDSI_CallbackTypeDef)(DSI_HandleTypeDef *hdsi); /*!< pointer to an DSI callback function */ - -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DSI_Exported_Constants DSI Exported Constants - * @{ - */ -/** @defgroup DSI_DCS_Command DSI DCS Command - * @{ - */ -#define DSI_ENTER_IDLE_MODE 0x39U -#define DSI_ENTER_INVERT_MODE 0x21U -#define DSI_ENTER_NORMAL_MODE 0x13U -#define DSI_ENTER_PARTIAL_MODE 0x12U -#define DSI_ENTER_SLEEP_MODE 0x10U -#define DSI_EXIT_IDLE_MODE 0x38U -#define DSI_EXIT_INVERT_MODE 0x20U -#define DSI_EXIT_SLEEP_MODE 0x11U -#define DSI_GET_3D_CONTROL 0x3FU -#define DSI_GET_ADDRESS_MODE 0x0BU -#define DSI_GET_BLUE_CHANNEL 0x08U -#define DSI_GET_DIAGNOSTIC_RESULT 0x0FU -#define DSI_GET_DISPLAY_MODE 0x0DU -#define DSI_GET_GREEN_CHANNEL 0x07U -#define DSI_GET_PIXEL_FORMAT 0x0CU -#define DSI_GET_POWER_MODE 0x0AU -#define DSI_GET_RED_CHANNEL 0x06U -#define DSI_GET_SCANLINE 0x45U -#define DSI_GET_SIGNAL_MODE 0x0EU -#define DSI_NOP 0x00U -#define DSI_READ_DDB_CONTINUE 0xA8U -#define DSI_READ_DDB_START 0xA1U -#define DSI_READ_MEMORY_CONTINUE 0x3EU -#define DSI_READ_MEMORY_START 0x2EU -#define DSI_SET_3D_CONTROL 0x3DU -#define DSI_SET_ADDRESS_MODE 0x36U -#define DSI_SET_COLUMN_ADDRESS 0x2AU -#define DSI_SET_DISPLAY_OFF 0x28U -#define DSI_SET_DISPLAY_ON 0x29U -#define DSI_SET_GAMMA_CURVE 0x26U -#define DSI_SET_PAGE_ADDRESS 0x2BU -#define DSI_SET_PARTIAL_COLUMNS 0x31U -#define DSI_SET_PARTIAL_ROWS 0x30U -#define DSI_SET_PIXEL_FORMAT 0x3AU -#define DSI_SET_SCROLL_AREA 0x33U -#define DSI_SET_SCROLL_START 0x37U -#define DSI_SET_TEAR_OFF 0x34U -#define DSI_SET_TEAR_ON 0x35U -#define DSI_SET_TEAR_SCANLINE 0x44U -#define DSI_SET_VSYNC_TIMING 0x40U -#define DSI_SOFT_RESET 0x01U -#define DSI_WRITE_LUT 0x2DU -#define DSI_WRITE_MEMORY_CONTINUE 0x3CU -#define DSI_WRITE_MEMORY_START 0x2CU -/** - * @} - */ - -/** @defgroup DSI_Video_Mode_Type DSI Video Mode Type - * @{ - */ -#define DSI_VID_MODE_NB_PULSES 0U -#define DSI_VID_MODE_NB_EVENTS 1U -#define DSI_VID_MODE_BURST 2U -/** - * @} - */ - -/** @defgroup DSI_Color_Mode DSI Color Mode - * @{ - */ -#define DSI_COLOR_MODE_FULL 0x00000000U -#define DSI_COLOR_MODE_EIGHT DSI_WCR_COLM -/** - * @} - */ - -/** @defgroup DSI_ShutDown DSI ShutDown - * @{ - */ -#define DSI_DISPLAY_ON 0x00000000U -#define DSI_DISPLAY_OFF DSI_WCR_SHTDN -/** - * @} - */ - -/** @defgroup DSI_LP_Command DSI LP Command - * @{ - */ -#define DSI_LP_COMMAND_DISABLE 0x00000000U -#define DSI_LP_COMMAND_ENABLE DSI_VMCR_LPCE -/** - * @} - */ - -/** @defgroup DSI_LP_HFP DSI LP HFP - * @{ - */ -#define DSI_LP_HFP_DISABLE 0x00000000U -#define DSI_LP_HFP_ENABLE DSI_VMCR_LPHFPE -/** - * @} - */ - -/** @defgroup DSI_LP_HBP DSI LP HBP - * @{ - */ -#define DSI_LP_HBP_DISABLE 0x00000000U -#define DSI_LP_HBP_ENABLE DSI_VMCR_LPHBPE -/** - * @} - */ - -/** @defgroup DSI_LP_VACT DSI LP VACT - * @{ - */ -#define DSI_LP_VACT_DISABLE 0x00000000U -#define DSI_LP_VACT_ENABLE DSI_VMCR_LPVAE -/** - * @} - */ - -/** @defgroup DSI_LP_VFP DSI LP VFP - * @{ - */ -#define DSI_LP_VFP_DISABLE 0x00000000U -#define DSI_LP_VFP_ENABLE DSI_VMCR_LPVFPE -/** - * @} - */ - -/** @defgroup DSI_LP_VBP DSI LP VBP - * @{ - */ -#define DSI_LP_VBP_DISABLE 0x00000000U -#define DSI_LP_VBP_ENABLE DSI_VMCR_LPVBPE -/** - * @} - */ - -/** @defgroup DSI_LP_VSYNC DSI LP VSYNC - * @{ - */ -#define DSI_LP_VSYNC_DISABLE 0x00000000U -#define DSI_LP_VSYNC_ENABLE DSI_VMCR_LPVSAE -/** - * @} - */ - -/** @defgroup DSI_FBTA_acknowledge DSI FBTA Acknowledge - * @{ - */ -#define DSI_FBTAA_DISABLE 0x00000000U -#define DSI_FBTAA_ENABLE DSI_VMCR_FBTAAE -/** - * @} - */ - -/** @defgroup DSI_TearingEffectSource DSI Tearing Effect Source - * @{ - */ -#define DSI_TE_DSILINK 0x00000000U -#define DSI_TE_EXTERNAL DSI_WCFGR_TESRC -/** - * @} - */ - -/** @defgroup DSI_TearingEffectPolarity DSI Tearing Effect Polarity - * @{ - */ -#define DSI_TE_RISING_EDGE 0x00000000U -#define DSI_TE_FALLING_EDGE DSI_WCFGR_TEPOL -/** - * @} - */ - -/** @defgroup DSI_Vsync_Polarity DSI Vsync Polarity - * @{ - */ -#define DSI_VSYNC_FALLING 0x00000000U -#define DSI_VSYNC_RISING DSI_WCFGR_VSPOL -/** - * @} - */ - -/** @defgroup DSI_AutomaticRefresh DSI Automatic Refresh - * @{ - */ -#define DSI_AR_DISABLE 0x00000000U -#define DSI_AR_ENABLE DSI_WCFGR_AR -/** - * @} - */ - -/** @defgroup DSI_TE_AcknowledgeRequest DSI TE Acknowledge Request - * @{ - */ -#define DSI_TE_ACKNOWLEDGE_DISABLE 0x00000000U -#define DSI_TE_ACKNOWLEDGE_ENABLE DSI_CMCR_TEARE -/** - * @} - */ - -/** @defgroup DSI_AcknowledgeRequest DSI Acknowledge Request - * @{ - */ -#define DSI_ACKNOWLEDGE_DISABLE 0x00000000U -#define DSI_ACKNOWLEDGE_ENABLE DSI_CMCR_ARE -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortWriteNoP DSI LP LPGen Short Write NoP - * @{ - */ -#define DSI_LP_GSW0P_DISABLE 0x00000000U -#define DSI_LP_GSW0P_ENABLE DSI_CMCR_GSW0TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortWriteOneP DSI LP LPGen Short Write OneP - * @{ - */ -#define DSI_LP_GSW1P_DISABLE 0x00000000U -#define DSI_LP_GSW1P_ENABLE DSI_CMCR_GSW1TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortWriteTwoP DSI LP LPGen Short Write TwoP - * @{ - */ -#define DSI_LP_GSW2P_DISABLE 0x00000000U -#define DSI_LP_GSW2P_ENABLE DSI_CMCR_GSW2TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortReadNoP DSI LP LPGen Short Read NoP - * @{ - */ -#define DSI_LP_GSR0P_DISABLE 0x00000000U -#define DSI_LP_GSR0P_ENABLE DSI_CMCR_GSR0TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortReadOneP DSI LP LPGen Short Read OneP - * @{ - */ -#define DSI_LP_GSR1P_DISABLE 0x00000000U -#define DSI_LP_GSR1P_ENABLE DSI_CMCR_GSR1TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortReadTwoP DSI LP LPGen Short Read TwoP - * @{ - */ -#define DSI_LP_GSR2P_DISABLE 0x00000000U -#define DSI_LP_GSR2P_ENABLE DSI_CMCR_GSR2TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenLongWrite DSI LP LPGen LongWrite - * @{ - */ -#define DSI_LP_GLW_DISABLE 0x00000000U -#define DSI_LP_GLW_ENABLE DSI_CMCR_GLWTX -/** - * @} - */ - -/** @defgroup DSI_LP_LPDcsShortWriteNoP DSI LP LPDcs Short Write NoP - * @{ - */ -#define DSI_LP_DSW0P_DISABLE 0x00000000U -#define DSI_LP_DSW0P_ENABLE DSI_CMCR_DSW0TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPDcsShortWriteOneP DSI LP LPDcs Short Write OneP - * @{ - */ -#define DSI_LP_DSW1P_DISABLE 0x00000000U -#define DSI_LP_DSW1P_ENABLE DSI_CMCR_DSW1TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPDcsShortReadNoP DSI LP LPDcs Short Read NoP - * @{ - */ -#define DSI_LP_DSR0P_DISABLE 0x00000000U -#define DSI_LP_DSR0P_ENABLE DSI_CMCR_DSR0TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPDcsLongWrite DSI LP LPDcs Long Write - * @{ - */ -#define DSI_LP_DLW_DISABLE 0x00000000U -#define DSI_LP_DLW_ENABLE DSI_CMCR_DLWTX -/** - * @} - */ - -/** @defgroup DSI_LP_LPMaxReadPacket DSI LP LPMax Read Packet - * @{ - */ -#define DSI_LP_MRDP_DISABLE 0x00000000U -#define DSI_LP_MRDP_ENABLE DSI_CMCR_MRDPS -/** - * @} - */ - -/** @defgroup DSI_HS_PrespMode DSI HS Presp Mode - * @{ - */ -#define DSI_HS_PM_DISABLE 0x00000000U -#define DSI_HS_PM_ENABLE DSI_TCCR3_PM -/** - * @} - */ - - -/** @defgroup DSI_Automatic_Clk_Lane_Control DSI Automatic Clk Lane Control - * @{ - */ -#define DSI_AUTO_CLK_LANE_CTRL_DISABLE 0x00000000U -#define DSI_AUTO_CLK_LANE_CTRL_ENABLE DSI_CLCR_ACR -/** - * @} - */ - -/** @defgroup DSI_Number_Of_Lanes DSI Number Of Lanes - * @{ - */ -#define DSI_ONE_DATA_LANE 0U -#define DSI_TWO_DATA_LANES 1U -/** - * @} - */ - -/** @defgroup DSI_FlowControl DSI Flow Control - * @{ - */ -#define DSI_FLOW_CONTROL_CRC_RX DSI_PCR_CRCRXE -#define DSI_FLOW_CONTROL_ECC_RX DSI_PCR_ECCRXE -#define DSI_FLOW_CONTROL_BTA DSI_PCR_BTAE -#define DSI_FLOW_CONTROL_EOTP_RX DSI_PCR_ETRXE -#define DSI_FLOW_CONTROL_EOTP_TX DSI_PCR_ETTXE -#define DSI_FLOW_CONTROL_ALL (DSI_FLOW_CONTROL_CRC_RX | DSI_FLOW_CONTROL_ECC_RX | \ - DSI_FLOW_CONTROL_BTA | DSI_FLOW_CONTROL_EOTP_RX | \ - DSI_FLOW_CONTROL_EOTP_TX) -/** - * @} - */ - -/** @defgroup DSI_Color_Coding DSI Color Coding - * @{ - */ -#define DSI_RGB565 0x00000000U /*!< The values 0x00000001 and 0x00000002 can also be used for the RGB565 color mode configuration */ -#define DSI_RGB666 0x00000003U /*!< The value 0x00000004 can also be used for the RGB666 color mode configuration */ -#define DSI_RGB888 0x00000005U -/** - * @} - */ - -/** @defgroup DSI_LooselyPacked DSI Loosely Packed - * @{ - */ -#define DSI_LOOSELY_PACKED_ENABLE DSI_LCOLCR_LPE -#define DSI_LOOSELY_PACKED_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup DSI_HSYNC_Polarity DSI HSYNC Polarity - * @{ - */ -#define DSI_HSYNC_ACTIVE_HIGH 0x00000000U -#define DSI_HSYNC_ACTIVE_LOW DSI_LPCR_HSP -/** - * @} - */ - -/** @defgroup DSI_VSYNC_Active_Polarity DSI VSYNC Active Polarity - * @{ - */ -#define DSI_VSYNC_ACTIVE_HIGH 0x00000000U -#define DSI_VSYNC_ACTIVE_LOW DSI_LPCR_VSP -/** - * @} - */ - -/** @defgroup DSI_DATA_ENABLE_Polarity DSI DATA ENABLE Polarity - * @{ - */ -#define DSI_DATA_ENABLE_ACTIVE_HIGH 0x00000000U -#define DSI_DATA_ENABLE_ACTIVE_LOW DSI_LPCR_DEP -/** - * @} - */ - -/** @defgroup DSI_PLL_IDF DSI PLL IDF - * @{ - */ -#define DSI_PLL_IN_DIV1 0x00000001U -#define DSI_PLL_IN_DIV2 0x00000002U -#define DSI_PLL_IN_DIV3 0x00000003U -#define DSI_PLL_IN_DIV4 0x00000004U -#define DSI_PLL_IN_DIV5 0x00000005U -#define DSI_PLL_IN_DIV6 0x00000006U -#define DSI_PLL_IN_DIV7 0x00000007U -/** - * @} - */ - -/** @defgroup DSI_PLL_ODF DSI PLL ODF - * @{ - */ -#define DSI_PLL_OUT_DIV1 0x00000000U -#define DSI_PLL_OUT_DIV2 0x00000001U -#define DSI_PLL_OUT_DIV4 0x00000002U -#define DSI_PLL_OUT_DIV8 0x00000003U -/** - * @} - */ - -/** @defgroup DSI_Flags DSI Flags - * @{ - */ -#define DSI_FLAG_TE DSI_WISR_TEIF -#define DSI_FLAG_ER DSI_WISR_ERIF -#define DSI_FLAG_BUSY DSI_WISR_BUSY -#define DSI_FLAG_PLLLS DSI_WISR_PLLLS -#define DSI_FLAG_PLLL DSI_WISR_PLLLIF -#define DSI_FLAG_PLLU DSI_WISR_PLLUIF -#define DSI_FLAG_RRS DSI_WISR_RRS -#define DSI_FLAG_RR DSI_WISR_RRIF -/** - * @} - */ - -/** @defgroup DSI_Interrupts DSI Interrupts - * @{ - */ -#define DSI_IT_TE DSI_WIER_TEIE -#define DSI_IT_ER DSI_WIER_ERIE -#define DSI_IT_PLLL DSI_WIER_PLLLIE -#define DSI_IT_PLLU DSI_WIER_PLLUIE -#define DSI_IT_RR DSI_WIER_RRIE -/** - * @} - */ - -/** @defgroup DSI_SHORT_WRITE_PKT_Data_Type DSI SHORT WRITE PKT Data Type - * @{ - */ -#define DSI_DCS_SHORT_PKT_WRITE_P0 0x00000005U /*!< DCS short write, no parameters */ -#define DSI_DCS_SHORT_PKT_WRITE_P1 0x00000015U /*!< DCS short write, one parameter */ -#define DSI_GEN_SHORT_PKT_WRITE_P0 0x00000003U /*!< Generic short write, no parameters */ -#define DSI_GEN_SHORT_PKT_WRITE_P1 0x00000013U /*!< Generic short write, one parameter */ -#define DSI_GEN_SHORT_PKT_WRITE_P2 0x00000023U /*!< Generic short write, two parameters */ -/** - * @} - */ - -/** @defgroup DSI_LONG_WRITE_PKT_Data_Type DSI LONG WRITE PKT Data Type - * @{ - */ -#define DSI_DCS_LONG_PKT_WRITE 0x00000039U /*!< DCS long write */ -#define DSI_GEN_LONG_PKT_WRITE 0x00000029U /*!< Generic long write */ -/** - * @} - */ - -/** @defgroup DSI_SHORT_READ_PKT_Data_Type DSI SHORT READ PKT Data Type - * @{ - */ -#define DSI_DCS_SHORT_PKT_READ 0x00000006U /*!< DCS short read */ -#define DSI_GEN_SHORT_PKT_READ_P0 0x00000004U /*!< Generic short read, no parameters */ -#define DSI_GEN_SHORT_PKT_READ_P1 0x00000014U /*!< Generic short read, one parameter */ -#define DSI_GEN_SHORT_PKT_READ_P2 0x00000024U /*!< Generic short read, two parameters */ -/** - * @} - */ - -/** @defgroup DSI_Error_Data_Type DSI Error Data Type - * @{ - */ -#define HAL_DSI_ERROR_NONE 0U -#define HAL_DSI_ERROR_ACK 0x00000001U /*!< acknowledge errors */ -#define HAL_DSI_ERROR_PHY 0x00000002U /*!< PHY related errors */ -#define HAL_DSI_ERROR_TX 0x00000004U /*!< transmission error */ -#define HAL_DSI_ERROR_RX 0x00000008U /*!< reception error */ -#define HAL_DSI_ERROR_ECC 0x00000010U /*!< ECC errors */ -#define HAL_DSI_ERROR_CRC 0x00000020U /*!< CRC error */ -#define HAL_DSI_ERROR_PSE 0x00000040U /*!< Packet Size error */ -#define HAL_DSI_ERROR_EOT 0x00000080U /*!< End Of Transmission error */ -#define HAL_DSI_ERROR_OVF 0x00000100U /*!< FIFO overflow error */ -#define HAL_DSI_ERROR_GEN 0x00000200U /*!< Generic FIFO related errors */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -#define HAL_DSI_ERROR_INVALID_CALLBACK 0x00000400U /*!< DSI Invalid Callback error */ -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup DSI_Lane_Group DSI Lane Group - * @{ - */ -#define DSI_CLOCK_LANE 0x00000000U -#define DSI_DATA_LANES 0x00000001U -/** - * @} - */ - -/** @defgroup DSI_Communication_Delay DSI Communication Delay - * @{ - */ -#define DSI_SLEW_RATE_HSTX 0x00000000U -#define DSI_SLEW_RATE_LPTX 0x00000001U -#define DSI_HS_DELAY 0x00000002U -/** - * @} - */ - -/** @defgroup DSI_CustomLane DSI CustomLane - * @{ - */ -#define DSI_SWAP_LANE_PINS 0x00000000U -#define DSI_INVERT_HS_SIGNAL 0x00000001U -/** - * @} - */ - -/** @defgroup DSI_Lane_Select DSI Lane Select - * @{ - */ -#define DSI_CLK_LANE 0x00000000U -#define DSI_DATA_LANE0 0x00000001U -#define DSI_DATA_LANE1 0x00000002U -/** - * @} - */ - -/** @defgroup DSI_PHY_Timing DSI PHY Timing - * @{ - */ -#define DSI_TCLK_POST 0x00000000U -#define DSI_TLPX_CLK 0x00000001U -#define DSI_THS_EXIT 0x00000002U -#define DSI_TLPX_DATA 0x00000003U -#define DSI_THS_ZERO 0x00000004U -#define DSI_THS_TRAIL 0x00000005U -#define DSI_THS_PREPARE 0x00000006U -#define DSI_TCLK_ZERO 0x00000007U -#define DSI_TCLK_PREPARE 0x00000008U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup DSI_Exported_Macros DSI Exported Macros - * @{ - */ - -/** - * @brief Reset DSI handle state. - * @param __HANDLE__ DSI handle - * @retval None - */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -#define __HAL_DSI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DSI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_DSI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DSI_STATE_RESET) -#endif /*USE_HAL_DSI_REGISTER_CALLBACKS */ - -/** - * @brief Enables the DSI host. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_ENABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT((__HANDLE__)->Instance->CR, DSI_CR_EN);\ - /* Delay after an DSI Host enabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->CR, DSI_CR_EN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Disables the DSI host. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_DISABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - CLEAR_BIT((__HANDLE__)->Instance->CR, DSI_CR_EN);\ - /* Delay after an DSI Host disabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->CR, DSI_CR_EN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Enables the DSI wrapper. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_WRAPPER_ENABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT((__HANDLE__)->Instance->WCR, DSI_WCR_DSIEN);\ - /* Delay after an DSI warpper enabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WCR, DSI_WCR_DSIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Disable the DSI wrapper. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_WRAPPER_DISABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - CLEAR_BIT((__HANDLE__)->Instance->WCR, DSI_WCR_DSIEN);\ - /* Delay after an DSI warpper disabling*/ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WCR, DSI_WCR_DSIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Enables the DSI PLL. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_PLL_ENABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_PLLEN);\ - /* Delay after an DSI PLL enabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_PLLEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Disables the DSI PLL. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_PLL_DISABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - CLEAR_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_PLLEN);\ - /* Delay after an DSI PLL disabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_PLLEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Enables the DSI regulator. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_REG_ENABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_REGEN);\ - /* Delay after an DSI regulator enabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_REGEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Disables the DSI regulator. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_REG_DISABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - CLEAR_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_REGEN);\ - /* Delay after an DSI regulator disabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_REGEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Get the DSI pending flags. - * @param __HANDLE__ DSI handle. - * @param __FLAG__ Get the specified flag. - * This parameter can be any combination of the following values: - * @arg DSI_FLAG_TE : Tearing Effect Interrupt Flag - * @arg DSI_FLAG_ER : End of Refresh Interrupt Flag - * @arg DSI_FLAG_BUSY : Busy Flag - * @arg DSI_FLAG_PLLLS: PLL Lock Status - * @arg DSI_FLAG_PLLL : PLL Lock Interrupt Flag - * @arg DSI_FLAG_PLLU : PLL Unlock Interrupt Flag - * @arg DSI_FLAG_RRS : Regulator Ready Flag - * @arg DSI_FLAG_RR : Regulator Ready Interrupt Flag - * @retval The state of FLAG (SET or RESET). - */ -#define __HAL_DSI_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->WISR & (__FLAG__)) - -/** - * @brief Clears the DSI pending flags. - * @param __HANDLE__ DSI handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DSI_FLAG_TE : Tearing Effect Interrupt Flag - * @arg DSI_FLAG_ER : End of Refresh Interrupt Flag - * @arg DSI_FLAG_PLLL : PLL Lock Interrupt Flag - * @arg DSI_FLAG_PLLU : PLL Unlock Interrupt Flag - * @arg DSI_FLAG_RR : Regulator Ready Interrupt Flag - * @retval None - */ -#define __HAL_DSI_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->WIFCR = (__FLAG__)) - -/** - * @brief Enables the specified DSI interrupts. - * @param __HANDLE__ DSI handle. - * @param __INTERRUPT__ specifies the DSI interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg DSI_IT_TE : Tearing Effect Interrupt - * @arg DSI_IT_ER : End of Refresh Interrupt - * @arg DSI_IT_PLLL: PLL Lock Interrupt - * @arg DSI_IT_PLLU: PLL Unlock Interrupt - * @arg DSI_IT_RR : Regulator Ready Interrupt - * @retval None - */ -#define __HAL_DSI_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->WIER |= (__INTERRUPT__)) - -/** - * @brief Disables the specified DSI interrupts. - * @param __HANDLE__ DSI handle - * @param __INTERRUPT__ specifies the DSI interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg DSI_IT_TE : Tearing Effect Interrupt - * @arg DSI_IT_ER : End of Refresh Interrupt - * @arg DSI_IT_PLLL: PLL Lock Interrupt - * @arg DSI_IT_PLLU: PLL Unlock Interrupt - * @arg DSI_IT_RR : Regulator Ready Interrupt - * @retval None - */ -#define __HAL_DSI_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->WIER &= ~(__INTERRUPT__)) - -/** - * @brief Checks whether the specified DSI interrupt source is enabled or not. - * @param __HANDLE__ DSI handle - * @param __INTERRUPT__ specifies the DSI interrupt source to check. - * This parameter can be one of the following values: - * @arg DSI_IT_TE : Tearing Effect Interrupt - * @arg DSI_IT_ER : End of Refresh Interrupt - * @arg DSI_IT_PLLL: PLL Lock Interrupt - * @arg DSI_IT_PLLU: PLL Unlock Interrupt - * @arg DSI_IT_RR : Regulator Ready Interrupt - * @retval The state of INTERRUPT (SET or RESET). - */ -#define __HAL_DSI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->WIER & (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DSI_Exported_Functions DSI Exported Functions - * @{ - */ -HAL_StatusTypeDef HAL_DSI_Init(DSI_HandleTypeDef *hdsi, DSI_PLLInitTypeDef *PLLInit); -HAL_StatusTypeDef HAL_DSI_DeInit(DSI_HandleTypeDef *hdsi); -void HAL_DSI_MspInit(DSI_HandleTypeDef *hdsi); -void HAL_DSI_MspDeInit(DSI_HandleTypeDef *hdsi); - -void HAL_DSI_IRQHandler(DSI_HandleTypeDef *hdsi); -void HAL_DSI_TearingEffectCallback(DSI_HandleTypeDef *hdsi); -void HAL_DSI_EndOfRefreshCallback(DSI_HandleTypeDef *hdsi); -void HAL_DSI_ErrorCallback(DSI_HandleTypeDef *hdsi); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_DSI_RegisterCallback(DSI_HandleTypeDef *hdsi, HAL_DSI_CallbackIDTypeDef CallbackID, - pDSI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DSI_UnRegisterCallback(DSI_HandleTypeDef *hdsi, HAL_DSI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - -HAL_StatusTypeDef HAL_DSI_SetGenericVCID(DSI_HandleTypeDef *hdsi, uint32_t VirtualChannelID); -HAL_StatusTypeDef HAL_DSI_ConfigVideoMode(DSI_HandleTypeDef *hdsi, DSI_VidCfgTypeDef *VidCfg); -HAL_StatusTypeDef HAL_DSI_ConfigAdaptedCommandMode(DSI_HandleTypeDef *hdsi, DSI_CmdCfgTypeDef *CmdCfg); -HAL_StatusTypeDef HAL_DSI_ConfigCommand(DSI_HandleTypeDef *hdsi, DSI_LPCmdTypeDef *LPCmd); -HAL_StatusTypeDef HAL_DSI_ConfigFlowControl(DSI_HandleTypeDef *hdsi, uint32_t FlowControl); -HAL_StatusTypeDef HAL_DSI_ConfigPhyTimer(DSI_HandleTypeDef *hdsi, DSI_PHY_TimerTypeDef *PhyTimers); -HAL_StatusTypeDef HAL_DSI_ConfigHostTimeouts(DSI_HandleTypeDef *hdsi, DSI_HOST_TimeoutTypeDef *HostTimeouts); -HAL_StatusTypeDef HAL_DSI_Start(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_Stop(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_Refresh(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_ColorMode(DSI_HandleTypeDef *hdsi, uint32_t ColorMode); -HAL_StatusTypeDef HAL_DSI_Shutdown(DSI_HandleTypeDef *hdsi, uint32_t Shutdown); -HAL_StatusTypeDef HAL_DSI_ShortWrite(DSI_HandleTypeDef *hdsi, - uint32_t ChannelID, - uint32_t Mode, - uint32_t Param1, - uint32_t Param2); -HAL_StatusTypeDef HAL_DSI_LongWrite(DSI_HandleTypeDef *hdsi, - uint32_t ChannelID, - uint32_t Mode, - uint32_t NbParams, - uint32_t Param1, - uint8_t *ParametersTable); -HAL_StatusTypeDef HAL_DSI_Read(DSI_HandleTypeDef *hdsi, - uint32_t ChannelNbr, - uint8_t *Array, - uint32_t Size, - uint32_t Mode, - uint32_t DCSCmd, - uint8_t *ParametersTable); -HAL_StatusTypeDef HAL_DSI_EnterULPMData(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_ExitULPMData(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_EnterULPM(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_ExitULPM(DSI_HandleTypeDef *hdsi); - -HAL_StatusTypeDef HAL_DSI_PatternGeneratorStart(DSI_HandleTypeDef *hdsi, uint32_t Mode, uint32_t Orientation); -HAL_StatusTypeDef HAL_DSI_PatternGeneratorStop(DSI_HandleTypeDef *hdsi); - -HAL_StatusTypeDef HAL_DSI_SetSlewRateAndDelayTuning(DSI_HandleTypeDef *hdsi, uint32_t CommDelay, uint32_t Lane, - uint32_t Value); -HAL_StatusTypeDef HAL_DSI_SetLowPowerRXFilter(DSI_HandleTypeDef *hdsi, uint32_t Frequency); -HAL_StatusTypeDef HAL_DSI_SetSDD(DSI_HandleTypeDef *hdsi, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_SetLanePinsConfiguration(DSI_HandleTypeDef *hdsi, uint32_t CustomLane, uint32_t Lane, - FunctionalState State); -HAL_StatusTypeDef HAL_DSI_SetPHYTimings(DSI_HandleTypeDef *hdsi, uint32_t Timing, FunctionalState State, - uint32_t Value); -HAL_StatusTypeDef HAL_DSI_ForceTXStopMode(DSI_HandleTypeDef *hdsi, uint32_t Lane, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_ForceRXLowPower(DSI_HandleTypeDef *hdsi, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_ForceDataLanesInRX(DSI_HandleTypeDef *hdsi, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_SetPullDown(DSI_HandleTypeDef *hdsi, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_SetContentionDetectionOff(DSI_HandleTypeDef *hdsi, FunctionalState State); - -uint32_t HAL_DSI_GetError(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_ConfigErrorMonitor(DSI_HandleTypeDef *hdsi, uint32_t ActiveErrors); -HAL_DSI_StateTypeDef HAL_DSI_GetState(DSI_HandleTypeDef *hdsi); -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup DSI_Private_Types DSI Private Types - * @{ - */ - -/** - * @} - */ - -/* Private defines -----------------------------------------------------------*/ -/** @defgroup DSI_Private_Defines DSI Private Defines - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup DSI_Private_Variables DSI Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DSI_Private_Constants DSI Private Constants - * @{ - */ -#define DSI_MAX_RETURN_PKT_SIZE (0x00000037U) /*!< Maximum return packet configuration */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DSI_Private_Macros DSI Private Macros - * @{ - */ -#define IS_DSI_PLL_NDIV(NDIV) ((10U <= (NDIV)) && ((NDIV) <= 125U)) -#define IS_DSI_PLL_IDF(IDF) (((IDF) == DSI_PLL_IN_DIV1) || \ - ((IDF) == DSI_PLL_IN_DIV2) || \ - ((IDF) == DSI_PLL_IN_DIV3) || \ - ((IDF) == DSI_PLL_IN_DIV4) || \ - ((IDF) == DSI_PLL_IN_DIV5) || \ - ((IDF) == DSI_PLL_IN_DIV6) || \ - ((IDF) == DSI_PLL_IN_DIV7)) -#define IS_DSI_PLL_ODF(ODF) (((ODF) == DSI_PLL_OUT_DIV1) || \ - ((ODF) == DSI_PLL_OUT_DIV2) || \ - ((ODF) == DSI_PLL_OUT_DIV4) || \ - ((ODF) == DSI_PLL_OUT_DIV8)) -#define IS_DSI_AUTO_CLKLANE_CONTROL(AutoClkLane) (((AutoClkLane) == DSI_AUTO_CLK_LANE_CTRL_DISABLE) || ((AutoClkLane) == DSI_AUTO_CLK_LANE_CTRL_ENABLE)) -#define IS_DSI_NUMBER_OF_LANES(NumberOfLanes) (((NumberOfLanes) == DSI_ONE_DATA_LANE) || ((NumberOfLanes) == DSI_TWO_DATA_LANES)) -#define IS_DSI_FLOW_CONTROL(FlowControl) (((FlowControl) | DSI_FLOW_CONTROL_ALL) == DSI_FLOW_CONTROL_ALL) -#define IS_DSI_COLOR_CODING(ColorCoding) ((ColorCoding) <= 5U) -#define IS_DSI_LOOSELY_PACKED(LooselyPacked) (((LooselyPacked) == DSI_LOOSELY_PACKED_ENABLE) || ((LooselyPacked) == DSI_LOOSELY_PACKED_DISABLE)) -#define IS_DSI_DE_POLARITY(DataEnable) (((DataEnable) == DSI_DATA_ENABLE_ACTIVE_HIGH) || ((DataEnable) == DSI_DATA_ENABLE_ACTIVE_LOW)) -#define IS_DSI_VSYNC_POLARITY(VSYNC) (((VSYNC) == DSI_VSYNC_ACTIVE_HIGH) || ((VSYNC) == DSI_VSYNC_ACTIVE_LOW)) -#define IS_DSI_HSYNC_POLARITY(HSYNC) (((HSYNC) == DSI_HSYNC_ACTIVE_HIGH) || ((HSYNC) == DSI_HSYNC_ACTIVE_LOW)) -#define IS_DSI_VIDEO_MODE_TYPE(VideoModeType) (((VideoModeType) == DSI_VID_MODE_NB_PULSES) || \ - ((VideoModeType) == DSI_VID_MODE_NB_EVENTS) || \ - ((VideoModeType) == DSI_VID_MODE_BURST)) -#define IS_DSI_COLOR_MODE(ColorMode) (((ColorMode) == DSI_COLOR_MODE_FULL) || ((ColorMode) == DSI_COLOR_MODE_EIGHT)) -#define IS_DSI_SHUT_DOWN(ShutDown) (((ShutDown) == DSI_DISPLAY_ON) || ((ShutDown) == DSI_DISPLAY_OFF)) -#define IS_DSI_LP_COMMAND(LPCommand) (((LPCommand) == DSI_LP_COMMAND_DISABLE) || ((LPCommand) == DSI_LP_COMMAND_ENABLE)) -#define IS_DSI_LP_HFP(LPHFP) (((LPHFP) == DSI_LP_HFP_DISABLE) || ((LPHFP) == DSI_LP_HFP_ENABLE)) -#define IS_DSI_LP_HBP(LPHBP) (((LPHBP) == DSI_LP_HBP_DISABLE) || ((LPHBP) == DSI_LP_HBP_ENABLE)) -#define IS_DSI_LP_VACTIVE(LPVActive) (((LPVActive) == DSI_LP_VACT_DISABLE) || ((LPVActive) == DSI_LP_VACT_ENABLE)) -#define IS_DSI_LP_VFP(LPVFP) (((LPVFP) == DSI_LP_VFP_DISABLE) || ((LPVFP) == DSI_LP_VFP_ENABLE)) -#define IS_DSI_LP_VBP(LPVBP) (((LPVBP) == DSI_LP_VBP_DISABLE) || ((LPVBP) == DSI_LP_VBP_ENABLE)) -#define IS_DSI_LP_VSYNC(LPVSYNC) (((LPVSYNC) == DSI_LP_VSYNC_DISABLE) || ((LPVSYNC) == DSI_LP_VSYNC_ENABLE)) -#define IS_DSI_FBTAA(FrameBTAAcknowledge) (((FrameBTAAcknowledge) == DSI_FBTAA_DISABLE) || ((FrameBTAAcknowledge) == DSI_FBTAA_ENABLE)) -#define IS_DSI_TE_SOURCE(TESource) (((TESource) == DSI_TE_DSILINK) || ((TESource) == DSI_TE_EXTERNAL)) -#define IS_DSI_TE_POLARITY(TEPolarity) (((TEPolarity) == DSI_TE_RISING_EDGE) || ((TEPolarity) == DSI_TE_FALLING_EDGE)) -#define IS_DSI_AUTOMATIC_REFRESH(AutomaticRefresh) (((AutomaticRefresh) == DSI_AR_DISABLE) || ((AutomaticRefresh) == DSI_AR_ENABLE)) -#define IS_DSI_VS_POLARITY(VSPolarity) (((VSPolarity) == DSI_VSYNC_FALLING) || ((VSPolarity) == DSI_VSYNC_RISING)) -#define IS_DSI_TE_ACK_REQUEST(TEAcknowledgeRequest) (((TEAcknowledgeRequest) == DSI_TE_ACKNOWLEDGE_DISABLE) || ((TEAcknowledgeRequest) == DSI_TE_ACKNOWLEDGE_ENABLE)) -#define IS_DSI_ACK_REQUEST(AcknowledgeRequest) (((AcknowledgeRequest) == DSI_ACKNOWLEDGE_DISABLE) || ((AcknowledgeRequest) == DSI_ACKNOWLEDGE_ENABLE)) -#define IS_DSI_LP_GSW0P(LP_GSW0P) (((LP_GSW0P) == DSI_LP_GSW0P_DISABLE) || ((LP_GSW0P) == DSI_LP_GSW0P_ENABLE)) -#define IS_DSI_LP_GSW1P(LP_GSW1P) (((LP_GSW1P) == DSI_LP_GSW1P_DISABLE) || ((LP_GSW1P) == DSI_LP_GSW1P_ENABLE)) -#define IS_DSI_LP_GSW2P(LP_GSW2P) (((LP_GSW2P) == DSI_LP_GSW2P_DISABLE) || ((LP_GSW2P) == DSI_LP_GSW2P_ENABLE)) -#define IS_DSI_LP_GSR0P(LP_GSR0P) (((LP_GSR0P) == DSI_LP_GSR0P_DISABLE) || ((LP_GSR0P) == DSI_LP_GSR0P_ENABLE)) -#define IS_DSI_LP_GSR1P(LP_GSR1P) (((LP_GSR1P) == DSI_LP_GSR1P_DISABLE) || ((LP_GSR1P) == DSI_LP_GSR1P_ENABLE)) -#define IS_DSI_LP_GSR2P(LP_GSR2P) (((LP_GSR2P) == DSI_LP_GSR2P_DISABLE) || ((LP_GSR2P) == DSI_LP_GSR2P_ENABLE)) -#define IS_DSI_LP_GLW(LP_GLW) (((LP_GLW) == DSI_LP_GLW_DISABLE) || ((LP_GLW) == DSI_LP_GLW_ENABLE)) -#define IS_DSI_LP_DSW0P(LP_DSW0P) (((LP_DSW0P) == DSI_LP_DSW0P_DISABLE) || ((LP_DSW0P) == DSI_LP_DSW0P_ENABLE)) -#define IS_DSI_LP_DSW1P(LP_DSW1P) (((LP_DSW1P) == DSI_LP_DSW1P_DISABLE) || ((LP_DSW1P) == DSI_LP_DSW1P_ENABLE)) -#define IS_DSI_LP_DSR0P(LP_DSR0P) (((LP_DSR0P) == DSI_LP_DSR0P_DISABLE) || ((LP_DSR0P) == DSI_LP_DSR0P_ENABLE)) -#define IS_DSI_LP_DLW(LP_DLW) (((LP_DLW) == DSI_LP_DLW_DISABLE) || ((LP_DLW) == DSI_LP_DLW_ENABLE)) -#define IS_DSI_LP_MRDP(LP_MRDP) (((LP_MRDP) == DSI_LP_MRDP_DISABLE) || ((LP_MRDP) == DSI_LP_MRDP_ENABLE)) -#define IS_DSI_SHORT_WRITE_PACKET_TYPE(MODE) (((MODE) == DSI_DCS_SHORT_PKT_WRITE_P0) || \ - ((MODE) == DSI_DCS_SHORT_PKT_WRITE_P1) || \ - ((MODE) == DSI_GEN_SHORT_PKT_WRITE_P0) || \ - ((MODE) == DSI_GEN_SHORT_PKT_WRITE_P1) || \ - ((MODE) == DSI_GEN_SHORT_PKT_WRITE_P2)) -#define IS_DSI_LONG_WRITE_PACKET_TYPE(MODE) (((MODE) == DSI_DCS_LONG_PKT_WRITE) || \ - ((MODE) == DSI_GEN_LONG_PKT_WRITE)) -#define IS_DSI_READ_PACKET_TYPE(MODE) (((MODE) == DSI_DCS_SHORT_PKT_READ) || \ - ((MODE) == DSI_GEN_SHORT_PKT_READ_P0) || \ - ((MODE) == DSI_GEN_SHORT_PKT_READ_P1) || \ - ((MODE) == DSI_GEN_SHORT_PKT_READ_P2)) -#define IS_DSI_COMMUNICATION_DELAY(CommDelay) (((CommDelay) == DSI_SLEW_RATE_HSTX) || ((CommDelay) == DSI_SLEW_RATE_LPTX) || ((CommDelay) == DSI_HS_DELAY)) -#define IS_DSI_LANE_GROUP(Lane) (((Lane) == DSI_CLOCK_LANE) || ((Lane) == DSI_DATA_LANES)) -#define IS_DSI_CUSTOM_LANE(CustomLane) (((CustomLane) == DSI_SWAP_LANE_PINS) || ((CustomLane) == DSI_INVERT_HS_SIGNAL)) -#define IS_DSI_LANE(Lane) (((Lane) == DSI_CLOCK_LANE) || ((Lane) == DSI_DATA_LANE0) || ((Lane) == DSI_DATA_LANE1)) -#define IS_DSI_PHY_TIMING(Timing) (((Timing) == DSI_TCLK_POST ) || \ - ((Timing) == DSI_TLPX_CLK ) || \ - ((Timing) == DSI_THS_EXIT ) || \ - ((Timing) == DSI_TLPX_DATA ) || \ - ((Timing) == DSI_THS_ZERO ) || \ - ((Timing) == DSI_THS_TRAIL ) || \ - ((Timing) == DSI_THS_PREPARE ) || \ - ((Timing) == DSI_TCLK_ZERO ) || \ - ((Timing) == DSI_TCLK_PREPARE)) - -/** - * @} - */ - -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup DSI_Private_Functions_Prototypes DSI Private Functions Prototypes - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DSI_Private_Functions DSI Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* DSI */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_DSI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h deleted file mode 100644 index a0b0ad320786cd9..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h +++ /dev/null @@ -1,2213 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_eth.h - * @author MCD Application Team - * @brief Header file of ETH HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_ETH_H -#define __STM32F4xx_HAL_ETH_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup ETH - * @{ - */ - -/** @addtogroup ETH_Private_Macros - * @{ - */ -#define IS_ETH_PHY_ADDRESS(ADDRESS) ((ADDRESS) <= 0x20U) -#define IS_ETH_AUTONEGOTIATION(CMD) (((CMD) == ETH_AUTONEGOTIATION_ENABLE) || \ - ((CMD) == ETH_AUTONEGOTIATION_DISABLE)) -#define IS_ETH_SPEED(SPEED) (((SPEED) == ETH_SPEED_10M) || \ - ((SPEED) == ETH_SPEED_100M)) -#define IS_ETH_DUPLEX_MODE(MODE) (((MODE) == ETH_MODE_FULLDUPLEX) || \ - ((MODE) == ETH_MODE_HALFDUPLEX)) -#define IS_ETH_RX_MODE(MODE) (((MODE) == ETH_RXPOLLING_MODE) || \ - ((MODE) == ETH_RXINTERRUPT_MODE)) -#define IS_ETH_CHECKSUM_MODE(MODE) (((MODE) == ETH_CHECKSUM_BY_HARDWARE) || \ - ((MODE) == ETH_CHECKSUM_BY_SOFTWARE)) -#define IS_ETH_MEDIA_INTERFACE(MODE) (((MODE) == ETH_MEDIA_INTERFACE_MII) || \ - ((MODE) == ETH_MEDIA_INTERFACE_RMII)) -#define IS_ETH_WATCHDOG(CMD) (((CMD) == ETH_WATCHDOG_ENABLE) || \ - ((CMD) == ETH_WATCHDOG_DISABLE)) -#define IS_ETH_JABBER(CMD) (((CMD) == ETH_JABBER_ENABLE) || \ - ((CMD) == ETH_JABBER_DISABLE)) -#define IS_ETH_INTER_FRAME_GAP(GAP) (((GAP) == ETH_INTERFRAMEGAP_96BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_88BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_80BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_72BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_64BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_56BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_48BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_40BIT)) -#define IS_ETH_CARRIER_SENSE(CMD) (((CMD) == ETH_CARRIERSENCE_ENABLE) || \ - ((CMD) == ETH_CARRIERSENCE_DISABLE)) -#define IS_ETH_RECEIVE_OWN(CMD) (((CMD) == ETH_RECEIVEOWN_ENABLE) || \ - ((CMD) == ETH_RECEIVEOWN_DISABLE)) -#define IS_ETH_LOOPBACK_MODE(CMD) (((CMD) == ETH_LOOPBACKMODE_ENABLE) || \ - ((CMD) == ETH_LOOPBACKMODE_DISABLE)) -#define IS_ETH_CHECKSUM_OFFLOAD(CMD) (((CMD) == ETH_CHECKSUMOFFLAOD_ENABLE) || \ - ((CMD) == ETH_CHECKSUMOFFLAOD_DISABLE)) -#define IS_ETH_RETRY_TRANSMISSION(CMD) (((CMD) == ETH_RETRYTRANSMISSION_ENABLE) || \ - ((CMD) == ETH_RETRYTRANSMISSION_DISABLE)) -#define IS_ETH_AUTOMATIC_PADCRC_STRIP(CMD) (((CMD) == ETH_AUTOMATICPADCRCSTRIP_ENABLE) || \ - ((CMD) == ETH_AUTOMATICPADCRCSTRIP_DISABLE)) -#define IS_ETH_BACKOFF_LIMIT(LIMIT) (((LIMIT) == ETH_BACKOFFLIMIT_10) || \ - ((LIMIT) == ETH_BACKOFFLIMIT_8) || \ - ((LIMIT) == ETH_BACKOFFLIMIT_4) || \ - ((LIMIT) == ETH_BACKOFFLIMIT_1)) -#define IS_ETH_DEFERRAL_CHECK(CMD) (((CMD) == ETH_DEFFERRALCHECK_ENABLE) || \ - ((CMD) == ETH_DEFFERRALCHECK_DISABLE)) -#define IS_ETH_RECEIVE_ALL(CMD) (((CMD) == ETH_RECEIVEALL_ENABLE) || \ - ((CMD) == ETH_RECEIVEAll_DISABLE)) -#define IS_ETH_SOURCE_ADDR_FILTER(CMD) (((CMD) == ETH_SOURCEADDRFILTER_NORMAL_ENABLE) || \ - ((CMD) == ETH_SOURCEADDRFILTER_INVERSE_ENABLE) || \ - ((CMD) == ETH_SOURCEADDRFILTER_DISABLE)) -#define IS_ETH_CONTROL_FRAMES(PASS) (((PASS) == ETH_PASSCONTROLFRAMES_BLOCKALL) || \ - ((PASS) == ETH_PASSCONTROLFRAMES_FORWARDALL) || \ - ((PASS) == ETH_PASSCONTROLFRAMES_FORWARDPASSEDADDRFILTER)) -#define IS_ETH_BROADCAST_FRAMES_RECEPTION(CMD) (((CMD) == ETH_BROADCASTFRAMESRECEPTION_ENABLE) || \ - ((CMD) == ETH_BROADCASTFRAMESRECEPTION_DISABLE)) -#define IS_ETH_DESTINATION_ADDR_FILTER(FILTER) (((FILTER) == ETH_DESTINATIONADDRFILTER_NORMAL) || \ - ((FILTER) == ETH_DESTINATIONADDRFILTER_INVERSE)) -#define IS_ETH_PROMISCUOUS_MODE(CMD) (((CMD) == ETH_PROMISCUOUS_MODE_ENABLE) || \ - ((CMD) == ETH_PROMISCUOUS_MODE_DISABLE)) -#define IS_ETH_MULTICAST_FRAMES_FILTER(FILTER) (((FILTER) == ETH_MULTICASTFRAMESFILTER_PERFECTHASHTABLE) || \ - ((FILTER) == ETH_MULTICASTFRAMESFILTER_HASHTABLE) || \ - ((FILTER) == ETH_MULTICASTFRAMESFILTER_PERFECT) || \ - ((FILTER) == ETH_MULTICASTFRAMESFILTER_NONE)) -#define IS_ETH_UNICAST_FRAMES_FILTER(FILTER) (((FILTER) == ETH_UNICASTFRAMESFILTER_PERFECTHASHTABLE) || \ - ((FILTER) == ETH_UNICASTFRAMESFILTER_HASHTABLE) || \ - ((FILTER) == ETH_UNICASTFRAMESFILTER_PERFECT)) -#define IS_ETH_PAUSE_TIME(TIME) ((TIME) <= 0xFFFFU) -#define IS_ETH_ZEROQUANTA_PAUSE(CMD) (((CMD) == ETH_ZEROQUANTAPAUSE_ENABLE) || \ - ((CMD) == ETH_ZEROQUANTAPAUSE_DISABLE)) -#define IS_ETH_PAUSE_LOW_THRESHOLD(THRESHOLD) (((THRESHOLD) == ETH_PAUSELOWTHRESHOLD_MINUS4) || \ - ((THRESHOLD) == ETH_PAUSELOWTHRESHOLD_MINUS28) || \ - ((THRESHOLD) == ETH_PAUSELOWTHRESHOLD_MINUS144) || \ - ((THRESHOLD) == ETH_PAUSELOWTHRESHOLD_MINUS256)) -#define IS_ETH_UNICAST_PAUSE_FRAME_DETECT(CMD) (((CMD) == ETH_UNICASTPAUSEFRAMEDETECT_ENABLE) || \ - ((CMD) == ETH_UNICASTPAUSEFRAMEDETECT_DISABLE)) -#define IS_ETH_RECEIVE_FLOWCONTROL(CMD) (((CMD) == ETH_RECEIVEFLOWCONTROL_ENABLE) || \ - ((CMD) == ETH_RECEIVEFLOWCONTROL_DISABLE)) -#define IS_ETH_TRANSMIT_FLOWCONTROL(CMD) (((CMD) == ETH_TRANSMITFLOWCONTROL_ENABLE) || \ - ((CMD) == ETH_TRANSMITFLOWCONTROL_DISABLE)) -#define IS_ETH_VLAN_TAG_COMPARISON(COMPARISON) (((COMPARISON) == ETH_VLANTAGCOMPARISON_12BIT) || \ - ((COMPARISON) == ETH_VLANTAGCOMPARISON_16BIT)) -#define IS_ETH_VLAN_TAG_IDENTIFIER(IDENTIFIER) ((IDENTIFIER) <= 0xFFFFU) -#define IS_ETH_MAC_ADDRESS0123(ADDRESS) (((ADDRESS) == ETH_MAC_ADDRESS0) || \ - ((ADDRESS) == ETH_MAC_ADDRESS1) || \ - ((ADDRESS) == ETH_MAC_ADDRESS2) || \ - ((ADDRESS) == ETH_MAC_ADDRESS3)) -#define IS_ETH_MAC_ADDRESS123(ADDRESS) (((ADDRESS) == ETH_MAC_ADDRESS1) || \ - ((ADDRESS) == ETH_MAC_ADDRESS2) || \ - ((ADDRESS) == ETH_MAC_ADDRESS3)) -#define IS_ETH_MAC_ADDRESS_FILTER(FILTER) (((FILTER) == ETH_MAC_ADDRESSFILTER_SA) || \ - ((FILTER) == ETH_MAC_ADDRESSFILTER_DA)) -#define IS_ETH_MAC_ADDRESS_MASK(MASK) (((MASK) == ETH_MAC_ADDRESSMASK_BYTE6) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE5) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE4) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE3) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE2) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE1)) -#define IS_ETH_DROP_TCPIP_CHECKSUM_FRAME(CMD) (((CMD) == ETH_DROPTCPIPCHECKSUMERRORFRAME_ENABLE) || \ - ((CMD) == ETH_DROPTCPIPCHECKSUMERRORFRAME_DISABLE)) -#define IS_ETH_RECEIVE_STORE_FORWARD(CMD) (((CMD) == ETH_RECEIVESTOREFORWARD_ENABLE) || \ - ((CMD) == ETH_RECEIVESTOREFORWARD_DISABLE)) -#define IS_ETH_FLUSH_RECEIVE_FRAME(CMD) (((CMD) == ETH_FLUSHRECEIVEDFRAME_ENABLE) || \ - ((CMD) == ETH_FLUSHRECEIVEDFRAME_DISABLE)) -#define IS_ETH_TRANSMIT_STORE_FORWARD(CMD) (((CMD) == ETH_TRANSMITSTOREFORWARD_ENABLE) || \ - ((CMD) == ETH_TRANSMITSTOREFORWARD_DISABLE)) -#define IS_ETH_TRANSMIT_THRESHOLD_CONTROL(THRESHOLD) (((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_64BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_128BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_192BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_256BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_40BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_32BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_24BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_16BYTES)) -#define IS_ETH_FORWARD_ERROR_FRAMES(CMD) (((CMD) == ETH_FORWARDERRORFRAMES_ENABLE) || \ - ((CMD) == ETH_FORWARDERRORFRAMES_DISABLE)) -#define IS_ETH_FORWARD_UNDERSIZED_GOOD_FRAMES(CMD) (((CMD) == ETH_FORWARDUNDERSIZEDGOODFRAMES_ENABLE) || \ - ((CMD) == ETH_FORWARDUNDERSIZEDGOODFRAMES_DISABLE)) -#define IS_ETH_RECEIVE_THRESHOLD_CONTROL(THRESHOLD) (((THRESHOLD) == ETH_RECEIVEDTHRESHOLDCONTROL_64BYTES) || \ - ((THRESHOLD) == ETH_RECEIVEDTHRESHOLDCONTROL_32BYTES) || \ - ((THRESHOLD) == ETH_RECEIVEDTHRESHOLDCONTROL_96BYTES) || \ - ((THRESHOLD) == ETH_RECEIVEDTHRESHOLDCONTROL_128BYTES)) -#define IS_ETH_SECOND_FRAME_OPERATE(CMD) (((CMD) == ETH_SECONDFRAMEOPERARTE_ENABLE) || \ - ((CMD) == ETH_SECONDFRAMEOPERARTE_DISABLE)) -#define IS_ETH_ADDRESS_ALIGNED_BEATS(CMD) (((CMD) == ETH_ADDRESSALIGNEDBEATS_ENABLE) || \ - ((CMD) == ETH_ADDRESSALIGNEDBEATS_DISABLE)) -#define IS_ETH_FIXED_BURST(CMD) (((CMD) == ETH_FIXEDBURST_ENABLE) || \ - ((CMD) == ETH_FIXEDBURST_DISABLE)) -#define IS_ETH_RXDMA_BURST_LENGTH(LENGTH) (((LENGTH) == ETH_RXDMABURSTLENGTH_1BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_2BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_8BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_16BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_32BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_4BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_8BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_16BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_32BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_64BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_128BEAT)) -#define IS_ETH_TXDMA_BURST_LENGTH(LENGTH) (((LENGTH) == ETH_TXDMABURSTLENGTH_1BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_2BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_8BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_16BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_32BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_4BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_8BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_16BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_32BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_64BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_128BEAT)) -#define IS_ETH_DMA_DESC_SKIP_LENGTH(LENGTH) ((LENGTH) <= 0x1FU) -#define IS_ETH_DMA_ARBITRATION_ROUNDROBIN_RXTX(RATIO) (((RATIO) == ETH_DMAARBITRATION_ROUNDROBIN_RXTX_1_1) || \ - ((RATIO) == ETH_DMAARBITRATION_ROUNDROBIN_RXTX_2_1) || \ - ((RATIO) == ETH_DMAARBITRATION_ROUNDROBIN_RXTX_3_1) || \ - ((RATIO) == ETH_DMAARBITRATION_ROUNDROBIN_RXTX_4_1) || \ - ((RATIO) == ETH_DMAARBITRATION_RXPRIORTX)) -#define IS_ETH_DMATXDESC_GET_FLAG(FLAG) (((FLAG) == ETH_DMATXDESC_OWN) || \ - ((FLAG) == ETH_DMATXDESC_IC) || \ - ((FLAG) == ETH_DMATXDESC_LS) || \ - ((FLAG) == ETH_DMATXDESC_FS) || \ - ((FLAG) == ETH_DMATXDESC_DC) || \ - ((FLAG) == ETH_DMATXDESC_DP) || \ - ((FLAG) == ETH_DMATXDESC_TTSE) || \ - ((FLAG) == ETH_DMATXDESC_TER) || \ - ((FLAG) == ETH_DMATXDESC_TCH) || \ - ((FLAG) == ETH_DMATXDESC_TTSS) || \ - ((FLAG) == ETH_DMATXDESC_IHE) || \ - ((FLAG) == ETH_DMATXDESC_ES) || \ - ((FLAG) == ETH_DMATXDESC_JT) || \ - ((FLAG) == ETH_DMATXDESC_FF) || \ - ((FLAG) == ETH_DMATXDESC_PCE) || \ - ((FLAG) == ETH_DMATXDESC_LCA) || \ - ((FLAG) == ETH_DMATXDESC_NC) || \ - ((FLAG) == ETH_DMATXDESC_LCO) || \ - ((FLAG) == ETH_DMATXDESC_EC) || \ - ((FLAG) == ETH_DMATXDESC_VF) || \ - ((FLAG) == ETH_DMATXDESC_CC) || \ - ((FLAG) == ETH_DMATXDESC_ED) || \ - ((FLAG) == ETH_DMATXDESC_UF) || \ - ((FLAG) == ETH_DMATXDESC_DB)) -#define IS_ETH_DMA_TXDESC_SEGMENT(SEGMENT) (((SEGMENT) == ETH_DMATXDESC_LASTSEGMENTS) || \ - ((SEGMENT) == ETH_DMATXDESC_FIRSTSEGMENT)) -#define IS_ETH_DMA_TXDESC_CHECKSUM(CHECKSUM) (((CHECKSUM) == ETH_DMATXDESC_CHECKSUMBYPASS) || \ - ((CHECKSUM) == ETH_DMATXDESC_CHECKSUMIPV4HEADER) || \ - ((CHECKSUM) == ETH_DMATXDESC_CHECKSUMTCPUDPICMPSEGMENT) || \ - ((CHECKSUM) == ETH_DMATXDESC_CHECKSUMTCPUDPICMPFULL)) -#define IS_ETH_DMATXDESC_BUFFER_SIZE(SIZE) ((SIZE) <= 0x1FFFU) -#define IS_ETH_DMARXDESC_GET_FLAG(FLAG) (((FLAG) == ETH_DMARXDESC_OWN) || \ - ((FLAG) == ETH_DMARXDESC_AFM) || \ - ((FLAG) == ETH_DMARXDESC_ES) || \ - ((FLAG) == ETH_DMARXDESC_DE) || \ - ((FLAG) == ETH_DMARXDESC_SAF) || \ - ((FLAG) == ETH_DMARXDESC_LE) || \ - ((FLAG) == ETH_DMARXDESC_OE) || \ - ((FLAG) == ETH_DMARXDESC_VLAN) || \ - ((FLAG) == ETH_DMARXDESC_FS) || \ - ((FLAG) == ETH_DMARXDESC_LS) || \ - ((FLAG) == ETH_DMARXDESC_IPV4HCE) || \ - ((FLAG) == ETH_DMARXDESC_LC) || \ - ((FLAG) == ETH_DMARXDESC_FT) || \ - ((FLAG) == ETH_DMARXDESC_RWT) || \ - ((FLAG) == ETH_DMARXDESC_RE) || \ - ((FLAG) == ETH_DMARXDESC_DBE) || \ - ((FLAG) == ETH_DMARXDESC_CE) || \ - ((FLAG) == ETH_DMARXDESC_MAMPCE)) -#define IS_ETH_DMA_RXDESC_BUFFER(BUFFER) (((BUFFER) == ETH_DMARXDESC_BUFFER1) || \ - ((BUFFER) == ETH_DMARXDESC_BUFFER2)) -#define IS_ETH_PMT_GET_FLAG(FLAG) (((FLAG) == ETH_PMT_FLAG_WUFR) || \ - ((FLAG) == ETH_PMT_FLAG_MPR)) -#define IS_ETH_DMA_FLAG(FLAG) ((((FLAG) & 0xC7FE1800U) == 0x00U) && ((FLAG) != 0x00U)) -#define IS_ETH_DMA_GET_FLAG(FLAG) (((FLAG) == ETH_DMA_FLAG_TST) || ((FLAG) == ETH_DMA_FLAG_PMT) || \ - ((FLAG) == ETH_DMA_FLAG_MMC) || ((FLAG) == ETH_DMA_FLAG_DATATRANSFERERROR) || \ - ((FLAG) == ETH_DMA_FLAG_READWRITEERROR) || ((FLAG) == ETH_DMA_FLAG_ACCESSERROR) || \ - ((FLAG) == ETH_DMA_FLAG_NIS) || ((FLAG) == ETH_DMA_FLAG_AIS) || \ - ((FLAG) == ETH_DMA_FLAG_ER) || ((FLAG) == ETH_DMA_FLAG_FBE) || \ - ((FLAG) == ETH_DMA_FLAG_ET) || ((FLAG) == ETH_DMA_FLAG_RWT) || \ - ((FLAG) == ETH_DMA_FLAG_RPS) || ((FLAG) == ETH_DMA_FLAG_RBU) || \ - ((FLAG) == ETH_DMA_FLAG_R) || ((FLAG) == ETH_DMA_FLAG_TU) || \ - ((FLAG) == ETH_DMA_FLAG_RO) || ((FLAG) == ETH_DMA_FLAG_TJT) || \ - ((FLAG) == ETH_DMA_FLAG_TBU) || ((FLAG) == ETH_DMA_FLAG_TPS) || \ - ((FLAG) == ETH_DMA_FLAG_T)) -#define IS_ETH_MAC_IT(IT) ((((IT) & 0xFFFFFDF1U) == 0x00U) && ((IT) != 0x00U)) -#define IS_ETH_MAC_GET_IT(IT) (((IT) == ETH_MAC_IT_TST) || ((IT) == ETH_MAC_IT_MMCT) || \ - ((IT) == ETH_MAC_IT_MMCR) || ((IT) == ETH_MAC_IT_MMC) || \ - ((IT) == ETH_MAC_IT_PMT)) -#define IS_ETH_MAC_GET_FLAG(FLAG) (((FLAG) == ETH_MAC_FLAG_TST) || ((FLAG) == ETH_MAC_FLAG_MMCT) || \ - ((FLAG) == ETH_MAC_FLAG_MMCR) || ((FLAG) == ETH_MAC_FLAG_MMC) || \ - ((FLAG) == ETH_MAC_FLAG_PMT)) -#define IS_ETH_DMA_IT(IT) ((((IT) & 0xC7FE1800U) == 0x00U) && ((IT) != 0x00U)) -#define IS_ETH_DMA_GET_IT(IT) (((IT) == ETH_DMA_IT_TST) || ((IT) == ETH_DMA_IT_PMT) || \ - ((IT) == ETH_DMA_IT_MMC) || ((IT) == ETH_DMA_IT_NIS) || \ - ((IT) == ETH_DMA_IT_AIS) || ((IT) == ETH_DMA_IT_ER) || \ - ((IT) == ETH_DMA_IT_FBE) || ((IT) == ETH_DMA_IT_ET) || \ - ((IT) == ETH_DMA_IT_RWT) || ((IT) == ETH_DMA_IT_RPS) || \ - ((IT) == ETH_DMA_IT_RBU) || ((IT) == ETH_DMA_IT_R) || \ - ((IT) == ETH_DMA_IT_TU) || ((IT) == ETH_DMA_IT_RO) || \ - ((IT) == ETH_DMA_IT_TJT) || ((IT) == ETH_DMA_IT_TBU) || \ - ((IT) == ETH_DMA_IT_TPS) || ((IT) == ETH_DMA_IT_T)) -#define IS_ETH_DMA_GET_OVERFLOW(OVERFLOW) (((OVERFLOW) == ETH_DMA_OVERFLOW_RXFIFOCOUNTER) || \ - ((OVERFLOW) == ETH_DMA_OVERFLOW_MISSEDFRAMECOUNTER)) -#define IS_ETH_MMC_IT(IT) (((((IT) & 0xFFDF3FFFU) == 0x00U) || (((IT) & 0xEFFDFF9FU) == 0x00U)) && \ - ((IT) != 0x00U)) -#define IS_ETH_MMC_GET_IT(IT) (((IT) == ETH_MMC_IT_TGF) || ((IT) == ETH_MMC_IT_TGFMSC) || \ - ((IT) == ETH_MMC_IT_TGFSC) || ((IT) == ETH_MMC_IT_RGUF) || \ - ((IT) == ETH_MMC_IT_RFAE) || ((IT) == ETH_MMC_IT_RFCE)) -#define IS_ETH_ENHANCED_DESCRIPTOR_FORMAT(CMD) (((CMD) == ETH_DMAENHANCEDDESCRIPTOR_ENABLE) || \ - ((CMD) == ETH_DMAENHANCEDDESCRIPTOR_DISABLE)) - -/** - * @} - */ - -/** @addtogroup ETH_Private_Defines - * @{ - */ -/* Delay to wait when writing to some Ethernet registers */ -#define ETH_REG_WRITE_DELAY 0x00000001U - -/* ETHERNET Errors */ -#define ETH_SUCCESS 0U -#define ETH_ERROR 1U - -/* ETHERNET DMA Tx descriptors Collision Count Shift */ -#define ETH_DMATXDESC_COLLISION_COUNTSHIFT 3U - -/* ETHERNET DMA Tx descriptors Buffer2 Size Shift */ -#define ETH_DMATXDESC_BUFFER2_SIZESHIFT 16U - -/* ETHERNET DMA Rx descriptors Frame Length Shift */ -#define ETH_DMARXDESC_FRAME_LENGTHSHIFT 16U - -/* ETHERNET DMA Rx descriptors Buffer2 Size Shift */ -#define ETH_DMARXDESC_BUFFER2_SIZESHIFT 16U - -/* ETHERNET DMA Rx descriptors Frame length Shift */ -#define ETH_DMARXDESC_FRAMELENGTHSHIFT 16U - -/* ETHERNET MAC address offsets */ -#define ETH_MAC_ADDR_HBASE (uint32_t)(ETH_MAC_BASE + 0x40U) /* ETHERNET MAC address high offset */ -#define ETH_MAC_ADDR_LBASE (uint32_t)(ETH_MAC_BASE + 0x44U) /* ETHERNET MAC address low offset */ - -/* ETHERNET MACMIIAR register Mask */ -#define ETH_MACMIIAR_CR_MASK 0xFFFFFFE3U - -/* ETHERNET MACCR register Mask */ -#define ETH_MACCR_CLEAR_MASK 0xFF20810FU - -/* ETHERNET MACFCR register Mask */ -#define ETH_MACFCR_CLEAR_MASK 0x0000FF41U - -/* ETHERNET DMAOMR register Mask */ -#define ETH_DMAOMR_CLEAR_MASK 0xF8DE3F23U - -/* ETHERNET Remote Wake-up frame register length */ -#define ETH_WAKEUP_REGISTER_LENGTH 8U - -/* ETHERNET Missed frames counter Shift */ -#define ETH_DMA_RX_OVERFLOW_MISSEDFRAMES_COUNTERSHIFT 17U - /** - * @} - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup ETH_Exported_Types ETH Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_ETH_STATE_RESET = 0x00U, /*!< Peripheral not yet Initialized or disabled */ - HAL_ETH_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_ETH_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */ - HAL_ETH_STATE_BUSY_TX = 0x12U, /*!< Data Transmission process is ongoing */ - HAL_ETH_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_ETH_STATE_BUSY_TX_RX = 0x32U, /*!< Data Transmission and Reception process is ongoing */ - HAL_ETH_STATE_BUSY_WR = 0x42U, /*!< Write process is ongoing */ - HAL_ETH_STATE_BUSY_RD = 0x82U, /*!< Read process is ongoing */ - HAL_ETH_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_ETH_STATE_ERROR = 0x04U /*!< Reception process is ongoing */ -}HAL_ETH_StateTypeDef; - -/** - * @brief ETH Init Structure definition - */ - -typedef struct -{ - uint32_t AutoNegotiation; /*!< Selects or not the AutoNegotiation mode for the external PHY - The AutoNegotiation allows an automatic setting of the Speed (10/100Mbps) - and the mode (half/full-duplex). - This parameter can be a value of @ref ETH_AutoNegotiation */ - - uint32_t Speed; /*!< Sets the Ethernet speed: 10/100 Mbps. - This parameter can be a value of @ref ETH_Speed */ - - uint32_t DuplexMode; /*!< Selects the MAC duplex mode: Half-Duplex or Full-Duplex mode - This parameter can be a value of @ref ETH_Duplex_Mode */ - - uint16_t PhyAddress; /*!< Ethernet PHY address. - This parameter must be a number between Min_Data = 0 and Max_Data = 32 */ - - uint8_t *MACAddr; /*!< MAC Address of used Hardware: must be pointer on an array of 6 bytes */ - - uint32_t RxMode; /*!< Selects the Ethernet Rx mode: Polling mode, Interrupt mode. - This parameter can be a value of @ref ETH_Rx_Mode */ - - uint32_t ChecksumMode; /*!< Selects if the checksum is check by hardware or by software. - This parameter can be a value of @ref ETH_Checksum_Mode */ - - uint32_t MediaInterface; /*!< Selects the media-independent interface or the reduced media-independent interface. - This parameter can be a value of @ref ETH_Media_Interface */ - -} ETH_InitTypeDef; - - - /** - * @brief ETH MAC Configuration Structure definition - */ - -typedef struct -{ - uint32_t Watchdog; /*!< Selects or not the Watchdog timer - When enabled, the MAC allows no more then 2048 bytes to be received. - When disabled, the MAC can receive up to 16384 bytes. - This parameter can be a value of @ref ETH_Watchdog */ - - uint32_t Jabber; /*!< Selects or not Jabber timer - When enabled, the MAC allows no more then 2048 bytes to be sent. - When disabled, the MAC can send up to 16384 bytes. - This parameter can be a value of @ref ETH_Jabber */ - - uint32_t InterFrameGap; /*!< Selects the minimum IFG between frames during transmission. - This parameter can be a value of @ref ETH_Inter_Frame_Gap */ - - uint32_t CarrierSense; /*!< Selects or not the Carrier Sense. - This parameter can be a value of @ref ETH_Carrier_Sense */ - - uint32_t ReceiveOwn; /*!< Selects or not the ReceiveOwn, - ReceiveOwn allows the reception of frames when the TX_EN signal is asserted - in Half-Duplex mode. - This parameter can be a value of @ref ETH_Receive_Own */ - - uint32_t LoopbackMode; /*!< Selects or not the internal MAC MII Loopback mode. - This parameter can be a value of @ref ETH_Loop_Back_Mode */ - - uint32_t ChecksumOffload; /*!< Selects or not the IPv4 checksum checking for received frame payloads' TCP/UDP/ICMP headers. - This parameter can be a value of @ref ETH_Checksum_Offload */ - - uint32_t RetryTransmission; /*!< Selects or not the MAC attempt retries transmission, based on the settings of BL, - when a collision occurs (Half-Duplex mode). - This parameter can be a value of @ref ETH_Retry_Transmission */ - - uint32_t AutomaticPadCRCStrip; /*!< Selects or not the Automatic MAC Pad/CRC Stripping. - This parameter can be a value of @ref ETH_Automatic_Pad_CRC_Strip */ - - uint32_t BackOffLimit; /*!< Selects the BackOff limit value. - This parameter can be a value of @ref ETH_Back_Off_Limit */ - - uint32_t DeferralCheck; /*!< Selects or not the deferral check function (Half-Duplex mode). - This parameter can be a value of @ref ETH_Deferral_Check */ - - uint32_t ReceiveAll; /*!< Selects or not all frames reception by the MAC (No filtering). - This parameter can be a value of @ref ETH_Receive_All */ - - uint32_t SourceAddrFilter; /*!< Selects the Source Address Filter mode. - This parameter can be a value of @ref ETH_Source_Addr_Filter */ - - uint32_t PassControlFrames; /*!< Sets the forwarding mode of the control frames (including unicast and multicast PAUSE frames) - This parameter can be a value of @ref ETH_Pass_Control_Frames */ - - uint32_t BroadcastFramesReception; /*!< Selects or not the reception of Broadcast Frames. - This parameter can be a value of @ref ETH_Broadcast_Frames_Reception */ - - uint32_t DestinationAddrFilter; /*!< Sets the destination filter mode for both unicast and multicast frames. - This parameter can be a value of @ref ETH_Destination_Addr_Filter */ - - uint32_t PromiscuousMode; /*!< Selects or not the Promiscuous Mode - This parameter can be a value of @ref ETH_Promiscuous_Mode */ - - uint32_t MulticastFramesFilter; /*!< Selects the Multicast Frames filter mode: None/HashTableFilter/PerfectFilter/PerfectHashTableFilter. - This parameter can be a value of @ref ETH_Multicast_Frames_Filter */ - - uint32_t UnicastFramesFilter; /*!< Selects the Unicast Frames filter mode: HashTableFilter/PerfectFilter/PerfectHashTableFilter. - This parameter can be a value of @ref ETH_Unicast_Frames_Filter */ - - uint32_t HashTableHigh; /*!< This field holds the higher 32 bits of Hash table. - This parameter must be a number between Min_Data = 0x0 and Max_Data = 0xFFFFFFFFU */ - - uint32_t HashTableLow; /*!< This field holds the lower 32 bits of Hash table. - This parameter must be a number between Min_Data = 0x0 and Max_Data = 0xFFFFFFFFU */ - - uint32_t PauseTime; /*!< This field holds the value to be used in the Pause Time field in the transmit control frame. - This parameter must be a number between Min_Data = 0x0 and Max_Data = 0xFFFFU */ - - uint32_t ZeroQuantaPause; /*!< Selects or not the automatic generation of Zero-Quanta Pause Control frames. - This parameter can be a value of @ref ETH_Zero_Quanta_Pause */ - - uint32_t PauseLowThreshold; /*!< This field configures the threshold of the PAUSE to be checked for - automatic retransmission of PAUSE Frame. - This parameter can be a value of @ref ETH_Pause_Low_Threshold */ - - uint32_t UnicastPauseFrameDetect; /*!< Selects or not the MAC detection of the Pause frames (with MAC Address0 - unicast address and unique multicast address). - This parameter can be a value of @ref ETH_Unicast_Pause_Frame_Detect */ - - uint32_t ReceiveFlowControl; /*!< Enables or disables the MAC to decode the received Pause frame and - disable its transmitter for a specified time (Pause Time) - This parameter can be a value of @ref ETH_Receive_Flow_Control */ - - uint32_t TransmitFlowControl; /*!< Enables or disables the MAC to transmit Pause frames (Full-Duplex mode) - or the MAC back-pressure operation (Half-Duplex mode) - This parameter can be a value of @ref ETH_Transmit_Flow_Control */ - - uint32_t VLANTagComparison; /*!< Selects the 12-bit VLAN identifier or the complete 16-bit VLAN tag for - comparison and filtering. - This parameter can be a value of @ref ETH_VLAN_Tag_Comparison */ - - uint32_t VLANTagIdentifier; /*!< Holds the VLAN tag identifier for receive frames */ - -} ETH_MACInitTypeDef; - -/** - * @brief ETH DMA Configuration Structure definition - */ - -typedef struct -{ - uint32_t DropTCPIPChecksumErrorFrame; /*!< Selects or not the Dropping of TCP/IP Checksum Error Frames. - This parameter can be a value of @ref ETH_Drop_TCP_IP_Checksum_Error_Frame */ - - uint32_t ReceiveStoreForward; /*!< Enables or disables the Receive store and forward mode. - This parameter can be a value of @ref ETH_Receive_Store_Forward */ - - uint32_t FlushReceivedFrame; /*!< Enables or disables the flushing of received frames. - This parameter can be a value of @ref ETH_Flush_Received_Frame */ - - uint32_t TransmitStoreForward; /*!< Enables or disables Transmit store and forward mode. - This parameter can be a value of @ref ETH_Transmit_Store_Forward */ - - uint32_t TransmitThresholdControl; /*!< Selects or not the Transmit Threshold Control. - This parameter can be a value of @ref ETH_Transmit_Threshold_Control */ - - uint32_t ForwardErrorFrames; /*!< Selects or not the forward to the DMA of erroneous frames. - This parameter can be a value of @ref ETH_Forward_Error_Frames */ - - uint32_t ForwardUndersizedGoodFrames; /*!< Enables or disables the Rx FIFO to forward Undersized frames (frames with no Error - and length less than 64 bytes) including pad-bytes and CRC) - This parameter can be a value of @ref ETH_Forward_Undersized_Good_Frames */ - - uint32_t ReceiveThresholdControl; /*!< Selects the threshold level of the Receive FIFO. - This parameter can be a value of @ref ETH_Receive_Threshold_Control */ - - uint32_t SecondFrameOperate; /*!< Selects or not the Operate on second frame mode, which allows the DMA to process a second - frame of Transmit data even before obtaining the status for the first frame. - This parameter can be a value of @ref ETH_Second_Frame_Operate */ - - uint32_t AddressAlignedBeats; /*!< Enables or disables the Address Aligned Beats. - This parameter can be a value of @ref ETH_Address_Aligned_Beats */ - - uint32_t FixedBurst; /*!< Enables or disables the AHB Master interface fixed burst transfers. - This parameter can be a value of @ref ETH_Fixed_Burst */ - - uint32_t RxDMABurstLength; /*!< Indicates the maximum number of beats to be transferred in one Rx DMA transaction. - This parameter can be a value of @ref ETH_Rx_DMA_Burst_Length */ - - uint32_t TxDMABurstLength; /*!< Indicates the maximum number of beats to be transferred in one Tx DMA transaction. - This parameter can be a value of @ref ETH_Tx_DMA_Burst_Length */ - - uint32_t EnhancedDescriptorFormat; /*!< Enables the enhanced descriptor format. - This parameter can be a value of @ref ETH_DMA_Enhanced_descriptor_format */ - - uint32_t DescriptorSkipLength; /*!< Specifies the number of word to skip between two unchained descriptors (Ring mode) - This parameter must be a number between Min_Data = 0 and Max_Data = 32 */ - - uint32_t DMAArbitration; /*!< Selects the DMA Tx/Rx arbitration. - This parameter can be a value of @ref ETH_DMA_Arbitration */ -} ETH_DMAInitTypeDef; - - -/** - * @brief ETH DMA Descriptors data structure definition - */ - -typedef struct -{ - __IO uint32_t Status; /*!< Status */ - - uint32_t ControlBufferSize; /*!< Control and Buffer1, Buffer2 lengths */ - - uint32_t Buffer1Addr; /*!< Buffer1 address pointer */ - - uint32_t Buffer2NextDescAddr; /*!< Buffer2 or next descriptor address pointer */ - - /*!< Enhanced ETHERNET DMA PTP Descriptors */ - uint32_t ExtendedStatus; /*!< Extended status for PTP receive descriptor */ - - uint32_t Reserved1; /*!< Reserved */ - - uint32_t TimeStampLow; /*!< Time Stamp Low value for transmit and receive */ - - uint32_t TimeStampHigh; /*!< Time Stamp High value for transmit and receive */ - -} ETH_DMADescTypeDef; - -/** - * @brief Received Frame Informations structure definition - */ -typedef struct -{ - ETH_DMADescTypeDef *FSRxDesc; /*!< First Segment Rx Desc */ - - ETH_DMADescTypeDef *LSRxDesc; /*!< Last Segment Rx Desc */ - - uint32_t SegCount; /*!< Segment count */ - - uint32_t length; /*!< Frame length */ - - uint32_t buffer; /*!< Frame buffer */ - -} ETH_DMARxFrameInfos; - -/** - * @brief ETH Handle Structure definition - */ - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -typedef struct __ETH_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ -{ - ETH_TypeDef *Instance; /*!< Register base address */ - - ETH_InitTypeDef Init; /*!< Ethernet Init Configuration */ - - uint32_t LinkStatus; /*!< Ethernet link status */ - - ETH_DMADescTypeDef *RxDesc; /*!< Rx descriptor to Get */ - - ETH_DMADescTypeDef *TxDesc; /*!< Tx descriptor to Set */ - - ETH_DMARxFrameInfos RxFrameInfos; /*!< last Rx frame infos */ - - __IO HAL_ETH_StateTypeDef State; /*!< ETH communication state */ - - HAL_LockTypeDef Lock; /*!< ETH Lock */ - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) - - void (* TxCpltCallback) ( struct __ETH_HandleTypeDef * heth); /*!< ETH Tx Complete Callback */ - void (* RxCpltCallback) ( struct __ETH_HandleTypeDef * heth); /*!< ETH Rx Complete Callback */ - void (* DMAErrorCallback) ( struct __ETH_HandleTypeDef * heth); /*!< DMA Error Callback */ - void (* MspInitCallback) ( struct __ETH_HandleTypeDef * heth); /*!< ETH Msp Init callback */ - void (* MspDeInitCallback) ( struct __ETH_HandleTypeDef * heth); /*!< ETH Msp DeInit callback */ - -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - -} ETH_HandleTypeDef; - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -/** - * @brief HAL ETH Callback ID enumeration definition - */ -typedef enum -{ - HAL_ETH_MSPINIT_CB_ID = 0x00U, /*!< ETH MspInit callback ID */ - HAL_ETH_MSPDEINIT_CB_ID = 0x01U, /*!< ETH MspDeInit callback ID */ - HAL_ETH_TX_COMPLETE_CB_ID = 0x02U, /*!< ETH Tx Complete Callback ID */ - HAL_ETH_RX_COMPLETE_CB_ID = 0x03U, /*!< ETH Rx Complete Callback ID */ - HAL_ETH_DMA_ERROR_CB_ID = 0x04U, /*!< ETH DMA Error Callback ID */ - -}HAL_ETH_CallbackIDTypeDef; - -/** - * @brief HAL ETH Callback pointer definition - */ -typedef void (*pETH_CallbackTypeDef)(ETH_HandleTypeDef * heth); /*!< pointer to an ETH callback function */ - -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - - /** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup ETH_Exported_Constants ETH Exported Constants - * @{ - */ - -/** @defgroup ETH_Buffers_setting ETH Buffers setting - * @{ - */ -#define ETH_MAX_PACKET_SIZE 1524U /*!< ETH_HEADER + ETH_EXTRA + ETH_VLAN_TAG + ETH_MAX_ETH_PAYLOAD + ETH_CRC */ -#define ETH_HEADER 14U /*!< 6 byte Dest addr, 6 byte Src addr, 2 byte length/type */ -#define ETH_CRC 4U /*!< Ethernet CRC */ -#define ETH_EXTRA 2U /*!< Extra bytes in some cases */ -#define ETH_VLAN_TAG 4U /*!< optional 802.1q VLAN Tag */ -#define ETH_MIN_ETH_PAYLOAD 46U /*!< Minimum Ethernet payload size */ -#define ETH_MAX_ETH_PAYLOAD 1500U /*!< Maximum Ethernet payload size */ -#define ETH_JUMBO_FRAME_PAYLOAD 9000U /*!< Jumbo frame payload size */ - - /* Ethernet driver receive buffers are organized in a chained linked-list, when - an ethernet packet is received, the Rx-DMA will transfer the packet from RxFIFO - to the driver receive buffers memory. - - Depending on the size of the received ethernet packet and the size of - each ethernet driver receive buffer, the received packet can take one or more - ethernet driver receive buffer. - - In below are defined the size of one ethernet driver receive buffer ETH_RX_BUF_SIZE - and the total count of the driver receive buffers ETH_RXBUFNB. - - The configured value for ETH_RX_BUF_SIZE and ETH_RXBUFNB are only provided as - example, they can be reconfigured in the application layer to fit the application - needs */ - -/* Here we configure each Ethernet driver receive buffer to fit the Max size Ethernet - packet */ -#ifndef ETH_RX_BUF_SIZE - #define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE -#endif - -/* 5 Ethernet driver receive buffers are used (in a chained linked list)*/ -#ifndef ETH_RXBUFNB - #define ETH_RXBUFNB 5U /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ -#endif - - - /* Ethernet driver transmit buffers are organized in a chained linked-list, when - an ethernet packet is transmitted, Tx-DMA will transfer the packet from the - driver transmit buffers memory to the TxFIFO. - - Depending on the size of the Ethernet packet to be transmitted and the size of - each ethernet driver transmit buffer, the packet to be transmitted can take - one or more ethernet driver transmit buffer. - - In below are defined the size of one ethernet driver transmit buffer ETH_TX_BUF_SIZE - and the total count of the driver transmit buffers ETH_TXBUFNB. - - The configured value for ETH_TX_BUF_SIZE and ETH_TXBUFNB are only provided as - example, they can be reconfigured in the application layer to fit the application - needs */ - -/* Here we configure each Ethernet driver transmit buffer to fit the Max size Ethernet - packet */ -#ifndef ETH_TX_BUF_SIZE - #define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE -#endif - -/* 5 ethernet driver transmit buffers are used (in a chained linked list)*/ -#ifndef ETH_TXBUFNB - #define ETH_TXBUFNB 5U /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ -#endif - - /** - * @} - */ - -/** @defgroup ETH_DMA_TX_Descriptor ETH DMA TX Descriptor - * @{ - */ - -/* - DMA Tx Descriptor - ----------------------------------------------------------------------------------------------- - TDES0 | OWN(31) | CTRL[30:26] | Reserved[25:24] | CTRL[23:20] | Reserved[19:17] | Status[16:0] | - ----------------------------------------------------------------------------------------------- - TDES1 | Reserved[31:29] | Buffer2 ByteCount[28:16] | Reserved[15:13] | Buffer1 ByteCount[12:0] | - ----------------------------------------------------------------------------------------------- - TDES2 | Buffer1 Address [31:0] | - ----------------------------------------------------------------------------------------------- - TDES3 | Buffer2 Address [31:0] / Next Descriptor Address [31:0] | - ----------------------------------------------------------------------------------------------- -*/ - -/** - * @brief Bit definition of TDES0 register: DMA Tx descriptor status register - */ -#define ETH_DMATXDESC_OWN 0x80000000U /*!< OWN bit: descriptor is owned by DMA engine */ -#define ETH_DMATXDESC_IC 0x40000000U /*!< Interrupt on Completion */ -#define ETH_DMATXDESC_LS 0x20000000U /*!< Last Segment */ -#define ETH_DMATXDESC_FS 0x10000000U /*!< First Segment */ -#define ETH_DMATXDESC_DC 0x08000000U /*!< Disable CRC */ -#define ETH_DMATXDESC_DP 0x04000000U /*!< Disable Padding */ -#define ETH_DMATXDESC_TTSE 0x02000000U /*!< Transmit Time Stamp Enable */ -#define ETH_DMATXDESC_CIC 0x00C00000U /*!< Checksum Insertion Control: 4 cases */ -#define ETH_DMATXDESC_CIC_BYPASS 0x00000000U /*!< Do Nothing: Checksum Engine is bypassed */ -#define ETH_DMATXDESC_CIC_IPV4HEADER 0x00400000U /*!< IPV4 header Checksum Insertion */ -#define ETH_DMATXDESC_CIC_TCPUDPICMP_SEGMENT 0x00800000U /*!< TCP/UDP/ICMP Checksum Insertion calculated over segment only */ -#define ETH_DMATXDESC_CIC_TCPUDPICMP_FULL 0x00C00000U /*!< TCP/UDP/ICMP Checksum Insertion fully calculated */ -#define ETH_DMATXDESC_TER 0x00200000U /*!< Transmit End of Ring */ -#define ETH_DMATXDESC_TCH 0x00100000U /*!< Second Address Chained */ -#define ETH_DMATXDESC_TTSS 0x00020000U /*!< Tx Time Stamp Status */ -#define ETH_DMATXDESC_IHE 0x00010000U /*!< IP Header Error */ -#define ETH_DMATXDESC_ES 0x00008000U /*!< Error summary: OR of the following bits: UE || ED || EC || LCO || NC || LCA || FF || JT */ -#define ETH_DMATXDESC_JT 0x00004000U /*!< Jabber Timeout */ -#define ETH_DMATXDESC_FF 0x00002000U /*!< Frame Flushed: DMA/MTL flushed the frame due to SW flush */ -#define ETH_DMATXDESC_PCE 0x00001000U /*!< Payload Checksum Error */ -#define ETH_DMATXDESC_LCA 0x00000800U /*!< Loss of Carrier: carrier lost during transmission */ -#define ETH_DMATXDESC_NC 0x00000400U /*!< No Carrier: no carrier signal from the transceiver */ -#define ETH_DMATXDESC_LCO 0x00000200U /*!< Late Collision: transmission aborted due to collision */ -#define ETH_DMATXDESC_EC 0x00000100U /*!< Excessive Collision: transmission aborted after 16 collisions */ -#define ETH_DMATXDESC_VF 0x00000080U /*!< VLAN Frame */ -#define ETH_DMATXDESC_CC 0x00000078U /*!< Collision Count */ -#define ETH_DMATXDESC_ED 0x00000004U /*!< Excessive Deferral */ -#define ETH_DMATXDESC_UF 0x00000002U /*!< Underflow Error: late data arrival from the memory */ -#define ETH_DMATXDESC_DB 0x00000001U /*!< Deferred Bit */ - -/** - * @brief Bit definition of TDES1 register - */ -#define ETH_DMATXDESC_TBS2 0x1FFF0000U /*!< Transmit Buffer2 Size */ -#define ETH_DMATXDESC_TBS1 0x00001FFFU /*!< Transmit Buffer1 Size */ - -/** - * @brief Bit definition of TDES2 register - */ -#define ETH_DMATXDESC_B1AP 0xFFFFFFFFU /*!< Buffer1 Address Pointer */ - -/** - * @brief Bit definition of TDES3 register - */ -#define ETH_DMATXDESC_B2AP 0xFFFFFFFFU /*!< Buffer2 Address Pointer */ - - /*--------------------------------------------------------------------------------------------- - TDES6 | Transmit Time Stamp Low [31:0] | - ----------------------------------------------------------------------------------------------- - TDES7 | Transmit Time Stamp High [31:0] | - ----------------------------------------------------------------------------------------------*/ - -/* Bit definition of TDES6 register */ - #define ETH_DMAPTPTXDESC_TTSL 0xFFFFFFFFU /* Transmit Time Stamp Low */ - -/* Bit definition of TDES7 register */ - #define ETH_DMAPTPTXDESC_TTSH 0xFFFFFFFFU /* Transmit Time Stamp High */ - -/** - * @} - */ -/** @defgroup ETH_DMA_RX_Descriptor ETH DMA RX Descriptor - * @{ - */ - -/* - DMA Rx Descriptor - -------------------------------------------------------------------------------------------------------------------- - RDES0 | OWN(31) | Status [30:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES1 | CTRL(31) | Reserved[30:29] | Buffer2 ByteCount[28:16] | CTRL[15:14] | Reserved(13) | Buffer1 ByteCount[12:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES2 | Buffer1 Address [31:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES3 | Buffer2 Address [31:0] / Next Descriptor Address [31:0] | - --------------------------------------------------------------------------------------------------------------------- -*/ - -/** - * @brief Bit definition of RDES0 register: DMA Rx descriptor status register - */ -#define ETH_DMARXDESC_OWN 0x80000000U /*!< OWN bit: descriptor is owned by DMA engine */ -#define ETH_DMARXDESC_AFM 0x40000000U /*!< DA Filter Fail for the rx frame */ -#define ETH_DMARXDESC_FL 0x3FFF0000U /*!< Receive descriptor frame length */ -#define ETH_DMARXDESC_ES 0x00008000U /*!< Error summary: OR of the following bits: DE || OE || IPC || LC || RWT || RE || CE */ -#define ETH_DMARXDESC_DE 0x00004000U /*!< Descriptor error: no more descriptors for receive frame */ -#define ETH_DMARXDESC_SAF 0x00002000U /*!< SA Filter Fail for the received frame */ -#define ETH_DMARXDESC_LE 0x00001000U /*!< Frame size not matching with length field */ -#define ETH_DMARXDESC_OE 0x00000800U /*!< Overflow Error: Frame was damaged due to buffer overflow */ -#define ETH_DMARXDESC_VLAN 0x00000400U /*!< VLAN Tag: received frame is a VLAN frame */ -#define ETH_DMARXDESC_FS 0x00000200U /*!< First descriptor of the frame */ -#define ETH_DMARXDESC_LS 0x00000100U /*!< Last descriptor of the frame */ -#define ETH_DMARXDESC_IPV4HCE 0x00000080U /*!< IPC Checksum Error: Rx Ipv4 header checksum error */ -#define ETH_DMARXDESC_LC 0x00000040U /*!< Late collision occurred during reception */ -#define ETH_DMARXDESC_FT 0x00000020U /*!< Frame type - Ethernet, otherwise 802.3 */ -#define ETH_DMARXDESC_RWT 0x00000010U /*!< Receive Watchdog Timeout: watchdog timer expired during reception */ -#define ETH_DMARXDESC_RE 0x00000008U /*!< Receive error: error reported by MII interface */ -#define ETH_DMARXDESC_DBE 0x00000004U /*!< Dribble bit error: frame contains non int multiple of 8 bits */ -#define ETH_DMARXDESC_CE 0x00000002U /*!< CRC error */ -#define ETH_DMARXDESC_MAMPCE 0x00000001U /*!< Rx MAC Address/Payload Checksum Error: Rx MAC address matched/ Rx Payload Checksum Error */ - -/** - * @brief Bit definition of RDES1 register - */ -#define ETH_DMARXDESC_DIC 0x80000000U /*!< Disable Interrupt on Completion */ -#define ETH_DMARXDESC_RBS2 0x1FFF0000U /*!< Receive Buffer2 Size */ -#define ETH_DMARXDESC_RER 0x00008000U /*!< Receive End of Ring */ -#define ETH_DMARXDESC_RCH 0x00004000U /*!< Second Address Chained */ -#define ETH_DMARXDESC_RBS1 0x00001FFFU /*!< Receive Buffer1 Size */ - -/** - * @brief Bit definition of RDES2 register - */ -#define ETH_DMARXDESC_B1AP 0xFFFFFFFFU /*!< Buffer1 Address Pointer */ - -/** - * @brief Bit definition of RDES3 register - */ -#define ETH_DMARXDESC_B2AP 0xFFFFFFFFU /*!< Buffer2 Address Pointer */ - -/*--------------------------------------------------------------------------------------------------------------------- - RDES4 | Reserved[31:15] | Extended Status [14:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES5 | Reserved[31:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES6 | Receive Time Stamp Low [31:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES7 | Receive Time Stamp High [31:0] | - --------------------------------------------------------------------------------------------------------------------*/ - -/* Bit definition of RDES4 register */ -#define ETH_DMAPTPRXDESC_PTPV 0x00002000U /* PTP Version */ -#define ETH_DMAPTPRXDESC_PTPFT 0x00001000U /* PTP Frame Type */ -#define ETH_DMAPTPRXDESC_PTPMT 0x00000F00U /* PTP Message Type */ - #define ETH_DMAPTPRXDESC_PTPMT_SYNC 0x00000100U /* SYNC message (all clock types) */ - #define ETH_DMAPTPRXDESC_PTPMT_FOLLOWUP 0x00000200U /* FollowUp message (all clock types) */ - #define ETH_DMAPTPRXDESC_PTPMT_DELAYREQ 0x00000300U /* DelayReq message (all clock types) */ - #define ETH_DMAPTPRXDESC_PTPMT_DELAYRESP 0x00000400U /* DelayResp message (all clock types) */ - #define ETH_DMAPTPRXDESC_PTPMT_PDELAYREQ_ANNOUNCE 0x00000500U /* PdelayReq message (peer-to-peer transparent clock) or Announce message (Ordinary or Boundary clock) */ - #define ETH_DMAPTPRXDESC_PTPMT_PDELAYRESP_MANAG 0x00000600U /* PdelayResp message (peer-to-peer transparent clock) or Management message (Ordinary or Boundary clock) */ - #define ETH_DMAPTPRXDESC_PTPMT_PDELAYRESPFOLLOWUP_SIGNAL 0x00000700U /* PdelayRespFollowUp message (peer-to-peer transparent clock) or Signaling message (Ordinary or Boundary clock) */ -#define ETH_DMAPTPRXDESC_IPV6PR 0x00000080U /* IPv6 Packet Received */ -#define ETH_DMAPTPRXDESC_IPV4PR 0x00000040U /* IPv4 Packet Received */ -#define ETH_DMAPTPRXDESC_IPCB 0x00000020U /* IP Checksum Bypassed */ -#define ETH_DMAPTPRXDESC_IPPE 0x00000010U /* IP Payload Error */ -#define ETH_DMAPTPRXDESC_IPHE 0x00000008U /* IP Header Error */ -#define ETH_DMAPTPRXDESC_IPPT 0x00000007U /* IP Payload Type */ - #define ETH_DMAPTPRXDESC_IPPT_UDP 0x00000001U /* UDP payload encapsulated in the IP datagram */ - #define ETH_DMAPTPRXDESC_IPPT_TCP 0x00000002U /* TCP payload encapsulated in the IP datagram */ - #define ETH_DMAPTPRXDESC_IPPT_ICMP 0x00000003U /* ICMP payload encapsulated in the IP datagram */ - -/* Bit definition of RDES6 register */ -#define ETH_DMAPTPRXDESC_RTSL 0xFFFFFFFFU /* Receive Time Stamp Low */ - -/* Bit definition of RDES7 register */ -#define ETH_DMAPTPRXDESC_RTSH 0xFFFFFFFFU /* Receive Time Stamp High */ -/** - * @} - */ - /** @defgroup ETH_AutoNegotiation ETH AutoNegotiation - * @{ - */ -#define ETH_AUTONEGOTIATION_ENABLE 0x00000001U -#define ETH_AUTONEGOTIATION_DISABLE 0x00000000U - -/** - * @} - */ -/** @defgroup ETH_Speed ETH Speed - * @{ - */ -#define ETH_SPEED_10M 0x00000000U -#define ETH_SPEED_100M 0x00004000U - -/** - * @} - */ -/** @defgroup ETH_Duplex_Mode ETH Duplex Mode - * @{ - */ -#define ETH_MODE_FULLDUPLEX 0x00000800U -#define ETH_MODE_HALFDUPLEX 0x00000000U -/** - * @} - */ -/** @defgroup ETH_Rx_Mode ETH Rx Mode - * @{ - */ -#define ETH_RXPOLLING_MODE 0x00000000U -#define ETH_RXINTERRUPT_MODE 0x00000001U -/** - * @} - */ - -/** @defgroup ETH_Checksum_Mode ETH Checksum Mode - * @{ - */ -#define ETH_CHECKSUM_BY_HARDWARE 0x00000000U -#define ETH_CHECKSUM_BY_SOFTWARE 0x00000001U -/** - * @} - */ - -/** @defgroup ETH_Media_Interface ETH Media Interface - * @{ - */ -#define ETH_MEDIA_INTERFACE_MII 0x00000000U -#define ETH_MEDIA_INTERFACE_RMII ((uint32_t)SYSCFG_PMC_MII_RMII_SEL) -/** - * @} - */ - -/** @defgroup ETH_Watchdog ETH Watchdog - * @{ - */ -#define ETH_WATCHDOG_ENABLE 0x00000000U -#define ETH_WATCHDOG_DISABLE 0x00800000U -/** - * @} - */ - -/** @defgroup ETH_Jabber ETH Jabber - * @{ - */ -#define ETH_JABBER_ENABLE 0x00000000U -#define ETH_JABBER_DISABLE 0x00400000U -/** - * @} - */ - -/** @defgroup ETH_Inter_Frame_Gap ETH Inter Frame Gap - * @{ - */ -#define ETH_INTERFRAMEGAP_96BIT 0x00000000U /*!< minimum IFG between frames during transmission is 96Bit */ -#define ETH_INTERFRAMEGAP_88BIT 0x00020000U /*!< minimum IFG between frames during transmission is 88Bit */ -#define ETH_INTERFRAMEGAP_80BIT 0x00040000U /*!< minimum IFG between frames during transmission is 80Bit */ -#define ETH_INTERFRAMEGAP_72BIT 0x00060000U /*!< minimum IFG between frames during transmission is 72Bit */ -#define ETH_INTERFRAMEGAP_64BIT 0x00080000U /*!< minimum IFG between frames during transmission is 64Bit */ -#define ETH_INTERFRAMEGAP_56BIT 0x000A0000U /*!< minimum IFG between frames during transmission is 56Bit */ -#define ETH_INTERFRAMEGAP_48BIT 0x000C0000U /*!< minimum IFG between frames during transmission is 48Bit */ -#define ETH_INTERFRAMEGAP_40BIT 0x000E0000U /*!< minimum IFG between frames during transmission is 40Bit */ -/** - * @} - */ - -/** @defgroup ETH_Carrier_Sense ETH Carrier Sense - * @{ - */ -#define ETH_CARRIERSENCE_ENABLE 0x00000000U -#define ETH_CARRIERSENCE_DISABLE 0x00010000U -/** - * @} - */ - -/** @defgroup ETH_Receive_Own ETH Receive Own - * @{ - */ -#define ETH_RECEIVEOWN_ENABLE 0x00000000U -#define ETH_RECEIVEOWN_DISABLE 0x00002000U -/** - * @} - */ - -/** @defgroup ETH_Loop_Back_Mode ETH Loop Back Mode - * @{ - */ -#define ETH_LOOPBACKMODE_ENABLE 0x00001000U -#define ETH_LOOPBACKMODE_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Checksum_Offload ETH Checksum Offload - * @{ - */ -#define ETH_CHECKSUMOFFLAOD_ENABLE 0x00000400U -#define ETH_CHECKSUMOFFLAOD_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Retry_Transmission ETH Retry Transmission - * @{ - */ -#define ETH_RETRYTRANSMISSION_ENABLE 0x00000000U -#define ETH_RETRYTRANSMISSION_DISABLE 0x00000200U -/** - * @} - */ - -/** @defgroup ETH_Automatic_Pad_CRC_Strip ETH Automatic Pad CRC Strip - * @{ - */ -#define ETH_AUTOMATICPADCRCSTRIP_ENABLE 0x00000080U -#define ETH_AUTOMATICPADCRCSTRIP_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Back_Off_Limit ETH Back Off Limit - * @{ - */ -#define ETH_BACKOFFLIMIT_10 0x00000000U -#define ETH_BACKOFFLIMIT_8 0x00000020U -#define ETH_BACKOFFLIMIT_4 0x00000040U -#define ETH_BACKOFFLIMIT_1 0x00000060U -/** - * @} - */ - -/** @defgroup ETH_Deferral_Check ETH Deferral Check - * @{ - */ -#define ETH_DEFFERRALCHECK_ENABLE 0x00000010U -#define ETH_DEFFERRALCHECK_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Receive_All ETH Receive All - * @{ - */ -#define ETH_RECEIVEALL_ENABLE 0x80000000U -#define ETH_RECEIVEAll_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Source_Addr_Filter ETH Source Addr Filter - * @{ - */ -#define ETH_SOURCEADDRFILTER_NORMAL_ENABLE 0x00000200U -#define ETH_SOURCEADDRFILTER_INVERSE_ENABLE 0x00000300U -#define ETH_SOURCEADDRFILTER_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Pass_Control_Frames ETH Pass Control Frames - * @{ - */ -#define ETH_PASSCONTROLFRAMES_BLOCKALL 0x00000040U /*!< MAC filters all control frames from reaching the application */ -#define ETH_PASSCONTROLFRAMES_FORWARDALL 0x00000080U /*!< MAC forwards all control frames to application even if they fail the Address Filter */ -#define ETH_PASSCONTROLFRAMES_FORWARDPASSEDADDRFILTER 0x000000C0U /*!< MAC forwards control frames that pass the Address Filter. */ -/** - * @} - */ - -/** @defgroup ETH_Broadcast_Frames_Reception ETH Broadcast Frames Reception - * @{ - */ -#define ETH_BROADCASTFRAMESRECEPTION_ENABLE 0x00000000U -#define ETH_BROADCASTFRAMESRECEPTION_DISABLE 0x00000020U -/** - * @} - */ - -/** @defgroup ETH_Destination_Addr_Filter ETH Destination Addr Filter - * @{ - */ -#define ETH_DESTINATIONADDRFILTER_NORMAL 0x00000000U -#define ETH_DESTINATIONADDRFILTER_INVERSE 0x00000008U -/** - * @} - */ - -/** @defgroup ETH_Promiscuous_Mode ETH Promiscuous Mode - * @{ - */ -#define ETH_PROMISCUOUS_MODE_ENABLE 0x00000001U -#define ETH_PROMISCUOUS_MODE_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Multicast_Frames_Filter ETH Multicast Frames Filter - * @{ - */ -#define ETH_MULTICASTFRAMESFILTER_PERFECTHASHTABLE 0x00000404U -#define ETH_MULTICASTFRAMESFILTER_HASHTABLE 0x00000004U -#define ETH_MULTICASTFRAMESFILTER_PERFECT 0x00000000U -#define ETH_MULTICASTFRAMESFILTER_NONE 0x00000010U -/** - * @} - */ - -/** @defgroup ETH_Unicast_Frames_Filter ETH Unicast Frames Filter - * @{ - */ -#define ETH_UNICASTFRAMESFILTER_PERFECTHASHTABLE 0x00000402U -#define ETH_UNICASTFRAMESFILTER_HASHTABLE 0x00000002U -#define ETH_UNICASTFRAMESFILTER_PERFECT 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Zero_Quanta_Pause ETH Zero Quanta Pause - * @{ - */ -#define ETH_ZEROQUANTAPAUSE_ENABLE 0x00000000U -#define ETH_ZEROQUANTAPAUSE_DISABLE 0x00000080U -/** - * @} - */ - -/** @defgroup ETH_Pause_Low_Threshold ETH Pause Low Threshold - * @{ - */ -#define ETH_PAUSELOWTHRESHOLD_MINUS4 0x00000000U /*!< Pause time minus 4 slot times */ -#define ETH_PAUSELOWTHRESHOLD_MINUS28 0x00000010U /*!< Pause time minus 28 slot times */ -#define ETH_PAUSELOWTHRESHOLD_MINUS144 0x00000020U /*!< Pause time minus 144 slot times */ -#define ETH_PAUSELOWTHRESHOLD_MINUS256 0x00000030U /*!< Pause time minus 256 slot times */ -/** - * @} - */ - -/** @defgroup ETH_Unicast_Pause_Frame_Detect ETH Unicast Pause Frame Detect - * @{ - */ -#define ETH_UNICASTPAUSEFRAMEDETECT_ENABLE 0x00000008U -#define ETH_UNICASTPAUSEFRAMEDETECT_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Receive_Flow_Control ETH Receive Flow Control - * @{ - */ -#define ETH_RECEIVEFLOWCONTROL_ENABLE 0x00000004U -#define ETH_RECEIVEFLOWCONTROL_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Transmit_Flow_Control ETH Transmit Flow Control - * @{ - */ -#define ETH_TRANSMITFLOWCONTROL_ENABLE 0x00000002U -#define ETH_TRANSMITFLOWCONTROL_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_VLAN_Tag_Comparison ETH VLAN Tag Comparison - * @{ - */ -#define ETH_VLANTAGCOMPARISON_12BIT 0x00010000U -#define ETH_VLANTAGCOMPARISON_16BIT 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_MAC_addresses ETH MAC addresses - * @{ - */ -#define ETH_MAC_ADDRESS0 0x00000000U -#define ETH_MAC_ADDRESS1 0x00000008U -#define ETH_MAC_ADDRESS2 0x00000010U -#define ETH_MAC_ADDRESS3 0x00000018U -/** - * @} - */ - -/** @defgroup ETH_MAC_addresses_filter_SA_DA ETH MAC addresses filter SA DA - * @{ - */ -#define ETH_MAC_ADDRESSFILTER_SA 0x00000000U -#define ETH_MAC_ADDRESSFILTER_DA 0x00000008U -/** - * @} - */ - -/** @defgroup ETH_MAC_addresses_filter_Mask_bytes ETH MAC addresses filter Mask bytes - * @{ - */ -#define ETH_MAC_ADDRESSMASK_BYTE6 0x20000000U /*!< Mask MAC Address high reg bits [15:8] */ -#define ETH_MAC_ADDRESSMASK_BYTE5 0x10000000U /*!< Mask MAC Address high reg bits [7:0] */ -#define ETH_MAC_ADDRESSMASK_BYTE4 0x08000000U /*!< Mask MAC Address low reg bits [31:24] */ -#define ETH_MAC_ADDRESSMASK_BYTE3 0x04000000U /*!< Mask MAC Address low reg bits [23:16] */ -#define ETH_MAC_ADDRESSMASK_BYTE2 0x02000000U /*!< Mask MAC Address low reg bits [15:8] */ -#define ETH_MAC_ADDRESSMASK_BYTE1 0x01000000U /*!< Mask MAC Address low reg bits [70] */ -/** - * @} - */ - -/** @defgroup ETH_Drop_TCP_IP_Checksum_Error_Frame ETH Drop TCP IP Checksum Error Frame - * @{ - */ -#define ETH_DROPTCPIPCHECKSUMERRORFRAME_ENABLE 0x00000000U -#define ETH_DROPTCPIPCHECKSUMERRORFRAME_DISABLE 0x04000000U -/** - * @} - */ - -/** @defgroup ETH_Receive_Store_Forward ETH Receive Store Forward - * @{ - */ -#define ETH_RECEIVESTOREFORWARD_ENABLE 0x02000000U -#define ETH_RECEIVESTOREFORWARD_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Flush_Received_Frame ETH Flush Received Frame - * @{ - */ -#define ETH_FLUSHRECEIVEDFRAME_ENABLE 0x00000000U -#define ETH_FLUSHRECEIVEDFRAME_DISABLE 0x01000000U -/** - * @} - */ - -/** @defgroup ETH_Transmit_Store_Forward ETH Transmit Store Forward - * @{ - */ -#define ETH_TRANSMITSTOREFORWARD_ENABLE 0x00200000U -#define ETH_TRANSMITSTOREFORWARD_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Transmit_Threshold_Control ETH Transmit Threshold Control - * @{ - */ -#define ETH_TRANSMITTHRESHOLDCONTROL_64BYTES 0x00000000U /*!< threshold level of the MTL Transmit FIFO is 64 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_128BYTES 0x00004000U /*!< threshold level of the MTL Transmit FIFO is 128 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_192BYTES 0x00008000U /*!< threshold level of the MTL Transmit FIFO is 192 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_256BYTES 0x0000C000U /*!< threshold level of the MTL Transmit FIFO is 256 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_40BYTES 0x00010000U /*!< threshold level of the MTL Transmit FIFO is 40 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_32BYTES 0x00014000U /*!< threshold level of the MTL Transmit FIFO is 32 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_24BYTES 0x00018000U /*!< threshold level of the MTL Transmit FIFO is 24 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_16BYTES 0x0001C000U /*!< threshold level of the MTL Transmit FIFO is 16 Bytes */ -/** - * @} - */ - -/** @defgroup ETH_Forward_Error_Frames ETH Forward Error Frames - * @{ - */ -#define ETH_FORWARDERRORFRAMES_ENABLE 0x00000080U -#define ETH_FORWARDERRORFRAMES_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Forward_Undersized_Good_Frames ETH Forward Undersized Good Frames - * @{ - */ -#define ETH_FORWARDUNDERSIZEDGOODFRAMES_ENABLE 0x00000040U -#define ETH_FORWARDUNDERSIZEDGOODFRAMES_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Receive_Threshold_Control ETH Receive Threshold Control - * @{ - */ -#define ETH_RECEIVEDTHRESHOLDCONTROL_64BYTES 0x00000000U /*!< threshold level of the MTL Receive FIFO is 64 Bytes */ -#define ETH_RECEIVEDTHRESHOLDCONTROL_32BYTES 0x00000008U /*!< threshold level of the MTL Receive FIFO is 32 Bytes */ -#define ETH_RECEIVEDTHRESHOLDCONTROL_96BYTES 0x00000010U /*!< threshold level of the MTL Receive FIFO is 96 Bytes */ -#define ETH_RECEIVEDTHRESHOLDCONTROL_128BYTES 0x00000018U /*!< threshold level of the MTL Receive FIFO is 128 Bytes */ -/** - * @} - */ - -/** @defgroup ETH_Second_Frame_Operate ETH Second Frame Operate - * @{ - */ -#define ETH_SECONDFRAMEOPERARTE_ENABLE 0x00000004U -#define ETH_SECONDFRAMEOPERARTE_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Address_Aligned_Beats ETH Address Aligned Beats - * @{ - */ -#define ETH_ADDRESSALIGNEDBEATS_ENABLE 0x02000000U -#define ETH_ADDRESSALIGNEDBEATS_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Fixed_Burst ETH Fixed Burst - * @{ - */ -#define ETH_FIXEDBURST_ENABLE 0x00010000U -#define ETH_FIXEDBURST_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Rx_DMA_Burst_Length ETH Rx DMA Burst Length - * @{ - */ -#define ETH_RXDMABURSTLENGTH_1BEAT 0x00020000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 1 */ -#define ETH_RXDMABURSTLENGTH_2BEAT 0x00040000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 2 */ -#define ETH_RXDMABURSTLENGTH_4BEAT 0x00080000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 4 */ -#define ETH_RXDMABURSTLENGTH_8BEAT 0x00100000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 8 */ -#define ETH_RXDMABURSTLENGTH_16BEAT 0x00200000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 16 */ -#define ETH_RXDMABURSTLENGTH_32BEAT 0x00400000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 32 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_4BEAT 0x01020000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 4 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_8BEAT 0x01040000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 8 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_16BEAT 0x01080000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 16 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_32BEAT 0x01100000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 32 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_64BEAT 0x01200000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 64 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_128BEAT 0x01400000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 128 */ -/** - * @} - */ - -/** @defgroup ETH_Tx_DMA_Burst_Length ETH Tx DMA Burst Length - * @{ - */ -#define ETH_TXDMABURSTLENGTH_1BEAT 0x00000100U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 1 */ -#define ETH_TXDMABURSTLENGTH_2BEAT 0x00000200U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 2 */ -#define ETH_TXDMABURSTLENGTH_4BEAT 0x00000400U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */ -#define ETH_TXDMABURSTLENGTH_8BEAT 0x00000800U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */ -#define ETH_TXDMABURSTLENGTH_16BEAT 0x00001000U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */ -#define ETH_TXDMABURSTLENGTH_32BEAT 0x00002000U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_4BEAT 0x01000100U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_8BEAT 0x01000200U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_16BEAT 0x01000400U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_32BEAT 0x01000800U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_64BEAT 0x01001000U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 64 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_128BEAT 0x01002000U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 128 */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Enhanced_descriptor_format ETH DMA Enhanced descriptor format - * @{ - */ -#define ETH_DMAENHANCEDDESCRIPTOR_ENABLE 0x00000080U -#define ETH_DMAENHANCEDDESCRIPTOR_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_DMA_Arbitration ETH DMA Arbitration - * @{ - */ -#define ETH_DMAARBITRATION_ROUNDROBIN_RXTX_1_1 0x00000000U -#define ETH_DMAARBITRATION_ROUNDROBIN_RXTX_2_1 0x00004000U -#define ETH_DMAARBITRATION_ROUNDROBIN_RXTX_3_1 0x00008000U -#define ETH_DMAARBITRATION_ROUNDROBIN_RXTX_4_1 0x0000C000U -#define ETH_DMAARBITRATION_RXPRIORTX 0x00000002U -/** - * @} - */ - -/** @defgroup ETH_DMA_Tx_descriptor_segment ETH DMA Tx descriptor segment - * @{ - */ -#define ETH_DMATXDESC_LASTSEGMENTS 0x40000000U /*!< Last Segment */ -#define ETH_DMATXDESC_FIRSTSEGMENT 0x20000000U /*!< First Segment */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Tx_descriptor_Checksum_Insertion_Control ETH DMA Tx descriptor Checksum Insertion Control - * @{ - */ -#define ETH_DMATXDESC_CHECKSUMBYPASS 0x00000000U /*!< Checksum engine bypass */ -#define ETH_DMATXDESC_CHECKSUMIPV4HEADER 0x00400000U /*!< IPv4 header checksum insertion */ -#define ETH_DMATXDESC_CHECKSUMTCPUDPICMPSEGMENT 0x00800000U /*!< TCP/UDP/ICMP checksum insertion. Pseudo header checksum is assumed to be present */ -#define ETH_DMATXDESC_CHECKSUMTCPUDPICMPFULL 0x00C00000U /*!< TCP/UDP/ICMP checksum fully in hardware including pseudo header */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Rx_descriptor_buffers ETH DMA Rx descriptor buffers - * @{ - */ -#define ETH_DMARXDESC_BUFFER1 0x00000000U /*!< DMA Rx Desc Buffer1 */ -#define ETH_DMARXDESC_BUFFER2 0x00000001U /*!< DMA Rx Desc Buffer2 */ -/** - * @} - */ - -/** @defgroup ETH_PMT_Flags ETH PMT Flags - * @{ - */ -#define ETH_PMT_FLAG_WUFFRPR 0x80000000U /*!< Wake-Up Frame Filter Register Pointer Reset */ -#define ETH_PMT_FLAG_WUFR 0x00000040U /*!< Wake-Up Frame Received */ -#define ETH_PMT_FLAG_MPR 0x00000020U /*!< Magic Packet Received */ -/** - * @} - */ - -/** @defgroup ETH_MMC_Tx_Interrupts ETH MMC Tx Interrupts - * @{ - */ -#define ETH_MMC_IT_TGF 0x00200000U /*!< When Tx good frame counter reaches half the maximum value */ -#define ETH_MMC_IT_TGFMSC 0x00008000U /*!< When Tx good multi col counter reaches half the maximum value */ -#define ETH_MMC_IT_TGFSC 0x00004000U /*!< When Tx good single col counter reaches half the maximum value */ -/** - * @} - */ - -/** @defgroup ETH_MMC_Rx_Interrupts ETH MMC Rx Interrupts - * @{ - */ -#define ETH_MMC_IT_RGUF 0x10020000U /*!< When Rx good unicast frames counter reaches half the maximum value */ -#define ETH_MMC_IT_RFAE 0x10000040U /*!< When Rx alignment error counter reaches half the maximum value */ -#define ETH_MMC_IT_RFCE 0x10000020U /*!< When Rx crc error counter reaches half the maximum value */ -/** - * @} - */ - -/** @defgroup ETH_MAC_Flags ETH MAC Flags - * @{ - */ -#define ETH_MAC_FLAG_TST 0x00000200U /*!< Time stamp trigger flag (on MAC) */ -#define ETH_MAC_FLAG_MMCT 0x00000040U /*!< MMC transmit flag */ -#define ETH_MAC_FLAG_MMCR 0x00000020U /*!< MMC receive flag */ -#define ETH_MAC_FLAG_MMC 0x00000010U /*!< MMC flag (on MAC) */ -#define ETH_MAC_FLAG_PMT 0x00000008U /*!< PMT flag (on MAC) */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Flags ETH DMA Flags - * @{ - */ -#define ETH_DMA_FLAG_TST 0x20000000U /*!< Time-stamp trigger interrupt (on DMA) */ -#define ETH_DMA_FLAG_PMT 0x10000000U /*!< PMT interrupt (on DMA) */ -#define ETH_DMA_FLAG_MMC 0x08000000U /*!< MMC interrupt (on DMA) */ -#define ETH_DMA_FLAG_DATATRANSFERERROR 0x00800000U /*!< Error bits 0-Rx DMA, 1-Tx DMA */ -#define ETH_DMA_FLAG_READWRITEERROR 0x01000000U /*!< Error bits 0-write transfer, 1-read transfer */ -#define ETH_DMA_FLAG_ACCESSERROR 0x02000000U /*!< Error bits 0-data buffer, 1-desc. access */ -#define ETH_DMA_FLAG_NIS 0x00010000U /*!< Normal interrupt summary flag */ -#define ETH_DMA_FLAG_AIS 0x00008000U /*!< Abnormal interrupt summary flag */ -#define ETH_DMA_FLAG_ER 0x00004000U /*!< Early receive flag */ -#define ETH_DMA_FLAG_FBE 0x00002000U /*!< Fatal bus error flag */ -#define ETH_DMA_FLAG_ET 0x00000400U /*!< Early transmit flag */ -#define ETH_DMA_FLAG_RWT 0x00000200U /*!< Receive watchdog timeout flag */ -#define ETH_DMA_FLAG_RPS 0x00000100U /*!< Receive process stopped flag */ -#define ETH_DMA_FLAG_RBU 0x00000080U /*!< Receive buffer unavailable flag */ -#define ETH_DMA_FLAG_R 0x00000040U /*!< Receive flag */ -#define ETH_DMA_FLAG_TU 0x00000020U /*!< Underflow flag */ -#define ETH_DMA_FLAG_RO 0x00000010U /*!< Overflow flag */ -#define ETH_DMA_FLAG_TJT 0x00000008U /*!< Transmit jabber timeout flag */ -#define ETH_DMA_FLAG_TBU 0x00000004U /*!< Transmit buffer unavailable flag */ -#define ETH_DMA_FLAG_TPS 0x00000002U /*!< Transmit process stopped flag */ -#define ETH_DMA_FLAG_T 0x00000001U /*!< Transmit flag */ -/** - * @} - */ - -/** @defgroup ETH_MAC_Interrupts ETH MAC Interrupts - * @{ - */ -#define ETH_MAC_IT_TST 0x00000200U /*!< Time stamp trigger interrupt (on MAC) */ -#define ETH_MAC_IT_MMCT 0x00000040U /*!< MMC transmit interrupt */ -#define ETH_MAC_IT_MMCR 0x00000020U /*!< MMC receive interrupt */ -#define ETH_MAC_IT_MMC 0x00000010U /*!< MMC interrupt (on MAC) */ -#define ETH_MAC_IT_PMT 0x00000008U /*!< PMT interrupt (on MAC) */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Interrupts ETH DMA Interrupts - * @{ - */ -#define ETH_DMA_IT_TST 0x20000000U /*!< Time-stamp trigger interrupt (on DMA) */ -#define ETH_DMA_IT_PMT 0x10000000U /*!< PMT interrupt (on DMA) */ -#define ETH_DMA_IT_MMC 0x08000000U /*!< MMC interrupt (on DMA) */ -#define ETH_DMA_IT_NIS 0x00010000U /*!< Normal interrupt summary */ -#define ETH_DMA_IT_AIS 0x00008000U /*!< Abnormal interrupt summary */ -#define ETH_DMA_IT_ER 0x00004000U /*!< Early receive interrupt */ -#define ETH_DMA_IT_FBE 0x00002000U /*!< Fatal bus error interrupt */ -#define ETH_DMA_IT_ET 0x00000400U /*!< Early transmit interrupt */ -#define ETH_DMA_IT_RWT 0x00000200U /*!< Receive watchdog timeout interrupt */ -#define ETH_DMA_IT_RPS 0x00000100U /*!< Receive process stopped interrupt */ -#define ETH_DMA_IT_RBU 0x00000080U /*!< Receive buffer unavailable interrupt */ -#define ETH_DMA_IT_R 0x00000040U /*!< Receive interrupt */ -#define ETH_DMA_IT_TU 0x00000020U /*!< Underflow interrupt */ -#define ETH_DMA_IT_RO 0x00000010U /*!< Overflow interrupt */ -#define ETH_DMA_IT_TJT 0x00000008U /*!< Transmit jabber timeout interrupt */ -#define ETH_DMA_IT_TBU 0x00000004U /*!< Transmit buffer unavailable interrupt */ -#define ETH_DMA_IT_TPS 0x00000002U /*!< Transmit process stopped interrupt */ -#define ETH_DMA_IT_T 0x00000001U /*!< Transmit interrupt */ -/** - * @} - */ - -/** @defgroup ETH_DMA_transmit_process_state ETH DMA transmit process state - * @{ - */ -#define ETH_DMA_TRANSMITPROCESS_STOPPED 0x00000000U /*!< Stopped - Reset or Stop Tx Command issued */ -#define ETH_DMA_TRANSMITPROCESS_FETCHING 0x00100000U /*!< Running - fetching the Tx descriptor */ -#define ETH_DMA_TRANSMITPROCESS_WAITING 0x00200000U /*!< Running - waiting for status */ -#define ETH_DMA_TRANSMITPROCESS_READING 0x00300000U /*!< Running - reading the data from host memory */ -#define ETH_DMA_TRANSMITPROCESS_SUSPENDED 0x00600000U /*!< Suspended - Tx Descriptor unavailable */ -#define ETH_DMA_TRANSMITPROCESS_CLOSING 0x00700000U /*!< Running - closing Rx descriptor */ - -/** - * @} - */ - - -/** @defgroup ETH_DMA_receive_process_state ETH DMA receive process state - * @{ - */ -#define ETH_DMA_RECEIVEPROCESS_STOPPED 0x00000000U /*!< Stopped - Reset or Stop Rx Command issued */ -#define ETH_DMA_RECEIVEPROCESS_FETCHING 0x00020000U /*!< Running - fetching the Rx descriptor */ -#define ETH_DMA_RECEIVEPROCESS_WAITING 0x00060000U /*!< Running - waiting for packet */ -#define ETH_DMA_RECEIVEPROCESS_SUSPENDED 0x00080000U /*!< Suspended - Rx Descriptor unavailable */ -#define ETH_DMA_RECEIVEPROCESS_CLOSING 0x000A0000U /*!< Running - closing descriptor */ -#define ETH_DMA_RECEIVEPROCESS_QUEUING 0x000E0000U /*!< Running - queuing the receive frame into host memory */ - -/** - * @} - */ - -/** @defgroup ETH_DMA_overflow ETH DMA overflow - * @{ - */ -#define ETH_DMA_OVERFLOW_RXFIFOCOUNTER 0x10000000U /*!< Overflow bit for FIFO overflow counter */ -#define ETH_DMA_OVERFLOW_MISSEDFRAMECOUNTER 0x00010000U /*!< Overflow bit for missed frame counter */ -/** - * @} - */ - -/** @defgroup ETH_EXTI_LINE_WAKEUP ETH EXTI LINE WAKEUP - * @{ - */ -#define ETH_EXTI_LINE_WAKEUP 0x00080000U /*!< External interrupt line 19 Connected to the ETH EXTI Line */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup ETH_Exported_Macros ETH Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ - -/** @brief Reset ETH handle state - * @param __HANDLE__ specifies the ETH handle. - * @retval None - */ -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -#define __HAL_ETH_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_ETH_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_ETH_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_ETH_STATE_RESET) -#endif /*USE_HAL_ETH_REGISTER_CALLBACKS */ - -/** - * @brief Checks whether the specified ETHERNET DMA Tx Desc flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag of TDES0 to check. - * @retval the ETH_DMATxDescFlag (SET or RESET). - */ -#define __HAL_ETH_DMATXDESC_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->TxDesc->Status & (__FLAG__) == (__FLAG__)) - -/** - * @brief Checks whether the specified ETHERNET DMA Rx Desc flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag of RDES0 to check. - * @retval the ETH_DMATxDescFlag (SET or RESET). - */ -#define __HAL_ETH_DMARXDESC_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->RxDesc->Status & (__FLAG__) == (__FLAG__)) - -/** - * @brief Enables the specified DMA Rx Desc receive interrupt. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMARXDESC_ENABLE_IT(__HANDLE__) ((__HANDLE__)->RxDesc->ControlBufferSize &=(~(uint32_t)ETH_DMARXDESC_DIC)) - -/** - * @brief Disables the specified DMA Rx Desc receive interrupt. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMARXDESC_DISABLE_IT(__HANDLE__) ((__HANDLE__)->RxDesc->ControlBufferSize |= ETH_DMARXDESC_DIC) - -/** - * @brief Set the specified DMA Rx Desc Own bit. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMARXDESC_SET_OWN_BIT(__HANDLE__) ((__HANDLE__)->RxDesc->Status |= ETH_DMARXDESC_OWN) - -/** - * @brief Returns the specified ETHERNET DMA Tx Desc collision count. - * @param __HANDLE__ ETH Handle - * @retval The Transmit descriptor collision counter value. - */ -#define __HAL_ETH_DMATXDESC_GET_COLLISION_COUNT(__HANDLE__) (((__HANDLE__)->TxDesc->Status & ETH_DMATXDESC_CC) >> ETH_DMATXDESC_COLLISION_COUNTSHIFT) - -/** - * @brief Set the specified DMA Tx Desc Own bit. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_SET_OWN_BIT(__HANDLE__) ((__HANDLE__)->TxDesc->Status |= ETH_DMATXDESC_OWN) - -/** - * @brief Enables the specified DMA Tx Desc Transmit interrupt. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_ENABLE_IT(__HANDLE__) ((__HANDLE__)->TxDesc->Status |= ETH_DMATXDESC_IC) - -/** - * @brief Disables the specified DMA Tx Desc Transmit interrupt. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_DISABLE_IT(__HANDLE__) ((__HANDLE__)->TxDesc->Status &= ~ETH_DMATXDESC_IC) - -/** - * @brief Selects the specified ETHERNET DMA Tx Desc Checksum Insertion. - * @param __HANDLE__ ETH Handle - * @param __CHECKSUM__ specifies is the DMA Tx desc checksum insertion. - * This parameter can be one of the following values: - * @arg ETH_DMATXDESC_CHECKSUMBYPASS : Checksum bypass - * @arg ETH_DMATXDESC_CHECKSUMIPV4HEADER : IPv4 header checksum - * @arg ETH_DMATXDESC_CHECKSUMTCPUDPICMPSEGMENT : TCP/UDP/ICMP checksum. Pseudo header checksum is assumed to be present - * @arg ETH_DMATXDESC_CHECKSUMTCPUDPICMPFULL : TCP/UDP/ICMP checksum fully in hardware including pseudo header - * @retval None - */ -#define __HAL_ETH_DMATXDESC_CHECKSUM_INSERTION(__HANDLE__, __CHECKSUM__) ((__HANDLE__)->TxDesc->Status |= (__CHECKSUM__)) - -/** - * @brief Enables the DMA Tx Desc CRC. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_CRC_ENABLE(__HANDLE__) ((__HANDLE__)->TxDesc->Status &= ~ETH_DMATXDESC_DC) - -/** - * @brief Disables the DMA Tx Desc CRC. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_CRC_DISABLE(__HANDLE__) ((__HANDLE__)->TxDesc->Status |= ETH_DMATXDESC_DC) - -/** - * @brief Enables the DMA Tx Desc padding for frame shorter than 64 bytes. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_SHORT_FRAME_PADDING_ENABLE(__HANDLE__) ((__HANDLE__)->TxDesc->Status &= ~ETH_DMATXDESC_DP) - -/** - * @brief Disables the DMA Tx Desc padding for frame shorter than 64 bytes. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_SHORT_FRAME_PADDING_DISABLE(__HANDLE__) ((__HANDLE__)->TxDesc->Status |= ETH_DMATXDESC_DP) - -/** - * @brief Enables the specified ETHERNET MAC interrupts. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the ETHERNET MAC interrupt sources to be - * enabled or disabled. - * This parameter can be any combination of the following values: - * @arg ETH_MAC_IT_TST : Time stamp trigger interrupt - * @arg ETH_MAC_IT_PMT : PMT interrupt - * @retval None - */ -#define __HAL_ETH_MAC_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MACIMR |= (__INTERRUPT__)) - -/** - * @brief Disables the specified ETHERNET MAC interrupts. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the ETHERNET MAC interrupt sources to be - * enabled or disabled. - * This parameter can be any combination of the following values: - * @arg ETH_MAC_IT_TST : Time stamp trigger interrupt - * @arg ETH_MAC_IT_PMT : PMT interrupt - * @retval None - */ -#define __HAL_ETH_MAC_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MACIMR &= ~(__INTERRUPT__)) - -/** - * @brief Initiate a Pause Control Frame (Full-duplex only). - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_INITIATE_PAUSE_CONTROL_FRAME(__HANDLE__) ((__HANDLE__)->Instance->MACFCR |= ETH_MACFCR_FCBBPA) - -/** - * @brief Checks whether the ETHERNET flow control busy bit is set or not. - * @param __HANDLE__ ETH Handle - * @retval The new state of flow control busy status bit (SET or RESET). - */ -#define __HAL_ETH_GET_FLOW_CONTROL_BUSY_STATUS(__HANDLE__) (((__HANDLE__)->Instance->MACFCR & ETH_MACFCR_FCBBPA) == ETH_MACFCR_FCBBPA) - -/** - * @brief Enables the MAC Back Pressure operation activation (Half-duplex only). - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_BACK_PRESSURE_ACTIVATION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACFCR |= ETH_MACFCR_FCBBPA) - -/** - * @brief Disables the MAC BackPressure operation activation (Half-duplex only). - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_BACK_PRESSURE_ACTIVATION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACFCR &= ~ETH_MACFCR_FCBBPA) - -/** - * @brief Checks whether the specified ETHERNET MAC flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg ETH_MAC_FLAG_TST : Time stamp trigger flag - * @arg ETH_MAC_FLAG_MMCT : MMC transmit flag - * @arg ETH_MAC_FLAG_MMCR : MMC receive flag - * @arg ETH_MAC_FLAG_MMC : MMC flag - * @arg ETH_MAC_FLAG_PMT : PMT flag - * @retval The state of ETHERNET MAC flag. - */ -#define __HAL_ETH_MAC_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->MACSR &( __FLAG__)) == ( __FLAG__)) - -/** - * @brief Enables the specified ETHERNET DMA interrupts. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the ETHERNET DMA interrupt sources to be - * enabled @ref ETH_DMA_Interrupts - * @retval None - */ -#define __HAL_ETH_DMA_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DMAIER |= (__INTERRUPT__)) - -/** - * @brief Disables the specified ETHERNET DMA interrupts. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the ETHERNET DMA interrupt sources to be - * disabled. @ref ETH_DMA_Interrupts - * @retval None - */ -#define __HAL_ETH_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DMAIER &= ~(__INTERRUPT__)) - -/** - * @brief Clears the ETHERNET DMA IT pending bit. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. @ref ETH_DMA_Interrupts - * @retval None - */ -#define __HAL_ETH_DMA_CLEAR_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DMASR =(__INTERRUPT__)) - -/** - * @brief Checks whether the specified ETHERNET DMA flag is set or not. -* @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag to check. @ref ETH_DMA_Flags - * @retval The new state of ETH_DMA_FLAG (SET or RESET). - */ -#define __HAL_ETH_DMA_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->DMASR &( __FLAG__)) == ( __FLAG__)) - -/** - * @brief Checks whether the specified ETHERNET DMA flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag to clear. @ref ETH_DMA_Flags - * @retval The new state of ETH_DMA_FLAG (SET or RESET). - */ -#define __HAL_ETH_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->DMASR = (__FLAG__)) - -/** - * @brief Checks whether the specified ETHERNET DMA overflow flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __OVERFLOW__ specifies the DMA overflow flag to check. - * This parameter can be one of the following values: - * @arg ETH_DMA_OVERFLOW_RXFIFOCOUNTER : Overflow for FIFO Overflows Counter - * @arg ETH_DMA_OVERFLOW_MISSEDFRAMECOUNTER : Overflow for Buffer Unavailable Missed Frame Counter - * @retval The state of ETHERNET DMA overflow Flag (SET or RESET). - */ -#define __HAL_ETH_GET_DMA_OVERFLOW_STATUS(__HANDLE__, __OVERFLOW__) (((__HANDLE__)->Instance->DMAMFBOCR & (__OVERFLOW__)) == (__OVERFLOW__)) - -/** - * @brief Set the DMA Receive status watchdog timer register value - * @param __HANDLE__ ETH Handle - * @param __VALUE__ DMA Receive status watchdog timer register value - * @retval None - */ -#define __HAL_ETH_SET_RECEIVE_WATCHDOG_TIMER(__HANDLE__, __VALUE__) ((__HANDLE__)->Instance->DMARSWTR = (__VALUE__)) - -/** - * @brief Enables any unicast packet filtered by the MAC address - * recognition to be a wake-up frame. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_GLOBAL_UNICAST_WAKEUP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR |= ETH_MACPMTCSR_GU) - -/** - * @brief Disables any unicast packet filtered by the MAC address - * recognition to be a wake-up frame. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_GLOBAL_UNICAST_WAKEUP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR &= ~ETH_MACPMTCSR_GU) - -/** - * @brief Enables the MAC Wake-Up Frame Detection. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_WAKEUP_FRAME_DETECTION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR |= ETH_MACPMTCSR_WFE) - -/** - * @brief Disables the MAC Wake-Up Frame Detection. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_WAKEUP_FRAME_DETECTION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR &= ~ETH_MACPMTCSR_WFE) - -/** - * @brief Enables the MAC Magic Packet Detection. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MAGIC_PACKET_DETECTION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR |= ETH_MACPMTCSR_MPE) - -/** - * @brief Disables the MAC Magic Packet Detection. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MAGIC_PACKET_DETECTION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR &= ~ETH_MACPMTCSR_WFE) - -/** - * @brief Enables the MAC Power Down. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_POWER_DOWN_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR |= ETH_MACPMTCSR_PD) - -/** - * @brief Disables the MAC Power Down. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_POWER_DOWN_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR &= ~ETH_MACPMTCSR_PD) - -/** - * @brief Checks whether the specified ETHERNET PMT flag is set or not. - * @param __HANDLE__ ETH Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg ETH_PMT_FLAG_WUFFRPR : Wake-Up Frame Filter Register Pointer Reset - * @arg ETH_PMT_FLAG_WUFR : Wake-Up Frame Received - * @arg ETH_PMT_FLAG_MPR : Magic Packet Received - * @retval The new state of ETHERNET PMT Flag (SET or RESET). - */ -#define __HAL_ETH_GET_PMT_FLAG_STATUS(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->MACPMTCSR &( __FLAG__)) == ( __FLAG__)) - -/** - * @brief Preset and Initialize the MMC counters to almost-full value: 0xFFFF_FFF0 (full - 16) - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTER_FULL_PRESET(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= (ETH_MMCCR_MCFHP | ETH_MMCCR_MCP)) - -/** - * @brief Preset and Initialize the MMC counters to almost-half value: 0x7FFF_FFF0 (half - 16) - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTER_HALF_PRESET(__HANDLE__) do{(__HANDLE__)->Instance->MMCCR &= ~ETH_MMCCR_MCFHP;\ - (__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_MCP;} while (0) - -/** - * @brief Enables the MMC Counter Freeze. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTER_FREEZE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_MCF) - -/** - * @brief Disables the MMC Counter Freeze. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTER_FREEZE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR &= ~ETH_MMCCR_MCF) - -/** - * @brief Enables the MMC Reset On Read. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_ETH_MMC_RESET_ONREAD_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_ROR) - -/** - * @brief Disables the MMC Reset On Read. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_ETH_MMC_RESET_ONREAD_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR &= ~ETH_MMCCR_ROR) - -/** - * @brief Enables the MMC Counter Stop Rollover. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_ETH_MMC_COUNTER_ROLLOVER_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR &= ~ETH_MMCCR_CSR) - -/** - * @brief Disables the MMC Counter Stop Rollover. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_ETH_MMC_COUNTER_ROLLOVER_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_CSR) - -/** - * @brief Resets the MMC Counters. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTERS_RESET(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_CR) - -/** - * @brief Enables the specified ETHERNET MMC Rx interrupts. - * @param __HANDLE__ ETH Handle. - * @param __INTERRUPT__ specifies the ETHERNET MMC interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg ETH_MMC_IT_RGUF : When Rx good unicast frames counter reaches half the maximum value - * @arg ETH_MMC_IT_RFAE : When Rx alignment error counter reaches half the maximum value - * @arg ETH_MMC_IT_RFCE : When Rx crc error counter reaches half the maximum value - * @retval None - */ -#define __HAL_ETH_MMC_RX_IT_ENABLE(__HANDLE__, __INTERRUPT__) (__HANDLE__)->Instance->MMCRIMR &= ~((__INTERRUPT__) & 0xEFFFFFFFU) -/** - * @brief Disables the specified ETHERNET MMC Rx interrupts. - * @param __HANDLE__ ETH Handle. - * @param __INTERRUPT__ specifies the ETHERNET MMC interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg ETH_MMC_IT_RGUF : When Rx good unicast frames counter reaches half the maximum value - * @arg ETH_MMC_IT_RFAE : When Rx alignment error counter reaches half the maximum value - * @arg ETH_MMC_IT_RFCE : When Rx crc error counter reaches half the maximum value - * @retval None - */ -#define __HAL_ETH_MMC_RX_IT_DISABLE(__HANDLE__, __INTERRUPT__) (__HANDLE__)->Instance->MMCRIMR |= ((__INTERRUPT__) & 0xEFFFFFFFU) -/** - * @brief Enables the specified ETHERNET MMC Tx interrupts. - * @param __HANDLE__ ETH Handle. - * @param __INTERRUPT__ specifies the ETHERNET MMC interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg ETH_MMC_IT_TGF : When Tx good frame counter reaches half the maximum value - * @arg ETH_MMC_IT_TGFMSC: When Tx good multi col counter reaches half the maximum value - * @arg ETH_MMC_IT_TGFSC : When Tx good single col counter reaches half the maximum value - * @retval None - */ -#define __HAL_ETH_MMC_TX_IT_ENABLE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MMCRIMR &= ~ (__INTERRUPT__)) - -/** - * @brief Disables the specified ETHERNET MMC Tx interrupts. - * @param __HANDLE__ ETH Handle. - * @param __INTERRUPT__ specifies the ETHERNET MMC interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg ETH_MMC_IT_TGF : When Tx good frame counter reaches half the maximum value - * @arg ETH_MMC_IT_TGFMSC: When Tx good multi col counter reaches half the maximum value - * @arg ETH_MMC_IT_TGFSC : When Tx good single col counter reaches half the maximum value - * @retval None - */ -#define __HAL_ETH_MMC_TX_IT_DISABLE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MMCRIMR |= (__INTERRUPT__)) - -/** - * @brief Enables the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Disables the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Enable event on ETH External event line. - * @retval None. - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_EVENT() EXTI->EMR |= (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Disable event on ETH External event line - * @retval None. - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_EVENT() EXTI->EMR &= ~(ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Get flag of the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Clear flag of the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Enables rising edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_RISING_EDGE_TRIGGER() EXTI->RTSR |= ETH_EXTI_LINE_WAKEUP - -/** - * @brief Disables the rising edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_RISING_EDGE_TRIGGER() EXTI->RTSR &= ~(ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Enables falling edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLING_EDGE_TRIGGER() EXTI->FTSR |= (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Disables falling edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_FALLING_EDGE_TRIGGER() EXTI->FTSR &= ~(ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Enables rising/falling edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLINGRISING_TRIGGER() do{EXTI->RTSR |= ETH_EXTI_LINE_WAKEUP;\ - EXTI->FTSR |= ETH_EXTI_LINE_WAKEUP;\ - }while(0U) - -/** - * @brief Disables rising/falling edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_FALLINGRISING_TRIGGER() do{EXTI->RTSR &= ~(ETH_EXTI_LINE_WAKEUP);\ - EXTI->FTSR &= ~(ETH_EXTI_LINE_WAKEUP);\ - }while(0U) - -/** - * @brief Generate a Software interrupt on selected EXTI line. - * @retval None. - */ -#define __HAL_ETH_WAKEUP_EXTI_GENERATE_SWIT() EXTI->SWIER|= ETH_EXTI_LINE_WAKEUP - -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup ETH_Exported_Functions - * @{ - */ - -/* Initialization and de-initialization functions ****************************/ - -/** @addtogroup ETH_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_ETH_Init(ETH_HandleTypeDef *heth); -HAL_StatusTypeDef HAL_ETH_DeInit(ETH_HandleTypeDef *heth); -void HAL_ETH_MspInit(ETH_HandleTypeDef *heth); -void HAL_ETH_MspDeInit(ETH_HandleTypeDef *heth); -HAL_StatusTypeDef HAL_ETH_DMATxDescListInit(ETH_HandleTypeDef *heth, ETH_DMADescTypeDef *DMATxDescTab, uint8_t* TxBuff, uint32_t TxBuffCount); -HAL_StatusTypeDef HAL_ETH_DMARxDescListInit(ETH_HandleTypeDef *heth, ETH_DMADescTypeDef *DMARxDescTab, uint8_t *RxBuff, uint32_t RxBuffCount); -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_ETH_RegisterCallback(ETH_HandleTypeDef *heth, HAL_ETH_CallbackIDTypeDef CallbackID, pETH_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_ETH_UnRegisterCallback(ETH_HandleTypeDef *heth, HAL_ETH_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* IO operation functions ****************************************************/ - -/** @addtogroup ETH_Exported_Functions_Group2 - * @{ - */ -HAL_StatusTypeDef HAL_ETH_TransmitFrame(ETH_HandleTypeDef *heth, uint32_t FrameLength); -HAL_StatusTypeDef HAL_ETH_GetReceivedFrame(ETH_HandleTypeDef *heth); -/* Communication with PHY functions*/ -HAL_StatusTypeDef HAL_ETH_ReadPHYRegister(ETH_HandleTypeDef *heth, uint16_t PHYReg, uint32_t *RegValue); -HAL_StatusTypeDef HAL_ETH_WritePHYRegister(ETH_HandleTypeDef *heth, uint16_t PHYReg, uint32_t RegValue); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_ETH_GetReceivedFrame_IT(ETH_HandleTypeDef *heth); -void HAL_ETH_IRQHandler(ETH_HandleTypeDef *heth); -/* Callback in non blocking modes (Interrupt) */ -void HAL_ETH_TxCpltCallback(ETH_HandleTypeDef *heth); -void HAL_ETH_RxCpltCallback(ETH_HandleTypeDef *heth); -void HAL_ETH_ErrorCallback(ETH_HandleTypeDef *heth); -/** - * @} - */ - -/* Peripheral Control functions **********************************************/ - -/** @addtogroup ETH_Exported_Functions_Group3 - * @{ - */ - -HAL_StatusTypeDef HAL_ETH_Start(ETH_HandleTypeDef *heth); -HAL_StatusTypeDef HAL_ETH_Stop(ETH_HandleTypeDef *heth); -HAL_StatusTypeDef HAL_ETH_ConfigMAC(ETH_HandleTypeDef *heth, ETH_MACInitTypeDef *macconf); -HAL_StatusTypeDef HAL_ETH_ConfigDMA(ETH_HandleTypeDef *heth, ETH_DMAInitTypeDef *dmaconf); -/** - * @} - */ - -/* Peripheral State functions ************************************************/ - -/** @addtogroup ETH_Exported_Functions_Group4 - * @{ - */ -HAL_ETH_StateTypeDef HAL_ETH_GetState(ETH_HandleTypeDef *heth); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx ||\ - STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_ETH_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h deleted file mode 100644 index 857011236b0e995..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h +++ /dev/null @@ -1,368 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_exti.h - * @author MCD Application Team - * @brief Header file of EXTI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2018 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32f4xx_HAL_EXTI_H -#define STM32f4xx_HAL_EXTI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup EXTI EXTI - * @brief EXTI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup EXTI_Exported_Types EXTI Exported Types - * @{ - */ -typedef enum -{ - HAL_EXTI_COMMON_CB_ID = 0x00U -} EXTI_CallbackIDTypeDef; - -/** - * @brief EXTI Handle structure definition - */ -typedef struct -{ - uint32_t Line; /*!< Exti line number */ - void (* PendingCallback)(void); /*!< Exti pending callback */ -} EXTI_HandleTypeDef; - -/** - * @brief EXTI Configuration structure definition - */ -typedef struct -{ - uint32_t Line; /*!< The Exti line to be configured. This parameter - can be a value of @ref EXTI_Line */ - uint32_t Mode; /*!< The Exit Mode to be configured for a core. - This parameter can be a combination of @ref EXTI_Mode */ - uint32_t Trigger; /*!< The Exti Trigger to be configured. This parameter - can be a value of @ref EXTI_Trigger */ - uint32_t GPIOSel; /*!< The Exti GPIO multiplexer selection to be configured. - This parameter is only possible for line 0 to 15. It - can be a value of @ref EXTI_GPIOSel */ -} EXTI_ConfigTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Constants EXTI Exported Constants - * @{ - */ - -/** @defgroup EXTI_Line EXTI Line - * @{ - */ -#define EXTI_LINE_0 (EXTI_GPIO | 0x00u) /*!< External interrupt line 0 */ -#define EXTI_LINE_1 (EXTI_GPIO | 0x01u) /*!< External interrupt line 1 */ -#define EXTI_LINE_2 (EXTI_GPIO | 0x02u) /*!< External interrupt line 2 */ -#define EXTI_LINE_3 (EXTI_GPIO | 0x03u) /*!< External interrupt line 3 */ -#define EXTI_LINE_4 (EXTI_GPIO | 0x04u) /*!< External interrupt line 4 */ -#define EXTI_LINE_5 (EXTI_GPIO | 0x05u) /*!< External interrupt line 5 */ -#define EXTI_LINE_6 (EXTI_GPIO | 0x06u) /*!< External interrupt line 6 */ -#define EXTI_LINE_7 (EXTI_GPIO | 0x07u) /*!< External interrupt line 7 */ -#define EXTI_LINE_8 (EXTI_GPIO | 0x08u) /*!< External interrupt line 8 */ -#define EXTI_LINE_9 (EXTI_GPIO | 0x09u) /*!< External interrupt line 9 */ -#define EXTI_LINE_10 (EXTI_GPIO | 0x0Au) /*!< External interrupt line 10 */ -#define EXTI_LINE_11 (EXTI_GPIO | 0x0Bu) /*!< External interrupt line 11 */ -#define EXTI_LINE_12 (EXTI_GPIO | 0x0Cu) /*!< External interrupt line 12 */ -#define EXTI_LINE_13 (EXTI_GPIO | 0x0Du) /*!< External interrupt line 13 */ -#define EXTI_LINE_14 (EXTI_GPIO | 0x0Eu) /*!< External interrupt line 14 */ -#define EXTI_LINE_15 (EXTI_GPIO | 0x0Fu) /*!< External interrupt line 15 */ -#define EXTI_LINE_16 (EXTI_CONFIG | 0x10u) /*!< External interrupt line 16 Connected to the PVD Output */ -#define EXTI_LINE_17 (EXTI_CONFIG | 0x11u) /*!< External interrupt line 17 Connected to the RTC Alarm event */ -#if defined(EXTI_IMR_IM18) -#define EXTI_LINE_18 (EXTI_CONFIG | 0x12u) /*!< External interrupt line 18 Connected to the USB OTG FS Wakeup from suspend event */ -#else -#define EXTI_LINE_18 (EXTI_RESERVED | 0x12u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM18 */ -#if defined(EXTI_IMR_IM19) -#define EXTI_LINE_19 (EXTI_CONFIG | 0x13u) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ -#else -#define EXTI_LINE_19 (EXTI_RESERVED | 0x13u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM19 */ -#if defined(EXTI_IMR_IM20) -#define EXTI_LINE_20 (EXTI_CONFIG | 0x14u) /*!< External interrupt line 20 Connected to the USB OTG HS (configured in FS) Wakeup event */ -#else -#define EXTI_LINE_20 (EXTI_RESERVED | 0x14u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM20 */ -#define EXTI_LINE_21 (EXTI_CONFIG | 0x15u) /*!< External interrupt line 21 Connected to the RTC Tamper and Time Stamp events */ -#define EXTI_LINE_22 (EXTI_CONFIG | 0x16u) /*!< External interrupt line 22 Connected to the RTC Wakeup event */ -#if defined(EXTI_IMR_IM23) -#define EXTI_LINE_23 (EXTI_CONFIG | 0x17u) /*!< External interrupt line 23 Connected to the LPTIM1 asynchronous event */ -#endif /* EXTI_IMR_IM23 */ - -/** - * @} - */ - -/** @defgroup EXTI_Mode EXTI Mode - * @{ - */ -#define EXTI_MODE_NONE 0x00000000u -#define EXTI_MODE_INTERRUPT 0x00000001u -#define EXTI_MODE_EVENT 0x00000002u -/** - * @} - */ - -/** @defgroup EXTI_Trigger EXTI Trigger - * @{ - */ - -#define EXTI_TRIGGER_NONE 0x00000000u -#define EXTI_TRIGGER_RISING 0x00000001u -#define EXTI_TRIGGER_FALLING 0x00000002u -#define EXTI_TRIGGER_RISING_FALLING (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING) -/** - * @} - */ - -/** @defgroup EXTI_GPIOSel EXTI GPIOSel - * @brief - * @{ - */ -#define EXTI_GPIOA 0x00000000u -#define EXTI_GPIOB 0x00000001u -#define EXTI_GPIOC 0x00000002u -#if defined (GPIOD) -#define EXTI_GPIOD 0x00000003u -#endif /* GPIOD */ -#if defined (GPIOE) -#define EXTI_GPIOE 0x00000004u -#endif /* GPIOE */ -#if defined (GPIOF) -#define EXTI_GPIOF 0x00000005u -#endif /* GPIOF */ -#if defined (GPIOG) -#define EXTI_GPIOG 0x00000006u -#endif /* GPIOG */ -#if defined (GPIOH) -#define EXTI_GPIOH 0x00000007u -#endif /* GPIOH */ -#if defined (GPIOI) -#define EXTI_GPIOI 0x00000008u -#endif /* GPIOI */ -#if defined (GPIOJ) -#define EXTI_GPIOJ 0x00000009u -#endif /* GPIOJ */ -#if defined (GPIOK) -#define EXTI_GPIOK 0x0000000Au -#endif /* GPIOK */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Macros EXTI Exported Macros - * @{ - */ - -/** - * @} - */ - -/* Private constants --------------------------------------------------------*/ -/** @defgroup EXTI_Private_Constants EXTI Private Constants - * @{ - */ -/** - * @brief EXTI Line property definition - */ -#define EXTI_PROPERTY_SHIFT 24u -#define EXTI_CONFIG (0x02uL << EXTI_PROPERTY_SHIFT) -#define EXTI_GPIO ((0x04uL << EXTI_PROPERTY_SHIFT) | EXTI_CONFIG) -#define EXTI_RESERVED (0x08uL << EXTI_PROPERTY_SHIFT) -#define EXTI_PROPERTY_MASK (EXTI_CONFIG | EXTI_GPIO) - -/** - * @brief EXTI bit usage - */ -#define EXTI_PIN_MASK 0x0000001Fu - -/** - * @brief EXTI Mask for interrupt & event mode - */ -#define EXTI_MODE_MASK (EXTI_MODE_EVENT | EXTI_MODE_INTERRUPT) - -/** - * @brief EXTI Mask for trigger possibilities - */ -#define EXTI_TRIGGER_MASK (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING) - -/** - * @brief EXTI Line number - */ -#if defined(EXTI_IMR_IM23) -#define EXTI_LINE_NB 24UL -#else -#define EXTI_LINE_NB 23UL -#endif /* EXTI_IMR_IM23 */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup EXTI_Private_Macros EXTI Private Macros - * @{ - */ -#define IS_EXTI_LINE(__EXTI_LINE__) ((((__EXTI_LINE__) & ~(EXTI_PROPERTY_MASK | EXTI_PIN_MASK)) == 0x00u) && \ - ((((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_CONFIG) || \ - (((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_GPIO)) && \ - (((__EXTI_LINE__) & EXTI_PIN_MASK) < EXTI_LINE_NB)) - -#define IS_EXTI_MODE(__EXTI_LINE__) ((((__EXTI_LINE__) & EXTI_MODE_MASK) != 0x00u) && \ - (((__EXTI_LINE__) & ~EXTI_MODE_MASK) == 0x00u)) - -#define IS_EXTI_TRIGGER(__EXTI_LINE__) (((__EXTI_LINE__) & ~EXTI_TRIGGER_MASK) == 0x00u) - -#define IS_EXTI_PENDING_EDGE(__EXTI_LINE__) ((__EXTI_LINE__) == EXTI_TRIGGER_RISING_FALLING) - -#define IS_EXTI_CONFIG_LINE(__EXTI_LINE__) (((__EXTI_LINE__) & EXTI_CONFIG) != 0x00u) - -#if !defined (GPIOD) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOE) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOF) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOI) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOJ) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH) || \ - ((__PORT__) == EXTI_GPIOI)) -#else -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH) || \ - ((__PORT__) == EXTI_GPIOI) || \ - ((__PORT__) == EXTI_GPIOJ) || \ - ((__PORT__) == EXTI_GPIOK)) -#endif /* GPIOD */ - -#define IS_EXTI_GPIO_PIN(__PIN__) ((__PIN__) < 16U) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Functions EXTI Exported Functions - * @brief EXTI Exported Functions - * @{ - */ - -/** @defgroup EXTI_Exported_Functions_Group1 Configuration functions - * @brief Configuration functions - * @{ - */ -/* Configuration functions ****************************************************/ -HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig); -HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig); -HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti); -HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void)); -HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine); -/** - * @} - */ - -/** @defgroup EXTI_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * @{ - */ -/* IO operation functions *****************************************************/ -void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti); -uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge); -void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge); -void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32f4xx_HAL_EXTI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h deleted file mode 100644 index b817f63b7605ddb..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h +++ /dev/null @@ -1,428 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash.h - * @author MCD Application Team - * @brief Header file of FLASH HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_FLASH_H -#define __STM32F4xx_HAL_FLASH_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASH - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Types FLASH Exported Types - * @{ - */ - -/** - * @brief FLASH Procedure structure definition - */ -typedef enum -{ - FLASH_PROC_NONE = 0U, - FLASH_PROC_SECTERASE, - FLASH_PROC_MASSERASE, - FLASH_PROC_PROGRAM -} FLASH_ProcedureTypeDef; - -/** - * @brief FLASH handle Structure definition - */ -typedef struct -{ - __IO FLASH_ProcedureTypeDef ProcedureOnGoing; /*Internal variable to indicate which procedure is ongoing or not in IT context*/ - - __IO uint32_t NbSectorsToErase; /*Internal variable to save the remaining sectors to erase in IT context*/ - - __IO uint8_t VoltageForErase; /*Internal variable to provide voltage range selected by user in IT context*/ - - __IO uint32_t Sector; /*Internal variable to define the current sector which is erasing*/ - - __IO uint32_t Bank; /*Internal variable to save current bank selected during mass erase*/ - - __IO uint32_t Address; /*Internal variable to save address selected for program*/ - - HAL_LockTypeDef Lock; /* FLASH locking object */ - - __IO uint32_t ErrorCode; /* FLASH error code */ - -}FLASH_ProcessTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Constants FLASH Exported Constants - * @{ - */ -/** @defgroup FLASH_Error_Code FLASH Error Code - * @brief FLASH Error Code - * @{ - */ -#define HAL_FLASH_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_FLASH_ERROR_RD 0x00000001U /*!< Read Protection error */ -#define HAL_FLASH_ERROR_PGS 0x00000002U /*!< Programming Sequence error */ -#define HAL_FLASH_ERROR_PGP 0x00000004U /*!< Programming Parallelism error */ -#define HAL_FLASH_ERROR_PGA 0x00000008U /*!< Programming Alignment error */ -#define HAL_FLASH_ERROR_WRP 0x00000010U /*!< Write protection error */ -#define HAL_FLASH_ERROR_OPERATION 0x00000020U /*!< Operation Error */ -/** - * @} - */ - -/** @defgroup FLASH_Type_Program FLASH Type Program - * @{ - */ -#define FLASH_TYPEPROGRAM_BYTE 0x00000000U /*!< Program byte (8-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_HALFWORD 0x00000001U /*!< Program a half-word (16-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_WORD 0x00000002U /*!< Program a word (32-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_DOUBLEWORD 0x00000003U /*!< Program a double word (64-bit) at a specified address */ -/** - * @} - */ - -/** @defgroup FLASH_Flag_definition FLASH Flag definition - * @brief Flag definition - * @{ - */ -#define FLASH_FLAG_EOP FLASH_SR_EOP /*!< FLASH End of Operation flag */ -#define FLASH_FLAG_OPERR FLASH_SR_SOP /*!< FLASH operation Error flag */ -#define FLASH_FLAG_WRPERR FLASH_SR_WRPERR /*!< FLASH Write protected error flag */ -#define FLASH_FLAG_PGAERR FLASH_SR_PGAERR /*!< FLASH Programming Alignment error flag */ -#define FLASH_FLAG_PGPERR FLASH_SR_PGPERR /*!< FLASH Programming Parallelism error flag */ -#define FLASH_FLAG_PGSERR FLASH_SR_PGSERR /*!< FLASH Programming Sequence error flag */ -#if defined(FLASH_SR_RDERR) -#define FLASH_FLAG_RDERR FLASH_SR_RDERR /*!< Read Protection error flag (PCROP) */ -#endif /* FLASH_SR_RDERR */ -#define FLASH_FLAG_BSY FLASH_SR_BSY /*!< FLASH Busy flag */ -/** - * @} - */ - -/** @defgroup FLASH_Interrupt_definition FLASH Interrupt definition - * @brief FLASH Interrupt definition - * @{ - */ -#define FLASH_IT_EOP FLASH_CR_EOPIE /*!< End of FLASH Operation Interrupt source */ -#define FLASH_IT_ERR 0x02000000U /*!< Error Interrupt source */ -/** - * @} - */ - -/** @defgroup FLASH_Program_Parallelism FLASH Program Parallelism - * @{ - */ -#define FLASH_PSIZE_BYTE 0x00000000U -#define FLASH_PSIZE_HALF_WORD 0x00000100U -#define FLASH_PSIZE_WORD 0x00000200U -#define FLASH_PSIZE_DOUBLE_WORD 0x00000300U -#define CR_PSIZE_MASK 0xFFFFFCFFU -/** - * @} - */ - -/** @defgroup FLASH_Keys FLASH Keys - * @{ - */ -#define RDP_KEY ((uint16_t)0x00A5) -#define FLASH_KEY1 0x45670123U -#define FLASH_KEY2 0xCDEF89ABU -#define FLASH_OPT_KEY1 0x08192A3BU -#define FLASH_OPT_KEY2 0x4C5D6E7FU -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Macros FLASH Exported Macros - * @{ - */ -/** - * @brief Set the FLASH Latency. - * @param __LATENCY__ FLASH Latency - * The value of this parameter depend on device used within the same series - * @retval none - */ -#define __HAL_FLASH_SET_LATENCY(__LATENCY__) (*(__IO uint8_t *)ACR_BYTE0_ADDRESS = (uint8_t)(__LATENCY__)) - -/** - * @brief Get the FLASH Latency. - * @retval FLASH Latency - * The value of this parameter depend on device used within the same series - */ -#define __HAL_FLASH_GET_LATENCY() (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY)) - -/** - * @brief Enable the FLASH prefetch buffer. - * @retval none - */ -#define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTEN) - -/** - * @brief Disable the FLASH prefetch buffer. - * @retval none - */ -#define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTEN)) - -/** - * @brief Enable the FLASH instruction cache. - * @retval none - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_ICEN) - -/** - * @brief Disable the FLASH instruction cache. - * @retval none - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_ICEN)) - -/** - * @brief Enable the FLASH data cache. - * @retval none - */ -#define __HAL_FLASH_DATA_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_DCEN) - -/** - * @brief Disable the FLASH data cache. - * @retval none - */ -#define __HAL_FLASH_DATA_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_DCEN)) - -/** - * @brief Resets the FLASH instruction Cache. - * @note This function must be used only when the Instruction Cache is disabled. - * @retval None - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_ICRST; \ - FLASH->ACR &= ~FLASH_ACR_ICRST; \ - }while(0U) - -/** - * @brief Resets the FLASH data Cache. - * @note This function must be used only when the data Cache is disabled. - * @retval None - */ -#define __HAL_FLASH_DATA_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_DCRST; \ - FLASH->ACR &= ~FLASH_ACR_DCRST; \ - }while(0U) -/** - * @brief Enable the specified FLASH interrupt. - * @param __INTERRUPT__ FLASH interrupt - * This parameter can be any combination of the following values: - * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt - * @arg FLASH_IT_ERR: Error Interrupt - * @retval none - */ -#define __HAL_FLASH_ENABLE_IT(__INTERRUPT__) (FLASH->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the specified FLASH interrupt. - * @param __INTERRUPT__ FLASH interrupt - * This parameter can be any combination of the following values: - * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt - * @arg FLASH_IT_ERR: Error Interrupt - * @retval none - */ -#define __HAL_FLASH_DISABLE_IT(__INTERRUPT__) (FLASH->CR &= ~(uint32_t)(__INTERRUPT__)) - -/** - * @brief Get the specified FLASH flag status. - * @param __FLAG__ specifies the FLASH flags to check. - * This parameter can be any combination of the following values: - * @arg FLASH_FLAG_EOP : FLASH End of Operation flag - * @arg FLASH_FLAG_OPERR : FLASH operation Error flag - * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag - * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag - * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag - * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag - * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*) - * @arg FLASH_FLAG_BSY : FLASH Busy flag - * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define __HAL_FLASH_GET_FLAG(__FLAG__) ((FLASH->SR & (__FLAG__))) - -/** - * @brief Clear the specified FLASH flags. - * @param __FLAG__ specifies the FLASH flags to clear. - * This parameter can be any combination of the following values: - * @arg FLASH_FLAG_EOP : FLASH End of Operation flag - * @arg FLASH_FLAG_OPERR : FLASH operation Error flag - * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag - * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag - * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag - * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag - * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*) - * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices - * @retval none - */ -#define __HAL_FLASH_CLEAR_FLAG(__FLAG__) (FLASH->SR = (__FLAG__)) -/** - * @} - */ - -/* Include FLASH HAL Extension module */ -#include "stm32f4xx_hal_flash_ex.h" -#include "stm32f4xx_hal_flash_ramfunc.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FLASH_Exported_Functions - * @{ - */ -/** @addtogroup FLASH_Exported_Functions_Group1 - * @{ - */ -/* Program operation functions ***********************************************/ -HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data); -HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data); -/* FLASH IRQ handler method */ -void HAL_FLASH_IRQHandler(void); -/* Callbacks in non blocking modes */ -void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue); -void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue); -/** - * @} - */ - -/** @addtogroup FLASH_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions **********************************************/ -HAL_StatusTypeDef HAL_FLASH_Unlock(void); -HAL_StatusTypeDef HAL_FLASH_Lock(void); -HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void); -HAL_StatusTypeDef HAL_FLASH_OB_Lock(void); -/* Option bytes control */ -HAL_StatusTypeDef HAL_FLASH_OB_Launch(void); -/** - * @} - */ - -/** @addtogroup FLASH_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -uint32_t HAL_FLASH_GetError(void); -HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Variables FLASH Private Variables - * @{ - */ - -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Constants FLASH Private Constants - * @{ - */ - -/** - * @brief ACR register byte 0 (Bits[7:0]) base address - */ -#define ACR_BYTE0_ADDRESS 0x40023C00U -/** - * @brief OPTCR register byte 0 (Bits[7:0]) base address - */ -#define OPTCR_BYTE0_ADDRESS 0x40023C14U -/** - * @brief OPTCR register byte 1 (Bits[15:8]) base address - */ -#define OPTCR_BYTE1_ADDRESS 0x40023C15U -/** - * @brief OPTCR register byte 2 (Bits[23:16]) base address - */ -#define OPTCR_BYTE2_ADDRESS 0x40023C16U -/** - * @brief OPTCR register byte 3 (Bits[31:24]) base address - */ -#define OPTCR_BYTE3_ADDRESS 0x40023C17U - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FLASH_Private_Macros FLASH Private Macros - * @{ - */ - -/** @defgroup FLASH_IS_FLASH_Definitions FLASH Private macros to check input parameters - * @{ - */ -#define IS_FLASH_TYPEPROGRAM(VALUE)(((VALUE) == FLASH_TYPEPROGRAM_BYTE) || \ - ((VALUE) == FLASH_TYPEPROGRAM_HALFWORD) || \ - ((VALUE) == FLASH_TYPEPROGRAM_WORD) || \ - ((VALUE) == FLASH_TYPEPROGRAM_DOUBLEWORD)) -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Functions FLASH Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_FLASH_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h deleted file mode 100644 index 4dbad67323334b4..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h +++ /dev/null @@ -1,1066 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ex.h - * @author MCD Application Team - * @brief Header file of FLASH HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_FLASH_EX_H -#define __STM32F4xx_HAL_FLASH_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASHEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FLASHEx_Exported_Types FLASH Exported Types - * @{ - */ - -/** - * @brief FLASH Erase structure definition - */ -typedef struct -{ - uint32_t TypeErase; /*!< Mass erase or sector Erase. - This parameter can be a value of @ref FLASHEx_Type_Erase */ - - uint32_t Banks; /*!< Select banks to erase when Mass erase is enabled. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint32_t Sector; /*!< Initial FLASH sector to erase when Mass erase is disabled - This parameter must be a value of @ref FLASHEx_Sectors */ - - uint32_t NbSectors; /*!< Number of sectors to be erased. - This parameter must be a value between 1 and (max number of sectors - value of Initial sector)*/ - - uint32_t VoltageRange;/*!< The device voltage range which defines the erase parallelism - This parameter must be a value of @ref FLASHEx_Voltage_Range */ - -} FLASH_EraseInitTypeDef; - -/** - * @brief FLASH Option Bytes Program structure definition - */ -typedef struct -{ - uint32_t OptionType; /*!< Option byte to be configured. - This parameter can be a value of @ref FLASHEx_Option_Type */ - - uint32_t WRPState; /*!< Write protection activation or deactivation. - This parameter can be a value of @ref FLASHEx_WRP_State */ - - uint32_t WRPSector; /*!< Specifies the sector(s) to be write protected. - The value of this parameter depend on device used within the same series */ - - uint32_t Banks; /*!< Select banks for WRP activation/deactivation of all sectors. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint32_t RDPLevel; /*!< Set the read protection level. - This parameter can be a value of @ref FLASHEx_Option_Bytes_Read_Protection */ - - uint32_t BORLevel; /*!< Set the BOR Level. - This parameter can be a value of @ref FLASHEx_BOR_Reset_Level */ - - uint8_t USERConfig; /*!< Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. */ - -} FLASH_OBProgramInitTypeDef; - -/** - * @brief FLASH Advanced Option Bytes Program structure definition - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -typedef struct -{ - uint32_t OptionType; /*!< Option byte to be configured for extension. - This parameter can be a value of @ref FLASHEx_Advanced_Option_Type */ - - uint32_t PCROPState; /*!< PCROP activation or deactivation. - This parameter can be a value of @ref FLASHEx_PCROP_State */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - uint16_t Sectors; /*!< specifies the sector(s) set for PCROP. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx ||\ - STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - uint32_t Banks; /*!< Select banks for PCROP activation/deactivation of all sectors. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint16_t SectorsBank1; /*!< Specifies the sector(s) set for PCROP for Bank1. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ - - uint16_t SectorsBank2; /*!< Specifies the sector(s) set for PCROP for Bank2. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ - - uint8_t BootConfig; /*!< Specifies Option bytes for boot config. - This parameter can be a value of @ref FLASHEx_Dual_Boot */ - -#endif /*STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -}FLASH_AdvOBProgramInitTypeDef; -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || - STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup FLASHEx_Exported_Constants FLASH Exported Constants - * @{ - */ - -/** @defgroup FLASHEx_Type_Erase FLASH Type Erase - * @{ - */ -#define FLASH_TYPEERASE_SECTORS 0x00000000U /*!< Sectors erase only */ -#define FLASH_TYPEERASE_MASSERASE 0x00000001U /*!< Flash Mass erase activation */ -/** - * @} - */ - -/** @defgroup FLASHEx_Voltage_Range FLASH Voltage Range - * @{ - */ -#define FLASH_VOLTAGE_RANGE_1 0x00000000U /*!< Device operating range: 1.8V to 2.1V */ -#define FLASH_VOLTAGE_RANGE_2 0x00000001U /*!< Device operating range: 2.1V to 2.7V */ -#define FLASH_VOLTAGE_RANGE_3 0x00000002U /*!< Device operating range: 2.7V to 3.6V */ -#define FLASH_VOLTAGE_RANGE_4 0x00000003U /*!< Device operating range: 2.7V to 3.6V + External Vpp */ -/** - * @} - */ - -/** @defgroup FLASHEx_WRP_State FLASH WRP State - * @{ - */ -#define OB_WRPSTATE_DISABLE 0x00000000U /*!< Disable the write protection of the desired bank 1 sectors */ -#define OB_WRPSTATE_ENABLE 0x00000001U /*!< Enable the write protection of the desired bank 1 sectors */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Type FLASH Option Type - * @{ - */ -#define OPTIONBYTE_WRP 0x00000001U /*!< WRP option byte configuration */ -#define OPTIONBYTE_RDP 0x00000002U /*!< RDP option byte configuration */ -#define OPTIONBYTE_USER 0x00000004U /*!< USER option byte configuration */ -#define OPTIONBYTE_BOR 0x00000008U /*!< BOR option byte configuration */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_Read_Protection FLASH Option Bytes Read Protection - * @{ - */ -#define OB_RDP_LEVEL_0 ((uint8_t)0xAA) -#define OB_RDP_LEVEL_1 ((uint8_t)0x55) -#define OB_RDP_LEVEL_2 ((uint8_t)0xCC) /*!< Warning: When enabling read protection level 2 - it s no more possible to go back to level 1 or 0 */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_IWatchdog FLASH Option Bytes IWatchdog - * @{ - */ -#define OB_IWDG_SW ((uint8_t)0x20) /*!< Software IWDG selected */ -#define OB_IWDG_HW ((uint8_t)0x00) /*!< Hardware IWDG selected */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_nRST_STOP FLASH Option Bytes nRST_STOP - * @{ - */ -#define OB_STOP_NO_RST ((uint8_t)0x40) /*!< No reset generated when entering in STOP */ -#define OB_STOP_RST ((uint8_t)0x00) /*!< Reset generated when entering in STOP */ -/** - * @} - */ - - -/** @defgroup FLASHEx_Option_Bytes_nRST_STDBY FLASH Option Bytes nRST_STDBY - * @{ - */ -#define OB_STDBY_NO_RST ((uint8_t)0x80) /*!< No reset generated when entering in STANDBY */ -#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */ -/** - * @} - */ - -/** @defgroup FLASHEx_BOR_Reset_Level FLASH BOR Reset Level - * @{ - */ -#define OB_BOR_LEVEL3 ((uint8_t)0x00) /*!< Supply voltage ranges from 2.70 to 3.60 V */ -#define OB_BOR_LEVEL2 ((uint8_t)0x04) /*!< Supply voltage ranges from 2.40 to 2.70 V */ -#define OB_BOR_LEVEL1 ((uint8_t)0x08) /*!< Supply voltage ranges from 2.10 to 2.40 V */ -#define OB_BOR_OFF ((uint8_t)0x0C) /*!< Supply voltage ranges from 1.62 to 2.10 V */ -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup FLASHEx_PCROP_State FLASH PCROP State - * @{ - */ -#define OB_PCROP_STATE_DISABLE 0x00000000U /*!< Disable PCROP */ -#define OB_PCROP_STATE_ENABLE 0x00000001U /*!< Enable PCROP */ -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** @defgroup FLASHEx_Advanced_Option_Type FLASH Advanced Option Type - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define OPTIONBYTE_PCROP 0x00000001U /*!< PCROP option byte configuration */ -#define OPTIONBYTE_BOOTCONFIG 0x00000002U /*!< BOOTConfig option byte configuration */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -#define OPTIONBYTE_PCROP 0x00000001U /*!= FLASH_BASE) && ((ADDRESS) <= FLASH_END)) || \ - (((ADDRESS) >= FLASH_OTP_BASE) && ((ADDRESS) <= FLASH_OTP_END))) - -#define IS_FLASH_NBSECTORS(NBSECTORS) (((NBSECTORS) != 0) && ((NBSECTORS) <= FLASH_SECTOR_TOTAL)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFF000000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFF8000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F401xC) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xC */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFF8000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F401xC) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xC */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_BOOT(BOOT) (((BOOT) == OB_DUAL_BOOT_ENABLE) || ((BOOT) == OB_DUAL_BOOT_DISABLE)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_PCROP_SELECT(PCROP) (((PCROP) == OB_PCROP_SELECTED) || ((PCROP) == OB_PCROP_DESELECTED)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FLASHEx_Private_Functions FLASH Private Functions - * @{ - */ -void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange); -void FLASH_FlushCaches(void); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_FLASH_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h deleted file mode 100644 index 9fab0c98c56a1f5..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h +++ /dev/null @@ -1,79 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ramfunc.h - * @author MCD Application Team - * @brief Header file of FLASH RAMFUNC driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_FLASH_RAMFUNC_H -#define __STM32F4xx_FLASH_RAMFUNC_H - -#ifdef __cplusplus - extern "C" { -#endif -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASH_RAMFUNC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FLASH_RAMFUNC_Exported_Functions - * @{ - */ - -/** @addtogroup FLASH_RAMFUNC_Exported_Functions_Group1 - * @{ - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_FLASH_RAMFUNC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c.h deleted file mode 100644 index b7f370a8f4012da..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c.h +++ /dev/null @@ -1,840 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpi2c.h - * @author MCD Application Team - * @brief Header file of FMPI2C HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_FMPI2C_H -#define STM32F4xx_HAL_FMPI2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMPI2C - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FMPI2C_Exported_Types FMPI2C Exported Types - * @{ - */ - -/** @defgroup FMPI2C_Configuration_Structure_definition FMPI2C Configuration Structure definition - * @brief FMPI2C Configuration Structure definition - * @{ - */ -typedef struct -{ - uint32_t Timing; /*!< Specifies the FMPI2C_TIMINGR_register value. - This parameter calculated by referring to FMPI2C initialization section - in Reference manual */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected. - This parameter can be a value of @ref FMPI2C_ADDRESSING_MODE */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref FMPI2C_DUAL_ADDRESSING_MODE */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected - This parameter can be a 7-bit address. */ - - uint32_t OwnAddress2Masks; /*!< Specifies the acknowledge mask address second device own address if dual addressing - mode is selected. - This parameter can be a value of @ref FMPI2C_OWN_ADDRESS2_MASKS */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref FMPI2C_GENERAL_CALL_ADDRESSING_MODE */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref FMPI2C_NOSTRETCH_MODE */ - -} FMPI2C_InitTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_state_structure_definition HAL state structure definition - * @brief HAL State structure definition - * @note HAL FMPI2C State value coding follow below described bitmap :\n - * b7-b6 Error information\n - * 00 : No Error\n - * 01 : Abort (Abort user request on going)\n - * 10 : Timeout\n - * 11 : Error\n - * b5 Peripheral initialization status\n - * 0 : Reset (peripheral not initialized)\n - * 1 : Init done (peripheral initialized and ready to use. HAL FMPI2C Init function called)\n - * b4 (not used)\n - * x : Should be set to 0\n - * b3\n - * 0 : Ready or Busy (No Listen mode ongoing)\n - * 1 : Listen (peripheral in Address Listen Mode)\n - * b2 Intrinsic process state\n - * 0 : Ready\n - * 1 : Busy (peripheral busy with some configuration or internal operations)\n - * b1 Rx state\n - * 0 : Ready (no Rx operation ongoing)\n - * 1 : Busy (Rx operation ongoing)\n - * b0 Tx state\n - * 0 : Ready (no Tx operation ongoing)\n - * 1 : Busy (Tx operation ongoing) - * @{ - */ -typedef enum -{ - HAL_FMPI2C_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_FMPI2C_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */ - HAL_FMPI2C_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */ - HAL_FMPI2C_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */ - HAL_FMPI2C_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_FMPI2C_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */ - HAL_FMPI2C_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission - process is ongoing */ - HAL_FMPI2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception - process is ongoing */ - HAL_FMPI2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ - HAL_FMPI2C_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */ - HAL_FMPI2C_STATE_ERROR = 0xE0U /*!< Error */ - -} HAL_FMPI2C_StateTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_mode_structure_definition HAL mode structure definition - * @brief HAL Mode structure definition - * @note HAL FMPI2C Mode value coding follow below described bitmap :\n - * b7 (not used)\n - * x : Should be set to 0\n - * b6\n - * 0 : None\n - * 1 : Memory (HAL FMPI2C communication is in Memory Mode)\n - * b5\n - * 0 : None\n - * 1 : Slave (HAL FMPI2C communication is in Slave Mode)\n - * b4\n - * 0 : None\n - * 1 : Master (HAL FMPI2C communication is in Master Mode)\n - * b3-b2-b1-b0 (not used)\n - * xxxx : Should be set to 0000 - * @{ - */ -typedef enum -{ - HAL_FMPI2C_MODE_NONE = 0x00U, /*!< No FMPI2C communication on going */ - HAL_FMPI2C_MODE_MASTER = 0x10U, /*!< FMPI2C communication is in Master Mode */ - HAL_FMPI2C_MODE_SLAVE = 0x20U, /*!< FMPI2C communication is in Slave Mode */ - HAL_FMPI2C_MODE_MEM = 0x40U /*!< FMPI2C communication is in Memory Mode */ - -} HAL_FMPI2C_ModeTypeDef; - -/** - * @} - */ - -/** @defgroup FMPI2C_Error_Code_definition FMPI2C Error Code definition - * @brief FMPI2C Error Code definition - * @{ - */ -#define HAL_FMPI2C_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_FMPI2C_ERROR_BERR (0x00000001U) /*!< BERR error */ -#define HAL_FMPI2C_ERROR_ARLO (0x00000002U) /*!< ARLO error */ -#define HAL_FMPI2C_ERROR_AF (0x00000004U) /*!< ACKF error */ -#define HAL_FMPI2C_ERROR_OVR (0x00000008U) /*!< OVR error */ -#define HAL_FMPI2C_ERROR_DMA (0x00000010U) /*!< DMA transfer error */ -#define HAL_FMPI2C_ERROR_TIMEOUT (0x00000020U) /*!< Timeout error */ -#define HAL_FMPI2C_ERROR_SIZE (0x00000040U) /*!< Size Management error */ -#define HAL_FMPI2C_ERROR_DMA_PARAM (0x00000080U) /*!< DMA Parameter Error */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -#define HAL_FMPI2C_ERROR_INVALID_CALLBACK (0x00000100U) /*!< Invalid Callback error */ -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -#define HAL_FMPI2C_ERROR_INVALID_PARAM (0x00000200U) /*!< Invalid Parameters error */ -/** - * @} - */ - -/** @defgroup FMPI2C_handle_Structure_definition FMPI2C handle Structure definition - * @brief FMPI2C handle Structure definition - * @{ - */ -typedef struct __FMPI2C_HandleTypeDef -{ - FMPI2C_TypeDef *Instance; /*!< FMPI2C registers base address */ - - FMPI2C_InitTypeDef Init; /*!< FMPI2C communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to FMPI2C transfer buffer */ - - uint16_t XferSize; /*!< FMPI2C transfer size */ - - __IO uint16_t XferCount; /*!< FMPI2C transfer counter */ - - __IO uint32_t XferOptions; /*!< FMPI2C sequantial transfer options, this parameter can - be a value of @ref FMPI2C_XFEROPTIONS */ - - __IO uint32_t PreviousState; /*!< FMPI2C communication Previous state */ - - HAL_StatusTypeDef(*XferISR)(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, uint32_t ITSources); - /*!< FMPI2C transfer IRQ handler function pointer */ - - DMA_HandleTypeDef *hdmatx; /*!< FMPI2C Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< FMPI2C Rx DMA handle parameters */ - - HAL_LockTypeDef Lock; /*!< FMPI2C locking object */ - - __IO HAL_FMPI2C_StateTypeDef State; /*!< FMPI2C communication state */ - - __IO HAL_FMPI2C_ModeTypeDef Mode; /*!< FMPI2C communication mode */ - - __IO uint32_t ErrorCode; /*!< FMPI2C Error code */ - - __IO uint32_t AddrEventCount; /*!< FMPI2C Address Event counter */ - -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Listen Complete callback */ - void (* MemTxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Memory Tx Transfer completed callback */ - void (* MemRxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Memory Rx Transfer completed callback */ - void (* ErrorCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Error callback */ - void (* AbortCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Abort callback */ - - void (* AddrCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); - /*!< FMPI2C Slave Address Match callback */ - - void (* MspInitCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Msp Init callback */ - void (* MspDeInitCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Msp DeInit callback */ - -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -} FMPI2C_HandleTypeDef; - -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -/** - * @brief HAL FMPI2C Callback ID enumeration definition - */ -typedef enum -{ - HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< FMPI2C Master Tx Transfer completed callback ID */ - HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< FMPI2C Master Rx Transfer completed callback ID */ - HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< FMPI2C Slave Tx Transfer completed callback ID */ - HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< FMPI2C Slave Rx Transfer completed callback ID */ - HAL_FMPI2C_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< FMPI2C Listen Complete callback ID */ - HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID = 0x05U, /*!< FMPI2C Memory Tx Transfer callback ID */ - HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID = 0x06U, /*!< FMPI2C Memory Rx Transfer completed callback ID */ - HAL_FMPI2C_ERROR_CB_ID = 0x07U, /*!< FMPI2C Error callback ID */ - HAL_FMPI2C_ABORT_CB_ID = 0x08U, /*!< FMPI2C Abort callback ID */ - - HAL_FMPI2C_MSPINIT_CB_ID = 0x09U, /*!< FMPI2C Msp Init callback ID */ - HAL_FMPI2C_MSPDEINIT_CB_ID = 0x0AU /*!< FMPI2C Msp DeInit callback ID */ - -} HAL_FMPI2C_CallbackIDTypeDef; - -/** - * @brief HAL FMPI2C Callback pointer definition - */ -typedef void (*pFMPI2C_CallbackTypeDef)(FMPI2C_HandleTypeDef *hfmpi2c); -/*!< pointer to an FMPI2C callback function */ -typedef void (*pFMPI2C_AddrCallbackTypeDef)(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t TransferDirection, - uint16_t AddrMatchCode); -/*!< pointer to an FMPI2C Address Match callback function */ - -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup FMPI2C_Exported_Constants FMPI2C Exported Constants - * @{ - */ - -/** @defgroup FMPI2C_XFEROPTIONS FMPI2C Sequential Transfer Options - * @{ - */ -#define FMPI2C_FIRST_FRAME ((uint32_t)FMPI2C_SOFTEND_MODE) -#define FMPI2C_FIRST_AND_NEXT_FRAME ((uint32_t)(FMPI2C_RELOAD_MODE | FMPI2C_SOFTEND_MODE)) -#define FMPI2C_NEXT_FRAME ((uint32_t)(FMPI2C_RELOAD_MODE | FMPI2C_SOFTEND_MODE)) -#define FMPI2C_FIRST_AND_LAST_FRAME ((uint32_t)FMPI2C_AUTOEND_MODE) -#define FMPI2C_LAST_FRAME ((uint32_t)FMPI2C_AUTOEND_MODE) -#define FMPI2C_LAST_FRAME_NO_STOP ((uint32_t)FMPI2C_SOFTEND_MODE) - -/* List of XferOptions in usage of : - * 1- Restart condition in all use cases (direction change or not) - */ -#define FMPI2C_OTHER_FRAME (0x000000AAU) -#define FMPI2C_OTHER_AND_LAST_FRAME (0x0000AA00U) -/** - * @} - */ - -/** @defgroup FMPI2C_ADDRESSING_MODE FMPI2C Addressing Mode - * @{ - */ -#define FMPI2C_ADDRESSINGMODE_7BIT (0x00000001U) -#define FMPI2C_ADDRESSINGMODE_10BIT (0x00000002U) -/** - * @} - */ - -/** @defgroup FMPI2C_DUAL_ADDRESSING_MODE FMPI2C Dual Addressing Mode - * @{ - */ -#define FMPI2C_DUALADDRESS_DISABLE (0x00000000U) -#define FMPI2C_DUALADDRESS_ENABLE FMPI2C_OAR2_OA2EN -/** - * @} - */ - -/** @defgroup FMPI2C_OWN_ADDRESS2_MASKS FMPI2C Own Address2 Masks - * @{ - */ -#define FMPI2C_OA2_NOMASK ((uint8_t)0x00U) -#define FMPI2C_OA2_MASK01 ((uint8_t)0x01U) -#define FMPI2C_OA2_MASK02 ((uint8_t)0x02U) -#define FMPI2C_OA2_MASK03 ((uint8_t)0x03U) -#define FMPI2C_OA2_MASK04 ((uint8_t)0x04U) -#define FMPI2C_OA2_MASK05 ((uint8_t)0x05U) -#define FMPI2C_OA2_MASK06 ((uint8_t)0x06U) -#define FMPI2C_OA2_MASK07 ((uint8_t)0x07U) -/** - * @} - */ - -/** @defgroup FMPI2C_GENERAL_CALL_ADDRESSING_MODE FMPI2C General Call Addressing Mode - * @{ - */ -#define FMPI2C_GENERALCALL_DISABLE (0x00000000U) -#define FMPI2C_GENERALCALL_ENABLE FMPI2C_CR1_GCEN -/** - * @} - */ - -/** @defgroup FMPI2C_NOSTRETCH_MODE FMPI2C No-Stretch Mode - * @{ - */ -#define FMPI2C_NOSTRETCH_DISABLE (0x00000000U) -#define FMPI2C_NOSTRETCH_ENABLE FMPI2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup FMPI2C_MEMORY_ADDRESS_SIZE FMPI2C Memory Address Size - * @{ - */ -#define FMPI2C_MEMADD_SIZE_8BIT (0x00000001U) -#define FMPI2C_MEMADD_SIZE_16BIT (0x00000002U) -/** - * @} - */ - -/** @defgroup FMPI2C_XFERDIRECTION FMPI2C Transfer Direction Master Point of View - * @{ - */ -#define FMPI2C_DIRECTION_TRANSMIT (0x00000000U) -#define FMPI2C_DIRECTION_RECEIVE (0x00000001U) -/** - * @} - */ - -/** @defgroup FMPI2C_RELOAD_END_MODE FMPI2C Reload End Mode - * @{ - */ -#define FMPI2C_RELOAD_MODE FMPI2C_CR2_RELOAD -#define FMPI2C_AUTOEND_MODE FMPI2C_CR2_AUTOEND -#define FMPI2C_SOFTEND_MODE (0x00000000U) -/** - * @} - */ - -/** @defgroup FMPI2C_START_STOP_MODE FMPI2C Start or Stop Mode - * @{ - */ -#define FMPI2C_NO_STARTSTOP (0x00000000U) -#define FMPI2C_GENERATE_STOP (uint32_t)(0x80000000U | FMPI2C_CR2_STOP) -#define FMPI2C_GENERATE_START_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | FMPI2C_CR2_RD_WRN) -#define FMPI2C_GENERATE_START_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/** - * @} - */ - -/** @defgroup FMPI2C_Interrupt_configuration_definition FMPI2C Interrupt configuration definition - * @brief FMPI2C Interrupt definition - * Elements values convention: 0xXXXXXXXX - * - XXXXXXXX : Interrupt control mask - * @{ - */ -#define FMPI2C_IT_ERRI FMPI2C_CR1_ERRIE -#define FMPI2C_IT_TCI FMPI2C_CR1_TCIE -#define FMPI2C_IT_STOPI FMPI2C_CR1_STOPIE -#define FMPI2C_IT_NACKI FMPI2C_CR1_NACKIE -#define FMPI2C_IT_ADDRI FMPI2C_CR1_ADDRIE -#define FMPI2C_IT_RXI FMPI2C_CR1_RXIE -#define FMPI2C_IT_TXI FMPI2C_CR1_TXIE -/** - * @} - */ - -/** @defgroup FMPI2C_Flag_definition FMPI2C Flag definition - * @{ - */ -#define FMPI2C_FLAG_TXE FMPI2C_ISR_TXE -#define FMPI2C_FLAG_TXIS FMPI2C_ISR_TXIS -#define FMPI2C_FLAG_RXNE FMPI2C_ISR_RXNE -#define FMPI2C_FLAG_ADDR FMPI2C_ISR_ADDR -#define FMPI2C_FLAG_AF FMPI2C_ISR_NACKF -#define FMPI2C_FLAG_STOPF FMPI2C_ISR_STOPF -#define FMPI2C_FLAG_TC FMPI2C_ISR_TC -#define FMPI2C_FLAG_TCR FMPI2C_ISR_TCR -#define FMPI2C_FLAG_BERR FMPI2C_ISR_BERR -#define FMPI2C_FLAG_ARLO FMPI2C_ISR_ARLO -#define FMPI2C_FLAG_OVR FMPI2C_ISR_OVR -#define FMPI2C_FLAG_PECERR FMPI2C_ISR_PECERR -#define FMPI2C_FLAG_TIMEOUT FMPI2C_ISR_TIMEOUT -#define FMPI2C_FLAG_ALERT FMPI2C_ISR_ALERT -#define FMPI2C_FLAG_BUSY FMPI2C_ISR_BUSY -#define FMPI2C_FLAG_DIR FMPI2C_ISR_DIR -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ - -/** @defgroup FMPI2C_Exported_Macros FMPI2C Exported Macros - * @{ - */ - -/** @brief Reset FMPI2C handle state. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @retval None - */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -#define __HAL_FMPI2C_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_FMPI2C_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_FMPI2C_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_FMPI2C_STATE_RESET) -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - -/** @brief Enable the specified FMPI2C interrupt. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_IT_ERRI Errors interrupt enable - * @arg @ref FMPI2C_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPI2C_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPI2C_IT_NACKI NACK received interrupt enable - * @arg @ref FMPI2C_IT_ADDRI Address match interrupt enable - * @arg @ref FMPI2C_IT_RXI RX interrupt enable - * @arg @ref FMPI2C_IT_TXI TX interrupt enable - * - * @retval None - */ -#define __HAL_FMPI2C_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 |= (__INTERRUPT__)) - -/** @brief Disable the specified FMPI2C interrupt. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __INTERRUPT__ specifies the interrupt source to disable. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_IT_ERRI Errors interrupt enable - * @arg @ref FMPI2C_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPI2C_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPI2C_IT_NACKI NACK received interrupt enable - * @arg @ref FMPI2C_IT_ADDRI Address match interrupt enable - * @arg @ref FMPI2C_IT_RXI RX interrupt enable - * @arg @ref FMPI2C_IT_TXI TX interrupt enable - * - * @retval None - */ -#define __HAL_FMPI2C_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 &= (~(__INTERRUPT__))) - -/** @brief Check whether the specified FMPI2C interrupt source is enabled or not. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __INTERRUPT__ specifies the FMPI2C interrupt source to check. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_IT_ERRI Errors interrupt enable - * @arg @ref FMPI2C_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPI2C_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPI2C_IT_NACKI NACK received interrupt enable - * @arg @ref FMPI2C_IT_ADDRI Address match interrupt enable - * @arg @ref FMPI2C_IT_RXI RX interrupt enable - * @arg @ref FMPI2C_IT_TXI TX interrupt enable - * - * @retval The new state of __INTERRUPT__ (SET or RESET). - */ -#define __HAL_FMPI2C_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR1 & \ - (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified FMPI2C flag is set or not. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_FLAG_TXE Transmit data register empty - * @arg @ref FMPI2C_FLAG_TXIS Transmit interrupt status - * @arg @ref FMPI2C_FLAG_RXNE Receive data register not empty - * @arg @ref FMPI2C_FLAG_ADDR Address matched (slave mode) - * @arg @ref FMPI2C_FLAG_AF Acknowledge failure received flag - * @arg @ref FMPI2C_FLAG_STOPF STOP detection flag - * @arg @ref FMPI2C_FLAG_TC Transfer complete (master mode) - * @arg @ref FMPI2C_FLAG_TCR Transfer complete reload - * @arg @ref FMPI2C_FLAG_BERR Bus error - * @arg @ref FMPI2C_FLAG_ARLO Arbitration lost - * @arg @ref FMPI2C_FLAG_OVR Overrun/Underrun - * @arg @ref FMPI2C_FLAG_PECERR PEC error in reception - * @arg @ref FMPI2C_FLAG_TIMEOUT Timeout or Tlow detection flag - * @arg @ref FMPI2C_FLAG_ALERT SMBus alert - * @arg @ref FMPI2C_FLAG_BUSY Bus busy - * @arg @ref FMPI2C_FLAG_DIR Transfer direction (slave mode) - * - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define FMPI2C_FLAG_MASK (0x0001FFFFU) -#define __HAL_FMPI2C_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & \ - (__FLAG__)) == (__FLAG__)) ? SET : RESET) - -/** @brief Clear the FMPI2C pending flags which are cleared by writing 1 in a specific bit. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg @ref FMPI2C_FLAG_TXE Transmit data register empty - * @arg @ref FMPI2C_FLAG_ADDR Address matched (slave mode) - * @arg @ref FMPI2C_FLAG_AF Acknowledge failure received flag - * @arg @ref FMPI2C_FLAG_STOPF STOP detection flag - * @arg @ref FMPI2C_FLAG_BERR Bus error - * @arg @ref FMPI2C_FLAG_ARLO Arbitration lost - * @arg @ref FMPI2C_FLAG_OVR Overrun/Underrun - * @arg @ref FMPI2C_FLAG_PECERR PEC error in reception - * @arg @ref FMPI2C_FLAG_TIMEOUT Timeout or Tlow detection flag - * @arg @ref FMPI2C_FLAG_ALERT SMBus alert - * - * @retval None - */ -#define __HAL_FMPI2C_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__FLAG__) == FMPI2C_FLAG_TXE) ? \ - ((__HANDLE__)->Instance->ISR |= (__FLAG__)) : \ - ((__HANDLE__)->Instance->ICR = (__FLAG__))) - -/** @brief Enable the specified FMPI2C peripheral. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @retval None - */ -#define __HAL_FMPI2C_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR1, FMPI2C_CR1_PE)) - -/** @brief Disable the specified FMPI2C peripheral. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @retval None - */ -#define __HAL_FMPI2C_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, FMPI2C_CR1_PE)) - -/** @brief Generate a Non-Acknowledge FMPI2C peripheral in Slave mode. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @retval None - */ -#define __HAL_FMPI2C_GENERATE_NACK(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR2, FMPI2C_CR2_NACK)) -/** - * @} - */ - -/* Include FMPI2C HAL Extended module */ -#include "stm32f4xx_hal_fmpi2c_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPI2C_Exported_Functions - * @{ - */ - -/** @addtogroup FMPI2C_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -/* Initialization and de-initialization functions******************************/ -HAL_StatusTypeDef HAL_FMPI2C_Init(FMPI2C_HandleTypeDef *hfmpi2c); -HAL_StatusTypeDef HAL_FMPI2C_DeInit(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MspInit(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MspDeInit(FMPI2C_HandleTypeDef *hfmpi2c); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_FMPI2C_RegisterCallback(FMPI2C_HandleTypeDef *hfmpi2c, HAL_FMPI2C_CallbackIDTypeDef CallbackID, - pFMPI2C_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_FMPI2C_UnRegisterCallback(FMPI2C_HandleTypeDef *hfmpi2c, HAL_FMPI2C_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_FMPI2C_RegisterAddrCallback(FMPI2C_HandleTypeDef *hfmpi2c, pFMPI2C_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_FMPI2C_UnRegisterAddrCallback(FMPI2C_HandleTypeDef *hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup FMPI2C_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* IO operation functions ****************************************************/ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_IsDeviceReady(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint32_t Trials, - uint32_t Timeout); - -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_EnableListen_IT(FMPI2C_HandleTypeDef *hfmpi2c); -HAL_StatusTypeDef HAL_FMPI2C_DisableListen_IT(FMPI2C_HandleTypeDef *hfmpi2c); -HAL_StatusTypeDef HAL_FMPI2C_Master_Abort_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress); - -/******* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -/** - * @} - */ - -/** @addtogroup FMPI2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* FMPI2C IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_FMPI2C_EV_IRQHandler(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_ER_IRQHandler(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MasterTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MasterRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_SlaveTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_SlaveRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_AddrCallback(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_FMPI2C_ListenCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MemTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MemRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_ErrorCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_AbortCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -/** - * @} - */ - -/** @addtogroup FMPI2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @{ - */ -/* Peripheral State, Mode and Error functions *********************************/ -HAL_FMPI2C_StateTypeDef HAL_FMPI2C_GetState(FMPI2C_HandleTypeDef *hfmpi2c); -HAL_FMPI2C_ModeTypeDef HAL_FMPI2C_GetMode(FMPI2C_HandleTypeDef *hfmpi2c); -uint32_t HAL_FMPI2C_GetError(FMPI2C_HandleTypeDef *hfmpi2c); - -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPI2C_Private_Constants FMPI2C Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FMPI2C_Private_Macro FMPI2C Private Macros - * @{ - */ - -#define IS_FMPI2C_ADDRESSING_MODE(MODE) (((MODE) == FMPI2C_ADDRESSINGMODE_7BIT) || \ - ((MODE) == FMPI2C_ADDRESSINGMODE_10BIT)) - -#define IS_FMPI2C_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == FMPI2C_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == FMPI2C_DUALADDRESS_ENABLE)) - -#define IS_FMPI2C_OWN_ADDRESS2_MASK(MASK) (((MASK) == FMPI2C_OA2_NOMASK) || \ - ((MASK) == FMPI2C_OA2_MASK01) || \ - ((MASK) == FMPI2C_OA2_MASK02) || \ - ((MASK) == FMPI2C_OA2_MASK03) || \ - ((MASK) == FMPI2C_OA2_MASK04) || \ - ((MASK) == FMPI2C_OA2_MASK05) || \ - ((MASK) == FMPI2C_OA2_MASK06) || \ - ((MASK) == FMPI2C_OA2_MASK07)) - -#define IS_FMPI2C_GENERAL_CALL(CALL) (((CALL) == FMPI2C_GENERALCALL_DISABLE) || \ - ((CALL) == FMPI2C_GENERALCALL_ENABLE)) - -#define IS_FMPI2C_NO_STRETCH(STRETCH) (((STRETCH) == FMPI2C_NOSTRETCH_DISABLE) || \ - ((STRETCH) == FMPI2C_NOSTRETCH_ENABLE)) - -#define IS_FMPI2C_MEMADD_SIZE(SIZE) (((SIZE) == FMPI2C_MEMADD_SIZE_8BIT) || \ - ((SIZE) == FMPI2C_MEMADD_SIZE_16BIT)) - -#define IS_TRANSFER_MODE(MODE) (((MODE) == FMPI2C_RELOAD_MODE) || \ - ((MODE) == FMPI2C_AUTOEND_MODE) || \ - ((MODE) == FMPI2C_SOFTEND_MODE)) - -#define IS_TRANSFER_REQUEST(REQUEST) (((REQUEST) == FMPI2C_GENERATE_STOP) || \ - ((REQUEST) == FMPI2C_GENERATE_START_READ) || \ - ((REQUEST) == FMPI2C_GENERATE_START_WRITE) || \ - ((REQUEST) == FMPI2C_NO_STARTSTOP)) - -#define IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == FMPI2C_FIRST_FRAME) || \ - ((REQUEST) == FMPI2C_FIRST_AND_NEXT_FRAME) || \ - ((REQUEST) == FMPI2C_NEXT_FRAME) || \ - ((REQUEST) == FMPI2C_FIRST_AND_LAST_FRAME) || \ - ((REQUEST) == FMPI2C_LAST_FRAME) || \ - ((REQUEST) == FMPI2C_LAST_FRAME_NO_STOP) || \ - IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST)) - -#define IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == FMPI2C_OTHER_FRAME) || \ - ((REQUEST) == FMPI2C_OTHER_AND_LAST_FRAME)) - -#define FMPI2C_RESET_CR2(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= \ - (uint32_t)~((uint32_t)(FMPI2C_CR2_SADD | FMPI2C_CR2_HEAD10R | \ - FMPI2C_CR2_NBYTES | FMPI2C_CR2_RELOAD | \ - FMPI2C_CR2_RD_WRN))) - -#define FMPI2C_GET_ADDR_MATCH(__HANDLE__) ((uint16_t)(((__HANDLE__)->Instance->ISR & FMPI2C_ISR_ADDCODE) \ - >> 16U)) -#define FMPI2C_GET_DIR(__HANDLE__) ((uint8_t)(((__HANDLE__)->Instance->ISR & FMPI2C_ISR_DIR) \ - >> 16U)) -#define FMPI2C_GET_STOP_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & FMPI2C_CR2_AUTOEND) -#define FMPI2C_GET_OWN_ADDRESS1(__HANDLE__) ((uint16_t)((__HANDLE__)->Instance->OAR1 & FMPI2C_OAR1_OA1)) -#define FMPI2C_GET_OWN_ADDRESS2(__HANDLE__) ((uint16_t)((__HANDLE__)->Instance->OAR2 & FMPI2C_OAR2_OA2)) - -#define IS_FMPI2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x000003FFU) -#define IS_FMPI2C_OWN_ADDRESS2(ADDRESS2) ((ADDRESS2) <= (uint16_t)0x00FFU) - -#define FMPI2C_MEM_ADD_MSB(__ADDRESS__) ((uint8_t)((uint16_t)(((uint16_t)((__ADDRESS__) & \ - (uint16_t)(0xFF00U))) >> 8U))) -#define FMPI2C_MEM_ADD_LSB(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FFU)))) - -#define FMPI2C_GENERATE_START(__ADDMODE__,__ADDRESS__) (((__ADDMODE__) == FMPI2C_ADDRESSINGMODE_7BIT) ? \ - (uint32_t)((((uint32_t)(__ADDRESS__) & (FMPI2C_CR2_SADD)) | \ - (FMPI2C_CR2_START) | (FMPI2C_CR2_AUTOEND)) & \ - (~FMPI2C_CR2_RD_WRN)) : \ - (uint32_t)((((uint32_t)(__ADDRESS__) & (FMPI2C_CR2_SADD)) | \ - (FMPI2C_CR2_ADD10) | (FMPI2C_CR2_START)) & \ - (~FMPI2C_CR2_RD_WRN))) - -#define FMPI2C_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & FMPI2C_FLAG_MASK)) == \ - ((__FLAG__) & FMPI2C_FLAG_MASK)) ? SET : RESET) -#define FMPI2C_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET) -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup FMPI2C_Private_Functions FMPI2C Private Functions - * @{ - */ -/* Private functions are defined in stm32f4xx_hal_fmpi2c.c file */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_FMPI2C_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c_ex.h deleted file mode 100644 index 6a5df0b1a1025c7..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c_ex.h +++ /dev/null @@ -1,153 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpi2c_ex.h - * @author MCD Application Team - * @brief Header file of FMPI2C HAL Extended module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_FMPI2C_EX_H -#define STM32F4xx_HAL_FMPI2C_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMPI2CEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Exported_Constants FMPI2C Extended Exported Constants - * @{ - */ - -/** @defgroup FMPI2CEx_Analog_Filter FMPI2C Extended Analog Filter - * @{ - */ -#define FMPI2C_ANALOGFILTER_ENABLE 0x00000000U -#define FMPI2C_ANALOGFILTER_DISABLE FMPI2C_CR1_ANFOFF -/** - * @} - */ - -/** @defgroup FMPI2CEx_FastModePlus FMPI2C Extended Fast Mode Plus - * @{ - */ -#define FMPI2C_FASTMODEPLUS_SCL SYSCFG_CFGR_FMPI2C1_SCL /*!< Enable Fast Mode Plus on FMPI2C1 SCL pins */ -#define FMPI2C_FASTMODEPLUS_SDA SYSCFG_CFGR_FMPI2C1_SDA /*!< Enable Fast Mode Plus on FMPI2C1 SDA pins */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Exported_Macros FMPI2C Extended Exported Macros - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPI2CEx_Exported_Functions FMPI2C Extended Exported Functions - * @{ - */ - -/** @addtogroup FMPI2CEx_Exported_Functions_Group1 Filter Mode Functions - * @{ - */ -/* Peripheral Control functions ************************************************/ -HAL_StatusTypeDef HAL_FMPI2CEx_ConfigAnalogFilter(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_FMPI2CEx_ConfigDigitalFilter(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t DigitalFilter); -/** - * @} - */ - -/** @addtogroup FMPI2CEx_Exported_Functions_Group3 Fast Mode Plus Functions - * @{ - */ -void HAL_FMPI2CEx_EnableFastModePlus(uint32_t ConfigFastModePlus); -void HAL_FMPI2CEx_DisableFastModePlus(uint32_t ConfigFastModePlus); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Private_Constants FMPI2C Extended Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Private_Macro FMPI2C Extended Private Macros - * @{ - */ -#define IS_FMPI2C_ANALOG_FILTER(FILTER) (((FILTER) == FMPI2C_ANALOGFILTER_ENABLE) || \ - ((FILTER) == FMPI2C_ANALOGFILTER_DISABLE)) - -#define IS_FMPI2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) - -#define IS_FMPI2C_FASTMODEPLUS(__CONFIG__) ((((__CONFIG__) & (FMPI2C_FASTMODEPLUS_SCL)) == FMPI2C_FASTMODEPLUS_SCL) || \ - (((__CONFIG__) & (FMPI2C_FASTMODEPLUS_SDA)) == FMPI2C_FASTMODEPLUS_SDA)) -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Private_Functions FMPI2C Extended Private Functions - * @{ - */ -/* Private functions are defined in stm32f4xx_hal_fmpi2c_ex.c file */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_FMPI2C_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus.h deleted file mode 100644 index 9d5e0307ed3558f..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus.h +++ /dev/null @@ -1,793 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpsmbus.h - * @author MCD Application Team - * @brief Header file of FMPSMBUS HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_FMPSMBUS_H -#define STM32F4xx_HAL_FMPSMBUS_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMPSMBUS - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Exported_Types FMPSMBUS Exported Types - * @{ - */ - -/** @defgroup FMPSMBUS_Configuration_Structure_definition FMPSMBUS Configuration Structure definition - * @brief FMPSMBUS Configuration Structure definition - * @{ - */ -typedef struct -{ - uint32_t Timing; /*!< Specifies the FMPSMBUS_TIMINGR_register value. - This parameter calculated by referring to FMPSMBUS initialization section - in Reference manual */ - uint32_t AnalogFilter; /*!< Specifies if Analog Filter is enable or not. - This parameter can be a value of @ref FMPSMBUS_Analog_Filter */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode for master is selected. - This parameter can be a value of @ref FMPSMBUS_addressing_mode */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref FMPSMBUS_dual_addressing_mode */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected - This parameter can be a 7-bit address. */ - - uint32_t OwnAddress2Masks; /*!< Specifies the acknowledge mask address second device own address - if dual addressing mode is selected - This parameter can be a value of @ref FMPSMBUS_own_address2_masks. */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref FMPSMBUS_general_call_addressing_mode. */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref FMPSMBUS_nostretch_mode */ - - uint32_t PacketErrorCheckMode; /*!< Specifies if Packet Error Check mode is selected. - This parameter can be a value of @ref FMPSMBUS_packet_error_check_mode */ - - uint32_t PeripheralMode; /*!< Specifies which mode of Periphal is selected. - This parameter can be a value of @ref FMPSMBUS_peripheral_mode */ - - uint32_t SMBusTimeout; /*!< Specifies the content of the 32 Bits FMPSMBUS_TIMEOUT_register value. - (Enable bits and different timeout values) - This parameter calculated by referring to FMPSMBUS initialization section - in Reference manual */ -} FMPSMBUS_InitTypeDef; -/** - * @} - */ - -/** @defgroup HAL_state_definition HAL state definition - * @brief HAL State definition - * @{ - */ -#define HAL_FMPSMBUS_STATE_RESET (0x00000000U) /*!< FMPSMBUS not yet initialized or disabled */ -#define HAL_FMPSMBUS_STATE_READY (0x00000001U) /*!< FMPSMBUS initialized and ready for use */ -#define HAL_FMPSMBUS_STATE_BUSY (0x00000002U) /*!< FMPSMBUS internal process is ongoing */ -#define HAL_FMPSMBUS_STATE_MASTER_BUSY_TX (0x00000012U) /*!< Master Data Transmission process is ongoing */ -#define HAL_FMPSMBUS_STATE_MASTER_BUSY_RX (0x00000022U) /*!< Master Data Reception process is ongoing */ -#define HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX (0x00000032U) /*!< Slave Data Transmission process is ongoing */ -#define HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX (0x00000042U) /*!< Slave Data Reception process is ongoing */ -#define HAL_FMPSMBUS_STATE_TIMEOUT (0x00000003U) /*!< Timeout state */ -#define HAL_FMPSMBUS_STATE_ERROR (0x00000004U) /*!< Reception process is ongoing */ -#define HAL_FMPSMBUS_STATE_LISTEN (0x00000008U) /*!< Address Listen Mode is ongoing */ -/** - * @} - */ - -/** @defgroup FMPSMBUS_Error_Code_definition FMPSMBUS Error Code definition - * @brief FMPSMBUS Error Code definition - * @{ - */ -#define HAL_FMPSMBUS_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_FMPSMBUS_ERROR_BERR (0x00000001U) /*!< BERR error */ -#define HAL_FMPSMBUS_ERROR_ARLO (0x00000002U) /*!< ARLO error */ -#define HAL_FMPSMBUS_ERROR_ACKF (0x00000004U) /*!< ACKF error */ -#define HAL_FMPSMBUS_ERROR_OVR (0x00000008U) /*!< OVR error */ -#define HAL_FMPSMBUS_ERROR_HALTIMEOUT (0x00000010U) /*!< Timeout error */ -#define HAL_FMPSMBUS_ERROR_BUSTIMEOUT (0x00000020U) /*!< Bus Timeout error */ -#define HAL_FMPSMBUS_ERROR_ALERT (0x00000040U) /*!< Alert error */ -#define HAL_FMPSMBUS_ERROR_PECERR (0x00000080U) /*!< PEC error */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -#define HAL_FMPSMBUS_ERROR_INVALID_CALLBACK (0x00000100U) /*!< Invalid Callback error */ -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -#define HAL_FMPSMBUS_ERROR_INVALID_PARAM (0x00000200U) /*!< Invalid Parameters error */ -/** - * @} - */ - -/** @defgroup FMPSMBUS_handle_Structure_definition FMPSMBUS handle Structure definition - * @brief FMPSMBUS handle Structure definition - * @{ - */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -typedef struct __FMPSMBUS_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -{ - FMPI2C_TypeDef *Instance; /*!< FMPSMBUS registers base address */ - - FMPSMBUS_InitTypeDef Init; /*!< FMPSMBUS communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to FMPSMBUS transfer buffer */ - - uint16_t XferSize; /*!< FMPSMBUS transfer size */ - - __IO uint16_t XferCount; /*!< FMPSMBUS transfer counter */ - - __IO uint32_t XferOptions; /*!< FMPSMBUS transfer options */ - - __IO uint32_t PreviousState; /*!< FMPSMBUS communication Previous state */ - - HAL_LockTypeDef Lock; /*!< FMPSMBUS locking object */ - - __IO uint32_t State; /*!< FMPSMBUS communication state */ - - __IO uint32_t ErrorCode; /*!< FMPSMBUS Error code */ - -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Listen Complete callback */ - void (* ErrorCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Error callback */ - - void (* AddrCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); - /*!< FMPSMBUS Slave Address Match callback */ - - void (* MspInitCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Msp Init callback */ - void (* MspDeInitCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Msp DeInit callback */ - -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -} FMPSMBUS_HandleTypeDef; - -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -/** - * @brief HAL FMPSMBUS Callback ID enumeration definition - */ -typedef enum -{ - HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< FMPSMBUS Master Tx Transfer completed callback ID */ - HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< FMPSMBUS Master Rx Transfer completed callback ID */ - HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< FMPSMBUS Slave Tx Transfer completed callback ID */ - HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< FMPSMBUS Slave Rx Transfer completed callback ID */ - HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< FMPSMBUS Listen Complete callback ID */ - HAL_FMPSMBUS_ERROR_CB_ID = 0x05U, /*!< FMPSMBUS Error callback ID */ - - HAL_FMPSMBUS_MSPINIT_CB_ID = 0x06U, /*!< FMPSMBUS Msp Init callback ID */ - HAL_FMPSMBUS_MSPDEINIT_CB_ID = 0x07U /*!< FMPSMBUS Msp DeInit callback ID */ - -} HAL_FMPSMBUS_CallbackIDTypeDef; - -/** - * @brief HAL FMPSMBUS Callback pointer definition - */ -typedef void (*pFMPSMBUS_CallbackTypeDef)(FMPSMBUS_HandleTypeDef *hfmpsmbus); -/*!< pointer to an FMPSMBUS callback function */ -typedef void (*pFMPSMBUS_AddrCallbackTypeDef)(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t TransferDirection, - uint16_t AddrMatchCode); -/*!< pointer to an FMPSMBUS Address Match callback function */ - -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup FMPSMBUS_Exported_Constants FMPSMBUS Exported Constants - * @{ - */ - -/** @defgroup FMPSMBUS_Analog_Filter FMPSMBUS Analog Filter - * @{ - */ -#define FMPSMBUS_ANALOGFILTER_ENABLE (0x00000000U) -#define FMPSMBUS_ANALOGFILTER_DISABLE FMPI2C_CR1_ANFOFF -/** - * @} - */ - -/** @defgroup FMPSMBUS_addressing_mode FMPSMBUS addressing mode - * @{ - */ -#define FMPSMBUS_ADDRESSINGMODE_7BIT (0x00000001U) -#define FMPSMBUS_ADDRESSINGMODE_10BIT (0x00000002U) -/** - * @} - */ - -/** @defgroup FMPSMBUS_dual_addressing_mode FMPSMBUS dual addressing mode - * @{ - */ - -#define FMPSMBUS_DUALADDRESS_DISABLE (0x00000000U) -#define FMPSMBUS_DUALADDRESS_ENABLE FMPI2C_OAR2_OA2EN -/** - * @} - */ - -/** @defgroup FMPSMBUS_own_address2_masks FMPSMBUS ownaddress2 masks - * @{ - */ - -#define FMPSMBUS_OA2_NOMASK ((uint8_t)0x00U) -#define FMPSMBUS_OA2_MASK01 ((uint8_t)0x01U) -#define FMPSMBUS_OA2_MASK02 ((uint8_t)0x02U) -#define FMPSMBUS_OA2_MASK03 ((uint8_t)0x03U) -#define FMPSMBUS_OA2_MASK04 ((uint8_t)0x04U) -#define FMPSMBUS_OA2_MASK05 ((uint8_t)0x05U) -#define FMPSMBUS_OA2_MASK06 ((uint8_t)0x06U) -#define FMPSMBUS_OA2_MASK07 ((uint8_t)0x07U) -/** - * @} - */ - - -/** @defgroup FMPSMBUS_general_call_addressing_mode FMPSMBUS general call addressing mode - * @{ - */ -#define FMPSMBUS_GENERALCALL_DISABLE (0x00000000U) -#define FMPSMBUS_GENERALCALL_ENABLE FMPI2C_CR1_GCEN -/** - * @} - */ - -/** @defgroup FMPSMBUS_nostretch_mode FMPSMBUS nostretch mode - * @{ - */ -#define FMPSMBUS_NOSTRETCH_DISABLE (0x00000000U) -#define FMPSMBUS_NOSTRETCH_ENABLE FMPI2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup FMPSMBUS_packet_error_check_mode FMPSMBUS packet error check mode - * @{ - */ -#define FMPSMBUS_PEC_DISABLE (0x00000000U) -#define FMPSMBUS_PEC_ENABLE FMPI2C_CR1_PECEN -/** - * @} - */ - -/** @defgroup FMPSMBUS_peripheral_mode FMPSMBUS peripheral mode - * @{ - */ -#define FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_HOST FMPI2C_CR1_SMBHEN -#define FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE (0x00000000U) -#define FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE_ARP FMPI2C_CR1_SMBDEN -/** - * @} - */ - -/** @defgroup FMPSMBUS_ReloadEndMode_definition FMPSMBUS ReloadEndMode definition - * @{ - */ - -#define FMPSMBUS_SOFTEND_MODE (0x00000000U) -#define FMPSMBUS_RELOAD_MODE FMPI2C_CR2_RELOAD -#define FMPSMBUS_AUTOEND_MODE FMPI2C_CR2_AUTOEND -#define FMPSMBUS_SENDPEC_MODE FMPI2C_CR2_PECBYTE -/** - * @} - */ - -/** @defgroup FMPSMBUS_StartStopMode_definition FMPSMBUS StartStopMode definition - * @{ - */ - -#define FMPSMBUS_NO_STARTSTOP (0x00000000U) -#define FMPSMBUS_GENERATE_STOP (uint32_t)(0x80000000U | FMPI2C_CR2_STOP) -#define FMPSMBUS_GENERATE_START_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | FMPI2C_CR2_RD_WRN) -#define FMPSMBUS_GENERATE_START_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/** - * @} - */ - -/** @defgroup FMPSMBUS_XferOptions_definition FMPSMBUS XferOptions definition - * @{ - */ - -/* List of XferOptions in usage of : - * 1- Restart condition when direction change - * 2- No Restart condition in other use cases - */ -#define FMPSMBUS_FIRST_FRAME FMPSMBUS_SOFTEND_MODE -#define FMPSMBUS_NEXT_FRAME ((uint32_t)(FMPSMBUS_RELOAD_MODE | FMPSMBUS_SOFTEND_MODE)) -#define FMPSMBUS_FIRST_AND_LAST_FRAME_NO_PEC FMPSMBUS_AUTOEND_MODE -#define FMPSMBUS_LAST_FRAME_NO_PEC FMPSMBUS_AUTOEND_MODE -#define FMPSMBUS_FIRST_FRAME_WITH_PEC ((uint32_t)(FMPSMBUS_SOFTEND_MODE | FMPSMBUS_SENDPEC_MODE)) -#define FMPSMBUS_FIRST_AND_LAST_FRAME_WITH_PEC ((uint32_t)(FMPSMBUS_AUTOEND_MODE | FMPSMBUS_SENDPEC_MODE)) -#define FMPSMBUS_LAST_FRAME_WITH_PEC ((uint32_t)(FMPSMBUS_AUTOEND_MODE | FMPSMBUS_SENDPEC_MODE)) - -/* List of XferOptions in usage of : - * 1- Restart condition in all use cases (direction change or not) - */ -#define FMPSMBUS_OTHER_FRAME_NO_PEC (0x000000AAU) -#define FMPSMBUS_OTHER_FRAME_WITH_PEC (0x0000AA00U) -#define FMPSMBUS_OTHER_AND_LAST_FRAME_NO_PEC (0x00AA0000U) -#define FMPSMBUS_OTHER_AND_LAST_FRAME_WITH_PEC (0xAA000000U) -/** - * @} - */ - -/** @defgroup FMPSMBUS_Interrupt_configuration_definition FMPSMBUS Interrupt configuration definition - * @brief FMPSMBUS Interrupt definition - * Elements values convention: 0xXXXXXXXX - * - XXXXXXXX : Interrupt control mask - * @{ - */ -#define FMPSMBUS_IT_ERRI FMPI2C_CR1_ERRIE -#define FMPSMBUS_IT_TCI FMPI2C_CR1_TCIE -#define FMPSMBUS_IT_STOPI FMPI2C_CR1_STOPIE -#define FMPSMBUS_IT_NACKI FMPI2C_CR1_NACKIE -#define FMPSMBUS_IT_ADDRI FMPI2C_CR1_ADDRIE -#define FMPSMBUS_IT_RXI FMPI2C_CR1_RXIE -#define FMPSMBUS_IT_TXI FMPI2C_CR1_TXIE -#define FMPSMBUS_IT_TX (FMPSMBUS_IT_ERRI | FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | \ - FMPSMBUS_IT_NACKI | FMPSMBUS_IT_TXI) -#define FMPSMBUS_IT_RX (FMPSMBUS_IT_ERRI | FMPSMBUS_IT_TCI | FMPSMBUS_IT_NACKI | \ - FMPSMBUS_IT_RXI) -#define FMPSMBUS_IT_ALERT (FMPSMBUS_IT_ERRI) -#define FMPSMBUS_IT_ADDR (FMPSMBUS_IT_ADDRI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI) -/** - * @} - */ - -/** @defgroup FMPSMBUS_Flag_definition FMPSMBUS Flag definition - * @brief Flag definition - * Elements values convention: 0xXXXXYYYY - * - XXXXXXXX : Flag mask - * @{ - */ - -#define FMPSMBUS_FLAG_TXE FMPI2C_ISR_TXE -#define FMPSMBUS_FLAG_TXIS FMPI2C_ISR_TXIS -#define FMPSMBUS_FLAG_RXNE FMPI2C_ISR_RXNE -#define FMPSMBUS_FLAG_ADDR FMPI2C_ISR_ADDR -#define FMPSMBUS_FLAG_AF FMPI2C_ISR_NACKF -#define FMPSMBUS_FLAG_STOPF FMPI2C_ISR_STOPF -#define FMPSMBUS_FLAG_TC FMPI2C_ISR_TC -#define FMPSMBUS_FLAG_TCR FMPI2C_ISR_TCR -#define FMPSMBUS_FLAG_BERR FMPI2C_ISR_BERR -#define FMPSMBUS_FLAG_ARLO FMPI2C_ISR_ARLO -#define FMPSMBUS_FLAG_OVR FMPI2C_ISR_OVR -#define FMPSMBUS_FLAG_PECERR FMPI2C_ISR_PECERR -#define FMPSMBUS_FLAG_TIMEOUT FMPI2C_ISR_TIMEOUT -#define FMPSMBUS_FLAG_ALERT FMPI2C_ISR_ALERT -#define FMPSMBUS_FLAG_BUSY FMPI2C_ISR_BUSY -#define FMPSMBUS_FLAG_DIR FMPI2C_ISR_DIR -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros ------------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Exported_Macros FMPSMBUS Exported Macros - * @{ - */ - -/** @brief Reset FMPSMBUS handle state. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @retval None - */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -#define __HAL_FMPSMBUS_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_FMPSMBUS_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_FMPSMBUS_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_FMPSMBUS_STATE_RESET) -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - -/** @brief Enable the specified FMPSMBUS interrupts. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_IT_ERRI Errors interrupt enable - * @arg @ref FMPSMBUS_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPSMBUS_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPSMBUS_IT_NACKI NACK received interrupt enable - * @arg @ref FMPSMBUS_IT_ADDRI Address match interrupt enable - * @arg @ref FMPSMBUS_IT_RXI RX interrupt enable - * @arg @ref FMPSMBUS_IT_TXI TX interrupt enable - * - * @retval None - */ -#define __HAL_FMPSMBUS_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 |= (__INTERRUPT__)) - -/** @brief Disable the specified FMPSMBUS interrupts. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __INTERRUPT__ specifies the interrupt source to disable. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_IT_ERRI Errors interrupt enable - * @arg @ref FMPSMBUS_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPSMBUS_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPSMBUS_IT_NACKI NACK received interrupt enable - * @arg @ref FMPSMBUS_IT_ADDRI Address match interrupt enable - * @arg @ref FMPSMBUS_IT_RXI RX interrupt enable - * @arg @ref FMPSMBUS_IT_TXI TX interrupt enable - * - * @retval None - */ -#define __HAL_FMPSMBUS_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 &= (~(__INTERRUPT__))) - -/** @brief Check whether the specified FMPSMBUS interrupt source is enabled or not. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __INTERRUPT__ specifies the FMPSMBUS interrupt source to check. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_IT_ERRI Errors interrupt enable - * @arg @ref FMPSMBUS_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPSMBUS_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPSMBUS_IT_NACKI NACK received interrupt enable - * @arg @ref FMPSMBUS_IT_ADDRI Address match interrupt enable - * @arg @ref FMPSMBUS_IT_RXI RX interrupt enable - * @arg @ref FMPSMBUS_IT_TXI TX interrupt enable - * - * @retval The new state of __IT__ (SET or RESET). - */ -#define __HAL_FMPSMBUS_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) \ - ((((__HANDLE__)->Instance->CR1 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified FMPSMBUS flag is set or not. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_FLAG_TXE Transmit data register empty - * @arg @ref FMPSMBUS_FLAG_TXIS Transmit interrupt status - * @arg @ref FMPSMBUS_FLAG_RXNE Receive data register not empty - * @arg @ref FMPSMBUS_FLAG_ADDR Address matched (slave mode) - * @arg @ref FMPSMBUS_FLAG_AF NACK received flag - * @arg @ref FMPSMBUS_FLAG_STOPF STOP detection flag - * @arg @ref FMPSMBUS_FLAG_TC Transfer complete (master mode) - * @arg @ref FMPSMBUS_FLAG_TCR Transfer complete reload - * @arg @ref FMPSMBUS_FLAG_BERR Bus error - * @arg @ref FMPSMBUS_FLAG_ARLO Arbitration lost - * @arg @ref FMPSMBUS_FLAG_OVR Overrun/Underrun - * @arg @ref FMPSMBUS_FLAG_PECERR PEC error in reception - * @arg @ref FMPSMBUS_FLAG_TIMEOUT Timeout or Tlow detection flag - * @arg @ref FMPSMBUS_FLAG_ALERT SMBus alert - * @arg @ref FMPSMBUS_FLAG_BUSY Bus busy - * @arg @ref FMPSMBUS_FLAG_DIR Transfer direction (slave mode) - * - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define FMPSMBUS_FLAG_MASK (0x0001FFFFU) -#define __HAL_FMPSMBUS_GET_FLAG(__HANDLE__, __FLAG__) \ - (((((__HANDLE__)->Instance->ISR) & ((__FLAG__) & FMPSMBUS_FLAG_MASK)) == \ - ((__FLAG__) & FMPSMBUS_FLAG_MASK)) ? SET : RESET) - -/** @brief Clear the FMPSMBUS pending flags which are cleared by writing 1 in a specific bit. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg @ref FMPSMBUS_FLAG_ADDR Address matched (slave mode) - * @arg @ref FMPSMBUS_FLAG_AF NACK received flag - * @arg @ref FMPSMBUS_FLAG_STOPF STOP detection flag - * @arg @ref FMPSMBUS_FLAG_BERR Bus error - * @arg @ref FMPSMBUS_FLAG_ARLO Arbitration lost - * @arg @ref FMPSMBUS_FLAG_OVR Overrun/Underrun - * @arg @ref FMPSMBUS_FLAG_PECERR PEC error in reception - * @arg @ref FMPSMBUS_FLAG_TIMEOUT Timeout or Tlow detection flag - * @arg @ref FMPSMBUS_FLAG_ALERT SMBus alert - * - * @retval None - */ -#define __HAL_FMPSMBUS_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__)) - -/** @brief Enable the specified FMPSMBUS peripheral. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @retval None - */ -#define __HAL_FMPSMBUS_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR1, FMPI2C_CR1_PE)) - -/** @brief Disable the specified FMPSMBUS peripheral. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @retval None - */ -#define __HAL_FMPSMBUS_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, FMPI2C_CR1_PE)) - -/** @brief Generate a Non-Acknowledge FMPSMBUS peripheral in Slave mode. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @retval None - */ -#define __HAL_FMPSMBUS_GENERATE_NACK(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR2, FMPI2C_CR2_NACK)) - -/** - * @} - */ - - -/* Private constants ---------------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Private_Macro FMPSMBUS Private Macros - * @{ - */ - -#define IS_FMPSMBUS_ANALOG_FILTER(FILTER) (((FILTER) == FMPSMBUS_ANALOGFILTER_ENABLE) || \ - ((FILTER) == FMPSMBUS_ANALOGFILTER_DISABLE)) - -#define IS_FMPSMBUS_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) - -#define IS_FMPSMBUS_ADDRESSING_MODE(MODE) (((MODE) == FMPSMBUS_ADDRESSINGMODE_7BIT) || \ - ((MODE) == FMPSMBUS_ADDRESSINGMODE_10BIT)) - -#define IS_FMPSMBUS_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == FMPSMBUS_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == FMPSMBUS_DUALADDRESS_ENABLE)) - -#define IS_FMPSMBUS_OWN_ADDRESS2_MASK(MASK) (((MASK) == FMPSMBUS_OA2_NOMASK) || \ - ((MASK) == FMPSMBUS_OA2_MASK01) || \ - ((MASK) == FMPSMBUS_OA2_MASK02) || \ - ((MASK) == FMPSMBUS_OA2_MASK03) || \ - ((MASK) == FMPSMBUS_OA2_MASK04) || \ - ((MASK) == FMPSMBUS_OA2_MASK05) || \ - ((MASK) == FMPSMBUS_OA2_MASK06) || \ - ((MASK) == FMPSMBUS_OA2_MASK07)) - -#define IS_FMPSMBUS_GENERAL_CALL(CALL) (((CALL) == FMPSMBUS_GENERALCALL_DISABLE) || \ - ((CALL) == FMPSMBUS_GENERALCALL_ENABLE)) - -#define IS_FMPSMBUS_NO_STRETCH(STRETCH) (((STRETCH) == FMPSMBUS_NOSTRETCH_DISABLE) || \ - ((STRETCH) == FMPSMBUS_NOSTRETCH_ENABLE)) - -#define IS_FMPSMBUS_PEC(PEC) (((PEC) == FMPSMBUS_PEC_DISABLE) || \ - ((PEC) == FMPSMBUS_PEC_ENABLE)) - -#define IS_FMPSMBUS_PERIPHERAL_MODE(MODE) (((MODE) == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_HOST) || \ - ((MODE) == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE) || \ - ((MODE) == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE_ARP)) - -#define IS_FMPSMBUS_TRANSFER_MODE(MODE) (((MODE) == FMPSMBUS_RELOAD_MODE) || \ - ((MODE) == FMPSMBUS_AUTOEND_MODE) || \ - ((MODE) == FMPSMBUS_SOFTEND_MODE) || \ - ((MODE) == FMPSMBUS_SENDPEC_MODE) || \ - ((MODE) == (FMPSMBUS_RELOAD_MODE | FMPSMBUS_SENDPEC_MODE)) || \ - ((MODE) == (FMPSMBUS_AUTOEND_MODE | FMPSMBUS_SENDPEC_MODE)) || \ - ((MODE) == (FMPSMBUS_AUTOEND_MODE | FMPSMBUS_RELOAD_MODE)) || \ - ((MODE) == (FMPSMBUS_AUTOEND_MODE | FMPSMBUS_SENDPEC_MODE | \ - FMPSMBUS_RELOAD_MODE ))) - - -#define IS_FMPSMBUS_TRANSFER_REQUEST(REQUEST) (((REQUEST) == FMPSMBUS_GENERATE_STOP) || \ - ((REQUEST) == FMPSMBUS_GENERATE_START_READ) || \ - ((REQUEST) == FMPSMBUS_GENERATE_START_WRITE) || \ - ((REQUEST) == FMPSMBUS_NO_STARTSTOP)) - - -#define IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(REQUEST) (IS_FMPSMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) || \ - ((REQUEST) == FMPSMBUS_FIRST_FRAME) || \ - ((REQUEST) == FMPSMBUS_NEXT_FRAME) || \ - ((REQUEST) == FMPSMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == FMPSMBUS_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == FMPSMBUS_FIRST_FRAME_WITH_PEC) || \ - ((REQUEST) == FMPSMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || \ - ((REQUEST) == FMPSMBUS_LAST_FRAME_WITH_PEC)) - -#define IS_FMPSMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == FMPSMBUS_OTHER_FRAME_NO_PEC) || \ - ((REQUEST) == FMPSMBUS_OTHER_AND_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == FMPSMBUS_OTHER_FRAME_WITH_PEC) || \ - ((REQUEST) == FMPSMBUS_OTHER_AND_LAST_FRAME_WITH_PEC)) - -#define FMPSMBUS_RESET_CR1(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= \ - (uint32_t)~((uint32_t)(FMPI2C_CR1_SMBHEN | FMPI2C_CR1_SMBDEN | \ - FMPI2C_CR1_PECEN))) -#define FMPSMBUS_RESET_CR2(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= \ - (uint32_t)~((uint32_t)(FMPI2C_CR2_SADD | FMPI2C_CR2_HEAD10R | \ - FMPI2C_CR2_NBYTES | FMPI2C_CR2_RELOAD | \ - FMPI2C_CR2_RD_WRN))) - -#define FMPSMBUS_GENERATE_START(__ADDMODE__,__ADDRESS__) (((__ADDMODE__) == FMPSMBUS_ADDRESSINGMODE_7BIT) ? \ - (uint32_t)((((uint32_t)(__ADDRESS__) & (FMPI2C_CR2_SADD)) | \ - (FMPI2C_CR2_START) | (FMPI2C_CR2_AUTOEND)) & \ - (~FMPI2C_CR2_RD_WRN)) : \ - (uint32_t)((((uint32_t)(__ADDRESS__) & \ - (FMPI2C_CR2_SADD)) | (FMPI2C_CR2_ADD10) | \ - (FMPI2C_CR2_START)) & (~FMPI2C_CR2_RD_WRN))) - -#define FMPSMBUS_GET_ADDR_MATCH(__HANDLE__) (((__HANDLE__)->Instance->ISR & FMPI2C_ISR_ADDCODE) >> 17U) -#define FMPSMBUS_GET_DIR(__HANDLE__) (((__HANDLE__)->Instance->ISR & FMPI2C_ISR_DIR) >> 16U) -#define FMPSMBUS_GET_STOP_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & FMPI2C_CR2_AUTOEND) -#define FMPSMBUS_GET_PEC_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & FMPI2C_CR2_PECBYTE) -#define FMPSMBUS_GET_ALERT_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR1 & FMPI2C_CR1_ALERTEN) - -#define FMPSMBUS_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & FMPSMBUS_FLAG_MASK)) == \ - ((__FLAG__) & FMPSMBUS_FLAG_MASK)) ? SET : RESET) -#define FMPSMBUS_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET) - -#define IS_FMPSMBUS_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x000003FFU) -#define IS_FMPSMBUS_OWN_ADDRESS2(ADDRESS2) ((ADDRESS2) <= (uint16_t)0x00FFU) - -/** - * @} - */ - -/* Include FMPSMBUS HAL Extended module */ -#include "stm32f4xx_hal_fmpsmbus_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPSMBUS_Exported_Functions FMPSMBUS Exported Functions - * @{ - */ - -/** @addtogroup FMPSMBUS_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization and de-initialization functions ****************************/ -HAL_StatusTypeDef HAL_FMPSMBUS_Init(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_DeInit(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_MspInit(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_MspDeInit(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_ConfigAnalogFilter(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_FMPSMBUS_ConfigDigitalFilter(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t DigitalFilter); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_FMPSMBUS_RegisterCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - HAL_FMPSMBUS_CallbackIDTypeDef CallbackID, - pFMPSMBUS_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_FMPSMBUS_UnRegisterCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - HAL_FMPSMBUS_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_FMPSMBUS_RegisterAddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - pFMPSMBUS_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_FMPSMBUS_UnRegisterAddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup FMPSMBUS_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ - -/* IO operation functions *****************************************************/ -/** @addtogroup Blocking_mode_Polling Blocking mode Polling - * @{ - */ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_FMPSMBUS_IsDeviceReady(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint32_t Trials, - uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup Non-Blocking_mode_Interrupt Non-Blocking mode Interrupt - * @{ - */ -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Transmit_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, - uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Receive_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, - uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Abort_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress); -HAL_StatusTypeDef HAL_FMPSMBUS_Slave_Transmit_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPSMBUS_Slave_Receive_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); - -HAL_StatusTypeDef HAL_FMPSMBUS_EnableAlert_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_DisableAlert_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_EnableListen_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_DisableListen_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus); -/** - * @} - */ - -/** @addtogroup FMPSMBUS_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* FMPSMBUS IRQHandler and Callbacks used in non blocking modes (Interrupt) */ -void HAL_FMPSMBUS_EV_IRQHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_ER_IRQHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_MasterTxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_MasterRxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_SlaveTxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_SlaveRxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_AddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_FMPSMBUS_ListenCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_ErrorCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); - -/** - * @} - */ - -/** @addtogroup FMPSMBUS_Exported_Functions_Group3 Peripheral State and Errors functions - * @{ - */ - -/* Peripheral State and Errors functions **************************************************/ -uint32_t HAL_FMPSMBUS_GetState(FMPSMBUS_HandleTypeDef *hfmpsmbus); -uint32_t HAL_FMPSMBUS_GetError(FMPSMBUS_HandleTypeDef *hfmpsmbus); - -/** - * @} - */ - -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Private_Functions FMPSMBUS Private Functions - * @{ - */ -/* Private functions are defined in stm32f4xx_hal_fmpsmbus.c file */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_FMPSMBUS_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus_ex.h deleted file mode 100644 index d5439e7ce8aee0a..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus_ex.h +++ /dev/null @@ -1,139 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpsmbus_ex.h - * @author MCD Application Team - * @brief Header file of FMPSMBUS HAL Extended module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_FMPSMBUS_EX_H -#define STM32F4xx_HAL_FMPSMBUS_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMPSMBUSEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Exported_Constants FMPSMBUS Extended Exported Constants - * @{ - */ - -/** @defgroup FMPSMBUSEx_FastModePlus FMPSMBUS Extended Fast Mode Plus - * @{ - */ -#define FMPSMBUS_FASTMODEPLUS_SCL SYSCFG_CFGR_FMPI2C1_SCL /*!< Enable Fast Mode Plus on FMPI2C1 SCL pins */ -#define FMPSMBUS_FASTMODEPLUS_SDA SYSCFG_CFGR_FMPI2C1_SDA /*!< Enable Fast Mode Plus on FMPI2C1 SDA pins */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Exported_Macros FMPSMBUS Extended Exported Macros - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPSMBUSEx_Exported_Functions FMPSMBUS Extended Exported Functions - * @{ - */ - -/** @addtogroup FMPSMBUSEx_Exported_Functions_Group2 WakeUp Mode Functions - * @{ - */ -/* Peripheral Control functions ************************************************/ -/** - * @} - */ - -/** @addtogroup FMPSMBUSEx_Exported_Functions_Group3 Fast Mode Plus Functions - * @{ - */ -void HAL_FMPSMBUSEx_EnableFastModePlus(uint32_t ConfigFastModePlus); -void HAL_FMPSMBUSEx_DisableFastModePlus(uint32_t ConfigFastModePlus); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Private_Constants FMPSMBUS Extended Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Private_Macro FMPSMBUS Extended Private Macros - * @{ - */ -#define IS_FMPSMBUS_FASTMODEPLUS(__CONFIG__) ((((__CONFIG__) & (FMPSMBUS_FASTMODEPLUS_SCL)) == \ - FMPSMBUS_FASTMODEPLUS_SCL) || \ - (((__CONFIG__) & (FMPSMBUS_FASTMODEPLUS_SDA)) == \ - FMPSMBUS_FASTMODEPLUS_SDA)) -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Private_Functions FMPSMBUS Extended Private Functions - * @{ - */ -/* Private functions are defined in stm32f4xx_hal_fmpsmbus_ex.c file */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_FMPSMBUS_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h deleted file mode 100644 index cacfdee235c5360..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h +++ /dev/null @@ -1,327 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio.h - * @author MCD Application Team - * @brief Header file of GPIO HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_GPIO_H -#define __STM32F4xx_HAL_GPIO_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup GPIO - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup GPIO_Exported_Types GPIO Exported Types - * @{ - */ - -/** - * @brief GPIO Init structure definition - */ -typedef struct -{ - uint32_t Pin; /*!< Specifies the GPIO pins to be configured. - This parameter can be any value of @ref GPIO_pins_define */ - - uint32_t Mode; /*!< Specifies the operating mode for the selected pins. - This parameter can be a value of @ref GPIO_mode_define */ - - uint32_t Pull; /*!< Specifies the Pull-up or Pull-Down activation for the selected pins. - This parameter can be a value of @ref GPIO_pull_define */ - - uint32_t Speed; /*!< Specifies the speed for the selected pins. - This parameter can be a value of @ref GPIO_speed_define */ - - uint32_t Alternate; /*!< Peripheral to be connected to the selected pins. - This parameter can be a value of @ref GPIO_Alternate_function_selection */ -}GPIO_InitTypeDef; - -/** - * @brief GPIO Bit SET and Bit RESET enumeration - */ -typedef enum -{ - GPIO_PIN_RESET = 0, - GPIO_PIN_SET -}GPIO_PinState; -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup GPIO_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_pins_define GPIO pins define - * @{ - */ -#define GPIO_PIN_0 ((uint16_t)0x0001) /* Pin 0 selected */ -#define GPIO_PIN_1 ((uint16_t)0x0002) /* Pin 1 selected */ -#define GPIO_PIN_2 ((uint16_t)0x0004) /* Pin 2 selected */ -#define GPIO_PIN_3 ((uint16_t)0x0008) /* Pin 3 selected */ -#define GPIO_PIN_4 ((uint16_t)0x0010) /* Pin 4 selected */ -#define GPIO_PIN_5 ((uint16_t)0x0020) /* Pin 5 selected */ -#define GPIO_PIN_6 ((uint16_t)0x0040) /* Pin 6 selected */ -#define GPIO_PIN_7 ((uint16_t)0x0080) /* Pin 7 selected */ -#define GPIO_PIN_8 ((uint16_t)0x0100) /* Pin 8 selected */ -#define GPIO_PIN_9 ((uint16_t)0x0200) /* Pin 9 selected */ -#define GPIO_PIN_10 ((uint16_t)0x0400) /* Pin 10 selected */ -#define GPIO_PIN_11 ((uint16_t)0x0800) /* Pin 11 selected */ -#define GPIO_PIN_12 ((uint16_t)0x1000) /* Pin 12 selected */ -#define GPIO_PIN_13 ((uint16_t)0x2000) /* Pin 13 selected */ -#define GPIO_PIN_14 ((uint16_t)0x4000) /* Pin 14 selected */ -#define GPIO_PIN_15 ((uint16_t)0x8000) /* Pin 15 selected */ -#define GPIO_PIN_All ((uint16_t)0xFFFF) /* All pins selected */ - -#define GPIO_PIN_MASK 0x0000FFFFU /* PIN mask for assert test */ -/** - * @} - */ - -/** @defgroup GPIO_mode_define GPIO mode define - * @brief GPIO Configuration Mode - * Elements values convention: 0x00WX00YZ - * - W : EXTI trigger detection on 3 bits - * - X : EXTI mode (IT or Event) on 2 bits - * - Y : Output type (Push Pull or Open Drain) on 1 bit - * - Z : GPIO mode (Input, Output, Alternate or Analog) on 2 bits - * @{ - */ -#define GPIO_MODE_INPUT MODE_INPUT /*!< Input Floating Mode */ -#define GPIO_MODE_OUTPUT_PP (MODE_OUTPUT | OUTPUT_PP) /*!< Output Push Pull Mode */ -#define GPIO_MODE_OUTPUT_OD (MODE_OUTPUT | OUTPUT_OD) /*!< Output Open Drain Mode */ -#define GPIO_MODE_AF_PP (MODE_AF | OUTPUT_PP) /*!< Alternate Function Push Pull Mode */ -#define GPIO_MODE_AF_OD (MODE_AF | OUTPUT_OD) /*!< Alternate Function Open Drain Mode */ - -#define GPIO_MODE_ANALOG MODE_ANALOG /*!< Analog Mode */ - -#define GPIO_MODE_IT_RISING (MODE_INPUT | EXTI_IT | TRIGGER_RISING) /*!< External Interrupt Mode with Rising edge trigger detection */ -#define GPIO_MODE_IT_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_FALLING) /*!< External Interrupt Mode with Falling edge trigger detection */ -#define GPIO_MODE_IT_RISING_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */ - -#define GPIO_MODE_EVT_RISING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING) /*!< External Event Mode with Rising edge trigger detection */ -#define GPIO_MODE_EVT_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_FALLING) /*!< External Event Mode with Falling edge trigger detection */ -#define GPIO_MODE_EVT_RISING_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Event Mode with Rising/Falling edge trigger detection */ - -/** - * @} - */ - -/** @defgroup GPIO_speed_define GPIO speed define - * @brief GPIO Output Maximum frequency - * @{ - */ -#define GPIO_SPEED_FREQ_LOW 0x00000000U /*!< IO works at 2 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_MEDIUM 0x00000001U /*!< range 12,5 MHz to 50 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_HIGH 0x00000002U /*!< range 25 MHz to 100 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_VERY_HIGH 0x00000003U /*!< range 50 MHz to 200 MHz, please refer to the product datasheet */ -/** - * @} - */ - - /** @defgroup GPIO_pull_define GPIO pull define - * @brief GPIO Pull-Up or Pull-Down Activation - * @{ - */ -#define GPIO_NOPULL 0x00000000U /*!< No Pull-up or Pull-down activation */ -#define GPIO_PULLUP 0x00000001U /*!< Pull-up activation */ -#define GPIO_PULLDOWN 0x00000002U /*!< Pull-down activation */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIO_Exported_Macros GPIO Exported Macros - * @{ - */ - -/** - * @brief Checks whether the specified EXTI line flag is set or not. - * @param __EXTI_LINE__ specifies the EXTI line flag to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval The new state of __EXTI_LINE__ (SET or RESET). - */ -#define __HAL_GPIO_EXTI_GET_FLAG(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__)) - -/** - * @brief Clears the EXTI's line pending flags. - * @param __EXTI_LINE__ specifies the EXTI lines flags to clear. - * This parameter can be any combination of GPIO_PIN_x where x can be (0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_CLEAR_FLAG(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__)) - -/** - * @brief Checks whether the specified EXTI line is asserted or not. - * @param __EXTI_LINE__ specifies the EXTI line to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval The new state of __EXTI_LINE__ (SET or RESET). - */ -#define __HAL_GPIO_EXTI_GET_IT(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__)) - -/** - * @brief Clears the EXTI's line pending bits. - * @param __EXTI_LINE__ specifies the EXTI lines to clear. - * This parameter can be any combination of GPIO_PIN_x where x can be (0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_CLEAR_IT(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__)) - -/** - * @brief Generates a Software interrupt on selected EXTI line. - * @param __EXTI_LINE__ specifies the EXTI line to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__)) -/** - * @} - */ - -/* Include GPIO HAL Extension module */ -#include "stm32f4xx_hal_gpio_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup GPIO_Exported_Functions - * @{ - */ - -/** @addtogroup GPIO_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init); -void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin); -/** - * @} - */ - -/** @addtogroup GPIO_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState); -void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin); -void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIO_Private_Constants GPIO Private Constants - * @{ - */ -#define GPIO_MODE_Pos 0U -#define GPIO_MODE (0x3UL << GPIO_MODE_Pos) -#define MODE_INPUT (0x0UL << GPIO_MODE_Pos) -#define MODE_OUTPUT (0x1UL << GPIO_MODE_Pos) -#define MODE_AF (0x2UL << GPIO_MODE_Pos) -#define MODE_ANALOG (0x3UL << GPIO_MODE_Pos) -#define OUTPUT_TYPE_Pos 4U -#define OUTPUT_TYPE (0x1UL << OUTPUT_TYPE_Pos) -#define OUTPUT_PP (0x0UL << OUTPUT_TYPE_Pos) -#define OUTPUT_OD (0x1UL << OUTPUT_TYPE_Pos) -#define EXTI_MODE_Pos 16U -#define EXTI_MODE (0x3UL << EXTI_MODE_Pos) -#define EXTI_IT (0x1UL << EXTI_MODE_Pos) -#define EXTI_EVT (0x2UL << EXTI_MODE_Pos) -#define TRIGGER_MODE_Pos 20U -#define TRIGGER_MODE (0x7UL << TRIGGER_MODE_Pos) -#define TRIGGER_RISING (0x1UL << TRIGGER_MODE_Pos) -#define TRIGGER_FALLING (0x2UL << TRIGGER_MODE_Pos) - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIO_Private_Macros GPIO Private Macros - * @{ - */ -#define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET)) -#define IS_GPIO_PIN(PIN) (((((uint32_t)PIN) & GPIO_PIN_MASK ) != 0x00U) && ((((uint32_t)PIN) & ~GPIO_PIN_MASK) == 0x00U)) -#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_MODE_INPUT) ||\ - ((MODE) == GPIO_MODE_OUTPUT_PP) ||\ - ((MODE) == GPIO_MODE_OUTPUT_OD) ||\ - ((MODE) == GPIO_MODE_AF_PP) ||\ - ((MODE) == GPIO_MODE_AF_OD) ||\ - ((MODE) == GPIO_MODE_IT_RISING) ||\ - ((MODE) == GPIO_MODE_IT_FALLING) ||\ - ((MODE) == GPIO_MODE_IT_RISING_FALLING) ||\ - ((MODE) == GPIO_MODE_EVT_RISING) ||\ - ((MODE) == GPIO_MODE_EVT_FALLING) ||\ - ((MODE) == GPIO_MODE_EVT_RISING_FALLING) ||\ - ((MODE) == GPIO_MODE_ANALOG)) -#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_SPEED_FREQ_LOW) || ((SPEED) == GPIO_SPEED_FREQ_MEDIUM) || \ - ((SPEED) == GPIO_SPEED_FREQ_HIGH) || ((SPEED) == GPIO_SPEED_FREQ_VERY_HIGH)) -#define IS_GPIO_PULL(PULL) (((PULL) == GPIO_NOPULL) || ((PULL) == GPIO_PULLUP) || \ - ((PULL) == GPIO_PULLDOWN)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIO_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_GPIO_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h deleted file mode 100644 index 7db36ccaecf591c..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h +++ /dev/null @@ -1,1592 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio_ex.h - * @author MCD Application Team - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_GPIO_EX_H -#define __STM32F4xx_HAL_GPIO_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection - * @{ - */ - -/*------------------------------------------ STM32F429xx/STM32F439xx ---------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -/** @brief GPIO_Legacy - */ -#define GPIO_AF5_I2S3ext GPIO_AF5_SPI3 /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ - - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-------------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM1 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0A) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FMC ((uint8_t)0x0A) /* FMC Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F413xx/STM32F423xx-------------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_DFSDM2 ((uint8_t)0x03) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF6_DFSDM2 ((uint8_t)0x06) /* DFSDM2 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SAI1 ((uint8_t)0x07) /* SAI1 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ -#define GPIO_AF7_DFSDM2 ((uint8_t)0x07) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_SAI1 ((uint8_t)0x0A) /* SAI1 Alternate Function mapping */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0A) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_DFSDM2 ((uint8_t)0x0A) /* DFSDM2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FSMC ((uint8_t)0x0A) /* FSMC Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_UART4 ((uint8_t)0x0B) /* UART4 Alternate Function mapping */ -#define GPIO_AF11_UART5 ((uint8_t)0x0B) /* UART5 Alternate Function mapping */ -#define GPIO_AF11_UART9 ((uint8_t)0x0B) /* UART9 Alternate Function mapping */ -#define GPIO_AF11_UART10 ((uint8_t)0x0B) /* UART10 Alternate Function mapping */ -#define GPIO_AF11_CAN3 ((uint8_t)0x0B) /* CAN3 Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_RNG ((uint8_t)0x0E) /* RNG Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F413xx || STM32F423xx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F411xE */ - -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI1 ((uint8_t)0x06) /* SPI1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F446xx -----------------------*/ -#if defined(STM32F446xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_CEC ((uint8_t)0x03) /* CEC Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4 Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_UART5 ((uint8_t)0x07) /* UART5 Alternate Function mapping */ -#define GPIO_AF7_SPI2 ((uint8_t)0x07) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SPDIFRX ((uint8_t)0x07) /* SPDIFRX Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_SPDIFRX ((uint8_t)0x08) /* SPDIFRX Alternate Function mapping */ -#define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F469xx/STM32F479xx--------------------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LCD-TFT Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ -#define GPIO_AF13_DSI ((uint8_t)0x0D) /* DSI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ -/** - * @} - */ - -/** - * @} - */ - -/* 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 - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#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 : 8U) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#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 :\ - ((__GPIOx__) == (GPIOJ))? 9U : 10U) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U : 7U) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U : 7U) -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#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 : 7U) -#endif /* STM32F446xx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U : 7U) -#endif /* STM32F412Vx */ -#if defined(STM32F412Rx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U : 7U) -#endif /* STM32F412Rx */ -#if defined(STM32F412Cx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U : 7U) -#endif /* STM32F412Cx */ - -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -/*------------------------- STM32F429xx/STM32F439xx---------------------------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -#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_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC)) - -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -#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_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1)) - -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -#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)) - -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -#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 /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF12_SDIO) || \ - ((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_TIM9) || \ - ((AF) == GPIO_AF3_TIM10) || ((AF) == GPIO_AF3_TIM11) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF7_USART1) || \ - ((AF) == GPIO_AF7_USART2) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF15_EVENTOUT)) -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_GPIO_AF(AF) (((AF) < 10U) || ((AF) == 15U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -#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_AF4_I2C1) || \ - ((AF) == GPIO_AF4_I2C2) || ((AF) == GPIO_AF4_I2C3) || \ - ((AF) == GPIO_AF5_SPI1) || ((AF) == GPIO_AF5_SPI2) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI4) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF6_SPI5) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF8_USART6) || ((AF) == GPIO_AF10_OTG_FS) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F411xE */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------------------------- STM32F446xx ----------------*/ -#if defined(STM32F446xx) -#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_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF3_CEC) || ((AF) == GPIO_AF4_CEC) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI2) || \ - ((AF) == GPIO_AF6_SPI4) || ((AF) == GPIO_AF7_UART5) || \ - ((AF) == GPIO_AF7_SPI2) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_SPDIFRX) || ((AF) == GPIO_AF8_SPDIFRX) || \ - ((AF) == GPIO_AF8_SAI2) || ((AF) == GPIO_AF9_QSPI) || \ - ((AF) == GPIO_AF10_SAI2) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------------------- STM32F469xx/STM32F479xx --------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -#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_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC) || ((AF) == GPIO_AF13_DSI) || \ - ((AF) == GPIO_AF9_QSPI) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-----------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 11U) && ((AF) != 14U) && ((AF) != 13U)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F413xx/STM32F423xx-----------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 13U)) -#endif /* STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_GPIO_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash.h deleted file mode 100644 index 3b73282edf795a2..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash.h +++ /dev/null @@ -1,636 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hash.h - * @author MCD Application Team - * @brief Header file of HASH HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_HASH_H -#define STM32F4xx_HAL_HASH_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (HASH) -/** @addtogroup HASH - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup HASH_Exported_Types HASH Exported Types - * @{ - */ - -/** - * @brief HASH Configuration Structure definition - */ -typedef struct -{ - uint32_t DataType; /*!< 32-bit data, 16-bit data, 8-bit data or 1-bit data. - This parameter can be a value of @ref HASH_Data_Type. */ - - uint32_t KeySize; /*!< The key size is used only in HMAC operation. */ - - uint8_t *pKey; /*!< The key is used only in HMAC operation. */ - -} HASH_InitTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_HASH_STATE_RESET = 0x00U, /*!< Peripheral is not initialized */ - HAL_HASH_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_HASH_STATE_BUSY = 0x02U, /*!< Processing (hashing) is ongoing */ - HAL_HASH_STATE_TIMEOUT = 0x06U, /*!< Timeout state */ - HAL_HASH_STATE_ERROR = 0x07U, /*!< Error state */ - HAL_HASH_STATE_SUSPENDED = 0x08U /*!< Suspended state */ -} HAL_HASH_StateTypeDef; - -/** - * @brief HAL phase structures definition - */ -typedef enum -{ - HAL_HASH_PHASE_READY = 0x01U, /*!< HASH peripheral is ready to start */ - HAL_HASH_PHASE_PROCESS = 0x02U, /*!< HASH peripheral is in HASH processing phase */ - HAL_HASH_PHASE_HMAC_STEP_1 = 0x03U, /*!< HASH peripheral is in HMAC step 1 processing phase - (step 1 consists in entering the inner hash function key) */ - HAL_HASH_PHASE_HMAC_STEP_2 = 0x04U, /*!< HASH peripheral is in HMAC step 2 processing phase - (step 2 consists in entering the message text) */ - HAL_HASH_PHASE_HMAC_STEP_3 = 0x05U /*!< HASH peripheral is in HMAC step 3 processing phase - (step 3 consists in entering the outer hash function key) */ -} HAL_HASH_PhaseTypeDef; - -/** - * @brief HAL HASH mode suspend definitions - */ -typedef enum -{ - HAL_HASH_SUSPEND_NONE = 0x00U, /*!< HASH peripheral suspension not requested */ - HAL_HASH_SUSPEND = 0x01U /*!< HASH peripheral suspension is requested */ -} HAL_HASH_SuspendTypeDef; - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL HASH common Callback ID enumeration definition - */ -typedef enum -{ - HAL_HASH_MSPINIT_CB_ID = 0x00U, /*!< HASH MspInit callback ID */ - HAL_HASH_MSPDEINIT_CB_ID = 0x01U, /*!< HASH MspDeInit callback ID */ - HAL_HASH_INPUTCPLT_CB_ID = 0x02U, /*!< HASH input completion callback ID */ - HAL_HASH_DGSTCPLT_CB_ID = 0x03U, /*!< HASH digest computation completion callback ID */ - HAL_HASH_ERROR_CB_ID = 0x04U, /*!< HASH error callback ID */ -} HAL_HASH_CallbackIDTypeDef; -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - -/** - * @brief HASH Handle Structure definition - */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) -typedef struct __HASH_HandleTypeDef -#else -typedef struct -#endif /* (USE_HAL_HASH_REGISTER_CALLBACKS) */ -{ - HASH_InitTypeDef Init; /*!< HASH required parameters */ - - uint8_t *pHashInBuffPtr; /*!< Pointer to input buffer */ - - uint8_t *pHashOutBuffPtr; /*!< Pointer to output buffer (digest) */ - - uint8_t *pHashKeyBuffPtr; /*!< Pointer to key buffer (HMAC only) */ - - uint8_t *pHashMsgBuffPtr; /*!< Pointer to message buffer (HMAC only) */ - - uint32_t HashBuffSize; /*!< Size of buffer to be processed */ - - __IO uint32_t HashInCount; /*!< Counter of inputted data */ - - __IO uint32_t HashITCounter; /*!< Counter of issued interrupts */ - - __IO uint32_t HashKeyCount; /*!< Counter for Key inputted data (HMAC only) */ - - HAL_StatusTypeDef Status; /*!< HASH peripheral status */ - - HAL_HASH_PhaseTypeDef Phase; /*!< HASH peripheral phase */ - - DMA_HandleTypeDef *hdmain; /*!< HASH In DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_HASH_StateTypeDef State; /*!< HASH peripheral state */ - - HAL_HASH_SuspendTypeDef SuspendRequest; /*!< HASH peripheral suspension request flag */ - - FlagStatus DigestCalculationDisable; /*!< Digest calculation phase skip (MDMAT bit control) for multi-buffers DMA-based HMAC computation */ - - __IO uint32_t NbWordsAlreadyPushed; /*!< Numbers of words already pushed in FIFO before inputting new block */ - - __IO uint32_t ErrorCode; /*!< HASH Error code */ - - __IO uint32_t Accumulation; /*!< HASH multi buffers accumulation flag */ - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - void (* InCpltCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH input completion callback */ - - void (* DgstCpltCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH digest computation completion callback */ - - void (* ErrorCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH error callback */ - - void (* MspInitCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH Msp Init callback */ - - void (* MspDeInitCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH Msp DeInit callback */ - -#endif /* (USE_HAL_HASH_REGISTER_CALLBACKS) */ -} HASH_HandleTypeDef; - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL HASH Callback pointer definition - */ -typedef void (*pHASH_CallbackTypeDef)(HASH_HandleTypeDef *hhash); /*!< pointer to a HASH common callback functions */ -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup HASH_Exported_Constants HASH Exported Constants - * @{ - */ - -/** @defgroup HASH_Algo_Selection HASH algorithm selection - * @{ - */ -#define HASH_ALGOSELECTION_SHA1 0x00000000U /*!< HASH function is SHA1 */ -#define HASH_ALGOSELECTION_MD5 HASH_CR_ALGO_0 /*!< HASH function is MD5 */ -#define HASH_ALGOSELECTION_SHA224 HASH_CR_ALGO_1 /*!< HASH function is SHA224 */ -#define HASH_ALGOSELECTION_SHA256 HASH_CR_ALGO /*!< HASH function is SHA256 */ -/** - * @} - */ - -/** @defgroup HASH_Algorithm_Mode HASH algorithm mode - * @{ - */ -#define HASH_ALGOMODE_HASH 0x00000000U /*!< Algorithm is HASH */ -#define HASH_ALGOMODE_HMAC HASH_CR_MODE /*!< Algorithm is HMAC */ -/** - * @} - */ - -/** @defgroup HASH_Data_Type HASH input data type - * @{ - */ -#define HASH_DATATYPE_32B 0x00000000U /*!< 32-bit data. No swapping */ -#define HASH_DATATYPE_16B HASH_CR_DATATYPE_0 /*!< 16-bit data. Each half word is swapped */ -#define HASH_DATATYPE_8B HASH_CR_DATATYPE_1 /*!< 8-bit data. All bytes are swapped */ -#define HASH_DATATYPE_1B HASH_CR_DATATYPE /*!< 1-bit data. In the word all bits are swapped */ -/** - * @} - */ - -/** @defgroup HASH_HMAC_Long_key_only_for_HMAC_mode HMAC key length type - * @{ - */ -#define HASH_HMAC_KEYTYPE_SHORTKEY 0x00000000U /*!< HMAC Key size is <= 64 bytes */ -#define HASH_HMAC_KEYTYPE_LONGKEY HASH_CR_LKEY /*!< HMAC Key size is > 64 bytes */ -/** - * @} - */ - -/** @defgroup HASH_flags_definition HASH flags definitions - * @{ - */ -#define HASH_FLAG_DINIS HASH_SR_DINIS /*!< 16 locations are free in the DIN : a new block can be entered in the Peripheral */ -#define HASH_FLAG_DCIS HASH_SR_DCIS /*!< Digest calculation complete */ -#define HASH_FLAG_DMAS HASH_SR_DMAS /*!< DMA interface is enabled (DMAE=1) or a transfer is ongoing */ -#define HASH_FLAG_BUSY HASH_SR_BUSY /*!< The hash core is Busy, processing a block of data */ -#define HASH_FLAG_DINNE HASH_CR_DINNE /*!< DIN not empty : the input buffer contains at least one word of data */ - -/** - * @} - */ - -/** @defgroup HASH_interrupts_definition HASH interrupts definitions - * @{ - */ -#define HASH_IT_DINI HASH_IMR_DINIE /*!< A new block can be entered into the input buffer (DIN) */ -#define HASH_IT_DCI HASH_IMR_DCIE /*!< Digest calculation complete */ - -/** - * @} - */ - -/** @defgroup HASH_Error_Definition HASH Error Definition - * @{ - */ -#define HAL_HASH_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_HASH_ERROR_IT 0x00000001U /*!< IT-based process error */ -#define HAL_HASH_ERROR_DMA 0x00000002U /*!< DMA-based process error */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1U) -#define HAL_HASH_ERROR_INVALID_CALLBACK 0x00000004U /*!< Invalid Callback error */ -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup HASH_Exported_Macros HASH Exported Macros - * @{ - */ - -/** @brief Check whether or not the specified HASH flag is set. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg @ref HASH_FLAG_DINIS A new block can be entered into the input buffer. - * @arg @ref HASH_FLAG_DCIS Digest calculation complete. - * @arg @ref HASH_FLAG_DMAS DMA interface is enabled (DMAE=1) or a transfer is ongoing. - * @arg @ref HASH_FLAG_BUSY The hash core is Busy : processing a block of data. - * @arg @ref HASH_FLAG_DINNE DIN not empty : the input buffer contains at least one word of data. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_HASH_GET_FLAG(__FLAG__) (((__FLAG__) > 8U) ? \ - ((HASH->CR & (__FLAG__)) == (__FLAG__)) :\ - ((HASH->SR & (__FLAG__)) == (__FLAG__)) ) - - -/** @brief Clear the specified HASH flag. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be one of the following values: - * @arg @ref HASH_FLAG_DINIS A new block can be entered into the input buffer. - * @arg @ref HASH_FLAG_DCIS Digest calculation complete - * @retval None - */ -#define __HAL_HASH_CLEAR_FLAG(__FLAG__) CLEAR_BIT(HASH->SR, (__FLAG__)) - - -/** @brief Enable the specified HASH interrupt. - * @param __INTERRUPT__ specifies the HASH interrupt source to enable. - * This parameter can be one of the following values: - * @arg @ref HASH_IT_DINI A new block can be entered into the input buffer (DIN) - * @arg @ref HASH_IT_DCI Digest calculation complete - * @retval None - */ -#define __HAL_HASH_ENABLE_IT(__INTERRUPT__) SET_BIT(HASH->IMR, (__INTERRUPT__)) - -/** @brief Disable the specified HASH interrupt. - * @param __INTERRUPT__ specifies the HASH interrupt source to disable. - * This parameter can be one of the following values: - * @arg @ref HASH_IT_DINI A new block can be entered into the input buffer (DIN) - * @arg @ref HASH_IT_DCI Digest calculation complete - * @retval None - */ -#define __HAL_HASH_DISABLE_IT(__INTERRUPT__) CLEAR_BIT(HASH->IMR, (__INTERRUPT__)) - -/** @brief Reset HASH handle state. - * @param __HANDLE__ HASH handle. - * @retval None - */ - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) -#define __HAL_HASH_RESET_HANDLE_STATE(__HANDLE__) do{\ - (__HANDLE__)->State = HAL_HASH_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - }while(0) -#else -#define __HAL_HASH_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_HASH_STATE_RESET) -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - -/** @brief Reset HASH handle status. - * @param __HANDLE__ HASH handle. - * @retval None - */ -#define __HAL_HASH_RESET_HANDLE_STATUS(__HANDLE__) ((__HANDLE__)->Status = HAL_OK) - -/** - * @brief Enable the multi-buffer DMA transfer mode. - * @note This bit is set when hashing large files when multiple DMA transfers are needed. - * @retval None - */ -#define __HAL_HASH_SET_MDMAT() SET_BIT(HASH->CR, HASH_CR_MDMAT) - -/** - * @brief Disable the multi-buffer DMA transfer mode. - * @retval None - */ -#define __HAL_HASH_RESET_MDMAT() CLEAR_BIT(HASH->CR, HASH_CR_MDMAT) - - -/** - * @brief Start the digest computation. - * @retval None - */ -#define __HAL_HASH_START_DIGEST() SET_BIT(HASH->STR, HASH_STR_DCAL) - -/** - * @brief Set the number of valid bits in the last word written in data register DIN. - * @param __SIZE__ size in bytes of last data written in Data register. - * @retval None - */ -#define __HAL_HASH_SET_NBVALIDBITS(__SIZE__) MODIFY_REG(HASH->STR, HASH_STR_NBLW, 8U * ((__SIZE__) % 4U)) - -/** - * @brief Reset the HASH core. - * @retval None - */ -#define __HAL_HASH_INIT() SET_BIT(HASH->CR, HASH_CR_INIT) - -/** - * @} - */ - - -/* Private macros --------------------------------------------------------*/ -/** @defgroup HASH_Private_Macros HASH Private Macros - * @{ - */ -/** - * @brief Return digest length in bytes. - * @retval Digest length - */ -#if defined(HASH_CR_MDMAT) -#define HASH_DIGEST_LENGTH() ((READ_BIT(HASH->CR, HASH_CR_ALGO) == HASH_ALGOSELECTION_SHA1) ? 20U : \ - ((READ_BIT(HASH->CR, HASH_CR_ALGO) == HASH_ALGOSELECTION_SHA224) ? 28U : \ - ((READ_BIT(HASH->CR, HASH_CR_ALGO) == HASH_ALGOSELECTION_SHA256) ? 32U : 16U ) ) ) -#else -#define HASH_DIGEST_LENGTH() ((READ_BIT(HASH->CR, HASH_CR_ALGO) == HASH_ALGOSELECTION_SHA1) ? 20U : 16) -#endif /* HASH_CR_MDMAT*/ -/** - * @brief Return number of words already pushed in the FIFO. - * @retval Number of words already pushed in the FIFO - */ -#define HASH_NBW_PUSHED() ((READ_BIT(HASH->CR, HASH_CR_NBW)) >> 8U) - -/** - * @brief Ensure that HASH input data type is valid. - * @param __DATATYPE__ HASH input data type. - * @retval SET (__DATATYPE__ is valid) or RESET (__DATATYPE__ is invalid) - */ -#define IS_HASH_DATATYPE(__DATATYPE__) (((__DATATYPE__) == HASH_DATATYPE_32B)|| \ - ((__DATATYPE__) == HASH_DATATYPE_16B)|| \ - ((__DATATYPE__) == HASH_DATATYPE_8B) || \ - ((__DATATYPE__) == HASH_DATATYPE_1B)) - -/** - * @brief Ensure that input data buffer size is valid for multi-buffer HASH - * processing in DMA mode. - * @note This check is valid only for multi-buffer HASH processing in DMA mode. - * @param __SIZE__ input data buffer size. - * @retval SET (__SIZE__ is valid) or RESET (__SIZE__ is invalid) - */ -#define IS_HASH_DMA_MULTIBUFFER_SIZE(__SIZE__) ((READ_BIT(HASH->CR, HASH_CR_MDMAT) == 0U) || (((__SIZE__) % 4U) == 0U)) - -/** - * @brief Ensure that input data buffer size is valid for multi-buffer HMAC - * processing in DMA mode. - * @note This check is valid only for multi-buffer HMAC processing in DMA mode. - * @param __HANDLE__ HASH handle. - * @param __SIZE__ input data buffer size. - * @retval SET (__SIZE__ is valid) or RESET (__SIZE__ is invalid) - */ -#define IS_HMAC_DMA_MULTIBUFFER_SIZE(__HANDLE__,__SIZE__) ((((__HANDLE__)->DigestCalculationDisable) == RESET)\ - || (((__SIZE__) % 4U) == 0U)) -/** - * @brief Ensure that handle phase is set to HASH processing. - * @param __HANDLE__ HASH handle. - * @retval SET (handle phase is set to HASH processing) or RESET (handle phase is not set to HASH processing) - */ -#define IS_HASH_PROCESSING(__HANDLE__) ((__HANDLE__)->Phase == HAL_HASH_PHASE_PROCESS) - -/** - * @brief Ensure that handle phase is set to HMAC processing. - * @param __HANDLE__ HASH handle. - * @retval SET (handle phase is set to HMAC processing) or RESET (handle phase is not set to HMAC processing) - */ -#define IS_HMAC_PROCESSING(__HANDLE__) (((__HANDLE__)->Phase == HAL_HASH_PHASE_HMAC_STEP_1) || \ - ((__HANDLE__)->Phase == HAL_HASH_PHASE_HMAC_STEP_2) || \ - ((__HANDLE__)->Phase == HAL_HASH_PHASE_HMAC_STEP_3)) - -/** - * @} - */ - -/* Include HASH HAL Extended module */ -#include "stm32f4xx_hal_hash_ex.h" -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup HASH_Exported_Functions HASH Exported Functions - * @{ - */ - -/** @addtogroup HASH_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization methods **********************************/ -HAL_StatusTypeDef HAL_HASH_Init(HASH_HandleTypeDef *hhash); -HAL_StatusTypeDef HAL_HASH_DeInit(HASH_HandleTypeDef *hhash); -void HAL_HASH_MspInit(HASH_HandleTypeDef *hhash); -void HAL_HASH_MspDeInit(HASH_HandleTypeDef *hhash); -void HAL_HASH_InCpltCallback(HASH_HandleTypeDef *hhash); -void HAL_HASH_DgstCpltCallback(HASH_HandleTypeDef *hhash); -void HAL_HASH_ErrorCallback(HASH_HandleTypeDef *hhash); -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_HASH_RegisterCallback(HASH_HandleTypeDef *hhash, HAL_HASH_CallbackIDTypeDef CallbackID, - pHASH_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_HASH_UnRegisterCallback(HASH_HandleTypeDef *hhash, HAL_HASH_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group2 HASH processing functions in polling mode - * @{ - */ - - -/* HASH processing using polling *********************************************/ -HAL_StatusTypeDef HAL_HASH_SHA1_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout); -HAL_StatusTypeDef HAL_HASH_MD5_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout); -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); - - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group3 HASH processing functions in interrupt mode - * @{ - */ - -/* HASH processing using IT **************************************************/ -HAL_StatusTypeDef HAL_HASH_SHA1_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASH_MD5_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -void HAL_HASH_IRQHandler(HASH_HandleTypeDef *hhash); -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group4 HASH processing functions in DMA mode - * @{ - */ - -/* HASH processing using DMA *************************************************/ -HAL_StatusTypeDef HAL_HASH_SHA1_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_SHA1_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASH_MD5_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_MD5_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group5 HMAC processing functions in polling mode - * @{ - */ - -/* HASH-MAC processing using polling *****************************************/ -HAL_StatusTypeDef HAL_HMAC_SHA1_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout); -HAL_StatusTypeDef HAL_HMAC_MD5_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group6 HMAC processing functions in interrupt mode - * @{ - */ - -HAL_StatusTypeDef HAL_HMAC_MD5_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HMAC_SHA1_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group7 HMAC processing functions in DMA mode - * @{ - */ - -/* HASH-HMAC processing using DMA ********************************************/ -HAL_StatusTypeDef HAL_HMAC_SHA1_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMAC_MD5_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group8 Peripheral states functions - * @{ - */ - - -/* Peripheral State methods **************************************************/ -HAL_HASH_StateTypeDef HAL_HASH_GetState(HASH_HandleTypeDef *hhash); -HAL_StatusTypeDef HAL_HASH_GetStatus(HASH_HandleTypeDef *hhash); -void HAL_HASH_ContextSaving(HASH_HandleTypeDef *hhash, uint8_t *pMemBuffer); -void HAL_HASH_ContextRestoring(HASH_HandleTypeDef *hhash, uint8_t *pMemBuffer); -void HAL_HASH_SwFeed_ProcessSuspend(HASH_HandleTypeDef *hhash); -HAL_StatusTypeDef HAL_HASH_DMAFeed_ProcessSuspend(HASH_HandleTypeDef *hhash); -uint32_t HAL_HASH_GetError(HASH_HandleTypeDef *hhash); - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions -----------------------------------------------------------*/ - -/** @addtogroup HASH_Private_Functions HASH Private Functions - * @{ - */ - -/* Private functions */ -HAL_StatusTypeDef HASH_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout, uint32_t Algorithm); -HAL_StatusTypeDef HASH_Accumulate(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm); -HAL_StatusTypeDef HASH_Accumulate_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm); -HAL_StatusTypeDef HASH_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Algorithm); -HAL_StatusTypeDef HASH_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm); -HAL_StatusTypeDef HASH_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HMAC_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout, uint32_t Algorithm); -HAL_StatusTypeDef HMAC_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Algorithm); -HAL_StatusTypeDef HMAC_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm); - -/** - * @} - */ - -/** - * @} - */ -#endif /* HASH*/ -/** - * @} - */ - - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_HASH_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash_ex.h deleted file mode 100644 index 0a9844c0ae07194..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash_ex.h +++ /dev/null @@ -1,177 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hash_ex.h - * @author MCD Application Team - * @brief Header file of HASH HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_HASH_EX_H -#define STM32F4xx_HAL_HASH_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (HASH) -/** @addtogroup HASHEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ - - -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup HASHEx_Exported_Functions HASH Extended Exported Functions - * @{ - */ - -/** @addtogroup HASHEx_Exported_Functions_Group1 HASH extended processing functions in polling mode - * @{ - */ - -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group2 HASH extended processing functions in interrupt mode - * @{ - */ - -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group3 HASH extended processing functions in DMA mode - * @{ - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group4 HMAC extended processing functions in polling mode - * @{ - */ -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group5 HMAC extended processing functions in interrupt mode - * @{ - */ - -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group6 HMAC extended processing functions in DMA mode - * @{ - */ - -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group7 Multi-buffer HMAC extended processing functions in DMA mode - * @{ - */ - -HAL_StatusTypeDef HAL_HMACEx_MD5_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_MD5_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_MD5_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); - -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); - -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* HASH*/ -/** - * @} - */ - - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_HASH_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hcd.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hcd.h deleted file mode 100644 index 6025e032c278ba0..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hcd.h +++ /dev/null @@ -1,319 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hcd.h - * @author MCD Application Team - * @brief Header file of HCD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_HCD_H -#define STM32F4xx_HAL_HCD_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_usb.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup HCD HCD - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup HCD_Exported_Types HCD Exported Types - * @{ - */ - -/** @defgroup HCD_Exported_Types_Group1 HCD State Structure definition - * @{ - */ -typedef enum -{ - HAL_HCD_STATE_RESET = 0x00, - HAL_HCD_STATE_READY = 0x01, - HAL_HCD_STATE_ERROR = 0x02, - HAL_HCD_STATE_BUSY = 0x03, - HAL_HCD_STATE_TIMEOUT = 0x04 -} HCD_StateTypeDef; - -typedef USB_OTG_GlobalTypeDef HCD_TypeDef; -typedef USB_OTG_CfgTypeDef HCD_InitTypeDef; -typedef USB_OTG_HCTypeDef HCD_HCTypeDef; -typedef USB_OTG_URBStateTypeDef HCD_URBStateTypeDef; -typedef USB_OTG_HCStateTypeDef HCD_HCStateTypeDef; -/** - * @} - */ - -/** @defgroup HCD_Exported_Types_Group2 HCD Handle Structure definition - * @{ - */ -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) -typedef struct __HCD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ -{ - HCD_TypeDef *Instance; /*!< Register base address */ - HCD_InitTypeDef Init; /*!< HCD required parameters */ - HCD_HCTypeDef hc[16]; /*!< Host channels parameters */ - HAL_LockTypeDef Lock; /*!< HCD peripheral status */ - __IO HCD_StateTypeDef State; /*!< HCD communication state */ - __IO uint32_t ErrorCode; /*!< HCD Error code */ - void *pData; /*!< Pointer Stack Handler */ -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - void (* SOFCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD SOF callback */ - void (* ConnectCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Connect callback */ - void (* DisconnectCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Disconnect callback */ - void (* PortEnabledCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Port Enable callback */ - void (* PortDisabledCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Port Disable callback */ - void (* HC_NotifyURBChangeCallback)(struct __HCD_HandleTypeDef *hhcd, uint8_t chnum, - HCD_URBStateTypeDef urb_state); /*!< USB OTG HCD Host Channel Notify URB Change callback */ - - void (* MspInitCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Msp Init callback */ - void (* MspDeInitCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Msp DeInit callback */ -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ -} HCD_HandleTypeDef; -/** - * @} - */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup HCD_Exported_Constants HCD Exported Constants - * @{ - */ - -/** @defgroup HCD_Speed HCD Speed - * @{ - */ -#define HCD_SPEED_HIGH USBH_HS_SPEED -#define HCD_SPEED_FULL USBH_FSLS_SPEED -#define HCD_SPEED_LOW USBH_FSLS_SPEED -/** - * @} - */ - -/** @defgroup HCD_Device_Speed HCD Device Speed - * @{ - */ -#define HCD_DEVICE_SPEED_HIGH 0U -#define HCD_DEVICE_SPEED_FULL 1U -#define HCD_DEVICE_SPEED_LOW 2U -/** - * @} - */ - -/** @defgroup HCD_PHY_Module HCD PHY Module - * @{ - */ -#define HCD_PHY_ULPI 1U -#define HCD_PHY_EMBEDDED 2U -/** - * @} - */ - -/** @defgroup HCD_Error_Code_definition HCD Error Code definition - * @brief HCD Error Code definition - * @{ - */ -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) -#define HAL_HCD_ERROR_INVALID_CALLBACK (0x00000010U) /*!< Invalid Callback error */ -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup HCD_Exported_Macros HCD Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -#define __HAL_HCD_ENABLE(__HANDLE__) (void)USB_EnableGlobalInt ((__HANDLE__)->Instance) -#define __HAL_HCD_DISABLE(__HANDLE__) (void)USB_DisableGlobalInt ((__HANDLE__)->Instance) - -#define __HAL_HCD_GET_FLAG(__HANDLE__, __INTERRUPT__) ((USB_ReadInterrupts((__HANDLE__)->Instance)\ - & (__INTERRUPT__)) == (__INTERRUPT__)) -#define __HAL_HCD_CLEAR_FLAG(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->GINTSTS) = (__INTERRUPT__)) -#define __HAL_HCD_IS_INVALID_INTERRUPT(__HANDLE__) (USB_ReadInterrupts((__HANDLE__)->Instance) == 0U) - -#define __HAL_HCD_CLEAR_HC_INT(chnum, __INTERRUPT__) (USBx_HC(chnum)->HCINT = (__INTERRUPT__)) -#define __HAL_HCD_MASK_HALT_HC_INT(chnum) (USBx_HC(chnum)->HCINTMSK &= ~USB_OTG_HCINTMSK_CHHM) -#define __HAL_HCD_UNMASK_HALT_HC_INT(chnum) (USBx_HC(chnum)->HCINTMSK |= USB_OTG_HCINTMSK_CHHM) -#define __HAL_HCD_MASK_ACK_HC_INT(chnum) (USBx_HC(chnum)->HCINTMSK &= ~USB_OTG_HCINTMSK_ACKM) -#define __HAL_HCD_UNMASK_ACK_HC_INT(chnum) (USBx_HC(chnum)->HCINTMSK |= USB_OTG_HCINTMSK_ACKM) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup HCD_Exported_Functions HCD Exported Functions - * @{ - */ - -/** @defgroup HCD_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_HCD_Init(HCD_HandleTypeDef *hhcd); -HAL_StatusTypeDef HAL_HCD_DeInit(HCD_HandleTypeDef *hhcd); -HAL_StatusTypeDef HAL_HCD_HC_Init(HCD_HandleTypeDef *hhcd, uint8_t ch_num, - uint8_t epnum, uint8_t dev_address, - uint8_t speed, uint8_t ep_type, uint16_t mps); - -HAL_StatusTypeDef HAL_HCD_HC_Halt(HCD_HandleTypeDef *hhcd, uint8_t ch_num); -void HAL_HCD_MspInit(HCD_HandleTypeDef *hhcd); -void HAL_HCD_MspDeInit(HCD_HandleTypeDef *hhcd); - -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) -/** @defgroup HAL_HCD_Callback_ID_enumeration_definition HAL USB OTG HCD Callback ID enumeration definition - * @brief HAL USB OTG HCD Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_HCD_SOF_CB_ID = 0x01, /*!< USB HCD SOF callback ID */ - HAL_HCD_CONNECT_CB_ID = 0x02, /*!< USB HCD Connect callback ID */ - HAL_HCD_DISCONNECT_CB_ID = 0x03, /*!< USB HCD Disconnect callback ID */ - HAL_HCD_PORT_ENABLED_CB_ID = 0x04, /*!< USB HCD Port Enable callback ID */ - HAL_HCD_PORT_DISABLED_CB_ID = 0x05, /*!< USB HCD Port Disable callback ID */ - - HAL_HCD_MSPINIT_CB_ID = 0x06, /*!< USB HCD MspInit callback ID */ - HAL_HCD_MSPDEINIT_CB_ID = 0x07 /*!< USB HCD MspDeInit callback ID */ - -} HAL_HCD_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup HAL_HCD_Callback_pointer_definition HAL USB OTG HCD Callback pointer definition - * @brief HAL USB OTG HCD Callback pointer definition - * @{ - */ - -typedef void (*pHCD_CallbackTypeDef)(HCD_HandleTypeDef *hhcd); /*!< pointer to a common USB OTG HCD callback function */ -typedef void (*pHCD_HC_NotifyURBChangeCallbackTypeDef)(HCD_HandleTypeDef *hhcd, - uint8_t epnum, - HCD_URBStateTypeDef urb_state); /*!< pointer to USB OTG HCD host channel callback */ -/** - * @} - */ - -HAL_StatusTypeDef HAL_HCD_RegisterCallback(HCD_HandleTypeDef *hhcd, - HAL_HCD_CallbackIDTypeDef CallbackID, - pHCD_CallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_HCD_UnRegisterCallback(HCD_HandleTypeDef *hhcd, - HAL_HCD_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_HCD_RegisterHC_NotifyURBChangeCallback(HCD_HandleTypeDef *hhcd, - pHCD_HC_NotifyURBChangeCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_HCD_UnRegisterHC_NotifyURBChangeCallback(HCD_HandleTypeDef *hhcd); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* I/O operation functions ***************************************************/ -/** @addtogroup HCD_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -HAL_StatusTypeDef HAL_HCD_HC_SubmitRequest(HCD_HandleTypeDef *hhcd, uint8_t ch_num, - uint8_t direction, uint8_t ep_type, - uint8_t token, uint8_t *pbuff, - uint16_t length, uint8_t do_ping); - -/* Non-Blocking mode: Interrupt */ -void HAL_HCD_IRQHandler(HCD_HandleTypeDef *hhcd); -void HAL_HCD_WKUP_IRQHandler(HCD_HandleTypeDef *hhcd); -void HAL_HCD_SOF_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_Connect_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_Disconnect_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_PortEnabled_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_PortDisabled_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_HC_NotifyURBChange_Callback(HCD_HandleTypeDef *hhcd, uint8_t chnum, - HCD_URBStateTypeDef urb_state); -/** - * @} - */ - -/* Peripheral Control functions **********************************************/ -/** @addtogroup HCD_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_HCD_ResetPort(HCD_HandleTypeDef *hhcd); -HAL_StatusTypeDef HAL_HCD_Start(HCD_HandleTypeDef *hhcd); -HAL_StatusTypeDef HAL_HCD_Stop(HCD_HandleTypeDef *hhcd); -/** - * @} - */ - -/* Peripheral State functions ************************************************/ -/** @addtogroup HCD_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -HCD_StateTypeDef HAL_HCD_GetState(HCD_HandleTypeDef *hhcd); -HCD_URBStateTypeDef HAL_HCD_HC_GetURBState(HCD_HandleTypeDef *hhcd, uint8_t chnum); -HCD_HCStateTypeDef HAL_HCD_HC_GetState(HCD_HandleTypeDef *hhcd, uint8_t chnum); -uint32_t HAL_HCD_HC_GetXferCount(HCD_HandleTypeDef *hhcd, uint8_t chnum); -uint32_t HAL_HCD_GetCurrentFrame(HCD_HandleTypeDef *hhcd); -uint32_t HAL_HCD_GetCurrentSpeed(HCD_HandleTypeDef *hhcd); - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup HCD_Private_Macros HCD Private Macros - * @{ - */ -/** - * @} - */ -/* Private functions prototypes ----------------------------------------------*/ - -/** - * @} - */ -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_HCD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h deleted file mode 100644 index 9a622b82b3a2676..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h +++ /dev/null @@ -1,743 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c.h - * @author MCD Application Team - * @brief Header file of I2C HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_I2C_H -#define __STM32F4xx_HAL_I2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup I2C - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup I2C_Exported_Types I2C Exported Types - * @{ - */ - -/** @defgroup I2C_Configuration_Structure_definition I2C Configuration Structure definition - * @brief I2C Configuration Structure definition - * @{ - */ -typedef struct -{ - uint32_t ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 400kHz */ - - uint32_t DutyCycle; /*!< Specifies the I2C fast mode duty cycle. - This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected. - This parameter can be a value of @ref I2C_addressing_mode */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref I2C_dual_addressing_mode */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected - This parameter can be a 7-bit address. */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref I2C_general_call_addressing_mode */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref I2C_nostretch_mode */ - -} I2C_InitTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_state_structure_definition HAL state structure definition - * @brief HAL State structure definition - * @note HAL I2C State value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : Abort (Abort user request on going) - * 10 : Timeout - * 11 : Error - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized and ready to use. HAL I2C Init function called) - * b4 (not used) - * x : Should be set to 0 - * b3 - * 0 : Ready or Busy (No Listen mode ongoing) - * 1 : Listen (Peripheral in Address Listen Mode) - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (Peripheral busy with some configuration or internal operations) - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * @{ - */ -typedef enum -{ - HAL_I2C_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_I2C_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */ - HAL_I2C_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */ - HAL_I2C_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */ - HAL_I2C_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_I2C_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */ - HAL_I2C_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission - process is ongoing */ - HAL_I2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception - process is ongoing */ - HAL_I2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ - HAL_I2C_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */ - HAL_I2C_STATE_ERROR = 0xE0U /*!< Error */ - -} HAL_I2C_StateTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_mode_structure_definition HAL mode structure definition - * @brief HAL Mode structure definition - * @note HAL I2C Mode value coding follow below described bitmap :\n - * b7 (not used)\n - * x : Should be set to 0\n - * b6\n - * 0 : None\n - * 1 : Memory (HAL I2C communication is in Memory Mode)\n - * b5\n - * 0 : None\n - * 1 : Slave (HAL I2C communication is in Slave Mode)\n - * b4\n - * 0 : None\n - * 1 : Master (HAL I2C communication is in Master Mode)\n - * b3-b2-b1-b0 (not used)\n - * xxxx : Should be set to 0000 - * @{ - */ -typedef enum -{ - HAL_I2C_MODE_NONE = 0x00U, /*!< No I2C communication on going */ - HAL_I2C_MODE_MASTER = 0x10U, /*!< I2C communication is in Master Mode */ - HAL_I2C_MODE_SLAVE = 0x20U, /*!< I2C communication is in Slave Mode */ - HAL_I2C_MODE_MEM = 0x40U /*!< I2C communication is in Memory Mode */ - -} HAL_I2C_ModeTypeDef; - -/** - * @} - */ - -/** @defgroup I2C_Error_Code_definition I2C Error Code definition - * @brief I2C Error Code definition - * @{ - */ -#define HAL_I2C_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_I2C_ERROR_BERR 0x00000001U /*!< BERR error */ -#define HAL_I2C_ERROR_ARLO 0x00000002U /*!< ARLO error */ -#define HAL_I2C_ERROR_AF 0x00000004U /*!< AF error */ -#define HAL_I2C_ERROR_OVR 0x00000008U /*!< OVR error */ -#define HAL_I2C_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#define HAL_I2C_ERROR_TIMEOUT 0x00000020U /*!< Timeout Error */ -#define HAL_I2C_ERROR_SIZE 0x00000040U /*!< Size Management error */ -#define HAL_I2C_ERROR_DMA_PARAM 0x00000080U /*!< DMA Parameter Error */ -#define HAL_I2C_WRONG_START 0x00000200U /*!< Wrong start Error */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -#define HAL_I2C_ERROR_INVALID_CALLBACK 0x00000100U /*!< Invalid Callback error */ -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup I2C_handle_Structure_definition I2C handle Structure definition - * @brief I2C handle Structure definition - * @{ - */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -typedef struct __I2C_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -{ - I2C_TypeDef *Instance; /*!< I2C registers base address */ - - I2C_InitTypeDef Init; /*!< I2C communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to I2C transfer buffer */ - - uint16_t XferSize; /*!< I2C transfer size */ - - __IO uint16_t XferCount; /*!< I2C transfer counter */ - - __IO uint32_t XferOptions; /*!< I2C transfer options */ - - __IO uint32_t PreviousState; /*!< I2C communication Previous state and mode - context for internal usage */ - - DMA_HandleTypeDef *hdmatx; /*!< I2C Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< I2C Rx DMA handle parameters */ - - HAL_LockTypeDef Lock; /*!< I2C locking object */ - - __IO HAL_I2C_StateTypeDef State; /*!< I2C communication state */ - - __IO HAL_I2C_ModeTypeDef Mode; /*!< I2C communication mode */ - - __IO uint32_t ErrorCode; /*!< I2C Error code */ - - __IO uint32_t Devaddress; /*!< I2C Target device address */ - - __IO uint32_t Memaddress; /*!< I2C Target memory address */ - - __IO uint32_t MemaddSize; /*!< I2C Target memory address size */ - - __IO uint32_t EventCount; /*!< I2C Event counter */ - - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Listen Complete callback */ - void (* MemTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Memory Tx Transfer completed callback */ - void (* MemRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Memory Rx Transfer completed callback */ - void (* ErrorCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Error callback */ - void (* AbortCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Abort callback */ - - void (* AddrCallback)(struct __I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< I2C Slave Address Match callback */ - - void (* MspInitCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Msp Init callback */ - void (* MspDeInitCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Msp DeInit callback */ - -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -} I2C_HandleTypeDef; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -/** - * @brief HAL I2C Callback ID enumeration definition - */ -typedef enum -{ - HAL_I2C_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< I2C Master Tx Transfer completed callback ID */ - HAL_I2C_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< I2C Master Rx Transfer completed callback ID */ - HAL_I2C_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< I2C Slave Tx Transfer completed callback ID */ - HAL_I2C_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< I2C Slave Rx Transfer completed callback ID */ - HAL_I2C_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< I2C Listen Complete callback ID */ - HAL_I2C_MEM_TX_COMPLETE_CB_ID = 0x05U, /*!< I2C Memory Tx Transfer callback ID */ - HAL_I2C_MEM_RX_COMPLETE_CB_ID = 0x06U, /*!< I2C Memory Rx Transfer completed callback ID */ - HAL_I2C_ERROR_CB_ID = 0x07U, /*!< I2C Error callback ID */ - HAL_I2C_ABORT_CB_ID = 0x08U, /*!< I2C Abort callback ID */ - - HAL_I2C_MSPINIT_CB_ID = 0x09U, /*!< I2C Msp Init callback ID */ - HAL_I2C_MSPDEINIT_CB_ID = 0x0AU /*!< I2C Msp DeInit callback ID */ - -} HAL_I2C_CallbackIDTypeDef; - -/** - * @brief HAL I2C Callback pointer definition - */ -typedef void (*pI2C_CallbackTypeDef)(I2C_HandleTypeDef *hi2c); /*!< pointer to an I2C callback function */ -typedef void (*pI2C_AddrCallbackTypeDef)(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< pointer to an I2C Address Match callback function */ - -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup I2C_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2C_duty_cycle_in_fast_mode I2C duty cycle in fast mode - * @{ - */ -#define I2C_DUTYCYCLE_2 0x00000000U -#define I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY -/** - * @} - */ - -/** @defgroup I2C_addressing_mode I2C addressing mode - * @{ - */ -#define I2C_ADDRESSINGMODE_7BIT 0x00004000U -#define I2C_ADDRESSINGMODE_10BIT (I2C_OAR1_ADDMODE | 0x00004000U) -/** - * @} - */ - -/** @defgroup I2C_dual_addressing_mode I2C dual addressing mode - * @{ - */ -#define I2C_DUALADDRESS_DISABLE 0x00000000U -#define I2C_DUALADDRESS_ENABLE I2C_OAR2_ENDUAL -/** - * @} - */ - -/** @defgroup I2C_general_call_addressing_mode I2C general call addressing mode - * @{ - */ -#define I2C_GENERALCALL_DISABLE 0x00000000U -#define I2C_GENERALCALL_ENABLE I2C_CR1_ENGC -/** - * @} - */ - -/** @defgroup I2C_nostretch_mode I2C nostretch mode - * @{ - */ -#define I2C_NOSTRETCH_DISABLE 0x00000000U -#define I2C_NOSTRETCH_ENABLE I2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup I2C_Memory_Address_Size I2C Memory Address Size - * @{ - */ -#define I2C_MEMADD_SIZE_8BIT 0x00000001U -#define I2C_MEMADD_SIZE_16BIT 0x00000010U -/** - * @} - */ - -/** @defgroup I2C_XferDirection_definition I2C XferDirection definition - * @{ - */ -#define I2C_DIRECTION_RECEIVE 0x00000000U -#define I2C_DIRECTION_TRANSMIT 0x00000001U -/** - * @} - */ - -/** @defgroup I2C_XferOptions_definition I2C XferOptions definition - * @{ - */ -#define I2C_FIRST_FRAME 0x00000001U -#define I2C_FIRST_AND_NEXT_FRAME 0x00000002U -#define I2C_NEXT_FRAME 0x00000004U -#define I2C_FIRST_AND_LAST_FRAME 0x00000008U -#define I2C_LAST_FRAME_NO_STOP 0x00000010U -#define I2C_LAST_FRAME 0x00000020U - -/* List of XferOptions in usage of : - * 1- Restart condition in all use cases (direction change or not) - */ -#define I2C_OTHER_FRAME (0x00AA0000U) -#define I2C_OTHER_AND_LAST_FRAME (0xAA000000U) -/** - * @} - */ - -/** @defgroup I2C_Interrupt_configuration_definition I2C Interrupt configuration definition - * @brief I2C Interrupt definition - * Elements values convention: 0xXXXXXXXX - * - XXXXXXXX : Interrupt control mask - * @{ - */ -#define I2C_IT_BUF I2C_CR2_ITBUFEN -#define I2C_IT_EVT I2C_CR2_ITEVTEN -#define I2C_IT_ERR I2C_CR2_ITERREN -/** - * @} - */ - -/** @defgroup I2C_Flag_definition I2C Flag definition - * @{ - */ - -#define I2C_FLAG_OVR 0x00010800U -#define I2C_FLAG_AF 0x00010400U -#define I2C_FLAG_ARLO 0x00010200U -#define I2C_FLAG_BERR 0x00010100U -#define I2C_FLAG_TXE 0x00010080U -#define I2C_FLAG_RXNE 0x00010040U -#define I2C_FLAG_STOPF 0x00010010U -#define I2C_FLAG_ADD10 0x00010008U -#define I2C_FLAG_BTF 0x00010004U -#define I2C_FLAG_ADDR 0x00010002U -#define I2C_FLAG_SB 0x00010001U -#define I2C_FLAG_DUALF 0x00100080U -#define I2C_FLAG_GENCALL 0x00100010U -#define I2C_FLAG_TRA 0x00100004U -#define I2C_FLAG_BUSY 0x00100002U -#define I2C_FLAG_MSL 0x00100001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ - -/** @defgroup I2C_Exported_Macros I2C Exported Macros - * @{ - */ - -/** @brief Reset I2C handle state. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_I2C_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2C_STATE_RESET) -#endif - -/** @brief Enable or disable the specified I2C interrupts. - * @param __HANDLE__ specifies the I2C Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2C_IT_BUF: Buffer interrupt enable - * @arg I2C_IT_EVT: Event interrupt enable - * @arg I2C_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2C_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2,(__INTERRUPT__)) -#define __HAL_I2C_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Checks if the specified I2C interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the I2C Handle. - * @param __INTERRUPT__ specifies the I2C interrupt source to check. - * This parameter can be one of the following values: - * @arg I2C_IT_BUF: Buffer interrupt enable - * @arg I2C_IT_EVT: Event interrupt enable - * @arg I2C_IT_ERR: Error interrupt enable - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_I2C_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified I2C flag is set or not. - * @param __HANDLE__ specifies the I2C Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2C_FLAG_OVR: Overrun/Underrun flag - * @arg I2C_FLAG_AF: Acknowledge failure flag - * @arg I2C_FLAG_ARLO: Arbitration lost flag - * @arg I2C_FLAG_BERR: Bus error flag - * @arg I2C_FLAG_TXE: Data register empty flag - * @arg I2C_FLAG_RXNE: Data register not empty flag - * @arg I2C_FLAG_STOPF: Stop detection flag - * @arg I2C_FLAG_ADD10: 10-bit header sent flag - * @arg I2C_FLAG_BTF: Byte transfer finished flag - * @arg I2C_FLAG_ADDR: Address sent flag - * Address matched flag - * @arg I2C_FLAG_SB: Start bit flag - * @arg I2C_FLAG_DUALF: Dual flag - * @arg I2C_FLAG_GENCALL: General call header flag - * @arg I2C_FLAG_TRA: Transmitter/Receiver flag - * @arg I2C_FLAG_BUSY: Bus busy flag - * @arg I2C_FLAG_MSL: Master/Slave flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_I2C_GET_FLAG(__HANDLE__, __FLAG__) ((((uint8_t)((__FLAG__) >> 16U)) == 0x01U) ? \ - (((((__HANDLE__)->Instance->SR1) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET) : \ - (((((__HANDLE__)->Instance->SR2) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET)) - -/** @brief Clears the I2C pending flags which are cleared by writing 0 in a specific bit. - * @param __HANDLE__ specifies the I2C Handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) - * @arg I2C_FLAG_AF: Acknowledge failure flag - * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) - * @arg I2C_FLAG_BERR: Bus error flag - * @retval None - */ -#define __HAL_I2C_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR1 = ~((__FLAG__) & I2C_FLAG_MASK)) - -/** @brief Clears the I2C ADDR pending flag. - * @param __HANDLE__ specifies the I2C Handle. - * This parameter can be I2C where x: 1, 2, or 3 to select the I2C peripheral. - * @retval None - */ -#define __HAL_I2C_CLEAR_ADDRFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - tmpreg = (__HANDLE__)->Instance->SR2; \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Clears the I2C STOPF pending flag. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_CLEAR_STOPFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE); \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Enable the specified I2C peripheral. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE) - -/** @brief Disable the specified I2C peripheral. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE) - -/** - * @} - */ - -/* Include I2C HAL Extension module */ -#include "stm32f4xx_hal_i2c_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2C_Exported_Functions - * @{ - */ - -/** @addtogroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -/* Initialization and de-initialization functions******************************/ -HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID, pI2C_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup I2C_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* IO operation functions ****************************************************/ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout); - -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress); - -/******* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -/** - * @} - */ - -/** @addtogroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* I2C IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c); -void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c); -/** - * @} - */ - -/** @addtogroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @{ - */ -/* Peripheral State, Mode and Error functions *********************************/ -HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c); -HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c); -uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2C_Private_Constants I2C Private Constants - * @{ - */ -#define I2C_FLAG_MASK 0x0000FFFFU -#define I2C_MIN_PCLK_FREQ_STANDARD 2000000U /*!< 2 MHz */ -#define I2C_MIN_PCLK_FREQ_FAST 4000000U /*!< 4 MHz */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2C_Private_Macros I2C Private Macros - * @{ - */ - -#define I2C_MIN_PCLK_FREQ(__PCLK__, __SPEED__) (((__SPEED__) <= 100000U) ? ((__PCLK__) < I2C_MIN_PCLK_FREQ_STANDARD) : ((__PCLK__) < I2C_MIN_PCLK_FREQ_FAST)) -#define I2C_CCR_CALCULATION(__PCLK__, __SPEED__, __COEFF__) (((((__PCLK__) - 1U)/((__SPEED__) * (__COEFF__))) + 1U) & I2C_CCR_CCR) -#define I2C_FREQRANGE(__PCLK__) ((__PCLK__)/1000000U) -#define I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (((__SPEED__) <= 100000U) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U)) -#define I2C_SPEED_STANDARD(__PCLK__, __SPEED__) ((I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 2U) < 4U)? 4U:I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 2U)) -#define I2C_SPEED_FAST(__PCLK__, __SPEED__, __DUTYCYCLE__) (((__DUTYCYCLE__) == I2C_DUTYCYCLE_2)? I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 3U) : (I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 25U) | I2C_DUTYCYCLE_16_9)) -#define I2C_SPEED(__PCLK__, __SPEED__, __DUTYCYCLE__) (((__SPEED__) <= 100000U)? (I2C_SPEED_STANDARD((__PCLK__), (__SPEED__))) : \ - ((I2C_SPEED_FAST((__PCLK__), (__SPEED__), (__DUTYCYCLE__)) & I2C_CCR_CCR) == 0U)? 1U : \ - ((I2C_SPEED_FAST((__PCLK__), (__SPEED__), (__DUTYCYCLE__))) | I2C_CCR_FS)) - -#define I2C_7BIT_ADD_WRITE(__ADDRESS__) ((uint8_t)((__ADDRESS__) & (uint8_t)(~I2C_OAR1_ADD0))) -#define I2C_7BIT_ADD_READ(__ADDRESS__) ((uint8_t)((__ADDRESS__) | I2C_OAR1_ADD0)) - -#define I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) -#define I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)0x00F0))) -#define I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)(0x00F1)))) - -#define I2C_MEM_ADD_MSB(__ADDRESS__) ((uint8_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0xFF00)) >> 8))) -#define I2C_MEM_ADD_LSB(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) - -/** @defgroup I2C_IS_RTC_Definitions I2C Private macros to check input parameters - * @{ - */ -#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DUTYCYCLE_2) || \ - ((CYCLE) == I2C_DUTYCYCLE_16_9)) -#define IS_I2C_ADDRESSING_MODE(ADDRESS) (((ADDRESS) == I2C_ADDRESSINGMODE_7BIT) || \ - ((ADDRESS) == I2C_ADDRESSINGMODE_10BIT)) -#define IS_I2C_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == I2C_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == I2C_DUALADDRESS_ENABLE)) -#define IS_I2C_GENERAL_CALL(CALL) (((CALL) == I2C_GENERALCALL_DISABLE) || \ - ((CALL) == I2C_GENERALCALL_ENABLE)) -#define IS_I2C_NO_STRETCH(STRETCH) (((STRETCH) == I2C_NOSTRETCH_DISABLE) || \ - ((STRETCH) == I2C_NOSTRETCH_ENABLE)) -#define IS_I2C_MEMADD_SIZE(SIZE) (((SIZE) == I2C_MEMADD_SIZE_8BIT) || \ - ((SIZE) == I2C_MEMADD_SIZE_16BIT)) -#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) > 0U) && ((SPEED) <= 400000U)) -#define IS_I2C_OWN_ADDRESS1(ADDRESS1) (((ADDRESS1) & 0xFFFFFC00U) == 0U) -#define IS_I2C_OWN_ADDRESS2(ADDRESS2) (((ADDRESS2) & 0xFFFFFF01U) == 0U) -#define IS_I2C_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_FIRST_FRAME) || \ - ((REQUEST) == I2C_FIRST_AND_NEXT_FRAME) || \ - ((REQUEST) == I2C_NEXT_FRAME) || \ - ((REQUEST) == I2C_FIRST_AND_LAST_FRAME) || \ - ((REQUEST) == I2C_LAST_FRAME) || \ - ((REQUEST) == I2C_LAST_FRAME_NO_STOP) || \ - IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST)) - -#define IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_OTHER_FRAME) || \ - ((REQUEST) == I2C_OTHER_AND_LAST_FRAME)) - -#define I2C_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET) -#define I2C_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET) -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup I2C_Private_Functions I2C Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_I2C_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h deleted file mode 100644 index 6864d83519f5745..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h +++ /dev/null @@ -1,117 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c_ex.h - * @author MCD Application Team - * @brief Header file of I2C HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_I2C_EX_H -#define __STM32F4xx_HAL_I2C_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup I2CEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2CEx_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2CEx_Analog_Filter I2C Analog Filter - * @{ - */ -#define I2C_ANALOGFILTER_ENABLE 0x00000000U -#define I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2CEx_Exported_Functions - * @{ - */ - -/** @addtogroup I2CEx_Exported_Functions_Group1 - * @{ - */ -/* Peripheral Control functions ************************************************/ -HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2CEx_Private_Constants I2C Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2CEx_Private_Macros I2C Private Macros - * @{ - */ -#define IS_I2C_ANALOG_FILTER(FILTER) (((FILTER) == I2C_ANALOGFILTER_ENABLE) || \ - ((FILTER) == I2C_ANALOGFILTER_DISABLE)) -#define IS_I2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_I2C_EX_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s.h deleted file mode 100644 index 1e9676f868d2473..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s.h +++ /dev/null @@ -1,620 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2s.h - * @author MCD Application Team - * @brief Header file of I2S HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_I2S_H -#define STM32F4xx_HAL_I2S_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup I2S - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup I2S_Exported_Types I2S Exported Types - * @{ - */ - -/** - * @brief I2S Init structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Specifies the I2S operating mode. - This parameter can be a value of @ref I2S_Mode */ - - uint32_t Standard; /*!< Specifies the standard used for the I2S communication. - This parameter can be a value of @ref I2S_Standard */ - - uint32_t DataFormat; /*!< Specifies the data format for the I2S communication. - This parameter can be a value of @ref I2S_Data_Format */ - - uint32_t MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. - This parameter can be a value of @ref I2S_MCLK_Output */ - - uint32_t AudioFreq; /*!< Specifies the frequency selected for the I2S communication. - This parameter can be a value of @ref I2S_Audio_Frequency */ - - uint32_t CPOL; /*!< Specifies the idle state of the I2S clock. - This parameter can be a value of @ref I2S_Clock_Polarity */ - - uint32_t ClockSource; /*!< Specifies the I2S Clock Source. - This parameter can be a value of @ref I2S_Clock_Source */ - uint32_t FullDuplexMode; /*!< Specifies the I2S FullDuplex mode. - This parameter can be a value of @ref I2S_FullDuplex_Mode */ -} I2S_InitTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_I2S_STATE_RESET = 0x00U, /*!< I2S not yet initialized or disabled */ - HAL_I2S_STATE_READY = 0x01U, /*!< I2S initialized and ready for use */ - HAL_I2S_STATE_BUSY = 0x02U, /*!< I2S internal process is ongoing */ - HAL_I2S_STATE_BUSY_TX = 0x03U, /*!< Data Transmission process is ongoing */ - HAL_I2S_STATE_BUSY_RX = 0x04U, /*!< Data Reception process is ongoing */ - HAL_I2S_STATE_BUSY_TX_RX = 0x05U, /*!< Data Transmission and Reception process is ongoing */ - HAL_I2S_STATE_TIMEOUT = 0x06U, /*!< I2S timeout state */ - HAL_I2S_STATE_ERROR = 0x07U /*!< I2S error state */ -} HAL_I2S_StateTypeDef; - -/** - * @brief I2S handle Structure definition - */ -typedef struct __I2S_HandleTypeDef -{ - SPI_TypeDef *Instance; /*!< I2S registers base address */ - - I2S_InitTypeDef Init; /*!< I2S communication parameters */ - - uint16_t *pTxBuffPtr; /*!< Pointer to I2S Tx transfer buffer */ - - __IO uint16_t TxXferSize; /*!< I2S Tx transfer size */ - - __IO uint16_t TxXferCount; /*!< I2S Tx transfer Counter */ - - uint16_t *pRxBuffPtr; /*!< Pointer to I2S Rx transfer buffer */ - - __IO uint16_t RxXferSize; /*!< I2S Rx transfer size */ - - __IO uint16_t RxXferCount; /*!< I2S Rx transfer counter - (This field is initialized at the - same value as transfer size at the - beginning of the transfer and - decremented when a sample is received - NbSamplesReceived = RxBufferSize-RxBufferCount) */ - void (*IrqHandlerISR)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S function pointer on IrqHandler */ - - DMA_HandleTypeDef *hdmatx; /*!< I2S Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< I2S Rx DMA handle parameters */ - - __IO HAL_LockTypeDef Lock; /*!< I2S locking object */ - - __IO HAL_I2S_StateTypeDef State; /*!< I2S communication state */ - - __IO uint32_t ErrorCode; /*!< I2S Error code - This parameter can be a value of @ref I2S_Error */ - -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Tx Completed callback */ - void (* RxCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Rx Completed callback */ - void (* TxRxCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S TxRx Completed callback */ - void (* TxHalfCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Tx Half Completed callback */ - void (* RxHalfCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Rx Half Completed callback */ - void (* TxRxHalfCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S TxRx Half Completed callback */ - void (* ErrorCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Error callback */ - void (* MspInitCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Msp Init callback */ - void (* MspDeInitCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Msp DeInit callback */ - -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} I2S_HandleTypeDef; - -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL I2S Callback ID enumeration definition - */ -typedef enum -{ - HAL_I2S_TX_COMPLETE_CB_ID = 0x00U, /*!< I2S Tx Completed callback ID */ - HAL_I2S_RX_COMPLETE_CB_ID = 0x01U, /*!< I2S Rx Completed callback ID */ - HAL_I2S_TX_RX_COMPLETE_CB_ID = 0x02U, /*!< I2S TxRx Completed callback ID */ - HAL_I2S_TX_HALF_COMPLETE_CB_ID = 0x03U, /*!< I2S Tx Half Completed callback ID */ - HAL_I2S_RX_HALF_COMPLETE_CB_ID = 0x04U, /*!< I2S Rx Half Completed callback ID */ - HAL_I2S_TX_RX_HALF_COMPLETE_CB_ID = 0x05U, /*!< I2S TxRx Half Completed callback ID */ - HAL_I2S_ERROR_CB_ID = 0x06U, /*!< I2S Error callback ID */ - HAL_I2S_MSPINIT_CB_ID = 0x07U, /*!< I2S Msp Init callback ID */ - HAL_I2S_MSPDEINIT_CB_ID = 0x08U /*!< I2S Msp DeInit callback ID */ - -} HAL_I2S_CallbackIDTypeDef; - -/** - * @brief HAL I2S Callback pointer definition - */ -typedef void (*pI2S_CallbackTypeDef)(I2S_HandleTypeDef *hi2s); /*!< pointer to an I2S callback function */ - -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2S_Exported_Constants I2S Exported Constants - * @{ - */ -/** @defgroup I2S_Error I2S Error - * @{ - */ -#define HAL_I2S_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_I2S_ERROR_TIMEOUT (0x00000001U) /*!< Timeout error */ -#define HAL_I2S_ERROR_OVR (0x00000002U) /*!< OVR error */ -#define HAL_I2S_ERROR_UDR (0x00000004U) /*!< UDR error */ -#define HAL_I2S_ERROR_DMA (0x00000008U) /*!< DMA transfer error */ -#define HAL_I2S_ERROR_PRESCALER (0x00000010U) /*!< Prescaler Calculation error */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -#define HAL_I2S_ERROR_INVALID_CALLBACK (0x00000020U) /*!< Invalid Callback error */ -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -#define HAL_I2S_ERROR_BUSY_LINE_RX (0x00000040U) /*!< Busy Rx Line error */ -/** - * @} - */ - -/** @defgroup I2S_Mode I2S Mode - * @{ - */ -#define I2S_MODE_SLAVE_TX (0x00000000U) -#define I2S_MODE_SLAVE_RX (SPI_I2SCFGR_I2SCFG_0) -#define I2S_MODE_MASTER_TX (SPI_I2SCFGR_I2SCFG_1) -#define I2S_MODE_MASTER_RX ((SPI_I2SCFGR_I2SCFG_0 | SPI_I2SCFGR_I2SCFG_1)) -/** - * @} - */ - -/** @defgroup I2S_Standard I2S Standard - * @{ - */ -#define I2S_STANDARD_PHILIPS (0x00000000U) -#define I2S_STANDARD_MSB (SPI_I2SCFGR_I2SSTD_0) -#define I2S_STANDARD_LSB (SPI_I2SCFGR_I2SSTD_1) -#define I2S_STANDARD_PCM_SHORT ((SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1)) -#define I2S_STANDARD_PCM_LONG ((SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1 | SPI_I2SCFGR_PCMSYNC)) -/** - * @} - */ - -/** @defgroup I2S_Data_Format I2S Data Format - * @{ - */ -#define I2S_DATAFORMAT_16B (0x00000000U) -#define I2S_DATAFORMAT_16B_EXTENDED (SPI_I2SCFGR_CHLEN) -#define I2S_DATAFORMAT_24B ((SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_0)) -#define I2S_DATAFORMAT_32B ((SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_1)) -/** - * @} - */ - -/** @defgroup I2S_MCLK_Output I2S MCLK Output - * @{ - */ -#define I2S_MCLKOUTPUT_ENABLE (SPI_I2SPR_MCKOE) -#define I2S_MCLKOUTPUT_DISABLE (0x00000000U) -/** - * @} - */ - -/** @defgroup I2S_Audio_Frequency I2S Audio Frequency - * @{ - */ -#define I2S_AUDIOFREQ_192K (192000U) -#define I2S_AUDIOFREQ_96K (96000U) -#define I2S_AUDIOFREQ_48K (48000U) -#define I2S_AUDIOFREQ_44K (44100U) -#define I2S_AUDIOFREQ_32K (32000U) -#define I2S_AUDIOFREQ_22K (22050U) -#define I2S_AUDIOFREQ_16K (16000U) -#define I2S_AUDIOFREQ_11K (11025U) -#define I2S_AUDIOFREQ_8K (8000U) -#define I2S_AUDIOFREQ_DEFAULT (2U) -/** - * @} - */ - -/** @defgroup I2S_FullDuplex_Mode I2S FullDuplex Mode - * @{ - */ -#define I2S_FULLDUPLEXMODE_DISABLE (0x00000000U) -#define I2S_FULLDUPLEXMODE_ENABLE (0x00000001U) -/** - * @} - */ - -/** @defgroup I2S_Clock_Polarity I2S Clock Polarity - * @{ - */ -#define I2S_CPOL_LOW (0x00000000U) -#define I2S_CPOL_HIGH (SPI_I2SCFGR_CKPOL) -/** - * @} - */ - -/** @defgroup I2S_Interrupts_Definition I2S Interrupts Definition - * @{ - */ -#define I2S_IT_TXE SPI_CR2_TXEIE -#define I2S_IT_RXNE SPI_CR2_RXNEIE -#define I2S_IT_ERR SPI_CR2_ERRIE -/** - * @} - */ - -/** @defgroup I2S_Flags_Definition I2S Flags Definition - * @{ - */ -#define I2S_FLAG_TXE SPI_SR_TXE -#define I2S_FLAG_RXNE SPI_SR_RXNE - -#define I2S_FLAG_UDR SPI_SR_UDR -#define I2S_FLAG_OVR SPI_SR_OVR -#define I2S_FLAG_FRE SPI_SR_FRE - -#define I2S_FLAG_CHSIDE SPI_SR_CHSIDE -#define I2S_FLAG_BSY SPI_SR_BSY - -#define I2S_FLAG_MASK (SPI_SR_RXNE\ - | SPI_SR_TXE | SPI_SR_UDR | SPI_SR_OVR | SPI_SR_FRE | SPI_SR_CHSIDE | SPI_SR_BSY) -/** - * @} - */ - -/** @defgroup I2S_Clock_Source I2S Clock Source Definition - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) || defined(STM32F479xx) -#define I2S_CLOCK_PLL (0x00000000U) -#define I2S_CLOCK_EXTERNAL (0x00000001U) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define I2S_CLOCK_PLL (0x00000000U) -#define I2S_CLOCK_EXTERNAL (0x00000001U) -#define I2S_CLOCK_PLLR (0x00000002U) -#define I2S_CLOCK_PLLSRC (0x00000003U) -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define I2S_CLOCK_PLLSRC (0x00000000U) -#define I2S_CLOCK_EXTERNAL (0x00000001U) -#define I2S_CLOCK_PLLR (0x00000002U) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup I2S_Exported_macros I2S Exported Macros - * @{ - */ - -/** @brief Reset I2S handle state - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -#define __HAL_I2S_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_I2S_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_I2S_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2S_STATE_RESET) -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - -/** @brief Enable the specified SPI peripheral (in I2S mode). - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) - -/** @brief Disable the specified SPI peripheral (in I2S mode). - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) - -/** @brief Enable the specified I2S interrupts. - * @param __HANDLE__ specifies the I2S Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2S_ENABLE_IT(__HANDLE__, __INTERRUPT__) (SET_BIT((__HANDLE__)->Instance->CR2,(__INTERRUPT__))) - -/** @brief Disable the specified I2S interrupts. - * @param __HANDLE__ specifies the I2S Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2S_DISABLE_IT(__HANDLE__, __INTERRUPT__) (CLEAR_BIT((__HANDLE__)->Instance->CR2,(__INTERRUPT__))) - -/** @brief Checks if the specified I2S interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the I2S Handle. - * This parameter can be I2S where x: 1, 2, or 3 to select the I2S peripheral. - * @param __INTERRUPT__ specifies the I2S interrupt source to check. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_I2S_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified I2S flag is set or not. - * @param __HANDLE__ specifies the I2S Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2S_FLAG_RXNE: Receive buffer not empty flag - * @arg I2S_FLAG_TXE: Transmit buffer empty flag - * @arg I2S_FLAG_UDR: Underrun flag - * @arg I2S_FLAG_OVR: Overrun flag - * @arg I2S_FLAG_FRE: Frame error flag - * @arg I2S_FLAG_CHSIDE: Channel Side flag - * @arg I2S_FLAG_BSY: Busy flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_I2S_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clears the I2S OVR pending flag. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_CLEAR_OVRFLAG(__HANDLE__) do{ \ - __IO uint32_t tmpreg_ovr = 0x00U; \ - tmpreg_ovr = (__HANDLE__)->Instance->DR; \ - tmpreg_ovr = (__HANDLE__)->Instance->SR; \ - UNUSED(tmpreg_ovr); \ - }while(0U) -/** @brief Clears the I2S UDR pending flag. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_CLEAR_UDRFLAG(__HANDLE__) do{\ - __IO uint32_t tmpreg_udr = 0x00U;\ - tmpreg_udr = ((__HANDLE__)->Instance->SR);\ - UNUSED(tmpreg_udr); \ - }while(0U) -/** @brief Flush the I2S DR Register. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_FLUSH_RX_DR(__HANDLE__) do{\ - __IO uint32_t tmpreg_dr = 0x00U;\ - tmpreg_dr = ((__HANDLE__)->Instance->DR);\ - UNUSED(tmpreg_dr); \ - }while(0U) -/** - * @} - */ - -/* Include I2S Extension module */ -#include "stm32f4xx_hal_i2s_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2S_Exported_Functions - * @{ - */ - -/** @addtogroup I2S_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_I2S_Init(I2S_HandleTypeDef *hi2s); -HAL_StatusTypeDef HAL_I2S_DeInit(I2S_HandleTypeDef *hi2s); -void HAL_I2S_MspInit(I2S_HandleTypeDef *hi2s); -void HAL_I2S_MspDeInit(I2S_HandleTypeDef *hi2s); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -HAL_StatusTypeDef HAL_I2S_RegisterCallback(I2S_HandleTypeDef *hi2s, HAL_I2S_CallbackIDTypeDef CallbackID, - pI2S_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_I2S_UnRegisterCallback(I2S_HandleTypeDef *hi2s, HAL_I2S_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup I2S_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_I2S_Transmit(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2S_Receive(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_I2S_Transmit_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2S_Receive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size); -void HAL_I2S_IRQHandler(I2S_HandleTypeDef *hi2s); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_I2S_Transmit_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2S_Receive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_I2S_DMAPause(I2S_HandleTypeDef *hi2s); -HAL_StatusTypeDef HAL_I2S_DMAResume(I2S_HandleTypeDef *hi2s); -HAL_StatusTypeDef HAL_I2S_DMAStop(I2S_HandleTypeDef *hi2s); - -/* Callbacks used in non blocking modes (Interrupt and DMA) *******************/ -void HAL_I2S_TxHalfCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2S_TxCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2S_RxHalfCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2S_RxCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2S_ErrorCallback(I2S_HandleTypeDef *hi2s); -/** - * @} - */ - -/** @addtogroup I2S_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control and State functions ************************************/ -HAL_I2S_StateTypeDef HAL_I2S_GetState(I2S_HandleTypeDef *hi2s); -uint32_t HAL_I2S_GetError(I2S_HandleTypeDef *hi2s); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2S_Private_Macros I2S Private Macros - * @{ - */ - -/** @brief Check whether the specified SPI flag is set or not. - * @param __SR__ copy of I2S SR register. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2S_FLAG_RXNE: Receive buffer not empty flag - * @arg I2S_FLAG_TXE: Transmit buffer empty flag - * @arg I2S_FLAG_UDR: Underrun error flag - * @arg I2S_FLAG_OVR: Overrun flag - * @arg I2S_FLAG_CHSIDE: Channel side flag - * @arg I2S_FLAG_BSY: Busy flag - * @retval SET or RESET. - */ -#define I2S_CHECK_FLAG(__SR__, __FLAG__) ((((__SR__)\ - & ((__FLAG__) & I2S_FLAG_MASK)) == ((__FLAG__) & I2S_FLAG_MASK)) ? SET : RESET) - -/** @brief Check whether the specified SPI Interrupt is set or not. - * @param __CR2__ copy of I2S CR2 register. - * @param __INTERRUPT__ specifies the SPI interrupt source to check. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval SET or RESET. - */ -#define I2S_CHECK_IT_SOURCE(__CR2__, __INTERRUPT__) ((((__CR2__)\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks if I2S Mode parameter is in allowed range. - * @param __MODE__ specifies the I2S Mode. - * This parameter can be a value of @ref I2S_Mode - * @retval None - */ -#define IS_I2S_MODE(__MODE__) (((__MODE__) == I2S_MODE_SLAVE_TX) || \ - ((__MODE__) == I2S_MODE_SLAVE_RX) || \ - ((__MODE__) == I2S_MODE_MASTER_TX) || \ - ((__MODE__) == I2S_MODE_MASTER_RX)) - -#define IS_I2S_STANDARD(__STANDARD__) (((__STANDARD__) == I2S_STANDARD_PHILIPS) || \ - ((__STANDARD__) == I2S_STANDARD_MSB) || \ - ((__STANDARD__) == I2S_STANDARD_LSB) || \ - ((__STANDARD__) == I2S_STANDARD_PCM_SHORT) || \ - ((__STANDARD__) == I2S_STANDARD_PCM_LONG)) - -#define IS_I2S_DATA_FORMAT(__FORMAT__) (((__FORMAT__) == I2S_DATAFORMAT_16B) || \ - ((__FORMAT__) == I2S_DATAFORMAT_16B_EXTENDED) || \ - ((__FORMAT__) == I2S_DATAFORMAT_24B) || \ - ((__FORMAT__) == I2S_DATAFORMAT_32B)) - -#define IS_I2S_MCLK_OUTPUT(__OUTPUT__) (((__OUTPUT__) == I2S_MCLKOUTPUT_ENABLE) || \ - ((__OUTPUT__) == I2S_MCLKOUTPUT_DISABLE)) - -#define IS_I2S_AUDIO_FREQ(__FREQ__) ((((__FREQ__) >= I2S_AUDIOFREQ_8K) && \ - ((__FREQ__) <= I2S_AUDIOFREQ_192K)) || \ - ((__FREQ__) == I2S_AUDIOFREQ_DEFAULT)) - -#define IS_I2S_FULLDUPLEX_MODE(MODE) (((MODE) == I2S_FULLDUPLEXMODE_DISABLE) || \ - ((MODE) == I2S_FULLDUPLEXMODE_ENABLE)) - -/** @brief Checks if I2S Serial clock steady state parameter is in allowed range. - * @param __CPOL__ specifies the I2S serial clock steady state. - * This parameter can be a value of @ref I2S_Clock_Polarity - * @retval None - */ -#define IS_I2S_CPOL(__CPOL__) (((__CPOL__) == I2S_CPOL_LOW) || \ - ((__CPOL__) == I2S_CPOL_HIGH)) - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_I2S_CLOCKSOURCE(CLOCK) (((CLOCK) == I2S_CLOCK_EXTERNAL) ||\ - ((CLOCK) == I2S_CLOCK_PLL)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined (STM32F413xx) || defined(STM32F423xx) -#define IS_I2S_CLOCKSOURCE(CLOCK) (((CLOCK) == I2S_CLOCK_EXTERNAL) ||\ - ((CLOCK) == I2S_CLOCK_PLL) ||\ - ((CLOCK) == I2S_CLOCK_PLLSRC) ||\ - ((CLOCK) == I2S_CLOCK_PLLR)) -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_I2S_CLOCKSOURCE(CLOCK) (((CLOCK) == I2S_CLOCK_EXTERNAL) ||\ - ((CLOCK) == I2S_CLOCK_PLLSRC) ||\ - ((CLOCK) == I2S_CLOCK_PLLR)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_I2S_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s_ex.h deleted file mode 100644 index 10335f49f4dba6b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s_ex.h +++ /dev/null @@ -1,185 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2s_ex.h - * @author MCD Application Team - * @brief Header file of I2S HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_I2S_EX_H -#define STM32F4xx_HAL_I2S_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined(SPI_I2S_FULLDUPLEX_SUPPORT) -/** @addtogroup I2SEx I2SEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup I2SEx_Exported_Macros I2S Extended Exported Macros - * @{ - */ - -#define I2SxEXT(__INSTANCE__) ((__INSTANCE__) == (SPI2)? (SPI_TypeDef *)(I2S2ext_BASE): (SPI_TypeDef *)(I2S3ext_BASE)) - -/** @brief Enable or disable the specified I2SExt peripheral. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2SEXT_ENABLE(__HANDLE__) (I2SxEXT((__HANDLE__)->Instance)->I2SCFGR |= SPI_I2SCFGR_I2SE) -#define __HAL_I2SEXT_DISABLE(__HANDLE__) (I2SxEXT((__HANDLE__)->Instance)->I2SCFGR &= ~SPI_I2SCFGR_I2SE) - -/** @brief Enable or disable the specified I2SExt interrupts. - * @param __HANDLE__ specifies the I2S Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2SEXT_ENABLE_IT(__HANDLE__, __INTERRUPT__) (I2SxEXT((__HANDLE__)->Instance)->CR2 |= (__INTERRUPT__)) -#define __HAL_I2SEXT_DISABLE_IT(__HANDLE__, __INTERRUPT__) (I2SxEXT((__HANDLE__)->Instance)->CR2 &= ~(__INTERRUPT__)) - -/** @brief Checks if the specified I2SExt interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the I2S Handle. - * This parameter can be I2S where x: 1, 2, or 3 to select the I2S peripheral. - * @param __INTERRUPT__ specifies the I2S interrupt source to check. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_I2SEXT_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((I2SxEXT((__HANDLE__)->Instance)->CR2\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified I2SExt flag is set or not. - * @param __HANDLE__ specifies the I2S Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2S_FLAG_RXNE: Receive buffer not empty flag - * @arg I2S_FLAG_TXE: Transmit buffer empty flag - * @arg I2S_FLAG_UDR: Underrun flag - * @arg I2S_FLAG_OVR: Overrun flag - * @arg I2S_FLAG_FRE: Frame error flag - * @arg I2S_FLAG_CHSIDE: Channel Side flag - * @arg I2S_FLAG_BSY: Busy flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_I2SEXT_GET_FLAG(__HANDLE__, __FLAG__) (((I2SxEXT((__HANDLE__)->Instance)->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clears the I2SExt OVR pending flag. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2SEXT_CLEAR_OVRFLAG(__HANDLE__) do{ \ - __IO uint32_t tmpreg_ovr = 0x00U; \ - tmpreg_ovr = I2SxEXT((__HANDLE__)->Instance)->DR;\ - tmpreg_ovr = I2SxEXT((__HANDLE__)->Instance)->SR;\ - UNUSED(tmpreg_ovr); \ - }while(0U) -/** @brief Clears the I2SExt UDR pending flag. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2SEXT_CLEAR_UDRFLAG(__HANDLE__) do{ \ - __IO uint32_t tmpreg_udr = 0x00U; \ - tmpreg_udr = I2SxEXT((__HANDLE__)->Instance)->SR;\ - UNUSED(tmpreg_udr); \ - }while(0U) -/** @brief Flush the I2S and I2SExt DR Registers. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2SEXT_FLUSH_RX_DR(__HANDLE__) do{ \ - __IO uint32_t tmpreg_dr = 0x00U; \ - tmpreg_dr = I2SxEXT((__HANDLE__)->Instance)->DR; \ - tmpreg_dr = ((__HANDLE__)->Instance->DR); \ - UNUSED(tmpreg_dr); \ - }while(0U) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2SEx_Exported_Functions I2S Extended Exported Functions - * @{ - */ - -/** @addtogroup I2SEx_Exported_Functions_Group1 I2S Extended IO operation functions - * @{ - */ - -/* Extended features functions *************************************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive(I2S_HandleTypeDef *hi2s, uint16_t *pTxData, uint16_t *pRxData, - uint16_t Size, uint32_t Timeout); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pTxData, uint16_t *pRxData, - uint16_t Size); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pTxData, uint16_t *pRxData, - uint16_t Size); -/* I2S IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_I2SEx_FullDuplex_IRQHandler(I2S_HandleTypeDef *hi2s); -void HAL_I2SEx_TxRxHalfCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2SEx_TxRxCpltCallback(I2S_HandleTypeDef *hi2s); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ - -/** - * @} - */ - -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_I2S_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_irda.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_irda.h deleted file mode 100644 index 4d83abc22d09315..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_irda.h +++ /dev/null @@ -1,684 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_irda.h - * @author MCD Application Team - * @brief Header file of IRDA HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_IRDA_H -#define __STM32F4xx_HAL_IRDA_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup IRDA - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup IRDA_Exported_Types IRDA Exported Types - * @{ - */ -/** - * @brief IRDA Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the IRDA communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (8 * (hirda->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8) + 0.5 */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref IRDA_Word_Length */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref IRDA_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits). */ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref IRDA_Mode */ - - uint8_t Prescaler; /*!< Specifies the Prescaler value to be programmed - in the IrDA low-power Baud Register, for defining pulse width on which - burst acceptance/rejection will be decided. This value is used as divisor - of system clock to achieve required pulse width. */ - - uint32_t IrDAMode; /*!< Specifies the IrDA mode - This parameter can be a value of @ref IRDA_Low_Power */ -} IRDA_InitTypeDef; - -/** - * @brief HAL IRDA State structures definition - * @note HAL IRDA State value is a combination of 2 different substates: gState and RxState. - * - gState contains IRDA state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : (Not Used) - * 10 : Timeout - * 11 : Error - * b5 IP initialisation status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized. HAL IRDA Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (IP busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 IP initialisation status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef enum -{ - HAL_IRDA_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ - HAL_IRDA_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ - HAL_IRDA_STATE_BUSY = 0x24U, /*!< An internal process is ongoing - Value is allowed for gState only */ - HAL_IRDA_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing - Value is allowed for gState only */ - HAL_IRDA_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing - Value is allowed for RxState only */ - HAL_IRDA_STATE_BUSY_TX_RX = 0x23U, /*!< Data Transmission and Reception process is ongoing - Not to be used for neither gState nor RxState. - Value is result of combination (Or) between gState and RxState values */ - HAL_IRDA_STATE_TIMEOUT = 0xA0U, /*!< Timeout state - Value is allowed for gState only */ - HAL_IRDA_STATE_ERROR = 0xE0U /*!< Error - Value is allowed for gState only */ -} HAL_IRDA_StateTypeDef; - -/** - * @brief IRDA handle Structure definition - */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -typedef struct __IRDA_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ -{ - USART_TypeDef *Instance; /*!< USART registers base address */ - - IRDA_InitTypeDef Init; /*!< IRDA communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to IRDA Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< IRDA Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< IRDA Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to IRDA Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< IRDA Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< IRDA Rx Transfer Counter */ - - DMA_HandleTypeDef *hdmatx; /*!< IRDA Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< IRDA Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_IRDA_StateTypeDef gState; /*!< IRDA state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_IRDA_StateTypeDef */ - - __IO HAL_IRDA_StateTypeDef RxState; /*!< IRDA state information related to Rx operations. - This parameter can be a value of @ref HAL_IRDA_StateTypeDef */ - - __IO uint32_t ErrorCode; /*!< IRDA Error code */ - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - void (* TxHalfCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Tx Half Complete Callback */ - - void (* TxCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Tx Complete Callback */ - - void (* RxHalfCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Rx Half Complete Callback */ - - void (* RxCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Rx Complete Callback */ - - void (* ErrorCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Error Callback */ - - void (* AbortCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Abort Complete Callback */ - - void (* AbortTransmitCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Abort Transmit Complete Callback */ - - void (* AbortReceiveCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Abort Receive Complete Callback */ - - - void (* MspInitCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Msp Init callback */ - - void (* MspDeInitCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Msp DeInit callback */ -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - -} IRDA_HandleTypeDef; - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -/** - * @brief HAL IRDA Callback ID enumeration definition - */ -typedef enum -{ - HAL_IRDA_TX_HALFCOMPLETE_CB_ID = 0x00U, /*!< IRDA Tx Half Complete Callback ID */ - HAL_IRDA_TX_COMPLETE_CB_ID = 0x01U, /*!< IRDA Tx Complete Callback ID */ - HAL_IRDA_RX_HALFCOMPLETE_CB_ID = 0x02U, /*!< IRDA Rx Half Complete Callback ID */ - HAL_IRDA_RX_COMPLETE_CB_ID = 0x03U, /*!< IRDA Rx Complete Callback ID */ - HAL_IRDA_ERROR_CB_ID = 0x04U, /*!< IRDA Error Callback ID */ - HAL_IRDA_ABORT_COMPLETE_CB_ID = 0x05U, /*!< IRDA Abort Complete Callback ID */ - HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID = 0x06U, /*!< IRDA Abort Transmit Complete Callback ID */ - HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID = 0x07U, /*!< IRDA Abort Receive Complete Callback ID */ - - HAL_IRDA_MSPINIT_CB_ID = 0x08U, /*!< IRDA MspInit callback ID */ - HAL_IRDA_MSPDEINIT_CB_ID = 0x09U /*!< IRDA MspDeInit callback ID */ - -} HAL_IRDA_CallbackIDTypeDef; - -/** - * @brief HAL IRDA Callback pointer definition - */ -typedef void (*pIRDA_CallbackTypeDef)(IRDA_HandleTypeDef *hirda); /*!< pointer to an IRDA callback function */ - -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup IRDA_Exported_Constants IRDA Exported constants - * @{ - */ -/** @defgroup IRDA_Error_Code IRDA Error Code - * @{ - */ -#define HAL_IRDA_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_IRDA_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_IRDA_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_IRDA_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_IRDA_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_IRDA_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -#define HAL_IRDA_ERROR_INVALID_CALLBACK ((uint32_t)0x00000020U) /*!< Invalid Callback error */ -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup IRDA_Word_Length IRDA Word Length - * @{ - */ -#define IRDA_WORDLENGTH_8B 0x00000000U -#define IRDA_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup IRDA_Parity IRDA Parity - * @{ - */ -#define IRDA_PARITY_NONE 0x00000000U -#define IRDA_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define IRDA_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup IRDA_Mode IRDA Transfer Mode - * @{ - */ -#define IRDA_MODE_RX ((uint32_t)USART_CR1_RE) -#define IRDA_MODE_TX ((uint32_t)USART_CR1_TE) -#define IRDA_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup IRDA_Low_Power IRDA Low Power - * @{ - */ -#define IRDA_POWERMODE_LOWPOWER ((uint32_t)USART_CR3_IRLP) -#define IRDA_POWERMODE_NORMAL 0x00000000U -/** - * @} - */ - -/** @defgroup IRDA_Flags IRDA Flags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define IRDA_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define IRDA_FLAG_TC ((uint32_t)USART_SR_TC) -#define IRDA_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define IRDA_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define IRDA_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define IRDA_FLAG_NE ((uint32_t)USART_SR_NE) -#define IRDA_FLAG_FE ((uint32_t)USART_SR_FE) -#define IRDA_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup IRDA_Interrupt_definition IRDA Interrupt Definitions - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask in the XX register - * - Y : Interrupt source register (2bits) - * - 01: CR1 register - * - 10: CR2 register - * - 11: CR3 register - * @{ - */ -#define IRDA_IT_PE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define IRDA_IT_TXE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define IRDA_IT_TC ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define IRDA_IT_RXNE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define IRDA_IT_IDLE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) - -#define IRDA_IT_LBD ((uint32_t)(IRDA_CR2_REG_INDEX << 28U | USART_CR2_LBDIE)) - -#define IRDA_IT_CTS ((uint32_t)(IRDA_CR3_REG_INDEX << 28U | USART_CR3_CTSIE)) -#define IRDA_IT_ERR ((uint32_t)(IRDA_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup IRDA_Exported_Macros IRDA Exported Macros - * @{ - */ - -/** @brief Reset IRDA handle gstate & RxState - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#if USE_HAL_IRDA_REGISTER_CALLBACKS == 1 -#define __HAL_IRDA_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_IRDA_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_IRDA_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_IRDA_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_IRDA_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_IRDA_STATE_RESET; \ - } while(0U) -#endif /*USE_HAL_IRDA_REGISTER_CALLBACKS */ - -/** @brief Flush the IRDA DR register - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) - -/** @brief Check whether the specified IRDA flag is set or not. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg IRDA_FLAG_TXE: Transmit data register empty flag - * @arg IRDA_FLAG_TC: Transmission Complete flag - * @arg IRDA_FLAG_RXNE: Receive data register not empty flag - * @arg IRDA_FLAG_IDLE: Idle Line detection flag - * @arg IRDA_FLAG_ORE: OverRun Error flag - * @arg IRDA_FLAG_NE: Noise Error flag - * @arg IRDA_FLAG_FE: Framing Error flag - * @arg IRDA_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_IRDA_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified IRDA pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg IRDA_FLAG_TC: Transmission Complete flag. - * @arg IRDA_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun - * error) and IDLE (Idle line detected) flags are cleared by software - * sequence: a read operation to USART_SR register followed by a read - * operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * @retval None - */ -#define __HAL_IRDA_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clear the IRDA PE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clear the IRDA FE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_FEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the IRDA NE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_NEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the IRDA ORE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_OREFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the IRDA IDLE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_IDLEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enable the specified IRDA interrupt. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the IRDA interrupt source to enable. - * This parameter can be one of the following values: - * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt - * @arg IRDA_IT_TC: Transmission complete interrupt - * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt - * @arg IRDA_IT_IDLE: Idle line detection interrupt - * @arg IRDA_IT_PE: Parity Error interrupt - * @arg IRDA_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_IRDA_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == IRDA_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & IRDA_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == IRDA_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & IRDA_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & IRDA_IT_MASK))) -/** @brief Disable the specified IRDA interrupt. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the IRDA interrupt source to disable. - * This parameter can be one of the following values: - * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt - * @arg IRDA_IT_TC: Transmission complete interrupt - * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt - * @arg IRDA_IT_IDLE: Idle line detection interrupt - * @arg IRDA_IT_PE: Parity Error interrupt - * @arg IRDA_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_IRDA_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == IRDA_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & IRDA_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == IRDA_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & IRDA_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & IRDA_IT_MASK))) - -/** @brief Check whether the specified IRDA interrupt has occurred or not. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __IT__ specifies the IRDA interrupt source to check. - * This parameter can be one of the following values: - * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt - * @arg IRDA_IT_TC: Transmission complete interrupt - * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt - * @arg IRDA_IT_IDLE: Idle line detection interrupt - * @arg IRDA_IT_ERR: Error interrupt - * @arg IRDA_IT_PE: Parity Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_IRDA_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == IRDA_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == IRDA_CR2_REG_INDEX)? \ - (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & IRDA_IT_MASK)) - -/** @brief Macro to enable the IRDA's one bit sample method - * @param __HANDLE__ specifies the IRDA Handle. - * @retval None - */ -#define __HAL_IRDA_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 |= USART_CR3_ONEBIT) - -/** @brief Macro to disable the IRDA's one bit sample method - * @param __HANDLE__ specifies the IRDA Handle. - * @retval None - */ -#define __HAL_IRDA_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable UART/USART associated to IRDA Handle - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR1, USART_CR1_UE)) - -/** @brief Disable UART/USART associated to IRDA Handle - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, USART_CR1_UE)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup IRDA_Exported_Functions - * @{ - */ - -/** @addtogroup IRDA_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_IRDA_Init(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_DeInit(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_MspInit(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_MspDeInit(IRDA_HandleTypeDef *hirda); - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_IRDA_RegisterCallback(IRDA_HandleTypeDef *hirda, HAL_IRDA_CallbackIDTypeDef CallbackID, pIRDA_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_IRDA_UnRegisterCallback(IRDA_HandleTypeDef *hirda, HAL_IRDA_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup IRDA_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_IRDA_Transmit(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_IRDA_Receive(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_IRDA_Receive_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_IRDA_Transmit_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_IRDA_Receive_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_IRDA_DMAPause(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_DMAResume(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_DMAStop(IRDA_HandleTypeDef *hirda); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_IRDA_Abort(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_AbortTransmit(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_AbortReceive(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_Abort_IT(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_AbortTransmit_IT(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_AbortReceive_IT(IRDA_HandleTypeDef *hirda); - -void HAL_IRDA_IRQHandler(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_TxCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_RxCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_TxHalfCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_RxHalfCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_ErrorCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_AbortCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_AbortTransmitCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_AbortReceiveCpltCallback(IRDA_HandleTypeDef *hirda); -/** - * @} - */ - -/** @addtogroup IRDA_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions **************************************************/ -HAL_IRDA_StateTypeDef HAL_IRDA_GetState(IRDA_HandleTypeDef *hirda); -uint32_t HAL_IRDA_GetError(IRDA_HandleTypeDef *hirda); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup IRDA_Private_Constants IRDA Private Constants - * @{ - */ - -/** @brief IRDA interruptions flag mask - * - */ -#define IRDA_IT_MASK ((uint32_t) USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RXNEIE | \ - USART_CR1_IDLEIE | USART_CR2_LBDIE | USART_CR3_CTSIE | USART_CR3_EIE ) - -#define IRDA_CR1_REG_INDEX 1U -#define IRDA_CR2_REG_INDEX 2U -#define IRDA_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros --------------------------------------------------------*/ -/** @defgroup IRDA_Private_Macros IRDA Private Macros - * @{ - */ -#define IS_IRDA_WORD_LENGTH(LENGTH) (((LENGTH) == IRDA_WORDLENGTH_8B) || \ - ((LENGTH) == IRDA_WORDLENGTH_9B)) - -#define IS_IRDA_PARITY(PARITY) (((PARITY) == IRDA_PARITY_NONE) || \ - ((PARITY) == IRDA_PARITY_EVEN) || \ - ((PARITY) == IRDA_PARITY_ODD)) - -#define IS_IRDA_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x00000000U)) - -#define IS_IRDA_POWERMODE(MODE) (((MODE) == IRDA_POWERMODE_LOWPOWER) || \ - ((MODE) == IRDA_POWERMODE_NORMAL)) - -#define IS_IRDA_BAUDRATE(BAUDRATE) ((BAUDRATE) < 115201U) - -#define IRDA_DIV(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(4U*(((uint64_t)(_BAUD_)))))) - -#define IRDA_DIVMANT(_PCLK_, _BAUD_) (IRDA_DIV((_PCLK_), (_BAUD_))/100U) - -#define IRDA_DIVFRAQ(_PCLK_, _BAUD_) ((((IRDA_DIV((_PCLK_), (_BAUD_)) - (IRDA_DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) - -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + (UART DIVFRAQ & 0xF0) + (UART DIVFRAQ & 0x0FU) */ -#define IRDA_BRR(_PCLK_, _BAUD_) (((IRDA_DIVMANT((_PCLK_), (_BAUD_)) << 4U) + \ - (IRDA_DIVFRAQ((_PCLK_), (_BAUD_)) & 0xF0U)) + \ - (IRDA_DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup IRDA_Private_Functions IRDA Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_IRDA_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h deleted file mode 100644 index 32f5ff027ae8dd5..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h +++ /dev/null @@ -1,223 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_iwdg.h - * @author MCD Application Team - * @brief Header file of IWDG HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_IWDG_H -#define STM32F4xx_HAL_IWDG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup IWDG IWDG - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup IWDG_Exported_Types IWDG Exported Types - * @{ - */ - -/** - * @brief IWDG Init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Select the prescaler of the IWDG. - This parameter can be a value of @ref IWDG_Prescaler */ - - uint32_t Reload; /*!< Specifies the IWDG down-counter reload value. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x0FFF */ - -} IWDG_InitTypeDef; - -/** - * @brief IWDG Handle Structure definition - */ -typedef struct -{ - IWDG_TypeDef *Instance; /*!< Register base address */ - - IWDG_InitTypeDef Init; /*!< IWDG required parameters */ -} IWDG_HandleTypeDef; - - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup IWDG_Exported_Constants IWDG Exported Constants - * @{ - */ - -/** @defgroup IWDG_Prescaler IWDG Prescaler - * @{ - */ -#define IWDG_PRESCALER_4 0x00000000u /*!< IWDG prescaler set to 4 */ -#define IWDG_PRESCALER_8 IWDG_PR_PR_0 /*!< IWDG prescaler set to 8 */ -#define IWDG_PRESCALER_16 IWDG_PR_PR_1 /*!< IWDG prescaler set to 16 */ -#define IWDG_PRESCALER_32 (IWDG_PR_PR_1 | IWDG_PR_PR_0) /*!< IWDG prescaler set to 32 */ -#define IWDG_PRESCALER_64 IWDG_PR_PR_2 /*!< IWDG prescaler set to 64 */ -#define IWDG_PRESCALER_128 (IWDG_PR_PR_2 | IWDG_PR_PR_0) /*!< IWDG prescaler set to 128 */ -#define IWDG_PRESCALER_256 (IWDG_PR_PR_2 | IWDG_PR_PR_1) /*!< IWDG prescaler set to 256 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup IWDG_Exported_Macros IWDG Exported Macros - * @{ - */ - -/** - * @brief Enable the IWDG peripheral. - * @param __HANDLE__ IWDG handle - * @retval None - */ -#define __HAL_IWDG_START(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_ENABLE) - -/** - * @brief Reload IWDG counter with value defined in the reload register - * (write access to IWDG_PR and IWDG_RLR registers disabled). - * @param __HANDLE__ IWDG handle - * @retval None - */ -#define __HAL_IWDG_RELOAD_COUNTER(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_RELOAD) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup IWDG_Exported_Functions IWDG Exported Functions - * @{ - */ - -/** @defgroup IWDG_Exported_Functions_Group1 Initialization and Start functions - * @{ - */ -/* Initialization/Start functions ********************************************/ -HAL_StatusTypeDef HAL_IWDG_Init(IWDG_HandleTypeDef *hiwdg); -/** - * @} - */ - -/** @defgroup IWDG_Exported_Functions_Group2 IO operation functions - * @{ - */ -/* I/O operation functions ****************************************************/ -HAL_StatusTypeDef HAL_IWDG_Refresh(IWDG_HandleTypeDef *hiwdg); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup IWDG_Private_Constants IWDG Private Constants - * @{ - */ - -/** - * @brief IWDG Key Register BitMask - */ -#define IWDG_KEY_RELOAD 0x0000AAAAu /*!< IWDG Reload Counter Enable */ -#define IWDG_KEY_ENABLE 0x0000CCCCu /*!< IWDG Peripheral Enable */ -#define IWDG_KEY_WRITE_ACCESS_ENABLE 0x00005555u /*!< IWDG KR Write Access Enable */ -#define IWDG_KEY_WRITE_ACCESS_DISABLE 0x00000000u /*!< IWDG KR Write Access Disable */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup IWDG_Private_Macros IWDG Private Macros - * @{ - */ - -/** - * @brief Enable write access to IWDG_PR and IWDG_RLR registers. - * @param __HANDLE__ IWDG handle - * @retval None - */ -#define IWDG_ENABLE_WRITE_ACCESS(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_WRITE_ACCESS_ENABLE) - -/** - * @brief Disable write access to IWDG_PR and IWDG_RLR registers. - * @param __HANDLE__ IWDG handle - * @retval None - */ -#define IWDG_DISABLE_WRITE_ACCESS(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_WRITE_ACCESS_DISABLE) - -/** - * @brief Check IWDG prescaler value. - * @param __PRESCALER__ IWDG prescaler value - * @retval None - */ -#define IS_IWDG_PRESCALER(__PRESCALER__) (((__PRESCALER__) == IWDG_PRESCALER_4) || \ - ((__PRESCALER__) == IWDG_PRESCALER_8) || \ - ((__PRESCALER__) == IWDG_PRESCALER_16) || \ - ((__PRESCALER__) == IWDG_PRESCALER_32) || \ - ((__PRESCALER__) == IWDG_PRESCALER_64) || \ - ((__PRESCALER__) == IWDG_PRESCALER_128)|| \ - ((__PRESCALER__) == IWDG_PRESCALER_256)) - -/** - * @brief Check IWDG reload value. - * @param __RELOAD__ IWDG reload value - * @retval None - */ -#define IS_IWDG_RELOAD(__RELOAD__) ((__RELOAD__) <= IWDG_RLR_RL) - - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_IWDG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_lptim.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_lptim.h deleted file mode 100644 index 80ea203720e2054..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_lptim.h +++ /dev/null @@ -1,858 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_lptim.h - * @author MCD Application Team - * @brief Header file of LPTIM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_LPTIM_H -#define STM32F4xx_HAL_LPTIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (LPTIM1) - -/** @addtogroup LPTIM - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup LPTIM_Exported_Types LPTIM Exported Types - * @{ - */ -#define LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT EXTI_IMR_MR23 /*!< External interrupt line 23 Connected to the LPTIM EXTI Line */ - -/** - * @brief LPTIM Clock configuration definition - */ -typedef struct -{ - uint32_t Source; /*!< Selects the clock source. - This parameter can be a value of @ref LPTIM_Clock_Source */ - - uint32_t Prescaler; /*!< Specifies the counter clock Prescaler. - This parameter can be a value of @ref LPTIM_Clock_Prescaler */ - -} LPTIM_ClockConfigTypeDef; - -/** - * @brief LPTIM Clock configuration definition - */ -typedef struct -{ - uint32_t Polarity; /*!< Selects the polarity of the active edge for the counter unit - if the ULPTIM input is selected. - Note: This parameter is used only when Ultra low power clock source is used. - Note: If the polarity is configured on 'both edges', an auxiliary clock - (one of the Low power oscillator) must be active. - This parameter can be a value of @ref LPTIM_Clock_Polarity */ - - uint32_t SampleTime; /*!< Selects the clock sampling time to configure the clock glitch filter. - Note: This parameter is used only when Ultra low power clock source is used. - This parameter can be a value of @ref LPTIM_Clock_Sample_Time */ - -} LPTIM_ULPClockConfigTypeDef; - -/** - * @brief LPTIM Trigger configuration definition - */ -typedef struct -{ - uint32_t Source; /*!< Selects the Trigger source. - This parameter can be a value of @ref LPTIM_Trigger_Source */ - - uint32_t ActiveEdge; /*!< Selects the Trigger active edge. - Note: This parameter is used only when an external trigger is used. - This parameter can be a value of @ref LPTIM_External_Trigger_Polarity */ - - uint32_t SampleTime; /*!< Selects the trigger sampling time to configure the clock glitch filter. - Note: This parameter is used only when an external trigger is used. - This parameter can be a value of @ref LPTIM_Trigger_Sample_Time */ -} LPTIM_TriggerConfigTypeDef; - -/** - * @brief LPTIM Initialization Structure definition - */ -typedef struct -{ - LPTIM_ClockConfigTypeDef Clock; /*!< Specifies the clock parameters */ - - LPTIM_ULPClockConfigTypeDef UltraLowPowerClock;/*!< Specifies the Ultra Low Power clock parameters */ - - LPTIM_TriggerConfigTypeDef Trigger; /*!< Specifies the Trigger parameters */ - - uint32_t OutputPolarity; /*!< Specifies the Output polarity. - This parameter can be a value of @ref LPTIM_Output_Polarity */ - - uint32_t UpdateMode; /*!< Specifies whether the update of the autoreload and the compare - values is done immediately or after the end of current period. - This parameter can be a value of @ref LPTIM_Updating_Mode */ - - uint32_t CounterSource; /*!< Specifies whether the counter is incremented each internal event - or each external event. - This parameter can be a value of @ref LPTIM_Counter_Source */ -} LPTIM_InitTypeDef; - -/** - * @brief HAL LPTIM State structure definition - */ -typedef enum -{ - HAL_LPTIM_STATE_RESET = 0x00U, /*!< Peripheral not yet initialized or disabled */ - HAL_LPTIM_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_LPTIM_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */ - HAL_LPTIM_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_LPTIM_STATE_ERROR = 0x04U /*!< Internal Process is ongoing */ -} HAL_LPTIM_StateTypeDef; - -/** - * @brief LPTIM handle Structure definition - */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -typedef struct __LPTIM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -{ - LPTIM_TypeDef *Instance; /*!< Register base address */ - - LPTIM_InitTypeDef Init; /*!< LPTIM required parameters */ - - HAL_StatusTypeDef Status; /*!< LPTIM peripheral status */ - - HAL_LockTypeDef Lock; /*!< LPTIM locking object */ - - __IO HAL_LPTIM_StateTypeDef State; /*!< LPTIM peripheral state */ - -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - void (* MspInitCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< LPTIM Base Msp Init Callback */ - void (* MspDeInitCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< LPTIM Base Msp DeInit Callback */ - void (* CompareMatchCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Compare match Callback */ - void (* AutoReloadMatchCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Auto-reload match Callback */ - void (* TriggerCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< External trigger event detection Callback */ - void (* CompareWriteCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Compare register write complete Callback */ - void (* AutoReloadWriteCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Auto-reload register write complete Callback */ - void (* DirectionUpCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Up-counting direction change Callback */ - void (* DirectionDownCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Down-counting direction change Callback */ -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -} LPTIM_HandleTypeDef; - -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL LPTIM Callback ID enumeration definition - */ -typedef enum -{ - HAL_LPTIM_MSPINIT_CB_ID = 0x00U, /*!< LPTIM Base Msp Init Callback ID */ - HAL_LPTIM_MSPDEINIT_CB_ID = 0x01U, /*!< LPTIM Base Msp DeInit Callback ID */ - HAL_LPTIM_COMPARE_MATCH_CB_ID = 0x02U, /*!< Compare match Callback ID */ - HAL_LPTIM_AUTORELOAD_MATCH_CB_ID = 0x03U, /*!< Auto-reload match Callback ID */ - HAL_LPTIM_TRIGGER_CB_ID = 0x04U, /*!< External trigger event detection Callback ID */ - HAL_LPTIM_COMPARE_WRITE_CB_ID = 0x05U, /*!< Compare register write complete Callback ID */ - HAL_LPTIM_AUTORELOAD_WRITE_CB_ID = 0x06U, /*!< Auto-reload register write complete Callback ID */ - HAL_LPTIM_DIRECTION_UP_CB_ID = 0x07U, /*!< Up-counting direction change Callback ID */ - HAL_LPTIM_DIRECTION_DOWN_CB_ID = 0x08U, /*!< Down-counting direction change Callback ID */ -} HAL_LPTIM_CallbackIDTypeDef; - -/** - * @brief HAL TIM Callback pointer definition - */ -typedef void (*pLPTIM_CallbackTypeDef)(LPTIM_HandleTypeDef *hlptim); /*!< pointer to the LPTIM callback function */ - -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup LPTIM_Exported_Constants LPTIM Exported Constants - * @{ - */ - -/** @defgroup LPTIM_Clock_Source LPTIM Clock Source - * @{ - */ -#define LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC 0x00000000U -#define LPTIM_CLOCKSOURCE_ULPTIM LPTIM_CFGR_CKSEL -/** - * @} - */ - -/** @defgroup LPTIM_Clock_Prescaler LPTIM Clock Prescaler - * @{ - */ -#define LPTIM_PRESCALER_DIV1 0x00000000U -#define LPTIM_PRESCALER_DIV2 LPTIM_CFGR_PRESC_0 -#define LPTIM_PRESCALER_DIV4 LPTIM_CFGR_PRESC_1 -#define LPTIM_PRESCALER_DIV8 (LPTIM_CFGR_PRESC_0 | LPTIM_CFGR_PRESC_1) -#define LPTIM_PRESCALER_DIV16 LPTIM_CFGR_PRESC_2 -#define LPTIM_PRESCALER_DIV32 (LPTIM_CFGR_PRESC_0 | LPTIM_CFGR_PRESC_2) -#define LPTIM_PRESCALER_DIV64 (LPTIM_CFGR_PRESC_1 | LPTIM_CFGR_PRESC_2) -#define LPTIM_PRESCALER_DIV128 LPTIM_CFGR_PRESC -/** - * @} - */ - -/** @defgroup LPTIM_Output_Polarity LPTIM Output Polarity - * @{ - */ - -#define LPTIM_OUTPUTPOLARITY_HIGH 0x00000000U -#define LPTIM_OUTPUTPOLARITY_LOW LPTIM_CFGR_WAVPOL -/** - * @} - */ - -/** @defgroup LPTIM_Clock_Sample_Time LPTIM Clock Sample Time - * @{ - */ -#define LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION 0x00000000U -#define LPTIM_CLOCKSAMPLETIME_2TRANSITIONS LPTIM_CFGR_CKFLT_0 -#define LPTIM_CLOCKSAMPLETIME_4TRANSITIONS LPTIM_CFGR_CKFLT_1 -#define LPTIM_CLOCKSAMPLETIME_8TRANSITIONS LPTIM_CFGR_CKFLT -/** - * @} - */ - -/** @defgroup LPTIM_Clock_Polarity LPTIM Clock Polarity - * @{ - */ -#define LPTIM_CLOCKPOLARITY_RISING 0x00000000U -#define LPTIM_CLOCKPOLARITY_FALLING LPTIM_CFGR_CKPOL_0 -#define LPTIM_CLOCKPOLARITY_RISING_FALLING LPTIM_CFGR_CKPOL_1 -/** - * @} - */ - -/** @defgroup LPTIM_Trigger_Source LPTIM Trigger Source - * @{ - */ -#define LPTIM_TRIGSOURCE_SOFTWARE 0x0000FFFFU -#define LPTIM_TRIGSOURCE_0 0x00000000U -#define LPTIM_TRIGSOURCE_1 LPTIM_CFGR_TRIGSEL_0 -#define LPTIM_TRIGSOURCE_2 LPTIM_CFGR_TRIGSEL_1 -#define LPTIM_TRIGSOURCE_3 (LPTIM_CFGR_TRIGSEL_0 | LPTIM_CFGR_TRIGSEL_1) -#define LPTIM_TRIGSOURCE_4 LPTIM_CFGR_TRIGSEL_2 -#define LPTIM_TRIGSOURCE_5 (LPTIM_CFGR_TRIGSEL_0 | LPTIM_CFGR_TRIGSEL_2) -/** - * @} - */ - -/** @defgroup LPTIM_External_Trigger_Polarity LPTIM External Trigger Polarity - * @{ - */ -#define LPTIM_ACTIVEEDGE_RISING LPTIM_CFGR_TRIGEN_0 -#define LPTIM_ACTIVEEDGE_FALLING LPTIM_CFGR_TRIGEN_1 -#define LPTIM_ACTIVEEDGE_RISING_FALLING LPTIM_CFGR_TRIGEN -/** - * @} - */ - -/** @defgroup LPTIM_Trigger_Sample_Time LPTIM Trigger Sample Time - * @{ - */ -#define LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION 0x00000000U -#define LPTIM_TRIGSAMPLETIME_2TRANSITIONS LPTIM_CFGR_TRGFLT_0 -#define LPTIM_TRIGSAMPLETIME_4TRANSITIONS LPTIM_CFGR_TRGFLT_1 -#define LPTIM_TRIGSAMPLETIME_8TRANSITIONS LPTIM_CFGR_TRGFLT -/** - * @} - */ - -/** @defgroup LPTIM_Updating_Mode LPTIM Updating Mode - * @{ - */ - -#define LPTIM_UPDATE_IMMEDIATE 0x00000000U -#define LPTIM_UPDATE_ENDOFPERIOD LPTIM_CFGR_PRELOAD -/** - * @} - */ - -/** @defgroup LPTIM_Counter_Source LPTIM Counter Source - * @{ - */ - -#define LPTIM_COUNTERSOURCE_INTERNAL 0x00000000U -#define LPTIM_COUNTERSOURCE_EXTERNAL LPTIM_CFGR_COUNTMODE -/** - * @} - */ - -/** @defgroup LPTIM_Flag_Definition LPTIM Flags Definition - * @{ - */ - -#define LPTIM_FLAG_DOWN LPTIM_ISR_DOWN -#define LPTIM_FLAG_UP LPTIM_ISR_UP -#define LPTIM_FLAG_ARROK LPTIM_ISR_ARROK -#define LPTIM_FLAG_CMPOK LPTIM_ISR_CMPOK -#define LPTIM_FLAG_EXTTRIG LPTIM_ISR_EXTTRIG -#define LPTIM_FLAG_ARRM LPTIM_ISR_ARRM -#define LPTIM_FLAG_CMPM LPTIM_ISR_CMPM -/** - * @} - */ - -/** @defgroup LPTIM_Interrupts_Definition LPTIM Interrupts Definition - * @{ - */ -#define LPTIM_IT_DOWN LPTIM_IER_DOWNIE -#define LPTIM_IT_UP LPTIM_IER_UPIE -#define LPTIM_IT_ARROK LPTIM_IER_ARROKIE -#define LPTIM_IT_CMPOK LPTIM_IER_CMPOKIE -#define LPTIM_IT_EXTTRIG LPTIM_IER_EXTTRIGIE -#define LPTIM_IT_ARRM LPTIM_IER_ARRMIE -#define LPTIM_IT_CMPM LPTIM_IER_CMPMIE -/** - * @} - */ - -/** @defgroup LPTIM_Option Register Definition - * @{ - */ -#define LPTIM_OP_PAD_AF 0x00000000U -#define LPTIM_OP_PAD_PA4 LPTIM_OR_LPT_IN1_RMP_0 -#define LPTIM_OP_PAD_PB9 LPTIM_OR_LPT_IN1_RMP_1 -#define LPTIM_OP_TIM_DAC LPTIM_OR_LPT_IN1_RMP -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup LPTIM_Exported_Macros LPTIM Exported Macros - * @{ - */ - -/** @brief Reset LPTIM handle state. - * @param __HANDLE__ LPTIM handle - * @retval None - */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -#define __HAL_LPTIM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_LPTIM_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_LPTIM_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_LPTIM_STATE_RESET) -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - -/** - * @brief Enable the LPTIM peripheral. - * @param __HANDLE__ LPTIM handle - * @retval None - */ -#define __HAL_LPTIM_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (LPTIM_CR_ENABLE)) - -/** - * @brief Disable the LPTIM peripheral. - * @param __HANDLE__ LPTIM handle - * @note The following sequence is required to solve LPTIM disable HW limitation. - * Please check Errata Sheet ES0335 for more details under "MCU may remain - * stuck in LPTIM interrupt when entering Stop mode" section. - * @note Please call @ref HAL_LPTIM_GetState() after a call to __HAL_LPTIM_DISABLE to - * check for TIMEOUT. - * @retval None - */ -#define __HAL_LPTIM_DISABLE(__HANDLE__) LPTIM_Disable(__HANDLE__) - -/** - * @brief Start the LPTIM peripheral in Continuous mode. - * @param __HANDLE__ LPTIM handle - * @retval None - */ -#define __HAL_LPTIM_START_CONTINUOUS(__HANDLE__) ((__HANDLE__)->Instance->CR |= LPTIM_CR_CNTSTRT) -/** - * @brief Start the LPTIM peripheral in single mode. - * @param __HANDLE__ LPTIM handle - * @retval None - */ -#define __HAL_LPTIM_START_SINGLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= LPTIM_CR_SNGSTRT) - -/** - * @brief Write the passed parameter in the Autoreload register. - * @param __HANDLE__ LPTIM handle - * @param __VALUE__ Autoreload value - * @retval None - * @note The ARR register can only be modified when the LPTIM instance is enabled. - */ -#define __HAL_LPTIM_AUTORELOAD_SET(__HANDLE__ , __VALUE__) ((__HANDLE__)->Instance->ARR = (__VALUE__)) - -/** - * @brief Write the passed parameter in the Compare register. - * @param __HANDLE__ LPTIM handle - * @param __VALUE__ Compare value - * @retval None - * @note The CMP register can only be modified when the LPTIM instance is enabled. - */ -#define __HAL_LPTIM_COMPARE_SET(__HANDLE__ , __VALUE__) ((__HANDLE__)->Instance->CMP = (__VALUE__)) - -/** - * @brief Check whether the specified LPTIM flag is set or not. - * @param __HANDLE__ LPTIM handle - * @param __FLAG__ LPTIM flag to check - * This parameter can be a value of: - * @arg LPTIM_FLAG_DOWN : Counter direction change up Flag. - * @arg LPTIM_FLAG_UP : Counter direction change down to up Flag. - * @arg LPTIM_FLAG_ARROK : Autoreload register update OK Flag. - * @arg LPTIM_FLAG_CMPOK : Compare register update OK Flag. - * @arg LPTIM_FLAG_EXTTRIG : External trigger edge event Flag. - * @arg LPTIM_FLAG_ARRM : Autoreload match Flag. - * @arg LPTIM_FLAG_CMPM : Compare match Flag. - * @retval The state of the specified flag (SET or RESET). - */ -#define __HAL_LPTIM_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->ISR &(__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear the specified LPTIM flag. - * @param __HANDLE__ LPTIM handle. - * @param __FLAG__ LPTIM flag to clear. - * This parameter can be a value of: - * @arg LPTIM_FLAG_DOWN : Counter direction change up Flag. - * @arg LPTIM_FLAG_UP : Counter direction change down to up Flag. - * @arg LPTIM_FLAG_ARROK : Autoreload register update OK Flag. - * @arg LPTIM_FLAG_CMPOK : Compare register update OK Flag. - * @arg LPTIM_FLAG_EXTTRIG : External trigger edge event Flag. - * @arg LPTIM_FLAG_ARRM : Autoreload match Flag. - * @arg LPTIM_FLAG_CMPM : Compare match Flag. - * @retval None. - */ -#define __HAL_LPTIM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__)) - -/** - * @brief Enable the specified LPTIM interrupt. - * @param __HANDLE__ LPTIM handle. - * @param __INTERRUPT__ LPTIM interrupt to set. - * This parameter can be a value of: - * @arg LPTIM_IT_DOWN : Counter direction change up Interrupt. - * @arg LPTIM_IT_UP : Counter direction change down to up Interrupt. - * @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt. - * @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt. - * @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt. - * @arg LPTIM_IT_ARRM : Autoreload match Interrupt. - * @arg LPTIM_IT_CMPM : Compare match Interrupt. - * @retval None. - * @note The LPTIM interrupts can only be enabled when the LPTIM instance is disabled. - */ -#define __HAL_LPTIM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__)) - -/** - * @brief Disable the specified LPTIM interrupt. - * @param __HANDLE__ LPTIM handle. - * @param __INTERRUPT__ LPTIM interrupt to set. - * This parameter can be a value of: - * @arg LPTIM_IT_DOWN : Counter direction change up Interrupt. - * @arg LPTIM_IT_UP : Counter direction change down to up Interrupt. - * @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt. - * @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt. - * @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt. - * @arg LPTIM_IT_ARRM : Autoreload match Interrupt. - * @arg LPTIM_IT_CMPM : Compare match Interrupt. - * @retval None. - * @note The LPTIM interrupts can only be disabled when the LPTIM instance is disabled. - */ -#define __HAL_LPTIM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= (~(__INTERRUPT__))) - -/** - * @brief Check whether the specified LPTIM interrupt source is enabled or not. - * @param __HANDLE__ LPTIM handle. - * @param __INTERRUPT__ LPTIM interrupt to check. - * This parameter can be a value of: - * @arg LPTIM_IT_DOWN : Counter direction change up Interrupt. - * @arg LPTIM_IT_UP : Counter direction change down to up Interrupt. - * @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt. - * @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt. - * @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt. - * @arg LPTIM_IT_ARRM : Autoreload match Interrupt. - * @arg LPTIM_IT_CMPM : Compare match Interrupt. - * @retval Interrupt status. - */ - -#define __HAL_LPTIM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IER\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief LPTIM Option Register - * @param __HANDLE__ LPTIM handle - * @param __VALUE__ This parameter can be a value of : - * @arg LPTIM_OP_PAD_AF - * @arg LPTIM_OP_PAD_PA4 - * @arg LPTIM_OP_PAD_PB9 - * @arg LPTIM_OP_TIM_DAC - * @retval None - */ -#define __HAL_LPTIM_OPTR_CONFIG(__HANDLE__ , __VALUE__) ((__HANDLE__)->Instance->OR = (__VALUE__)) - - -/** - * @brief Enable interrupt on the LPTIM Wake-up Timer associated Exti line. - * @retval None - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT() (EXTI->IMR\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable interrupt on the LPTIM Wake-up Timer associated Exti line. - * @retval None - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT() (EXTI->IMR\ - &= ~(LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable event on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_EVENT() (EXTI->EMR\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable event on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_EVENT() (EXTI->EMR\ - &= ~(LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT)) -#if defined(EXTI_IMR_MR23) - -/** - * @brief Enable falling edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_FALLING_EDGE() (EXTI->FTSR\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable falling edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_FALLING_EDGE() (EXTI->FTSR\ - &= ~(LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable rising edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE() (EXTI->RTSR\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable rising edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE() (EXTI->RTSR\ - &= ~(LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable rising & falling edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_FALLING_EDGE() do{__HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE();\ - __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_FALLING_EDGE();\ - }while(0) - -/** - * @brief Disable rising & falling edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_FALLING_EDGE() do{__HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE();\ - __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_FALLING_EDGE();\ - }while(0) - -/** - * @brief Check whether the LPTIM Wake-up Timer associated Exti line interrupt flag is set or not. - * @retval Line Status. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_GET_FLAG() (EXTI->PR\ - & LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Clear the LPTIM Wake-up Timer associated Exti line flag. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_CLEAR_FLAG() (EXTI->PR\ - = LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Generate a Software interrupt on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_GENERATE_SWIT() (EXTI->SWIER\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) -#endif /* EXTI_IMR_MR23 */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup LPTIM_Exported_Functions LPTIM Exported Functions - * @{ - */ - -/** @addtogroup LPTIM_Exported_Functions_Group1 - * @brief Initialization and Configuration functions. - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_LPTIM_Init(LPTIM_HandleTypeDef *hlptim); -HAL_StatusTypeDef HAL_LPTIM_DeInit(LPTIM_HandleTypeDef *hlptim); - -/* MSP functions *************************************************************/ -void HAL_LPTIM_MspInit(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_MspDeInit(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** @addtogroup LPTIM_Exported_Functions_Group2 - * @brief Start-Stop operation functions. - * @{ - */ -/* Start/Stop operation functions *********************************************/ -/* ################################# PWM Mode ################################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_PWM_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_PWM_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_PWM_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_PWM_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################# One Pulse Mode ##############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################## Set once Mode ##############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################### Encoder Mode ##############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_Encoder_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period); -HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_Encoder_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period); -HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################# Time out Mode ##############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout); -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout); -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################## Counter Mode ###############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_Counter_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period); -HAL_StatusTypeDef HAL_LPTIM_Counter_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_Counter_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period); -HAL_StatusTypeDef HAL_LPTIM_Counter_Stop_IT(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** @addtogroup LPTIM_Exported_Functions_Group3 - * @brief Read operation functions. - * @{ - */ -/* Reading operation functions ************************************************/ -uint32_t HAL_LPTIM_ReadCounter(LPTIM_HandleTypeDef *hlptim); -uint32_t HAL_LPTIM_ReadAutoReload(LPTIM_HandleTypeDef *hlptim); -uint32_t HAL_LPTIM_ReadCompare(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** @addtogroup LPTIM_Exported_Functions_Group4 - * @brief LPTIM IRQ handler and callback functions. - * @{ - */ -/* LPTIM IRQ functions *******************************************************/ -void HAL_LPTIM_IRQHandler(LPTIM_HandleTypeDef *hlptim); - -/* CallBack functions ********************************************************/ -void HAL_LPTIM_CompareMatchCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_TriggerCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_CompareWriteCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_AutoReloadWriteCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_DirectionUpCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_DirectionDownCallback(LPTIM_HandleTypeDef *hlptim); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_LPTIM_RegisterCallback(LPTIM_HandleTypeDef *lphtim, HAL_LPTIM_CallbackIDTypeDef CallbackID, - pLPTIM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_LPTIM_UnRegisterCallback(LPTIM_HandleTypeDef *lphtim, HAL_LPTIM_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup LPTIM_Group5 - * @brief Peripheral State functions. - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_LPTIM_StateTypeDef HAL_LPTIM_GetState(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Types LPTIM Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Variables LPTIM Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Constants LPTIM Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Macros LPTIM Private Macros - * @{ - */ - -#define IS_LPTIM_CLOCK_SOURCE(__SOURCE__) (((__SOURCE__) == LPTIM_CLOCKSOURCE_ULPTIM) || \ - ((__SOURCE__) == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC)) - - -#define IS_LPTIM_CLOCK_PRESCALER(__PRESCALER__) (((__PRESCALER__) == LPTIM_PRESCALER_DIV1 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV2 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV4 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV8 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV16 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV32 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV64 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV128)) - -#define IS_LPTIM_CLOCK_PRESCALERDIV1(__PRESCALER__) ((__PRESCALER__) == LPTIM_PRESCALER_DIV1) - -#define IS_LPTIM_OUTPUT_POLARITY(__POLARITY__) (((__POLARITY__) == LPTIM_OUTPUTPOLARITY_LOW ) || \ - ((__POLARITY__) == LPTIM_OUTPUTPOLARITY_HIGH)) - -#define IS_LPTIM_CLOCK_SAMPLE_TIME(__SAMPLETIME__) (((__SAMPLETIME__) == LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION) || \ - ((__SAMPLETIME__) == LPTIM_CLOCKSAMPLETIME_2TRANSITIONS) || \ - ((__SAMPLETIME__) == LPTIM_CLOCKSAMPLETIME_4TRANSITIONS) || \ - ((__SAMPLETIME__) == LPTIM_CLOCKSAMPLETIME_8TRANSITIONS)) - -#define IS_LPTIM_CLOCK_POLARITY(__POLARITY__) (((__POLARITY__) == LPTIM_CLOCKPOLARITY_RISING) || \ - ((__POLARITY__) == LPTIM_CLOCKPOLARITY_FALLING) || \ - ((__POLARITY__) == LPTIM_CLOCKPOLARITY_RISING_FALLING)) - -#define IS_LPTIM_TRG_SOURCE(__TRIG__) (((__TRIG__) == LPTIM_TRIGSOURCE_SOFTWARE) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_0) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_1) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_2) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_3) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_4) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_5)) - -#define IS_LPTIM_EXT_TRG_POLARITY(__POLARITY__) (((__POLARITY__) == LPTIM_ACTIVEEDGE_RISING ) || \ - ((__POLARITY__) == LPTIM_ACTIVEEDGE_FALLING ) || \ - ((__POLARITY__) == LPTIM_ACTIVEEDGE_RISING_FALLING )) - -#define IS_LPTIM_TRIG_SAMPLE_TIME(__SAMPLETIME__) (((__SAMPLETIME__) == LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION) || \ - ((__SAMPLETIME__) == LPTIM_TRIGSAMPLETIME_2TRANSITIONS ) || \ - ((__SAMPLETIME__) == LPTIM_TRIGSAMPLETIME_4TRANSITIONS ) || \ - ((__SAMPLETIME__) == LPTIM_TRIGSAMPLETIME_8TRANSITIONS )) - -#define IS_LPTIM_UPDATE_MODE(__MODE__) (((__MODE__) == LPTIM_UPDATE_IMMEDIATE) || \ - ((__MODE__) == LPTIM_UPDATE_ENDOFPERIOD)) - -#define IS_LPTIM_COUNTER_SOURCE(__SOURCE__) (((__SOURCE__) == LPTIM_COUNTERSOURCE_INTERNAL) || \ - ((__SOURCE__) == LPTIM_COUNTERSOURCE_EXTERNAL)) - -#define IS_LPTIM_AUTORELOAD(__AUTORELOAD__) ((__AUTORELOAD__) <= 0x0000FFFFUL) - -#define IS_LPTIM_COMPARE(__COMPARE__) ((__COMPARE__) <= 0x0000FFFFUL) - -#define IS_LPTIM_PERIOD(__PERIOD__) ((__PERIOD__) <= 0x0000FFFFUL) - -#define IS_LPTIM_PULSE(__PULSE__) ((__PULSE__) <= 0x0000FFFFUL) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Functions LPTIM Private Functions - * @{ - */ -void LPTIM_Disable(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** - * @} - */ - -#endif /* LPTIM1 */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_LPTIM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc.h deleted file mode 100644 index 0cab8446ef6947a..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc.h +++ /dev/null @@ -1,688 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_ltdc.h - * @author MCD Application Team - * @brief Header file of LTDC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_LTDC_H -#define STM32F4xx_HAL_LTDC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (LTDC) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup LTDC LTDC - * @brief LTDC HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup LTDC_Exported_Types LTDC Exported Types - * @{ - */ -#define MAX_LAYER 2U - -/** - * @brief LTDC color structure definition - */ -typedef struct -{ - uint8_t Blue; /*!< Configures the blue value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint8_t Green; /*!< Configures the green value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint8_t Red; /*!< Configures the red value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint8_t Reserved; /*!< Reserved 0xFF */ -} LTDC_ColorTypeDef; - -/** - * @brief LTDC Init structure definition - */ -typedef struct -{ - uint32_t HSPolarity; /*!< configures the horizontal synchronization polarity. - This parameter can be one value of @ref LTDC_HS_POLARITY */ - - uint32_t VSPolarity; /*!< configures the vertical synchronization polarity. - This parameter can be one value of @ref LTDC_VS_POLARITY */ - - uint32_t DEPolarity; /*!< configures the data enable polarity. - This parameter can be one of value of @ref LTDC_DE_POLARITY */ - - uint32_t PCPolarity; /*!< configures the pixel clock polarity. - This parameter can be one of value of @ref LTDC_PC_POLARITY */ - - uint32_t HorizontalSync; /*!< configures the number of Horizontal synchronization width. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF. */ - - uint32_t VerticalSync; /*!< configures the number of Vertical synchronization height. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0x7FF. */ - - uint32_t AccumulatedHBP; /*!< configures the accumulated horizontal back porch width. - This parameter must be a number between Min_Data = LTDC_HorizontalSync and Max_Data = 0xFFF. */ - - uint32_t AccumulatedVBP; /*!< configures the accumulated vertical back porch height. - This parameter must be a number between Min_Data = LTDC_VerticalSync and Max_Data = 0x7FF. */ - - uint32_t AccumulatedActiveW; /*!< configures the accumulated active width. - This parameter must be a number between Min_Data = LTDC_AccumulatedHBP and Max_Data = 0xFFF. */ - - uint32_t AccumulatedActiveH; /*!< configures the accumulated active height. - This parameter must be a number between Min_Data = LTDC_AccumulatedVBP and Max_Data = 0x7FF. */ - - uint32_t TotalWidth; /*!< configures the total width. - This parameter must be a number between Min_Data = LTDC_AccumulatedActiveW and Max_Data = 0xFFF. */ - - uint32_t TotalHeigh; /*!< configures the total height. - This parameter must be a number between Min_Data = LTDC_AccumulatedActiveH and Max_Data = 0x7FF. */ - - LTDC_ColorTypeDef Backcolor; /*!< Configures the background color. */ -} LTDC_InitTypeDef; - -/** - * @brief LTDC Layer structure definition - */ -typedef struct -{ - uint32_t WindowX0; /*!< Configures the Window Horizontal Start Position. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF. */ - - uint32_t WindowX1; /*!< Configures the Window Horizontal Stop Position. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF. */ - - uint32_t WindowY0; /*!< Configures the Window vertical Start Position. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0x7FF. */ - - uint32_t WindowY1; /*!< Configures the Window vertical Stop Position. - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x7FF. */ - - uint32_t PixelFormat; /*!< Specifies the pixel format. - This parameter can be one of value of @ref LTDC_Pixelformat */ - - uint32_t Alpha; /*!< Specifies the constant alpha used for blending. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint32_t Alpha0; /*!< Configures the default alpha value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint32_t BlendingFactor1; /*!< Select the blending factor 1. - This parameter can be one of value of @ref LTDC_BlendingFactor1 */ - - uint32_t BlendingFactor2; /*!< Select the blending factor 2. - This parameter can be one of value of @ref LTDC_BlendingFactor2 */ - - uint32_t FBStartAdress; /*!< Configures the color frame buffer address */ - - uint32_t ImageWidth; /*!< Configures the color frame buffer line length. - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x1FFF. */ - - uint32_t ImageHeight; /*!< Specifies the number of line in frame buffer. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0x7FF. */ - - LTDC_ColorTypeDef Backcolor; /*!< Configures the layer background color. */ -} LTDC_LayerCfgTypeDef; - -/** - * @brief HAL LTDC State structures definition - */ -typedef enum -{ - HAL_LTDC_STATE_RESET = 0x00U, /*!< LTDC not yet initialized or disabled */ - HAL_LTDC_STATE_READY = 0x01U, /*!< LTDC initialized and ready for use */ - HAL_LTDC_STATE_BUSY = 0x02U, /*!< LTDC internal process is ongoing */ - HAL_LTDC_STATE_TIMEOUT = 0x03U, /*!< LTDC Timeout state */ - HAL_LTDC_STATE_ERROR = 0x04U /*!< LTDC state error */ -} HAL_LTDC_StateTypeDef; - -/** - * @brief LTDC handle Structure definition - */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -typedef struct __LTDC_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ -{ - LTDC_TypeDef *Instance; /*!< LTDC Register base address */ - - LTDC_InitTypeDef Init; /*!< LTDC parameters */ - - LTDC_LayerCfgTypeDef LayerCfg[MAX_LAYER]; /*!< LTDC Layers parameters */ - - HAL_LockTypeDef Lock; /*!< LTDC Lock */ - - __IO HAL_LTDC_StateTypeDef State; /*!< LTDC state */ - - __IO uint32_t ErrorCode; /*!< LTDC Error code */ - -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) - void (* LineEventCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Line Event Callback */ - void (* ReloadEventCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Reload Event Callback */ - void (* ErrorCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Error Callback */ - - void (* MspInitCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Msp Init callback */ - void (* MspDeInitCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Msp DeInit callback */ - -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - - -} LTDC_HandleTypeDef; - -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL LTDC Callback ID enumeration definition - */ -typedef enum -{ - HAL_LTDC_MSPINIT_CB_ID = 0x00U, /*!< LTDC MspInit callback ID */ - HAL_LTDC_MSPDEINIT_CB_ID = 0x01U, /*!< LTDC MspDeInit callback ID */ - - HAL_LTDC_LINE_EVENT_CB_ID = 0x02U, /*!< LTDC Line Event Callback ID */ - HAL_LTDC_RELOAD_EVENT_CB_ID = 0x03U, /*!< LTDC Reload Callback ID */ - HAL_LTDC_ERROR_CB_ID = 0x04U /*!< LTDC Error Callback ID */ - -} HAL_LTDC_CallbackIDTypeDef; - -/** - * @brief HAL LTDC Callback pointer definition - */ -typedef void (*pLTDC_CallbackTypeDef)(LTDC_HandleTypeDef *hltdc); /*!< pointer to an LTDC callback function */ - -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup LTDC_Exported_Constants LTDC Exported Constants - * @{ - */ - -/** @defgroup LTDC_Error_Code LTDC Error Code - * @{ - */ -#define HAL_LTDC_ERROR_NONE 0x00000000U /*!< LTDC No error */ -#define HAL_LTDC_ERROR_TE 0x00000001U /*!< LTDC Transfer error */ -#define HAL_LTDC_ERROR_FU 0x00000002U /*!< LTDC FIFO Underrun */ -#define HAL_LTDC_ERROR_TIMEOUT 0x00000020U /*!< LTDC Timeout error */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -#define HAL_LTDC_ERROR_INVALID_CALLBACK 0x00000040U /*!< LTDC Invalid Callback error */ -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup LTDC_Layer LTDC Layer - * @{ - */ -#define LTDC_LAYER_1 0x00000000U /*!< LTDC Layer 1 */ -#define LTDC_LAYER_2 0x00000001U /*!< LTDC Layer 2 */ -/** - * @} - */ - -/** @defgroup LTDC_HS_POLARITY LTDC HS POLARITY - * @{ - */ -#define LTDC_HSPOLARITY_AL 0x00000000U /*!< Horizontal Synchronization is active low. */ -#define LTDC_HSPOLARITY_AH LTDC_GCR_HSPOL /*!< Horizontal Synchronization is active high. */ -/** - * @} - */ - -/** @defgroup LTDC_VS_POLARITY LTDC VS POLARITY - * @{ - */ -#define LTDC_VSPOLARITY_AL 0x00000000U /*!< Vertical Synchronization is active low. */ -#define LTDC_VSPOLARITY_AH LTDC_GCR_VSPOL /*!< Vertical Synchronization is active high. */ -/** - * @} - */ - -/** @defgroup LTDC_DE_POLARITY LTDC DE POLARITY - * @{ - */ -#define LTDC_DEPOLARITY_AL 0x00000000U /*!< Data Enable, is active low. */ -#define LTDC_DEPOLARITY_AH LTDC_GCR_DEPOL /*!< Data Enable, is active high. */ -/** - * @} - */ - -/** @defgroup LTDC_PC_POLARITY LTDC PC POLARITY - * @{ - */ -#define LTDC_PCPOLARITY_IPC 0x00000000U /*!< input pixel clock. */ -#define LTDC_PCPOLARITY_IIPC LTDC_GCR_PCPOL /*!< inverted input pixel clock. */ -/** - * @} - */ - -/** @defgroup LTDC_SYNC LTDC SYNC - * @{ - */ -#define LTDC_HORIZONTALSYNC (LTDC_SSCR_HSW >> 16U) /*!< Horizontal synchronization width. */ -#define LTDC_VERTICALSYNC LTDC_SSCR_VSH /*!< Vertical synchronization height. */ -/** - * @} - */ - -/** @defgroup LTDC_BACK_COLOR LTDC BACK COLOR - * @{ - */ -#define LTDC_COLOR 0x000000FFU /*!< Color mask */ -/** - * @} - */ - -/** @defgroup LTDC_BlendingFactor1 LTDC Blending Factor1 - * @{ - */ -#define LTDC_BLENDING_FACTOR1_CA 0x00000400U /*!< Blending factor : Cte Alpha */ -#define LTDC_BLENDING_FACTOR1_PAxCA 0x00000600U /*!< Blending factor : Cte Alpha x Pixel Alpha*/ -/** - * @} - */ - -/** @defgroup LTDC_BlendingFactor2 LTDC Blending Factor2 - * @{ - */ -#define LTDC_BLENDING_FACTOR2_CA 0x00000005U /*!< Blending factor : Cte Alpha */ -#define LTDC_BLENDING_FACTOR2_PAxCA 0x00000007U /*!< Blending factor : Cte Alpha x Pixel Alpha*/ -/** - * @} - */ - -/** @defgroup LTDC_Pixelformat LTDC Pixel format - * @{ - */ -#define LTDC_PIXEL_FORMAT_ARGB8888 0x00000000U /*!< ARGB8888 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_RGB888 0x00000001U /*!< RGB888 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_RGB565 0x00000002U /*!< RGB565 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_ARGB1555 0x00000003U /*!< ARGB1555 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_ARGB4444 0x00000004U /*!< ARGB4444 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_L8 0x00000005U /*!< L8 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_AL44 0x00000006U /*!< AL44 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_AL88 0x00000007U /*!< AL88 LTDC pixel format */ -/** - * @} - */ - -/** @defgroup LTDC_Alpha LTDC Alpha - * @{ - */ -#define LTDC_ALPHA LTDC_LxCACR_CONSTA /*!< LTDC Constant Alpha mask */ -/** - * @} - */ - -/** @defgroup LTDC_LAYER_Config LTDC LAYER Config - * @{ - */ -#define LTDC_STOPPOSITION (LTDC_LxWHPCR_WHSPPOS >> 16U) /*!< LTDC Layer stop position */ -#define LTDC_STARTPOSITION LTDC_LxWHPCR_WHSTPOS /*!< LTDC Layer start position */ - -#define LTDC_COLOR_FRAME_BUFFER LTDC_LxCFBLR_CFBLL /*!< LTDC Layer Line length */ -#define LTDC_LINE_NUMBER LTDC_LxCFBLNR_CFBLNBR /*!< LTDC Layer Line number */ -/** - * @} - */ - -/** @defgroup LTDC_Interrupts LTDC Interrupts - * @{ - */ -#define LTDC_IT_LI LTDC_IER_LIE /*!< LTDC Line Interrupt */ -#define LTDC_IT_FU LTDC_IER_FUIE /*!< LTDC FIFO Underrun Interrupt */ -#define LTDC_IT_TE LTDC_IER_TERRIE /*!< LTDC Transfer Error Interrupt */ -#define LTDC_IT_RR LTDC_IER_RRIE /*!< LTDC Register Reload Interrupt */ -/** - * @} - */ - -/** @defgroup LTDC_Flags LTDC Flags - * @{ - */ -#define LTDC_FLAG_LI LTDC_ISR_LIF /*!< LTDC Line Interrupt Flag */ -#define LTDC_FLAG_FU LTDC_ISR_FUIF /*!< LTDC FIFO Underrun interrupt Flag */ -#define LTDC_FLAG_TE LTDC_ISR_TERRIF /*!< LTDC Transfer Error interrupt Flag */ -#define LTDC_FLAG_RR LTDC_ISR_RRIF /*!< LTDC Register Reload interrupt Flag */ -/** - * @} - */ - -/** @defgroup LTDC_Reload_Type LTDC Reload Type - * @{ - */ -#define LTDC_RELOAD_IMMEDIATE LTDC_SRCR_IMR /*!< Immediate Reload */ -#define LTDC_RELOAD_VERTICAL_BLANKING LTDC_SRCR_VBR /*!< Vertical Blanking Reload */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup LTDC_Exported_Macros LTDC Exported Macros - * @{ - */ - -/** @brief Reset LTDC handle state. - * @param __HANDLE__ LTDC handle - * @retval None - */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -#define __HAL_LTDC_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_LTDC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_LTDC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_LTDC_STATE_RESET) -#endif /*USE_HAL_LTDC_REGISTER_CALLBACKS */ - -/** - * @brief Enable the LTDC. - * @param __HANDLE__ LTDC handle - * @retval None. - */ -#define __HAL_LTDC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->GCR |= LTDC_GCR_LTDCEN) - -/** - * @brief Disable the LTDC. - * @param __HANDLE__ LTDC handle - * @retval None. - */ -#define __HAL_LTDC_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->GCR &= ~(LTDC_GCR_LTDCEN)) - -/** - * @brief Enable the LTDC Layer. - * @param __HANDLE__ LTDC handle - * @param __LAYER__ Specify the layer to be enabled. - * This parameter can be LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). - * @retval None. - */ -#define __HAL_LTDC_LAYER_ENABLE(__HANDLE__, __LAYER__) ((LTDC_LAYER((__HANDLE__), (__LAYER__)))->CR |= (uint32_t)LTDC_LxCR_LEN) - -/** - * @brief Disable the LTDC Layer. - * @param __HANDLE__ LTDC handle - * @param __LAYER__ Specify the layer to be disabled. - * This parameter can be LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). - * @retval None. - */ -#define __HAL_LTDC_LAYER_DISABLE(__HANDLE__, __LAYER__) ((LTDC_LAYER((__HANDLE__), (__LAYER__)))->CR &= ~(uint32_t)LTDC_LxCR_LEN) - -/** - * @brief Reload immediately all LTDC Layers. - * @param __HANDLE__ LTDC handle - * @retval None. - */ -#define __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG(__HANDLE__) ((__HANDLE__)->Instance->SRCR |= LTDC_SRCR_IMR) - -/** - * @brief Reload during vertical blanking period all LTDC Layers. - * @param __HANDLE__ LTDC handle - * @retval None. - */ -#define __HAL_LTDC_VERTICAL_BLANKING_RELOAD_CONFIG(__HANDLE__) ((__HANDLE__)->Instance->SRCR |= LTDC_SRCR_VBR) - -/* Interrupt & Flag management */ -/** - * @brief Get the LTDC pending flags. - * @param __HANDLE__ LTDC handle - * @param __FLAG__ Get the specified flag. - * This parameter can be any combination of the following values: - * @arg LTDC_FLAG_LI: Line Interrupt flag - * @arg LTDC_FLAG_FU: FIFO Underrun Interrupt flag - * @arg LTDC_FLAG_TE: Transfer Error interrupt flag - * @arg LTDC_FLAG_RR: Register Reload Interrupt Flag - * @retval The state of FLAG (SET or RESET). - */ -#define __HAL_LTDC_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR & (__FLAG__)) - -/** - * @brief Clears the LTDC pending flags. - * @param __HANDLE__ LTDC handle - * @param __FLAG__ Specify the flag to clear. - * This parameter can be any combination of the following values: - * @arg LTDC_FLAG_LI: Line Interrupt flag - * @arg LTDC_FLAG_FU: FIFO Underrun Interrupt flag - * @arg LTDC_FLAG_TE: Transfer Error interrupt flag - * @arg LTDC_FLAG_RR: Register Reload Interrupt Flag - * @retval None - */ -#define __HAL_LTDC_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__)) - -/** - * @brief Enables the specified LTDC interrupts. - * @param __HANDLE__ LTDC handle - * @param __INTERRUPT__ Specify the LTDC interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg LTDC_IT_LI: Line Interrupt flag - * @arg LTDC_IT_FU: FIFO Underrun Interrupt flag - * @arg LTDC_IT_TE: Transfer Error interrupt flag - * @arg LTDC_IT_RR: Register Reload Interrupt Flag - * @retval None - */ -#define __HAL_LTDC_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__)) - -/** - * @brief Disables the specified LTDC interrupts. - * @param __HANDLE__ LTDC handle - * @param __INTERRUPT__ Specify the LTDC interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg LTDC_IT_LI: Line Interrupt flag - * @arg LTDC_IT_FU: FIFO Underrun Interrupt flag - * @arg LTDC_IT_TE: Transfer Error interrupt flag - * @arg LTDC_IT_RR: Register Reload Interrupt Flag - * @retval None - */ -#define __HAL_LTDC_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified LTDC interrupt has occurred or not. - * @param __HANDLE__ LTDC handle - * @param __INTERRUPT__ Specify the LTDC interrupt source to check. - * This parameter can be one of the following values: - * @arg LTDC_IT_LI: Line Interrupt flag - * @arg LTDC_IT_FU: FIFO Underrun Interrupt flag - * @arg LTDC_IT_TE: Transfer Error interrupt flag - * @arg LTDC_IT_RR: Register Reload Interrupt Flag - * @retval The state of INTERRUPT (SET or RESET). - */ -#define __HAL_LTDC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER & (__INTERRUPT__)) -/** - * @} - */ - -/* Include LTDC HAL Extension module */ -#include "stm32f4xx_hal_ltdc_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup LTDC_Exported_Functions - * @{ - */ -/** @addtogroup LTDC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_LTDC_Init(LTDC_HandleTypeDef *hltdc); -HAL_StatusTypeDef HAL_LTDC_DeInit(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_MspInit(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_MspDeInit(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_ErrorCallback(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_LineEventCallback(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_ReloadEventCallback(LTDC_HandleTypeDef *hltdc); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_LTDC_RegisterCallback(LTDC_HandleTypeDef *hltdc, HAL_LTDC_CallbackIDTypeDef CallbackID, pLTDC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_LTDC_UnRegisterCallback(LTDC_HandleTypeDef *hltdc, HAL_LTDC_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup LTDC_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -void HAL_LTDC_IRQHandler(LTDC_HandleTypeDef *hltdc); -/** - * @} - */ - -/** @addtogroup LTDC_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -HAL_StatusTypeDef HAL_LTDC_ConfigLayer(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetWindowSize(LTDC_HandleTypeDef *hltdc, uint32_t XSize, uint32_t YSize, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetWindowPosition(LTDC_HandleTypeDef *hltdc, uint32_t X0, uint32_t Y0, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetPixelFormat(LTDC_HandleTypeDef *hltdc, uint32_t Pixelformat, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetAlpha(LTDC_HandleTypeDef *hltdc, uint32_t Alpha, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetAddress(LTDC_HandleTypeDef *hltdc, uint32_t Address, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetPitch(LTDC_HandleTypeDef *hltdc, uint32_t LinePitchInPixels, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_ConfigColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t RGBValue, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_ConfigCLUT(LTDC_HandleTypeDef *hltdc, uint32_t *pCLUT, uint32_t CLUTSize, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_EnableColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_DisableColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_EnableCLUT(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_DisableCLUT(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_ProgramLineEvent(LTDC_HandleTypeDef *hltdc, uint32_t Line); -HAL_StatusTypeDef HAL_LTDC_EnableDither(LTDC_HandleTypeDef *hltdc); -HAL_StatusTypeDef HAL_LTDC_DisableDither(LTDC_HandleTypeDef *hltdc); -HAL_StatusTypeDef HAL_LTDC_Reload(LTDC_HandleTypeDef *hltdc, uint32_t ReloadType); -HAL_StatusTypeDef HAL_LTDC_ConfigLayer_NoReload(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetWindowSize_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t XSize, uint32_t YSize, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetWindowPosition_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t X0, uint32_t Y0, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetPixelFormat_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Pixelformat, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetAlpha_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Alpha, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetAddress_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Address, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetPitch_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LinePitchInPixels, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_ConfigColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t RGBValue, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_EnableColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_DisableColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_EnableCLUT_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_DisableCLUT_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); - -/** - * @} - */ - -/** @addtogroup LTDC_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State functions *************************************************/ -HAL_LTDC_StateTypeDef HAL_LTDC_GetState(LTDC_HandleTypeDef *hltdc); -uint32_t HAL_LTDC_GetError(LTDC_HandleTypeDef *hltdc); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup LTDC_Private_Macros LTDC Private Macros - * @{ - */ -#define LTDC_LAYER(__HANDLE__, __LAYER__) ((LTDC_Layer_TypeDef *)((uint32_t)(((uint32_t)((__HANDLE__)->Instance)) + 0x84U + (0x80U*(__LAYER__))))) -#define IS_LTDC_LAYER(__LAYER__) ((__LAYER__) < MAX_LAYER) -#define IS_LTDC_HSPOL(__HSPOL__) (((__HSPOL__) == LTDC_HSPOLARITY_AL) || ((__HSPOL__) == LTDC_HSPOLARITY_AH)) -#define IS_LTDC_VSPOL(__VSPOL__) (((__VSPOL__) == LTDC_VSPOLARITY_AL) || ((__VSPOL__) == LTDC_VSPOLARITY_AH)) -#define IS_LTDC_DEPOL(__DEPOL__) (((__DEPOL__) == LTDC_DEPOLARITY_AL) || ((__DEPOL__) == LTDC_DEPOLARITY_AH)) -#define IS_LTDC_PCPOL(__PCPOL__) (((__PCPOL__) == LTDC_PCPOLARITY_IPC) || ((__PCPOL__) == LTDC_PCPOLARITY_IIPC)) -#define IS_LTDC_HSYNC(__HSYNC__) ((__HSYNC__) <= LTDC_HORIZONTALSYNC) -#define IS_LTDC_VSYNC(__VSYNC__) ((__VSYNC__) <= LTDC_VERTICALSYNC) -#define IS_LTDC_AHBP(__AHBP__) ((__AHBP__) <= LTDC_HORIZONTALSYNC) -#define IS_LTDC_AVBP(__AVBP__) ((__AVBP__) <= LTDC_VERTICALSYNC) -#define IS_LTDC_AAW(__AAW__) ((__AAW__) <= LTDC_HORIZONTALSYNC) -#define IS_LTDC_AAH(__AAH__) ((__AAH__) <= LTDC_VERTICALSYNC) -#define IS_LTDC_TOTALW(__TOTALW__) ((__TOTALW__) <= LTDC_HORIZONTALSYNC) -#define IS_LTDC_TOTALH(__TOTALH__) ((__TOTALH__) <= LTDC_VERTICALSYNC) -#define IS_LTDC_BLUEVALUE(__BBLUE__) ((__BBLUE__) <= LTDC_COLOR) -#define IS_LTDC_GREENVALUE(__BGREEN__) ((__BGREEN__) <= LTDC_COLOR) -#define IS_LTDC_REDVALUE(__BRED__) ((__BRED__) <= LTDC_COLOR) -#define IS_LTDC_BLENDING_FACTOR1(__BLENDING_FACTOR1__) (((__BLENDING_FACTOR1__) == LTDC_BLENDING_FACTOR1_CA) || \ - ((__BLENDING_FACTOR1__) == LTDC_BLENDING_FACTOR1_PAxCA)) -#define IS_LTDC_BLENDING_FACTOR2(__BLENDING_FACTOR1__) (((__BLENDING_FACTOR1__) == LTDC_BLENDING_FACTOR2_CA) || \ - ((__BLENDING_FACTOR1__) == LTDC_BLENDING_FACTOR2_PAxCA)) -#define IS_LTDC_PIXEL_FORMAT(__PIXEL_FORMAT__) (((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_ARGB8888) || ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_RGB888) || \ - ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_RGB565) || ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_ARGB1555) || \ - ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_ARGB4444) || ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_L8) || \ - ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_AL44) || ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_AL88)) -#define IS_LTDC_ALPHA(__ALPHA__) ((__ALPHA__) <= LTDC_ALPHA) -#define IS_LTDC_HCONFIGST(__HCONFIGST__) ((__HCONFIGST__) <= LTDC_STARTPOSITION) -#define IS_LTDC_HCONFIGSP(__HCONFIGSP__) ((__HCONFIGSP__) <= LTDC_STOPPOSITION) -#define IS_LTDC_VCONFIGST(__VCONFIGST__) ((__VCONFIGST__) <= LTDC_STARTPOSITION) -#define IS_LTDC_VCONFIGSP(__VCONFIGSP__) ((__VCONFIGSP__) <= LTDC_STOPPOSITION) -#define IS_LTDC_CFBP(__CFBP__) ((__CFBP__) <= LTDC_COLOR_FRAME_BUFFER) -#define IS_LTDC_CFBLL(__CFBLL__) ((__CFBLL__) <= LTDC_COLOR_FRAME_BUFFER) -#define IS_LTDC_CFBLNBR(__CFBLNBR__) ((__CFBLNBR__) <= LTDC_LINE_NUMBER) -#define IS_LTDC_LIPOS(__LIPOS__) ((__LIPOS__) <= 0x7FFU) -#define IS_LTDC_RELOAD(__RELOADTYPE__) (((__RELOADTYPE__) == LTDC_RELOAD_IMMEDIATE) || ((__RELOADTYPE__) == LTDC_RELOAD_VERTICAL_BLANKING)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup LTDC_Private_Functions LTDC Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* LTDC */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_LTDC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc_ex.h deleted file mode 100644 index 37a5fdf47a3e7e2..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc_ex.h +++ /dev/null @@ -1,86 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_ltdc_ex.h - * @author MCD Application Team - * @brief Header file of LTDC HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_LTDC_EX_H -#define STM32F4xx_HAL_LTDC_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (LTDC) && defined (DSI) - -#include "stm32f4xx_hal_dsi.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup LTDCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup LTDCEx_Exported_Functions - * @{ - */ - -/** @addtogroup LTDCEx_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_LTDCEx_StructInitFromVideoConfig(LTDC_HandleTypeDef *hltdc, DSI_VidCfgTypeDef *VidCfg); -HAL_StatusTypeDef HAL_LTDCEx_StructInitFromAdaptedCommandConfig(LTDC_HandleTypeDef *hltdc, DSI_CmdCfgTypeDef *CmdCfg); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* LTDC && DSI */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_LTDC_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_mmc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_mmc.h deleted file mode 100644 index e65172acd65cba0..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_mmc.h +++ /dev/null @@ -1,745 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_mmc.h - * @author MCD Application Team - * @brief Header file of MMC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_MMC_H -#define STM32F4xx_HAL_MMC_H - -#if defined(SDIO) - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_sdmmc.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup MMC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup MMC_Exported_Types MMC Exported Types - * @{ - */ - -/** @defgroup MMC_Exported_Types_Group1 MMC State enumeration structure - * @{ - */ -typedef enum -{ - HAL_MMC_STATE_RESET = 0x00000000U, /*!< MMC not yet initialized or disabled */ - HAL_MMC_STATE_READY = 0x00000001U, /*!< MMC initialized and ready for use */ - HAL_MMC_STATE_TIMEOUT = 0x00000002U, /*!< MMC Timeout state */ - HAL_MMC_STATE_BUSY = 0x00000003U, /*!< MMC process ongoing */ - HAL_MMC_STATE_PROGRAMMING = 0x00000004U, /*!< MMC Programming State */ - HAL_MMC_STATE_RECEIVING = 0x00000005U, /*!< MMC Receinving State */ - HAL_MMC_STATE_TRANSFER = 0x00000006U, /*!< MMC Transfer State */ - HAL_MMC_STATE_ERROR = 0x0000000FU /*!< MMC is in error state */ -}HAL_MMC_StateTypeDef; -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group2 MMC Card State enumeration structure - * @{ - */ -typedef uint32_t HAL_MMC_CardStateTypeDef; - -#define HAL_MMC_CARD_READY 0x00000001U /*!< Card state is ready */ -#define HAL_MMC_CARD_IDENTIFICATION 0x00000002U /*!< Card is in identification state */ -#define HAL_MMC_CARD_STANDBY 0x00000003U /*!< Card is in standby state */ -#define HAL_MMC_CARD_TRANSFER 0x00000004U /*!< Card is in transfer state */ -#define HAL_MMC_CARD_SENDING 0x00000005U /*!< Card is sending an operation */ -#define HAL_MMC_CARD_RECEIVING 0x00000006U /*!< Card is receiving operation information */ -#define HAL_MMC_CARD_PROGRAMMING 0x00000007U /*!< Card is in programming state */ -#define HAL_MMC_CARD_DISCONNECTED 0x00000008U /*!< Card is disconnected */ -#define HAL_MMC_CARD_ERROR 0x000000FFU /*!< Card response Error */ -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group3 MMC Handle Structure definition - * @{ - */ -#define MMC_InitTypeDef SDIO_InitTypeDef -#define MMC_TypeDef SDIO_TypeDef - -/** - * @brief MMC Card Information Structure definition - */ -typedef struct -{ - uint32_t CardType; /*!< Specifies the card Type */ - - uint32_t Class; /*!< Specifies the class of the card class */ - - uint32_t RelCardAdd; /*!< Specifies the Relative Card Address */ - - uint32_t BlockNbr; /*!< Specifies the Card Capacity in blocks */ - - uint32_t BlockSize; /*!< Specifies one block size in bytes */ - - uint32_t LogBlockNbr; /*!< Specifies the Card logical Capacity in blocks */ - - uint32_t LogBlockSize; /*!< Specifies logical block size in bytes */ - -}HAL_MMC_CardInfoTypeDef; - -/** - * @brief MMC handle Structure definition - */ -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -typedef struct __MMC_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_MMC_REGISTER_CALLBACKS */ -{ - MMC_TypeDef *Instance; /*!< MMC registers base address */ - - MMC_InitTypeDef Init; /*!< MMC required parameters */ - - HAL_LockTypeDef Lock; /*!< MMC locking object */ - - uint8_t *pTxBuffPtr; /*!< Pointer to MMC Tx transfer Buffer */ - - uint32_t TxXferSize; /*!< MMC Tx Transfer size */ - - uint8_t *pRxBuffPtr; /*!< Pointer to MMC Rx transfer Buffer */ - - uint32_t RxXferSize; /*!< MMC Rx Transfer size */ - - __IO uint32_t Context; /*!< MMC transfer context */ - - __IO HAL_MMC_StateTypeDef State; /*!< MMC card State */ - - __IO uint32_t ErrorCode; /*!< MMC Card Error codes */ - - DMA_HandleTypeDef *hdmarx; /*!< MMC Rx DMA handle parameters */ - - DMA_HandleTypeDef *hdmatx; /*!< MMC Tx DMA handle parameters */ - - HAL_MMC_CardInfoTypeDef MmcCard; /*!< MMC Card information */ - - uint32_t CSD[4U]; /*!< MMC card specific data table */ - - uint32_t CID[4U]; /*!< MMC card identification number table */ - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback) (struct __MMC_HandleTypeDef *hmmc); - void (* RxCpltCallback) (struct __MMC_HandleTypeDef *hmmc); - void (* ErrorCallback) (struct __MMC_HandleTypeDef *hmmc); - void (* AbortCpltCallback) (struct __MMC_HandleTypeDef *hmmc); - - void (* MspInitCallback) (struct __MMC_HandleTypeDef *hmmc); - void (* MspDeInitCallback) (struct __MMC_HandleTypeDef *hmmc); -#endif -}MMC_HandleTypeDef; - -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group4 Card Specific Data: CSD Register - * @{ - */ -typedef struct -{ - __IO uint8_t CSDStruct; /*!< CSD structure */ - __IO uint8_t SysSpecVersion; /*!< System specification version */ - __IO uint8_t Reserved1; /*!< Reserved */ - __IO uint8_t TAAC; /*!< Data read access time 1 */ - __IO uint8_t NSAC; /*!< Data read access time 2 in CLK cycles */ - __IO uint8_t MaxBusClkFrec; /*!< Max. bus clock frequency */ - __IO uint16_t CardComdClasses; /*!< Card command classes */ - __IO uint8_t RdBlockLen; /*!< Max. read data block length */ - __IO uint8_t PartBlockRead; /*!< Partial blocks for read allowed */ - __IO uint8_t WrBlockMisalign; /*!< Write block misalignment */ - __IO uint8_t RdBlockMisalign; /*!< Read block misalignment */ - __IO uint8_t DSRImpl; /*!< DSR implemented */ - __IO uint8_t Reserved2; /*!< Reserved */ - __IO uint32_t DeviceSize; /*!< Device Size */ - __IO uint8_t MaxRdCurrentVDDMin; /*!< Max. read current @ VDD min */ - __IO uint8_t MaxRdCurrentVDDMax; /*!< Max. read current @ VDD max */ - __IO uint8_t MaxWrCurrentVDDMin; /*!< Max. write current @ VDD min */ - __IO uint8_t MaxWrCurrentVDDMax; /*!< Max. write current @ VDD max */ - __IO uint8_t DeviceSizeMul; /*!< Device size multiplier */ - __IO uint8_t EraseGrSize; /*!< Erase group size */ - __IO uint8_t EraseGrMul; /*!< Erase group size multiplier */ - __IO uint8_t WrProtectGrSize; /*!< Write protect group size */ - __IO uint8_t WrProtectGrEnable; /*!< Write protect group enable */ - __IO uint8_t ManDeflECC; /*!< Manufacturer default ECC */ - __IO uint8_t WrSpeedFact; /*!< Write speed factor */ - __IO uint8_t MaxWrBlockLen; /*!< Max. write data block length */ - __IO uint8_t WriteBlockPaPartial; /*!< Partial blocks for write allowed */ - __IO uint8_t Reserved3; /*!< Reserved */ - __IO uint8_t ContentProtectAppli; /*!< Content protection application */ - __IO uint8_t FileFormatGroup; /*!< File format group */ - __IO uint8_t CopyFlag; /*!< Copy flag (OTP) */ - __IO uint8_t PermWrProtect; /*!< Permanent write protection */ - __IO uint8_t TempWrProtect; /*!< Temporary write protection */ - __IO uint8_t FileFormat; /*!< File format */ - __IO uint8_t ECC; /*!< ECC code */ - __IO uint8_t CSD_CRC; /*!< CSD CRC */ - __IO uint8_t Reserved4; /*!< Always 1 */ - -}HAL_MMC_CardCSDTypeDef; -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group5 Card Identification Data: CID Register - * @{ - */ -typedef struct -{ - __IO uint8_t ManufacturerID; /*!< Manufacturer ID */ - __IO uint16_t OEM_AppliID; /*!< OEM/Application ID */ - __IO uint32_t ProdName1; /*!< Product Name part1 */ - __IO uint8_t ProdName2; /*!< Product Name part2 */ - __IO uint8_t ProdRev; /*!< Product Revision */ - __IO uint32_t ProdSN; /*!< Product Serial Number */ - __IO uint8_t Reserved1; /*!< Reserved1 */ - __IO uint16_t ManufactDate; /*!< Manufacturing Date */ - __IO uint8_t CID_CRC; /*!< CID CRC */ - __IO uint8_t Reserved2; /*!< Always 1 */ - -}HAL_MMC_CardCIDTypeDef; -/** - * @} - */ - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -/** @defgroup MMC_Exported_Types_Group6 MMC Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_MMC_TX_CPLT_CB_ID = 0x00U, /*!< MMC Tx Complete Callback ID */ - HAL_MMC_RX_CPLT_CB_ID = 0x01U, /*!< MMC Rx Complete Callback ID */ - HAL_MMC_ERROR_CB_ID = 0x02U, /*!< MMC Error Callback ID */ - HAL_MMC_ABORT_CB_ID = 0x03U, /*!< MMC Abort Callback ID */ - - HAL_MMC_MSP_INIT_CB_ID = 0x10U, /*!< MMC MspInit Callback ID */ - HAL_MMC_MSP_DEINIT_CB_ID = 0x11U /*!< MMC MspDeInit Callback ID */ -}HAL_MMC_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group7 MMC Callback pointer definition - * @{ - */ -typedef void (*pMMC_CallbackTypeDef) (MMC_HandleTypeDef *hmmc); -/** - * @} - */ -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup MMC_Exported_Constants Exported Constants - * @{ - */ - -#define MMC_BLOCKSIZE 512U /*!< Block size is 512 bytes */ - -/** @defgroup MMC_Exported_Constansts_Group1 MMC Error status enumeration Structure definition - * @{ - */ -#define HAL_MMC_ERROR_NONE SDMMC_ERROR_NONE /*!< No error */ -#define HAL_MMC_ERROR_CMD_CRC_FAIL SDMMC_ERROR_CMD_CRC_FAIL /*!< Command response received (but CRC check failed) */ -#define HAL_MMC_ERROR_DATA_CRC_FAIL SDMMC_ERROR_DATA_CRC_FAIL /*!< Data block sent/received (CRC check failed) */ -#define HAL_MMC_ERROR_CMD_RSP_TIMEOUT SDMMC_ERROR_CMD_RSP_TIMEOUT /*!< Command response timeout */ -#define HAL_MMC_ERROR_DATA_TIMEOUT SDMMC_ERROR_DATA_TIMEOUT /*!< Data timeout */ -#define HAL_MMC_ERROR_TX_UNDERRUN SDMMC_ERROR_TX_UNDERRUN /*!< Transmit FIFO underrun */ -#define HAL_MMC_ERROR_RX_OVERRUN SDMMC_ERROR_RX_OVERRUN /*!< Receive FIFO overrun */ -#define HAL_MMC_ERROR_ADDR_MISALIGNED SDMMC_ERROR_ADDR_MISALIGNED /*!< Misaligned address */ -#define HAL_MMC_ERROR_BLOCK_LEN_ERR SDMMC_ERROR_BLOCK_LEN_ERR /*!< Transferred block length is not allowed for the card or the - number of transferred bytes does not match the block length */ -#define HAL_MMC_ERROR_ERASE_SEQ_ERR SDMMC_ERROR_ERASE_SEQ_ERR /*!< An error in the sequence of erase command occurs */ -#define HAL_MMC_ERROR_BAD_ERASE_PARAM SDMMC_ERROR_BAD_ERASE_PARAM /*!< An invalid selection for erase groups */ -#define HAL_MMC_ERROR_WRITE_PROT_VIOLATION SDMMC_ERROR_WRITE_PROT_VIOLATION /*!< Attempt to program a write protect block */ -#define HAL_MMC_ERROR_LOCK_UNLOCK_FAILED SDMMC_ERROR_LOCK_UNLOCK_FAILED /*!< Sequence or password error has been detected in unlock - command or if there was an attempt to access a locked card */ -#define HAL_MMC_ERROR_COM_CRC_FAILED SDMMC_ERROR_COM_CRC_FAILED /*!< CRC check of the previous command failed */ -#define HAL_MMC_ERROR_ILLEGAL_CMD SDMMC_ERROR_ILLEGAL_CMD /*!< Command is not legal for the card state */ -#define HAL_MMC_ERROR_CARD_ECC_FAILED SDMMC_ERROR_CARD_ECC_FAILED /*!< Card internal ECC was applied but failed to correct the data */ -#define HAL_MMC_ERROR_CC_ERR SDMMC_ERROR_CC_ERR /*!< Internal card controller error */ -#define HAL_MMC_ERROR_GENERAL_UNKNOWN_ERR SDMMC_ERROR_GENERAL_UNKNOWN_ERR /*!< General or unknown error */ -#define HAL_MMC_ERROR_STREAM_READ_UNDERRUN SDMMC_ERROR_STREAM_READ_UNDERRUN /*!< The card could not sustain data reading in stream rmode */ -#define HAL_MMC_ERROR_STREAM_WRITE_OVERRUN SDMMC_ERROR_STREAM_WRITE_OVERRUN /*!< The card could not sustain data programming in stream mode */ -#define HAL_MMC_ERROR_CID_CSD_OVERWRITE SDMMC_ERROR_CID_CSD_OVERWRITE /*!< CID/CSD overwrite error */ -#define HAL_MMC_ERROR_WP_ERASE_SKIP SDMMC_ERROR_WP_ERASE_SKIP /*!< Only partial address space was erased */ -#define HAL_MMC_ERROR_CARD_ECC_DISABLED SDMMC_ERROR_CARD_ECC_DISABLED /*!< Command has been executed without using internal ECC */ -#define HAL_MMC_ERROR_ERASE_RESET SDMMC_ERROR_ERASE_RESET /*!< Erase sequence was cleared before executing because an out - of erase sequence command was received */ -#define HAL_MMC_ERROR_AKE_SEQ_ERR SDMMC_ERROR_AKE_SEQ_ERR /*!< Error in sequence of authentication */ -#define HAL_MMC_ERROR_INVALID_VOLTRANGE SDMMC_ERROR_INVALID_VOLTRANGE /*!< Error in case of invalid voltage range */ -#define HAL_MMC_ERROR_ADDR_OUT_OF_RANGE SDMMC_ERROR_ADDR_OUT_OF_RANGE /*!< Error when addressed block is out of range */ -#define HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE SDMMC_ERROR_REQUEST_NOT_APPLICABLE /*!< Error when command request is not applicable */ -#define HAL_MMC_ERROR_PARAM SDMMC_ERROR_INVALID_PARAMETER /*!< the used parameter is not valid */ -#define HAL_MMC_ERROR_UNSUPPORTED_FEATURE SDMMC_ERROR_UNSUPPORTED_FEATURE /*!< Error when feature is not insupported */ -#define HAL_MMC_ERROR_BUSY SDMMC_ERROR_BUSY /*!< Error when transfer process is busy */ -#define HAL_MMC_ERROR_DMA SDMMC_ERROR_DMA /*!< Error while DMA transfer */ -#define HAL_MMC_ERROR_TIMEOUT SDMMC_ERROR_TIMEOUT /*!< Timeout error */ - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -#define HAL_MMC_ERROR_INVALID_CALLBACK SDMMC_ERROR_INVALID_PARAMETER /*!< Invalid callback error */ -#endif -/** - * @} - */ - -/** @defgroup MMC_Exported_Constansts_Group2 MMC context enumeration - * @{ - */ -#define MMC_CONTEXT_NONE 0x00000000U /*!< None */ -#define MMC_CONTEXT_READ_SINGLE_BLOCK 0x00000001U /*!< Read single block operation */ -#define MMC_CONTEXT_READ_MULTIPLE_BLOCK 0x00000002U /*!< Read multiple blocks operation */ -#define MMC_CONTEXT_WRITE_SINGLE_BLOCK 0x00000010U /*!< Write single block operation */ -#define MMC_CONTEXT_WRITE_MULTIPLE_BLOCK 0x00000020U /*!< Write multiple blocks operation */ -#define MMC_CONTEXT_IT 0x00000008U /*!< Process in Interrupt mode */ -#define MMC_CONTEXT_DMA 0x00000080U /*!< Process in DMA mode */ - -/** - * @} - */ - -/** @defgroup MMC_Exported_Constansts_Group3 MMC Voltage mode - * @{ - */ -/** - * @brief - */ -#define MMC_HIGH_VOLTAGE_RANGE 0x80FF8000U /*!< VALUE OF ARGUMENT */ -#define MMC_DUAL_VOLTAGE_RANGE 0x80FF8080U /*!< VALUE OF ARGUMENT */ -#define eMMC_HIGH_VOLTAGE_RANGE 0xC0FF8000U /*!< for eMMC > 2Gb sector mode */ -#define eMMC_DUAL_VOLTAGE_RANGE 0xC0FF8080U /*!< for eMMC > 2Gb sector mode */ -#define MMC_INVALID_VOLTAGE_RANGE 0x0001FF01U -/** - * @} - */ - -/** @defgroup MMC_Exported_Constansts_Group4 MMC Memory Cards - * @{ - */ -#define MMC_LOW_CAPACITY_CARD 0x00000000U /*!< MMC Card Capacity <=2Gbytes */ -#define MMC_HIGH_CAPACITY_CARD 0x00000001U /*!< MMC Card Capacity >2Gbytes and <2Tbytes */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup MMC_Exported_macros MMC Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -/** @brief Reset MMC handle state. - * @param __HANDLE__ : MMC handle. - * @retval None - */ -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -#define __HAL_MMC_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_MMC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_MMC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_MMC_STATE_RESET) -#endif - -/** - * @brief Enable the MMC device. - * @retval None - */ -#define __HAL_MMC_ENABLE(__HANDLE__) __SDIO_ENABLE((__HANDLE__)->Instance) - -/** - * @brief Disable the MMC device. - * @retval None - */ -#define __HAL_MMC_DISABLE(__HANDLE__) __SDIO_DISABLE((__HANDLE__)->Instance) - -/** - * @brief Enable the SDMMC DMA transfer. - * @retval None - */ -#define __HAL_MMC_DMA_ENABLE(__HANDLE__) __SDIO_DMA_ENABLE((__HANDLE__)->Instance) - -/** - * @brief Disable the SDMMC DMA transfer. - * @retval None - */ -#define __HAL_MMC_DMA_DISABLE(__HANDLE__) __SDIO_DMA_DISABLE((__HANDLE__)->Instance) - -/** - * @brief Enable the MMC device interrupt. - * @param __HANDLE__: MMC Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt sources to be enabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @retval None - */ -#define __HAL_MMC_ENABLE_IT(__HANDLE__, __INTERRUPT__) __SDIO_ENABLE_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Disable the MMC device interrupt. - * @param __HANDLE__: MMC Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt sources to be disabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @retval None - */ -#define __HAL_MMC_DISABLE_IT(__HANDLE__, __INTERRUPT__) __SDIO_DISABLE_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Check whether the specified MMC flag is set or not. - * @param __HANDLE__: MMC Handle - * @param __FLAG__: specifies the flag to check. - * This parameter can be one of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_CMDACT: Command transfer in progress - * @arg SDIO_FLAG_TXACT: Data transmit in progress - * @arg SDIO_FLAG_RXACT: Data receive in progress - * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty - * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full - * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full - * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full - * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty - * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty - * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO - * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO - * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received - * @retval The new state of MMC FLAG (SET or RESET). - */ -#define __HAL_MMC_GET_FLAG(__HANDLE__, __FLAG__) __SDIO_GET_FLAG((__HANDLE__)->Instance, (__FLAG__)) - -/** - * @brief Clear the MMC's pending flags. - * @param __HANDLE__: MMC Handle - * @param __FLAG__: specifies the flag to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received - * @retval None - */ -#define __HAL_MMC_CLEAR_FLAG(__HANDLE__, __FLAG__) __SDIO_CLEAR_FLAG((__HANDLE__)->Instance, (__FLAG__)) - -/** - * @brief Check whether the specified MMC interrupt has occurred or not. - * @param __HANDLE__: MMC Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt source to check. - * This parameter can be one of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @retval The new state of MMC IT (SET or RESET). - */ -#define __HAL_MMC_GET_IT(__HANDLE__, __INTERRUPT__) __SDIO_GET_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Clear the MMC's interrupt pending bits. - * @param __HANDLE__: MMC Handle - * @param __INTERRUPT__: specifies the interrupt pending bit to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @retval None - */ -#define __HAL_MMC_CLEAR_IT(__HANDLE__, __INTERRUPT__) __SDIO_CLEAR_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup MMC_Exported_Functions MMC Exported Functions - * @{ - */ - -/** @defgroup MMC_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_MMC_Init(MMC_HandleTypeDef *hmmc); -HAL_StatusTypeDef HAL_MMC_InitCard(MMC_HandleTypeDef *hmmc); -HAL_StatusTypeDef HAL_MMC_DeInit (MMC_HandleTypeDef *hmmc); -void HAL_MMC_MspInit(MMC_HandleTypeDef *hmmc); -void HAL_MMC_MspDeInit(MMC_HandleTypeDef *hmmc); - -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout); -HAL_StatusTypeDef HAL_MMC_WriteBlocks(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout); -HAL_StatusTypeDef HAL_MMC_Erase(MMC_HandleTypeDef *hmmc, uint32_t BlockStartAdd, uint32_t BlockEndAdd); -/* Non-Blocking mode: IT */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks_IT(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -HAL_StatusTypeDef HAL_MMC_WriteBlocks_IT(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks_DMA(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -HAL_StatusTypeDef HAL_MMC_WriteBlocks_DMA(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); - -void HAL_MMC_IRQHandler(MMC_HandleTypeDef *hmmc); - -/* Callback in non blocking modes (DMA) */ -void HAL_MMC_TxCpltCallback(MMC_HandleTypeDef *hmmc); -void HAL_MMC_RxCpltCallback(MMC_HandleTypeDef *hmmc); -void HAL_MMC_ErrorCallback(MMC_HandleTypeDef *hmmc); -void HAL_MMC_AbortCallback(MMC_HandleTypeDef *hmmc); - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -/* MMC callback registering/unregistering */ -HAL_StatusTypeDef HAL_MMC_RegisterCallback (MMC_HandleTypeDef *hmmc, HAL_MMC_CallbackIDTypeDef CallbackId, pMMC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_MMC_UnRegisterCallback(MMC_HandleTypeDef *hmmc, HAL_MMC_CallbackIDTypeDef CallbackId); -#endif -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_MMC_ConfigWideBusOperation(MMC_HandleTypeDef *hmmc, uint32_t WideMode); -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group4 MMC card related functions - * @{ - */ -HAL_MMC_CardStateTypeDef HAL_MMC_GetCardState(MMC_HandleTypeDef *hmmc); -HAL_StatusTypeDef HAL_MMC_GetCardCID(MMC_HandleTypeDef *hmmc, HAL_MMC_CardCIDTypeDef *pCID); -HAL_StatusTypeDef HAL_MMC_GetCardCSD(MMC_HandleTypeDef *hmmc, HAL_MMC_CardCSDTypeDef *pCSD); -HAL_StatusTypeDef HAL_MMC_GetCardInfo(MMC_HandleTypeDef *hmmc, HAL_MMC_CardInfoTypeDef *pCardInfo); -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group5 Peripheral State and Errors functions - * @{ - */ -HAL_MMC_StateTypeDef HAL_MMC_GetState(MMC_HandleTypeDef *hmmc); -uint32_t HAL_MMC_GetError(MMC_HandleTypeDef *hmmc); -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group6 Perioheral Abort management - * @{ - */ -HAL_StatusTypeDef HAL_MMC_Abort(MMC_HandleTypeDef *hmmc); -HAL_StatusTypeDef HAL_MMC_Abort_IT(MMC_HandleTypeDef *hmmc); -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup MMC_Private_Types MMC Private Types - * @{ - */ - -/** - * @} - */ - -/* Private defines -----------------------------------------------------------*/ -/** @defgroup MMC_Private_Defines MMC Private Defines - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup MMC_Private_Variables MMC Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup MMC_Private_Constants MMC Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup MMC_Private_Macros MMC Private Macros - * @{ - */ - -/** - * @} - */ - -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup MMC_Private_Functions_Prototypes MMC Private Functions Prototypes - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup MMC_Private_Functions MMC Private Functions - * @{ - */ - -/** - * @} - */ - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* SDIO */ - -#endif /* STM32F4xx_HAL_MMC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nand.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nand.h deleted file mode 100644 index e6aaabbb5d35325..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nand.h +++ /dev/null @@ -1,381 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_nand.h - * @author MCD Application Team - * @brief Header file of NAND HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_NAND_H -#define __STM32F4xx_HAL_NAND_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) - #include "stm32f4xx_ll_fsmc.h" -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #include "stm32f4xx_ll_fmc.h" -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ - STM32F479xx */ - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup NAND - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/* Exported typedef ----------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup NAND_Exported_Types NAND Exported Types - * @{ - */ - -/** - * @brief HAL NAND State structures definition - */ -typedef enum -{ - HAL_NAND_STATE_RESET = 0x00U, /*!< NAND not yet initialized or disabled */ - HAL_NAND_STATE_READY = 0x01U, /*!< NAND initialized and ready for use */ - HAL_NAND_STATE_BUSY = 0x02U, /*!< NAND internal process is ongoing */ - HAL_NAND_STATE_ERROR = 0x03U /*!< NAND error state */ -}HAL_NAND_StateTypeDef; - -/** - * @brief NAND Memory electronic signature Structure definition - */ -typedef struct -{ - /*State = HAL_NAND_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_NAND_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_NAND_STATE_RESET) -#endif - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup NAND_Exported_Functions NAND Exported Functions - * @{ - */ - -/** @addtogroup NAND_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization functions ********************************/ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_NAND_Init(NAND_HandleTypeDef *hnand, FMC_NAND_PCC_TimingTypeDef *ComSpace_Timing, FMC_NAND_PCC_TimingTypeDef *AttSpace_Timing); -HAL_StatusTypeDef HAL_NAND_DeInit(NAND_HandleTypeDef *hnand); - -HAL_StatusTypeDef HAL_NAND_ConfigDevice(NAND_HandleTypeDef *hnand, NAND_DeviceConfigTypeDef *pDeviceConfig); - -HAL_StatusTypeDef HAL_NAND_Read_ID(NAND_HandleTypeDef *hnand, NAND_IDTypeDef *pNAND_ID); - -void HAL_NAND_MspInit(NAND_HandleTypeDef *hnand); -void HAL_NAND_MspDeInit(NAND_HandleTypeDef *hnand); -void HAL_NAND_IRQHandler(NAND_HandleTypeDef *hnand); -void HAL_NAND_ITCallback(NAND_HandleTypeDef *hnand); - -/** - * @} - */ - -/** @addtogroup NAND_Exported_Functions_Group2 Input and Output functions - * @{ - */ - -/* IO operation functions ****************************************************/ -HAL_StatusTypeDef HAL_NAND_Reset(NAND_HandleTypeDef *hnand); - -HAL_StatusTypeDef HAL_NAND_Read_Page_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumPageToRead); -HAL_StatusTypeDef HAL_NAND_Write_Page_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumPageToWrite); -HAL_StatusTypeDef HAL_NAND_Read_SpareArea_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumSpareAreaToRead); -HAL_StatusTypeDef HAL_NAND_Write_SpareArea_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumSpareAreaTowrite); - -HAL_StatusTypeDef HAL_NAND_Read_Page_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumPageToRead); -HAL_StatusTypeDef HAL_NAND_Write_Page_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumPageToWrite); -HAL_StatusTypeDef HAL_NAND_Read_SpareArea_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumSpareAreaToRead); -HAL_StatusTypeDef HAL_NAND_Write_SpareArea_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumSpareAreaTowrite); - -HAL_StatusTypeDef HAL_NAND_Erase_Block(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress); - -uint32_t HAL_NAND_Read_Status(NAND_HandleTypeDef *hnand); -uint32_t HAL_NAND_Address_Inc(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress); - -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) -/* NAND callback registering/unregistering */ -HAL_StatusTypeDef HAL_NAND_RegisterCallback(NAND_HandleTypeDef *hnand, HAL_NAND_CallbackIDTypeDef CallbackId, pNAND_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_NAND_UnRegisterCallback(NAND_HandleTypeDef *hnand, HAL_NAND_CallbackIDTypeDef CallbackId); -#endif - -/** - * @} - */ - -/** @addtogroup NAND_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ - -/* NAND Control functions ****************************************************/ -HAL_StatusTypeDef HAL_NAND_ECC_Enable(NAND_HandleTypeDef *hnand); -HAL_StatusTypeDef HAL_NAND_ECC_Disable(NAND_HandleTypeDef *hnand); -HAL_StatusTypeDef HAL_NAND_GetECC(NAND_HandleTypeDef *hnand, uint32_t *ECCval, uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup NAND_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -/* NAND State functions *******************************************************/ -HAL_NAND_StateTypeDef HAL_NAND_GetState(NAND_HandleTypeDef *hnand); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup NAND_Private_Constants NAND Private Constants - * @{ - */ -#define NAND_DEVICE1 0x70000000U -#define NAND_DEVICE2 0x80000000U -#define NAND_WRITE_TIMEOUT 0x01000000U - -#define CMD_AREA ((uint32_t)(1U<<16U)) /* A16 = CLE high */ -#define ADDR_AREA ((uint32_t)(1U<<17U)) /* A17 = ALE high */ - -#define NAND_CMD_AREA_A ((uint8_t)0x00) -#define NAND_CMD_AREA_B ((uint8_t)0x01) -#define NAND_CMD_AREA_C ((uint8_t)0x50) -#define NAND_CMD_AREA_TRUE1 ((uint8_t)0x30) - -#define NAND_CMD_WRITE0 ((uint8_t)0x80) -#define NAND_CMD_WRITE_TRUE1 ((uint8_t)0x10) -#define NAND_CMD_ERASE0 ((uint8_t)0x60) -#define NAND_CMD_ERASE1 ((uint8_t)0xD0) -#define NAND_CMD_READID ((uint8_t)0x90) -#define NAND_CMD_STATUS ((uint8_t)0x70) -#define NAND_CMD_LOCK_STATUS ((uint8_t)0x7A) -#define NAND_CMD_RESET ((uint8_t)0xFF) - -/* NAND memory status */ -#define NAND_VALID_ADDRESS 0x00000100U -#define NAND_INVALID_ADDRESS 0x00000200U -#define NAND_TIMEOUT_ERROR 0x00000400U -#define NAND_BUSY 0x00000000U -#define NAND_ERROR 0x00000001U -#define NAND_READY 0x00000040U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup NAND_Private_Macros NAND Private Macros - * @{ - */ - -/** - * @brief NAND memory address computation. - * @param __ADDRESS__ NAND memory address. - * @param __HANDLE__ NAND handle. - * @retval NAND Raw address value - */ -#define ARRAY_ADDRESS(__ADDRESS__ , __HANDLE__) ((__ADDRESS__)->Page + \ - (((__ADDRESS__)->Block + (((__ADDRESS__)->Plane) * ((__HANDLE__)->Config.PlaneSize)))* ((__HANDLE__)->Config.BlockSize))) - -/** - * @brief NAND memory Column address computation. - * @param __HANDLE__ NAND handle. - * @retval NAND Raw address value - */ -#define COLUMN_ADDRESS( __HANDLE__) ((__HANDLE__)->Config.PageSize) - -/** - * @brief NAND memory address cycling. - * @param __ADDRESS__ NAND memory address. - * @retval NAND address cycling value. - */ -#define ADDR_1ST_CYCLE(__ADDRESS__) (uint8_t)(__ADDRESS__) /* 1st addressing cycle */ -#define ADDR_2ND_CYCLE(__ADDRESS__) (uint8_t)((__ADDRESS__) >> 8) /* 2nd addressing cycle */ -#define ADDR_3RD_CYCLE(__ADDRESS__) (uint8_t)((__ADDRESS__) >> 16) /* 3rd addressing cycle */ -#define ADDR_4TH_CYCLE(__ADDRESS__) (uint8_t)((__ADDRESS__) >> 24) /* 4th addressing cycle */ - -/** - * @brief NAND memory Columns cycling. - * @param __ADDRESS__ NAND memory address. - * @retval NAND Column address cycling value. - */ -#define COLUMN_1ST_CYCLE(__ADDRESS__) (uint8_t)(__ADDRESS__) /* 1st Column addressing cycle */ -#define COLUMN_2ND_CYCLE(__ADDRESS__) (uint8_t)((__ADDRESS__) >> 8) /* 2nd Column addressing cycle */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ - STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx ||\ - STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_NAND_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nor.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nor.h deleted file mode 100644 index dcd25c505725c4f..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nor.h +++ /dev/null @@ -1,326 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_nor.h - * @author MCD Application Team - * @brief Header file of NOR HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_NOR_H -#define __STM32F4xx_HAL_NOR_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - #include "stm32f4xx_ll_fsmc.h" -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #include "stm32f4xx_ll_fmc.h" -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup NOR - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - -/* Exported typedef ----------------------------------------------------------*/ -/** @defgroup NOR_Exported_Types NOR Exported Types - * @{ - */ - -/** - * @brief HAL SRAM State structures definition - */ -typedef enum -{ - HAL_NOR_STATE_RESET = 0x00U, /*!< NOR not yet initialized or disabled */ - HAL_NOR_STATE_READY = 0x01U, /*!< NOR initialized and ready for use */ - HAL_NOR_STATE_BUSY = 0x02U, /*!< NOR internal processing is ongoing */ - HAL_NOR_STATE_ERROR = 0x03U, /*!< NOR error state */ - HAL_NOR_STATE_PROTECTED = 0x04U /*!< NOR NORSRAM device write protected */ -}HAL_NOR_StateTypeDef; - -/** - * @brief FMC NOR Status typedef - */ -typedef enum -{ - HAL_NOR_STATUS_SUCCESS = 0U, - HAL_NOR_STATUS_ONGOING, - HAL_NOR_STATUS_ERROR, - HAL_NOR_STATUS_TIMEOUT -}HAL_NOR_StatusTypeDef; - -/** - * @brief FMC NOR ID typedef - */ -typedef struct -{ - uint16_t Manufacturer_Code; /*!< Defines the device's manufacturer code used to identify the memory */ - - uint16_t Device_Code1; - - uint16_t Device_Code2; - - uint16_t Device_Code3; /*!< Defines the device's codes used to identify the memory. - These codes can be accessed by performing read operations with specific - control signals and addresses set.They can also be accessed by issuing - an Auto Select command */ -}NOR_IDTypeDef; - -/** - * @brief FMC NOR CFI typedef - */ -typedef struct -{ - /*!< Defines the information stored in the memory's Common flash interface - which contains a description of various electrical and timing parameters, - density information and functions supported by the memory */ - - uint16_t CFI_1; - - uint16_t CFI_2; - - uint16_t CFI_3; - - uint16_t CFI_4; -}NOR_CFITypeDef; - -/** - * @brief NOR handle Structure definition - */ -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -typedef struct __NOR_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_NOR_REGISTER_CALLBACKS */ - -{ - FMC_NORSRAM_TypeDef *Instance; /*!< Register base address */ - - FMC_NORSRAM_EXTENDED_TypeDef *Extended; /*!< Extended mode register base address */ - - FMC_NORSRAM_InitTypeDef Init; /*!< NOR device control configuration parameters */ - - HAL_LockTypeDef Lock; /*!< NOR locking object */ - - __IO HAL_NOR_StateTypeDef State; /*!< NOR device access state */ - -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) - void (* MspInitCallback) ( struct __NOR_HandleTypeDef * hnor); /*!< NOR Msp Init callback */ - void (* MspDeInitCallback) ( struct __NOR_HandleTypeDef * hnor); /*!< NOR Msp DeInit callback */ -#endif -} NOR_HandleTypeDef; - -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -/** - * @brief HAL NOR Callback ID enumeration definition - */ -typedef enum -{ - HAL_NOR_MSP_INIT_CB_ID = 0x00U, /*!< NOR MspInit Callback ID */ - HAL_NOR_MSP_DEINIT_CB_ID = 0x01U /*!< NOR MspDeInit Callback ID */ -}HAL_NOR_CallbackIDTypeDef; - -/** - * @brief HAL NOR Callback pointer definition - */ -typedef void (*pNOR_CallbackTypeDef)(NOR_HandleTypeDef *hnor); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/* Exported macros ------------------------------------------------------------*/ -/** @defgroup NOR_Exported_Macros NOR Exported Macros - * @{ - */ -/** @brief Reset NOR handle state - * @param __HANDLE__ specifies the NOR handle. - * @retval None - */ -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -#define __HAL_NOR_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_NOR_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_NOR_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_NOR_STATE_RESET) -#endif -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup NOR_Exported_Functions - * @{ - */ - -/** @addtogroup NOR_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_NOR_Init(NOR_HandleTypeDef *hnor, FMC_NORSRAM_TimingTypeDef *Timing, FMC_NORSRAM_TimingTypeDef *ExtTiming); -HAL_StatusTypeDef HAL_NOR_DeInit(NOR_HandleTypeDef *hnor); -void HAL_NOR_MspInit(NOR_HandleTypeDef *hnor); -void HAL_NOR_MspDeInit(NOR_HandleTypeDef *hnor); -void HAL_NOR_MspWait(NOR_HandleTypeDef *hnor, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup NOR_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -HAL_StatusTypeDef HAL_NOR_Read_ID(NOR_HandleTypeDef *hnor, NOR_IDTypeDef *pNOR_ID); -HAL_StatusTypeDef HAL_NOR_ReturnToReadMode(NOR_HandleTypeDef *hnor); -HAL_StatusTypeDef HAL_NOR_Read(NOR_HandleTypeDef *hnor, uint32_t *pAddress, uint16_t *pData); -HAL_StatusTypeDef HAL_NOR_Program(NOR_HandleTypeDef *hnor, uint32_t *pAddress, uint16_t *pData); - -HAL_StatusTypeDef HAL_NOR_ReadBuffer(NOR_HandleTypeDef *hnor, uint32_t uwAddress, uint16_t *pData, uint32_t uwBufferSize); -HAL_StatusTypeDef HAL_NOR_ProgramBuffer(NOR_HandleTypeDef *hnor, uint32_t uwAddress, uint16_t *pData, uint32_t uwBufferSize); - -HAL_StatusTypeDef HAL_NOR_Erase_Block(NOR_HandleTypeDef *hnor, uint32_t BlockAddress, uint32_t Address); -HAL_StatusTypeDef HAL_NOR_Erase_Chip(NOR_HandleTypeDef *hnor, uint32_t Address); -HAL_StatusTypeDef HAL_NOR_Read_CFI(NOR_HandleTypeDef *hnor, NOR_CFITypeDef *pNOR_CFI); - -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -/* NOR callback registering/unregistering */ -HAL_StatusTypeDef HAL_NOR_RegisterCallback(NOR_HandleTypeDef *hnor, HAL_NOR_CallbackIDTypeDef CallbackId, pNOR_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_NOR_UnRegisterCallback(NOR_HandleTypeDef *hnor, HAL_NOR_CallbackIDTypeDef CallbackId); -#endif -/** - * @} - */ - -/** @addtogroup NOR_Exported_Functions_Group3 - * @{ - */ -/* NOR Control functions *****************************************************/ -HAL_StatusTypeDef HAL_NOR_WriteOperation_Enable(NOR_HandleTypeDef *hnor); -HAL_StatusTypeDef HAL_NOR_WriteOperation_Disable(NOR_HandleTypeDef *hnor); -/** - * @} - */ - -/** @addtogroup NOR_Exported_Functions_Group4 - * @{ - */ -/* NOR State functions ********************************************************/ -HAL_NOR_StateTypeDef HAL_NOR_GetState(NOR_HandleTypeDef *hnor); -HAL_NOR_StatusTypeDef HAL_NOR_GetStatus(NOR_HandleTypeDef *hnor, uint32_t Address, uint32_t Timeout); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup NOR_Private_Constants NOR Private Constants - * @{ - */ -/* NOR device IDs addresses */ -#define MC_ADDRESS ((uint16_t)0x0000) -#define DEVICE_CODE1_ADDR ((uint16_t)0x0001) -#define DEVICE_CODE2_ADDR ((uint16_t)0x000E) -#define DEVICE_CODE3_ADDR ((uint16_t)0x000F) - -/* NOR CFI IDs addresses */ -#define CFI1_ADDRESS ((uint16_t)0x0061) -#define CFI2_ADDRESS ((uint16_t)0x0062) -#define CFI3_ADDRESS ((uint16_t)0x0063) -#define CFI4_ADDRESS ((uint16_t)0x0064) - -/* NOR operation wait timeout */ -#define NOR_TMEOUT ((uint16_t)0xFFFF) - -/* NOR memory data width */ -#define NOR_MEMORY_8B ((uint8_t)0x00) -#define NOR_MEMORY_16B ((uint8_t)0x01) - -/* NOR memory device read/write start address */ -#define NOR_MEMORY_ADRESS1 0x60000000U -#define NOR_MEMORY_ADRESS2 0x64000000U -#define NOR_MEMORY_ADRESS3 0x68000000U -#define NOR_MEMORY_ADRESS4 0x6C000000U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup NOR_Private_Macros NOR Private Macros - * @{ - */ -/** - * @brief NOR memory address shifting. - * @param __NOR_ADDRESS__ NOR base address - * @param NOR_MEMORY_WIDTH NOR memory width - * @param ADDRESS NOR memory address - * @retval NOR shifted address value - */ -#define NOR_ADDR_SHIFT(__NOR_ADDRESS__, NOR_MEMORY_WIDTH, ADDRESS) (uint32_t)(((NOR_MEMORY_WIDTH) == NOR_MEMORY_16B)? ((uint32_t)((__NOR_ADDRESS__) + (2U * (ADDRESS)))):\ - ((uint32_t)((__NOR_ADDRESS__) + (ADDRESS)))) - -/** - * @brief NOR memory write data to specified address. - * @param ADDRESS NOR memory address - * @param DATA Data to write - * @retval None - */ -#define NOR_WRITE(ADDRESS, DATA) (*(__IO uint16_t *)((uint32_t)(ADDRESS)) = (DATA)) - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ - STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx ||\ - STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_NOR_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pccard.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pccard.h deleted file mode 100644 index 41d7824e06339f9..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pccard.h +++ /dev/null @@ -1,287 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pccard.h - * @author MCD Application Team - * @brief Header file of PCCARD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_PCCARD_H -#define __STM32F4xx_HAL_PCCARD_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) - #include "stm32f4xx_ll_fsmc.h" -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) - #include "stm32f4xx_ll_fmc.h" -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) - -/** @addtogroup PCCARD - * @{ - */ - -/* Exported typedef ----------------------------------------------------------*/ -/** @defgroup PCCARD_Exported_Types PCCARD Exported Types - * @{ - */ - -/** - * @brief HAL PCCARD State structures definition - */ -typedef enum -{ - HAL_PCCARD_STATE_RESET = 0x00U, /*!< PCCARD peripheral not yet initialized or disabled */ - HAL_PCCARD_STATE_READY = 0x01U, /*!< PCCARD peripheral ready */ - HAL_PCCARD_STATE_BUSY = 0x02U, /*!< PCCARD peripheral busy */ - HAL_PCCARD_STATE_ERROR = 0x04U /*!< PCCARD peripheral error */ -}HAL_PCCARD_StateTypeDef; - -typedef enum -{ - HAL_PCCARD_STATUS_SUCCESS = 0U, - HAL_PCCARD_STATUS_ONGOING, - HAL_PCCARD_STATUS_ERROR, - HAL_PCCARD_STATUS_TIMEOUT -}HAL_PCCARD_StatusTypeDef; - -/** - * @brief FMC_PCCARD handle Structure definition - */ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -typedef struct __PCCARD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_PCCARD_REGISTER_CALLBACKS */ -{ - FMC_PCCARD_TypeDef *Instance; /*!< Register base address for PCCARD device */ - - FMC_PCCARD_InitTypeDef Init; /*!< PCCARD device control configuration parameters */ - - __IO HAL_PCCARD_StateTypeDef State; /*!< PCCARD device access state */ - - HAL_LockTypeDef Lock; /*!< PCCARD Lock */ - -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) - void (* MspInitCallback) ( struct __PCCARD_HandleTypeDef * hpccard); /*!< PCCARD Msp Init callback */ - void (* MspDeInitCallback) ( struct __PCCARD_HandleTypeDef * hpccard); /*!< PCCARD Msp DeInit callback */ - void (* ItCallback) ( struct __PCCARD_HandleTypeDef * hpccard); /*!< PCCARD IT callback */ -#endif -} PCCARD_HandleTypeDef; - -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -/** - * @brief HAL PCCARD Callback ID enumeration definition - */ -typedef enum -{ - HAL_PCCARD_MSP_INIT_CB_ID = 0x00U, /*!< PCCARD MspInit Callback ID */ - HAL_PCCARD_MSP_DEINIT_CB_ID = 0x01U, /*!< PCCARD MspDeInit Callback ID */ - HAL_PCCARD_IT_CB_ID = 0x02U /*!< PCCARD IT Callback ID */ -}HAL_PCCARD_CallbackIDTypeDef; - -/** - * @brief HAL PCCARD Callback pointer definition - */ -typedef void (*pPCCARD_CallbackTypeDef)(PCCARD_HandleTypeDef *hpccard); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PCCARD_Exported_Macros PCCARD Exported Macros - * @{ - */ -/** @brief Reset PCCARD handle state - * @param __HANDLE__ specifies the PCCARD handle. - * @retval None - */ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -#define __HAL_PCCARD_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_PCCARD_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_PCCARD_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_PCCARD_STATE_RESET) -#endif -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PCCARD_Exported_Functions - * @{ - */ - -/** @addtogroup PCCARD_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_PCCARD_Init(PCCARD_HandleTypeDef *hpccard, FMC_NAND_PCC_TimingTypeDef *ComSpaceTiming, FMC_NAND_PCC_TimingTypeDef *AttSpaceTiming, FMC_NAND_PCC_TimingTypeDef *IOSpaceTiming); -HAL_StatusTypeDef HAL_PCCARD_DeInit(PCCARD_HandleTypeDef *hpccard); -void HAL_PCCARD_MspInit(PCCARD_HandleTypeDef *hpccard); -void HAL_PCCARD_MspDeInit(PCCARD_HandleTypeDef *hpccard); -/** - * @} - */ - -/** @addtogroup PCCARD_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -HAL_StatusTypeDef HAL_PCCARD_Read_ID(PCCARD_HandleTypeDef *hpccard, uint8_t CompactFlash_ID[], uint8_t *pStatus); -HAL_StatusTypeDef HAL_PCCARD_Write_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t *pBuffer, uint16_t SectorAddress, uint8_t *pStatus); -HAL_StatusTypeDef HAL_PCCARD_Read_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t *pBuffer, uint16_t SectorAddress, uint8_t *pStatus); -HAL_StatusTypeDef HAL_PCCARD_Erase_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t SectorAddress, uint8_t *pStatus); -HAL_StatusTypeDef HAL_PCCARD_Reset(PCCARD_HandleTypeDef *hpccard); -void HAL_PCCARD_IRQHandler(PCCARD_HandleTypeDef *hpccard); -void HAL_PCCARD_ITCallback(PCCARD_HandleTypeDef *hpccard); - -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -/* PCCARD callback registering/unregistering */ -HAL_StatusTypeDef HAL_PCCARD_RegisterCallback(PCCARD_HandleTypeDef *hpccard, HAL_PCCARD_CallbackIDTypeDef CallbackId, pPCCARD_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_PCCARD_UnRegisterCallback(PCCARD_HandleTypeDef *hpccard, HAL_PCCARD_CallbackIDTypeDef CallbackId); -#endif -/** - * @} - */ - -/** @addtogroup PCCARD_Exported_Functions_Group3 - * @{ - */ -/* PCCARD State functions *******************************************************/ -HAL_PCCARD_StateTypeDef HAL_PCCARD_GetState(PCCARD_HandleTypeDef *hpccard); -HAL_PCCARD_StatusTypeDef HAL_PCCARD_GetStatus(PCCARD_HandleTypeDef *hpccard); -HAL_PCCARD_StatusTypeDef HAL_PCCARD_ReadStatus(PCCARD_HandleTypeDef *hpccard); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PCCARD_Private_Constants PCCARD Private Constants - * @{ - */ -#define PCCARD_DEVICE_ADDRESS 0x90000000U -#define PCCARD_ATTRIBUTE_SPACE_ADDRESS 0x98000000U /* Attribute space size to @0x9BFF FFFF */ -#define PCCARD_COMMON_SPACE_ADDRESS PCCARD_DEVICE_ADDRESS /* Common space size to @0x93FF FFFF */ -#define PCCARD_IO_SPACE_ADDRESS 0x9C000000U /* IO space size to @0x9FFF FFFF */ -#define PCCARD_IO_SPACE_PRIMARY_ADDR 0x9C0001F0U /* IO space size to @0x9FFF FFFF */ - -/* Flash-ATA registers description */ -#define ATA_DATA ((uint8_t)0x00) /* Data register */ -#define ATA_SECTOR_COUNT ((uint8_t)0x02) /* Sector Count register */ -#define ATA_SECTOR_NUMBER ((uint8_t)0x03) /* Sector Number register */ -#define ATA_CYLINDER_LOW ((uint8_t)0x04) /* Cylinder low register */ -#define ATA_CYLINDER_HIGH ((uint8_t)0x05) /* Cylinder high register */ -#define ATA_CARD_HEAD ((uint8_t)0x06) /* Card/Head register */ -#define ATA_STATUS_CMD ((uint8_t)0x07) /* Status(read)/Command(write) register */ -#define ATA_STATUS_CMD_ALTERNATE ((uint8_t)0x0E) /* Alternate Status(read)/Command(write) register */ -#define ATA_COMMON_DATA_AREA ((uint16_t)0x0400) /* Start of data area (for Common access only!) */ -#define ATA_CARD_CONFIGURATION ((uint16_t)0x0202) /* Card Configuration and Status Register */ - -/* Flash-ATA commands */ -#define ATA_READ_SECTOR_CMD ((uint8_t)0x20) -#define ATA_WRITE_SECTOR_CMD ((uint8_t)0x30) -#define ATA_ERASE_SECTOR_CMD ((uint8_t)0xC0) -#define ATA_IDENTIFY_CMD ((uint8_t)0xEC) - -/* PC Card/Compact Flash status */ -#define PCCARD_TIMEOUT_ERROR ((uint8_t)0x60) -#define PCCARD_BUSY ((uint8_t)0x80) -#define PCCARD_PROGR ((uint8_t)0x01) -#define PCCARD_READY ((uint8_t)0x40) - -#define PCCARD_SECTOR_SIZE 255U /* In half words */ - -/** - * @} - */ -/* Compact Flash redefinition */ -#define HAL_CF_Init HAL_PCCARD_Init -#define HAL_CF_DeInit HAL_PCCARD_DeInit -#define HAL_CF_MspInit HAL_PCCARD_MspInit -#define HAL_CF_MspDeInit HAL_PCCARD_MspDeInit - -#define HAL_CF_Read_ID HAL_PCCARD_Read_ID -#define HAL_CF_Write_Sector HAL_PCCARD_Write_Sector -#define HAL_CF_Read_Sector HAL_PCCARD_Read_Sector -#define HAL_CF_Erase_Sector HAL_PCCARD_Erase_Sector -#define HAL_CF_Reset HAL_PCCARD_Reset -#define HAL_CF_IRQHandler HAL_PCCARD_IRQHandler -#define HAL_CF_ITCallback HAL_PCCARD_ITCallback - -#define HAL_CF_GetState HAL_PCCARD_GetState -#define HAL_CF_GetStatus HAL_PCCARD_GetStatus -#define HAL_CF_ReadStatus HAL_PCCARD_ReadStatus - -#define HAL_CF_STATUS_SUCCESS HAL_PCCARD_STATUS_SUCCESS -#define HAL_CF_STATUS_ONGOING HAL_PCCARD_STATUS_ONGOING -#define HAL_CF_STATUS_ERROR HAL_PCCARD_STATUS_ERROR -#define HAL_CF_STATUS_TIMEOUT HAL_PCCARD_STATUS_TIMEOUT -#define HAL_CF_StatusTypeDef HAL_PCCARD_StatusTypeDef - -#define CF_DEVICE_ADDRESS PCCARD_DEVICE_ADDRESS -#define CF_ATTRIBUTE_SPACE_ADDRESS PCCARD_ATTRIBUTE_SPACE_ADDRESS -#define CF_COMMON_SPACE_ADDRESS PCCARD_COMMON_SPACE_ADDRESS -#define CF_IO_SPACE_ADDRESS PCCARD_IO_SPACE_ADDRESS -#define CF_IO_SPACE_PRIMARY_ADDR PCCARD_IO_SPACE_PRIMARY_ADDR - -#define CF_TIMEOUT_ERROR PCCARD_TIMEOUT_ERROR -#define CF_BUSY PCCARD_BUSY -#define CF_PROGR PCCARD_PROGR -#define CF_READY PCCARD_READY - -#define CF_SECTOR_SIZE PCCARD_SECTOR_SIZE - -/* Private macros ------------------------------------------------------------*/ -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ - STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_PCCARD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h deleted file mode 100644 index e28285d47515f13..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h +++ /dev/null @@ -1,472 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd.h - * @author MCD Application Team - * @brief Header file of PCD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_PCD_H -#define STM32F4xx_HAL_PCD_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_usb.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PCD - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup PCD_Exported_Types PCD Exported Types - * @{ - */ - -/** - * @brief PCD State structure definition - */ -typedef enum -{ - HAL_PCD_STATE_RESET = 0x00, - HAL_PCD_STATE_READY = 0x01, - HAL_PCD_STATE_ERROR = 0x02, - HAL_PCD_STATE_BUSY = 0x03, - HAL_PCD_STATE_TIMEOUT = 0x04 -} PCD_StateTypeDef; - -/* Device LPM suspend state */ -typedef enum -{ - LPM_L0 = 0x00, /* on */ - LPM_L1 = 0x01, /* LPM L1 sleep */ - LPM_L2 = 0x02, /* suspend */ - LPM_L3 = 0x03, /* off */ -} PCD_LPM_StateTypeDef; - -typedef enum -{ - PCD_LPM_L0_ACTIVE = 0x00, /* on */ - PCD_LPM_L1_ACTIVE = 0x01, /* LPM L1 sleep */ -} PCD_LPM_MsgTypeDef; - -typedef enum -{ - PCD_BCD_ERROR = 0xFF, - PCD_BCD_CONTACT_DETECTION = 0xFE, - PCD_BCD_STD_DOWNSTREAM_PORT = 0xFD, - PCD_BCD_CHARGING_DOWNSTREAM_PORT = 0xFC, - PCD_BCD_DEDICATED_CHARGING_PORT = 0xFB, - PCD_BCD_DISCOVERY_COMPLETED = 0x00, - -} PCD_BCD_MsgTypeDef; - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -typedef USB_OTG_GlobalTypeDef PCD_TypeDef; -typedef USB_OTG_CfgTypeDef PCD_InitTypeDef; -typedef USB_OTG_EPTypeDef PCD_EPTypeDef; -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/** - * @brief PCD Handle Structure definition - */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -typedef struct __PCD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -{ - PCD_TypeDef *Instance; /*!< Register base address */ - PCD_InitTypeDef Init; /*!< PCD required parameters */ - __IO uint8_t USB_Address; /*!< USB Address */ - PCD_EPTypeDef IN_ep[16]; /*!< IN endpoint parameters */ - PCD_EPTypeDef OUT_ep[16]; /*!< OUT endpoint parameters */ - HAL_LockTypeDef Lock; /*!< PCD peripheral status */ - __IO PCD_StateTypeDef State; /*!< PCD communication state */ - __IO uint32_t ErrorCode; /*!< PCD Error code */ - uint32_t Setup[12]; /*!< Setup packet buffer */ - PCD_LPM_StateTypeDef LPM_State; /*!< LPM State */ - uint32_t BESL; - - - uint32_t lpm_active; /*!< Enable or disable the Link Power Management . - This parameter can be set to ENABLE or DISABLE */ - - uint32_t battery_charging_active; /*!< Enable or disable Battery charging. - This parameter can be set to ENABLE or DISABLE */ - void *pData; /*!< Pointer to upper stack Handler */ - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - void (* SOFCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD SOF callback */ - void (* SetupStageCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Setup Stage callback */ - void (* ResetCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Reset callback */ - void (* SuspendCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Suspend callback */ - void (* ResumeCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Resume callback */ - void (* ConnectCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Connect callback */ - void (* DisconnectCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Disconnect callback */ - - void (* DataOutStageCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD Data OUT Stage callback */ - void (* DataInStageCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD Data IN Stage callback */ - void (* ISOOUTIncompleteCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD ISO OUT Incomplete callback */ - void (* ISOINIncompleteCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD ISO IN Incomplete callback */ - void (* BCDCallback)(struct __PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); /*!< USB OTG PCD BCD callback */ - void (* LPMCallback)(struct __PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); /*!< USB OTG PCD LPM callback */ - - void (* MspInitCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Msp Init callback */ - void (* MspDeInitCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Msp DeInit callback */ -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -} PCD_HandleTypeDef; - -/** - * @} - */ - -/* Include PCD HAL Extended module */ -#include "stm32f4xx_hal_pcd_ex.h" - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PCD_Exported_Constants PCD Exported Constants - * @{ - */ - -/** @defgroup PCD_Speed PCD Speed - * @{ - */ -#define PCD_SPEED_HIGH USBD_HS_SPEED -#define PCD_SPEED_HIGH_IN_FULL USBD_HSINFS_SPEED -#define PCD_SPEED_FULL USBD_FS_SPEED -/** - * @} - */ - -/** @defgroup PCD_PHY_Module PCD PHY Module - * @{ - */ -#define PCD_PHY_ULPI 1U -#define PCD_PHY_EMBEDDED 2U -#define PCD_PHY_UTMI 3U -/** - * @} - */ - -/** @defgroup PCD_Error_Code_definition PCD Error Code definition - * @brief PCD Error Code definition - * @{ - */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -#define HAL_PCD_ERROR_INVALID_CALLBACK (0x00000010U) /*!< Invalid Callback error */ -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup PCD_Exported_Macros PCD Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define __HAL_PCD_ENABLE(__HANDLE__) (void)USB_EnableGlobalInt ((__HANDLE__)->Instance) -#define __HAL_PCD_DISABLE(__HANDLE__) (void)USB_DisableGlobalInt ((__HANDLE__)->Instance) - -#define __HAL_PCD_GET_FLAG(__HANDLE__, __INTERRUPT__) \ - ((USB_ReadInterrupts((__HANDLE__)->Instance) & (__INTERRUPT__)) == (__INTERRUPT__)) - -#define __HAL_PCD_CLEAR_FLAG(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->GINTSTS) &= (__INTERRUPT__)) -#define __HAL_PCD_IS_INVALID_INTERRUPT(__HANDLE__) (USB_ReadInterrupts((__HANDLE__)->Instance) == 0U) - -#define __HAL_PCD_UNGATE_PHYCLOCK(__HANDLE__) \ - *(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE) &= ~(USB_OTG_PCGCCTL_STOPCLK) - -#define __HAL_PCD_GATE_PHYCLOCK(__HANDLE__) \ - *(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE) |= USB_OTG_PCGCCTL_STOPCLK - -#define __HAL_PCD_IS_PHY_SUSPENDED(__HANDLE__) \ - ((*(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE)) & 0x10U) - -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= (USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = (USB_OTG_HS_WAKEUP_EXTI_LINE) - -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE() \ - do { \ - EXTI->FTSR &= ~(USB_OTG_HS_WAKEUP_EXTI_LINE); \ - EXTI->RTSR |= USB_OTG_HS_WAKEUP_EXTI_LINE; \ - } while(0U) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= USB_OTG_FS_WAKEUP_EXTI_LINE -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_OTG_FS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (USB_OTG_FS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = USB_OTG_FS_WAKEUP_EXTI_LINE - -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE() \ - do { \ - EXTI->FTSR &= ~(USB_OTG_FS_WAKEUP_EXTI_LINE); \ - EXTI->RTSR |= USB_OTG_FS_WAKEUP_EXTI_LINE; \ - } while(0U) -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PCD_Exported_Functions PCD Exported Functions - * @{ - */ - -/* Initialization/de-initialization functions ********************************/ -/** @addtogroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd); -void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd); -void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd); - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -/** @defgroup HAL_PCD_Callback_ID_enumeration_definition HAL USB OTG PCD Callback ID enumeration definition - * @brief HAL USB OTG PCD Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_PCD_SOF_CB_ID = 0x01, /*!< USB PCD SOF callback ID */ - HAL_PCD_SETUPSTAGE_CB_ID = 0x02, /*!< USB PCD Setup Stage callback ID */ - HAL_PCD_RESET_CB_ID = 0x03, /*!< USB PCD Reset callback ID */ - HAL_PCD_SUSPEND_CB_ID = 0x04, /*!< USB PCD Suspend callback ID */ - HAL_PCD_RESUME_CB_ID = 0x05, /*!< USB PCD Resume callback ID */ - HAL_PCD_CONNECT_CB_ID = 0x06, /*!< USB PCD Connect callback ID */ - HAL_PCD_DISCONNECT_CB_ID = 0x07, /*!< USB PCD Disconnect callback ID */ - - HAL_PCD_MSPINIT_CB_ID = 0x08, /*!< USB PCD MspInit callback ID */ - HAL_PCD_MSPDEINIT_CB_ID = 0x09 /*!< USB PCD MspDeInit callback ID */ - -} HAL_PCD_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup HAL_PCD_Callback_pointer_definition HAL USB OTG PCD Callback pointer definition - * @brief HAL USB OTG PCD Callback pointer definition - * @{ - */ - -typedef void (*pPCD_CallbackTypeDef)(PCD_HandleTypeDef *hpcd); /*!< pointer to a common USB OTG PCD callback function */ -typedef void (*pPCD_DataOutStageCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD Data OUT Stage callback */ -typedef void (*pPCD_DataInStageCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD Data IN Stage callback */ -typedef void (*pPCD_IsoOutIncpltCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD ISO OUT Incomplete callback */ -typedef void (*pPCD_IsoInIncpltCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD ISO IN Incomplete callback */ -typedef void (*pPCD_LpmCallbackTypeDef)(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); /*!< pointer to USB OTG PCD LPM callback */ -typedef void (*pPCD_BcdCallbackTypeDef)(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); /*!< pointer to USB OTG PCD BCD callback */ - -/** - * @} - */ - -HAL_StatusTypeDef HAL_PCD_RegisterCallback(PCD_HandleTypeDef *hpcd, - HAL_PCD_CallbackIDTypeDef CallbackID, - pPCD_CallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterCallback(PCD_HandleTypeDef *hpcd, - HAL_PCD_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_PCD_RegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataOutStageCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterDataInStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataInStageCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterDataInStageCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoOutIncpltCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoInIncpltCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterBcdCallback(PCD_HandleTypeDef *hpcd, - pPCD_BcdCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterBcdCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterLpmCallback(PCD_HandleTypeDef *hpcd, - pPCD_LpmCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterLpmCallback(PCD_HandleTypeDef *hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* I/O operation functions ***************************************************/ -/* Non-Blocking mode: Interrupt */ -/** @addtogroup PCD_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd); -void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd); -void HAL_PCD_WKUP_IRQHandler(PCD_HandleTypeDef *hpcd); - -void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd); - -void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -/** - * @} - */ - -/* Peripheral Control functions **********************************************/ -/** @addtogroup PCD_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address); -HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, - uint16_t ep_mps, uint8_t ep_type); - -HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, - uint8_t *pBuf, uint32_t len); - -HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, - uint8_t *pBuf, uint32_t len); - - -HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd); - -uint32_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -/** - * @} - */ - -/* Peripheral State functions ************************************************/ -/** @addtogroup PCD_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PCD_Private_Constants PCD Private Constants - * @{ - */ -/** @defgroup USB_EXTI_Line_Interrupt USB EXTI line interrupt - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define USB_OTG_FS_WAKEUP_EXTI_LINE (0x1U << 18) /*!< USB FS EXTI Line WakeUp Interrupt */ -#define USB_OTG_HS_WAKEUP_EXTI_LINE (0x1U << 20) /*!< USB HS EXTI Line WakeUp Interrupt */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ -/** - * @} - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#ifndef USB_OTG_DOEPINT_OTEPSPR -#define USB_OTG_DOEPINT_OTEPSPR (0x1UL << 5) /*!< Status Phase Received interrupt */ -#endif /* defined USB_OTG_DOEPINT_OTEPSPR */ - -#ifndef USB_OTG_DOEPMSK_OTEPSPRM -#define USB_OTG_DOEPMSK_OTEPSPRM (0x1UL << 5) /*!< Setup Packet Received interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_OTEPSPRM */ - -#ifndef USB_OTG_DOEPINT_NAK -#define USB_OTG_DOEPINT_NAK (0x1UL << 13) /*!< NAK interrupt */ -#endif /* defined USB_OTG_DOEPINT_NAK */ - -#ifndef USB_OTG_DOEPMSK_NAKM -#define USB_OTG_DOEPMSK_NAKM (0x1UL << 13) /*!< OUT Packet NAK interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_NAKM */ - -#ifndef USB_OTG_DOEPINT_STPKTRX -#define USB_OTG_DOEPINT_STPKTRX (0x1UL << 15) /*!< Setup Packet Received interrupt */ -#endif /* defined USB_OTG_DOEPINT_STPKTRX */ - -#ifndef USB_OTG_DOEPMSK_NYETM -#define USB_OTG_DOEPMSK_NYETM (0x1UL << 14) /*!< Setup Packet Received interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_NYETM */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PCD_Private_Macros PCD Private Macros - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_PCD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h deleted file mode 100644 index 71e9a2c18b4f44f..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h +++ /dev/null @@ -1,91 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd_ex.h - * @author MCD Application Team - * @brief Header file of PCD HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_PCD_EX_H -#define STM32F4xx_HAL_PCD_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PCDEx - * @{ - */ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macros -----------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PCDEx_Exported_Functions PCDEx Exported Functions - * @{ - */ -/** @addtogroup PCDEx_Exported_Functions_Group1 Peripheral Control functions - * @{ - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size); -HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size); -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd); -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd); -void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd); -#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); -void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_PCD_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h deleted file mode 100644 index 6f3bf7141c93df3..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h +++ /dev/null @@ -1,431 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr.h - * @author MCD Application Team - * @brief Header file of PWR HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_PWR_H -#define __STM32F4xx_HAL_PWR_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PWR - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup PWR_Exported_Types PWR Exported Types - * @{ - */ - -/** - * @brief PWR PVD configuration structure definition - */ -typedef struct -{ - uint32_t PVDLevel; /*!< PVDLevel: Specifies the PVD detection level. - This parameter can be a value of @ref PWR_PVD_detection_level */ - - uint32_t Mode; /*!< Mode: Specifies the operating mode for the selected pins. - This parameter can be a value of @ref PWR_PVD_Mode */ -}PWR_PVDTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWR_Exported_Constants PWR Exported Constants - * @{ - */ - -/** @defgroup PWR_WakeUp_Pins PWR WakeUp Pins - * @{ - */ -#define PWR_WAKEUP_PIN1 0x00000100U -/** - * @} - */ - -/** @defgroup PWR_PVD_detection_level PWR PVD detection level - * @{ - */ -#define PWR_PVDLEVEL_0 PWR_CR_PLS_LEV0 -#define PWR_PVDLEVEL_1 PWR_CR_PLS_LEV1 -#define PWR_PVDLEVEL_2 PWR_CR_PLS_LEV2 -#define PWR_PVDLEVEL_3 PWR_CR_PLS_LEV3 -#define PWR_PVDLEVEL_4 PWR_CR_PLS_LEV4 -#define PWR_PVDLEVEL_5 PWR_CR_PLS_LEV5 -#define PWR_PVDLEVEL_6 PWR_CR_PLS_LEV6 -#define PWR_PVDLEVEL_7 PWR_CR_PLS_LEV7/* External input analog voltage - (Compare internally to VREFINT) */ -/** - * @} - */ - -/** @defgroup PWR_PVD_Mode PWR PVD Mode - * @{ - */ -#define PWR_PVD_MODE_NORMAL 0x00000000U /*!< basic mode is used */ -#define PWR_PVD_MODE_IT_RISING 0x00010001U /*!< External Interrupt Mode with Rising edge trigger detection */ -#define PWR_PVD_MODE_IT_FALLING 0x00010002U /*!< External Interrupt Mode with Falling edge trigger detection */ -#define PWR_PVD_MODE_IT_RISING_FALLING 0x00010003U /*!< External Interrupt Mode with Rising/Falling edge trigger detection */ -#define PWR_PVD_MODE_EVENT_RISING 0x00020001U /*!< Event Mode with Rising edge trigger detection */ -#define PWR_PVD_MODE_EVENT_FALLING 0x00020002U /*!< Event Mode with Falling edge trigger detection */ -#define PWR_PVD_MODE_EVENT_RISING_FALLING 0x00020003U /*!< Event Mode with Rising/Falling edge trigger detection */ -/** - * @} - */ - - -/** @defgroup PWR_Regulator_state_in_STOP_mode PWR Regulator state in SLEEP/STOP mode - * @{ - */ -#define PWR_MAINREGULATOR_ON 0x00000000U -#define PWR_LOWPOWERREGULATOR_ON PWR_CR_LPDS -/** - * @} - */ - -/** @defgroup PWR_SLEEP_mode_entry PWR SLEEP mode entry - * @{ - */ -#define PWR_SLEEPENTRY_WFI ((uint8_t)0x01) -#define PWR_SLEEPENTRY_WFE ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup PWR_STOP_mode_entry PWR STOP mode entry - * @{ - */ -#define PWR_STOPENTRY_WFI ((uint8_t)0x01) -#define PWR_STOPENTRY_WFE ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup PWR_Flag PWR Flag - * @{ - */ -#define PWR_FLAG_WU PWR_CSR_WUF -#define PWR_FLAG_SB PWR_CSR_SBF -#define PWR_FLAG_PVDO PWR_CSR_PVDO -#define PWR_FLAG_BRR PWR_CSR_BRR -#define PWR_FLAG_VOSRDY PWR_CSR_VOSRDY -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWR_Exported_Macro PWR Exported Macro - * @{ - */ - -/** @brief Check PWR flag is set or not. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event - * was received from the WKUP pin or from the RTC alarm (Alarm A - * or Alarm B), RTC Tamper event, RTC TimeStamp event or RTC Wakeup. - * An additional wakeup event is detected if the WKUP pin is enabled - * (by setting the EWUP bit) when the WKUP pin level is already high. - * @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was - * resumed from StandBy mode. - * @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled - * by the HAL_PWR_EnablePVD() function. The PVD is stopped by Standby mode - * For this reason, this bit is equal to 0 after Standby or reset - * until the PVDE bit is set. - * @arg PWR_FLAG_BRR: Backup regulator ready flag. This bit is not reset - * when the device wakes up from Standby mode or by a system reset - * or power reset. - * @arg PWR_FLAG_VOSRDY: This flag indicates that the Regulator voltage - * scaling output selection is ready. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_PWR_GET_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the PWR's pending flags. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be one of the following values: - * @arg PWR_FLAG_WU: Wake Up flag - * @arg PWR_FLAG_SB: StandBy flag - */ -#define __HAL_PWR_CLEAR_FLAG(__FLAG__) (PWR->CR |= (__FLAG__) << 2U) - -/** - * @brief Enable the PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_IT() (EXTI->IMR |= (PWR_EXTI_LINE_PVD)) - -/** - * @brief Disable the PVD EXTI Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_IT() (EXTI->IMR &= ~(PWR_EXTI_LINE_PVD)) - -/** - * @brief Enable event on PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_EVENT() (EXTI->EMR |= (PWR_EXTI_LINE_PVD)) - -/** - * @brief Disable event on PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(PWR_EXTI_LINE_PVD)) - -/** - * @brief Enable the PVD Extended Interrupt Rising Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE() SET_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD) - -/** - * @brief Disable the PVD Extended Interrupt Rising Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE() CLEAR_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD) - -/** - * @brief Enable the PVD Extended Interrupt Falling Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE() SET_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD) - - -/** - * @brief Disable the PVD Extended Interrupt Falling Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE() CLEAR_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD) - - -/** - * @brief PVD EXTI line configuration: set rising & falling edge trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_FALLING_EDGE() do{__HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE();\ - __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE();\ - }while(0U) - -/** - * @brief Disable the PVD Extended Interrupt Rising & Falling Trigger. - * This parameter can be: - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_FALLING_EDGE() do{__HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();\ - __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE();\ - }while(0U) - -/** - * @brief checks whether the specified PVD Exti interrupt flag is set or not. - * @retval EXTI PVD Line Status. - */ -#define __HAL_PWR_PVD_EXTI_GET_FLAG() (EXTI->PR & (PWR_EXTI_LINE_PVD)) - -/** - * @brief Clear the PVD Exti flag. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_CLEAR_FLAG() (EXTI->PR = (PWR_EXTI_LINE_PVD)) - -/** - * @brief Generates a Software interrupt on PVD EXTI line. - * @retval None - */ -#define __HAL_PWR_PVD_EXTI_GENERATE_SWIT() (EXTI->SWIER |= (PWR_EXTI_LINE_PVD)) - -/** - * @} - */ - -/* Include PWR HAL Extension module */ -#include "stm32f4xx_hal_pwr_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PWR_Exported_Functions PWR Exported Functions - * @{ - */ - -/** @addtogroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_PWR_DeInit(void); -void HAL_PWR_EnableBkUpAccess(void); -void HAL_PWR_DisableBkUpAccess(void); -/** - * @} - */ - -/** @addtogroup PWR_Exported_Functions_Group2 Peripheral Control functions - * @{ - */ -/* Peripheral Control functions **********************************************/ -/* PVD configuration */ -void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD); -void HAL_PWR_EnablePVD(void); -void HAL_PWR_DisablePVD(void); - -/* WakeUp pins configuration */ -void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx); -void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx); - -/* Low Power modes entry */ -void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry); -void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry); -void HAL_PWR_EnterSTANDBYMode(void); - -/* Power PVD IRQ Handler */ -void HAL_PWR_PVD_IRQHandler(void); -void HAL_PWR_PVDCallback(void); - -/* Cortex System Control functions *******************************************/ -void HAL_PWR_EnableSleepOnExit(void); -void HAL_PWR_DisableSleepOnExit(void); -void HAL_PWR_EnableSEVOnPend(void); -void HAL_PWR_DisableSEVOnPend(void); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PWR_Private_Constants PWR Private Constants - * @{ - */ - -/** @defgroup PWR_PVD_EXTI_Line PWR PVD EXTI Line - * @{ - */ -#define PWR_EXTI_LINE_PVD ((uint32_t)EXTI_IMR_MR16) /*!< External interrupt line 16 Connected to the PVD EXTI Line */ -/** - * @} - */ - -/** @defgroup PWR_register_alias_address PWR Register alias address - * @{ - */ -/* ------------- PWR registers bit address in the alias region ---------------*/ -#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) -#define PWR_CR_OFFSET 0x00U -#define PWR_CSR_OFFSET 0x04U -#define PWR_CR_OFFSET_BB (PWR_OFFSET + PWR_CR_OFFSET) -#define PWR_CSR_OFFSET_BB (PWR_OFFSET + PWR_CSR_OFFSET) -/** - * @} - */ - -/** @defgroup PWR_CR_register_alias PWR CR Register alias address - * @{ - */ -/* --- CR Register ---*/ -/* Alias word address of DBP bit */ -#define DBP_BIT_NUMBER PWR_CR_DBP_Pos -#define CR_DBP_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (DBP_BIT_NUMBER * 4U)) - -/* Alias word address of PVDE bit */ -#define PVDE_BIT_NUMBER PWR_CR_PVDE_Pos -#define CR_PVDE_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (PVDE_BIT_NUMBER * 4U)) - -/* Alias word address of VOS bit */ -#define VOS_BIT_NUMBER PWR_CR_VOS_Pos -#define CR_VOS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (VOS_BIT_NUMBER * 4U)) -/** - * @} - */ - -/** @defgroup PWR_CSR_register_alias PWR CSR Register alias address - * @{ - */ -/* --- CSR Register ---*/ -/* Alias word address of EWUP bit */ -#define EWUP_BIT_NUMBER PWR_CSR_EWUP_Pos -#define CSR_EWUP_BB (PERIPH_BB_BASE + (PWR_CSR_OFFSET_BB * 32U) + (EWUP_BIT_NUMBER * 4U)) -/** - * @} - */ - -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PWR_Private_Macros PWR Private Macros - * @{ - */ - -/** @defgroup PWR_IS_PWR_Definitions PWR Private macros to check input parameters - * @{ - */ -#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLEVEL_0) || ((LEVEL) == PWR_PVDLEVEL_1)|| \ - ((LEVEL) == PWR_PVDLEVEL_2) || ((LEVEL) == PWR_PVDLEVEL_3)|| \ - ((LEVEL) == PWR_PVDLEVEL_4) || ((LEVEL) == PWR_PVDLEVEL_5)|| \ - ((LEVEL) == PWR_PVDLEVEL_6) || ((LEVEL) == PWR_PVDLEVEL_7)) -#define IS_PWR_PVD_MODE(MODE) (((MODE) == PWR_PVD_MODE_IT_RISING)|| ((MODE) == PWR_PVD_MODE_IT_FALLING) || \ - ((MODE) == PWR_PVD_MODE_IT_RISING_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING) || \ - ((MODE) == PWR_PVD_MODE_EVENT_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING_FALLING) || \ - ((MODE) == PWR_PVD_MODE_NORMAL)) -#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_ON) || \ - ((REGULATOR) == PWR_LOWPOWERREGULATOR_ON)) -#define IS_PWR_SLEEP_ENTRY(ENTRY) (((ENTRY) == PWR_SLEEPENTRY_WFI) || ((ENTRY) == PWR_SLEEPENTRY_WFE)) -#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPENTRY_WFI) || ((ENTRY) == PWR_STOPENTRY_WFE)) -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_PWR_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h deleted file mode 100644 index 10e017a1041f1ac..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h +++ /dev/null @@ -1,344 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr_ex.h - * @author MCD Application Team - * @brief Header file of PWR HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_PWR_EX_H -#define __STM32F4xx_HAL_PWR_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PWREx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWREx_Exported_Constants PWREx Exported Constants - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** @defgroup PWREx_Regulator_state_in_UnderDrive_mode PWREx Regulator state in UnderDrive mode - * @{ - */ -#define PWR_MAINREGULATOR_UNDERDRIVE_ON PWR_CR_MRUDS -#define PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON ((uint32_t)(PWR_CR_LPDS | PWR_CR_LPUDS)) -/** - * @} - */ - -/** @defgroup PWREx_Over_Under_Drive_Flag PWREx Over Under Drive Flag - * @{ - */ -#define PWR_FLAG_ODRDY PWR_CSR_ODRDY -#define PWR_FLAG_ODSWRDY PWR_CSR_ODSWRDY -#define PWR_FLAG_UDRDY PWR_CSR_UDSWRDY -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** @defgroup PWREx_Regulator_Voltage_Scale PWREx Regulator Voltage Scale - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS /* Scale 1 mode(default value at reset): the maximum value of fHCLK = 168 MHz. */ -#define PWR_REGULATOR_VOLTAGE_SCALE2 0x00000000U /* Scale 2 mode: the maximum value of fHCLK = 144 MHz. */ -#else -#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS /* Scale 1 mode(default value at reset): the maximum value of fHCLK is 168 MHz. It can be extended to - 180 MHz by activating the over-drive mode. */ -#define PWR_REGULATOR_VOLTAGE_SCALE2 PWR_CR_VOS_1 /* Scale 2 mode: the maximum value of fHCLK is 144 MHz. It can be extended to - 168 MHz by activating the over-drive mode. */ -#define PWR_REGULATOR_VOLTAGE_SCALE3 PWR_CR_VOS_0 /* Scale 3 mode: the maximum value of fHCLK is 120 MHz. */ -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ -/** - * @} - */ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup PWREx_WakeUp_Pins PWREx WakeUp Pins - * @{ - */ -#define PWR_WAKEUP_PIN2 0x00000080U -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define PWR_WAKEUP_PIN3 0x00000040U -#endif /* STM32F410xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Zx || STM32F412Vx || \ - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ -#endif /* STM32F410xx || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWREx_Exported_Constants PWREx Exported Constants - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -/** @brief macros configure the main internal regulator output voltage. - * @param __REGULATOR__ specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption when the device does - * not operate at the maximum frequency (refer to the datasheets for more details). - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode - * @retval None - */ -#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)); \ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(PWR->CR, PWR_CR_VOS); \ - UNUSED(tmpreg); \ - } while(0U) -#else -/** @brief macros configure the main internal regulator output voltage. - * @param __REGULATOR__ specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption when the device does - * not operate at the maximum frequency (refer to the datasheets for more details). - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode - * @retval None - */ -#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)); \ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(PWR->CR, PWR_CR_VOS); \ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macros to enable or disable the Over drive mode. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_OVERDRIVE_ENABLE() (*(__IO uint32_t *) CR_ODEN_BB = ENABLE) -#define __HAL_PWR_OVERDRIVE_DISABLE() (*(__IO uint32_t *) CR_ODEN_BB = DISABLE) - -/** @brief Macros to enable or disable the Over drive switching. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_OVERDRIVESWITCHING_ENABLE() (*(__IO uint32_t *) CR_ODSWEN_BB = ENABLE) -#define __HAL_PWR_OVERDRIVESWITCHING_DISABLE() (*(__IO uint32_t *) CR_ODSWEN_BB = DISABLE) - -/** @brief Macros to enable or disable the Under drive mode. - * @note This mode is enabled only with STOP low power mode. - * In this mode, the 1.2V domain is preserved in reduced leakage mode. This - * mode is only available when the main regulator or the low power regulator - * is in low voltage mode. - * @note If the Under-drive mode was enabled, it is automatically disabled after - * exiting Stop mode. - * When the voltage regulator operates in Under-drive mode, an additional - * startup delay is induced when waking up from Stop mode. - */ -#define __HAL_PWR_UNDERDRIVE_ENABLE() (PWR->CR |= (uint32_t)PWR_CR_UDEN) -#define __HAL_PWR_UNDERDRIVE_DISABLE() (PWR->CR &= (uint32_t)(~PWR_CR_UDEN)) - -/** @brief Check PWR flag is set or not. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg PWR_FLAG_ODRDY: This flag indicates that the Over-drive mode - * is ready - * @arg PWR_FLAG_ODSWRDY: This flag indicates that the Over-drive mode - * switching is ready - * @arg PWR_FLAG_UDRDY: This flag indicates that the Under-drive mode - * is enabled in Stop mode - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_PWR_GET_ODRUDR_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the Under-Drive Ready flag. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_CLEAR_ODRUDR_FLAG() (PWR->CSR |= PWR_FLAG_UDRDY) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PWREx_Exported_Functions PWREx Exported Functions - * @{ - */ - -/** @addtogroup PWREx_Exported_Functions_Group1 - * @{ - */ -void HAL_PWREx_EnableFlashPowerDown(void); -void HAL_PWREx_DisableFlashPowerDown(void); -HAL_StatusTypeDef HAL_PWREx_EnableBkUpReg(void); -HAL_StatusTypeDef HAL_PWREx_DisableBkUpReg(void); -uint32_t HAL_PWREx_GetVoltageRange(void); -HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling); - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F401xC) ||\ - defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -void HAL_PWREx_EnableMainRegulatorLowVoltage(void); -void HAL_PWREx_DisableMainRegulatorLowVoltage(void); -void HAL_PWREx_EnableLowRegulatorLowVoltage(void); -void HAL_PWREx_DisableLowRegulatorLowVoltage(void); -#endif /* STM32F410xx || STM32F401xC || STM32F401xE || STM32F411xE || STM32F412Zx || STM32F412Vx ||\ - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -HAL_StatusTypeDef HAL_PWREx_EnableOverDrive(void); -HAL_StatusTypeDef HAL_PWREx_DisableOverDrive(void); -HAL_StatusTypeDef HAL_PWREx_EnterUnderDriveSTOPMode(uint32_t Regulator, uint8_t STOPEntry); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PWREx_Private_Constants PWREx Private Constants - * @{ - */ - -/** @defgroup PWREx_register_alias_address PWREx Register alias address - * @{ - */ -/* ------------- PWR registers bit address in the alias region ---------------*/ -/* --- CR Register ---*/ -/* Alias word address of FPDS bit */ -#define FPDS_BIT_NUMBER PWR_CR_FPDS_Pos -#define CR_FPDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (FPDS_BIT_NUMBER * 4U)) - -/* Alias word address of ODEN bit */ -#define ODEN_BIT_NUMBER PWR_CR_ODEN_Pos -#define CR_ODEN_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (ODEN_BIT_NUMBER * 4U)) - -/* Alias word address of ODSWEN bit */ -#define ODSWEN_BIT_NUMBER PWR_CR_ODSWEN_Pos -#define CR_ODSWEN_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (ODSWEN_BIT_NUMBER * 4U)) - -/* Alias word address of MRLVDS bit */ -#define MRLVDS_BIT_NUMBER PWR_CR_MRLVDS_Pos -#define CR_MRLVDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (MRLVDS_BIT_NUMBER * 4U)) - -/* Alias word address of LPLVDS bit */ -#define LPLVDS_BIT_NUMBER PWR_CR_LPLVDS_Pos -#define CR_LPLVDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (LPLVDS_BIT_NUMBER * 4U)) - - /** - * @} - */ - -/** @defgroup PWREx_CSR_register_alias PWRx CSR Register alias address - * @{ - */ -/* --- CSR Register ---*/ -/* Alias word address of BRE bit */ -#define BRE_BIT_NUMBER PWR_CSR_BRE_Pos -#define CSR_BRE_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CSR_OFFSET_BB * 32U) + (BRE_BIT_NUMBER * 4U)) - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PWREx_Private_Macros PWREx Private Macros - * @{ - */ - -/** @defgroup PWREx_IS_PWR_Definitions PWREx Private macros to check input parameters - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_PWR_REGULATOR_UNDERDRIVE(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_UNDERDRIVE_ON) || \ - ((REGULATOR) == PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -#define IS_PWR_VOLTAGE_SCALING_RANGE(VOLTAGE) (((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE2)) -#else -#define IS_PWR_VOLTAGE_SCALING_RANGE(VOLTAGE) (((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE2) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE3)) -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ - -#if defined(STM32F446xx) -#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2)) -#elif defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2) || \ - ((PIN) == PWR_WAKEUP_PIN3)) -#else -#define IS_PWR_WAKEUP_PIN(PIN) ((PIN) == PWR_WAKEUP_PIN1) -#endif /* STM32F446xx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_PWR_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_qspi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_qspi.h deleted file mode 100644 index 97e9324f34cf041..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_qspi.h +++ /dev/null @@ -1,753 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_qspi.h - * @author MCD Application Team - * @brief Header file of QSPI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_QSPI_H -#define STM32F4xx_HAL_QSPI_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(QUADSPI) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup QSPI - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup QSPI_Exported_Types QSPI Exported Types - * @{ - */ - -/** - * @brief QSPI Init structure definition - */ -typedef struct -{ - uint32_t ClockPrescaler; /* Specifies the prescaler factor for generating clock based on the AHB clock. - This parameter can be a number between 0 and 255 */ - uint32_t FifoThreshold; /* Specifies the threshold number of bytes in the FIFO (used only in indirect mode) - This parameter can be a value between 1 and 32 */ - uint32_t SampleShifting; /* Specifies the Sample Shift. The data is sampled 1/2 clock cycle delay later to - take in account external signal delays. (It should be QSPI_SAMPLE_SHIFTING_NONE in DDR mode) - This parameter can be a value of @ref QSPI_SampleShifting */ - uint32_t FlashSize; /* Specifies the Flash Size. FlashSize+1 is effectively the number of address bits - required to address the flash memory. The flash capacity can be up to 4GB - (addressed using 32 bits) in indirect mode, but the addressable space in - memory-mapped mode is limited to 256MB - This parameter can be a number between 0 and 31 */ - uint32_t ChipSelectHighTime; /* Specifies the Chip Select High Time. ChipSelectHighTime+1 defines the minimum number - of clock cycles which the chip select must remain high between commands. - This parameter can be a value of @ref QSPI_ChipSelectHighTime */ - uint32_t ClockMode; /* Specifies the Clock Mode. It indicates the level that clock takes between commands. - This parameter can be a value of @ref QSPI_ClockMode */ - uint32_t FlashID; /* Specifies the Flash which will be used, - This parameter can be a value of @ref QSPI_Flash_Select */ - uint32_t DualFlash; /* Specifies the Dual Flash Mode State - This parameter can be a value of @ref QSPI_DualFlash_Mode */ -}QSPI_InitTypeDef; - -/** - * @brief HAL QSPI State structures definition - */ -typedef enum -{ - HAL_QSPI_STATE_RESET = 0x00U, /*!< Peripheral not initialized */ - HAL_QSPI_STATE_READY = 0x01U, /*!< Peripheral initialized and ready for use */ - HAL_QSPI_STATE_BUSY = 0x02U, /*!< Peripheral in indirect mode and busy */ - HAL_QSPI_STATE_BUSY_INDIRECT_TX = 0x12U, /*!< Peripheral in indirect mode with transmission ongoing */ - HAL_QSPI_STATE_BUSY_INDIRECT_RX = 0x22U, /*!< Peripheral in indirect mode with reception ongoing */ - HAL_QSPI_STATE_BUSY_AUTO_POLLING = 0x42U, /*!< Peripheral in auto polling mode ongoing */ - HAL_QSPI_STATE_BUSY_MEM_MAPPED = 0x82U, /*!< Peripheral in memory mapped mode ongoing */ - HAL_QSPI_STATE_ABORT = 0x08U, /*!< Peripheral with abort request ongoing */ - HAL_QSPI_STATE_ERROR = 0x04U /*!< Peripheral in error */ -}HAL_QSPI_StateTypeDef; - -/** - * @brief QSPI Handle Structure definition - */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -typedef struct __QSPI_HandleTypeDef -#else -typedef struct -#endif -{ - QUADSPI_TypeDef *Instance; /* QSPI registers base address */ - QSPI_InitTypeDef Init; /* QSPI communication parameters */ - uint8_t *pTxBuffPtr; /* Pointer to QSPI Tx transfer Buffer */ - __IO uint32_t TxXferSize; /* QSPI Tx Transfer size */ - __IO uint32_t TxXferCount; /* QSPI Tx Transfer Counter */ - uint8_t *pRxBuffPtr; /* Pointer to QSPI Rx transfer Buffer */ - __IO uint32_t RxXferSize; /* QSPI Rx Transfer size */ - __IO uint32_t RxXferCount; /* QSPI Rx Transfer Counter */ - DMA_HandleTypeDef *hdma; /* QSPI Rx/Tx DMA Handle parameters */ - __IO HAL_LockTypeDef Lock; /* Locking object */ - __IO HAL_QSPI_StateTypeDef State; /* QSPI communication state */ - __IO uint32_t ErrorCode; /* QSPI Error code */ - uint32_t Timeout; /* Timeout for the QSPI memory access */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - void (* ErrorCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* AbortCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* FifoThresholdCallback)(struct __QSPI_HandleTypeDef *hqspi); - void (* CmdCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* RxCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* TxCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* RxHalfCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* TxHalfCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* StatusMatchCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* TimeOutCallback) (struct __QSPI_HandleTypeDef *hqspi); - - void (* MspInitCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* MspDeInitCallback) (struct __QSPI_HandleTypeDef *hqspi); -#endif -}QSPI_HandleTypeDef; - -/** - * @brief QSPI Command structure definition - */ -typedef struct -{ - uint32_t Instruction; /* Specifies the Instruction to be sent - This parameter can be a value (8-bit) between 0x00 and 0xFF */ - uint32_t Address; /* Specifies the Address to be sent (Size from 1 to 4 bytes according AddressSize) - This parameter can be a value (32-bits) between 0x0 and 0xFFFFFFFF */ - uint32_t AlternateBytes; /* Specifies the Alternate Bytes to be sent (Size from 1 to 4 bytes according AlternateBytesSize) - This parameter can be a value (32-bits) between 0x0 and 0xFFFFFFFF */ - uint32_t AddressSize; /* Specifies the Address Size - This parameter can be a value of @ref QSPI_AddressSize */ - uint32_t AlternateBytesSize; /* Specifies the Alternate Bytes Size - This parameter can be a value of @ref QSPI_AlternateBytesSize */ - uint32_t DummyCycles; /* Specifies the Number of Dummy Cycles. - This parameter can be a number between 0 and 31 */ - uint32_t InstructionMode; /* Specifies the Instruction Mode - This parameter can be a value of @ref QSPI_InstructionMode */ - uint32_t AddressMode; /* Specifies the Address Mode - This parameter can be a value of @ref QSPI_AddressMode */ - uint32_t AlternateByteMode; /* Specifies the Alternate Bytes Mode - This parameter can be a value of @ref QSPI_AlternateBytesMode */ - uint32_t DataMode; /* Specifies the Data Mode (used for dummy cycles and data phases) - This parameter can be a value of @ref QSPI_DataMode */ - uint32_t NbData; /* Specifies the number of data to transfer. (This is the number of bytes) - This parameter can be any value between 0 and 0xFFFFFFFF (0 means undefined length - until end of memory)*/ - uint32_t DdrMode; /* Specifies the double data rate mode for address, alternate byte and data phase - This parameter can be a value of @ref QSPI_DdrMode */ - uint32_t DdrHoldHalfCycle; /* Specifies if the DDR hold is enabled. When enabled it delays the data - output by one half of system clock in DDR mode. - This parameter can be a value of @ref QSPI_DdrHoldHalfCycle */ - uint32_t SIOOMode; /* Specifies the send instruction only once mode - This parameter can be a value of @ref QSPI_SIOOMode */ -}QSPI_CommandTypeDef; - -/** - * @brief QSPI Auto Polling mode configuration structure definition - */ -typedef struct -{ - uint32_t Match; /* Specifies the value to be compared with the masked status register to get a match. - This parameter can be any value between 0 and 0xFFFFFFFF */ - uint32_t Mask; /* Specifies the mask to be applied to the status bytes received. - This parameter can be any value between 0 and 0xFFFFFFFF */ - uint32_t Interval; /* Specifies the number of clock cycles between two read during automatic polling phases. - This parameter can be any value between 0 and 0xFFFF */ - uint32_t StatusBytesSize; /* Specifies the size of the status bytes received. - This parameter can be any value between 1 and 4 */ - uint32_t MatchMode; /* Specifies the method used for determining a match. - This parameter can be a value of @ref QSPI_MatchMode */ - uint32_t AutomaticStop; /* Specifies if automatic polling is stopped after a match. - This parameter can be a value of @ref QSPI_AutomaticStop */ -}QSPI_AutoPollingTypeDef; - -/** - * @brief QSPI Memory Mapped mode configuration structure definition - */ -typedef struct -{ - uint32_t TimeOutPeriod; /* Specifies the number of clock to wait when the FIFO is full before to release the chip select. - This parameter can be any value between 0 and 0xFFFF */ - uint32_t TimeOutActivation; /* Specifies if the timeout counter is enabled to release the chip select. - This parameter can be a value of @ref QSPI_TimeOutActivation */ -}QSPI_MemoryMappedTypeDef; - -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -/** - * @brief HAL QSPI Callback ID enumeration definition - */ -typedef enum -{ - HAL_QSPI_ERROR_CB_ID = 0x00U, /*!< QSPI Error Callback ID */ - HAL_QSPI_ABORT_CB_ID = 0x01U, /*!< QSPI Abort Callback ID */ - HAL_QSPI_FIFO_THRESHOLD_CB_ID = 0x02U, /*!< QSPI FIFO Threshold Callback ID */ - HAL_QSPI_CMD_CPLT_CB_ID = 0x03U, /*!< QSPI Command Complete Callback ID */ - HAL_QSPI_RX_CPLT_CB_ID = 0x04U, /*!< QSPI Rx Complete Callback ID */ - HAL_QSPI_TX_CPLT_CB_ID = 0x05U, /*!< QSPI Tx Complete Callback ID */ - HAL_QSPI_RX_HALF_CPLT_CB_ID = 0x06U, /*!< QSPI Rx Half Complete Callback ID */ - HAL_QSPI_TX_HALF_CPLT_CB_ID = 0x07U, /*!< QSPI Tx Half Complete Callback ID */ - HAL_QSPI_STATUS_MATCH_CB_ID = 0x08U, /*!< QSPI Status Match Callback ID */ - HAL_QSPI_TIMEOUT_CB_ID = 0x09U, /*!< QSPI Timeout Callback ID */ - - HAL_QSPI_MSP_INIT_CB_ID = 0x0AU, /*!< QSPI MspInit Callback ID */ - HAL_QSPI_MSP_DEINIT_CB_ID = 0x0B0 /*!< QSPI MspDeInit Callback ID */ -}HAL_QSPI_CallbackIDTypeDef; - -/** - * @brief HAL QSPI Callback pointer definition - */ -typedef void (*pQSPI_CallbackTypeDef)(QSPI_HandleTypeDef *hqspi); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup QSPI_Exported_Constants QSPI Exported Constants - * @{ - */ - -/** @defgroup QSPI_ErrorCode QSPI Error Code - * @{ - */ -#define HAL_QSPI_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_QSPI_ERROR_TIMEOUT 0x00000001U /*!< Timeout error */ -#define HAL_QSPI_ERROR_TRANSFER 0x00000002U /*!< Transfer error */ -#define HAL_QSPI_ERROR_DMA 0x00000004U /*!< DMA transfer error */ -#define HAL_QSPI_ERROR_INVALID_PARAM 0x00000008U /*!< Invalid parameters error */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -#define HAL_QSPI_ERROR_INVALID_CALLBACK 0x00000010U /*!< Invalid callback error */ -#endif -/** - * @} - */ - -/** @defgroup QSPI_SampleShifting QSPI Sample Shifting - * @{ - */ -#define QSPI_SAMPLE_SHIFTING_NONE 0x00000000U /*!State = HAL_QSPI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_QSPI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_QSPI_STATE_RESET) -#endif - -/** @brief Enable the QSPI peripheral. - * @param __HANDLE__ : specifies the QSPI Handle. - * @retval None - */ -#define __HAL_QSPI_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR, QUADSPI_CR_EN) - -/** @brief Disable the QSPI peripheral. - * @param __HANDLE__ : specifies the QSPI Handle. - * @retval None - */ -#define __HAL_QSPI_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR, QUADSPI_CR_EN) - -/** @brief Enable the specified QSPI interrupt. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __INTERRUPT__ : specifies the QSPI interrupt source to enable. - * This parameter can be one of the following values: - * @arg QSPI_IT_TO: QSPI Timeout interrupt - * @arg QSPI_IT_SM: QSPI Status match interrupt - * @arg QSPI_IT_FT: QSPI FIFO threshold interrupt - * @arg QSPI_IT_TC: QSPI Transfer complete interrupt - * @arg QSPI_IT_TE: QSPI Transfer error interrupt - * @retval None - */ -#define __HAL_QSPI_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR, (__INTERRUPT__)) - - -/** @brief Disable the specified QSPI interrupt. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __INTERRUPT__ : specifies the QSPI interrupt source to disable. - * This parameter can be one of the following values: - * @arg QSPI_IT_TO: QSPI Timeout interrupt - * @arg QSPI_IT_SM: QSPI Status match interrupt - * @arg QSPI_IT_FT: QSPI FIFO threshold interrupt - * @arg QSPI_IT_TC: QSPI Transfer complete interrupt - * @arg QSPI_IT_TE: QSPI Transfer error interrupt - * @retval None - */ -#define __HAL_QSPI_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR, (__INTERRUPT__)) - -/** @brief Check whether the specified QSPI interrupt source is enabled or not. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __INTERRUPT__ : specifies the QSPI interrupt source to check. - * This parameter can be one of the following values: - * @arg QSPI_IT_TO: QSPI Timeout interrupt - * @arg QSPI_IT_SM: QSPI Status match interrupt - * @arg QSPI_IT_FT: QSPI FIFO threshold interrupt - * @arg QSPI_IT_TC: QSPI Transfer complete interrupt - * @arg QSPI_IT_TE: QSPI Transfer error interrupt - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_QSPI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (READ_BIT((__HANDLE__)->Instance->CR, (__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @brief Check whether the selected QSPI flag is set or not. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __FLAG__ : specifies the QSPI flag to check. - * This parameter can be one of the following values: - * @arg QSPI_FLAG_BUSY: QSPI Busy flag - * @arg QSPI_FLAG_TO: QSPI Timeout flag - * @arg QSPI_FLAG_SM: QSPI Status match flag - * @arg QSPI_FLAG_FT: QSPI FIFO threshold flag - * @arg QSPI_FLAG_TC: QSPI Transfer complete flag - * @arg QSPI_FLAG_TE: QSPI Transfer error flag - * @retval None - */ -#define __HAL_QSPI_GET_FLAG(__HANDLE__, __FLAG__) ((READ_BIT((__HANDLE__)->Instance->SR, (__FLAG__)) != 0U) ? SET : RESET) - -/** @brief Clears the specified QSPI's flag status. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __FLAG__ : specifies the QSPI clear register flag that needs to be set - * This parameter can be one of the following values: - * @arg QSPI_FLAG_TO: QSPI Timeout flag - * @arg QSPI_FLAG_SM: QSPI Status match flag - * @arg QSPI_FLAG_TC: QSPI Transfer complete flag - * @arg QSPI_FLAG_TE: QSPI Transfer error flag - * @retval None - */ -#define __HAL_QSPI_CLEAR_FLAG(__HANDLE__, __FLAG__) WRITE_REG((__HANDLE__)->Instance->FCR, (__FLAG__)) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup QSPI_Exported_Functions - * @{ - */ - -/** @addtogroup QSPI_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_QSPI_Init (QSPI_HandleTypeDef *hqspi); -HAL_StatusTypeDef HAL_QSPI_DeInit (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_MspInit (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_MspDeInit(QSPI_HandleTypeDef *hqspi); -/** - * @} - */ - -/** @addtogroup QSPI_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -/* QSPI IRQ handler method */ -void HAL_QSPI_IRQHandler(QSPI_HandleTypeDef *hqspi); - -/* QSPI indirect mode */ -HAL_StatusTypeDef HAL_QSPI_Command (QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_Transmit (QSPI_HandleTypeDef *hqspi, uint8_t *pData, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_Receive (QSPI_HandleTypeDef *hqspi, uint8_t *pData, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_Command_IT (QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd); -HAL_StatusTypeDef HAL_QSPI_Transmit_IT (QSPI_HandleTypeDef *hqspi, uint8_t *pData); -HAL_StatusTypeDef HAL_QSPI_Receive_IT (QSPI_HandleTypeDef *hqspi, uint8_t *pData); -HAL_StatusTypeDef HAL_QSPI_Transmit_DMA (QSPI_HandleTypeDef *hqspi, uint8_t *pData); -HAL_StatusTypeDef HAL_QSPI_Receive_DMA (QSPI_HandleTypeDef *hqspi, uint8_t *pData); - -/* QSPI status flag polling mode */ -HAL_StatusTypeDef HAL_QSPI_AutoPolling (QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_AutoPollingTypeDef *cfg, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_AutoPolling_IT(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_AutoPollingTypeDef *cfg); - -/* QSPI memory-mapped mode */ -HAL_StatusTypeDef HAL_QSPI_MemoryMapped(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_MemoryMappedTypeDef *cfg); - -/* Callback functions in non-blocking modes ***********************************/ -void HAL_QSPI_ErrorCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_AbortCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_FifoThresholdCallback(QSPI_HandleTypeDef *hqspi); - -/* QSPI indirect mode */ -void HAL_QSPI_CmdCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_RxCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_TxCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_RxHalfCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_TxHalfCpltCallback (QSPI_HandleTypeDef *hqspi); - -/* QSPI status flag polling mode */ -void HAL_QSPI_StatusMatchCallback (QSPI_HandleTypeDef *hqspi); - -/* QSPI memory-mapped mode */ -void HAL_QSPI_TimeOutCallback (QSPI_HandleTypeDef *hqspi); - -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -/* QSPI callback registering/unregistering */ -HAL_StatusTypeDef HAL_QSPI_RegisterCallback (QSPI_HandleTypeDef *hqspi, HAL_QSPI_CallbackIDTypeDef CallbackId, pQSPI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_QSPI_UnRegisterCallback (QSPI_HandleTypeDef *hqspi, HAL_QSPI_CallbackIDTypeDef CallbackId); -#endif -/** - * @} - */ - -/** @addtogroup QSPI_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control and State functions ************************************/ -HAL_QSPI_StateTypeDef HAL_QSPI_GetState (QSPI_HandleTypeDef *hqspi); -uint32_t HAL_QSPI_GetError (QSPI_HandleTypeDef *hqspi); -HAL_StatusTypeDef HAL_QSPI_Abort (QSPI_HandleTypeDef *hqspi); -HAL_StatusTypeDef HAL_QSPI_Abort_IT (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_SetTimeout (QSPI_HandleTypeDef *hqspi, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_SetFifoThreshold(QSPI_HandleTypeDef *hqspi, uint32_t Threshold); -uint32_t HAL_QSPI_GetFifoThreshold(QSPI_HandleTypeDef *hqspi); -HAL_StatusTypeDef HAL_QSPI_SetFlashID (QSPI_HandleTypeDef *hqspi, uint32_t FlashID); -/** - * @} - */ - -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup QSPI_Private_Macros QSPI Private Macros - * @{ - */ -#define IS_QSPI_CLOCK_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFU) - -#define IS_QSPI_FIFO_THRESHOLD(THR) (((THR) > 0U) && ((THR) <= 32U)) - -#define IS_QSPI_SSHIFT(SSHIFT) (((SSHIFT) == QSPI_SAMPLE_SHIFTING_NONE) || \ - ((SSHIFT) == QSPI_SAMPLE_SHIFTING_HALFCYCLE)) - -#define IS_QSPI_FLASH_SIZE(FSIZE) (((FSIZE) <= 31U)) - -#define IS_QSPI_CS_HIGH_TIME(CSHTIME) (((CSHTIME) == QSPI_CS_HIGH_TIME_1_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_2_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_3_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_4_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_5_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_6_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_7_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_8_CYCLE)) - -#define IS_QSPI_CLOCK_MODE(CLKMODE) (((CLKMODE) == QSPI_CLOCK_MODE_0) || \ - ((CLKMODE) == QSPI_CLOCK_MODE_3)) - -#define IS_QSPI_FLASH_ID(FLASH_ID) (((FLASH_ID) == QSPI_FLASH_ID_1) || \ - ((FLASH_ID) == QSPI_FLASH_ID_2)) - -#define IS_QSPI_DUAL_FLASH_MODE(MODE) (((MODE) == QSPI_DUALFLASH_ENABLE) || \ - ((MODE) == QSPI_DUALFLASH_DISABLE)) - -#define IS_QSPI_INSTRUCTION(INSTRUCTION) ((INSTRUCTION) <= 0xFFU) - -#define IS_QSPI_ADDRESS_SIZE(ADDR_SIZE) (((ADDR_SIZE) == QSPI_ADDRESS_8_BITS) || \ - ((ADDR_SIZE) == QSPI_ADDRESS_16_BITS) || \ - ((ADDR_SIZE) == QSPI_ADDRESS_24_BITS) || \ - ((ADDR_SIZE) == QSPI_ADDRESS_32_BITS)) - -#define IS_QSPI_ALTERNATE_BYTES_SIZE(SIZE) (((SIZE) == QSPI_ALTERNATE_BYTES_8_BITS) || \ - ((SIZE) == QSPI_ALTERNATE_BYTES_16_BITS) || \ - ((SIZE) == QSPI_ALTERNATE_BYTES_24_BITS) || \ - ((SIZE) == QSPI_ALTERNATE_BYTES_32_BITS)) - -#define IS_QSPI_DUMMY_CYCLES(DCY) ((DCY) <= 31U) - -#define IS_QSPI_INSTRUCTION_MODE(MODE) (((MODE) == QSPI_INSTRUCTION_NONE) || \ - ((MODE) == QSPI_INSTRUCTION_1_LINE) || \ - ((MODE) == QSPI_INSTRUCTION_2_LINES) || \ - ((MODE) == QSPI_INSTRUCTION_4_LINES)) - -#define IS_QSPI_ADDRESS_MODE(MODE) (((MODE) == QSPI_ADDRESS_NONE) || \ - ((MODE) == QSPI_ADDRESS_1_LINE) || \ - ((MODE) == QSPI_ADDRESS_2_LINES) || \ - ((MODE) == QSPI_ADDRESS_4_LINES)) - -#define IS_QSPI_ALTERNATE_BYTES_MODE(MODE) (((MODE) == QSPI_ALTERNATE_BYTES_NONE) || \ - ((MODE) == QSPI_ALTERNATE_BYTES_1_LINE) || \ - ((MODE) == QSPI_ALTERNATE_BYTES_2_LINES) || \ - ((MODE) == QSPI_ALTERNATE_BYTES_4_LINES)) - -#define IS_QSPI_DATA_MODE(MODE) (((MODE) == QSPI_DATA_NONE) || \ - ((MODE) == QSPI_DATA_1_LINE) || \ - ((MODE) == QSPI_DATA_2_LINES) || \ - ((MODE) == QSPI_DATA_4_LINES)) - -#define IS_QSPI_DDR_MODE(DDR_MODE) (((DDR_MODE) == QSPI_DDR_MODE_DISABLE) || \ - ((DDR_MODE) == QSPI_DDR_MODE_ENABLE)) - -#define IS_QSPI_DDR_HHC(DDR_HHC) (((DDR_HHC) == QSPI_DDR_HHC_ANALOG_DELAY) || \ - ((DDR_HHC) == QSPI_DDR_HHC_HALF_CLK_DELAY)) - -#define IS_QSPI_SIOO_MODE(SIOO_MODE) (((SIOO_MODE) == QSPI_SIOO_INST_EVERY_CMD) || \ - ((SIOO_MODE) == QSPI_SIOO_INST_ONLY_FIRST_CMD)) - -#define IS_QSPI_INTERVAL(INTERVAL) ((INTERVAL) <= QUADSPI_PIR_INTERVAL) - -#define IS_QSPI_STATUS_BYTES_SIZE(SIZE) (((SIZE) >= 1U) && ((SIZE) <= 4U)) - -#define IS_QSPI_MATCH_MODE(MODE) (((MODE) == QSPI_MATCH_MODE_AND) || \ - ((MODE) == QSPI_MATCH_MODE_OR)) - -#define IS_QSPI_AUTOMATIC_STOP(APMS) (((APMS) == QSPI_AUTOMATIC_STOP_DISABLE) || \ - ((APMS) == QSPI_AUTOMATIC_STOP_ENABLE)) - -#define IS_QSPI_TIMEOUT_ACTIVATION(TCEN) (((TCEN) == QSPI_TIMEOUT_COUNTER_DISABLE) || \ - ((TCEN) == QSPI_TIMEOUT_COUNTER_ENABLE)) - -#define IS_QSPI_TIMEOUT_PERIOD(PERIOD) ((PERIOD) <= 0xFFFFU) -/** -* @} -*/ -/* End of private macros -----------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(QUADSPI) || defined(QUADSPI1) || defined(QUADSPI2) */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_QSPI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h deleted file mode 100644 index 2eeff3482eb6cfa..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h +++ /dev/null @@ -1,1462 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc.h - * @author MCD Application Team - * @brief Header file of RCC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RCC_H -#define __STM32F4xx_HAL_RCC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/* Include RCC HAL Extended module */ -/* (include on top of file since RCC structures are defined in extended file) */ -#include "stm32f4xx_hal_rcc_ex.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RCC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RCC_Exported_Types RCC Exported Types - * @{ - */ - -/** - * @brief RCC Internal/External Oscillator (HSE, HSI, LSE and LSI) configuration structure definition - */ -typedef struct -{ - uint32_t OscillatorType; /*!< The oscillators to be configured. - This parameter can be a value of @ref RCC_Oscillator_Type */ - - uint32_t HSEState; /*!< The new state of the HSE. - This parameter can be a value of @ref RCC_HSE_Config */ - - uint32_t LSEState; /*!< The new state of the LSE. - This parameter can be a value of @ref RCC_LSE_Config */ - - uint32_t HSIState; /*!< The new state of the HSI. - This parameter can be a value of @ref RCC_HSI_Config */ - - uint32_t HSICalibrationValue; /*!< The HSI calibration trimming value (default is RCC_HSICALIBRATION_DEFAULT). - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */ - - uint32_t LSIState; /*!< The new state of the LSI. - This parameter can be a value of @ref RCC_LSI_Config */ - - RCC_PLLInitTypeDef PLL; /*!< PLL structure parameters */ -}RCC_OscInitTypeDef; - -/** - * @brief RCC System, AHB and APB busses clock configuration structure definition - */ -typedef struct -{ - uint32_t ClockType; /*!< The clock to be configured. - This parameter can be a value of @ref RCC_System_Clock_Type */ - - uint32_t SYSCLKSource; /*!< The clock source (SYSCLKS) used as system clock. - This parameter can be a value of @ref RCC_System_Clock_Source */ - - uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK). - This parameter can be a value of @ref RCC_AHB_Clock_Source */ - - uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */ - - uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */ - -}RCC_ClkInitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCC_Exported_Constants RCC Exported Constants - * @{ - */ - -/** @defgroup RCC_Oscillator_Type Oscillator Type - * @{ - */ -#define RCC_OSCILLATORTYPE_NONE 0x00000000U -#define RCC_OSCILLATORTYPE_HSE 0x00000001U -#define RCC_OSCILLATORTYPE_HSI 0x00000002U -#define RCC_OSCILLATORTYPE_LSE 0x00000004U -#define RCC_OSCILLATORTYPE_LSI 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_HSE_Config HSE Config - * @{ - */ -#define RCC_HSE_OFF 0x00000000U -#define RCC_HSE_ON RCC_CR_HSEON -#define RCC_HSE_BYPASS ((uint32_t)(RCC_CR_HSEBYP | RCC_CR_HSEON)) -/** - * @} - */ - -/** @defgroup RCC_LSE_Config LSE Config - * @{ - */ -#define RCC_LSE_OFF 0x00000000U -#define RCC_LSE_ON RCC_BDCR_LSEON -#define RCC_LSE_BYPASS ((uint32_t)(RCC_BDCR_LSEBYP | RCC_BDCR_LSEON)) -/** - * @} - */ - -/** @defgroup RCC_HSI_Config HSI Config - * @{ - */ -#define RCC_HSI_OFF ((uint8_t)0x00) -#define RCC_HSI_ON ((uint8_t)0x01) - -#define RCC_HSICALIBRATION_DEFAULT 0x10U /* Default HSI calibration trimming value */ -/** - * @} - */ - -/** @defgroup RCC_LSI_Config LSI Config - * @{ - */ -#define RCC_LSI_OFF ((uint8_t)0x00) -#define RCC_LSI_ON ((uint8_t)0x01) -/** - * @} - */ - -/** @defgroup RCC_PLL_Config PLL Config - * @{ - */ -#define RCC_PLL_NONE ((uint8_t)0x00) -#define RCC_PLL_OFF ((uint8_t)0x01) -#define RCC_PLL_ON ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup RCC_PLLP_Clock_Divider PLLP Clock Divider - * @{ - */ -#define RCC_PLLP_DIV2 0x00000002U -#define RCC_PLLP_DIV4 0x00000004U -#define RCC_PLLP_DIV6 0x00000006U -#define RCC_PLLP_DIV8 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_PLL_Clock_Source PLL Clock Source - * @{ - */ -#define RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI -#define RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Type System Clock Type - * @{ - */ -#define RCC_CLOCKTYPE_SYSCLK 0x00000001U -#define RCC_CLOCKTYPE_HCLK 0x00000002U -#define RCC_CLOCKTYPE_PCLK1 0x00000004U -#define RCC_CLOCKTYPE_PCLK2 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Source System Clock Source - * @note The RCC_SYSCLKSOURCE_PLLRCLK parameter is available only for - * STM32F446xx devices. - * @{ - */ -#define RCC_SYSCLKSOURCE_HSI RCC_CFGR_SW_HSI -#define RCC_SYSCLKSOURCE_HSE RCC_CFGR_SW_HSE -#define RCC_SYSCLKSOURCE_PLLCLK RCC_CFGR_SW_PLL -#define RCC_SYSCLKSOURCE_PLLRCLK ((uint32_t)(RCC_CFGR_SW_0 | RCC_CFGR_SW_1)) -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Source_Status System Clock Source Status - * @note The RCC_SYSCLKSOURCE_STATUS_PLLRCLK parameter is available only for - * STM32F446xx devices. - * @{ - */ -#define RCC_SYSCLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_PLLCLK RCC_CFGR_SWS_PLL /*!< PLL used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_PLLRCLK ((uint32_t)(RCC_CFGR_SWS_0 | RCC_CFGR_SWS_1)) /*!< PLLR used as system clock */ -/** - * @} - */ - -/** @defgroup RCC_AHB_Clock_Source AHB Clock Source - * @{ - */ -#define RCC_SYSCLK_DIV1 RCC_CFGR_HPRE_DIV1 -#define RCC_SYSCLK_DIV2 RCC_CFGR_HPRE_DIV2 -#define RCC_SYSCLK_DIV4 RCC_CFGR_HPRE_DIV4 -#define RCC_SYSCLK_DIV8 RCC_CFGR_HPRE_DIV8 -#define RCC_SYSCLK_DIV16 RCC_CFGR_HPRE_DIV16 -#define RCC_SYSCLK_DIV64 RCC_CFGR_HPRE_DIV64 -#define RCC_SYSCLK_DIV128 RCC_CFGR_HPRE_DIV128 -#define RCC_SYSCLK_DIV256 RCC_CFGR_HPRE_DIV256 -#define RCC_SYSCLK_DIV512 RCC_CFGR_HPRE_DIV512 -/** - * @} - */ - -/** @defgroup RCC_APB1_APB2_Clock_Source APB1/APB2 Clock Source - * @{ - */ -#define RCC_HCLK_DIV1 RCC_CFGR_PPRE1_DIV1 -#define RCC_HCLK_DIV2 RCC_CFGR_PPRE1_DIV2 -#define RCC_HCLK_DIV4 RCC_CFGR_PPRE1_DIV4 -#define RCC_HCLK_DIV8 RCC_CFGR_PPRE1_DIV8 -#define RCC_HCLK_DIV16 RCC_CFGR_PPRE1_DIV16 -/** - * @} - */ - -/** @defgroup RCC_RTC_Clock_Source RTC Clock Source - * @{ - */ -#define RCC_RTCCLKSOURCE_NO_CLK 0x00000000U -#define RCC_RTCCLKSOURCE_LSE 0x00000100U -#define RCC_RTCCLKSOURCE_LSI 0x00000200U -#define RCC_RTCCLKSOURCE_HSE_DIVX 0x00000300U -#define RCC_RTCCLKSOURCE_HSE_DIV2 0x00020300U -#define RCC_RTCCLKSOURCE_HSE_DIV3 0x00030300U -#define RCC_RTCCLKSOURCE_HSE_DIV4 0x00040300U -#define RCC_RTCCLKSOURCE_HSE_DIV5 0x00050300U -#define RCC_RTCCLKSOURCE_HSE_DIV6 0x00060300U -#define RCC_RTCCLKSOURCE_HSE_DIV7 0x00070300U -#define RCC_RTCCLKSOURCE_HSE_DIV8 0x00080300U -#define RCC_RTCCLKSOURCE_HSE_DIV9 0x00090300U -#define RCC_RTCCLKSOURCE_HSE_DIV10 0x000A0300U -#define RCC_RTCCLKSOURCE_HSE_DIV11 0x000B0300U -#define RCC_RTCCLKSOURCE_HSE_DIV12 0x000C0300U -#define RCC_RTCCLKSOURCE_HSE_DIV13 0x000D0300U -#define RCC_RTCCLKSOURCE_HSE_DIV14 0x000E0300U -#define RCC_RTCCLKSOURCE_HSE_DIV15 0x000F0300U -#define RCC_RTCCLKSOURCE_HSE_DIV16 0x00100300U -#define RCC_RTCCLKSOURCE_HSE_DIV17 0x00110300U -#define RCC_RTCCLKSOURCE_HSE_DIV18 0x00120300U -#define RCC_RTCCLKSOURCE_HSE_DIV19 0x00130300U -#define RCC_RTCCLKSOURCE_HSE_DIV20 0x00140300U -#define RCC_RTCCLKSOURCE_HSE_DIV21 0x00150300U -#define RCC_RTCCLKSOURCE_HSE_DIV22 0x00160300U -#define RCC_RTCCLKSOURCE_HSE_DIV23 0x00170300U -#define RCC_RTCCLKSOURCE_HSE_DIV24 0x00180300U -#define RCC_RTCCLKSOURCE_HSE_DIV25 0x00190300U -#define RCC_RTCCLKSOURCE_HSE_DIV26 0x001A0300U -#define RCC_RTCCLKSOURCE_HSE_DIV27 0x001B0300U -#define RCC_RTCCLKSOURCE_HSE_DIV28 0x001C0300U -#define RCC_RTCCLKSOURCE_HSE_DIV29 0x001D0300U -#define RCC_RTCCLKSOURCE_HSE_DIV30 0x001E0300U -#define RCC_RTCCLKSOURCE_HSE_DIV31 0x001F0300U -/** - * @} - */ - -/** @defgroup RCC_MCO_Index MCO Index - * @{ - */ -#define RCC_MCO1 0x00000000U -#define RCC_MCO2 0x00000001U -/** - * @} - */ - -/** @defgroup RCC_MCO1_Clock_Source MCO1 Clock Source - * @{ - */ -#define RCC_MCO1SOURCE_HSI 0x00000000U -#define RCC_MCO1SOURCE_LSE RCC_CFGR_MCO1_0 -#define RCC_MCO1SOURCE_HSE RCC_CFGR_MCO1_1 -#define RCC_MCO1SOURCE_PLLCLK RCC_CFGR_MCO1 -/** - * @} - */ - -/** @defgroup RCC_MCOx_Clock_Prescaler MCOx Clock Prescaler - * @{ - */ -#define RCC_MCODIV_1 0x00000000U -#define RCC_MCODIV_2 RCC_CFGR_MCO1PRE_2 -#define RCC_MCODIV_3 ((uint32_t)RCC_CFGR_MCO1PRE_0 | RCC_CFGR_MCO1PRE_2) -#define RCC_MCODIV_4 ((uint32_t)RCC_CFGR_MCO1PRE_1 | RCC_CFGR_MCO1PRE_2) -#define RCC_MCODIV_5 RCC_CFGR_MCO1PRE -/** - * @} - */ - -/** @defgroup RCC_Interrupt Interrupts - * @{ - */ -#define RCC_IT_LSIRDY ((uint8_t)0x01) -#define RCC_IT_LSERDY ((uint8_t)0x02) -#define RCC_IT_HSIRDY ((uint8_t)0x04) -#define RCC_IT_HSERDY ((uint8_t)0x08) -#define RCC_IT_PLLRDY ((uint8_t)0x10) -#define RCC_IT_PLLI2SRDY ((uint8_t)0x20) -#define RCC_IT_CSS ((uint8_t)0x80) -/** - * @} - */ - -/** @defgroup RCC_Flag Flags - * Elements values convention: 0XXYYYYYb - * - YYYYY : Flag position in the register - * - 0XX : Register index - * - 01: CR register - * - 10: BDCR register - * - 11: CSR register - * @{ - */ -/* Flags in the CR register */ -#define RCC_FLAG_HSIRDY ((uint8_t)0x21) -#define RCC_FLAG_HSERDY ((uint8_t)0x31) -#define RCC_FLAG_PLLRDY ((uint8_t)0x39) -#define RCC_FLAG_PLLI2SRDY ((uint8_t)0x3B) - -/* Flags in the BDCR register */ -#define RCC_FLAG_LSERDY ((uint8_t)0x41) - -/* Flags in the CSR register */ -#define RCC_FLAG_LSIRDY ((uint8_t)0x61) -#define RCC_FLAG_BORRST ((uint8_t)0x79) -#define RCC_FLAG_PINRST ((uint8_t)0x7A) -#define RCC_FLAG_PORRST ((uint8_t)0x7B) -#define RCC_FLAG_SFTRST ((uint8_t)0x7C) -#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) -#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) -#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCC_Exported_Macros RCC Exported Macros - * @{ - */ - -/** @defgroup RCC_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOA_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOAEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOAEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOHEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_GPIOA_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOAEN)) -#define __HAL_RCC_GPIOB_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOBEN)) -#define __HAL_RCC_GPIOC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOCEN)) -#define __HAL_RCC_GPIOH_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOHEN)) -#define __HAL_RCC_DMA1_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA1EN)) -#define __HAL_RCC_DMA2_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA2EN)) -/** - * @} - */ - -/** @defgroup RCC_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOA_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOAEN)) != RESET) -#define __HAL_RCC_GPIOB_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOBEN)) != RESET) -#define __HAL_RCC_GPIOC_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOCEN)) != RESET) -#define __HAL_RCC_GPIOH_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOHEN)) != RESET) -#define __HAL_RCC_DMA1_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA1EN)) != RESET) -#define __HAL_RCC_DMA2_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA2EN)) != RESET) - -#define __HAL_RCC_GPIOA_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOAEN)) == RESET) -#define __HAL_RCC_GPIOB_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOBEN)) == RESET) -#define __HAL_RCC_GPIOC_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOCEN)) == RESET) -#define __HAL_RCC_GPIOH_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOHEN)) == RESET) -#define __HAL_RCC_DMA1_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA1EN)) == RESET) -#define __HAL_RCC_DMA2_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA2EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_WWDG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_PWR_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM5EN)) -#define __HAL_RCC_WWDG_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_WWDGEN)) -#define __HAL_RCC_SPI2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI2EN)) -#define __HAL_RCC_USART2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART2EN)) -#define __HAL_RCC_I2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C1EN)) -#define __HAL_RCC_I2C2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C2EN)) -#define __HAL_RCC_PWR_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_PWREN)) -/** - * @} - */ - -/** @defgroup RCC_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM5EN)) != RESET) -#define __HAL_RCC_WWDG_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) != RESET) -#define __HAL_RCC_SPI2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) != RESET) -#define __HAL_RCC_USART2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) != RESET) -#define __HAL_RCC_I2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) != RESET) -#define __HAL_RCC_I2C2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) != RESET) -#define __HAL_RCC_PWR_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) != RESET) - -#define __HAL_RCC_TIM5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM5EN)) == RESET) -#define __HAL_RCC_WWDG_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) == RESET) -#define __HAL_RCC_SPI2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) == RESET) -#define __HAL_RCC_USART2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) == RESET) -#define __HAL_RCC_I2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) == RESET) -#define __HAL_RCC_I2C2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) == RESET) -#define __HAL_RCC_PWR_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SYSCFG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM9_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM9EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM9EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM11_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM11EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM11EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM1EN)) -#define __HAL_RCC_USART1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART1EN)) -#define __HAL_RCC_USART6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART6EN)) -#define __HAL_RCC_ADC1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC1EN)) -#define __HAL_RCC_SPI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI1EN)) -#define __HAL_RCC_SYSCFG_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SYSCFGEN)) -#define __HAL_RCC_TIM9_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM9EN)) -#define __HAL_RCC_TIM11_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM11EN)) -/** - * @} - */ - -/** @defgroup RCC_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) != RESET) -#define __HAL_RCC_USART1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) != RESET) -#define __HAL_RCC_USART6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) != RESET) -#define __HAL_RCC_ADC1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) != RESET) -#define __HAL_RCC_SPI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) != RESET) -#define __HAL_RCC_SYSCFG_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) != RESET) -#define __HAL_RCC_TIM9_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM9EN)) != RESET) -#define __HAL_RCC_TIM11_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM11EN)) != RESET) - -#define __HAL_RCC_TIM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) == RESET) -#define __HAL_RCC_USART1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) == RESET) -#define __HAL_RCC_USART6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) == RESET) -#define __HAL_RCC_ADC1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) == RESET) -#define __HAL_RCC_SPI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) == RESET) -#define __HAL_RCC_SYSCFG_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) == RESET) -#define __HAL_RCC_TIM9_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM9EN)) == RESET) -#define __HAL_RCC_TIM11_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM11EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB1_FORCE_RESET() (RCC->AHB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_GPIOA_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOARST)) -#define __HAL_RCC_GPIOB_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOBRST)) -#define __HAL_RCC_GPIOC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOCRST)) -#define __HAL_RCC_GPIOH_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOHRST)) -#define __HAL_RCC_DMA1_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA1RST)) -#define __HAL_RCC_DMA2_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA2RST)) - -#define __HAL_RCC_AHB1_RELEASE_RESET() (RCC->AHB1RSTR = 0x00U) -#define __HAL_RCC_GPIOA_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOARST)) -#define __HAL_RCC_GPIOB_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOBRST)) -#define __HAL_RCC_GPIOC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOCRST)) -#define __HAL_RCC_GPIOH_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOHRST)) -#define __HAL_RCC_DMA1_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA1RST)) -#define __HAL_RCC_DMA2_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA2RST)) -/** - * @} - */ - -/** @defgroup RCC_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM5RST)) -#define __HAL_RCC_WWDG_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_WWDGRST)) -#define __HAL_RCC_SPI2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI2RST)) -#define __HAL_RCC_USART2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART2RST)) -#define __HAL_RCC_I2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C1RST)) -#define __HAL_RCC_I2C2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C2RST)) -#define __HAL_RCC_PWR_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_PWRRST)) - -#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00U) -#define __HAL_RCC_TIM5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM5RST)) -#define __HAL_RCC_WWDG_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_WWDGRST)) -#define __HAL_RCC_SPI2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI2RST)) -#define __HAL_RCC_USART2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART2RST)) -#define __HAL_RCC_I2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C1RST)) -#define __HAL_RCC_I2C2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C2RST)) -#define __HAL_RCC_PWR_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_PWRRST)) -/** - * @} - */ - -/** @defgroup RCC_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM1RST)) -#define __HAL_RCC_USART1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART1RST)) -#define __HAL_RCC_USART6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART6RST)) -#define __HAL_RCC_ADC_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_ADCRST)) -#define __HAL_RCC_SPI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI1RST)) -#define __HAL_RCC_SYSCFG_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SYSCFGRST)) -#define __HAL_RCC_TIM9_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM9RST)) -#define __HAL_RCC_TIM11_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM11RST)) - -#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00U) -#define __HAL_RCC_TIM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM1RST)) -#define __HAL_RCC_USART1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART1RST)) -#define __HAL_RCC_USART6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART6RST)) -#define __HAL_RCC_ADC_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_ADCRST)) -#define __HAL_RCC_SPI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI1RST)) -#define __HAL_RCC_SYSCFG_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SYSCFGRST)) -#define __HAL_RCC_TIM9_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM9RST)) -#define __HAL_RCC_TIM11_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM11RST)) -/** - * @} - */ - -/** @defgroup RCC_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOALPEN)) -#define __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOBLPEN)) -#define __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOCLPEN)) -#define __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOHLPEN)) -#define __HAL_RCC_DMA1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA1LPEN)) -#define __HAL_RCC_DMA2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA2LPEN)) - -#define __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOALPEN)) -#define __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOBLPEN)) -#define __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOCLPEN)) -#define __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOHLPEN)) -#define __HAL_RCC_DMA1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA1LPEN)) -#define __HAL_RCC_DMA2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA2LPEN)) -/** - * @} - */ - -/** @defgroup RCC_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM5LPEN)) -#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_WWDGLPEN)) -#define __HAL_RCC_SPI2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI2LPEN)) -#define __HAL_RCC_USART2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART2LPEN)) -#define __HAL_RCC_I2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C1LPEN)) -#define __HAL_RCC_I2C2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C2LPEN)) -#define __HAL_RCC_PWR_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_PWRLPEN)) - -#define __HAL_RCC_TIM5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM5LPEN)) -#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_WWDGLPEN)) -#define __HAL_RCC_SPI2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI2LPEN)) -#define __HAL_RCC_USART2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART2LPEN)) -#define __HAL_RCC_I2C1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C1LPEN)) -#define __HAL_RCC_I2C2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C2LPEN)) -#define __HAL_RCC_PWR_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_PWRLPEN)) -/** - * @} - */ - -/** @defgroup RCC_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM1LPEN)) -#define __HAL_RCC_USART1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_USART1LPEN)) -#define __HAL_RCC_USART6_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_USART6LPEN)) -#define __HAL_RCC_ADC1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC1LPEN)) -#define __HAL_RCC_SPI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI1LPEN)) -#define __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SYSCFGLPEN)) -#define __HAL_RCC_TIM9_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM9LPEN)) -#define __HAL_RCC_TIM11_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM11LPEN)) - -#define __HAL_RCC_TIM1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM1LPEN)) -#define __HAL_RCC_USART1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_USART1LPEN)) -#define __HAL_RCC_USART6_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_USART6LPEN)) -#define __HAL_RCC_ADC1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC1LPEN)) -#define __HAL_RCC_SPI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI1LPEN)) -#define __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SYSCFGLPEN)) -#define __HAL_RCC_TIM9_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM9LPEN)) -#define __HAL_RCC_TIM11_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM11LPEN)) -/** - * @} - */ - -/** @defgroup RCC_HSI_Configuration HSI Configuration - * @{ - */ - -/** @brief Macros to enable or disable the Internal High Speed oscillator (HSI). - * @note The HSI is stopped by hardware when entering STOP and STANDBY modes. - * It is used (enabled by hardware) as system clock source after startup - * from Reset, wake-up from STOP and STANDBY mode, or in case of failure - * of the HSE used directly or indirectly as system clock (if the Clock - * Security System CSS is enabled). - * @note HSI can not be stopped if it is used as system clock source. In this case, - * you have to select another source of the system clock then stop the HSI. - * @note After enabling the HSI, the application software should wait on HSIRDY - * flag to be set indicating that HSI clock is stable and can be used as - * system clock source. - * This parameter can be: ENABLE or DISABLE. - * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator - * clock cycles. - */ -#define __HAL_RCC_HSI_ENABLE() (*(__IO uint32_t *) RCC_CR_HSION_BB = ENABLE) -#define __HAL_RCC_HSI_DISABLE() (*(__IO uint32_t *) RCC_CR_HSION_BB = DISABLE) - -/** @brief Macro to adjust the Internal High Speed oscillator (HSI) calibration value. - * @note The calibration is used to compensate for the variations in voltage - * and temperature that influence the frequency of the internal HSI RC. - * @param __HSICalibrationValue__ specifies the calibration trimming value. - * (default is RCC_HSICALIBRATION_DEFAULT). - * This parameter must be a number between 0 and 0x1F. - */ -#define __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(__HSICalibrationValue__) (MODIFY_REG(RCC->CR,\ - RCC_CR_HSITRIM, (uint32_t)(__HSICalibrationValue__) << RCC_CR_HSITRIM_Pos)) -/** - * @} - */ - -/** @defgroup RCC_LSI_Configuration LSI Configuration - * @{ - */ - -/** @brief Macros to enable or disable the Internal Low Speed oscillator (LSI). - * @note After enabling the LSI, the application software should wait on - * LSIRDY flag to be set indicating that LSI clock is stable and can - * be used to clock the IWDG and/or the RTC. - * @note LSI can not be disabled if the IWDG is running. - * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator - * clock cycles. - */ -#define __HAL_RCC_LSI_ENABLE() (*(__IO uint32_t *) RCC_CSR_LSION_BB = ENABLE) -#define __HAL_RCC_LSI_DISABLE() (*(__IO uint32_t *) RCC_CSR_LSION_BB = DISABLE) -/** - * @} - */ - -/** @defgroup RCC_HSE_Configuration HSE Configuration - * @{ - */ - -/** - * @brief Macro to configure the External High Speed oscillator (HSE). - * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not supported by this macro. - * User should request a transition to HSE Off first and then HSE On or HSE Bypass. - * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application - * software should wait on HSERDY flag to be set indicating that HSE clock - * is stable and can be used to clock the PLL and/or system clock. - * @note HSE state can not be changed if it is used directly or through the - * PLL as system clock. In this case, you have to select another source - * of the system clock then change the HSE state (ex. disable it). - * @note The HSE is stopped by hardware when entering STOP and STANDBY modes. - * @note This function reset the CSSON bit, so if the clock security system(CSS) - * was previously enabled you have to enable it again after calling this - * function. - * @param __STATE__ specifies the new state of the HSE. - * This parameter can be one of the following values: - * @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after - * 6 HSE oscillator clock cycles. - * @arg RCC_HSE_ON: turn ON the HSE oscillator. - * @arg RCC_HSE_BYPASS: HSE oscillator bypassed with external clock. - */ -#define __HAL_RCC_HSE_CONFIG(__STATE__) \ - do { \ - if ((__STATE__) == RCC_HSE_ON) \ - { \ - SET_BIT(RCC->CR, RCC_CR_HSEON); \ - } \ - else if ((__STATE__) == RCC_HSE_BYPASS) \ - { \ - SET_BIT(RCC->CR, RCC_CR_HSEBYP); \ - SET_BIT(RCC->CR, RCC_CR_HSEON); \ - } \ - else \ - { \ - CLEAR_BIT(RCC->CR, RCC_CR_HSEON); \ - CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); \ - } \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCC_LSE_Configuration LSE Configuration - * @{ - */ - -/** - * @brief Macro to configure the External Low Speed oscillator (LSE). - * @note Transition LSE Bypass to LSE On and LSE On to LSE Bypass are not supported by this macro. - * User should request a transition to LSE Off first and then LSE On or LSE Bypass. - * @note As the LSE is in the Backup domain and write access is denied to - * this domain after reset, you have to enable write access using - * HAL_PWR_EnableBkUpAccess() function before to configure the LSE - * (to be done once after reset). - * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_BYPASS), the application - * software should wait on LSERDY flag to be set indicating that LSE clock - * is stable and can be used to clock the RTC. - * @param __STATE__ specifies the new state of the LSE. - * This parameter can be one of the following values: - * @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after - * 6 LSE oscillator clock cycles. - * @arg RCC_LSE_ON: turn ON the LSE oscillator. - * @arg RCC_LSE_BYPASS: LSE oscillator bypassed with external clock. - */ -#define __HAL_RCC_LSE_CONFIG(__STATE__) \ - do { \ - if((__STATE__) == RCC_LSE_ON) \ - { \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - } \ - else if((__STATE__) == RCC_LSE_BYPASS) \ - { \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - } \ - else \ - { \ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \ - } \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCC_Internal_RTC_Clock_Configuration RTC Clock Configuration - * @{ - */ - -/** @brief Macros to enable or disable the RTC clock. - * @note These macros must be used only after the RTC clock source was selected. - */ -#define __HAL_RCC_RTC_ENABLE() (*(__IO uint32_t *) RCC_BDCR_RTCEN_BB = ENABLE) -#define __HAL_RCC_RTC_DISABLE() (*(__IO uint32_t *) RCC_BDCR_RTCEN_BB = DISABLE) - -/** @brief Macros to configure the RTC clock (RTCCLK). - * @note As the RTC clock configuration bits are in the Backup domain and write - * access is denied to this domain after reset, you have to enable write - * access using the Power Backup Access macro before to configure - * the RTC clock source (to be done once after reset). - * @note Once the RTC clock is configured it can't be changed unless the - * Backup domain is reset using __HAL_RCC_BackupReset_RELEASE() macro, or by - * a Power On Reset (POR). - * @param __RTCCLKSource__ specifies the RTC clock source. - * This parameter can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_NO_CLK : No clock selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_LSE : LSE selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_LSI : LSI selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - * @note If the LSE or LSI is used as RTC clock source, the RTC continues to - * work in STOP and STANDBY modes, and can be used as wake-up source. - * However, when the HSE clock is used as RTC clock source, the RTC - * cannot be used in STOP and STANDBY modes. - * @note The maximum input clock frequency for RTC is 1MHz (when using HSE as - * RTC clock source). - */ -#define __HAL_RCC_RTC_CLKPRESCALER(__RTCCLKSource__) (((__RTCCLKSource__) & RCC_BDCR_RTCSEL) == RCC_BDCR_RTCSEL) ? \ - MODIFY_REG(RCC->CFGR, RCC_CFGR_RTCPRE, ((__RTCCLKSource__) & 0xFFFFCFFU)) : CLEAR_BIT(RCC->CFGR, RCC_CFGR_RTCPRE) - -#define __HAL_RCC_RTC_CONFIG(__RTCCLKSource__) do { __HAL_RCC_RTC_CLKPRESCALER(__RTCCLKSource__); \ - RCC->BDCR |= ((__RTCCLKSource__) & 0x00000FFFU); \ - } while(0U) - -/** @brief Macro to get the RTC clock source. - * @retval The clock source can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_NO_CLK No clock selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_LSE LSE selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_LSI LSI selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - */ -#define __HAL_RCC_GET_RTC_SOURCE() (READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL)) - -/** - * @brief Get the RTC and HSE clock divider (RTCPRE). - * @retval Returned value can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - */ -#define __HAL_RCC_GET_RTC_HSE_PRESCALER() (READ_BIT(RCC->CFGR, RCC_CFGR_RTCPRE) | RCC_BDCR_RTCSEL) - -/** @brief Macros to force or release the Backup domain reset. - * @note This function resets the RTC peripheral (including the backup registers) - * and the RTC clock source selection in RCC_CSR register. - * @note The BKPSRAM is not affected by this reset. - */ -#define __HAL_RCC_BACKUPRESET_FORCE() (*(__IO uint32_t *) RCC_BDCR_BDRST_BB = ENABLE) -#define __HAL_RCC_BACKUPRESET_RELEASE() (*(__IO uint32_t *) RCC_BDCR_BDRST_BB = DISABLE) -/** - * @} - */ - -/** @defgroup RCC_PLL_Configuration PLL Configuration - * @{ - */ - -/** @brief Macros to enable or disable the main PLL. - * @note After enabling the main PLL, the application software should wait on - * PLLRDY flag to be set indicating that PLL clock is stable and can - * be used as system clock source. - * @note The main PLL can not be disabled if it is used as system clock source - * @note The main PLL is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLL_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLON_BB = ENABLE) -#define __HAL_RCC_PLL_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLON_BB = DISABLE) - -/** @brief Macro to configure the PLL clock source. - * @note This function must be used only when the main PLL is disabled. - * @param __PLLSOURCE__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * - */ -#define __HAL_RCC_PLL_PLLSOURCE_CONFIG(__PLLSOURCE__) MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, (__PLLSOURCE__)) - -/** @brief Macro to configure the PLL multiplication factor. - * @note This function must be used only when the main PLL is disabled. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * - */ -#define __HAL_RCC_PLL_PLLM_CONFIG(__PLLM__) MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, (__PLLM__)) -/** - * @} - */ - -/** @defgroup RCC_Get_Clock_source Get Clock source - * @{ - */ -/** - * @brief Macro to configure the system clock source. - * @param __RCC_SYSCLKSOURCE__ specifies the system clock source. - * This parameter can be one of the following values: - * - RCC_SYSCLKSOURCE_HSI: HSI oscillator is used as system clock source. - * - RCC_SYSCLKSOURCE_HSE: HSE oscillator is used as system clock source. - * - RCC_SYSCLKSOURCE_PLLCLK: PLL output is used as system clock source. - * - RCC_SYSCLKSOURCE_PLLRCLK: PLLR output is used as system clock source. This - * parameter is available only for STM32F446xx devices. - */ -#define __HAL_RCC_SYSCLK_CONFIG(__RCC_SYSCLKSOURCE__) MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, (__RCC_SYSCLKSOURCE__)) - -/** @brief Macro to get the clock source used as system clock. - * @retval The clock source used as system clock. The returned value can be one - * of the following: - * - RCC_SYSCLKSOURCE_STATUS_HSI: HSI used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_HSE: HSE used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_PLLCLK: PLL used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_PLLRCLK: PLLR used as system clock. This parameter - * is available only for STM32F446xx devices. - */ -#define __HAL_RCC_GET_SYSCLK_SOURCE() (RCC->CFGR & RCC_CFGR_SWS) - -/** @brief Macro to get the oscillator used as PLL clock source. - * @retval The oscillator used as PLL clock source. The returned value can be one - * of the following: - * - RCC_PLLSOURCE_HSI: HSI oscillator is used as PLL clock source. - * - RCC_PLLSOURCE_HSE: HSE oscillator is used as PLL clock source. - */ -#define __HAL_RCC_GET_PLL_OSCSOURCE() ((uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC)) -/** - * @} - */ - -/** @defgroup RCCEx_MCOx_Clock_Config RCC Extended MCOx Clock Config - * @{ - */ - -/** @brief Macro to configure the MCO1 clock. - * @param __MCOCLKSOURCE__ specifies the MCO clock source. - * This parameter can be one of the following values: - * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source - * @param __MCODIV__ specifies the MCO clock prescaler. - * This parameter can be one of the following values: - * @arg RCC_MCODIV_1: no division applied to MCOx clock - * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock - * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock - * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock - * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock - */ -#define __HAL_RCC_MCO1_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), ((__MCOCLKSOURCE__) | (__MCODIV__))) - -/** @brief Macro to configure the MCO2 clock. - * @param __MCOCLKSOURCE__ specifies the MCO clock source. - * This parameter can be one of the following values: - * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx - * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410Rx devices - * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source - * @param __MCODIV__ specifies the MCO clock prescaler. - * This parameter can be one of the following values: - * @arg RCC_MCODIV_1: no division applied to MCOx clock - * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock - * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock - * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock - * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock - * @note For STM32F410Rx devices, to output I2SCLK clock on MCO2, you should have - * at least one of the SPI clocks enabled (SPI1, SPI2 or SPI5). - */ -#define __HAL_RCC_MCO2_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), ((__MCOCLKSOURCE__) | ((__MCODIV__) << 3U))); -/** - * @} - */ - -/** @defgroup RCC_Flags_Interrupts_Management Flags Interrupts Management - * @brief macros to manage the specified RCC Flags and interrupts. - * @{ - */ - -/** @brief Enable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to enable - * the selected interrupts). - * @param __INTERRUPT__ specifies the RCC interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - */ -#define __HAL_RCC_ENABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS |= (__INTERRUPT__)) - -/** @brief Disable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to disable - * the selected interrupts). - * @param __INTERRUPT__ specifies the RCC interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - */ -#define __HAL_RCC_DISABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS &= (uint8_t)(~(__INTERRUPT__))) - -/** @brief Clear the RCC's interrupt pending bits (Perform Byte access to RCC_CIR[23:16] - * bits to clear the selected interrupt pending bits. - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - * @arg RCC_IT_CSS: Clock Security System interrupt - */ -#define __HAL_RCC_CLEAR_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE2_ADDRESS = (__INTERRUPT__)) - -/** @brief Check the RCC's interrupt has occurred or not. - * @param __INTERRUPT__ specifies the RCC interrupt source to check. - * This parameter can be one of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - * @arg RCC_IT_CSS: Clock Security System interrupt - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_RCC_GET_IT(__INTERRUPT__) ((RCC->CIR & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** @brief Set RMVF bit to clear the reset flags: RCC_FLAG_PINRST, RCC_FLAG_PORRST, - * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST and RCC_FLAG_LPWRRST. - */ -#define __HAL_RCC_CLEAR_RESET_FLAGS() (RCC->CSR |= RCC_CSR_RMVF) - -/** @brief Check RCC flag is set or not. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready. - * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready. - * @arg RCC_FLAG_PLLRDY: Main PLL clock ready. - * @arg RCC_FLAG_PLLI2SRDY: PLLI2S clock ready. - * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready. - * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready. - * @arg RCC_FLAG_BORRST: POR/PDR or BOR reset. - * @arg RCC_FLAG_PINRST: Pin reset. - * @arg RCC_FLAG_PORRST: POR/PDR reset. - * @arg RCC_FLAG_SFTRST: Software reset. - * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset. - * @arg RCC_FLAG_WWDGRST: Window Watchdog reset. - * @arg RCC_FLAG_LPWRRST: Low Power reset. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define RCC_FLAG_MASK ((uint8_t)0x1FU) -#define __HAL_RCC_GET_FLAG(__FLAG__) (((((((__FLAG__) >> 5U) == 1U)? RCC->CR :((((__FLAG__) >> 5U) == 2U) ? RCC->BDCR :((((__FLAG__) >> 5U) == 3U)? RCC->CSR :RCC->CIR))) & (1U << ((__FLAG__) & RCC_FLAG_MASK)))!= 0U)? 1U : 0U) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - /** @addtogroup RCC_Exported_Functions - * @{ - */ - -/** @addtogroup RCC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions ******************************/ -HAL_StatusTypeDef HAL_RCC_DeInit(void); -HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct); -HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency); -/** - * @} - */ - -/** @addtogroup RCC_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ************************************************/ -void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv); -void HAL_RCC_EnableCSS(void); -void HAL_RCC_DisableCSS(void); -uint32_t HAL_RCC_GetSysClockFreq(void); -uint32_t HAL_RCC_GetHCLKFreq(void); -uint32_t HAL_RCC_GetPCLK1Freq(void); -uint32_t HAL_RCC_GetPCLK2Freq(void); -void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct); -void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency); - -/* CSS NMI IRQ handler */ -void HAL_RCC_NMI_IRQHandler(void); - -/* User Callbacks in non blocking mode (IT mode) */ -void HAL_RCC_CSSCallback(void); - -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RCC_Private_Constants RCC Private Constants - * @{ - */ - -/** @defgroup RCC_BitAddress_AliasRegion RCC BitAddress AliasRegion - * @brief RCC registers bit address in the alias region - * @{ - */ -#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) -/* --- CR Register --- */ -/* Alias word address of HSION bit */ -#define RCC_CR_OFFSET (RCC_OFFSET + 0x00U) -#define RCC_HSION_BIT_NUMBER 0x00U -#define RCC_CR_HSION_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_HSION_BIT_NUMBER * 4U)) -/* Alias word address of CSSON bit */ -#define RCC_CSSON_BIT_NUMBER 0x13U -#define RCC_CR_CSSON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_CSSON_BIT_NUMBER * 4U)) -/* Alias word address of PLLON bit */ -#define RCC_PLLON_BIT_NUMBER 0x18U -#define RCC_CR_PLLON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLON_BIT_NUMBER * 4U)) - -/* --- BDCR Register --- */ -/* Alias word address of RTCEN bit */ -#define RCC_BDCR_OFFSET (RCC_OFFSET + 0x70U) -#define RCC_RTCEN_BIT_NUMBER 0x0FU -#define RCC_BDCR_RTCEN_BB (PERIPH_BB_BASE + (RCC_BDCR_OFFSET * 32U) + (RCC_RTCEN_BIT_NUMBER * 4U)) -/* Alias word address of BDRST bit */ -#define RCC_BDRST_BIT_NUMBER 0x10U -#define RCC_BDCR_BDRST_BB (PERIPH_BB_BASE + (RCC_BDCR_OFFSET * 32U) + (RCC_BDRST_BIT_NUMBER * 4U)) - -/* --- CSR Register --- */ -/* Alias word address of LSION bit */ -#define RCC_CSR_OFFSET (RCC_OFFSET + 0x74U) -#define RCC_LSION_BIT_NUMBER 0x00U -#define RCC_CSR_LSION_BB (PERIPH_BB_BASE + (RCC_CSR_OFFSET * 32U) + (RCC_LSION_BIT_NUMBER * 4U)) - -/* CR register byte 3 (Bits[23:16]) base address */ -#define RCC_CR_BYTE2_ADDRESS 0x40023802U - -/* CIR register byte 2 (Bits[15:8]) base address */ -#define RCC_CIR_BYTE1_ADDRESS ((uint32_t)(RCC_BASE + 0x0CU + 0x01U)) - -/* CIR register byte 3 (Bits[23:16]) base address */ -#define RCC_CIR_BYTE2_ADDRESS ((uint32_t)(RCC_BASE + 0x0CU + 0x02U)) - -/* BDCR register base address */ -#define RCC_BDCR_BYTE0_ADDRESS (PERIPH_BASE + RCC_BDCR_OFFSET) - -#define RCC_DBP_TIMEOUT_VALUE 2U -#define RCC_LSE_TIMEOUT_VALUE LSE_STARTUP_TIMEOUT - -#define HSE_TIMEOUT_VALUE HSE_STARTUP_TIMEOUT -#define HSI_TIMEOUT_VALUE 2U /* 2 ms */ -#define LSI_TIMEOUT_VALUE 2U /* 2 ms */ -#define CLOCKSWITCH_TIMEOUT_VALUE 5000U /* 5 s */ - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RCC_Private_Macros RCC Private Macros - * @{ - */ - -/** @defgroup RCC_IS_RCC_Definitions RCC Private macros to check input parameters - * @{ - */ -#define IS_RCC_OSCILLATORTYPE(OSCILLATOR) ((OSCILLATOR) <= 15U) - -#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ - ((HSE) == RCC_HSE_BYPASS)) - -#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ - ((LSE) == RCC_LSE_BYPASS)) - -#define IS_RCC_HSI(HSI) (((HSI) == RCC_HSI_OFF) || ((HSI) == RCC_HSI_ON)) - -#define IS_RCC_LSI(LSI) (((LSI) == RCC_LSI_OFF) || ((LSI) == RCC_LSI_ON)) - -#define IS_RCC_PLL(PLL) (((PLL) == RCC_PLL_NONE) ||((PLL) == RCC_PLL_OFF) || ((PLL) == RCC_PLL_ON)) - -#define IS_RCC_PLLSOURCE(SOURCE) (((SOURCE) == RCC_PLLSOURCE_HSI) || \ - ((SOURCE) == RCC_PLLSOURCE_HSE)) - -#define IS_RCC_SYSCLKSOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSOURCE_HSI) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_HSE) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_PLLCLK) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_PLLRCLK)) - -#define IS_RCC_RTCCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_RTCCLKSOURCE_LSE) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_LSI) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV2) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV3) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV4) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV5) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV6) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV7) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV8) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV9) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV10) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV11) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV12) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV13) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV14) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV15) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV16) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV17) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV18) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV19) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV20) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV21) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV22) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV23) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV24) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV25) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV26) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV27) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV28) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV29) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV30) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV31)) - -#define IS_RCC_PLLM_VALUE(VALUE) ((VALUE) <= 63U) - -#define IS_RCC_PLLP_VALUE(VALUE) (((VALUE) == 2U) || ((VALUE) == 4U) || ((VALUE) == 6U) || ((VALUE) == 8U)) - -#define IS_RCC_PLLQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_DIV1) || ((HCLK) == RCC_SYSCLK_DIV2) || \ - ((HCLK) == RCC_SYSCLK_DIV4) || ((HCLK) == RCC_SYSCLK_DIV8) || \ - ((HCLK) == RCC_SYSCLK_DIV16) || ((HCLK) == RCC_SYSCLK_DIV64) || \ - ((HCLK) == RCC_SYSCLK_DIV128) || ((HCLK) == RCC_SYSCLK_DIV256) || \ - ((HCLK) == RCC_SYSCLK_DIV512)) - -#define IS_RCC_CLOCKTYPE(CLK) ((1U <= (CLK)) && ((CLK) <= 15U)) - -#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_DIV1) || ((PCLK) == RCC_HCLK_DIV2) || \ - ((PCLK) == RCC_HCLK_DIV4) || ((PCLK) == RCC_HCLK_DIV8) || \ - ((PCLK) == RCC_HCLK_DIV16)) - -#define IS_RCC_MCO(MCOx) (((MCOx) == RCC_MCO1) || ((MCOx) == RCC_MCO2)) - -#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1SOURCE_HSI) || ((SOURCE) == RCC_MCO1SOURCE_LSE) || \ - ((SOURCE) == RCC_MCO1SOURCE_HSE) || ((SOURCE) == RCC_MCO1SOURCE_PLLCLK)) - -#define IS_RCC_MCODIV(DIV) (((DIV) == RCC_MCODIV_1) || ((DIV) == RCC_MCODIV_2) || \ - ((DIV) == RCC_MCODIV_3) || ((DIV) == RCC_MCODIV_4) || \ - ((DIV) == RCC_MCODIV_5)) -#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1FU) - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RCC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h deleted file mode 100644 index df6a66ab14dcb66..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h +++ /dev/null @@ -1,7114 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc_ex.h - * @author MCD Application Team - * @brief Header file of RCC HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RCC_EX_H -#define __STM32F4xx_HAL_RCC_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RCCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Types RCCEx Exported Types - * @{ - */ - -/** - * @brief RCC PLL configuration structure definition - */ -typedef struct -{ - uint32_t PLLState; /*!< The new state of the PLL. - This parameter can be a value of @ref RCC_PLL_Config */ - - uint32_t PLLSource; /*!< RCC_PLLSource: PLL entry clock source. - This parameter must be a value of @ref RCC_PLL_Clock_Source */ - - uint32_t PLLM; /*!< PLLM: Division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 0 and Max_Data = 63 */ - - uint32_t PLLN; /*!< PLLN: Multiplication factor for PLL VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 - except for STM32F411xE devices where the Min_Data = 192 */ - - uint32_t PLLP; /*!< PLLP: Division factor for main system clock (SYSCLK). - This parameter must be a value of @ref RCC_PLLP_Clock_Divider */ - - uint32_t PLLQ; /*!< PLLQ: Division factor for OTG FS, SDIO and RNG clocks. - This parameter must be a number between Min_Data = 2 and Max_Data = 15 */ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) - uint32_t PLLR; /*!< PLLR: PLL division factor for I2S, SAI, SYSTEM, SPDIFRX clocks. - This parameter is only available in STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx - and STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/STM32F413xx/STM32F423xx devices. - This parameter must be a number between Min_Data = 2 and Max_Data = 7 */ -#endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -}RCC_PLLInitTypeDef; - -#if defined(STM32F446xx) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLI2SP; /*!< Specifies division factor for SPDIFRX Clock. - This parameter must be a value of @ref RCCEx_PLLI2SP_Clock_Divider */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief PLLSAI Clock structure definition - */ -typedef struct -{ - uint32_t PLLSAIM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLSAIN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLSAIP; /*!< Specifies division factor for OTG FS, SDIO and RNG clocks. - This parameter must be a value of @ref RCCEx_PLLSAIP_Clock_Divider */ - - uint32_t PLLSAIQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ -}RCC_PLLSAIInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - RCC_PLLSAIInitTypeDef PLLSAI; /*!< PLL SAI structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source SAI or LTDC */ - - uint32_t PLLI2SDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLSAIDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ - - uint32_t Sai1ClockSelection; /*!< Specifies SAI1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_SAI1_Clock_Source */ - - uint32_t Sai2ClockSelection; /*!< Specifies SAI2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_SAI2_Clock_Source */ - - uint32_t I2sApb1ClockSelection; /*!< Specifies I2S APB1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB1_Clock_Source */ - - uint32_t I2sApb2ClockSelection; /*!< Specifies I2S APB2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB2_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ - - uint32_t CecClockSelection; /*!< Specifies CEC Clock Source Selection. - This parameter can be a value of @ref RCCEx_CEC_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint32_t SpdifClockSelection; /*!< Specifies SPDIFRX Clock Source Selection. - This parameter can be a value of @ref RCCEx_SPDIFRX_Clock_Source */ - - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F446xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - uint32_t I2SClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2S_APB_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t Lptim1ClockSelection; /*!< Specifies LPTIM1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_LPTIM1_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ - -#if defined(STM32F413xx) || defined(STM32F423xx) - uint32_t PLLDivR; /*!< Specifies the PLL division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLL is selected as Clock Source SAI */ - - uint32_t PLLI2SDivR; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ -#endif /* STM32F413xx || STM32F423xx */ - - uint32_t I2sApb1ClockSelection; /*!< Specifies I2S APB1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB1_Clock_Source */ - - uint32_t I2sApb2ClockSelection; /*!< Specifies I2S APB2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB2_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint32_t Dfsdm1ClockSelection; /*!< Specifies DFSDM1 Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM1_Kernel_Clock_Source */ - - uint32_t Dfsdm1AudioClockSelection;/*!< Specifies DFSDM1 Audio Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM1_Audio_Clock_Source */ - -#if defined(STM32F413xx) || defined(STM32F423xx) - uint32_t Dfsdm2ClockSelection; /*!< Specifies DFSDM2 Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM2_Kernel_Clock_Source */ - - uint32_t Dfsdm2AudioClockSelection;/*!< Specifies DFSDM2 Audio Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM2_Audio_Clock_Source */ - - uint32_t Lptim1ClockSelection; /*!< Specifies LPTIM1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_LPTIM1_Clock_Source */ - - uint32_t SaiAClockSelection; /*!< Specifies SAI1_A Clock Prescalers Selection - This parameter can be a value of @ref RCCEx_SAI1_BlockA_Clock_Source */ - - uint32_t SaiBClockSelection; /*!< Specifies SAI1_B Clock Prescalers Selection - This parameter can be a value of @ref RCCEx_SAI1_BlockB_Clock_Source */ -#endif /* STM32F413xx || STM32F423xx */ - - uint32_t PLLI2SSelection; /*!< Specifies PLL I2S Clock Source Selection. - This parameter can be a value of @ref RCCEx_PLL_I2S_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI1 clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief PLLSAI Clock structure definition - */ -typedef struct -{ - uint32_t PLLSAIN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432. - This parameter will be used only when PLLSAI is selected as Clock Source SAI or LTDC */ -#if defined(STM32F469xx) || defined(STM32F479xx) - uint32_t PLLSAIP; /*!< Specifies division factor for OTG FS and SDIO clocks. - This parameter is only available in STM32F469xx/STM32F479xx devices. - This parameter must be a value of @ref RCCEx_PLLSAIP_Clock_Divider */ -#endif /* STM32F469xx || STM32F479xx */ - - uint32_t PLLSAIQ; /*!< Specifies the division factor for SAI1 clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLSAI is selected as Clock Source SAI or LTDC */ - - uint32_t PLLSAIR; /*!< specifies the division factor for LTDC clock - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLSAI is selected as Clock Source LTDC */ - -}RCC_PLLSAIInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - RCC_PLLSAIInitTypeDef PLLSAI; /*!< PLL SAI structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source SAI or LTDC */ - - uint32_t PLLI2SDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLSAIDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ - - uint32_t PLLSAIDivR; /*!< Specifies the PLLSAI division factor for LTDC clock. - This parameter must be one value of @ref RCCEx_PLLSAI_DIVR */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Prescalers Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -#if defined(STM32F469xx) || defined(STM32F479xx) - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ -#endif /* STM32F469xx || STM32F479xx */ -}RCC_PeriphCLKInitTypeDef; - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ -#if defined(STM32F411xE) - uint32_t PLLI2SM; /*!< PLLM: Division factor for PLLI2S VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 62 */ -#endif /* STM32F411xE */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 - Except for STM32F411xE devices where the Min_Data = 192. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - -}RCC_PLLI2SInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Constants RCCEx Exported Constants - * @{ - */ - -/** @defgroup RCCEx_Periph_Clock_Selection RCC Periph Clock Selection - * @{ - */ -/* Peripheral Clock source for STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -#define RCC_PERIPHCLK_I2S_APB1 0x00000001U -#define RCC_PERIPHCLK_I2S_APB2 0x00000002U -#define RCC_PERIPHCLK_TIM 0x00000004U -#define RCC_PERIPHCLK_RTC 0x00000008U -#define RCC_PERIPHCLK_FMPI2C1 0x00000010U -#define RCC_PERIPHCLK_CLK48 0x00000020U -#define RCC_PERIPHCLK_SDIO 0x00000040U -#define RCC_PERIPHCLK_PLLI2S 0x00000080U -#define RCC_PERIPHCLK_DFSDM1 0x00000100U -#define RCC_PERIPHCLK_DFSDM1_AUDIO 0x00000200U -#endif /* STM32F412Zx || STM32F412Vx) || STM32F412Rx || STM32F412Cx */ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define RCC_PERIPHCLK_DFSDM2 0x00000400U -#define RCC_PERIPHCLK_DFSDM2_AUDIO 0x00000800U -#define RCC_PERIPHCLK_LPTIM1 0x00001000U -#define RCC_PERIPHCLK_SAIA 0x00002000U -#define RCC_PERIPHCLK_SAIB 0x00004000U -#endif /* STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- Peripheral Clock source for STM32F410xx ----------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_TIM 0x00000002U -#define RCC_PERIPHCLK_RTC 0x00000004U -#define RCC_PERIPHCLK_FMPI2C1 0x00000008U -#define RCC_PERIPHCLK_LPTIM1 0x00000010U -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- Peripheral Clock source for STM32F446xx ----------------*/ -#if defined(STM32F446xx) -#define RCC_PERIPHCLK_I2S_APB1 0x00000001U -#define RCC_PERIPHCLK_I2S_APB2 0x00000002U -#define RCC_PERIPHCLK_SAI1 0x00000004U -#define RCC_PERIPHCLK_SAI2 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_CEC 0x00000040U -#define RCC_PERIPHCLK_FMPI2C1 0x00000080U -#define RCC_PERIPHCLK_CLK48 0x00000100U -#define RCC_PERIPHCLK_SDIO 0x00000200U -#define RCC_PERIPHCLK_SPDIFRX 0x00000400U -#define RCC_PERIPHCLK_PLLI2S 0x00000800U -#endif /* STM32F446xx */ -/*-----------------------------------------------------------------------------*/ - -/*----------- Peripheral Clock source for STM32F469xx/STM32F479xx -------------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_SAI_PLLI2S 0x00000002U -#define RCC_PERIPHCLK_SAI_PLLSAI 0x00000004U -#define RCC_PERIPHCLK_LTDC 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_PLLI2S 0x00000040U -#define RCC_PERIPHCLK_CLK48 0x00000080U -#define RCC_PERIPHCLK_SDIO 0x00000100U -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*-------- Peripheral Clock source for STM32F42xxx/STM32F43xxx ---------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_SAI_PLLI2S 0x00000002U -#define RCC_PERIPHCLK_SAI_PLLSAI 0x00000004U -#define RCC_PERIPHCLK_LTDC 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_PLLI2S 0x00000040U -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*-------- Peripheral Clock source for STM32F40xxx/STM32F41xxx ---------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_RTC 0x00000002U -#define RCC_PERIPHCLK_PLLI2S 0x00000004U -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define RCC_PERIPHCLK_TIM 0x00000008U -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ -/*----------------------------------------------------------------------------*/ -/** - * @} - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) || \ - defined(STM32F479xx) -/** @defgroup RCCEx_I2S_Clock_Source I2S Clock Source - * @{ - */ -#define RCC_I2SCLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SCLKSOURCE_EXT 0x00000001U -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F469xx || STM32F479xx */ - -/** @defgroup RCCEx_PLLSAI_DIVR RCC PLLSAI DIVR - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PLLSAIDIVR_2 0x00000000U -#define RCC_PLLSAIDIVR_4 0x00010000U -#define RCC_PLLSAIDIVR_8 0x00020000U -#define RCC_PLLSAIDIVR_16 0x00030000U -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_PLLI2SP_Clock_Divider RCC PLLI2SP Clock Divider - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define RCC_PLLI2SP_DIV2 0x00000002U -#define RCC_PLLI2SP_DIV4 0x00000004U -#define RCC_PLLI2SP_DIV6 0x00000006U -#define RCC_PLLI2SP_DIV8 0x00000008U -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/** - * @} - */ - -/** @defgroup RCCEx_PLLSAIP_Clock_Divider RCC PLLSAIP Clock Divider - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PLLSAIP_DIV2 0x00000002U -#define RCC_PLLSAIP_DIV4 0x00000004U -#define RCC_PLLSAIP_DIV6 0x00000006U -#define RCC_PLLSAIP_DIV8 0x00000008U -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_SAI_BlockA_Clock_Source RCC SAI BlockA Clock Source - * @{ - */ -#define RCC_SAIACLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAIACLKSOURCE_PLLI2S 0x00100000U -#define RCC_SAIACLKSOURCE_EXT 0x00200000U -/** - * @} - */ - -/** @defgroup RCCEx_SAI_BlockB_Clock_Source RCC SAI BlockB Clock Source - * @{ - */ -#define RCC_SAIBCLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAIBCLKSOURCE_PLLI2S 0x00400000U -#define RCC_SAIBCLKSOURCE_EXT 0x00800000U -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLSAIP ((uint32_t)RCC_DCKCFGR_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_SDIOSEL) -/** - * @} - */ - -/** @defgroup RCCEx_DSI_Clock_Source RCC DSI Clock Source - * @{ - */ -#define RCC_DSICLKSOURCE_DSIPHY 0x00000000U -#define RCC_DSICLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_DSISEL) -/** - * @} - */ -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) -/** @defgroup RCCEx_SAI1_Clock_Source RCC SAI1 Clock Source - * @{ - */ -#define RCC_SAI1CLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAI1CLKSOURCE_PLLI2S ((uint32_t)RCC_DCKCFGR_SAI1SRC_0) -#define RCC_SAI1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1SRC_1) -#define RCC_SAI1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_SAI2_Clock_Source RCC SAI2 Clock Source - * @{ - */ -#define RCC_SAI2CLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAI2CLKSOURCE_PLLI2S ((uint32_t)RCC_DCKCFGR_SAI2SRC_0) -#define RCC_SAI2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI2SRC_1) -#define RCC_SAI2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB1_Clock_Source RCC I2S APB1 Clock Source - * @{ - */ -#define RCC_I2SAPB1CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S1SRC_0) -#define RCC_I2SAPB1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S1SRC_1) -#define RCC_I2SAPB1CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB2_Clock_Source RCC I2S APB2 Clock Source - * @{ - */ -#define RCC_I2SAPB2CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB2CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S2SRC_0) -#define RCC_I2SAPB2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S2SRC_1) -#define RCC_I2SAPB2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_CEC_Clock_Source RCC CEC Clock Source - * @{ - */ -#define RCC_CECCLKSOURCE_HSI 0x00000000U -#define RCC_CECCLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_CECSEL) -/** - * @} - */ - -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLSAIP ((uint32_t)RCC_DCKCFGR2_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_SDIOSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SPDIFRX_Clock_Source RCC SPDIFRX Clock Source - * @{ - */ -#define RCC_SPDIFRXCLKSOURCE_PLLR 0x00000000U -#define RCC_SPDIFRXCLKSOURCE_PLLI2SP ((uint32_t)RCC_DCKCFGR2_SPDIFRXSEL) -/** - * @} - */ - -#endif /* STM32F446xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_SAI1_BlockA_Clock_Source RCC SAI BlockA Clock Source - * @{ - */ -#define RCC_SAIACLKSOURCE_PLLI2SR 0x00000000U -#define RCC_SAIACLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1ASRC_0) -#define RCC_SAIACLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1ASRC_1) -#define RCC_SAIACLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI1ASRC_0 | RCC_DCKCFGR_SAI1ASRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_SAI1_BlockB_Clock_Source RCC SAI BlockB Clock Source - * @{ - */ -#define RCC_SAIBCLKSOURCE_PLLI2SR 0x00000000U -#define RCC_SAIBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1BSRC_0) -#define RCC_SAIBCLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1BSRC_1) -#define RCC_SAIBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI1BSRC_0 | RCC_DCKCFGR_SAI1BSRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_LPTIM1_Clock_Source RCC LPTIM1 Clock Source - * @{ - */ -#define RCC_LPTIM1CLKSOURCE_PCLK1 0x00000000U -#define RCC_LPTIM1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0) -#define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) -#define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) -/** - * @} - */ - - -/** @defgroup RCCEx_DFSDM2_Audio_Clock_Source RCC DFSDM2 Audio Clock Source - * @{ - */ -#define RCC_DFSDM2AUDIOCLKSOURCE_I2S1 0x00000000U -#define RCC_DFSDM2AUDIOCLKSOURCE_I2S2 ((uint32_t)RCC_DCKCFGR_CKDFSDM2ASEL) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM2_Kernel_Clock_Source RCC DFSDM2 Kernel Clock Source - * @{ - */ -#define RCC_DFSDM2CLKSOURCE_PCLK2 0x00000000U -#define RCC_DFSDM2CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_CKDFSDM1SEL) -/** - * @} - */ - -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_PLL_I2S_Clock_Source PLL I2S Clock Source - * @{ - */ -#define RCC_PLLI2SCLKSOURCE_PLLSRC 0x00000000U -#define RCC_PLLI2SCLKSOURCE_EXT ((uint32_t)RCC_PLLI2SCFGR_PLLI2SSRC) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM1_Audio_Clock_Source RCC DFSDM1 Audio Clock Source - * @{ - */ -#define RCC_DFSDM1AUDIOCLKSOURCE_I2S1 0x00000000U -#define RCC_DFSDM1AUDIOCLKSOURCE_I2S2 ((uint32_t)RCC_DCKCFGR_CKDFSDM1ASEL) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM1_Kernel_Clock_Source RCC DFSDM1 Kernel Clock Source - * @{ - */ -#define RCC_DFSDM1CLKSOURCE_PCLK2 0x00000000U -#define RCC_DFSDM1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_CKDFSDM1SEL) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB1_Clock_Source RCC I2S APB1 Clock Source - * @{ - */ -#define RCC_I2SAPB1CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S1SRC_0) -#define RCC_I2SAPB1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S1SRC_1) -#define RCC_I2SAPB1CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB2_Clock_Source RCC I2S APB2 Clock Source - * @{ - */ -#define RCC_I2SAPB2CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB2CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S2SRC_0) -#define RCC_I2SAPB2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S2SRC_1) -#define RCC_I2SAPB2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLI2SQ ((uint32_t)RCC_DCKCFGR2_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_SDIOSEL) -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) - -/** @defgroup RCCEx_I2S_APB_Clock_Source RCC I2S APB Clock Source - * @{ - */ -#define RCC_I2SAPBCLKSOURCE_PLLR 0x00000000U -#define RCC_I2SAPBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2SSRC_0) -#define RCC_I2SAPBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2SSRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_LPTIM1_Clock_Source RCC LPTIM1 Clock Source - * @{ - */ -#define RCC_LPTIM1CLKSOURCE_PCLK1 0x00000000U -#define RCC_LPTIM1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0) -#define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) -#define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_TIM_PRescaler_Selection RCC TIM PRescaler Selection - * @{ - */ -#define RCC_TIMPRES_DESACTIVATED ((uint8_t)0x00) -#define RCC_TIMPRES_ACTIVATED ((uint8_t)0x01) -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -/** @defgroup RCCEx_LSE_Dual_Mode_Selection RCC LSE Dual Mode Selection - * @{ - */ -#define RCC_LSE_LOWPOWER_MODE ((uint8_t)0x00) -#define RCC_LSE_HIGHDRIVE_MODE ((uint8_t)0x01) -/** - * @} - */ -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx ||\ - STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCC_MCO2_Clock_Source MCO2 Clock Source - * @{ - */ -#define RCC_MCO2SOURCE_SYSCLK 0x00000000U -#define RCC_MCO2SOURCE_PLLI2SCLK RCC_CFGR_MCO2_0 -#define RCC_MCO2SOURCE_HSE RCC_CFGR_MCO2_1 -#define RCC_MCO2SOURCE_PLLCLK RCC_CFGR_MCO2 -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F413xx | STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @defgroup RCC_MCO2_Clock_Source MCO2 Clock Source - * @{ - */ -#define RCC_MCO2SOURCE_SYSCLK 0x00000000U -#define RCC_MCO2SOURCE_I2SCLK RCC_CFGR_MCO2_0 -#define RCC_MCO2SOURCE_HSE RCC_CFGR_MCO2_1 -#define RCC_MCO2SOURCE_PLLCLK RCC_CFGR_MCO2 -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Macros RCCEx Exported Macros - * @{ - */ -/*------------------- STM32F42xxx/STM32F43xxx/STM32F469xx/STM32F479xx --------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOJ_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOJEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOJEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOK_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOKEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOKEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA2D_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2DEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2DEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACTX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACPTP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_GPIOI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOIEN)) -#define __HAL_RCC_GPIOJ_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOJEN)) -#define __HAL_RCC_GPIOK_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOKEN)) -#define __HAL_RCC_DMA2D_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA2DEN)) -#define __HAL_RCC_ETHMAC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACEN)) -#define __HAL_RCC_ETHMACTX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACTXEN)) -#define __HAL_RCC_ETHMACRX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACRXEN)) -#define __HAL_RCC_ETHMACPTP_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACPTPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) - -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETH_CLK_ENABLE() do { \ - __HAL_RCC_ETHMAC_CLK_ENABLE(); \ - __HAL_RCC_ETHMACTX_CLK_ENABLE(); \ - __HAL_RCC_ETHMACRX_CLK_ENABLE(); \ - } while(0U) -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETH_CLK_DISABLE() do { \ - __HAL_RCC_ETHMACTX_CLK_DISABLE(); \ - __HAL_RCC_ETHMACRX_CLK_DISABLE(); \ - __HAL_RCC_ETHMAC_CLK_DISABLE(); \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_GPIOI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) != RESET) -#define __HAL_RCC_GPIOJ_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOJEN)) != RESET) -#define __HAL_RCC_GPIOK_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOKEN)) != RESET) -#define __HAL_RCC_DMA2D_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_DMA2DEN)) != RESET) -#define __HAL_RCC_ETHMAC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) != RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) != RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) != RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_ETH_IS_CLK_ENABLED() (__HAL_RCC_ETHMAC_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_ENABLED()) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_GPIOI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) == RESET) -#define __HAL_RCC_GPIOJ_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOJEN)) == RESET) -#define __HAL_RCC_GPIOK_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOKEN)) == RESET) -#define __HAL_RCC_DMA2D_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_DMA2DEN)) == RESET) -#define __HAL_RCC_ETHMAC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) == RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) == RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) == RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) == RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_ETH_IS_CLK_DISABLED() (__HAL_RCC_ETHMAC_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_DISABLED()) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ - #define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_HASH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_CRYP_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_CRYPEN)) -#define __HAL_RCC_HASH_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_HASHEN)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) != RESET) -#define __HAL_RCC_CRYP_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) == RESET) - -#define __HAL_RCC_HASH_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) != RESET) -#define __HAL_RCC_HASH_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) == RESET) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FMCEN)) -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) != RESET) -#define __HAL_RCC_FMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) == RESET) -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -#define __HAL_RCC_UART7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART7EN)) -#define __HAL_RCC_UART8_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART8EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) -#define __HAL_RCC_UART7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) != RESET) -#define __HAL_RCC_UART8_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -#define __HAL_RCC_UART7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) == RESET) -#define __HAL_RCC_UART8_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#define __HAL_RCC_SPI6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI6EN)) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_LTDCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_LTDCEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_LTDC_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_LTDCEN)) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DSIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DSIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_DSI_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DSIEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#define __HAL_RCC_SPI6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI6EN)) != RESET) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN))!= RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN))== RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#define __HAL_RCC_SPI6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI6EN)) == RESET) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_LTDCEN)) != RESET) -#define __HAL_RCC_LTDC_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_LTDCEN)) == RESET) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DSIEN)) != RESET) -#define __HAL_RCC_DSI_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DSIEN)) == RESET) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_GPIOJ_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOJRST)) -#define __HAL_RCC_GPIOK_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOKRST)) -#define __HAL_RCC_DMA2D_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA2DRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_GPIOJ_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOJRST)) -#define __HAL_RCC_GPIOK_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOKRST)) -#define __HAL_RCC_DMA2D_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA2DRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_HASHRST)) - -#define __HAL_RCC_CRYP_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_HASHRST)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -#define __HAL_RCC_FMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_FMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FMCRST)) - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART8RST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART8RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI6RST)) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET()(RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI6RST)) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_LTDCRST)) -#define __HAL_RCC_LTDC_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_LTDCRST)) -#endif /* STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DSIRST)) -#define __HAL_RCC_DSI_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DSIRST)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOJLPEN)) -#define __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOKLPEN)) -#define __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM3LPEN)) -#define __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA2DLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOJLPEN)) -#define __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOKLPEN)) -#define __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA2DLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_HASHLPEN)) - -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_HASHLPEN)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FMCLPEN)) - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART8LPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART8LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SPI6_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI6LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SPI6_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI6LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_LTDCLPEN)) - -#define __HAL_RCC_LTDC_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_LTDCLPEN)) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DSILPEN)) -#define __HAL_RCC_DSI_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DSILPEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------------- STM32F40xxx/STM32F41xxx-----------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_GPIOI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOIEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#if defined(STM32F407xx)|| defined(STM32F417xx) -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACTX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACPTP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETH_CLK_ENABLE() do { \ - __HAL_RCC_ETHMAC_CLK_ENABLE(); \ - __HAL_RCC_ETHMACTX_CLK_ENABLE(); \ - __HAL_RCC_ETHMACRX_CLK_ENABLE(); \ - } while(0U) - -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACEN)) -#define __HAL_RCC_ETHMACTX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACTXEN)) -#define __HAL_RCC_ETHMACRX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACRXEN)) -#define __HAL_RCC_ETHMACPTP_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACPTPEN)) -#define __HAL_RCC_ETH_CLK_DISABLE() do { \ - __HAL_RCC_ETHMACTX_CLK_DISABLE(); \ - __HAL_RCC_ETHMACRX_CLK_DISABLE(); \ - __HAL_RCC_ETHMAC_CLK_DISABLE(); \ - } while(0U) -#endif /* STM32F407xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_GPIOI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN))== RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#if defined(STM32F407xx)|| defined(STM32F417xx) -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) != RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) != RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) != RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) != RESET) -#define __HAL_RCC_ETH_IS_CLK_ENABLED() (__HAL_RCC_ETHMAC_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_ENABLED()) -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) == RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) == RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) == RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) == RESET) -#define __HAL_RCC_ETH_IS_CLK_DISABLED() (__HAL_RCC_ETHMAC_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_DISABLED()) -#endif /* STM32F407xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_HASH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRYP_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_CRYPEN)) -#define __HAL_RCC_HASH_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_HASHEN)) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) != RESET) -#define __HAL_RCC_HASH_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) != RESET) - -#define __HAL_RCC_CRYP_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) == RESET) -#define __HAL_RCC_HASH_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) == RESET) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FSMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FSMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FSMCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FSMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) != RESET) -#define __HAL_RCC_FSMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) - /** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_HASHRST)) - -#define __HAL_RCC_CRYP_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_HASHRST)) -#endif /* STM32F415xx || STM32F417xx */ - -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FSMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_FSMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FSMCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET()(RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_HASHLPEN)) - -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_HASHLPEN)) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FSMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_FSMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FSMCLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------- STM32F401xE/STM32F401xC --------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -/** - * @} - */ -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB1_FORCE_RESET() (RCC->AHB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_AHB1_RELEASE_RESET() (RCC->AHB1RSTR = 0x00U) -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00U) -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00U) -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -/** - * @} - */ -#endif /* STM32F401xC || STM32F401xE*/ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F410xx -------------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_RNGEN)) != RESET) - -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB1) peripheral clock. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_RTCAPB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_RTCAPBEN)) -#define __HAL_RCC_LPTIM1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_LPTIM1EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) != RESET) -#define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) == RESET) -#define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_EXTIT_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#define __HAL_RCC_EXTIT_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_EXTITEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#define __HAL_RCC_EXTIT_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) != RESET) - -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#define __HAL_RCC_EXTIT_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_RNGRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() -#define __HAL_RCC_AHB2_RELEASE_RESET() -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() -#define __HAL_RCC_AHB3_RELEASE_RESET() -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_LPTIM1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_LPTIM1RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) - -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_LPTIM1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_LPTIM1RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_RNGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_RNGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_LPTIM1LPEN)) -#define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) - -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_LPTIM1LPEN)) -#define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_EXTITLPEN)) -/** - * @} - */ - -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F411xx -------------------------------*/ -#if defined(STM32F411xE) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEX_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -/** - * @} - */ -#endif /* STM32F411xE */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F446xx -----------------------------*/ -#if defined(STM32F446xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN))!= RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) == RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_FMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FMCEN)) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) - -#define __HAL_RCC_FMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) == RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPDIFRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPDIFRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPDIFRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CEC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_SPDIFRX_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPDIFRXEN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_CEC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CECEN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_SPDIFRX_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPDIFRXEN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_CEC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_SPDIFRX_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPDIFRXEN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_CEC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) -#define __HAL_RCC_SAI2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI2EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#define __HAL_RCC_SAI2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI2EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) -#define __HAL_RCC_SAI2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI2EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) - -#define __HAL_RCC_FMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_SPDIFRX_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPDIFRXRST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_CEC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CECRST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_SPDIFRX_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPDIFRXRST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_CEC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CECRST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SAI2_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI2RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SAI2_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI2RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) - -#define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_SPDIFRX_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPDIFRXLPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_CEC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CECLPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_SPDIFRX_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPDIFRXLPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_CEC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CECLPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SAI2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI2LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SAI2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI2LPEN)) -/** - * @} - */ - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*-------STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx-------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_AES_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_AESEN)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_AESEN)) != RESET) -#define __HAL_RCC_AES_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_AESEN)) == RESET) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_FSMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FSMCEN)) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) - -#define __HAL_RCC_FSMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) == RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_LPTIM1EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_RTCAPBEN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN3EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -#define __HAL_RCC_UART7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART7EN)) -#define __HAL_RCC_UART8_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART8EN)) -#endif /* STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN))!= RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN3EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) -#define __HAL_RCC_UART7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) != RESET) -#define __HAL_RCC_UART8_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN3EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -#define __HAL_RCC_UART7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) == RESET) -#define __HAL_RCC_UART8_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_UART9EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_UART9EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_UART10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_UART10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_EXTIT_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_UART9EN)) -#define __HAL_RCC_UART10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_UART10EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_EXTIT_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_EXTITEN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DFSDM1EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DFSDM2EN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART9EN)) != RESET) -#define __HAL_RCC_UART10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART10EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_EXTIT_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM1EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM2EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART9EN)) == RESET) -#define __HAL_RCC_UART10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART10EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_EXTIT_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM1EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM2EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) - -#if defined(STM32F423xx) -#define __HAL_RCC_AES_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_AESRST)) -#define __HAL_RCC_AES_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_AESRST)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FSMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) - -#define __HAL_RCC_FSMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Cx) -#define __HAL_RCC_AHB3_FORCE_RESET() -#define __HAL_RCC_AHB3_RELEASE_RESET() - -#define __HAL_RCC_FSMC_FORCE_RESET() -#define __HAL_RCC_QSPI_FORCE_RESET() - -#define __HAL_RCC_FSMC_RELEASE_RESET() -#define __HAL_RCC_QSPI_RELEASE_RESET() -#endif /* STM32F412Cx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_LPTIM1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN3RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART8RST)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_LPTIM1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN3RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART8RST)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_UART9RST)) -#define __HAL_RCC_UART10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_UART10RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DFSDM1RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DFSDM2RST)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_UART9RST)) -#define __HAL_RCC_UART10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_UART10RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DFSDM1RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DFSDM2RST)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_AESLPEN)) -#define __HAL_RCC_AES_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_AESLPEN)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) - -#define __HAL_RCC_FSMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_LPTIM1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN3LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART8LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_LPTIM1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN3LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART8LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_UART9LPEN)) -#define __HAL_RCC_UART10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_UART10LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DFSDM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DFSDM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_UART9LPEN)) -#define __HAL_RCC_UART10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_UART10LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DFSDM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DFSDM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------- PLL Configuration --------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the main PLL clock source, multiplication and division factors. - * @note This function must be used only when the main PLL is disabled. - * @param __RCC_PLLSource__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLN parameter correctly to ensure that the VCO - * output frequency is between 100 and 432 MHz. - * - * @param __PLLP__ specifies the division factor for main system clock (SYSCLK) - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLQ__ specifies the division factor for OTG FS, SDIO and RNG clocks - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note If the USB OTG FS is used in your application, you have to set the - * PLLQ parameter correctly to have 48 MHz clock for the USB. However, - * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work - * correctly. - * - * @param __PLLR__ PLL division factor for I2S, SAI, SYSTEM, SPDIFRX clocks. - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note This parameter is only available in STM32F446xx/STM32F469xx/STM32F479xx/ - STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/STM32F413xx/STM32F423xx devices. - * - */ -#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSource__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__,__PLLR__) \ - (RCC->PLLCFGR = ((__RCC_PLLSource__) | (__PLLM__) | \ - ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \ - ((((__PLLP__) >> 1U) -1U) << RCC_PLLCFGR_PLLP_Pos) | \ - ((__PLLQ__) << RCC_PLLCFGR_PLLQ_Pos) | \ - ((__PLLR__) << RCC_PLLCFGR_PLLR_Pos))) -#else -/** @brief Macro to configure the main PLL clock source, multiplication and division factors. - * @note This function must be used only when the main PLL is disabled. - * @param __RCC_PLLSource__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432 - * Except for STM32F411xE devices where Min_Data = 192. - * @note You have to set the PLLN parameter correctly to ensure that the VCO - * output frequency is between 100 and 432 MHz, Except for STM32F411xE devices - * where frequency is between 192 and 432 MHz. - * @param __PLLP__ specifies the division factor for main system clock (SYSCLK) - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLQ__ specifies the division factor for OTG FS, SDIO and RNG clocks - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note If the USB OTG FS is used in your application, you have to set the - * PLLQ parameter correctly to have 48 MHz clock for the USB. However, - * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work - * correctly. - * - */ -#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSource__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__) \ - (RCC->PLLCFGR = (0x20000000U | (__RCC_PLLSource__) | (__PLLM__)| \ - ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \ - ((((__PLLP__) >> 1U) -1U) << RCC_PLLCFGR_PLLP_Pos) | \ - ((__PLLQ__) << RCC_PLLCFGR_PLLQ_Pos))) - #endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------PLLI2S Configuration ---------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - -/** @brief Macros to enable or disable the PLLI2S. - * @note The PLLI2S is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLLI2S_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLI2SON_BB = ENABLE) -#define __HAL_RCC_PLLI2S_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLI2SON_BB = DISABLE) - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F412Cx */ -#if defined(STM32F446xx) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SP__ specifies division factor for SPDIFRX Clock. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * @note the PLLI2SP parameter is only available with STM32F446xx Devices - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - * @param __PLLI2SQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SP__, __PLLI2SQ__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((((__PLLI2SP__) >> 1U) -1U) << RCC_PLLI2SCFGR_PLLI2SP_Pos) |\ - ((__PLLI2SQ__) << RCC_PLLI2SCFGR_PLLI2SQ_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#elif defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - * @param __PLLI2SQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SQ__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SQ__) << RCC_PLLI2SCFGR_PLLI2SQ_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#else -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SN__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = (((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#endif /* STM32F446xx */ - -#if defined(STM32F411xE) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note The PLLI2SM parameter is only used with STM32F411xE/STM32F410xx Devices - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLLI2S jitter. - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 192 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 192 and Max_Data = 432 MHz. - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - */ -#define __HAL_RCC_PLLI2S_I2SCLK_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SR__) (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#endif /* STM32F411xE */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro used by the SAI HAL driver to configure the PLLI2S clock multiplication and division factors. - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API) - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * @param __PLLI2SQ__ specifies the division factor for SAI1 clock. - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note the PLLI2SQ parameter is only available with STM32F427xx/437xx/429xx/439xx/469xx/479xx - * Devices and can be configured using the __HAL_RCC_PLLI2S_PLLSAICLK_CONFIG() macro - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - */ -#define __HAL_RCC_PLLI2S_SAICLK_CONFIG(__PLLI2SN__, __PLLI2SQ__, __PLLI2SR__) (RCC->PLLI2SCFGR = ((__PLLI2SN__) << 6U) |\ - ((__PLLI2SQ__) << 24U) |\ - ((__PLLI2SR__) << 28U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------ PLLSAI Configuration ------------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macros to Enable or Disable the PLLISAI. - * @note The PLLSAI is only available with STM32F429x/439x Devices. - * @note The PLLSAI is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLLSAI_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLSAION_BB = ENABLE) -#define __HAL_RCC_PLLSAI_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLSAION_BB = DISABLE) - -#if defined(STM32F446xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIM__ specifies the division factor for PLLSAI VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLSAIM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * @note The PLLSAIM parameter is only used with STM32F446xx Devices - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIP__ specifies division factor for OTG FS, SDIO and RNG clocks. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * @note the PLLSAIP parameter is only available with STM32F446xx Devices - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note the PLLI2SR parameter is only available with STM32F427/437/429/439xx Devices - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIM__, __PLLSAIN__, __PLLSAIP__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = ((__PLLSAIM__) | \ - ((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) | \ - ((((__PLLSAIP__) >> 1U) -1U) << RCC_PLLSAICFGR_PLLSAIP_Pos) | \ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos))) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIP__ specifies division factor for SDIO and CLK48 clocks. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIN__, __PLLSAIP__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = (((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) |\ - ((((__PLLSAIP__) >> 1U) -1U) << RCC_PLLSAICFGR_PLLSAIP_Pos) |\ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos) |\ - ((__PLLSAIR__) << RCC_PLLSAICFGR_PLLSAIR_Pos))) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note the PLLI2SR parameter is only available with STM32F427/437/429/439xx Devices - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIN__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = (((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) | \ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos) | \ - ((__PLLSAIR__) << RCC_PLLSAICFGR_PLLSAIR_Pos))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- PLLSAI/PLLI2S Dividers Configuration -------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the SAI clock Divider coming from PLLI2S. - * @note This function must be called before enabling the PLLI2S. - * @param __PLLI2SDivR__ specifies the PLLI2S division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLI2SR) / __PLLI2SDivR__ - */ -#define __HAL_RCC_PLLI2S_PLLSAICLKDIVR_CONFIG(__PLLI2SDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR, (__PLLI2SDivR__)-1U)) - -/** @brief Macro to configure the SAI clock Divider coming from PLL. - * @param __PLLDivR__ specifies the PLL division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLR) / __PLLDivR__ - */ -#define __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(__PLLDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR, ((__PLLDivR__)-1U)<<8U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the SAI clock Divider coming from PLLI2S. - * @note This function must be called before enabling the PLLI2S. - * @param __PLLI2SDivQ__ specifies the PLLI2S division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLI2SQ) / __PLLI2SDivQ__ - */ -#define __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(__PLLI2SDivQ__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ, (__PLLI2SDivQ__)-1U)) - -/** @brief Macro to configure the SAI clock Divider coming from PLLSAI. - * @note This function must be called before enabling the PLLSAI. - * @param __PLLSAIDivQ__ specifies the PLLSAI division factor for SAI1 clock . - * This parameter must be a number between Min_Data = 1 and Max_Data = 32. - * SAI1 clock frequency = f(PLLSAIQ) / __PLLSAIDivQ__ - */ -#define __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(__PLLSAIDivQ__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ, ((__PLLSAIDivQ__)-1U)<<8U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the LTDC clock Divider coming from PLLSAI. - * - * @note The LTDC peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling the PLLSAI. - * @param __PLLSAIDivR__ specifies the PLLSAI division factor for LTDC clock . - * This parameter must be a number between Min_Data = 2 and Max_Data = 16. - * LTDC clock frequency = f(PLLSAIR) / __PLLSAIDivR__ - */ -#define __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(__PLLSAIDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR, (__PLLSAIDivR__))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------- Peripheral Clock selection -----------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) ||\ - defined(STM32F479xx) -/** @brief Macro to configure the I2S clock source (I2SCLK). - * @note This function must be called before enabling the I2S APB clock. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SCLKSOURCE_PLLI2S: PLLI2S clock used as I2S clock source. - * @arg RCC_I2SCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin - * used as I2S clock source. - */ -#define __HAL_RCC_I2S_CONFIG(__SOURCE__) (*(__IO uint32_t *) RCC_CFGR_I2SSRC_BB = (__SOURCE__)) - - -/** @brief Macro to get the I2S clock source (I2SCLK). - * @retval The clock source can be one of the following values: - * @arg @ref RCC_I2SCLKSOURCE_PLLI2S: PLLI2S clock used as I2S clock source. - * @arg @ref RCC_I2SCLKSOURCE_EXT External clock mapped on the I2S_CKIN pin - * used as I2S clock source - */ -#define __HAL_RCC_GET_I2S_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_I2SSRC))) -#endif /* STM32F40xxx || STM32F41xxx || STM32F42xxx || STM32F43xxx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** @brief Macro to configure SAI1BlockA clock source selection. - * @note The SAI peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used - * as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used - * as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_Ext: External clock mapped on the I2S_CKIN pin - * used as SAI1 Block A clock. - */ -#define __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC, (__SOURCE__))) - -/** @brief Macro to configure SAI1BlockB clock source selection. - * @note The SAI peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block B clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used - * as SAI1 Block B clock. - * @arg RCC_SAIBCLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used - * as SAI1 Block B clock. - * @arg RCC_SAIBCLKSOURCE_Ext: External clock mapped on the I2S_CKIN pin - * used as SAI1 Block B clock. - */ -#define __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC, (__SOURCE__))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) -/** @brief Macro to configure SAI1 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @note This function must be called before enabling PLL, PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI1 clock source. - * This parameter can be one of the following values: - * @arg RCC_SAI1CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 clock. - */ -#define __HAL_RCC_SAI1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1SRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAI1CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 clock. - */ -#define __HAL_RCC_GET_SAI1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1SRC)) - -/** @brief Macro to configure SAI2 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @note This function must be called before enabling PLL, PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI2 clock source. - * This parameter can be one of the following values: - * @arg RCC_SAI2CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL Source clock used as SAI2 clock. - */ -#define __HAL_RCC_SAI2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI2SRC, (__SOURCE__))) - -/** @brief Macro to Get SAI2 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAI2CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL Source clock used as SAI2 clock. - */ -#define __HAL_RCC_GET_SAI2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI2SRC)) - -/** @brief Macro to configure I2S APB1 clock source selection. - * @note This function must be called before enabling PLL, PLLI2S and the I2S clock. - * @param __SOURCE__ specifies the I2S APB1 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB1 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC)) - -/** @brief Macro to configure I2S APB2 clock source selection. - * @note This function must be called before enabling PLL, PLLI2S and the I2S clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB2 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC)) - -/** @brief Macro to configure the CEC clock. - * @param __SOURCE__ specifies the CEC clock source. - * This parameter can be one of the following values: - * @arg RCC_CECCLKSOURCE_HSI: HSI selected as CEC clock - * @arg RCC_CECCLKSOURCE_LSE: LSE selected as CEC clock - */ -#define __HAL_RCC_CEC_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CEC clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CECCLKSOURCE_HSI488: HSI selected as CEC clock - * @arg RCC_CECCLKSOURCE_LSE: LSE selected as CEC clock - */ -#define __HAL_RCC_GET_CEC_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL)) - -/** @brief Macro to configure the SPDIFRX clock. - * @param __SOURCE__ specifies the SPDIFRX clock source. - * This parameter can be one of the following values: - * @arg RCC_SPDIFRXCLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SPDIFRX clock. - * @arg RCC_SPDIFRXCLKSOURCE_PLLI2SP: PLLI2S VCO Output divided by PLLI2SP used as SPDIFRX clock. - */ -#define __HAL_RCC_SPDIFRX_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SPDIFRX clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SPDIFRXCLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SPDIFRX clock. - * @arg RCC_SPDIFRXCLKSOURCE_PLLI2SP: PLLI2S VCO Output divided by PLLI2SP used as SPDIFRX clock. - */ -#define __HAL_RCC_GET_SPDIFRX_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL)) - -/** @brief Macro to configure the DSI clock. - * @param __SOURCE__ specifies the DSI clock source. - * This parameter can be one of the following values: - * @arg RCC_DSICLKSOURCE_PLLR: PLLR output used as DSI clock. - * @arg RCC_DSICLKSOURCE_DSIPHY: DSI-PHY output used as DSI clock. - */ -#define __HAL_RCC_DSI_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the DSI clock. - * @retval The clock source can be one of the following values: - * @arg RCC_DSICLKSOURCE_PLLR: PLLR output used as DSI clock. - * @arg RCC_DSICLKSOURCE_DSIPHY: DSI-PHY output used as DSI clock. - */ -#define __HAL_RCC_GET_DSI_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL)) - -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) - /** @brief Macro to configure the DFSDM1 clock. - * @param __DFSDM1_CLKSOURCE__ specifies the DFSDM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM1CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM1CLKSOURCE_SYSCLK: System clock used as kernel clock. - * @retval None - */ -#define __HAL_RCC_DFSDM1_CONFIG(__DFSDM1_CLKSOURCE__) MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, (__DFSDM1_CLKSOURCE__)) - -/** @brief Macro to get the DFSDM1 clock source. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM1CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM1CLKSOURCE_SYSCLK: System clock used as kernel clock. - */ -#define __HAL_RCC_GET_DFSDM1_SOURCE() ((uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL))) - -/** @brief Macro to configure DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/ - STM32F413xx/STM32F423xx Devices. - * @param __SOURCE__ specifies the DFSDM1 Audio clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_DFSDM1AUDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1ASEL, (__SOURCE__))) - -/** @brief Macro to Get DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/ - STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_GET_DFSDM1AUDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1ASEL)) - -#if defined(STM32F413xx) || defined(STM32F423xx) - /** @brief Macro to configure the DFSDM2 clock. - * @param __DFSDM2_CLKSOURCE__ specifies the DFSDM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM2CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM2CLKSOURCE_SYSCLK: System clock used as kernel clock. - * @retval None - */ -#define __HAL_RCC_DFSDM2_CONFIG(__DFSDM2_CLKSOURCE__) MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, (__DFSDM2_CLKSOURCE__)) - -/** @brief Macro to get the DFSDM2 clock source. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM2CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM2CLKSOURCE_SYSCLK: System clock used as kernel clock. - */ -#define __HAL_RCC_GET_DFSDM2_SOURCE() ((uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL))) - -/** @brief Macro to configure DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @param __SOURCE__ specifies the DFSDM2 Audio clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_DFSDM2AUDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM2ASEL, (__SOURCE__))) - -/** @brief Macro to Get DFSDM2 Audio clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_GET_DFSDM2AUDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM2ASEL)) - -/** @brief Macro to configure SAI1BlockA clock source selection. - * @note The SAI peripheral is only available with STM32F413xx/STM32F423xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_EXT: External clock mapped on the I2S_CKIN pinused as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 BlockA clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_EXT: External clock mapped on the I2S_CKIN pinused as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_SAI_BLOCKA_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC)) - -/** @brief Macro to configure SAI1 BlockB clock source selection. - * @note The SAI peripheral is only available with STM32F413xx/STM32F423xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block B clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 BlockB clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_SAI_BLOCKB_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC)) - -/** @brief Macro to configure the LPTIM1 clock. - * @param __SOURCE__ specifies the LPTIM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_LPTIM1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the LPTIM1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_GET_LPTIM1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)) -#endif /* STM32F413xx || STM32F423xx */ - -/** @brief Macro to configure I2S APB1 clock source selection. - * @param __SOURCE__ specifies the I2S APB1 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB1 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC)) - -/** @brief Macro to configure I2S APB2 clock source selection. - * @param __SOURCE__ specifies the I2S APB2 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB2 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC)) - -/** @brief Macro to configure the PLL I2S clock source (PLLI2SCLK). - * @note This macro must be called before enabling the I2S APB clock. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLI2SCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - * @arg RCC_PLLI2SCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin - * used as I2S clock source. - */ -#define __HAL_RCC_PLL_I2S_CONFIG(__SOURCE__) (*(__IO uint32_t *) RCC_PLLI2SCFGR_PLLI2SSRC_BB = (__SOURCE__)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLI2SQ: PLLI2S VCO Output divided by PLLI2SQ used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLI2SQ: PLLI2S VCO Output divided by PLLI2SQ used as CLK48 clock - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL)) - -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @brief Macro to configure I2S clock source selection. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPBCLKSOURCE_PLLR: PLL VCO output clock divided by PLLR. - * @arg RCC_I2SAPBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPBCLKSOURCE_PLLSRC: HSI/HSE depends on PLLSRC. - */ -#define __HAL_RCC_I2S_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2SSRC, (__SOURCE__))) - -/** @brief Macro to Get I2S clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPBCLKSOURCE_PLLR: PLL VCO output clock divided by PLLR. - * @arg RCC_I2SAPBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPBCLKSOURCE_PLLSRC: HSI/HSE depends on PLLSRC. - */ -#define __HAL_RCC_GET_I2S_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2SSRC)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the LPTIM1 clock. - * @param __SOURCE__ specifies the LPTIM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK1 selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_LPTIM1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the LPTIM1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK1 selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_GET_LPTIM1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the Timers clocks prescalers - * @note This feature is only available with STM32F429x/439x Devices. - * @param __PRESC__ specifies the Timers clocks prescalers selection - * This parameter can be one of the following values: - * @arg RCC_TIMPRES_DESACTIVATED: The Timers kernels clocks prescaler is - * equal to HPRE if PPREx is corresponding to division by 1 or 2, - * else it is equal to [(HPRE * PPREx) / 2] if PPREx is corresponding to - * division by 4 or more. - * @arg RCC_TIMPRES_ACTIVATED: The Timers kernels clocks prescaler is - * equal to HPRE if PPREx is corresponding to division by 1, 2 or 4, - * else it is equal to [(HPRE * PPREx) / 4] if PPREx is corresponding - * to division by 8 or more. - */ -#define __HAL_RCC_TIMCLKPRESCALER(__PRESC__) (*(__IO uint32_t *) RCC_DCKCFGR_TIMPRE_BB = (__PRESC__)) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx) || STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE ||\ - STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx ||\ - STM32F423xx */ - -/*----------------------------------------------------------------------------*/ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Enable PLLSAI_RDY interrupt. - */ -#define __HAL_RCC_PLLSAI_ENABLE_IT() (RCC->CIR |= (RCC_CIR_PLLSAIRDYIE)) - -/** @brief Disable PLLSAI_RDY interrupt. - */ -#define __HAL_RCC_PLLSAI_DISABLE_IT() (RCC->CIR &= ~(RCC_CIR_PLLSAIRDYIE)) - -/** @brief Clear the PLLSAI RDY interrupt pending bits. - */ -#define __HAL_RCC_PLLSAI_CLEAR_IT() (RCC->CIR |= (RCC_CIR_PLLSAIRDYF)) - -/** @brief Check the PLLSAI RDY interrupt has occurred or not. - * @retval The new state (TRUE or FALSE). - */ -#define __HAL_RCC_PLLSAI_GET_IT() ((RCC->CIR & (RCC_CIR_PLLSAIRDYIE)) == (RCC_CIR_PLLSAIRDYIE)) - -/** @brief Check PLLSAI RDY flag is set or not. - * @retval The new state (TRUE or FALSE). - */ -#define __HAL_RCC_PLLSAI_GET_FLAG() ((RCC->CR & (RCC_CR_PLLSAIRDY)) == (RCC_CR_PLLSAIRDY)) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @brief Macros to enable or disable the RCC MCO1 feature. - */ -#define __HAL_RCC_MCO1_ENABLE() (*(__IO uint32_t *) RCC_CFGR_MCO1EN_BB = ENABLE) -#define __HAL_RCC_MCO1_DISABLE() (*(__IO uint32_t *) RCC_CFGR_MCO1EN_BB = DISABLE) - -/** @brief Macros to enable or disable the RCC MCO2 feature. - */ -#define __HAL_RCC_MCO2_ENABLE() (*(__IO uint32_t *) RCC_CFGR_MCO2EN_BB = ENABLE) -#define __HAL_RCC_MCO2_DISABLE() (*(__IO uint32_t *) RCC_CFGR_MCO2EN_BB = DISABLE) - -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup RCCEx_Exported_Functions - * @{ - */ - -/** @addtogroup RCCEx_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit); -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit); - -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk); - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -void HAL_RCCEx_SelectLSEMode(uint8_t Mode); -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -#if defined(RCC_PLLI2S_SUPPORT) -HAL_StatusTypeDef HAL_RCCEx_EnablePLLI2S(RCC_PLLI2SInitTypeDef *PLLI2SInit); -HAL_StatusTypeDef HAL_RCCEx_DisablePLLI2S(void); -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -HAL_StatusTypeDef HAL_RCCEx_EnablePLLSAI(RCC_PLLSAIInitTypeDef *PLLSAIInit); -HAL_StatusTypeDef HAL_RCCEx_DisablePLLSAI(void); -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RCCEx_Private_Constants RCCEx Private Constants - * @{ - */ - -/** @defgroup RCCEx_BitAddress_AliasRegion RCC BitAddress AliasRegion - * @brief RCC registers bit address in the alias region - * @{ - */ -/* --- CR Register ---*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/* Alias word address of PLLSAION bit */ -#define RCC_PLLSAION_BIT_NUMBER 0x1CU -#define RCC_CR_PLLSAION_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLSAION_BIT_NUMBER * 4U)) - -#define PLLSAI_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Alias word address of PLLI2SON bit */ -#define RCC_PLLI2SON_BIT_NUMBER 0x1AU -#define RCC_CR_PLLI2SON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLI2SON_BIT_NUMBER * 4U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/* --- DCKCFGR Register ---*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F401xC) ||\ - defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Alias word address of TIMPRE bit */ -#define RCC_DCKCFGR_OFFSET (RCC_OFFSET + 0x8CU) -#define RCC_TIMPRE_BIT_NUMBER 0x18U -#define RCC_DCKCFGR_TIMPRE_BB (PERIPH_BB_BASE + (RCC_DCKCFGR_OFFSET * 32U) + (RCC_TIMPRE_BIT_NUMBER * 4U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F410xx || STM32F401xC ||\ - STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/* --- CFGR Register ---*/ -#define RCC_CFGR_OFFSET (RCC_OFFSET + 0x08U) -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) -/* Alias word address of I2SSRC bit */ -#define RCC_I2SSRC_BIT_NUMBER 0x17U -#define RCC_CFGR_I2SSRC_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_I2SSRC_BIT_NUMBER * 4U)) - -#define PLLI2S_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -/* --- PLLI2SCFGR Register ---*/ -#define RCC_PLLI2SCFGR_OFFSET (RCC_OFFSET + 0x84U) -/* Alias word address of PLLI2SSRC bit */ -#define RCC_PLLI2SSRC_BIT_NUMBER 0x16U -#define RCC_PLLI2SCFGR_PLLI2SSRC_BB (PERIPH_BB_BASE + (RCC_PLLI2SCFGR_OFFSET * 32U) + (RCC_PLLI2SSRC_BIT_NUMBER * 4U)) - -#define PLLI2S_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx | STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/* Alias word address of MCO1EN bit */ -#define RCC_MCO1EN_BIT_NUMBER 0x8U -#define RCC_CFGR_MCO1EN_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_MCO1EN_BIT_NUMBER * 4U)) - -/* Alias word address of MCO2EN bit */ -#define RCC_MCO2EN_BIT_NUMBER 0x9U -#define RCC_CFGR_MCO2EN_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_MCO2EN_BIT_NUMBER * 4U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#define PLL_TIMEOUT_VALUE 2U /* 2 ms */ -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RCCEx_Private_Macros RCCEx Private Macros - * @{ - */ -/** @defgroup RCCEx_IS_RCC_Definitions RCC Private macros to check input parameters - * @{ - */ -#define IS_RCC_PLLN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) -#define IS_RCC_PLLI2SN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000007FU)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00000007U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000000FU)) -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000001FU)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F446xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00000FFFU)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x000001FFU)) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x000003FFU)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00007FFFU)) -#endif /* STM32F413xx || STM32F423xx */ - -#define IS_RCC_PLLI2SR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLSAIN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) - -#define IS_RCC_PLLSAIQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLSAIR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLSAI_DIVQ_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLI2S_DIVQ_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLSAI_DIVR_VALUE(VALUE) (((VALUE) == RCC_PLLSAIDIVR_2) ||\ - ((VALUE) == RCC_PLLSAIDIVR_4) ||\ - ((VALUE) == RCC_PLLSAIDIVR_8) ||\ - ((VALUE) == RCC_PLLSAIDIVR_16)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PLLI2SM_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 63U)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) -#endif /* STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_LPTIM1CLKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) - -#define IS_RCC_I2SAPBCLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPBCLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLSRC)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F446xx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLI2SP_VALUE(VALUE) (((VALUE) == RCC_PLLI2SP_DIV2) ||\ - ((VALUE) == RCC_PLLI2SP_DIV4) ||\ - ((VALUE) == RCC_PLLI2SP_DIV6) ||\ - ((VALUE) == RCC_PLLI2SP_DIV8)) - -#define IS_RCC_PLLSAIM_VALUE(VALUE) ((VALUE) <= 63U) - -#define IS_RCC_PLLSAIP_VALUE(VALUE) (((VALUE) == RCC_PLLSAIP_DIV2) ||\ - ((VALUE) == RCC_PLLSAIP_DIV4) ||\ - ((VALUE) == RCC_PLLSAIP_DIV6) ||\ - ((VALUE) == RCC_PLLSAIP_DIV8)) - -#define IS_RCC_SAI1CLKSOURCE(SOURCE) (((SOURCE) == RCC_SAI1CLKSOURCE_PLLSAI) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_EXT)) - -#define IS_RCC_SAI2CLKSOURCE(SOURCE) (((SOURCE) == RCC_SAI2CLKSOURCE_PLLSAI) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLSRC)) - -#define IS_RCC_I2SAPB1CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLSRC)) - - #define IS_RCC_I2SAPB2CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLSRC)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_CECCLKSOURCE(SOURCE) (((SOURCE) == RCC_CECCLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_CECCLKSOURCE_LSE)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLSAIP)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_SPDIFRXCLKSOURCE(SOURCE) (((SOURCE) == RCC_SPDIFRXCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SPDIFRXCLKSOURCE_PLLI2SP)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLSAIP_VALUE(VALUE) (((VALUE) == RCC_PLLSAIP_DIV2) ||\ - ((VALUE) == RCC_PLLSAIP_DIV4) ||\ - ((VALUE) == RCC_PLLSAIP_DIV6) ||\ - ((VALUE) == RCC_PLLSAIP_DIV8)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLSAIP)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_DSIBYTELANECLKSOURCE(SOURCE) (((SOURCE) == RCC_DSICLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_DSICLKSOURCE_DSIPHY)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLI2SCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_PLLI2SCLKSOURCE_PLLSRC) || \ - ((__SOURCE__) == RCC_PLLI2SCLKSOURCE_EXT)) - -#define IS_RCC_I2SAPB1CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLSRC)) - - #define IS_RCC_I2SAPB2CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLSRC)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLI2SQ)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM1CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM1CLKSOURCE_PCLK2) || \ - ((__SOURCE__) == RCC_DFSDM1CLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM1AUDIOCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM1AUDIOCLKSOURCE_I2S1) || \ - ((__SOURCE__) == RCC_DFSDM1AUDIOCLKSOURCE_I2S2)) - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_DFSDM2CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM2CLKSOURCE_PCLK2) || \ - ((__SOURCE__) == RCC_DFSDM2CLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM2AUDIOCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM2AUDIOCLKSOURCE_I2S1) || \ - ((__SOURCE__) == RCC_DFSDM2AUDIOCLKSOURCE_I2S2)) - -#define IS_RCC_LPTIM1CLKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) - -#define IS_RCC_SAIACLKSOURCE(SOURCE) (((SOURCE) == RCC_SAIACLKSOURCE_PLLI2SR) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_PLLSRC)) - -#define IS_RCC_SAIBCLKSOURCE(SOURCE) (((SOURCE) == RCC_SAIBCLKSOURCE_PLLI2SR) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_PLLSRC)) - -#define IS_RCC_PLL_DIVR_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLI2S_DIVR_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#endif /* STM32F413xx || STM32F423xx */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - -#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2SOURCE_SYSCLK) || ((SOURCE) == RCC_MCO2SOURCE_PLLI2SCLK)|| \ - ((SOURCE) == RCC_MCO2SOURCE_HSE) || ((SOURCE) == RCC_MCO2SOURCE_PLLCLK)) - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || \ - STM32F412Rx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2SOURCE_SYSCLK) || ((SOURCE) == RCC_MCO2SOURCE_I2SCLK)|| \ - ((SOURCE) == RCC_MCO2SOURCE_HSE) || ((SOURCE) == RCC_MCO2SOURCE_PLLCLK)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RCC_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rng.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rng.h deleted file mode 100644 index cde48592e35e879..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rng.h +++ /dev/null @@ -1,363 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rng.h - * @author MCD Application Team - * @brief Header file of RNG HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_RNG_H -#define STM32F4xx_HAL_RNG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (RNG) - -/** @defgroup RNG RNG - * @brief RNG HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup RNG_Exported_Types RNG Exported Types - * @{ - */ - -/** @defgroup RNG_Exported_Types_Group1 RNG Init Structure definition - * @{ - */ - -/** - * @} - */ - -/** @defgroup RNG_Exported_Types_Group2 RNG State Structure definition - * @{ - */ -typedef enum -{ - HAL_RNG_STATE_RESET = 0x00U, /*!< RNG not yet initialized or disabled */ - HAL_RNG_STATE_READY = 0x01U, /*!< RNG initialized and ready for use */ - HAL_RNG_STATE_BUSY = 0x02U, /*!< RNG internal process is ongoing */ - HAL_RNG_STATE_TIMEOUT = 0x03U, /*!< RNG timeout state */ - HAL_RNG_STATE_ERROR = 0x04U /*!< RNG error state */ - -} HAL_RNG_StateTypeDef; - -/** - * @} - */ - -/** @defgroup RNG_Exported_Types_Group3 RNG Handle Structure definition - * @{ - */ -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -typedef struct __RNG_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ -{ - RNG_TypeDef *Instance; /*!< Register base address */ - - HAL_LockTypeDef Lock; /*!< RNG locking object */ - - __IO HAL_RNG_StateTypeDef State; /*!< RNG communication state */ - - __IO uint32_t ErrorCode; /*!< RNG Error code */ - - uint32_t RandomNumber; /*!< Last Generated RNG Data */ - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) - void (* ReadyDataCallback)(struct __RNG_HandleTypeDef *hrng, uint32_t random32bit); /*!< RNG Data Ready Callback */ - void (* ErrorCallback)(struct __RNG_HandleTypeDef *hrng); /*!< RNG Error Callback */ - - void (* MspInitCallback)(struct __RNG_HandleTypeDef *hrng); /*!< RNG Msp Init callback */ - void (* MspDeInitCallback)(struct __RNG_HandleTypeDef *hrng); /*!< RNG Msp DeInit callback */ -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -} RNG_HandleTypeDef; - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -/** - * @brief HAL RNG Callback ID enumeration definition - */ -typedef enum -{ - HAL_RNG_ERROR_CB_ID = 0x00U, /*!< RNG Error Callback ID */ - - HAL_RNG_MSPINIT_CB_ID = 0x01U, /*!< RNG MspInit callback ID */ - HAL_RNG_MSPDEINIT_CB_ID = 0x02U /*!< RNG MspDeInit callback ID */ - -} HAL_RNG_CallbackIDTypeDef; - -/** - * @brief HAL RNG Callback pointer definition - */ -typedef void (*pRNG_CallbackTypeDef)(RNG_HandleTypeDef *hrng); /*!< pointer to a common RNG callback function */ -typedef void (*pRNG_ReadyDataCallbackTypeDef)(RNG_HandleTypeDef *hrng, uint32_t random32bit); /*!< pointer to an RNG Data Ready specific callback function */ - -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RNG_Exported_Constants RNG Exported Constants - * @{ - */ - -/** @defgroup RNG_Exported_Constants_Group1 RNG Interrupt definition - * @{ - */ -#define RNG_IT_DRDY RNG_SR_DRDY /*!< Data Ready interrupt */ -#define RNG_IT_CEI RNG_SR_CEIS /*!< Clock error interrupt */ -#define RNG_IT_SEI RNG_SR_SEIS /*!< Seed error interrupt */ -/** - * @} - */ - -/** @defgroup RNG_Exported_Constants_Group2 RNG Flag definition - * @{ - */ -#define RNG_FLAG_DRDY RNG_SR_DRDY /*!< Data ready */ -#define RNG_FLAG_CECS RNG_SR_CECS /*!< Clock error current status */ -#define RNG_FLAG_SECS RNG_SR_SECS /*!< Seed error current status */ -/** - * @} - */ - -/** @defgroup RNG_Error_Definition RNG Error Definition - * @{ - */ -#define HAL_RNG_ERROR_NONE 0x00000000U /*!< No error */ -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -#define HAL_RNG_ERROR_INVALID_CALLBACK 0x00000001U /*!< Invalid Callback error */ -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ -#define HAL_RNG_ERROR_TIMEOUT 0x00000002U /*!< Timeout error */ -#define HAL_RNG_ERROR_BUSY 0x00000004U /*!< Busy error */ -#define HAL_RNG_ERROR_SEED 0x00000008U /*!< Seed error */ -#define HAL_RNG_ERROR_CLOCK 0x00000010U /*!< Clock error */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup RNG_Exported_Macros RNG Exported Macros - * @{ - */ - -/** @brief Reset RNG handle state - * @param __HANDLE__ RNG Handle - * @retval None - */ -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -#define __HAL_RNG_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_RNG_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_RNG_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_RNG_STATE_RESET) -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -/** - * @brief Enables the RNG peripheral. - * @param __HANDLE__ RNG Handle - * @retval None - */ -#define __HAL_RNG_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= RNG_CR_RNGEN) - -/** - * @brief Disables the RNG peripheral. - * @param __HANDLE__ RNG Handle - * @retval None - */ -#define __HAL_RNG_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~RNG_CR_RNGEN) - -/** - * @brief Check the selected RNG flag status. - * @param __HANDLE__ RNG Handle - * @param __FLAG__ RNG flag - * This parameter can be one of the following values: - * @arg RNG_FLAG_DRDY: Data ready - * @arg RNG_FLAG_CECS: Clock error current status - * @arg RNG_FLAG_SECS: Seed error current status - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define __HAL_RNG_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** - * @brief Clears the selected RNG flag status. - * @param __HANDLE__ RNG handle - * @param __FLAG__ RNG flag to clear - * @note WARNING: This is a dummy macro for HAL code alignment, - * flags RNG_FLAG_DRDY, RNG_FLAG_CECS and RNG_FLAG_SECS are read-only. - * @retval None - */ -#define __HAL_RNG_CLEAR_FLAG(__HANDLE__, __FLAG__) /* dummy macro */ - -/** - * @brief Enables the RNG interrupts. - * @param __HANDLE__ RNG Handle - * @retval None - */ -#define __HAL_RNG_ENABLE_IT(__HANDLE__) ((__HANDLE__)->Instance->CR |= RNG_CR_IE) - -/** - * @brief Disables the RNG interrupts. - * @param __HANDLE__ RNG Handle - * @retval None - */ -#define __HAL_RNG_DISABLE_IT(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~RNG_CR_IE) - -/** - * @brief Checks whether the specified RNG interrupt has occurred or not. - * @param __HANDLE__ RNG Handle - * @param __INTERRUPT__ specifies the RNG interrupt status flag to check. - * This parameter can be one of the following values: - * @arg RNG_IT_DRDY: Data ready interrupt - * @arg RNG_IT_CEI: Clock error interrupt - * @arg RNG_IT_SEI: Seed error interrupt - * @retval The new state of __INTERRUPT__ (SET or RESET). - */ -#define __HAL_RNG_GET_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->SR & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @brief Clear the RNG interrupt status flags. - * @param __HANDLE__ RNG Handle - * @param __INTERRUPT__ specifies the RNG interrupt status flag to clear. - * This parameter can be one of the following values: - * @arg RNG_IT_CEI: Clock error interrupt - * @arg RNG_IT_SEI: Seed error interrupt - * @note RNG_IT_DRDY flag is read-only, reading RNG_DR register automatically clears RNG_IT_DRDY. - * @retval None - */ -#define __HAL_RNG_CLEAR_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->SR) = ~(__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RNG_Exported_Functions RNG Exported Functions - * @{ - */ - -/** @defgroup RNG_Exported_Functions_Group1 Initialization and configuration functions - * @{ - */ -HAL_StatusTypeDef HAL_RNG_Init(RNG_HandleTypeDef *hrng); -HAL_StatusTypeDef HAL_RNG_DeInit(RNG_HandleTypeDef *hrng); -void HAL_RNG_MspInit(RNG_HandleTypeDef *hrng); -void HAL_RNG_MspDeInit(RNG_HandleTypeDef *hrng); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_RNG_RegisterCallback(RNG_HandleTypeDef *hrng, HAL_RNG_CallbackIDTypeDef CallbackID, - pRNG_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_RNG_UnRegisterCallback(RNG_HandleTypeDef *hrng, HAL_RNG_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_RNG_RegisterReadyDataCallback(RNG_HandleTypeDef *hrng, pRNG_ReadyDataCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_RNG_UnRegisterReadyDataCallback(RNG_HandleTypeDef *hrng); -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup RNG_Exported_Functions_Group2 Peripheral Control functions - * @{ - */ -uint32_t HAL_RNG_GetRandomNumber(RNG_HandleTypeDef - *hrng); /* Obsolete, use HAL_RNG_GenerateRandomNumber() instead */ -uint32_t HAL_RNG_GetRandomNumber_IT(RNG_HandleTypeDef - *hrng); /* Obsolete, use HAL_RNG_GenerateRandomNumber_IT() instead */ -HAL_StatusTypeDef HAL_RNG_GenerateRandomNumber(RNG_HandleTypeDef *hrng, uint32_t *random32bit); -HAL_StatusTypeDef HAL_RNG_GenerateRandomNumber_IT(RNG_HandleTypeDef *hrng); -uint32_t HAL_RNG_ReadLastRandomNumber(RNG_HandleTypeDef *hrng); - -void HAL_RNG_IRQHandler(RNG_HandleTypeDef *hrng); -void HAL_RNG_ErrorCallback(RNG_HandleTypeDef *hrng); -void HAL_RNG_ReadyDataCallback(RNG_HandleTypeDef *hrng, uint32_t random32bit); - -/** - * @} - */ - -/** @defgroup RNG_Exported_Functions_Group3 Peripheral State functions - * @{ - */ -HAL_RNG_StateTypeDef HAL_RNG_GetState(RNG_HandleTypeDef *hrng); -uint32_t HAL_RNG_GetError(RNG_HandleTypeDef *hrng); -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RNG_Private_Macros RNG Private Macros - * @{ - */ -#define IS_RNG_IT(IT) (((IT) == RNG_IT_CEI) || \ - ((IT) == RNG_IT_SEI)) - -#define IS_RNG_FLAG(FLAG) (((FLAG) == RNG_FLAG_DRDY) || \ - ((FLAG) == RNG_FLAG_CECS) || \ - ((FLAG) == RNG_FLAG_SECS)) - -/** - * @} - */ - -/** - * @} - */ - -#endif /* RNG */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_RNG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h deleted file mode 100644 index 9afa8a14073a3e3..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h +++ /dev/null @@ -1,878 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rtc.h - * @author MCD Application Team - * @brief Header file of RTC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RTC_H -#define __STM32F4xx_HAL_RTC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RTC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RTC_Exported_Types RTC Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_RTC_STATE_RESET = 0x00U, /*!< RTC not yet initialized or disabled */ - HAL_RTC_STATE_READY = 0x01U, /*!< RTC initialized and ready for use */ - HAL_RTC_STATE_BUSY = 0x02U, /*!< RTC process is ongoing */ - HAL_RTC_STATE_TIMEOUT = 0x03U, /*!< RTC timeout state */ - HAL_RTC_STATE_ERROR = 0x04U /*!< RTC error state */ -}HAL_RTCStateTypeDef; - -/** - * @brief RTC Configuration Structure definition - */ -typedef struct -{ - uint32_t HourFormat; /*!< Specifies the RTC Hour Format. - This parameter can be a value of @ref RTC_Hour_Formats */ - - uint32_t AsynchPrediv; /*!< Specifies the RTC Asynchronous Predivider value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7F */ - - uint32_t SynchPrediv; /*!< Specifies the RTC Synchronous Predivider value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7FFFU */ - - uint32_t OutPut; /*!< Specifies which signal will be routed to the RTC output. - This parameter can be a value of @ref RTC_Output_selection_Definitions */ - - uint32_t OutPutPolarity; /*!< Specifies the polarity of the output signal. - This parameter can be a value of @ref RTC_Output_Polarity_Definitions */ - - uint32_t OutPutType; /*!< Specifies the RTC Output Pin mode. - This parameter can be a value of @ref RTC_Output_Type_ALARM_OUT */ -}RTC_InitTypeDef; - -/** - * @brief RTC Time structure definition - */ -typedef struct -{ - uint8_t Hours; /*!< Specifies the RTC Time Hour. - This parameter must be a number between Min_Data = 0 and Max_Data = 12 if the RTC_HourFormat_12 is selected. - This parameter must be a number between Min_Data = 0 and Max_Data = 23 if the RTC_HourFormat_24 is selected */ - - uint8_t Minutes; /*!< Specifies the RTC Time Minutes. - This parameter must be a number between Min_Data = 0 and Max_Data = 59 */ - - uint8_t Seconds; /*!< Specifies the RTC Time Seconds. - This parameter must be a number between Min_Data = 0 and Max_Data = 59 */ - - uint8_t TimeFormat; /*!< Specifies the RTC AM/PM Time. - This parameter can be a value of @ref RTC_AM_PM_Definitions */ - - uint32_t SubSeconds; /*!< Specifies the RTC_SSR RTC Sub Second register content. - This parameter corresponds to a time unit range between [0-1] Second - with [1 Sec / SecondFraction +1] granularity */ - - uint32_t SecondFraction; /*!< Specifies the range or granularity of Sub Second register content - corresponding to Synchronous pre-scaler factor value (PREDIV_S) - This parameter corresponds to a time unit range between [0-1] Second - with [1 Sec / SecondFraction +1] granularity. - This field will be used only by HAL_RTC_GetTime function */ - - uint32_t DayLightSaving; /*!< This interface is deprecated. To manage Daylight Saving Time, - please use HAL_RTC_DST_xxx functions */ - - uint32_t StoreOperation; /*!< This interface is deprecated. To manage Daylight Saving Time, - please use HAL_RTC_DST_xxx functions */ -}RTC_TimeTypeDef; - -/** - * @brief RTC Date structure definition - */ -typedef struct -{ - uint8_t WeekDay; /*!< Specifies the RTC Date WeekDay. - This parameter can be a value of @ref RTC_WeekDay_Definitions */ - - uint8_t Month; /*!< Specifies the RTC Date Month (in BCD format). - This parameter can be a value of @ref RTC_Month_Date_Definitions */ - - uint8_t Date; /*!< Specifies the RTC Date. - This parameter must be a number between Min_Data = 1 and Max_Data = 31 */ - - uint8_t Year; /*!< Specifies the RTC Date Year. - This parameter must be a number between Min_Data = 0 and Max_Data = 99 */ - -}RTC_DateTypeDef; - -/** - * @brief RTC Alarm structure definition - */ -typedef struct -{ - RTC_TimeTypeDef AlarmTime; /*!< Specifies the RTC Alarm Time members */ - - uint32_t AlarmMask; /*!< Specifies the RTC Alarm Masks. - This parameter can be a value of @ref RTC_AlarmMask_Definitions */ - - uint32_t AlarmSubSecondMask; /*!< Specifies the RTC Alarm SubSeconds Masks. - This parameter can be a value of @ref RTC_Alarm_Sub_Seconds_Masks_Definitions */ - - uint32_t AlarmDateWeekDaySel; /*!< Specifies the RTC Alarm is on Date or WeekDay. - This parameter can be a value of @ref RTC_AlarmDateWeekDay_Definitions */ - - uint8_t AlarmDateWeekDay; /*!< Specifies the RTC Alarm Date/WeekDay. - If the Alarm Date is selected, this parameter must be set to a value in the 1-31 range. - If the Alarm WeekDay is selected, this parameter can be a value of @ref RTC_WeekDay_Definitions */ - - uint32_t Alarm; /*!< Specifies the alarm . - This parameter can be a value of @ref RTC_Alarms_Definitions */ -}RTC_AlarmTypeDef; - -/** - * @brief RTC Handle Structure definition - */ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -typedef struct __RTC_HandleTypeDef -#else -typedef struct -#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ -{ - RTC_TypeDef *Instance; /*!< Register base address */ - - RTC_InitTypeDef Init; /*!< RTC required parameters */ - - HAL_LockTypeDef Lock; /*!< RTC locking object */ - - __IO HAL_RTCStateTypeDef State; /*!< Time communication state */ - -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - void (* AlarmAEventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Alarm A Event callback */ - - void (* AlarmBEventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Alarm B Event callback */ - - void (* TimeStampEventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC TimeStamp Event callback */ - - void (* WakeUpTimerEventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC WakeUpTimer Event callback */ - - void (* Tamper1EventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Tamper 1 Event callback */ - - void (* Tamper2EventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Tamper 2 Event callback */ - - void (* MspInitCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Msp Init callback */ - - void (* MspDeInitCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Msp DeInit callback */ - -#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ - -}RTC_HandleTypeDef; - -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL RTC Callback ID enumeration definition - */ -typedef enum -{ - HAL_RTC_ALARM_A_EVENT_CB_ID = 0x00u, /*!< RTC Alarm A Event Callback ID */ - HAL_RTC_ALARM_B_EVENT_CB_ID = 0x01u, /*!< RTC Alarm B Event Callback ID */ - HAL_RTC_TIMESTAMP_EVENT_CB_ID = 0x02u, /*!< RTC TimeStamp Event Callback ID */ - HAL_RTC_WAKEUPTIMER_EVENT_CB_ID = 0x03u, /*!< RTC Wake-Up Timer Event Callback ID */ - HAL_RTC_TAMPER1_EVENT_CB_ID = 0x04u, /*!< RTC Tamper 1 Callback ID */ - HAL_RTC_TAMPER2_EVENT_CB_ID = 0x05u, /*!< RTC Tamper 2 Callback ID */ - HAL_RTC_MSPINIT_CB_ID = 0x0Eu, /*!< RTC Msp Init callback ID */ - HAL_RTC_MSPDEINIT_CB_ID = 0x0Fu /*!< RTC Msp DeInit callback ID */ -}HAL_RTC_CallbackIDTypeDef; - -/** - * @brief HAL RTC Callback pointer definition - */ -typedef void (*pRTC_CallbackTypeDef)(RTC_HandleTypeDef * hrtc); /*!< pointer to an RTC callback function */ -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RTC_Exported_Constants RTC Exported Constants - * @{ - */ - -/** @defgroup RTC_Hour_Formats RTC Hour Formats - * @{ - */ -#define RTC_HOURFORMAT_24 0x00000000U -#define RTC_HOURFORMAT_12 0x00000040U -/** - * @} - */ - -/** @defgroup RTC_Output_selection_Definitions RTC Output Selection Definitions - * @{ - */ -#define RTC_OUTPUT_DISABLE 0x00000000U -#define RTC_OUTPUT_ALARMA 0x00200000U -#define RTC_OUTPUT_ALARMB 0x00400000U -#define RTC_OUTPUT_WAKEUP 0x00600000U -/** - * @} - */ - -/** @defgroup RTC_Output_Polarity_Definitions RTC Output Polarity Definitions - * @{ - */ -#define RTC_OUTPUT_POLARITY_HIGH 0x00000000U -#define RTC_OUTPUT_POLARITY_LOW 0x00100000U -/** - * @} - */ - -/** @defgroup RTC_Output_Type_ALARM_OUT RTC Output Type ALARM OUT - * @{ - */ -#define RTC_OUTPUT_TYPE_OPENDRAIN 0x00000000U -#define RTC_OUTPUT_TYPE_PUSHPULL 0x00040000U -/** - * @} - */ - -/** @defgroup RTC_AM_PM_Definitions RTC AM PM Definitions - * @{ - */ -#define RTC_HOURFORMAT12_AM ((uint8_t)0x00) -#define RTC_HOURFORMAT12_PM ((uint8_t)0x40) -/** - * @} - */ - -/** @defgroup RTC_DayLightSaving_Definitions RTC DayLight Saving Definitions - * @{ - */ -#define RTC_DAYLIGHTSAVING_SUB1H 0x00020000U -#define RTC_DAYLIGHTSAVING_ADD1H 0x00010000U -#define RTC_DAYLIGHTSAVING_NONE 0x00000000U -/** - * @} - */ - -/** @defgroup RTC_StoreOperation_Definitions RTC Store Operation Definitions - * @{ - */ -#define RTC_STOREOPERATION_RESET 0x00000000U -#define RTC_STOREOPERATION_SET 0x00040000U -/** - * @} - */ - -/** @defgroup RTC_Input_parameter_format_definitions RTC Input Parameter Format Definitions - * @{ - */ -#define RTC_FORMAT_BIN 0x00000000U -#define RTC_FORMAT_BCD 0x00000001U -/** - * @} - */ - -/** @defgroup RTC_Month_Date_Definitions RTC Month Date Definitions - * @{ - */ -/* Coded in BCD format */ -#define RTC_MONTH_JANUARY ((uint8_t)0x01) -#define RTC_MONTH_FEBRUARY ((uint8_t)0x02) -#define RTC_MONTH_MARCH ((uint8_t)0x03) -#define RTC_MONTH_APRIL ((uint8_t)0x04) -#define RTC_MONTH_MAY ((uint8_t)0x05) -#define RTC_MONTH_JUNE ((uint8_t)0x06) -#define RTC_MONTH_JULY ((uint8_t)0x07) -#define RTC_MONTH_AUGUST ((uint8_t)0x08) -#define RTC_MONTH_SEPTEMBER ((uint8_t)0x09) -#define RTC_MONTH_OCTOBER ((uint8_t)0x10) -#define RTC_MONTH_NOVEMBER ((uint8_t)0x11) -#define RTC_MONTH_DECEMBER ((uint8_t)0x12) -/** - * @} - */ - -/** @defgroup RTC_WeekDay_Definitions RTC WeekDay Definitions - * @{ - */ -#define RTC_WEEKDAY_MONDAY ((uint8_t)0x01) -#define RTC_WEEKDAY_TUESDAY ((uint8_t)0x02) -#define RTC_WEEKDAY_WEDNESDAY ((uint8_t)0x03) -#define RTC_WEEKDAY_THURSDAY ((uint8_t)0x04) -#define RTC_WEEKDAY_FRIDAY ((uint8_t)0x05) -#define RTC_WEEKDAY_SATURDAY ((uint8_t)0x06) -#define RTC_WEEKDAY_SUNDAY ((uint8_t)0x07) -/** - * @} - */ - -/** @defgroup RTC_AlarmDateWeekDay_Definitions RTC Alarm Date WeekDay Definitions - * @{ - */ -#define RTC_ALARMDATEWEEKDAYSEL_DATE 0x00000000U -#define RTC_ALARMDATEWEEKDAYSEL_WEEKDAY 0x40000000U -/** - * @} - */ - -/** @defgroup RTC_AlarmMask_Definitions RTC Alarm Mask Definitions - * @{ - */ -#define RTC_ALARMMASK_NONE 0x00000000U -#define RTC_ALARMMASK_DATEWEEKDAY RTC_ALRMAR_MSK4 -#define RTC_ALARMMASK_HOURS RTC_ALRMAR_MSK3 -#define RTC_ALARMMASK_MINUTES RTC_ALRMAR_MSK2 -#define RTC_ALARMMASK_SECONDS RTC_ALRMAR_MSK1 -#define RTC_ALARMMASK_ALL 0x80808080U -/** - * @} - */ - -/** @defgroup RTC_Alarms_Definitions RTC Alarms Definitions - * @{ - */ -#define RTC_ALARM_A RTC_CR_ALRAE -#define RTC_ALARM_B RTC_CR_ALRBE -/** - * @} - */ - -/** @defgroup RTC_Alarm_Sub_Seconds_Masks_Definitions RTC Alarm Sub Seconds Masks Definitions - * @{ - */ -#define RTC_ALARMSUBSECONDMASK_ALL 0x00000000U /*!< All Alarm SS fields are masked. - There is no comparison on sub seconds - for Alarm */ -#define RTC_ALARMSUBSECONDMASK_SS14_1 0x01000000U /*!< SS[14:1] are don't care in Alarm - comparison. Only SS[0] is compared. */ -#define RTC_ALARMSUBSECONDMASK_SS14_2 0x02000000U /*!< SS[14:2] are don't care in Alarm - comparison. Only SS[1:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_3 0x03000000U /*!< SS[14:3] are don't care in Alarm - comparison. Only SS[2:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_4 0x04000000U /*!< SS[14:4] are don't care in Alarm - comparison. Only SS[3:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_5 0x05000000U /*!< SS[14:5] are don't care in Alarm - comparison. Only SS[4:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_6 0x06000000U /*!< SS[14:6] are don't care in Alarm - comparison. Only SS[5:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_7 0x07000000U /*!< SS[14:7] are don't care in Alarm - comparison. Only SS[6:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_8 0x08000000U /*!< SS[14:8] are don't care in Alarm - comparison. Only SS[7:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_9 0x09000000U /*!< SS[14:9] are don't care in Alarm - comparison. Only SS[8:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_10 0x0A000000U /*!< SS[14:10] are don't care in Alarm - comparison. Only SS[9:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_11 0x0B000000U /*!< SS[14:11] are don't care in Alarm - comparison. Only SS[10:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_12 0x0C000000U /*!< SS[14:12] are don't care in Alarm - comparison.Only SS[11:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_13 0x0D000000U /*!< SS[14:13] are don't care in Alarm - comparison. Only SS[12:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14 0x0E000000U /*!< SS[14] is don't care in Alarm - comparison.Only SS[13:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_NONE 0x0F000000U /*!< SS[14:0] are compared and must match - to activate alarm. */ -/** - * @} - */ - -/** @defgroup RTC_Interrupts_Definitions RTC Interrupts Definitions - * @{ - */ -#define RTC_IT_TS 0x00008000U -#define RTC_IT_WUT 0x00004000U -#define RTC_IT_ALRB 0x00002000U -#define RTC_IT_ALRA 0x00001000U -#define RTC_IT_TAMP 0x00000004U /* Used only to Enable the Tamper Interrupt */ -#define RTC_IT_TAMP1 0x00020000U -#define RTC_IT_TAMP2 0x00040000U -/** - * @} - */ - -/** @defgroup RTC_Flags_Definitions RTC Flags Definitions - * @{ - */ -#define RTC_FLAG_RECALPF 0x00010000U -#define RTC_FLAG_TAMP2F 0x00004000U -#define RTC_FLAG_TAMP1F 0x00002000U -#define RTC_FLAG_TSOVF 0x00001000U -#define RTC_FLAG_TSF 0x00000800U -#define RTC_FLAG_WUTF 0x00000400U -#define RTC_FLAG_ALRBF 0x00000200U -#define RTC_FLAG_ALRAF 0x00000100U -#define RTC_FLAG_INITF 0x00000040U -#define RTC_FLAG_RSF 0x00000020U -#define RTC_FLAG_INITS 0x00000010U -#define RTC_FLAG_SHPF 0x00000008U -#define RTC_FLAG_WUTWF 0x00000004U -#define RTC_FLAG_ALRBWF 0x00000002U -#define RTC_FLAG_ALRAWF 0x00000001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RTC_Exported_Macros RTC Exported Macros - * @{ - */ - -/** @brief Reset RTC handle state - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -#define __HAL_RTC_RESET_HANDLE_STATE(__HANDLE__) do{\ - (__HANDLE__)->State = HAL_RTC_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL;\ - (__HANDLE__)->MspDeInitCallback = NULL;\ - }while(0u) -#else -#define __HAL_RTC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_RTC_STATE_RESET) -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - -/** - * @brief Disable the write protection for RTC registers. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_WRITEPROTECTION_DISABLE(__HANDLE__) \ - do{ \ - (__HANDLE__)->Instance->WPR = 0xCAU; \ - (__HANDLE__)->Instance->WPR = 0x53U; \ - } while(0U) - -/** - * @brief Enable the write protection for RTC registers. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_WRITEPROTECTION_ENABLE(__HANDLE__) \ - do{ \ - (__HANDLE__)->Instance->WPR = 0xFFU; \ - } while(0U) - -/** - * @brief Enable the RTC ALARMA peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_ALARMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_ALRAE)) - -/** - * @brief Disable the RTC ALARMA peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_ALARMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_ALRAE)) - -/** - * @brief Enable the RTC ALARMB peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_ALARMB_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_ALRBE)) - -/** - * @brief Disable the RTC ALARMB peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_ALARMB_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_ALRBE)) - -/** - * @brief Enable the RTC Alarm interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Alarm interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_ALRB: Alarm B interrupt - * @retval None - */ -#define __HAL_RTC_ALARM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the RTC Alarm interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Alarm interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_ALRB: Alarm B interrupt - * @retval None - */ -#define __HAL_RTC_ALARM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified RTC Alarm interrupt has occurred or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Alarm interrupt to check. - * This parameter can be: - * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_ALRB: Alarm B interrupt - * @retval None - */ -#define __HAL_RTC_ALARM_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->ISR)& ((__INTERRUPT__)>> 4U)) != RESET)? SET : RESET) - -/** - * @brief Get the selected RTC Alarm's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Alarm Flag to check. - * This parameter can be: - * @arg RTC_FLAG_ALRAF - * @arg RTC_FLAG_ALRBF - * @arg RTC_FLAG_ALRAWF - * @arg RTC_FLAG_ALRBWF - * @retval None - */ -#define __HAL_RTC_ALARM_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) - -/** - * @brief Clear the RTC Alarm's pending flags. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Alarm Flag sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_FLAG_ALRAF - * @arg RTC_FLAG_ALRBF - * @retval None - */ -#define __HAL_RTC_ALARM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~((__FLAG__) | RTC_ISR_INIT)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT)) - - -/** - * @brief Check whether the specified RTC Alarm interrupt has been enabled or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Alarm interrupt sources to check. - * This parameter can be: - * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_ALRB: Alarm B interrupt - * @retval None - */ -#define __HAL_RTC_ALARM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->CR) & (__INTERRUPT__)) != RESET) ? SET : RESET) - -/** - * @brief Enable interrupt on the RTC Alarm associated Exti line. - * @retval None - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_IT() (EXTI->IMR |= RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Disable interrupt on the RTC Alarm associated Exti line. - * @retval None - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_IT() (EXTI->IMR &= ~(RTC_EXTI_LINE_ALARM_EVENT)) - -/** - * @brief Enable event on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_EVENT() (EXTI->EMR |= RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Disable event on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(RTC_EXTI_LINE_ALARM_EVENT)) - -/** - * @brief Enable falling edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_FALLING_EDGE() (EXTI->FTSR |= RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Disable falling edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_FALLING_EDGE() (EXTI->FTSR &= ~(RTC_EXTI_LINE_ALARM_EVENT)) - -/** - * @brief Enable rising edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_RISING_EDGE() (EXTI->RTSR |= RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Disable rising edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_RISING_EDGE() (EXTI->RTSR &= ~(RTC_EXTI_LINE_ALARM_EVENT)) - -/** - * @brief Enable rising & falling edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_RISING_FALLING_EDGE() do { __HAL_RTC_ALARM_EXTI_ENABLE_RISING_EDGE(); \ - __HAL_RTC_ALARM_EXTI_ENABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Disable rising & falling edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_RISING_FALLING_EDGE() do { __HAL_RTC_ALARM_EXTI_DISABLE_RISING_EDGE();\ - __HAL_RTC_ALARM_EXTI_DISABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Check whether the RTC Alarm associated Exti line interrupt flag is set or not. - * @retval Line Status. - */ -#define __HAL_RTC_ALARM_EXTI_GET_FLAG() (EXTI->PR & RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Clear the RTC Alarm associated Exti line flag. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() (EXTI->PR = RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Generate a Software interrupt on RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() (EXTI->SWIER |= RTC_EXTI_LINE_ALARM_EVENT) -/** - * @} - */ - -/* Include RTC HAL Extension module */ -#include "stm32f4xx_hal_rtc_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup RTC_Exported_Functions - * @{ - */ - -/** @addtogroup RTC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions ****************************/ -HAL_StatusTypeDef HAL_RTC_Init(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTC_DeInit(RTC_HandleTypeDef *hrtc); -void HAL_RTC_MspInit(RTC_HandleTypeDef *hrtc); -void HAL_RTC_MspDeInit(RTC_HandleTypeDef *hrtc); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_RTC_RegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID, pRTC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_RTC_UnRegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup RTC_Exported_Functions_Group2 - * @{ - */ -/* RTC Time and Date functions ************************************************/ -HAL_StatusTypeDef HAL_RTC_SetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_GetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_SetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_GetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format); -void HAL_RTC_DST_Add1Hour(RTC_HandleTypeDef *hrtc); -void HAL_RTC_DST_Sub1Hour(RTC_HandleTypeDef *hrtc); -void HAL_RTC_DST_SetStoreOperation(RTC_HandleTypeDef *hrtc); -void HAL_RTC_DST_ClearStoreOperation(RTC_HandleTypeDef *hrtc); -uint32_t HAL_RTC_DST_ReadStoreOperation(RTC_HandleTypeDef *hrtc); -/** - * @} - */ - -/** @addtogroup RTC_Exported_Functions_Group3 - * @{ - */ -/* RTC Alarm functions ********************************************************/ -HAL_StatusTypeDef HAL_RTC_SetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_SetAlarm_IT(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_DeactivateAlarm(RTC_HandleTypeDef *hrtc, uint32_t Alarm); -HAL_StatusTypeDef HAL_RTC_GetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Alarm, uint32_t Format); -void HAL_RTC_AlarmIRQHandler(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTC_PollForAlarmAEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc); -/** - * @} - */ - -/** @addtogroup RTC_Exported_Functions_Group4 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -HAL_StatusTypeDef HAL_RTC_WaitForSynchro(RTC_HandleTypeDef* hrtc); -/** - * @} - */ - -/** @addtogroup RTC_Exported_Functions_Group5 - * @{ - */ -/* Peripheral State functions *************************************************/ -HAL_RTCStateTypeDef HAL_RTC_GetState(RTC_HandleTypeDef *hrtc); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RTC_Private_Constants RTC Private Constants - * @{ - */ -/* Masks Definition */ -#define RTC_TR_RESERVED_MASK 0x007F7F7FU -#define RTC_DR_RESERVED_MASK 0x00FFFF3FU -#define RTC_INIT_MASK 0xFFFFFFFFU -#define RTC_RSF_MASK 0xFFFFFF5FU -#define RTC_FLAGS_MASK ((uint32_t)(RTC_FLAG_TSOVF | RTC_FLAG_TSF | RTC_FLAG_WUTF | \ - RTC_FLAG_ALRBF | RTC_FLAG_ALRAF | RTC_FLAG_INITF | \ - RTC_FLAG_RSF | RTC_FLAG_INITS | RTC_FLAG_WUTWF | \ - RTC_FLAG_ALRBWF | RTC_FLAG_ALRAWF | RTC_FLAG_TAMP1F | \ - RTC_FLAG_RECALPF | RTC_FLAG_SHPF)) - -#define RTC_TIMEOUT_VALUE 1000 - -#define RTC_EXTI_LINE_ALARM_EVENT ((uint32_t)EXTI_IMR_MR17) /*!< External interrupt line 17 Connected to the RTC Alarm event */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RTC_Private_Macros RTC Private Macros - * @{ - */ - -/** @defgroup RTC_IS_RTC_Definitions RTC Private macros to check input parameters - * @{ - */ -#define IS_RTC_HOUR_FORMAT(FORMAT) (((FORMAT) == RTC_HOURFORMAT_12) || \ - ((FORMAT) == RTC_HOURFORMAT_24)) -#define IS_RTC_OUTPUT(OUTPUT) (((OUTPUT) == RTC_OUTPUT_DISABLE) || \ - ((OUTPUT) == RTC_OUTPUT_ALARMA) || \ - ((OUTPUT) == RTC_OUTPUT_ALARMB) || \ - ((OUTPUT) == RTC_OUTPUT_WAKEUP)) -#define IS_RTC_OUTPUT_POL(POL) (((POL) == RTC_OUTPUT_POLARITY_HIGH) || \ - ((POL) == RTC_OUTPUT_POLARITY_LOW)) -#define IS_RTC_OUTPUT_TYPE(TYPE) (((TYPE) == RTC_OUTPUT_TYPE_OPENDRAIN) || \ - ((TYPE) == RTC_OUTPUT_TYPE_PUSHPULL)) -#define IS_RTC_HOUR12(HOUR) (((HOUR) > 0U) && ((HOUR) <= 12U)) -#define IS_RTC_HOUR24(HOUR) ((HOUR) <= 23U) -#define IS_RTC_ASYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x7FU) -#define IS_RTC_SYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x7FFFU) -#define IS_RTC_MINUTES(MINUTES) ((MINUTES) <= 59U) -#define IS_RTC_SECONDS(SECONDS) ((SECONDS) <= 59U) - -#define IS_RTC_HOURFORMAT12(PM) (((PM) == RTC_HOURFORMAT12_AM) || ((PM) == RTC_HOURFORMAT12_PM)) -#define IS_RTC_DAYLIGHT_SAVING(SAVE) (((SAVE) == RTC_DAYLIGHTSAVING_SUB1H) || \ - ((SAVE) == RTC_DAYLIGHTSAVING_ADD1H) || \ - ((SAVE) == RTC_DAYLIGHTSAVING_NONE)) -#define IS_RTC_STORE_OPERATION(OPERATION) (((OPERATION) == RTC_STOREOPERATION_RESET) || \ - ((OPERATION) == RTC_STOREOPERATION_SET)) -#define IS_RTC_FORMAT(FORMAT) (((FORMAT) == RTC_FORMAT_BIN) || ((FORMAT) == RTC_FORMAT_BCD)) -#define IS_RTC_YEAR(YEAR) ((YEAR) <= 99U) -#define IS_RTC_MONTH(MONTH) (((MONTH) >= 1U) && ((MONTH) <= 12U)) -#define IS_RTC_DATE(DATE) (((DATE) >= 1U) && ((DATE) <= 31U)) -#define IS_RTC_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_WEEKDAY_MONDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_TUESDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_WEDNESDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_THURSDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_FRIDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_SATURDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_SUNDAY)) -#define IS_RTC_ALARM_DATE_WEEKDAY_DATE(DATE) (((DATE) > 0U) && ((DATE) <= 31U)) -#define IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_WEEKDAY_MONDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_TUESDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_WEDNESDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_THURSDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_FRIDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_SATURDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_SUNDAY)) -#define IS_RTC_ALARM_DATE_WEEKDAY_SEL(SEL) (((SEL) == RTC_ALARMDATEWEEKDAYSEL_DATE) || \ - ((SEL) == RTC_ALARMDATEWEEKDAYSEL_WEEKDAY)) -#define IS_RTC_ALARM_MASK(MASK) (((MASK) & 0x7F7F7F7FU) == (uint32_t)RESET) -#define IS_RTC_ALARM(ALARM) (((ALARM) == RTC_ALARM_A) || ((ALARM) == RTC_ALARM_B)) -#define IS_RTC_ALARM_SUB_SECOND_VALUE(VALUE) ((VALUE) <= 0x00007FFFU) - -#define IS_RTC_ALARM_SUB_SECOND_MASK(MASK) (((MASK) == RTC_ALARMSUBSECONDMASK_ALL) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_1) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_2) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_3) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_4) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_5) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_6) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_7) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_8) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_9) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_10) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_11) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_12) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_13) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_NONE)) -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup RTC_Private_Functions RTC Private Functions - * @{ - */ -HAL_StatusTypeDef RTC_EnterInitMode(RTC_HandleTypeDef* hrtc); -uint8_t RTC_ByteToBcd2(uint8_t Value); -uint8_t RTC_Bcd2ToByte(uint8_t Value); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RTC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h deleted file mode 100644 index 76859eeb26307fe..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h +++ /dev/null @@ -1,1011 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rtc_ex.h - * @author MCD Application Team - * @brief Header file of RTC HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RTC_EX_H -#define __STM32F4xx_HAL_RTC_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RTCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RTCEx_Exported_Types RTCEx Exported Types - * @{ - */ - -/** - * @brief RTC Tamper structure definition - */ -typedef struct -{ - uint32_t Tamper; /*!< Specifies the Tamper Pin. - This parameter can be a value of @ref RTCEx_Tamper_Pins_Definitions */ - - uint32_t PinSelection; /*!< Specifies the Tamper Pin. - This parameter can be a value of @ref RTCEx_Tamper_Pins_Selection */ - - uint32_t Trigger; /*!< Specifies the Tamper Trigger. - This parameter can be a value of @ref RTCEx_Tamper_Trigger_Definitions */ - - uint32_t Filter; /*!< Specifies the RTC Filter Tamper. - This parameter can be a value of @ref RTCEx_Tamper_Filter_Definitions */ - - uint32_t SamplingFrequency; /*!< Specifies the sampling frequency. - This parameter can be a value of @ref RTCEx_Tamper_Sampling_Frequencies_Definitions */ - - uint32_t PrechargeDuration; /*!< Specifies the Precharge Duration . - This parameter can be a value of @ref RTCEx_Tamper_Pin_Precharge_Duration_Definitions */ - - uint32_t TamperPullUp; /*!< Specifies the Tamper PullUp . - This parameter can be a value of @ref RTCEx_Tamper_Pull_UP_Definitions */ - - uint32_t TimeStampOnTamperDetection; /*!< Specifies the TimeStampOnTamperDetection. - This parameter can be a value of @ref RTCEx_Tamper_TimeStampOnTamperDetection_Definitions */ -}RTC_TamperTypeDef; -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RTCEx_Exported_Constants RTCEx Exported Constants - * @{ - */ - -/** @defgroup RTCEx_Backup_Registers_Definitions RTC Backup Registers Definitions - * @{ - */ -#define RTC_BKP_DR0 0x00000000U -#define RTC_BKP_DR1 0x00000001U -#define RTC_BKP_DR2 0x00000002U -#define RTC_BKP_DR3 0x00000003U -#define RTC_BKP_DR4 0x00000004U -#define RTC_BKP_DR5 0x00000005U -#define RTC_BKP_DR6 0x00000006U -#define RTC_BKP_DR7 0x00000007U -#define RTC_BKP_DR8 0x00000008U -#define RTC_BKP_DR9 0x00000009U -#define RTC_BKP_DR10 0x0000000AU -#define RTC_BKP_DR11 0x0000000BU -#define RTC_BKP_DR12 0x0000000CU -#define RTC_BKP_DR13 0x0000000DU -#define RTC_BKP_DR14 0x0000000EU -#define RTC_BKP_DR15 0x0000000FU -#define RTC_BKP_DR16 0x00000010U -#define RTC_BKP_DR17 0x00000011U -#define RTC_BKP_DR18 0x00000012U -#define RTC_BKP_DR19 0x00000013U -/** - * @} - */ - -/** @defgroup RTCEx_Time_Stamp_Edges_definitions RTC TimeStamp Edges Definitions - * @{ - */ -#define RTC_TIMESTAMPEDGE_RISING 0x00000000U -#define RTC_TIMESTAMPEDGE_FALLING 0x00000008U -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Pins_Definitions RTC Tamper Pins Definitions - * @{ - */ -#define RTC_TAMPER_1 RTC_TAFCR_TAMP1E - -#if !defined(STM32F412Zx) && !defined(STM32F412Vx) && !defined(STM32F412Rx) && !defined(STM32F412Cx) && !defined(STM32F413xx) && !defined(STM32F423xx) -#define RTC_TAMPER_2 RTC_TAFCR_TAMP2E -#endif -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Pins_Selection RTC tamper Pins Selection - * @{ - */ - -#define RTC_TAMPERPIN_DEFAULT 0x00000000U - -#if !defined(STM32F412Zx) && !defined(STM32F412Vx) && !defined(STM32F412Rx) && !defined(STM32F412Cx) && !defined(STM32F413xx) && !defined(STM32F423xx) -#define RTC_TAMPERPIN_POS1 0x00010000U -#endif -/** - * @} - */ - -/** @defgroup RTCEx_TimeStamp_Pin_Selection RTC TimeStamp Pins Selection - * @{ - */ -#define RTC_TIMESTAMPPIN_DEFAULT 0x00000000U - -#if !defined(STM32F412Zx) && !defined(STM32F412Vx) && !defined(STM32F412Rx) && !defined(STM32F412Cx) && !defined(STM32F413xx) && !defined(STM32F423xx) -#define RTC_TIMESTAMPPIN_POS1 0x00020000U -#endif -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Trigger_Definitions RTC Tamper Triggers Definitions - * @{ - */ -#define RTC_TAMPERTRIGGER_RISINGEDGE 0x00000000U -#define RTC_TAMPERTRIGGER_FALLINGEDGE 0x00000002U -#define RTC_TAMPERTRIGGER_LOWLEVEL RTC_TAMPERTRIGGER_RISINGEDGE -#define RTC_TAMPERTRIGGER_HIGHLEVEL RTC_TAMPERTRIGGER_FALLINGEDGE -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Filter_Definitions RTC Tamper Filter Definitions - * @{ - */ -#define RTC_TAMPERFILTER_DISABLE 0x00000000U /*!< Tamper filter is disabled */ - -#define RTC_TAMPERFILTER_2SAMPLE 0x00000800U /*!< Tamper is activated after 2 - consecutive samples at the active level */ -#define RTC_TAMPERFILTER_4SAMPLE 0x00001000U /*!< Tamper is activated after 4 - consecutive samples at the active level */ -#define RTC_TAMPERFILTER_8SAMPLE 0x00001800U /*!< Tamper is activated after 8 - consecutive samples at the active level. */ -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Sampling_Frequencies_Definitions RTC Tamper Sampling Frequencies Definitions - * @{ - */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV32768 0x00000000U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 32768 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV16384 0x00000100U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 16384 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV8192 0x00000200U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 8192 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV4096 0x00000300U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 4096 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV2048 0x00000400U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 2048 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV1024 0x00000500U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 1024 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV512 0x00000600U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 512 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV256 0x00000700U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 256 */ -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Pin_Precharge_Duration_Definitions RTC Tamper Pin Precharge Duration Definitions - * @{ - */ -#define RTC_TAMPERPRECHARGEDURATION_1RTCCLK 0x00000000U /*!< Tamper pins are pre-charged before - sampling during 1 RTCCLK cycle */ -#define RTC_TAMPERPRECHARGEDURATION_2RTCCLK 0x00002000U /*!< Tamper pins are pre-charged before - sampling during 2 RTCCLK cycles */ -#define RTC_TAMPERPRECHARGEDURATION_4RTCCLK 0x00004000U /*!< Tamper pins are pre-charged before - sampling during 4 RTCCLK cycles */ -#define RTC_TAMPERPRECHARGEDURATION_8RTCCLK 0x00006000U /*!< Tamper pins are pre-charged before - sampling during 8 RTCCLK cycles */ -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_TimeStampOnTamperDetection_Definitions RTC Tamper TimeStamp On Tamper Detection Definitions - * @{ - */ -#define RTC_TIMESTAMPONTAMPERDETECTION_ENABLE ((uint32_t)RTC_TAFCR_TAMPTS) /*!< TimeStamp on Tamper Detection event saved */ -#define RTC_TIMESTAMPONTAMPERDETECTION_DISABLE 0x00000000U /*!< TimeStamp on Tamper Detection event is not saved */ -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Pull_UP_Definitions RTC Tamper Pull Up Definitions - * @{ - */ -#define RTC_TAMPER_PULLUP_ENABLE 0x00000000U /*!< TimeStamp on Tamper Detection event saved */ -#define RTC_TAMPER_PULLUP_DISABLE ((uint32_t)RTC_TAFCR_TAMPPUDIS) /*!< TimeStamp on Tamper Detection event is not saved */ -/** - * @} - */ - -/** @defgroup RTCEx_Wakeup_Timer_Definitions RTC Wake-up Timer Definitions - * @{ - */ -#define RTC_WAKEUPCLOCK_RTCCLK_DIV16 0x00000000U -#define RTC_WAKEUPCLOCK_RTCCLK_DIV8 0x00000001U -#define RTC_WAKEUPCLOCK_RTCCLK_DIV4 0x00000002U -#define RTC_WAKEUPCLOCK_RTCCLK_DIV2 0x00000003U -#define RTC_WAKEUPCLOCK_CK_SPRE_16BITS 0x00000004U -#define RTC_WAKEUPCLOCK_CK_SPRE_17BITS 0x00000006U -/** - * @} - */ - -/** @defgroup RTCEx_Digital_Calibration_Definitions RTC Digital Calib Definitions - * @{ - */ -#define RTC_CALIBSIGN_POSITIVE 0x00000000U -#define RTC_CALIBSIGN_NEGATIVE 0x00000080U -/** - * @} - */ - -/** @defgroup RTCEx_Smooth_calib_period_Definitions RTC Smooth Calib Period Definitions - * @{ - */ -#define RTC_SMOOTHCALIB_PERIOD_32SEC 0x00000000U /*!< If RTCCLK = 32768 Hz, Smooth calibration - period is 32s, else 2exp20 RTCCLK seconds */ -#define RTC_SMOOTHCALIB_PERIOD_16SEC 0x00002000U /*!< If RTCCLK = 32768 Hz, Smooth calibration - period is 16s, else 2exp19 RTCCLK seconds */ -#define RTC_SMOOTHCALIB_PERIOD_8SEC 0x00004000U /*!< If RTCCLK = 32768 Hz, Smooth calibration - period is 8s, else 2exp18 RTCCLK seconds */ -/** - * @} - */ - -/** @defgroup RTCEx_Smooth_calib_Plus_pulses_Definitions RTC Smooth Calib Plus Pulses Definitions - * @{ - */ -#define RTC_SMOOTHCALIB_PLUSPULSES_SET 0x00008000U /*!< The number of RTCCLK pulses added - during a X -second window = Y - CALM[8:0] - with Y = 512, 256, 128 when X = 32, 16, 8 */ -#define RTC_SMOOTHCALIB_PLUSPULSES_RESET 0x00000000U /*!< The number of RTCCLK pulses subbstited - during a 32-second window = CALM[8:0] */ -/** - * @} - */ - -/** @defgroup RTCEx_Add_1_Second_Parameter_Definitions RTC Add 1 Second Parameter Definitions - * @{ - */ -#define RTC_SHIFTADD1S_RESET 0x00000000U -#define RTC_SHIFTADD1S_SET 0x80000000U -/** - * @} - */ - - - /** @defgroup RTCEx_Calib_Output_selection_Definitions RTC Calib Output Selection Definitions - * @{ - */ -#define RTC_CALIBOUTPUT_512HZ 0x00000000U -#define RTC_CALIBOUTPUT_1HZ 0x00080000U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RTCEx_Exported_Macros RTCEx Exported Macros - * @{ - */ - -/* ---------------------------------WAKEUPTIMER---------------------------------*/ -/** @defgroup RTCEx_WakeUp_Timer RTC WakeUp Timer - * @{ - */ - -/** - * @brief Enable the RTC WakeUp Timer peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_WUTE)) - -/** - * @brief Disable the RTC Wake-up Timer peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_WUTE)) - -/** - * @brief Enable the RTC WakeUpTimer interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC WakeUpTimer interrupt sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_IT_WUT: WakeUpTimer A interrupt - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the RTC WakeUpTimer interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC WakeUpTimer interrupt sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_IT_WUT: WakeUpTimer A interrupt - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified RTC WakeUpTimer interrupt has occurred or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC WakeUpTimer interrupt to check. - * This parameter can be: - * @arg RTC_IT_WUT: WakeUpTimer A interrupt - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->ISR) & ((__INTERRUPT__)>> 4U)) != RESET)? SET : RESET) - -/** - * @brief Check whether the specified RTC Wake Up timer interrupt has been enabled or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Wake Up timer interrupt sources to check. - * This parameter can be: - * @arg RTC_IT_WUT: WakeUpTimer interrupt - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->CR) & (__INTERRUPT__)) != RESET) ? SET : RESET) - -/** - * @brief Get the selected RTC WakeUpTimer's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC WakeUpTimer Flag to check. - * This parameter can be: - * @arg RTC_FLAG_WUTF - * @arg RTC_FLAG_WUTWF - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) - -/** - * @brief Clear the RTC Wake Up timer's pending flags. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Tamper Flag sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_FLAG_WUTF - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~((__FLAG__) | RTC_ISR_INIT)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT)) - -/** - * @brief Enable interrupt on the RTC Wake-up Timer associated Exti line. - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT() (EXTI->IMR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable interrupt on the RTC Wake-up Timer associated Exti line. - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_IT() (EXTI->IMR &= ~(RTC_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable event on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_EVENT() (EXTI->EMR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable event on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(RTC_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable falling edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_FALLING_EDGE() (EXTI->FTSR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable falling edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_FALLING_EDGE() (EXTI->FTSR &= ~(RTC_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable rising edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE() (EXTI->RTSR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable rising edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE() (EXTI->RTSR &= ~(RTC_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable rising & falling edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_RISING_FALLING_EDGE() do { __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE();\ - __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Disable rising & falling edge trigger on the RTC Wake-up Timer associated Exti line. - * This parameter can be: - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_RISING_FALLING_EDGE() do { __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE();\ - __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Check whether the RTC Wake-up Timer associated Exti line interrupt flag is set or not. - * @retval Line Status. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_GET_FLAG() (EXTI->PR & RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Clear the RTC Wake-up Timer associated Exti line flag. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG() (EXTI->PR = RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Generate a Software interrupt on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_GENERATE_SWIT() (EXTI->SWIER |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @} - */ - -/* ---------------------------------TIMESTAMP---------------------------------*/ -/** @defgroup RTCEx_Timestamp RTC Timestamp - * @{ - */ - -/** - * @brief Enable the RTC TimeStamp peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_TSE)) - -/** - * @brief Disable the RTC TimeStamp peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_TSE)) - -/** - * @brief Enable the RTC TimeStamp interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC TimeStamp interrupt sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_IT_TS: TimeStamp interrupt - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the RTC TimeStamp interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC TimeStamp interrupt sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_IT_TS: TimeStamp interrupt - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified RTC TimeStamp interrupt has occurred or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC TimeStamp interrupt to check. - * This parameter can be: - * @arg RTC_IT_TS: TimeStamp interrupt - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->ISR) & ((__INTERRUPT__)>> 4U)) != RESET)? SET : RESET) - -/** - * @brief Check whether the specified RTC Time Stamp interrupt has been enabled or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Time Stamp interrupt source to check. - * This parameter can be: - * @arg RTC_IT_TS: TimeStamp interrupt - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->CR) & (__INTERRUPT__)) != RESET) ? SET : RESET) - -/** - * @brief Get the selected RTC TimeStamp's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC TimeStamp flag to check. - * This parameter can be: - * @arg RTC_FLAG_TSF - * @arg RTC_FLAG_TSOVF - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) - -/** - * @brief Clear the RTC Time Stamp's pending flags. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Alarm Flag sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_FLAG_TSF - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~((__FLAG__) | RTC_ISR_INIT)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT)) - -/** - * @} - */ - -/* ---------------------------------TAMPER------------------------------------*/ -/** @defgroup RTCEx_Tamper RTC Tamper - * @{ - */ - -/** - * @brief Enable the RTC Tamper1 input detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TAMPER1_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->TAFCR |= (RTC_TAFCR_TAMP1E)) - -/** - * @brief Disable the RTC Tamper1 input detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TAMPER1_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->TAFCR &= ~(RTC_TAFCR_TAMP1E)) - -#if !defined(STM32F412Zx) && !defined(STM32F412Vx) && !defined(STM32F412Rx) && !defined(STM32F412Cx) && !defined(STM32F413xx) && !defined(STM32F423xx) -/** - * @brief Enable the RTC Tamper2 input detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TAMPER2_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->TAFCR |= (RTC_TAFCR_TAMP2E)) - -/** - * @brief Disable the RTC Tamper2 input detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TAMPER2_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->TAFCR &= ~(RTC_TAFCR_TAMP2E)) -#endif - -/** - * @brief Check whether the specified RTC Tamper interrupt has occurred or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Tamper interrupt to check. - * This parameter can be: - * @arg RTC_IT_TAMP1 - * @arg RTC_IT_TAMP2 - * @retval None - */ -#define __HAL_RTC_TAMPER_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->ISR) & ((__INTERRUPT__)>> 4U)) != RESET)? SET : RESET) - -/** - * @brief Check whether the specified RTC Tamper interrupt has been enabled or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Tamper interrupt source to check. - * This parameter can be: - * @arg RTC_IT_TAMP: Tamper interrupt - * @retval None - */ -#define __HAL_RTC_TAMPER_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->TAFCR) & (__INTERRUPT__)) != RESET) ? SET : RESET) - -/** - * @brief Get the selected RTC Tamper's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Tamper Flag sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_FLAG_TAMP1F - * @arg RTC_FLAG_TAMP2F - * @retval None - */ -#define __HAL_RTC_TAMPER_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) - -/** - * @brief Clear the RTC Tamper's pending flags. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Tamper Flag to clear. - * This parameter can be: - * @arg RTC_FLAG_TAMP1F - * @arg RTC_FLAG_TAMP2F - * @retval None - */ -#define __HAL_RTC_TAMPER_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~((__FLAG__) | RTC_ISR_INIT)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT)) -/** - * @} - */ - -/* --------------------------TAMPER/TIMESTAMP---------------------------------*/ -/** @defgroup RTCEx_Tamper_Timestamp EXTI RTC Tamper Timestamp EXTI - * @{ - */ - -/** - * @brief Enable interrupt on the RTC Tamper and Timestamp associated Exti line. - * @retval None - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT() (EXTI->IMR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Disable interrupt on the RTC Tamper and Timestamp associated Exti line. - * @retval None - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_IT() (EXTI->IMR &= ~(RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT)) - -/** - * @brief Enable event on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_EVENT() (EXTI->EMR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Disable event on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT)) - -/** - * @brief Enable falling edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_FALLING_EDGE() (EXTI->FTSR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Disable falling edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_FALLING_EDGE() (EXTI->FTSR &= ~(RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT)) - -/** - * @brief Enable rising edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_RISING_EDGE() (EXTI->RTSR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Disable rising edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_RISING_EDGE() (EXTI->RTSR &= ~(RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT)) - -/** - * @brief Enable rising & falling edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_RISING_FALLING_EDGE() do { __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_RISING_EDGE();\ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_FALLING_EDGE(); \ - } while(0U) - -/** - * @brief Disable rising & falling edge trigger on the RTC Tamper and Timestamp associated Exti line. - * This parameter can be: - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_RISING_FALLING_EDGE() do { __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_RISING_EDGE();\ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Check whether the RTC Tamper and Timestamp associated Exti line interrupt flag is set or not. - * @retval Line Status. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG() (EXTI->PR & RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Clear the RTC Tamper and Timestamp associated Exti line flag. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG() (EXTI->PR = RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Generate a Software interrupt on the RTC Tamper and Timestamp associated Exti line - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT() (EXTI->SWIER |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) -/** - * @} - */ - -/* ------------------------------Calibration----------------------------------*/ -/** @defgroup RTCEx_Calibration RTC Calibration - * @{ - */ - -/** - * @brief Enable the Coarse calibration process. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_COARSE_CALIB_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_DCE)) - -/** - * @brief Disable the Coarse calibration process. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_COARSE_CALIB_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_DCE)) - -/** - * @brief Enable the RTC calibration output. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_CALIBRATION_OUTPUT_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_COE)) - -/** - * @brief Disable the calibration output. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_CALIBRATION_OUTPUT_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_COE)) - -/** - * @brief Enable the clock reference detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_CLOCKREF_DETECTION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_REFCKON)) - -/** - * @brief Disable the clock reference detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_CLOCKREF_DETECTION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_REFCKON)) - -/** - * @brief Get the selected RTC shift operation's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC shift operation Flag is pending or not. - * This parameter can be: - * @arg RTC_FLAG_SHPF - * @retval None - */ -#define __HAL_RTC_SHIFT_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RTCEx_Exported_Functions RTCEx Exported Functions - * @{ - */ - -/** @addtogroup RTCEx_Exported_Functions_Group1 - * @{ - */ -/* RTC TimeStamp and Tamper functions *****************************************/ -HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin); -HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp_IT(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin); -HAL_StatusTypeDef HAL_RTCEx_DeactivateTimeStamp(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_GetTimeStamp(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTimeStamp, RTC_DateTypeDef *sTimeStampDate, uint32_t Format); - -HAL_StatusTypeDef HAL_RTCEx_SetTamper(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper); -HAL_StatusTypeDef HAL_RTCEx_SetTamper_IT(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper); -HAL_StatusTypeDef HAL_RTCEx_DeactivateTamper(RTC_HandleTypeDef *hrtc, uint32_t Tamper); -void HAL_RTCEx_TamperTimeStampIRQHandler(RTC_HandleTypeDef *hrtc); - -void HAL_RTCEx_Tamper1EventCallback(RTC_HandleTypeDef *hrtc); -void HAL_RTCEx_Tamper2EventCallback(RTC_HandleTypeDef *hrtc); -void HAL_RTCEx_TimeStampEventCallback(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_PollForTimeStampEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -HAL_StatusTypeDef HAL_RTCEx_PollForTamper1Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -HAL_StatusTypeDef HAL_RTCEx_PollForTamper2Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup RTCEx_Exported_Functions_Group2 - * @{ - */ -/* RTC Wake-up functions ******************************************************/ -HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock); -HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer_IT(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock); -uint32_t HAL_RTCEx_DeactivateWakeUpTimer(RTC_HandleTypeDef *hrtc); -uint32_t HAL_RTCEx_GetWakeUpTimer(RTC_HandleTypeDef *hrtc); -void HAL_RTCEx_WakeUpTimerIRQHandler(RTC_HandleTypeDef *hrtc); -void HAL_RTCEx_WakeUpTimerEventCallback(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_PollForWakeUpTimerEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup RTCEx_Exported_Functions_Group3 - * @{ - */ -/* Extension Control functions ************************************************/ -void HAL_RTCEx_BKUPWrite(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister, uint32_t Data); -uint32_t HAL_RTCEx_BKUPRead(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister); - -HAL_StatusTypeDef HAL_RTCEx_SetCoarseCalib(RTC_HandleTypeDef *hrtc, uint32_t CalibSign, uint32_t Value); -HAL_StatusTypeDef HAL_RTCEx_DeactivateCoarseCalib(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_SetSmoothCalib(RTC_HandleTypeDef *hrtc, uint32_t SmoothCalibPeriod, uint32_t SmoothCalibPlusPulses, uint32_t SmouthCalibMinusPulsesValue); -HAL_StatusTypeDef HAL_RTCEx_SetSynchroShift(RTC_HandleTypeDef *hrtc, uint32_t ShiftAdd1S, uint32_t ShiftSubFS); -HAL_StatusTypeDef HAL_RTCEx_SetCalibrationOutPut(RTC_HandleTypeDef *hrtc, uint32_t CalibOutput); -HAL_StatusTypeDef HAL_RTCEx_DeactivateCalibrationOutPut(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_SetRefClock(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_DeactivateRefClock(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_EnableBypassShadow(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_DisableBypassShadow(RTC_HandleTypeDef *hrtc); -/** - * @} - */ - -/** @addtogroup RTCEx_Exported_Functions_Group4 - * @{ - */ -/* Extension RTC features functions *******************************************/ -void HAL_RTCEx_AlarmBEventCallback(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_PollForAlarmBEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RTCEx_Private_Constants RTCEx Private Constants - * @{ - */ -#define RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT ((uint32_t)EXTI_IMR_MR21) /*!< External interrupt line 21 Connected to the RTC Tamper and Time Stamp events */ -#define RTC_EXTI_LINE_WAKEUPTIMER_EVENT ((uint32_t)EXTI_IMR_MR22) /*!< External interrupt line 22 Connected to the RTC Wake-up event */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RTCEx_Private_Macros RTCEx Private Macros - * @{ - */ - -/** @defgroup RTCEx_IS_RTC_Definitions Private macros to check input parameters - * @{ - */ -#define IS_RTC_BKP(BKP) (((BKP) == RTC_BKP_DR0) || \ - ((BKP) == RTC_BKP_DR1) || \ - ((BKP) == RTC_BKP_DR2) || \ - ((BKP) == RTC_BKP_DR3) || \ - ((BKP) == RTC_BKP_DR4) || \ - ((BKP) == RTC_BKP_DR5) || \ - ((BKP) == RTC_BKP_DR6) || \ - ((BKP) == RTC_BKP_DR7) || \ - ((BKP) == RTC_BKP_DR8) || \ - ((BKP) == RTC_BKP_DR9) || \ - ((BKP) == RTC_BKP_DR10) || \ - ((BKP) == RTC_BKP_DR11) || \ - ((BKP) == RTC_BKP_DR12) || \ - ((BKP) == RTC_BKP_DR13) || \ - ((BKP) == RTC_BKP_DR14) || \ - ((BKP) == RTC_BKP_DR15) || \ - ((BKP) == RTC_BKP_DR16) || \ - ((BKP) == RTC_BKP_DR17) || \ - ((BKP) == RTC_BKP_DR18) || \ - ((BKP) == RTC_BKP_DR19)) -#define IS_TIMESTAMP_EDGE(EDGE) (((EDGE) == RTC_TIMESTAMPEDGE_RISING) || \ - ((EDGE) == RTC_TIMESTAMPEDGE_FALLING)) - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RTC_TAMPER(TAMPER) ((((TAMPER) & ((uint32_t)!(RTC_TAFCR_TAMP1E ))) == 0x00U) && ((TAMPER) != (uint32_t)RESET)) -#else -#define IS_RTC_TAMPER(TAMPER) ((((TAMPER) & ((uint32_t)!(RTC_TAFCR_TAMP1E | RTC_TAFCR_TAMP2E))) == 0x00U) && ((TAMPER) != (uint32_t)RESET)) -#endif - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RTC_TAMPER_PIN(PIN) ((PIN) == RTC_TAMPERPIN_DEFAULT) -#else -#define IS_RTC_TAMPER_PIN(PIN) (((PIN) == RTC_TAMPERPIN_DEFAULT) || \ - ((PIN) == RTC_TAMPERPIN_POS1)) -#endif - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RTC_TIMESTAMP_PIN(PIN) ((PIN) == RTC_TIMESTAMPPIN_DEFAULT) -#else -#define IS_RTC_TIMESTAMP_PIN(PIN) (((PIN) == RTC_TIMESTAMPPIN_DEFAULT) || \ - ((PIN) == RTC_TIMESTAMPPIN_POS1)) -#endif -#define IS_RTC_TAMPER_TRIGGER(TRIGGER) (((TRIGGER) == RTC_TAMPERTRIGGER_RISINGEDGE) || \ - ((TRIGGER) == RTC_TAMPERTRIGGER_FALLINGEDGE) || \ - ((TRIGGER) == RTC_TAMPERTRIGGER_LOWLEVEL) || \ - ((TRIGGER) == RTC_TAMPERTRIGGER_HIGHLEVEL)) -#define IS_RTC_TAMPER_FILTER(FILTER) (((FILTER) == RTC_TAMPERFILTER_DISABLE) || \ - ((FILTER) == RTC_TAMPERFILTER_2SAMPLE) || \ - ((FILTER) == RTC_TAMPERFILTER_4SAMPLE) || \ - ((FILTER) == RTC_TAMPERFILTER_8SAMPLE)) -#define IS_RTC_TAMPER_SAMPLING_FREQ(FREQ) (((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV32768)|| \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV16384)|| \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV8192) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV4096) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV2048) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV1024) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV512) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV256)) -#define IS_RTC_TAMPER_PRECHARGE_DURATION(DURATION) (((DURATION) == RTC_TAMPERPRECHARGEDURATION_1RTCCLK) || \ - ((DURATION) == RTC_TAMPERPRECHARGEDURATION_2RTCCLK) || \ - ((DURATION) == RTC_TAMPERPRECHARGEDURATION_4RTCCLK) || \ - ((DURATION) == RTC_TAMPERPRECHARGEDURATION_8RTCCLK)) -#define IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION(DETECTION) (((DETECTION) == RTC_TIMESTAMPONTAMPERDETECTION_ENABLE) || \ - ((DETECTION) == RTC_TIMESTAMPONTAMPERDETECTION_DISABLE)) -#define IS_RTC_TAMPER_PULLUP_STATE(STATE) (((STATE) == RTC_TAMPER_PULLUP_ENABLE) || \ - ((STATE) == RTC_TAMPER_PULLUP_DISABLE)) -#define IS_RTC_WAKEUP_CLOCK(CLOCK) (((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV16) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV8) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV4) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV2) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_CK_SPRE_16BITS) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_CK_SPRE_17BITS)) - -#define IS_RTC_WAKEUP_COUNTER(COUNTER) ((COUNTER) <= 0xFFFFU) -#define IS_RTC_CALIB_SIGN(SIGN) (((SIGN) == RTC_CALIBSIGN_POSITIVE) || \ - ((SIGN) == RTC_CALIBSIGN_NEGATIVE)) - -#define IS_RTC_CALIB_VALUE(VALUE) ((VALUE) < 0x20U) - -#define IS_RTC_SMOOTH_CALIB_PERIOD(PERIOD) (((PERIOD) == RTC_SMOOTHCALIB_PERIOD_32SEC) || \ - ((PERIOD) == RTC_SMOOTHCALIB_PERIOD_16SEC) || \ - ((PERIOD) == RTC_SMOOTHCALIB_PERIOD_8SEC)) -#define IS_RTC_SMOOTH_CALIB_PLUS(PLUS) (((PLUS) == RTC_SMOOTHCALIB_PLUSPULSES_SET) || \ - ((PLUS) == RTC_SMOOTHCALIB_PLUSPULSES_RESET)) - -#define IS_RTC_SMOOTH_CALIB_MINUS(VALUE) ((VALUE) <= 0x000001FFU) -#define IS_RTC_SHIFT_ADD1S(SEL) (((SEL) == RTC_SHIFTADD1S_RESET) || \ - ((SEL) == RTC_SHIFTADD1S_SET)) -#define IS_RTC_SHIFT_SUBFS(FS) ((FS) <= 0x00007FFFU) -#define IS_RTC_CALIB_OUTPUT(OUTPUT) (((OUTPUT) == RTC_CALIBOUTPUT_512HZ) || \ - ((OUTPUT) == RTC_CALIBOUTPUT_1HZ)) -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RTC_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai.h deleted file mode 100644 index 0307f92333a24e1..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai.h +++ /dev/null @@ -1,897 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sai.h - * @author MCD Application Team - * @brief Header file of SAI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SAI_H -#define __STM32F4xx_HAL_SAI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || \ - defined(STM32F423xx) - -/** @addtogroup SAI - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SAI_Exported_Types SAI Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_SAI_STATE_RESET = 0x00U, /*!< SAI not yet initialized or disabled */ - HAL_SAI_STATE_READY = 0x01U, /*!< SAI initialized and ready for use */ - HAL_SAI_STATE_BUSY = 0x02U, /*!< SAI internal process is ongoing */ - HAL_SAI_STATE_BUSY_TX = 0x12U, /*!< Data transmission process is ongoing */ - HAL_SAI_STATE_BUSY_RX = 0x22U, /*!< Data reception process is ongoing */ - HAL_SAI_STATE_TIMEOUT = 0x03U, /*!< SAI timeout state */ - HAL_SAI_STATE_ERROR = 0x04U /*!< SAI error state */ -} HAL_SAI_StateTypeDef; - -/** - * @brief SAI Callback prototype - */ -typedef void (*SAIcallback)(void); - -/** @defgroup SAI_Init_Structure_definition SAI Init Structure definition - * @brief SAI Init Structure definition - * @{ - */ -typedef struct -{ - uint32_t AudioMode; /*!< Specifies the SAI Block audio Mode. - This parameter can be a value of @ref SAI_Block_Mode */ - - uint32_t Synchro; /*!< Specifies SAI Block synchronization - This parameter can be a value of @ref SAI_Block_Synchronization */ - - uint32_t SynchroExt; /*!< Specifies SAI external output synchronization, this setup is common - for BlockA and BlockB - This parameter can be a value of @ref SAI_Block_SyncExt - @note: If both audio blocks of same SAI are used, this parameter has - to be set to the same value for each audio block */ - - uint32_t OutputDrive; /*!< Specifies when SAI Block outputs are driven. - This parameter can be a value of @ref SAI_Block_Output_Drive - @note this value has to be set before enabling the audio block - but after the audio block configuration. */ - - uint32_t NoDivider; /*!< Specifies whether master clock will be divided or not. - This parameter can be a value of @ref SAI_Block_NoDivider - @note If bit NODIV in the SAI_xCR1 register is cleared, the frame length - should be aligned to a number equal to a power of 2, from 8 to 256. - If bit NODIV in the SAI_xCR1 register is set, the frame length can - take any of the values without constraint since the input clock of - the audio block should be equal to the bit clock. - There is no MCLK_x clock which can be output. */ - - uint32_t FIFOThreshold; /*!< Specifies SAI Block FIFO threshold. - This parameter can be a value of @ref SAI_Block_Fifo_Threshold */ - - uint32_t ClockSource; /*!< Specifies the SAI Block x Clock source. - This parameter is not used for STM32F446xx devices. */ - - uint32_t AudioFrequency; /*!< Specifies the audio frequency sampling. - This parameter can be a value of @ref SAI_Audio_Frequency */ - - uint32_t Mckdiv; /*!< Specifies the master clock divider. - This parameter must be a number between Min_Data = 0 and Max_Data = 15. - @note This parameter is used only if AudioFrequency is set to - SAI_AUDIO_FREQUENCY_MCKDIV otherwise it is internally computed. */ - - uint32_t MonoStereoMode; /*!< Specifies if the mono or stereo mode is selected. - This parameter can be a value of @ref SAI_Mono_Stereo_Mode */ - - uint32_t CompandingMode; /*!< Specifies the companding mode type. - This parameter can be a value of @ref SAI_Block_Companding_Mode */ - - uint32_t TriState; /*!< Specifies the companding mode type. - This parameter can be a value of @ref SAI_TRIState_Management */ - - /* This part of the structure is automatically filled if your are using the high level intialisation - function HAL_SAI_InitProtocol */ - - uint32_t Protocol; /*!< Specifies the SAI Block protocol. - This parameter can be a value of @ref SAI_Block_Protocol */ - - uint32_t DataSize; /*!< Specifies the SAI Block data size. - This parameter can be a value of @ref SAI_Block_Data_Size */ - - uint32_t FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. - This parameter can be a value of @ref SAI_Block_MSB_LSB_transmission */ - - uint32_t ClockStrobing; /*!< Specifies the SAI Block clock strobing edge sensitivity. - This parameter can be a value of @ref SAI_Block_Clock_Strobing */ -} SAI_InitTypeDef; -/** - * @} - */ - -/** @defgroup SAI_Frame_Structure_definition SAI Frame Structure definition - * @brief SAI Frame Init structure definition - * @note For SPDIF and AC97 protocol, these parameters are not used (set by hardware). - * @{ - */ -typedef struct -{ - uint32_t FrameLength; /*!< Specifies the Frame length, the number of SCK clocks for each audio frame. - This parameter must be a number between Min_Data = 8 and Max_Data = 256. - @note If master clock MCLK_x pin is declared as an output, the frame length - should be aligned to a number equal to power of 2 in order to keep - in an audio frame, an integer number of MCLK pulses by bit Clock. */ - - uint32_t ActiveFrameLength; /*!< Specifies the Frame synchronization active level length. - This Parameter specifies the length in number of bit clock (SCK + 1) - of the active level of FS signal in audio frame. - This parameter must be a number between Min_Data = 1 and Max_Data = 128 */ - - uint32_t FSDefinition; /*!< Specifies the Frame synchronization definition. - This parameter can be a value of @ref SAI_Block_FS_Definition */ - - uint32_t FSPolarity; /*!< Specifies the Frame synchronization Polarity. - This parameter can be a value of @ref SAI_Block_FS_Polarity */ - - uint32_t FSOffset; /*!< Specifies the Frame synchronization Offset. - This parameter can be a value of @ref SAI_Block_FS_Offset */ -} SAI_FrameInitTypeDef; -/** - * @} - */ - -/** @defgroup SAI_Slot_Structure_definition SAI Slot Structure definition - * @brief SAI Block Slot Init Structure definition - * @note For SPDIF protocol, these parameters are not used (set by hardware). - * @note For AC97 protocol, only SlotActive parameter is used (the others are set by hardware). - * @{ - */ -typedef struct -{ - uint32_t FirstBitOffset; /*!< Specifies the position of first data transfer bit in the slot. - This parameter must be a number between Min_Data = 0 and Max_Data = 24 */ - - uint32_t SlotSize; /*!< Specifies the Slot Size. - This parameter can be a value of @ref SAI_Block_Slot_Size */ - - uint32_t SlotNumber; /*!< Specifies the number of slot in the audio frame. - This parameter must be a number between Min_Data = 1 and Max_Data = 16 */ - - uint32_t SlotActive; /*!< Specifies the slots in audio frame that will be activated. - This parameter can be a value of @ref SAI_Block_Slot_Active */ -} SAI_SlotInitTypeDef; -/** - * @} - */ - -/** @defgroup SAI_Handle_Structure_definition SAI Handle Structure definition - * @brief SAI handle Structure definition - * @{ - */ -typedef struct __SAI_HandleTypeDef -{ - SAI_Block_TypeDef *Instance; /*!< SAI Blockx registers base address */ - - SAI_InitTypeDef Init; /*!< SAI communication parameters */ - - SAI_FrameInitTypeDef FrameInit; /*!< SAI Frame configuration parameters */ - - SAI_SlotInitTypeDef SlotInit; /*!< SAI Slot configuration parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to SAI transfer Buffer */ - - uint16_t XferSize; /*!< SAI transfer size */ - - uint16_t XferCount; /*!< SAI transfer counter */ - - DMA_HandleTypeDef *hdmatx; /*!< SAI Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SAI Rx DMA handle parameters */ - - SAIcallback mutecallback;/*!< SAI mute callback */ - - void (*InterruptServiceRoutine)(struct __SAI_HandleTypeDef *hsai); /* function pointer for IRQ handler */ - - HAL_LockTypeDef Lock; /*!< SAI locking object */ - - __IO HAL_SAI_StateTypeDef State; /*!< SAI communication state */ - - __IO uint32_t ErrorCode; /*!< SAI Error code */ - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - void (*RxCpltCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI receive complete callback */ - void (*RxHalfCpltCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI receive half complete callback */ - void (*TxCpltCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI transmit complete callback */ - void (*TxHalfCpltCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI transmit half complete callback */ - void (*ErrorCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI error callback */ - void (*MspInitCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI MSP init callback */ - void (*MspDeInitCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI MSP de-init callback */ -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -} SAI_HandleTypeDef; -/** - * @} - */ - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -/** - * @brief SAI callback ID enumeration definition - */ -typedef enum -{ - HAL_SAI_RX_COMPLETE_CB_ID = 0x00U, /*!< SAI receive complete callback ID */ - HAL_SAI_RX_HALFCOMPLETE_CB_ID = 0x01U, /*!< SAI receive half complete callback ID */ - HAL_SAI_TX_COMPLETE_CB_ID = 0x02U, /*!< SAI transmit complete callback ID */ - HAL_SAI_TX_HALFCOMPLETE_CB_ID = 0x03U, /*!< SAI transmit half complete callback ID */ - HAL_SAI_ERROR_CB_ID = 0x04U, /*!< SAI error callback ID */ - HAL_SAI_MSPINIT_CB_ID = 0x05U, /*!< SAI MSP init callback ID */ - HAL_SAI_MSPDEINIT_CB_ID = 0x06U /*!< SAI MSP de-init callback ID */ -} HAL_SAI_CallbackIDTypeDef; - -/** - * @brief SAI callback pointer definition - */ -typedef void (*pSAI_CallbackTypeDef)(SAI_HandleTypeDef *hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SAI_Exported_Constants SAI Exported Constants - * @{ - */ - -/** @defgroup SAI_Error_Code SAI Error Code - * @{ - */ -#define HAL_SAI_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_SAI_ERROR_OVR 0x00000001U /*!< Overrun Error */ -#define HAL_SAI_ERROR_UDR 0x00000002U /*!< Underrun error */ -#define HAL_SAI_ERROR_AFSDET 0x00000004U /*!< Anticipated Frame synchronisation detection */ -#define HAL_SAI_ERROR_LFSDET 0x00000008U /*!< Late Frame synchronisation detection */ -#define HAL_SAI_ERROR_CNREADY 0x00000010U /*!< codec not ready */ -#define HAL_SAI_ERROR_WCKCFG 0x00000020U /*!< Wrong clock configuration */ -#define HAL_SAI_ERROR_TIMEOUT 0x00000040U /*!< Timeout error */ -#define HAL_SAI_ERROR_DMA 0x00000080U /*!< DMA error */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -#define HAL_SAI_ERROR_INVALID_CALLBACK 0x00000100U /*!< Invalid callback error */ -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SAI_Block_SyncExt SAI External synchronisation - * @{ - */ -#define SAI_SYNCEXT_DISABLE 0U -#define SAI_SYNCEXT_OUTBLOCKA_ENABLE 1U -#define SAI_SYNCEXT_OUTBLOCKB_ENABLE 2U -/** - * @} - */ - -/** @defgroup SAI_Protocol SAI Supported protocol - * @{ - */ -#define SAI_I2S_STANDARD 0U -#define SAI_I2S_MSBJUSTIFIED 1U -#define SAI_I2S_LSBJUSTIFIED 2U -#define SAI_PCM_LONG 3U -#define SAI_PCM_SHORT 4U -/** - * @} - */ - -/** @defgroup SAI_Protocol_DataSize SAI protocol data size - * @{ - */ -#define SAI_PROTOCOL_DATASIZE_16BIT 0U -#define SAI_PROTOCOL_DATASIZE_16BITEXTENDED 1U -#define SAI_PROTOCOL_DATASIZE_24BIT 2U -#define SAI_PROTOCOL_DATASIZE_32BIT 3U -/** - * @} - */ - -/** @defgroup SAI_Audio_Frequency SAI Audio Frequency - * @{ - */ -#define SAI_AUDIO_FREQUENCY_192K 192000U -#define SAI_AUDIO_FREQUENCY_96K 96000U -#define SAI_AUDIO_FREQUENCY_48K 48000U -#define SAI_AUDIO_FREQUENCY_44K 44100U -#define SAI_AUDIO_FREQUENCY_32K 32000U -#define SAI_AUDIO_FREQUENCY_22K 22050U -#define SAI_AUDIO_FREQUENCY_16K 16000U -#define SAI_AUDIO_FREQUENCY_11K 11025U -#define SAI_AUDIO_FREQUENCY_8K 8000U -#define SAI_AUDIO_FREQUENCY_MCKDIV 0U -/** - * @} - */ - -/** @defgroup SAI_Block_Mode SAI Block Mode - * @{ - */ -#define SAI_MODEMASTER_TX 0x00000000U -#define SAI_MODEMASTER_RX ((uint32_t)SAI_xCR1_MODE_0) -#define SAI_MODESLAVE_TX ((uint32_t)SAI_xCR1_MODE_1) -#define SAI_MODESLAVE_RX ((uint32_t)(SAI_xCR1_MODE_1 | SAI_xCR1_MODE_0)) -/** - * @} - */ - -/** @defgroup SAI_Block_Protocol SAI Block Protocol - * @{ - */ -#define SAI_FREE_PROTOCOL 0x00000000U -#define SAI_SPDIF_PROTOCOL ((uint32_t)SAI_xCR1_PRTCFG_0) -#define SAI_AC97_PROTOCOL ((uint32_t)SAI_xCR1_PRTCFG_1) -/** - * @} - */ - -/** @defgroup SAI_Block_Data_Size SAI Block Data Size - * @{ - */ -#define SAI_DATASIZE_8 ((uint32_t)SAI_xCR1_DS_1) -#define SAI_DATASIZE_10 ((uint32_t)(SAI_xCR1_DS_1 | SAI_xCR1_DS_0)) -#define SAI_DATASIZE_16 ((uint32_t)SAI_xCR1_DS_2) -#define SAI_DATASIZE_20 ((uint32_t)(SAI_xCR1_DS_2 | SAI_xCR1_DS_0)) -#define SAI_DATASIZE_24 ((uint32_t)(SAI_xCR1_DS_2 | SAI_xCR1_DS_1)) -#define SAI_DATASIZE_32 ((uint32_t)(SAI_xCR1_DS_2 | SAI_xCR1_DS_1 | SAI_xCR1_DS_0)) -/** - * @} - */ - -/** @defgroup SAI_Block_MSB_LSB_transmission SAI Block MSB LSB transmission - * @{ - */ -#define SAI_FIRSTBIT_MSB 0x00000000U -#define SAI_FIRSTBIT_LSB ((uint32_t)SAI_xCR1_LSBFIRST) -/** - * @} - */ - -/** @defgroup SAI_Block_Clock_Strobing SAI Block Clock Strobing - * @{ - */ -#define SAI_CLOCKSTROBING_FALLINGEDGE 0U -#define SAI_CLOCKSTROBING_RISINGEDGE 1U -/** - * @} - */ - -/** @defgroup SAI_Block_Synchronization SAI Block Synchronization - * @{ - */ -#define SAI_ASYNCHRONOUS 0U /*!< Asynchronous */ -#define SAI_SYNCHRONOUS 1U /*!< Synchronous with other block of same SAI */ -#define SAI_SYNCHRONOUS_EXT_SAI1 2U /*!< Synchronous with other SAI, SAI1 */ -#define SAI_SYNCHRONOUS_EXT_SAI2 3U /*!< Synchronous with other SAI, SAI2 */ -/** - * @} - */ - -/** @defgroup SAI_Block_Output_Drive SAI Block Output Drive - * @{ - */ -#define SAI_OUTPUTDRIVE_DISABLE 0x00000000U -#define SAI_OUTPUTDRIVE_ENABLE ((uint32_t)SAI_xCR1_OUTDRIV) -/** - * @} - */ - -/** @defgroup SAI_Block_NoDivider SAI Block NoDivider - * @{ - */ -#define SAI_MASTERDIVIDER_ENABLE 0x00000000U -#define SAI_MASTERDIVIDER_DISABLE ((uint32_t)SAI_xCR1_NODIV) -/** - * @} - */ - -/** @defgroup SAI_Block_FS_Definition SAI Block FS Definition - * @{ - */ -#define SAI_FS_STARTFRAME 0x00000000U -#define SAI_FS_CHANNEL_IDENTIFICATION ((uint32_t)SAI_xFRCR_FSDEF) -/** - * @} - */ - -/** @defgroup SAI_Block_FS_Polarity SAI Block FS Polarity - * @{ - */ -#define SAI_FS_ACTIVE_LOW 0x00000000U -#define SAI_FS_ACTIVE_HIGH ((uint32_t)SAI_xFRCR_FSPOL) -/** - * @} - */ - -/** @defgroup SAI_Block_FS_Offset SAI Block FS Offset - * @{ - */ -#define SAI_FS_FIRSTBIT 0x00000000U -#define SAI_FS_BEFOREFIRSTBIT ((uint32_t)SAI_xFRCR_FSOFF) -/** - * @} - */ - -/** @defgroup SAI_Block_Slot_Size SAI Block Slot Size - * @{ - */ -#define SAI_SLOTSIZE_DATASIZE 0x00000000U -#define SAI_SLOTSIZE_16B ((uint32_t)SAI_xSLOTR_SLOTSZ_0) -#define SAI_SLOTSIZE_32B ((uint32_t)SAI_xSLOTR_SLOTSZ_1) -/** - * @} - */ - -/** @defgroup SAI_Block_Slot_Active SAI Block Slot Active - * @{ - */ -#define SAI_SLOT_NOTACTIVE 0x00000000U -#define SAI_SLOTACTIVE_0 0x00000001U -#define SAI_SLOTACTIVE_1 0x00000002U -#define SAI_SLOTACTIVE_2 0x00000004U -#define SAI_SLOTACTIVE_3 0x00000008U -#define SAI_SLOTACTIVE_4 0x00000010U -#define SAI_SLOTACTIVE_5 0x00000020U -#define SAI_SLOTACTIVE_6 0x00000040U -#define SAI_SLOTACTIVE_7 0x00000080U -#define SAI_SLOTACTIVE_8 0x00000100U -#define SAI_SLOTACTIVE_9 0x00000200U -#define SAI_SLOTACTIVE_10 0x00000400U -#define SAI_SLOTACTIVE_11 0x00000800U -#define SAI_SLOTACTIVE_12 0x00001000U -#define SAI_SLOTACTIVE_13 0x00002000U -#define SAI_SLOTACTIVE_14 0x00004000U -#define SAI_SLOTACTIVE_15 0x00008000U -#define SAI_SLOTACTIVE_ALL 0x0000FFFFU -/** - * @} - */ - -/** @defgroup SAI_Mono_Stereo_Mode SAI Mono Stereo Mode - * @{ - */ -#define SAI_STEREOMODE 0x00000000U -#define SAI_MONOMODE ((uint32_t)SAI_xCR1_MONO) -/** - * @} - */ - -/** @defgroup SAI_TRIState_Management SAI TRIState Management - * @{ - */ -#define SAI_OUTPUT_NOTRELEASED 0x00000000U -#define SAI_OUTPUT_RELEASED ((uint32_t)SAI_xCR2_TRIS) -/** - * @} - */ - -/** @defgroup SAI_Block_Fifo_Threshold SAI Block Fifo Threshold - * @{ - */ -#define SAI_FIFOTHRESHOLD_EMPTY 0x00000000U -#define SAI_FIFOTHRESHOLD_1QF ((uint32_t)(SAI_xCR2_FTH_0)) -#define SAI_FIFOTHRESHOLD_HF ((uint32_t)(SAI_xCR2_FTH_1)) -#define SAI_FIFOTHRESHOLD_3QF ((uint32_t)(SAI_xCR2_FTH_1 | SAI_xCR2_FTH_0)) -#define SAI_FIFOTHRESHOLD_FULL ((uint32_t)(SAI_xCR2_FTH_2)) -/** - * @} - */ - -/** @defgroup SAI_Block_Companding_Mode SAI Block Companding Mode - * @{ - */ -#define SAI_NOCOMPANDING 0x00000000U -#define SAI_ULAW_1CPL_COMPANDING ((uint32_t)(SAI_xCR2_COMP_1)) -#define SAI_ALAW_1CPL_COMPANDING ((uint32_t)(SAI_xCR2_COMP_1 | SAI_xCR2_COMP_0)) -#define SAI_ULAW_2CPL_COMPANDING ((uint32_t)(SAI_xCR2_COMP_1 | SAI_xCR2_CPL)) -#define SAI_ALAW_2CPL_COMPANDING ((uint32_t)(SAI_xCR2_COMP_1 | SAI_xCR2_COMP_0 | SAI_xCR2_CPL)) -/** - * @} - */ - -/** @defgroup SAI_Block_Mute_Value SAI Block Mute Value - * @{ - */ -#define SAI_ZERO_VALUE 0x00000000U -#define SAI_LAST_SENT_VALUE ((uint32_t)SAI_xCR2_MUTEVAL) -/** - * @} - */ - -/** @defgroup SAI_Block_Interrupts_Definition SAI Block Interrupts Definition - * @{ - */ -#define SAI_IT_OVRUDR ((uint32_t)SAI_xIMR_OVRUDRIE) -#define SAI_IT_MUTEDET ((uint32_t)SAI_xIMR_MUTEDETIE) -#define SAI_IT_WCKCFG ((uint32_t)SAI_xIMR_WCKCFGIE) -#define SAI_IT_FREQ ((uint32_t)SAI_xIMR_FREQIE) -#define SAI_IT_CNRDY ((uint32_t)SAI_xIMR_CNRDYIE) -#define SAI_IT_AFSDET ((uint32_t)SAI_xIMR_AFSDETIE) -#define SAI_IT_LFSDET ((uint32_t)SAI_xIMR_LFSDETIE) -/** - * @} - */ - -/** @defgroup SAI_Block_Flags_Definition SAI Block Flags Definition - * @{ - */ -#define SAI_FLAG_OVRUDR ((uint32_t)SAI_xSR_OVRUDR) -#define SAI_FLAG_MUTEDET ((uint32_t)SAI_xSR_MUTEDET) -#define SAI_FLAG_WCKCFG ((uint32_t)SAI_xSR_WCKCFG) -#define SAI_FLAG_FREQ ((uint32_t)SAI_xSR_FREQ) -#define SAI_FLAG_CNRDY ((uint32_t)SAI_xSR_CNRDY) -#define SAI_FLAG_AFSDET ((uint32_t)SAI_xSR_AFSDET) -#define SAI_FLAG_LFSDET ((uint32_t)SAI_xSR_LFSDET) -/** - * @} - */ - -/** @defgroup SAI_Block_Fifo_Status_Level SAI Block Fifo Status Level - * @{ - */ -#define SAI_FIFOSTATUS_EMPTY 0x00000000U -#define SAI_FIFOSTATUS_LESS1QUARTERFULL 0x00010000U -#define SAI_FIFOSTATUS_1QUARTERFULL 0x00020000U -#define SAI_FIFOSTATUS_HALFFULL 0x00030000U -#define SAI_FIFOSTATUS_3QUARTERFULL 0x00040000U -#define SAI_FIFOSTATUS_FULL 0x00050000U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SAI_Exported_Macros SAI Exported Macros - * @brief macros to handle interrupts and specific configurations - * @{ - */ - -/** @brief Reset SAI handle state - * @param __HANDLE__ specifies the SAI Handle. - * @retval None - */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -#define __HAL_SAI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_SAI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_SAI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SAI_STATE_RESET) -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - -/** @brief Enable or disable the specified SAI interrupts. - * @param __HANDLE__ specifies the SAI Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg SAI_IT_OVRUDR: Overrun underrun interrupt enable - * @arg SAI_IT_MUTEDET: Mute detection interrupt enable - * @arg SAI_IT_WCKCFG: Wrong Clock Configuration interrupt enable - * @arg SAI_IT_FREQ: FIFO request interrupt enable - * @arg SAI_IT_CNRDY: Codec not ready interrupt enable - * @arg SAI_IT_AFSDET: Anticipated frame synchronization detection interrupt enable - * @arg SAI_IT_LFSDET: Late frame synchronization detection interrupt enable - * @retval None - */ -#define __HAL_SAI_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IMR |= (__INTERRUPT__)) -#define __HAL_SAI_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IMR &= (~(__INTERRUPT__))) - -/** @brief Check if the specified SAI interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the SAI Handle. - * This parameter can be SAI where x: 1, 2, or 3 to select the SAI peripheral. - * @param __INTERRUPT__ specifies the SAI interrupt source to check. - * This parameter can be one of the following values: - * @arg SAI_IT_OVRUDR: Overrun underrun interrupt enable - * @arg SAI_IT_MUTEDET: Mute detection interrupt enable - * @arg SAI_IT_WCKCFG: Wrong Clock Configuration interrupt enable - * @arg SAI_IT_FREQ: FIFO request interrupt enable - * @arg SAI_IT_CNRDY: Codec not ready interrupt enable - * @arg SAI_IT_AFSDET: Anticipated frame synchronization detection interrupt enable - * @arg SAI_IT_LFSDET: Late frame synchronization detection interrupt enable - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_SAI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IMR & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified SAI flag is set or not. - * @param __HANDLE__ specifies the SAI Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SAI_FLAG_OVRUDR: Overrun underrun flag. - * @arg SAI_FLAG_MUTEDET: Mute detection flag. - * @arg SAI_FLAG_WCKCFG: Wrong Clock Configuration flag. - * @arg SAI_FLAG_FREQ: FIFO request flag. - * @arg SAI_FLAG_CNRDY: Codec not ready flag. - * @arg SAI_FLAG_AFSDET: Anticipated frame synchronization detection flag. - * @arg SAI_FLAG_LFSDET: Late frame synchronization detection flag. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SAI_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified SAI pending flag. - * @param __HANDLE__ specifies the SAI Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg SAI_FLAG_OVRUDR: Clear Overrun underrun - * @arg SAI_FLAG_MUTEDET: Clear Mute detection - * @arg SAI_FLAG_WCKCFG: Clear Wrong Clock Configuration - * @arg SAI_FLAG_FREQ: Clear FIFO request - * @arg SAI_FLAG_CNRDY: Clear Codec not ready - * @arg SAI_FLAG_AFSDET: Clear Anticipated frame synchronization detection - * @arg SAI_FLAG_LFSDET: Clear Late frame synchronization detection - * @retval None - */ -#define __HAL_SAI_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->CLRFR = (__FLAG__)) - -/** @brief Enable SAI - * @param __HANDLE__ specifies the SAI Handle. - * @retval None - */ -#define __HAL_SAI_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= SAI_xCR1_SAIEN) - -/** @brief Disable SAI - * @param __HANDLE__ specifies the SAI Handle. - * @retval None - */ -#define __HAL_SAI_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~SAI_xCR1_SAIEN) - -/** - * @} - */ - -/* Include HAL SAI Extension module */ -#include "stm32f4xx_hal_sai_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SAI_Exported_Functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -/** @addtogroup SAI_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_SAI_InitProtocol(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot); -HAL_StatusTypeDef HAL_SAI_Init(SAI_HandleTypeDef *hsai); -HAL_StatusTypeDef HAL_SAI_DeInit(SAI_HandleTypeDef *hsai); -void HAL_SAI_MspInit(SAI_HandleTypeDef *hsai); -void HAL_SAI_MspDeInit(SAI_HandleTypeDef *hsai); - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -/* SAI callbacks register/unregister functions ********************************/ -HAL_StatusTypeDef HAL_SAI_RegisterCallback(SAI_HandleTypeDef *hsai, - HAL_SAI_CallbackIDTypeDef CallbackID, - pSAI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SAI_UnRegisterCallback(SAI_HandleTypeDef *hsai, - HAL_SAI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* I/O operation functions *****************************************************/ -/** @addtogroup SAI_Exported_Functions_Group2 - * @{ - */ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_SAI_Transmit(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SAI_Receive(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size, uint32_t Timeout); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_SAI_Transmit_IT(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SAI_Receive_IT(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_SAI_Transmit_DMA(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SAI_Receive_DMA(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SAI_DMAPause(SAI_HandleTypeDef *hsai); -HAL_StatusTypeDef HAL_SAI_DMAResume(SAI_HandleTypeDef *hsai); -HAL_StatusTypeDef HAL_SAI_DMAStop(SAI_HandleTypeDef *hsai); - -/* Abort function */ -HAL_StatusTypeDef HAL_SAI_Abort(SAI_HandleTypeDef *hsai); - -/* Mute management */ -HAL_StatusTypeDef HAL_SAI_EnableTxMuteMode(SAI_HandleTypeDef *hsai, uint16_t val); -HAL_StatusTypeDef HAL_SAI_DisableTxMuteMode(SAI_HandleTypeDef *hsai); -HAL_StatusTypeDef HAL_SAI_EnableRxMuteMode(SAI_HandleTypeDef *hsai, SAIcallback callback, uint16_t counter); -HAL_StatusTypeDef HAL_SAI_DisableRxMuteMode(SAI_HandleTypeDef *hsai); - -/* SAI IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_SAI_IRQHandler(SAI_HandleTypeDef *hsai); -void HAL_SAI_TxHalfCpltCallback(SAI_HandleTypeDef *hsai); -void HAL_SAI_TxCpltCallback(SAI_HandleTypeDef *hsai); -void HAL_SAI_RxHalfCpltCallback(SAI_HandleTypeDef *hsai); -void HAL_SAI_RxCpltCallback(SAI_HandleTypeDef *hsai); -void HAL_SAI_ErrorCallback(SAI_HandleTypeDef *hsai); -/** - * @} - */ - -/** @addtogroup SAI_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_SAI_StateTypeDef HAL_SAI_GetState(SAI_HandleTypeDef *hsai); -uint32_t HAL_SAI_GetError(SAI_HandleTypeDef *hsai); -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup SAI_Private_Macros - * @{ - */ -#define IS_SAI_BLOCK_SYNCEXT(STATE) (((STATE) == SAI_SYNCEXT_DISABLE) ||\ - ((STATE) == SAI_SYNCEXT_OUTBLOCKA_ENABLE) ||\ - ((STATE) == SAI_SYNCEXT_OUTBLOCKB_ENABLE)) - -#define IS_SAI_SUPPORTED_PROTOCOL(PROTOCOL) (((PROTOCOL) == SAI_I2S_STANDARD) ||\ - ((PROTOCOL) == SAI_I2S_MSBJUSTIFIED) ||\ - ((PROTOCOL) == SAI_I2S_LSBJUSTIFIED) ||\ - ((PROTOCOL) == SAI_PCM_LONG) ||\ - ((PROTOCOL) == SAI_PCM_SHORT)) - -#define IS_SAI_PROTOCOL_DATASIZE(DATASIZE) (((DATASIZE) == SAI_PROTOCOL_DATASIZE_16BIT) ||\ - ((DATASIZE) == SAI_PROTOCOL_DATASIZE_16BITEXTENDED) ||\ - ((DATASIZE) == SAI_PROTOCOL_DATASIZE_24BIT) ||\ - ((DATASIZE) == SAI_PROTOCOL_DATASIZE_32BIT)) - -#define IS_SAI_AUDIO_FREQUENCY(AUDIO) (((AUDIO) == SAI_AUDIO_FREQUENCY_192K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_96K) || \ - ((AUDIO) == SAI_AUDIO_FREQUENCY_48K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_44K) || \ - ((AUDIO) == SAI_AUDIO_FREQUENCY_32K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_22K) || \ - ((AUDIO) == SAI_AUDIO_FREQUENCY_16K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_11K) || \ - ((AUDIO) == SAI_AUDIO_FREQUENCY_8K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_MCKDIV)) - -#define IS_SAI_BLOCK_MODE(MODE) (((MODE) == SAI_MODEMASTER_TX) || \ - ((MODE) == SAI_MODEMASTER_RX) || \ - ((MODE) == SAI_MODESLAVE_TX) || \ - ((MODE) == SAI_MODESLAVE_RX)) - -#define IS_SAI_BLOCK_PROTOCOL(PROTOCOL) (((PROTOCOL) == SAI_FREE_PROTOCOL) || \ - ((PROTOCOL) == SAI_AC97_PROTOCOL) || \ - ((PROTOCOL) == SAI_SPDIF_PROTOCOL)) - -#define IS_SAI_BLOCK_DATASIZE(DATASIZE) (((DATASIZE) == SAI_DATASIZE_8) || \ - ((DATASIZE) == SAI_DATASIZE_10) || \ - ((DATASIZE) == SAI_DATASIZE_16) || \ - ((DATASIZE) == SAI_DATASIZE_20) || \ - ((DATASIZE) == SAI_DATASIZE_24) || \ - ((DATASIZE) == SAI_DATASIZE_32)) - -#define IS_SAI_BLOCK_FIRST_BIT(BIT) (((BIT) == SAI_FIRSTBIT_MSB) || \ - ((BIT) == SAI_FIRSTBIT_LSB)) - -#define IS_SAI_BLOCK_CLOCK_STROBING(CLOCK) (((CLOCK) == SAI_CLOCKSTROBING_FALLINGEDGE) || \ - ((CLOCK) == SAI_CLOCKSTROBING_RISINGEDGE)) - -#define IS_SAI_BLOCK_SYNCHRO(SYNCHRO) (((SYNCHRO) == SAI_ASYNCHRONOUS) || \ - ((SYNCHRO) == SAI_SYNCHRONOUS) || \ - ((SYNCHRO) == SAI_SYNCHRONOUS_EXT_SAI1) ||\ - ((SYNCHRO) == SAI_SYNCHRONOUS_EXT_SAI2)) - -#define IS_SAI_BLOCK_OUTPUT_DRIVE(DRIVE) (((DRIVE) == SAI_OUTPUTDRIVE_DISABLE) || \ - ((DRIVE) == SAI_OUTPUTDRIVE_ENABLE)) - -#define IS_SAI_BLOCK_NODIVIDER(NODIVIDER) (((NODIVIDER) == SAI_MASTERDIVIDER_ENABLE) || \ - ((NODIVIDER) == SAI_MASTERDIVIDER_DISABLE)) - -#define IS_SAI_BLOCK_MUTE_COUNTER(COUNTER) ((COUNTER) <= 63U) - -#define IS_SAI_BLOCK_MUTE_VALUE(VALUE) (((VALUE) == SAI_ZERO_VALUE) || \ - ((VALUE) == SAI_LAST_SENT_VALUE)) - -#define IS_SAI_BLOCK_COMPANDING_MODE(MODE) (((MODE) == SAI_NOCOMPANDING) || \ - ((MODE) == SAI_ULAW_1CPL_COMPANDING) || \ - ((MODE) == SAI_ALAW_1CPL_COMPANDING) || \ - ((MODE) == SAI_ULAW_2CPL_COMPANDING) || \ - ((MODE) == SAI_ALAW_2CPL_COMPANDING)) - -#define IS_SAI_BLOCK_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == SAI_FIFOTHRESHOLD_EMPTY) || \ - ((THRESHOLD) == SAI_FIFOTHRESHOLD_1QF) || \ - ((THRESHOLD) == SAI_FIFOTHRESHOLD_HF) || \ - ((THRESHOLD) == SAI_FIFOTHRESHOLD_3QF) || \ - ((THRESHOLD) == SAI_FIFOTHRESHOLD_FULL)) - -#define IS_SAI_BLOCK_TRISTATE_MANAGEMENT(STATE) (((STATE) == SAI_OUTPUT_NOTRELEASED) ||\ - ((STATE) == SAI_OUTPUT_RELEASED)) - -#define IS_SAI_MONO_STEREO_MODE(MODE) (((MODE) == SAI_MONOMODE) ||\ - ((MODE) == SAI_STEREOMODE)) - -#define IS_SAI_SLOT_ACTIVE(ACTIVE) ((ACTIVE) <= SAI_SLOTACTIVE_ALL) - -#define IS_SAI_BLOCK_SLOT_NUMBER(NUMBER) ((1U <= (NUMBER)) && ((NUMBER) <= 16U)) - -#define IS_SAI_BLOCK_SLOT_SIZE(SIZE) (((SIZE) == SAI_SLOTSIZE_DATASIZE) || \ - ((SIZE) == SAI_SLOTSIZE_16B) || \ - ((SIZE) == SAI_SLOTSIZE_32B)) - -#define IS_SAI_BLOCK_FIRSTBIT_OFFSET(OFFSET) ((OFFSET) <= 24U) - -#define IS_SAI_BLOCK_FS_OFFSET(OFFSET) (((OFFSET) == SAI_FS_FIRSTBIT) || \ - ((OFFSET) == SAI_FS_BEFOREFIRSTBIT)) - -#define IS_SAI_BLOCK_FS_POLARITY(POLARITY) (((POLARITY) == SAI_FS_ACTIVE_LOW) || \ - ((POLARITY) == SAI_FS_ACTIVE_HIGH)) - -#define IS_SAI_BLOCK_FS_DEFINITION(DEFINITION) (((DEFINITION) == SAI_FS_STARTFRAME) || \ - ((DEFINITION) == SAI_FS_CHANNEL_IDENTIFICATION)) - -#define IS_SAI_BLOCK_MASTER_DIVIDER(DIVIDER) ((DIVIDER) <= 15U) - -#define IS_SAI_BLOCK_FRAME_LENGTH(LENGTH) ((8U <= (LENGTH)) && ((LENGTH) <= 256U)) - -#define IS_SAI_BLOCK_ACTIVE_FRAME(LENGTH) ((1U <= (LENGTH)) && ((LENGTH) <= 128U)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SAI_Private_Functions SAI Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SAI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai_ex.h deleted file mode 100644 index fbd44979deed2b3..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai_ex.h +++ /dev/null @@ -1,116 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sai_ex.h - * @author MCD Application Team - * @brief Header file of SAI Extension HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SAI_EX_H -#define __STM32F4xx_HAL_SAI_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SAIEx - * @{ - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || \ - defined(STM32F423xx) - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SAI_Clock_Source SAI Clock Source - * @{ - */ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define SAI_CLKSOURCE_PLLI2S 0x00000000U -#define SAI_CLKSOURCE_EXT 0x00100000U -#define SAI_CLKSOURCE_PLLR 0x00200000U -#define SAI_CLKSOURCE_HS 0x00300000U -#else -#define SAI_CLKSOURCE_PLLSAI 0x00000000U -#define SAI_CLKSOURCE_PLLI2S 0x00100000U -#define SAI_CLKSOURCE_EXT 0x00200000U -#define SAI_CLKSOURCE_NA 0x00400000U /*!< No applicable for STM32F446xx */ -#endif - - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SAIEx_Exported_Functions - * @{ - */ - -/** @addtogroup SAIEx_Exported_Functions_Group1 - * @{ - */ - -/* Extended features functions ************************************************/ -void SAI_BlockSynchroConfig(SAI_HandleTypeDef *hsai); -uint32_t SAI_GetInputClock(SAI_HandleTypeDef *hsai); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_SAI_CLK_SOURCE(SOURCE) (((SOURCE) == SAI_CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == SAI_CLKSOURCE_EXT)||\ - ((SOURCE) == SAI_CLKSOURCE_PLLR)||\ - ((SOURCE) == SAI_CLKSOURCE_HS)) -#else -#define IS_SAI_CLK_SOURCE(SOURCE) (((SOURCE) == SAI_CLKSOURCE_PLLSAI) ||\ - ((SOURCE) == SAI_CLKSOURCE_EXT)||\ - ((SOURCE) == SAI_CLKSOURCE_PLLI2S)||\ - ((SOURCE) == SAI_CLKSOURCE_NA)) -#endif -/* Private functions ---------------------------------------------------------*/ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SAI_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h deleted file mode 100644 index e82e7e0ce0ada18..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h +++ /dev/null @@ -1,761 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sd.h - * @author MCD Application Team - * @brief Header file of SD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_SD_H -#define STM32F4xx_HAL_SD_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(SDIO) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_sdmmc.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SD SD - * @brief SD HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SD_Exported_Types SD Exported Types - * @{ - */ - -/** @defgroup SD_Exported_Types_Group1 SD State enumeration structure - * @{ - */ -typedef enum -{ - HAL_SD_STATE_RESET = 0x00000000U, /*!< SD not yet initialized or disabled */ - HAL_SD_STATE_READY = 0x00000001U, /*!< SD initialized and ready for use */ - HAL_SD_STATE_TIMEOUT = 0x00000002U, /*!< SD Timeout state */ - HAL_SD_STATE_BUSY = 0x00000003U, /*!< SD process ongoing */ - HAL_SD_STATE_PROGRAMMING = 0x00000004U, /*!< SD Programming State */ - HAL_SD_STATE_RECEIVING = 0x00000005U, /*!< SD Receiving State */ - HAL_SD_STATE_TRANSFER = 0x00000006U, /*!< SD Transfer State */ - HAL_SD_STATE_ERROR = 0x0000000FU /*!< SD is in error state */ -}HAL_SD_StateTypeDef; -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group2 SD Card State enumeration structure - * @{ - */ -typedef uint32_t HAL_SD_CardStateTypeDef; - -#define HAL_SD_CARD_READY 0x00000001U /*!< Card state is ready */ -#define HAL_SD_CARD_IDENTIFICATION 0x00000002U /*!< Card is in identification state */ -#define HAL_SD_CARD_STANDBY 0x00000003U /*!< Card is in standby state */ -#define HAL_SD_CARD_TRANSFER 0x00000004U /*!< Card is in transfer state */ -#define HAL_SD_CARD_SENDING 0x00000005U /*!< Card is sending an operation */ -#define HAL_SD_CARD_RECEIVING 0x00000006U /*!< Card is receiving operation information */ -#define HAL_SD_CARD_PROGRAMMING 0x00000007U /*!< Card is in programming state */ -#define HAL_SD_CARD_DISCONNECTED 0x00000008U /*!< Card is disconnected */ -#define HAL_SD_CARD_ERROR 0x000000FFU /*!< Card response Error */ -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group3 SD Handle Structure definition - * @{ - */ -#define SD_InitTypeDef SDIO_InitTypeDef -#define SD_TypeDef SDIO_TypeDef - -/** - * @brief SD Card Information Structure definition - */ -typedef struct -{ - uint32_t CardType; /*!< Specifies the card Type */ - - uint32_t CardVersion; /*!< Specifies the card version */ - - uint32_t Class; /*!< Specifies the class of the card class */ - - uint32_t RelCardAdd; /*!< Specifies the Relative Card Address */ - - uint32_t BlockNbr; /*!< Specifies the Card Capacity in blocks */ - - uint32_t BlockSize; /*!< Specifies one block size in bytes */ - - uint32_t LogBlockNbr; /*!< Specifies the Card logical Capacity in blocks */ - - uint32_t LogBlockSize; /*!< Specifies logical block size in bytes */ - -}HAL_SD_CardInfoTypeDef; - -/** - * @brief SD handle Structure definition - */ -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -typedef struct __SD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ -{ - SD_TypeDef *Instance; /*!< SD registers base address */ - - SD_InitTypeDef Init; /*!< SD required parameters */ - - HAL_LockTypeDef Lock; /*!< SD locking object */ - - uint8_t *pTxBuffPtr; /*!< Pointer to SD Tx transfer Buffer */ - - uint32_t TxXferSize; /*!< SD Tx Transfer size */ - - uint8_t *pRxBuffPtr; /*!< Pointer to SD Rx transfer Buffer */ - - uint32_t RxXferSize; /*!< SD Rx Transfer size */ - - __IO uint32_t Context; /*!< SD transfer context */ - - __IO HAL_SD_StateTypeDef State; /*!< SD card State */ - - __IO uint32_t ErrorCode; /*!< SD Card Error codes */ - - DMA_HandleTypeDef *hdmatx; /*!< SD Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SD Rx DMA handle parameters */ - - HAL_SD_CardInfoTypeDef SdCard; /*!< SD Card information */ - - uint32_t CSD[4]; /*!< SD card specific data table */ - - uint32_t CID[4]; /*!< SD card identification number table */ - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback) (struct __SD_HandleTypeDef *hsd); - void (* RxCpltCallback) (struct __SD_HandleTypeDef *hsd); - void (* ErrorCallback) (struct __SD_HandleTypeDef *hsd); - void (* AbortCpltCallback) (struct __SD_HandleTypeDef *hsd); - - void (* MspInitCallback) (struct __SD_HandleTypeDef *hsd); - void (* MspDeInitCallback) (struct __SD_HandleTypeDef *hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ -}SD_HandleTypeDef; - -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group4 Card Specific Data: CSD Register - * @{ - */ -typedef struct -{ - __IO uint8_t CSDStruct; /*!< CSD structure */ - __IO uint8_t SysSpecVersion; /*!< System specification version */ - __IO uint8_t Reserved1; /*!< Reserved */ - __IO uint8_t TAAC; /*!< Data read access time 1 */ - __IO uint8_t NSAC; /*!< Data read access time 2 in CLK cycles */ - __IO uint8_t MaxBusClkFrec; /*!< Max. bus clock frequency */ - __IO uint16_t CardComdClasses; /*!< Card command classes */ - __IO uint8_t RdBlockLen; /*!< Max. read data block length */ - __IO uint8_t PartBlockRead; /*!< Partial blocks for read allowed */ - __IO uint8_t WrBlockMisalign; /*!< Write block misalignment */ - __IO uint8_t RdBlockMisalign; /*!< Read block misalignment */ - __IO uint8_t DSRImpl; /*!< DSR implemented */ - __IO uint8_t Reserved2; /*!< Reserved */ - __IO uint32_t DeviceSize; /*!< Device Size */ - __IO uint8_t MaxRdCurrentVDDMin; /*!< Max. read current @ VDD min */ - __IO uint8_t MaxRdCurrentVDDMax; /*!< Max. read current @ VDD max */ - __IO uint8_t MaxWrCurrentVDDMin; /*!< Max. write current @ VDD min */ - __IO uint8_t MaxWrCurrentVDDMax; /*!< Max. write current @ VDD max */ - __IO uint8_t DeviceSizeMul; /*!< Device size multiplier */ - __IO uint8_t EraseGrSize; /*!< Erase group size */ - __IO uint8_t EraseGrMul; /*!< Erase group size multiplier */ - __IO uint8_t WrProtectGrSize; /*!< Write protect group size */ - __IO uint8_t WrProtectGrEnable; /*!< Write protect group enable */ - __IO uint8_t ManDeflECC; /*!< Manufacturer default ECC */ - __IO uint8_t WrSpeedFact; /*!< Write speed factor */ - __IO uint8_t MaxWrBlockLen; /*!< Max. write data block length */ - __IO uint8_t WriteBlockPaPartial; /*!< Partial blocks for write allowed */ - __IO uint8_t Reserved3; /*!< Reserved */ - __IO uint8_t ContentProtectAppli; /*!< Content protection application */ - __IO uint8_t FileFormatGroup; /*!< File format group */ - __IO uint8_t CopyFlag; /*!< Copy flag (OTP) */ - __IO uint8_t PermWrProtect; /*!< Permanent write protection */ - __IO uint8_t TempWrProtect; /*!< Temporary write protection */ - __IO uint8_t FileFormat; /*!< File format */ - __IO uint8_t ECC; /*!< ECC code */ - __IO uint8_t CSD_CRC; /*!< CSD CRC */ - __IO uint8_t Reserved4; /*!< Always 1 */ -}HAL_SD_CardCSDTypeDef; -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group5 Card Identification Data: CID Register - * @{ - */ -typedef struct -{ - __IO uint8_t ManufacturerID; /*!< Manufacturer ID */ - __IO uint16_t OEM_AppliID; /*!< OEM/Application ID */ - __IO uint32_t ProdName1; /*!< Product Name part1 */ - __IO uint8_t ProdName2; /*!< Product Name part2 */ - __IO uint8_t ProdRev; /*!< Product Revision */ - __IO uint32_t ProdSN; /*!< Product Serial Number */ - __IO uint8_t Reserved1; /*!< Reserved1 */ - __IO uint16_t ManufactDate; /*!< Manufacturing Date */ - __IO uint8_t CID_CRC; /*!< CID CRC */ - __IO uint8_t Reserved2; /*!< Always 1 */ - -}HAL_SD_CardCIDTypeDef; -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group6 SD Card Status returned by ACMD13 - * @{ - */ -typedef struct -{ - __IO uint8_t DataBusWidth; /*!< Shows the currently defined data bus width */ - __IO uint8_t SecuredMode; /*!< Card is in secured mode of operation */ - __IO uint16_t CardType; /*!< Carries information about card type */ - __IO uint32_t ProtectedAreaSize; /*!< Carries information about the capacity of protected area */ - __IO uint8_t SpeedClass; /*!< Carries information about the speed class of the card */ - __IO uint8_t PerformanceMove; /*!< Carries information about the card's performance move */ - __IO uint8_t AllocationUnitSize; /*!< Carries information about the card's allocation unit size */ - __IO uint16_t EraseSize; /*!< Determines the number of AUs to be erased in one operation */ - __IO uint8_t EraseTimeout; /*!< Determines the timeout for any number of AU erase */ - __IO uint8_t EraseOffset; /*!< Carries information about the erase offset */ - -}HAL_SD_CardStatusTypeDef; -/** - * @} - */ - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -/** @defgroup SD_Exported_Types_Group7 SD Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_SD_TX_CPLT_CB_ID = 0x00U, /*!< SD Tx Complete Callback ID */ - HAL_SD_RX_CPLT_CB_ID = 0x01U, /*!< SD Rx Complete Callback ID */ - HAL_SD_ERROR_CB_ID = 0x02U, /*!< SD Error Callback ID */ - HAL_SD_ABORT_CB_ID = 0x03U, /*!< SD Abort Callback ID */ - - HAL_SD_MSP_INIT_CB_ID = 0x10U, /*!< SD MspInit Callback ID */ - HAL_SD_MSP_DEINIT_CB_ID = 0x11U /*!< SD MspDeInit Callback ID */ -}HAL_SD_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group8 SD Callback pointer definition - * @{ - */ -typedef void (*pSD_CallbackTypeDef) (SD_HandleTypeDef *hsd); -/** - * @} - */ -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SD_Exported_Constants Exported Constants - * @{ - */ - -#define BLOCKSIZE 512U /*!< Block size is 512 bytes */ - -/** @defgroup SD_Exported_Constansts_Group1 SD Error status enumeration Structure definition - * @{ - */ -#define HAL_SD_ERROR_NONE SDMMC_ERROR_NONE /*!< No error */ -#define HAL_SD_ERROR_CMD_CRC_FAIL SDMMC_ERROR_CMD_CRC_FAIL /*!< Command response received (but CRC check failed) */ -#define HAL_SD_ERROR_DATA_CRC_FAIL SDMMC_ERROR_DATA_CRC_FAIL /*!< Data block sent/received (CRC check failed) */ -#define HAL_SD_ERROR_CMD_RSP_TIMEOUT SDMMC_ERROR_CMD_RSP_TIMEOUT /*!< Command response timeout */ -#define HAL_SD_ERROR_DATA_TIMEOUT SDMMC_ERROR_DATA_TIMEOUT /*!< Data timeout */ -#define HAL_SD_ERROR_TX_UNDERRUN SDMMC_ERROR_TX_UNDERRUN /*!< Transmit FIFO underrun */ -#define HAL_SD_ERROR_RX_OVERRUN SDMMC_ERROR_RX_OVERRUN /*!< Receive FIFO overrun */ -#define HAL_SD_ERROR_ADDR_MISALIGNED SDMMC_ERROR_ADDR_MISALIGNED /*!< Misaligned address */ -#define HAL_SD_ERROR_BLOCK_LEN_ERR SDMMC_ERROR_BLOCK_LEN_ERR /*!< Transferred block length is not allowed for the card or the - number of transferred bytes does not match the block length */ -#define HAL_SD_ERROR_ERASE_SEQ_ERR SDMMC_ERROR_ERASE_SEQ_ERR /*!< An error in the sequence of erase command occurs */ -#define HAL_SD_ERROR_BAD_ERASE_PARAM SDMMC_ERROR_BAD_ERASE_PARAM /*!< An invalid selection for erase groups */ -#define HAL_SD_ERROR_WRITE_PROT_VIOLATION SDMMC_ERROR_WRITE_PROT_VIOLATION /*!< Attempt to program a write protect block */ -#define HAL_SD_ERROR_LOCK_UNLOCK_FAILED SDMMC_ERROR_LOCK_UNLOCK_FAILED /*!< Sequence or password error has been detected in unlock - command or if there was an attempt to access a locked card */ -#define HAL_SD_ERROR_COM_CRC_FAILED SDMMC_ERROR_COM_CRC_FAILED /*!< CRC check of the previous command failed */ -#define HAL_SD_ERROR_ILLEGAL_CMD SDMMC_ERROR_ILLEGAL_CMD /*!< Command is not legal for the card state */ -#define HAL_SD_ERROR_CARD_ECC_FAILED SDMMC_ERROR_CARD_ECC_FAILED /*!< Card internal ECC was applied but failed to correct the data */ -#define HAL_SD_ERROR_CC_ERR SDMMC_ERROR_CC_ERR /*!< Internal card controller error */ -#define HAL_SD_ERROR_GENERAL_UNKNOWN_ERR SDMMC_ERROR_GENERAL_UNKNOWN_ERR /*!< General or unknown error */ -#define HAL_SD_ERROR_STREAM_READ_UNDERRUN SDMMC_ERROR_STREAM_READ_UNDERRUN /*!< The card could not sustain data reading in stream rmode */ -#define HAL_SD_ERROR_STREAM_WRITE_OVERRUN SDMMC_ERROR_STREAM_WRITE_OVERRUN /*!< The card could not sustain data programming in stream mode */ -#define HAL_SD_ERROR_CID_CSD_OVERWRITE SDMMC_ERROR_CID_CSD_OVERWRITE /*!< CID/CSD overwrite error */ -#define HAL_SD_ERROR_WP_ERASE_SKIP SDMMC_ERROR_WP_ERASE_SKIP /*!< Only partial address space was erased */ -#define HAL_SD_ERROR_CARD_ECC_DISABLED SDMMC_ERROR_CARD_ECC_DISABLED /*!< Command has been executed without using internal ECC */ -#define HAL_SD_ERROR_ERASE_RESET SDMMC_ERROR_ERASE_RESET /*!< Erase sequence was cleared before executing because an out - of erase sequence command was received */ -#define HAL_SD_ERROR_AKE_SEQ_ERR SDMMC_ERROR_AKE_SEQ_ERR /*!< Error in sequence of authentication */ -#define HAL_SD_ERROR_INVALID_VOLTRANGE SDMMC_ERROR_INVALID_VOLTRANGE /*!< Error in case of invalid voltage range */ -#define HAL_SD_ERROR_ADDR_OUT_OF_RANGE SDMMC_ERROR_ADDR_OUT_OF_RANGE /*!< Error when addressed block is out of range */ -#define HAL_SD_ERROR_REQUEST_NOT_APPLICABLE SDMMC_ERROR_REQUEST_NOT_APPLICABLE /*!< Error when command request is not applicable */ -#define HAL_SD_ERROR_PARAM SDMMC_ERROR_INVALID_PARAMETER /*!< the used parameter is not valid */ -#define HAL_SD_ERROR_UNSUPPORTED_FEATURE SDMMC_ERROR_UNSUPPORTED_FEATURE /*!< Error when feature is not insupported */ -#define HAL_SD_ERROR_BUSY SDMMC_ERROR_BUSY /*!< Error when transfer process is busy */ -#define HAL_SD_ERROR_DMA SDMMC_ERROR_DMA /*!< Error while DMA transfer */ -#define HAL_SD_ERROR_TIMEOUT SDMMC_ERROR_TIMEOUT /*!< Timeout error */ - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -#define HAL_SD_ERROR_INVALID_CALLBACK SDMMC_ERROR_INVALID_PARAMETER /*!< Invalid callback error */ -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SD_Exported_Constansts_Group2 SD context enumeration - * @{ - */ -#define SD_CONTEXT_NONE 0x00000000U /*!< None */ -#define SD_CONTEXT_READ_SINGLE_BLOCK 0x00000001U /*!< Read single block operation */ -#define SD_CONTEXT_READ_MULTIPLE_BLOCK 0x00000002U /*!< Read multiple blocks operation */ -#define SD_CONTEXT_WRITE_SINGLE_BLOCK 0x00000010U /*!< Write single block operation */ -#define SD_CONTEXT_WRITE_MULTIPLE_BLOCK 0x00000020U /*!< Write multiple blocks operation */ -#define SD_CONTEXT_IT 0x00000008U /*!< Process in Interrupt mode */ -#define SD_CONTEXT_DMA 0x00000080U /*!< Process in DMA mode */ - -/** - * @} - */ - -/** @defgroup SD_Exported_Constansts_Group3 SD Supported Memory Cards - * @{ - */ -#define CARD_SDSC 0x00000000U /*!< SD Standard Capacity <2Go */ -#define CARD_SDHC_SDXC 0x00000001U /*!< SD High Capacity <32Go, SD Extended Capacity <2To */ -#define CARD_SECURED 0x00000003U - -/** - * @} - */ - -/** @defgroup SD_Exported_Constansts_Group4 SD Supported Version - * @{ - */ -#define CARD_V1_X 0x00000000U -#define CARD_V2_X 0x00000001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SD_Exported_macros SD Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -/** @brief Reset SD handle state. - * @param __HANDLE__ : SD handle. - * @retval None - */ -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -#define __HAL_SD_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_SD_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SD_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SD_STATE_RESET) -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - -/** - * @brief Enable the SD device. - * @retval None - */ -#define __HAL_SD_ENABLE(__HANDLE__) __SDIO_ENABLE((__HANDLE__)->Instance) - -/** - * @brief Disable the SD device. - * @retval None - */ -#define __HAL_SD_DISABLE(__HANDLE__) __SDIO_DISABLE((__HANDLE__)->Instance) - -/** - * @brief Enable the SDMMC DMA transfer. - * @retval None - */ -#define __HAL_SD_DMA_ENABLE(__HANDLE__) __SDIO_DMA_ENABLE((__HANDLE__)->Instance) - -/** - * @brief Disable the SDMMC DMA transfer. - * @retval None - */ -#define __HAL_SD_DMA_DISABLE(__HANDLE__) __SDIO_DMA_DISABLE((__HANDLE__)->Instance) - -/** - * @brief Enable the SD device interrupt. - * @param __HANDLE__: SD Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt sources to be enabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __HAL_SD_ENABLE_IT(__HANDLE__, __INTERRUPT__) __SDIO_ENABLE_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Disable the SD device interrupt. - * @param __HANDLE__: SD Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt sources to be disabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __HAL_SD_DISABLE_IT(__HANDLE__, __INTERRUPT__) __SDIO_DISABLE_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Check whether the specified SD flag is set or not. - * @param __HANDLE__: SD Handle - * @param __FLAG__: specifies the flag to check. - * This parameter can be one of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_CMDACT: Command transfer in progress - * @arg SDIO_FLAG_TXACT: Data transmit in progress - * @arg SDIO_FLAG_RXACT: Data receive in progress - * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty - * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full - * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full - * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full - * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty - * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty - * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO - * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO - * @arg SDIO_FLAG_SDIOIT: SDIO interrupt received - * @retval The new state of SD FLAG (SET or RESET). - */ -#define __HAL_SD_GET_FLAG(__HANDLE__, __FLAG__) __SDIO_GET_FLAG((__HANDLE__)->Instance, (__FLAG__)) - -/** - * @brief Clear the SD's pending flags. - * @param __HANDLE__: SD Handle - * @param __FLAG__: specifies the flag to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_SDIOIT: SDIO interrupt received - * @retval None - */ -#define __HAL_SD_CLEAR_FLAG(__HANDLE__, __FLAG__) __SDIO_CLEAR_FLAG((__HANDLE__)->Instance, (__FLAG__)) - -/** - * @brief Check whether the specified SD interrupt has occurred or not. - * @param __HANDLE__: SD Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt source to check. - * This parameter can be one of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval The new state of SD IT (SET or RESET). - */ -#define __HAL_SD_GET_IT(__HANDLE__, __INTERRUPT__) __SDIO_GET_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Clear the SD's interrupt pending bits. - * @param __HANDLE__: SD Handle - * @param __INTERRUPT__: specifies the interrupt pending bit to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __HAL_SD_CLEAR_IT(__HANDLE__, __INTERRUPT__) __SDIO_CLEAR_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SD_Exported_Functions SD Exported Functions - * @{ - */ - -/** @defgroup SD_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_SD_Init(SD_HandleTypeDef *hsd); -HAL_StatusTypeDef HAL_SD_InitCard(SD_HandleTypeDef *hsd); -HAL_StatusTypeDef HAL_SD_DeInit (SD_HandleTypeDef *hsd); -void HAL_SD_MspInit(SD_HandleTypeDef *hsd); -void HAL_SD_MspDeInit(SD_HandleTypeDef *hsd); -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_SD_ReadBlocks(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout); -HAL_StatusTypeDef HAL_SD_WriteBlocks(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout); -HAL_StatusTypeDef HAL_SD_Erase(SD_HandleTypeDef *hsd, uint32_t BlockStartAdd, uint32_t BlockEndAdd); -/* Non-Blocking mode: IT */ -HAL_StatusTypeDef HAL_SD_ReadBlocks_IT(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -HAL_StatusTypeDef HAL_SD_WriteBlocks_IT(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_SD_ReadBlocks_DMA(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -HAL_StatusTypeDef HAL_SD_WriteBlocks_DMA(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); - -void HAL_SD_IRQHandler(SD_HandleTypeDef *hsd); - -/* Callback in non blocking modes (DMA) */ -void HAL_SD_TxCpltCallback(SD_HandleTypeDef *hsd); -void HAL_SD_RxCpltCallback(SD_HandleTypeDef *hsd); -void HAL_SD_ErrorCallback(SD_HandleTypeDef *hsd); -void HAL_SD_AbortCallback(SD_HandleTypeDef *hsd); - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -/* SD callback registering/unregistering */ -HAL_StatusTypeDef HAL_SD_RegisterCallback (SD_HandleTypeDef *hsd, HAL_SD_CallbackIDTypeDef CallbackId, pSD_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SD_UnRegisterCallback(SD_HandleTypeDef *hsd, HAL_SD_CallbackIDTypeDef CallbackId); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_SD_ConfigWideBusOperation(SD_HandleTypeDef *hsd, uint32_t WideMode); -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group4 SD card related functions - * @{ - */ -HAL_StatusTypeDef HAL_SD_SendSDStatus(SD_HandleTypeDef *hsd, uint32_t *pSDstatus); -HAL_SD_CardStateTypeDef HAL_SD_GetCardState(SD_HandleTypeDef *hsd); -HAL_StatusTypeDef HAL_SD_GetCardCID(SD_HandleTypeDef *hsd, HAL_SD_CardCIDTypeDef *pCID); -HAL_StatusTypeDef HAL_SD_GetCardCSD(SD_HandleTypeDef *hsd, HAL_SD_CardCSDTypeDef *pCSD); -HAL_StatusTypeDef HAL_SD_GetCardStatus(SD_HandleTypeDef *hsd, HAL_SD_CardStatusTypeDef *pStatus); -HAL_StatusTypeDef HAL_SD_GetCardInfo(SD_HandleTypeDef *hsd, HAL_SD_CardInfoTypeDef *pCardInfo); -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group5 Peripheral State and Errors functions - * @{ - */ -HAL_SD_StateTypeDef HAL_SD_GetState(SD_HandleTypeDef *hsd); -uint32_t HAL_SD_GetError(SD_HandleTypeDef *hsd); -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group6 Perioheral Abort management - * @{ - */ -HAL_StatusTypeDef HAL_SD_Abort(SD_HandleTypeDef *hsd); -HAL_StatusTypeDef HAL_SD_Abort_IT(SD_HandleTypeDef *hsd); -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup SD_Private_Types SD Private Types - * @{ - */ - -/** - * @} - */ - -/* Private defines -----------------------------------------------------------*/ -/** @defgroup SD_Private_Defines SD Private Defines - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup SD_Private_Variables SD Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SD_Private_Constants SD Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SD_Private_Macros SD Private Macros - * @{ - */ - -/** - * @} - */ - -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup SD_Private_Functions_Prototypes SD Private Functions Prototypes - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SD_Private_Functions SD Private Functions - * @{ - */ - -/** - * @} - */ - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* SDIO */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_SD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sdram.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sdram.h deleted file mode 100644 index 3dd78027af28044..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sdram.h +++ /dev/null @@ -1,226 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sdram.h - * @author MCD Application Team - * @brief Header file of SDRAM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SDRAM_H -#define __STM32F4xx_HAL_SDRAM_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_fmc.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SDRAM - * @{ - */ - -/* Exported typedef ----------------------------------------------------------*/ -/** @defgroup SDRAM_Exported_Types SDRAM Exported Types - * @{ - */ - -/** - * @brief HAL SDRAM State structure definition - */ -typedef enum -{ - HAL_SDRAM_STATE_RESET = 0x00U, /*!< SDRAM not yet initialized or disabled */ - HAL_SDRAM_STATE_READY = 0x01U, /*!< SDRAM initialized and ready for use */ - HAL_SDRAM_STATE_BUSY = 0x02U, /*!< SDRAM internal process is ongoing */ - HAL_SDRAM_STATE_ERROR = 0x03U, /*!< SDRAM error state */ - HAL_SDRAM_STATE_WRITE_PROTECTED = 0x04U, /*!< SDRAM device write protected */ - HAL_SDRAM_STATE_PRECHARGED = 0x05U /*!< SDRAM device precharged */ - -} HAL_SDRAM_StateTypeDef; - -/** - * @brief SDRAM handle Structure definition - */ -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -typedef struct __SDRAM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_SDRAM_REGISTER_CALLBACKS */ -{ - FMC_SDRAM_TypeDef *Instance; /*!< Register base address */ - - FMC_SDRAM_InitTypeDef Init; /*!< SDRAM device configuration parameters */ - - __IO HAL_SDRAM_StateTypeDef State; /*!< SDRAM access state */ - - HAL_LockTypeDef Lock; /*!< SDRAM locking object */ - - DMA_HandleTypeDef *hdma; /*!< Pointer DMA handler */ - -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) - void (* MspInitCallback) ( struct __SDRAM_HandleTypeDef * hsdram); /*!< SDRAM Msp Init callback */ - void (* MspDeInitCallback) ( struct __SDRAM_HandleTypeDef * hsdram); /*!< SDRAM Msp DeInit callback */ - void (* RefreshErrorCallback) ( struct __SDRAM_HandleTypeDef * hsdram); /*!< SDRAM Refresh Error callback */ - void (* DmaXferCpltCallback) ( DMA_HandleTypeDef * hdma); /*!< SDRAM DMA Xfer Complete callback */ - void (* DmaXferErrorCallback) ( DMA_HandleTypeDef * hdma); /*!< SDRAM DMA Xfer Error callback */ -#endif -} SDRAM_HandleTypeDef; - -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SDRAM Callback ID enumeration definition - */ -typedef enum -{ - HAL_SDRAM_MSP_INIT_CB_ID = 0x00U, /*!< SDRAM MspInit Callback ID */ - HAL_SDRAM_MSP_DEINIT_CB_ID = 0x01U, /*!< SDRAM MspDeInit Callback ID */ - HAL_SDRAM_REFRESH_ERR_CB_ID = 0x02U, /*!< SDRAM Refresh Error Callback ID */ - HAL_SDRAM_DMA_XFER_CPLT_CB_ID = 0x03U, /*!< SDRAM DMA Xfer Complete Callback ID */ - HAL_SDRAM_DMA_XFER_ERR_CB_ID = 0x04U /*!< SDRAM DMA Xfer Error Callback ID */ -}HAL_SDRAM_CallbackIDTypeDef; - -/** - * @brief HAL SDRAM Callback pointer definition - */ -typedef void (*pSDRAM_CallbackTypeDef)(SDRAM_HandleTypeDef *hsdram); -typedef void (*pSDRAM_DmaCallbackTypeDef)(DMA_HandleTypeDef *hdma); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SDRAM_Exported_Macros SDRAM Exported Macros - * @{ - */ - -/** @brief Reset SDRAM handle state - * @param __HANDLE__ specifies the SDRAM handle. - * @retval None - */ -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -#define __HAL_SDRAM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_SDRAM_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SDRAM_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SDRAM_STATE_RESET) -#endif -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SDRAM_Exported_Functions SDRAM Exported Functions - * @{ - */ - -/** @addtogroup SDRAM_Exported_Functions_Group1 - * @{ - */ - -/* Initialization/de-initialization functions *********************************/ -HAL_StatusTypeDef HAL_SDRAM_Init(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_TimingTypeDef *Timing); -HAL_StatusTypeDef HAL_SDRAM_DeInit(SDRAM_HandleTypeDef *hsdram); -void HAL_SDRAM_MspInit(SDRAM_HandleTypeDef *hsdram); -void HAL_SDRAM_MspDeInit(SDRAM_HandleTypeDef *hsdram); - -void HAL_SDRAM_IRQHandler(SDRAM_HandleTypeDef *hsdram); -void HAL_SDRAM_RefreshErrorCallback(SDRAM_HandleTypeDef *hsdram); -void HAL_SDRAM_DMA_XferCpltCallback(DMA_HandleTypeDef *hdma); -void HAL_SDRAM_DMA_XferErrorCallback(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** @addtogroup SDRAM_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ****************************************************/ -HAL_StatusTypeDef HAL_SDRAM_Read_8b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint8_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Write_8b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint8_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Read_16b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint16_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Write_16b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint16_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Read_32b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Write_32b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize); - -HAL_StatusTypeDef HAL_SDRAM_Read_DMA(SDRAM_HandleTypeDef *hsdram, uint32_t * pAddress, uint32_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Write_DMA(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize); - -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -/* SDRAM callback registering/unregistering */ -HAL_StatusTypeDef HAL_SDRAM_RegisterCallback(SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId, pSDRAM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SDRAM_UnRegisterCallback(SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId); -HAL_StatusTypeDef HAL_SDRAM_RegisterDmaCallback(SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId, pSDRAM_DmaCallbackTypeDef pCallback); -#endif - -/** - * @} - */ - -/** @addtogroup SDRAM_Exported_Functions_Group3 - * @{ - */ -/* SDRAM Control functions *****************************************************/ -HAL_StatusTypeDef HAL_SDRAM_WriteProtection_Enable(SDRAM_HandleTypeDef *hsdram); -HAL_StatusTypeDef HAL_SDRAM_WriteProtection_Disable(SDRAM_HandleTypeDef *hsdram); -HAL_StatusTypeDef HAL_SDRAM_SendCommand(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout); -HAL_StatusTypeDef HAL_SDRAM_ProgramRefreshRate(SDRAM_HandleTypeDef *hsdram, uint32_t RefreshRate); -HAL_StatusTypeDef HAL_SDRAM_SetAutoRefreshNumber(SDRAM_HandleTypeDef *hsdram, uint32_t AutoRefreshNumber); -uint32_t HAL_SDRAM_GetModeStatus(SDRAM_HandleTypeDef *hsdram); -/** - * @} - */ - -/** @addtogroup SDRAM_Exported_Functions_Group4 - * @{ - */ -/* SDRAM State functions ********************************************************/ -HAL_SDRAM_StateTypeDef HAL_SDRAM_GetState(SDRAM_HandleTypeDef *hsdram); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SDRAM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smartcard.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smartcard.h deleted file mode 100644 index 36f16c757c36028..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smartcard.h +++ /dev/null @@ -1,757 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_smartcard.h - * @author MCD Application Team - * @brief Header file of SMARTCARD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SMARTCARD_H -#define __STM32F4xx_HAL_SMARTCARD_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SMARTCARD - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SMARTCARD_Exported_Types SMARTCARD Exported Types - * @{ - */ - -/** - * @brief SMARTCARD Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the SmartCard communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (16 * (hsc->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 16) + 0.5 */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref SMARTCARD_Word_Length */ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref SMARTCARD_Stop_Bits */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref SMARTCARD_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits).*/ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref SMARTCARD_Mode */ - - uint32_t CLKPolarity; /*!< Specifies the steady state of the serial clock. - This parameter can be a value of @ref SMARTCARD_Clock_Polarity */ - - uint32_t CLKPhase; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref SMARTCARD_Clock_Phase */ - - uint32_t CLKLastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted - data bit (MSB) has to be output on the SCLK pin in synchronous mode. - This parameter can be a value of @ref SMARTCARD_Last_Bit */ - - uint32_t Prescaler; /*!< Specifies the SmartCard Prescaler value used for dividing the system clock - to provide the smartcard clock. The value given in the register (5 significant bits) - is multiplied by 2 to give the division factor of the source clock frequency. - This parameter can be a value of @ref SMARTCARD_Prescaler */ - - uint32_t GuardTime; /*!< Specifies the SmartCard Guard Time value in terms of number of baud clocks */ - - uint32_t NACKState; /*!< Specifies the SmartCard NACK Transmission state. - This parameter can be a value of @ref SMARTCARD_NACK_State */ -}SMARTCARD_InitTypeDef; - -/** - * @brief HAL SMARTCARD State structures definition - * @note HAL SMARTCARD State value is a combination of 2 different substates: gState and RxState. - * - gState contains SMARTCARD state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : (Not Used) - * 10 : Timeout - * 11 : Error - * b5 IP initialization status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized. HAL SMARTCARD Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (IP busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 IP initialization status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef enum -{ - HAL_SMARTCARD_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ - HAL_SMARTCARD_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ - HAL_SMARTCARD_STATE_BUSY = 0x24U, /*!< an internal process is ongoing - Value is allowed for gState only */ - HAL_SMARTCARD_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing - Value is allowed for gState only */ - HAL_SMARTCARD_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing - Value is allowed for RxState only */ - HAL_SMARTCARD_STATE_BUSY_TX_RX = 0x23U, /*!< Data Transmission and Reception process is ongoing - Not to be used for neither gState nor RxState. - Value is result of combination (Or) between gState and RxState values */ - HAL_SMARTCARD_STATE_TIMEOUT = 0xA0U, /*!< Timeout state - Value is allowed for gState only */ - HAL_SMARTCARD_STATE_ERROR = 0xE0U /*!< Error - Value is allowed for gState only */ -}HAL_SMARTCARD_StateTypeDef; - -/** - * @brief SMARTCARD handle Structure definition - */ -typedef struct __SMARTCARD_HandleTypeDef -{ - USART_TypeDef *Instance; /*!< USART registers base address */ - - SMARTCARD_InitTypeDef Init; /*!< SmartCard communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to SmartCard Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< SmartCard Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< SmartCard Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to SmartCard Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< SmartCard Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< SmartCard Rx Transfer Counter */ - - DMA_HandleTypeDef *hdmatx; /*!< SmartCard Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SmartCard Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_SMARTCARD_StateTypeDef gState; /*!< SmartCard state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_SMARTCARD_StateTypeDef */ - - __IO HAL_SMARTCARD_StateTypeDef RxState; /*!< SmartCard state information related to Rx operations. - This parameter can be a value of @ref HAL_SMARTCARD_StateTypeDef */ - - __IO uint32_t ErrorCode; /*!< SmartCard Error code */ - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - void (* TxCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Tx Complete Callback */ - - void (* RxCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Rx Complete Callback */ - - void (* ErrorCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Error Callback */ - - void (* AbortCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Abort Complete Callback */ - - void (* AbortTransmitCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Abort Transmit Complete Callback */ - - void (* AbortReceiveCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Abort Receive Complete Callback */ - - void (* MspInitCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Msp Init callback */ - - void (* MspDeInitCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Msp DeInit callback */ -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - -} SMARTCARD_HandleTypeDef; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SMARTCARD Callback ID enumeration definition - */ -typedef enum -{ - HAL_SMARTCARD_TX_COMPLETE_CB_ID = 0x00U, /*!< SMARTCARD Tx Complete Callback ID */ - HAL_SMARTCARD_RX_COMPLETE_CB_ID = 0x01U, /*!< SMARTCARD Rx Complete Callback ID */ - HAL_SMARTCARD_ERROR_CB_ID = 0x02U, /*!< SMARTCARD Error Callback ID */ - HAL_SMARTCARD_ABORT_COMPLETE_CB_ID = 0x03U, /*!< SMARTCARD Abort Complete Callback ID */ - HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID = 0x04U, /*!< SMARTCARD Abort Transmit Complete Callback ID */ - HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID = 0x05U, /*!< SMARTCARD Abort Receive Complete Callback ID */ - - HAL_SMARTCARD_MSPINIT_CB_ID = 0x08U, /*!< SMARTCARD MspInit callback ID */ - HAL_SMARTCARD_MSPDEINIT_CB_ID = 0x09U /*!< SMARTCARD MspDeInit callback ID */ - -} HAL_SMARTCARD_CallbackIDTypeDef; - -/** - * @brief HAL SMARTCARD Callback pointer definition - */ -typedef void (*pSMARTCARD_CallbackTypeDef)(SMARTCARD_HandleTypeDef *hsc); /*!< pointer to an SMARTCARD callback function */ - -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SMARTCARD_Exported_Constants SMARTCARD Exported constants - * @{ - */ - -/** @defgroup SMARTCARD_Error_Code SMARTCARD Error Code - * @{ - */ -#define HAL_SMARTCARD_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_SMARTCARD_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_SMARTCARD_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_SMARTCARD_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_SMARTCARD_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_SMARTCARD_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -#define HAL_SMARTCARD_ERROR_INVALID_CALLBACK 0x00000020U /*!< Invalid Callback error */ -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SMARTCARD_Word_Length SMARTCARD Word Length - * @{ - */ -#define SMARTCARD_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup SMARTCARD_Stop_Bits SMARTCARD Number of Stop Bits - * @{ - */ -#define SMARTCARD_STOPBITS_0_5 ((uint32_t)USART_CR2_STOP_0) -#define SMARTCARD_STOPBITS_1_5 ((uint32_t)(USART_CR2_STOP_0 | USART_CR2_STOP_1)) -/** - * @} - */ - -/** @defgroup SMARTCARD_Parity SMARTCARD Parity - * @{ - */ -#define SMARTCARD_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define SMARTCARD_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup SMARTCARD_Mode SMARTCARD Mode - * @{ - */ -#define SMARTCARD_MODE_RX ((uint32_t)USART_CR1_RE) -#define SMARTCARD_MODE_TX ((uint32_t)USART_CR1_TE) -#define SMARTCARD_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup SMARTCARD_Clock_Polarity SMARTCARD Clock Polarity - * @{ - */ -#define SMARTCARD_POLARITY_LOW 0x00000000U -#define SMARTCARD_POLARITY_HIGH ((uint32_t)USART_CR2_CPOL) -/** - * @} - */ - -/** @defgroup SMARTCARD_Clock_Phase SMARTCARD Clock Phase - * @{ - */ -#define SMARTCARD_PHASE_1EDGE 0x00000000U -#define SMARTCARD_PHASE_2EDGE ((uint32_t)USART_CR2_CPHA) -/** - * @} - */ - -/** @defgroup SMARTCARD_Last_Bit SMARTCARD Last Bit - * @{ - */ -#define SMARTCARD_LASTBIT_DISABLE 0x00000000U -#define SMARTCARD_LASTBIT_ENABLE ((uint32_t)USART_CR2_LBCL) -/** - * @} - */ - -/** @defgroup SMARTCARD_NACK_State SMARTCARD NACK State - * @{ - */ -#define SMARTCARD_NACK_ENABLE ((uint32_t)USART_CR3_NACK) -#define SMARTCARD_NACK_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup SMARTCARD_DMA_Requests SMARTCARD DMA requests - * @{ - */ -#define SMARTCARD_DMAREQ_TX ((uint32_t)USART_CR3_DMAT) -#define SMARTCARD_DMAREQ_RX ((uint32_t)USART_CR3_DMAR) -/** - * @} - */ - -/** @defgroup SMARTCARD_Prescaler SMARTCARD Prescaler - * @{ - */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV2 0x00000001U /*!< SYSCLK divided by 2 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV4 0x00000002U /*!< SYSCLK divided by 4 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV6 0x00000003U /*!< SYSCLK divided by 6 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV8 0x00000004U /*!< SYSCLK divided by 8 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV10 0x00000005U /*!< SYSCLK divided by 10 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV12 0x00000006U /*!< SYSCLK divided by 12 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV14 0x00000007U /*!< SYSCLK divided by 14 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV16 0x00000008U /*!< SYSCLK divided by 16 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV18 0x00000009U /*!< SYSCLK divided by 18 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV20 0x0000000AU /*!< SYSCLK divided by 20 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV22 0x0000000BU /*!< SYSCLK divided by 22 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV24 0x0000000CU /*!< SYSCLK divided by 24 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV26 0x0000000DU /*!< SYSCLK divided by 26 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV28 0x0000000EU /*!< SYSCLK divided by 28 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV30 0x0000000FU /*!< SYSCLK divided by 30 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV32 0x00000010U /*!< SYSCLK divided by 32 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV34 0x00000011U /*!< SYSCLK divided by 34 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV36 0x00000012U /*!< SYSCLK divided by 36 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV38 0x00000013U /*!< SYSCLK divided by 38 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV40 0x00000014U /*!< SYSCLK divided by 40 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV42 0x00000015U /*!< SYSCLK divided by 42 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV44 0x00000016U /*!< SYSCLK divided by 44 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV46 0x00000017U /*!< SYSCLK divided by 46 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV48 0x00000018U /*!< SYSCLK divided by 48 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV50 0x00000019U /*!< SYSCLK divided by 50 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV52 0x0000001AU /*!< SYSCLK divided by 52 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV54 0x0000001BU /*!< SYSCLK divided by 54 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV56 0x0000001CU /*!< SYSCLK divided by 56 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV58 0x0000001DU /*!< SYSCLK divided by 58 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV60 0x0000001EU /*!< SYSCLK divided by 60 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV62 0x0000001FU /*!< SYSCLK divided by 62 */ -/** - * @} - */ - -/** @defgroup SmartCard_Flags SMARTCARD Flags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define SMARTCARD_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define SMARTCARD_FLAG_TC ((uint32_t)USART_SR_TC) -#define SMARTCARD_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define SMARTCARD_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define SMARTCARD_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define SMARTCARD_FLAG_NE ((uint32_t)USART_SR_NE) -#define SMARTCARD_FLAG_FE ((uint32_t)USART_SR_FE) -#define SMARTCARD_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup SmartCard_Interrupt_definition SMARTCARD Interrupts Definition - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask in the Y register - * - Y : Interrupt source register (2bits) - * - 01: CR1 register - * - 11: CR3 register - * @{ - */ -#define SMARTCARD_IT_PE ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define SMARTCARD_IT_TXE ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define SMARTCARD_IT_TC ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define SMARTCARD_IT_RXNE ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define SMARTCARD_IT_IDLE ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) -#define SMARTCARD_IT_ERR ((uint32_t)(SMARTCARD_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SMARTCARD_Exported_Macros SMARTCARD Exported Macros - * @{ - */ - -/** @brief Reset SMARTCARD handle gstate & RxState - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#if USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1 -#define __HAL_SMARTCARD_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_SMARTCARD_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_SMARTCARD_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_SMARTCARD_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_SMARTCARD_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_SMARTCARD_STATE_RESET; \ - } while(0U) -#endif /*USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - -/** @brief Flush the Smartcard DR register - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) - -/** @brief Check whether the specified Smartcard flag is set or not. - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SMARTCARD_FLAG_TXE: Transmit data register empty flag - * @arg SMARTCARD_FLAG_TC: Transmission Complete flag - * @arg SMARTCARD_FLAG_RXNE: Receive data register not empty flag - * @arg SMARTCARD_FLAG_IDLE: Idle Line detection flag - * @arg SMARTCARD_FLAG_ORE: Overrun Error flag - * @arg SMARTCARD_FLAG_NE: Noise Error flag - * @arg SMARTCARD_FLAG_FE: Framing Error flag - * @arg SMARTCARD_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SMARTCARD_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified Smartcard pending flags. - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg SMARTCARD_FLAG_TC: Transmission Complete flag. - * @arg SMARTCARD_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error) and ORE (Overrun - * error) flags are cleared by software sequence: a read operation to - * USART_SR register followed by a read operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clear the SMARTCARD PE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clear the SMARTCARD FE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_FEFLAG(__HANDLE__) __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the SMARTCARD NE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_NEFLAG(__HANDLE__) __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the SMARTCARD ORE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_OREFLAG(__HANDLE__) __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the SMARTCARD IDLE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_IDLEFLAG(__HANDLE__) __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enable the specified SmartCard interrupt. - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __INTERRUPT__ specifies the SMARTCARD interrupt to enable. - * This parameter can be one of the following values: - * @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt - * @arg SMARTCARD_IT_TC: Transmission complete interrupt - * @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt - * @arg SMARTCARD_IT_IDLE: Idle line detection interrupt - * @arg SMARTCARD_IT_PE: Parity Error interrupt - * @arg SMARTCARD_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_SMARTCARD_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == SMARTCARD_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & SMARTCARD_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & SMARTCARD_IT_MASK))) - -/** @brief Disable the specified SmartCard interrupt. - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __INTERRUPT__ specifies the SMARTCARD interrupt to disable. - * This parameter can be one of the following values: - * @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt - * @arg SMARTCARD_IT_TC: Transmission complete interrupt - * @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt - * @arg SMARTCARD_IT_IDLE: Idle line detection interrupt - * @arg SMARTCARD_IT_PE: Parity Error interrupt - * @arg SMARTCARD_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_SMARTCARD_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == SMARTCARD_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & SMARTCARD_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & SMARTCARD_IT_MASK))) - -/** @brief Checks whether the specified SmartCard interrupt has occurred or not. - * @param __HANDLE__ specifies the SmartCard Handle. - * @param __IT__ specifies the SMARTCARD interrupt source to check. - * This parameter can be one of the following values: - * @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt - * @arg SMARTCARD_IT_TC: Transmission complete interrupt - * @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt - * @arg SMARTCARD_IT_IDLE: Idle line detection interrupt - * @arg SMARTCARD_IT_ERR: Error interrupt - * @arg SMARTCARD_IT_PE: Parity Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_SMARTCARD_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == SMARTCARD_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1: (__HANDLE__)->Instance->CR3) & (((uint32_t)(__IT__)) & SMARTCARD_IT_MASK)) - -/** @brief Macro to enable the SMARTCARD's one bit sample method - * @param __HANDLE__ specifies the SMARTCARD Handle. - * @retval None - */ -#define __HAL_SMARTCARD_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3|= USART_CR3_ONEBIT) - -/** @brief Macro to disable the SMARTCARD's one bit sample method - * @param __HANDLE__ specifies the SMARTCARD Handle. - * @retval None - */ -#define __HAL_SMARTCARD_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable the USART associated to the SMARTCARD Handle - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) - -/** @brief Disable the USART associated to the SMARTCARD Handle - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) - -/** @brief Macros to enable the SmartCard DMA request. - * @param __HANDLE__ specifies the SmartCard Handle. - * @param __REQUEST__ specifies the SmartCard DMA request. - * This parameter can be one of the following values: - * @arg SMARTCARD_DMAREQ_TX: SmartCard DMA transmit request - * @arg SMARTCARD_DMAREQ_RX: SmartCard DMA receive request - * @retval None - */ -#define __HAL_SMARTCARD_DMA_REQUEST_ENABLE(__HANDLE__, __REQUEST__) ((__HANDLE__)->Instance->CR3 |= (__REQUEST__)) - -/** @brief Macros to disable the SmartCard DMA request. - * @param __HANDLE__ specifies the SmartCard Handle. - * @param __REQUEST__ specifies the SmartCard DMA request. - * This parameter can be one of the following values: - * @arg SMARTCARD_DMAREQ_TX: SmartCard DMA transmit request - * @arg SMARTCARD_DMAREQ_RX: SmartCard DMA receive request - * @retval None - */ -#define __HAL_SMARTCARD_DMA_REQUEST_DISABLE(__HANDLE__, __REQUEST__) ((__HANDLE__)->Instance->CR3 &= ~(__REQUEST__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SMARTCARD_Exported_Functions - * @{ - */ - -/** @addtogroup SMARTCARD_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_SMARTCARD_Init(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_ReInit(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_DeInit(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_MspInit(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_MspDeInit(SMARTCARD_HandleTypeDef *hsc); -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_SMARTCARD_RegisterCallback(SMARTCARD_HandleTypeDef *hsc, HAL_SMARTCARD_CallbackIDTypeDef CallbackID, pSMARTCARD_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SMARTCARD_UnRegisterCallback(SMARTCARD_HandleTypeDef *hsc, HAL_SMARTCARD_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup SMARTCARD_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_SMARTCARD_Transmit(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SMARTCARD_Receive(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SMARTCARD_Transmit_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SMARTCARD_Receive_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_SMARTCARD_Abort(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_Abort_IT(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit_IT(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive_IT(SMARTCARD_HandleTypeDef *hsc); - -void HAL_SMARTCARD_IRQHandler(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_TxCpltCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_RxCpltCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_ErrorCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_AbortCpltCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_AbortTransmitCpltCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_AbortReceiveCpltCallback(SMARTCARD_HandleTypeDef *hsc); -/** - * @} - */ - -/** @addtogroup SMARTCARD_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions **************************************************/ -HAL_SMARTCARD_StateTypeDef HAL_SMARTCARD_GetState(SMARTCARD_HandleTypeDef *hsc); -uint32_t HAL_SMARTCARD_GetError(SMARTCARD_HandleTypeDef *hsc); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SMARTCARD_Private_Constants SMARTCARD Private Constants - * @{ - */ - -/** @brief SMARTCARD interruptions flag mask - * - */ -#define SMARTCARD_IT_MASK ((uint32_t) USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RXNEIE | \ - USART_CR1_IDLEIE | USART_CR3_EIE ) - -#define SMARTCARD_CR1_REG_INDEX 1U -#define SMARTCARD_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros --------------------------------------------------------*/ -/** @defgroup SMARTCARD_Private_Macros SMARTCARD Private Macros - * @{ - */ -#define IS_SMARTCARD_WORD_LENGTH(LENGTH) ((LENGTH) == SMARTCARD_WORDLENGTH_9B) -#define IS_SMARTCARD_STOPBITS(STOPBITS) (((STOPBITS) == SMARTCARD_STOPBITS_0_5) || \ - ((STOPBITS) == SMARTCARD_STOPBITS_1_5)) -#define IS_SMARTCARD_PARITY(PARITY) (((PARITY) == SMARTCARD_PARITY_EVEN) || \ - ((PARITY) == SMARTCARD_PARITY_ODD)) -#define IS_SMARTCARD_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x000000U)) -#define IS_SMARTCARD_POLARITY(CPOL) (((CPOL) == SMARTCARD_POLARITY_LOW) || ((CPOL) == SMARTCARD_POLARITY_HIGH)) -#define IS_SMARTCARD_PHASE(CPHA) (((CPHA) == SMARTCARD_PHASE_1EDGE) || ((CPHA) == SMARTCARD_PHASE_2EDGE)) -#define IS_SMARTCARD_LASTBIT(LASTBIT) (((LASTBIT) == SMARTCARD_LASTBIT_DISABLE) || \ - ((LASTBIT) == SMARTCARD_LASTBIT_ENABLE)) -#define IS_SMARTCARD_NACK_STATE(NACK) (((NACK) == SMARTCARD_NACK_ENABLE) || \ - ((NACK) == SMARTCARD_NACK_DISABLE)) -#define IS_SMARTCARD_BAUDRATE(BAUDRATE) ((BAUDRATE) < 10500001U) - -#define SMARTCARD_DIV(__PCLK__, __BAUD__) ((uint32_t)((((uint64_t)(__PCLK__))*25U)/(4U*((uint64_t)(__BAUD__))))) -#define SMARTCARD_DIVMANT(__PCLK__, __BAUD__) (SMARTCARD_DIV((__PCLK__), (__BAUD__))/100U) -#define SMARTCARD_DIVFRAQ(__PCLK__, __BAUD__) ((((SMARTCARD_DIV((__PCLK__), (__BAUD__)) - (SMARTCARD_DIVMANT((__PCLK__), (__BAUD__)) * 100U)) * 16U) + 50U) / 100U) -/* SMARTCARD BRR = mantissa + overflow + fraction - = (SMARTCARD DIVMANT << 4) + (SMARTCARD DIVFRAQ & 0xF0) + (SMARTCARD DIVFRAQ & 0x0FU) */ -#define SMARTCARD_BRR(__PCLK__, __BAUD__) (((SMARTCARD_DIVMANT((__PCLK__), (__BAUD__)) << 4U) + \ - (SMARTCARD_DIVFRAQ((__PCLK__), (__BAUD__)) & 0xF0U)) + \ - (SMARTCARD_DIVFRAQ((__PCLK__), (__BAUD__)) & 0x0FU)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SMARTCARD_Private_Functions SMARTCARD Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SMARTCARD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smbus.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smbus.h deleted file mode 100644 index 056a600d175b89d..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smbus.h +++ /dev/null @@ -1,733 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_smbus.h - * @author MCD Application Team - * @brief Header file of SMBUS HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SMBUS_H -#define __STM32F4xx_HAL_SMBUS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SMBUS - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SMBUS_Exported_Types SMBUS Exported Types - * @{ - */ - -/** - * @brief SMBUS Configuration Structure definition - */ -typedef struct -{ - uint32_t ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 100kHz */ - - uint32_t AnalogFilter; /*!< Specifies if Analog Filter is enable or not. - This parameter can be a value of @ref SMBUS_Analog_Filter */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected. - This parameter can be a value of @ref SMBUS_addressing_mode */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref SMBUS_dual_addressing_mode */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is - selected. This parameter can be a 7-bit address. */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref SMBUS_general_call_addressing_mode */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref SMBUS_nostretch_mode */ - - uint32_t PacketErrorCheckMode; /*!< Specifies if Packet Error Check mode is selected. - This parameter can be a value of @ref SMBUS_packet_error_check_mode */ - - uint32_t PeripheralMode; /*!< Specifies which mode of Periphal is selected. - This parameter can be a value of @ref SMBUS_peripheral_mode */ - -} SMBUS_InitTypeDef; - -/** - * @brief HAL State structure definition - * @note HAL SMBUS State value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : Abort (Abort user request on going) - * 10 : Timeout - * 11 : Error - * b5 IP initialisation status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized and ready to use. HAL SMBUS Init function called) - * b4 (not used) - * x : Should be set to 0 - * b3 - * 0 : Ready or Busy (No Listen mode ongoing) - * 1 : Listen (IP in Address Listen Mode) - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (IP busy with some configuration or internal operations) - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - */ -typedef enum -{ - - HAL_SMBUS_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_SMBUS_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */ - HAL_SMBUS_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */ - HAL_SMBUS_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */ - HAL_SMBUS_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_SMBUS_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */ - HAL_SMBUS_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission - process is ongoing */ - HAL_SMBUS_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception - process is ongoing */ - HAL_SMBUS_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ - HAL_SMBUS_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */ - HAL_SMBUS_STATE_ERROR = 0xE0U /*!< Error */ -} HAL_SMBUS_StateTypeDef; - -/** - * @brief HAL Mode structure definition - * @note HAL SMBUS Mode value coding follow below described bitmap : - * b7 (not used) - * x : Should be set to 0 - * b6 (not used) - * x : Should be set to 0 - * b5 - * 0 : None - * 1 : Slave (HAL SMBUS communication is in Slave/Device Mode) - * b4 - * 0 : None - * 1 : Master (HAL SMBUS communication is in Master/Host Mode) - * b3-b2-b1-b0 (not used) - * xxxx : Should be set to 0000 - */ -typedef enum -{ - HAL_SMBUS_MODE_NONE = 0x00U, /*!< No SMBUS communication on going */ - HAL_SMBUS_MODE_MASTER = 0x10U, /*!< SMBUS communication is in Master Mode */ - HAL_SMBUS_MODE_SLAVE = 0x20U, /*!< SMBUS communication is in Slave Mode */ - -} HAL_SMBUS_ModeTypeDef; - -/** - * @brief SMBUS handle Structure definition - */ -typedef struct __SMBUS_HandleTypeDef -{ - I2C_TypeDef *Instance; /*!< SMBUS registers base address */ - - SMBUS_InitTypeDef Init; /*!< SMBUS communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to SMBUS transfer buffer */ - - uint16_t XferSize; /*!< SMBUS transfer size */ - - __IO uint16_t XferCount; /*!< SMBUS transfer counter */ - - __IO uint32_t XferOptions; /*!< SMBUS transfer options this parameter can - be a value of @ref SMBUS_OPTIONS */ - - __IO uint32_t PreviousState; /*!< SMBUS communication Previous state and mode - context for internal usage */ - - HAL_LockTypeDef Lock; /*!< SMBUS locking object */ - - __IO HAL_SMBUS_StateTypeDef State; /*!< SMBUS communication state */ - - __IO HAL_SMBUS_ModeTypeDef Mode; /*!< SMBUS communication mode */ - - __IO uint32_t ErrorCode; /*!< SMBUS Error code */ - - __IO uint32_t Devaddress; /*!< SMBUS Target device address */ - - __IO uint32_t EventCount; /*!< SMBUS Event counter */ - - uint8_t XferPEC; /*!< SMBUS PEC data in reception mode */ - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Listen Complete callback */ - void (* MemTxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Memory Tx Transfer completed callback */ - void (* MemRxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Memory Rx Transfer completed callback */ - void (* ErrorCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Error callback */ - void (* AbortCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Abort callback */ - void (* AddrCallback)(struct __SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< SMBUS Slave Address Match callback */ - void (* MspInitCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Msp Init callback */ - void (* MspDeInitCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Msp DeInit callback */ - -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ -} SMBUS_HandleTypeDef; - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SMBUS Callback ID enumeration definition - */ -typedef enum -{ - HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< SMBUS Master Tx Transfer completed callback ID */ - HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< SMBUS Master Rx Transfer completed callback ID */ - HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< SMBUS Slave Tx Transfer completed callback ID */ - HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< SMBUS Slave Rx Transfer completed callback ID */ - HAL_SMBUS_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< SMBUS Listen Complete callback ID */ - HAL_SMBUS_ERROR_CB_ID = 0x07U, /*!< SMBUS Error callback ID */ - HAL_SMBUS_ABORT_CB_ID = 0x08U, /*!< SMBUS Abort callback ID */ - HAL_SMBUS_MSPINIT_CB_ID = 0x09U, /*!< SMBUS Msp Init callback ID */ - HAL_SMBUS_MSPDEINIT_CB_ID = 0x0AU /*!< SMBUS Msp DeInit callback ID */ - -} HAL_SMBUS_CallbackIDTypeDef; - -/** - * @brief HAL SMBUS Callback pointer definition - */ -typedef void (*pSMBUS_CallbackTypeDef)(SMBUS_HandleTypeDef *hsmbus); /*!< pointer to an I2C callback function */ -typedef void (*pSMBUS_AddrCallbackTypeDef)(SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< pointer to an I2C Address Match callback function */ - -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SMBUS_Exported_Constants SMBUS Exported Constants - * @{ - */ - -/** @defgroup SMBUS_Error_Code_definition SMBUS Error Code - * @brief SMBUS Error Code - * @{ - */ -#define HAL_SMBUS_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_SMBUS_ERROR_BERR 0x00000001U /*!< BERR error */ -#define HAL_SMBUS_ERROR_ARLO 0x00000002U /*!< ARLO error */ -#define HAL_SMBUS_ERROR_AF 0x00000004U /*!< AF error */ -#define HAL_SMBUS_ERROR_OVR 0x00000008U /*!< OVR error */ -#define HAL_SMBUS_ERROR_TIMEOUT 0x00000010U /*!< Timeout Error */ -#define HAL_SMBUS_ERROR_ALERT 0x00000020U /*!< Alert error */ -#define HAL_SMBUS_ERROR_PECERR 0x00000040U /*!< PEC error */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -#define HAL_SMBUS_ERROR_INVALID_CALLBACK 0x00000080U /*!< Invalid Callback error */ -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup SMBUS_Analog_Filter SMBUS Analog Filter - * @{ - */ -#define SMBUS_ANALOGFILTER_ENABLE 0x00000000U -#define SMBUS_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF -/** - * @} - */ - -/** @defgroup SMBUS_addressing_mode SMBUS addressing mode - * @{ - */ -#define SMBUS_ADDRESSINGMODE_7BIT 0x00004000U -#define SMBUS_ADDRESSINGMODE_10BIT (I2C_OAR1_ADDMODE | 0x00004000U) -/** - * @} - */ - -/** @defgroup SMBUS_dual_addressing_mode SMBUS dual addressing mode - * @{ - */ -#define SMBUS_DUALADDRESS_DISABLE 0x00000000U -#define SMBUS_DUALADDRESS_ENABLE I2C_OAR2_ENDUAL -/** - * @} - */ - -/** @defgroup SMBUS_general_call_addressing_mode SMBUS general call addressing mode - * @{ - */ -#define SMBUS_GENERALCALL_DISABLE 0x00000000U -#define SMBUS_GENERALCALL_ENABLE I2C_CR1_ENGC -/** - * @} - */ - -/** @defgroup SMBUS_nostretch_mode SMBUS nostretch mode - * @{ - */ -#define SMBUS_NOSTRETCH_DISABLE 0x00000000U -#define SMBUS_NOSTRETCH_ENABLE I2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup SMBUS_packet_error_check_mode SMBUS packet error check mode - * @{ - */ -#define SMBUS_PEC_DISABLE 0x00000000U -#define SMBUS_PEC_ENABLE I2C_CR1_ENPEC -/** - * @} - */ - -/** @defgroup SMBUS_peripheral_mode SMBUS peripheral mode -* @{ -*/ -#define SMBUS_PERIPHERAL_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP) -#define SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE I2C_CR1_SMBUS -#define SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE_ARP (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_ENARP) -/** -* @} -*/ - -/** @defgroup SMBUS_XferDirection_definition SMBUS XferDirection definition - * @{ - */ -#define SMBUS_DIRECTION_RECEIVE 0x00000000U -#define SMBUS_DIRECTION_TRANSMIT 0x00000001U -/** - * @} - */ - -/** @defgroup SMBUS_XferOptions_definition SMBUS XferOptions definition - * @{ - */ -#define SMBUS_FIRST_FRAME 0x00000001U -#define SMBUS_NEXT_FRAME 0x00000002U -#define SMBUS_FIRST_AND_LAST_FRAME_NO_PEC 0x00000003U -#define SMBUS_LAST_FRAME_NO_PEC 0x00000004U -#define SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC 0x00000005U -#define SMBUS_LAST_FRAME_WITH_PEC 0x00000006U -/** - * @} - */ - -/** @defgroup SMBUS_Interrupt_configuration_definition SMBUS Interrupt configuration definition - * @{ - */ -#define SMBUS_IT_BUF I2C_CR2_ITBUFEN -#define SMBUS_IT_EVT I2C_CR2_ITEVTEN -#define SMBUS_IT_ERR I2C_CR2_ITERREN -/** - * @} - */ - -/** @defgroup SMBUS_Flag_definition SMBUS Flag definition - * @{ - */ -#define SMBUS_FLAG_SMBALERT 0x00018000U -#define SMBUS_FLAG_TIMEOUT 0x00014000U -#define SMBUS_FLAG_PECERR 0x00011000U -#define SMBUS_FLAG_OVR 0x00010800U -#define SMBUS_FLAG_AF 0x00010400U -#define SMBUS_FLAG_ARLO 0x00010200U -#define SMBUS_FLAG_BERR 0x00010100U -#define SMBUS_FLAG_TXE 0x00010080U -#define SMBUS_FLAG_RXNE 0x00010040U -#define SMBUS_FLAG_STOPF 0x00010010U -#define SMBUS_FLAG_ADD10 0x00010008U -#define SMBUS_FLAG_BTF 0x00010004U -#define SMBUS_FLAG_ADDR 0x00010002U -#define SMBUS_FLAG_SB 0x00010001U -#define SMBUS_FLAG_DUALF 0x00100080U -#define SMBUS_FLAG_SMBHOST 0x00100040U -#define SMBUS_FLAG_SMBDEFAULT 0x00100020U -#define SMBUS_FLAG_GENCALL 0x00100010U -#define SMBUS_FLAG_TRA 0x00100004U -#define SMBUS_FLAG_BUSY 0x00100002U -#define SMBUS_FLAG_MSL 0x00100001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SMBUS_Exported_Macros SMBUS Exported Macros - * @{ - */ - -/** @brief Reset SMBUS handle state - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @retval None - */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -#define __HAL_SMBUS_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_SMBUS_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SMBUS_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SMBUS_STATE_RESET) -#endif - -/** @brief Enable or disable the specified SMBUS interrupts. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg SMBUS_IT_BUF: Buffer interrupt enable - * @arg SMBUS_IT_EVT: Event interrupt enable - * @arg SMBUS_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_SMBUS_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR2 |= (__INTERRUPT__)) -#define __HAL_SMBUS_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR2 &= (~(__INTERRUPT__))) - -/** @brief Checks if the specified SMBUS interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @param __INTERRUPT__ specifies the SMBUS interrupt source to check. - * This parameter can be one of the following values: - * @arg SMBUS_IT_BUF: Buffer interrupt enable - * @arg SMBUS_IT_EVT: Event interrupt enable - * @arg SMBUS_IT_ERR: Error interrupt enable - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_SMBUS_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified SMBUS flag is set or not. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SMBUS_FLAG_SMBALERT: SMBus Alert flag - * @arg SMBUS_FLAG_TIMEOUT: Timeout or Tlow error flag - * @arg SMBUS_FLAG_PECERR: PEC error in reception flag - * @arg SMBUS_FLAG_OVR: Overrun/Underrun flag - * @arg SMBUS_FLAG_AF: Acknowledge failure flag - * @arg SMBUS_FLAG_ARLO: Arbitration lost flag - * @arg SMBUS_FLAG_BERR: Bus error flag - * @arg SMBUS_FLAG_TXE: Data register empty flag - * @arg SMBUS_FLAG_RXNE: Data register not empty flag - * @arg SMBUS_FLAG_STOPF: Stop detection flag - * @arg SMBUS_FLAG_ADD10: 10-bit header sent flag - * @arg SMBUS_FLAG_BTF: Byte transfer finished flag - * @arg SMBUS_FLAG_ADDR: Address sent flag - * Address matched flag - * @arg SMBUS_FLAG_SB: Start bit flag - * @arg SMBUS_FLAG_DUALF: Dual flag - * @arg SMBUS_FLAG_SMBHOST: SMBus host header - * @arg SMBUS_FLAG_SMBDEFAULT: SMBus default header - * @arg SMBUS_FLAG_GENCALL: General call header flag - * @arg SMBUS_FLAG_TRA: Transmitter/Receiver flag - * @arg SMBUS_FLAG_BUSY: Bus busy flag - * @arg SMBUS_FLAG_MSL: Master/Slave flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SMBUS_GET_FLAG(__HANDLE__, __FLAG__) ((((uint8_t)((__FLAG__) >> 16U)) == 0x01U)?((((__HANDLE__)->Instance->SR1) & ((__FLAG__) & SMBUS_FLAG_MASK)) == ((__FLAG__) & SMBUS_FLAG_MASK)): \ - ((((__HANDLE__)->Instance->SR2) & ((__FLAG__) & SMBUS_FLAG_MASK)) == ((__FLAG__) & SMBUS_FLAG_MASK))) - -/** @brief Clears the SMBUS pending flags which are cleared by writing 0 in a specific bit. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg SMBUS_FLAG_SMBALERT: SMBus Alert flag - * @arg SMBUS_FLAG_TIMEOUT: Timeout or Tlow error flag - * @arg SMBUS_FLAG_PECERR: PEC error in reception flag - * @arg SMBUS_FLAG_OVR: Overrun/Underrun flag (Slave mode) - * @arg SMBUS_FLAG_AF: Acknowledge failure flag - * @arg SMBUS_FLAG_ARLO: Arbitration lost flag (Master mode) - * @arg SMBUS_FLAG_BERR: Bus error flag - * @retval None - */ -#define __HAL_SMBUS_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR1 = ~((__FLAG__) & SMBUS_FLAG_MASK)) - -/** @brief Clears the SMBUS ADDR pending flag. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @retval None - */ -#define __HAL_SMBUS_CLEAR_ADDRFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - tmpreg = (__HANDLE__)->Instance->SR2; \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Clears the SMBUS STOPF pending flag. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @retval None - */ -#define __HAL_SMBUS_CLEAR_STOPFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - (__HANDLE__)->Instance->CR1 |= I2C_CR1_PE; \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Enable the SMBUS peripheral. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral. - * @retval None - */ -#define __HAL_SMBUS_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= I2C_CR1_PE) - -/** @brief Disable the SMBUS peripheral. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral. - * @retval None - */ -#define __HAL_SMBUS_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~I2C_CR1_PE) - -/** @brief Generate a Non-Acknowledge SMBUS peripheral in Slave mode. - * @param __HANDLE__ specifies the SMBUS Handle. - * @retval None - */ -#define __HAL_SMBUS_GENERATE_NACK(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_ACK)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SMBUS_Exported_Functions - * @{ - */ - -/** @addtogroup SMBUS_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_SMBUS_Init(SMBUS_HandleTypeDef *hsmbus); -HAL_StatusTypeDef HAL_SMBUS_DeInit(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_MspInit(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_MspDeInit(SMBUS_HandleTypeDef *hsmbus); - -/* Callbacks Register/UnRegister functions ************************************/ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_SMBUS_RegisterCallback(SMBUS_HandleTypeDef *hsmbus, HAL_SMBUS_CallbackIDTypeDef CallbackID, pSMBUS_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SMBUS_UnRegisterCallback(SMBUS_HandleTypeDef *hsmbus, HAL_SMBUS_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_SMBUS_RegisterAddrCallback(SMBUS_HandleTypeDef *hsmbus, pSMBUS_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SMBUS_UnRegisterAddrCallback(SMBUS_HandleTypeDef *hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup SMBUS_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ - -/* IO operation functions *****************************************************/ -/** @addtogroup Blocking_mode_Polling Blocking mode Polling - * @{ - */ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_SMBUS_IsDeviceReady(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup Non-Blocking_mode_Interrupt Non-Blocking mode Interrupt - * @{ - */ -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_SMBUS_Master_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_SMBUS_Master_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_SMBUS_Master_Abort_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress); -HAL_StatusTypeDef HAL_SMBUS_Slave_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_SMBUS_Slave_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions); - -HAL_StatusTypeDef HAL_SMBUS_EnableAlert_IT(SMBUS_HandleTypeDef *hsmbus); -HAL_StatusTypeDef HAL_SMBUS_DisableAlert_IT(SMBUS_HandleTypeDef *hsmbus); -HAL_StatusTypeDef HAL_SMBUS_EnableListen_IT(SMBUS_HandleTypeDef *hsmbus); -HAL_StatusTypeDef HAL_SMBUS_DisableListen_IT(SMBUS_HandleTypeDef *hsmbus); - -/****** Filter Configuration functions */ -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -HAL_StatusTypeDef HAL_SMBUS_ConfigAnalogFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_SMBUS_ConfigDigitalFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t DigitalFilter); -#endif -/** - * @} - */ - -/** @addtogroup SMBUS_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* SMBUS IRQHandler and Callbacks used in non blocking modes (Interrupt) */ -void HAL_SMBUS_EV_IRQHandler(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_ER_IRQHandler(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_MasterTxCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_MasterRxCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_SlaveTxCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_SlaveRxCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_AddrCallback(SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_SMBUS_ListenCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_ErrorCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_AbortCpltCallback(SMBUS_HandleTypeDef *hsmbus); - -/** - * @} - */ - -/** @addtogroup SMBUS_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @{ - */ - -/* Peripheral State, mode and Errors functions **************************************************/ -HAL_SMBUS_StateTypeDef HAL_SMBUS_GetState(SMBUS_HandleTypeDef *hsmbus); -HAL_SMBUS_ModeTypeDef HAL_SMBUS_GetMode(SMBUS_HandleTypeDef *hsmbus); -uint32_t HAL_SMBUS_GetError(SMBUS_HandleTypeDef *hsmbus); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SMBUS_Private_Constants SMBUS Private Constants - * @{ - */ -#define SMBUS_FLAG_MASK 0x0000FFFFU -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SMBUS_Private_Macros SMBUS Private Macros - * @{ - */ - -#define SMBUS_FREQRANGE(__PCLK__) ((__PCLK__)/1000000U) - -#define SMBUS_RISE_TIME(__FREQRANGE__) ( ((__FREQRANGE__) + 1U)) - -#define SMBUS_SPEED_STANDARD(__PCLK__, __SPEED__) (((((__PCLK__)/((__SPEED__) << 1U)) & I2C_CCR_CCR) < 4U)? 4U:((__PCLK__) / ((__SPEED__) << 1U))) - -#define SMBUS_7BIT_ADD_WRITE(__ADDRESS__) ((uint8_t)((__ADDRESS__) & (~I2C_OAR1_ADD0))) - -#define SMBUS_7BIT_ADD_READ(__ADDRESS__) ((uint8_t)((__ADDRESS__) | I2C_OAR1_ADD0)) - -#define SMBUS_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) - -#define SMBUS_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)0x00F0))) - -#define SMBUS_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)(0x00F1)))) - -#define SMBUS_GET_PEC_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR1 & I2C_CR1_ENPEC) - -#define SMBUS_GET_PEC_VALUE(__HANDLE__) ((__HANDLE__)->XferPEC) - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -#define IS_SMBUS_ANALOG_FILTER(FILTER) (((FILTER) == SMBUS_ANALOGFILTER_ENABLE) || \ - ((FILTER) == SMBUS_ANALOGFILTER_DISABLE)) -#define IS_SMBUS_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) -#endif -#define IS_SMBUS_ADDRESSING_MODE(ADDRESS) (((ADDRESS) == SMBUS_ADDRESSINGMODE_7BIT) || \ - ((ADDRESS) == SMBUS_ADDRESSINGMODE_10BIT)) - -#define IS_SMBUS_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == SMBUS_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == SMBUS_DUALADDRESS_ENABLE)) - -#define IS_SMBUS_GENERAL_CALL(CALL) (((CALL) == SMBUS_GENERALCALL_DISABLE) || \ - ((CALL) == SMBUS_GENERALCALL_ENABLE)) - -#define IS_SMBUS_NO_STRETCH(STRETCH) (((STRETCH) == SMBUS_NOSTRETCH_DISABLE) || \ - ((STRETCH) == SMBUS_NOSTRETCH_ENABLE)) - -#define IS_SMBUS_PEC(PEC) (((PEC) == SMBUS_PEC_DISABLE) || \ - ((PEC) == SMBUS_PEC_ENABLE)) - -#define IS_SMBUS_PERIPHERAL_MODE(MODE) (((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_HOST) || \ - ((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE) || \ - ((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE_ARP)) - -#define IS_SMBUS_CLOCK_SPEED(SPEED) (((SPEED) > 0U) && ((SPEED) <= 100000U)) - -#define IS_SMBUS_OWN_ADDRESS1(ADDRESS1) (((ADDRESS1) & 0xFFFFFC00U) == 0U) - -#define IS_SMBUS_OWN_ADDRESS2(ADDRESS2) (((ADDRESS2) & 0xFFFFFF01U) == 0U) - -#define IS_SMBUS_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == SMBUS_FIRST_FRAME) || \ - ((REQUEST) == SMBUS_NEXT_FRAME) || \ - ((REQUEST) == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == SMBUS_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || \ - ((REQUEST) == SMBUS_LAST_FRAME_WITH_PEC)) - -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup SMBUS_Private_Functions SMBUS Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** -* @} -*/ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_SMBUS_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spdifrx.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spdifrx.h deleted file mode 100644 index 73e30d22835a965..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spdifrx.h +++ /dev/null @@ -1,600 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_spdifrx.h - * @author MCD Application Team - * @brief Header file of SPDIFRX HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_SPDIFRX_H -#define STM32F4xx_HAL_SPDIFRX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(STM32F446xx) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (SPDIFRX) - -/** @addtogroup SPDIFRX - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SPDIFRX_Exported_Types SPDIFRX Exported Types - * @{ - */ - -/** - * @brief SPDIFRX Init structure definition - */ -typedef struct -{ - uint32_t InputSelection; /*!< Specifies the SPDIF input selection. - This parameter can be a value of @ref SPDIFRX_Input_Selection */ - - uint32_t Retries; /*!< Specifies the Maximum allowed re-tries during synchronization phase. - This parameter can be a value of @ref SPDIFRX_Max_Retries */ - - uint32_t WaitForActivity; /*!< Specifies the wait for activity on SPDIF selected input. - This parameter can be a value of @ref SPDIFRX_Wait_For_Activity. */ - - uint32_t ChannelSelection; /*!< Specifies whether the control flow will take the channel status from channel A or B. - This parameter can be a value of @ref SPDIFRX_Channel_Selection */ - - uint32_t DataFormat; /*!< Specifies the Data samples format (LSB, MSB, ...). - This parameter can be a value of @ref SPDIFRX_Data_Format */ - - uint32_t StereoMode; /*!< Specifies whether the peripheral is in stereo or mono mode. - This parameter can be a value of @ref SPDIFRX_Stereo_Mode */ - - uint32_t PreambleTypeMask; /*!< Specifies whether The preamble type bits are copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_PT_Mask */ - - uint32_t ChannelStatusMask; /*!< Specifies whether the channel status and user bits are copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_ChannelStatus_Mask */ - - uint32_t ValidityBitMask; /*!< Specifies whether the validity bit is copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_V_Mask */ - - uint32_t ParityErrorMask; /*!< Specifies whether the parity error bit is copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_PE_Mask */ -} SPDIFRX_InitTypeDef; - -/** - * @brief SPDIFRX SetDataFormat structure definition - */ -typedef struct -{ - uint32_t DataFormat; /*!< Specifies the Data samples format (LSB, MSB, ...). - This parameter can be a value of @ref SPDIFRX_Data_Format */ - - uint32_t StereoMode; /*!< Specifies whether the peripheral is in stereo or mono mode. - This parameter can be a value of @ref SPDIFRX_Stereo_Mode */ - - uint32_t PreambleTypeMask; /*!< Specifies whether The preamble type bits are copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_PT_Mask */ - - uint32_t ChannelStatusMask; /*!< Specifies whether the channel status and user bits are copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_ChannelStatus_Mask */ - - uint32_t ValidityBitMask; /*!< Specifies whether the validity bit is copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_V_Mask */ - - uint32_t ParityErrorMask; /*!< Specifies whether the parity error bit is copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_PE_Mask */ - -} SPDIFRX_SetDataFormatTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_SPDIFRX_STATE_RESET = 0x00U, /*!< SPDIFRX not yet initialized or disabled */ - HAL_SPDIFRX_STATE_READY = 0x01U, /*!< SPDIFRX initialized and ready for use */ - HAL_SPDIFRX_STATE_BUSY = 0x02U, /*!< SPDIFRX internal process is ongoing */ - HAL_SPDIFRX_STATE_BUSY_RX = 0x03U, /*!< SPDIFRX internal Data Flow RX process is ongoing */ - HAL_SPDIFRX_STATE_BUSY_CX = 0x04U, /*!< SPDIFRX internal Control Flow RX process is ongoing */ - HAL_SPDIFRX_STATE_ERROR = 0x07U /*!< SPDIFRX error state */ -} HAL_SPDIFRX_StateTypeDef; - -/** - * @brief SPDIFRX handle Structure definition - */ -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -typedef struct __SPDIFRX_HandleTypeDef -#else -typedef struct -#endif -{ - SPDIFRX_TypeDef *Instance; /* SPDIFRX registers base address */ - - SPDIFRX_InitTypeDef Init; /* SPDIFRX communication parameters */ - - uint32_t *pRxBuffPtr; /* Pointer to SPDIFRX Rx transfer buffer */ - - uint32_t *pCsBuffPtr; /* Pointer to SPDIFRX Cx transfer buffer */ - - __IO uint16_t RxXferSize; /* SPDIFRX Rx transfer size */ - - __IO uint16_t RxXferCount; /* SPDIFRX Rx transfer counter - (This field is initialized at the - same value as transfer size at the - beginning of the transfer and - decremented when a sample is received. - NbSamplesReceived = RxBufferSize-RxBufferCount) */ - - __IO uint16_t CsXferSize; /* SPDIFRX Rx transfer size */ - - __IO uint16_t CsXferCount; /* SPDIFRX Rx transfer counter - (This field is initialized at the - same value as transfer size at the - beginning of the transfer and - decremented when a sample is received. - NbSamplesReceived = RxBufferSize-RxBufferCount) */ - - DMA_HandleTypeDef *hdmaCsRx; /* SPDIFRX EC60958_channel_status and user_information DMA handle parameters */ - - DMA_HandleTypeDef *hdmaDrRx; /* SPDIFRX Rx DMA handle parameters */ - - __IO HAL_LockTypeDef Lock; /* SPDIFRX locking object */ - - __IO HAL_SPDIFRX_StateTypeDef State; /* SPDIFRX communication state */ - - __IO uint32_t ErrorCode; /* SPDIFRX Error code */ - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - void (*RxHalfCpltCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX Data flow half completed callback */ - void (*RxCpltCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX Data flow completed callback */ - void (*CxHalfCpltCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX Control flow half completed callback */ - void (*CxCpltCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX Control flow completed callback */ - void (*ErrorCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX error callback */ - void (* MspInitCallback)( struct __SPDIFRX_HandleTypeDef * hspdif); /*!< SPDIFRX Msp Init callback */ - void (* MspDeInitCallback)( struct __SPDIFRX_HandleTypeDef * hspdif); /*!< SPDIFRX Msp DeInit callback */ -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - -} SPDIFRX_HandleTypeDef; -/** - * @} - */ - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SPDIFRX Callback ID enumeration definition - */ -typedef enum -{ - HAL_SPDIFRX_RX_HALF_CB_ID = 0x00U, /*!< SPDIFRX Data flow half completed callback ID */ - HAL_SPDIFRX_RX_CPLT_CB_ID = 0x01U, /*!< SPDIFRX Data flow completed callback */ - HAL_SPDIFRX_CX_HALF_CB_ID = 0x02U, /*!< SPDIFRX Control flow half completed callback */ - HAL_SPDIFRX_CX_CPLT_CB_ID = 0x03U, /*!< SPDIFRX Control flow completed callback */ - HAL_SPDIFRX_ERROR_CB_ID = 0x04U, /*!< SPDIFRX error callback */ - HAL_SPDIFRX_MSPINIT_CB_ID = 0x05U, /*!< SPDIFRX Msp Init callback ID */ - HAL_SPDIFRX_MSPDEINIT_CB_ID = 0x06U /*!< SPDIFRX Msp DeInit callback ID */ -}HAL_SPDIFRX_CallbackIDTypeDef; - -/** - * @brief HAL SPDIFRX Callback pointer definition - */ -typedef void (*pSPDIFRX_CallbackTypeDef)(SPDIFRX_HandleTypeDef * hspdif); /*!< pointer to an SPDIFRX callback function */ -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SPDIFRX_Exported_Constants SPDIFRX Exported Constants - * @{ - */ -/** @defgroup SPDIFRX_ErrorCode SPDIFRX Error Code - * @{ - */ -#define HAL_SPDIFRX_ERROR_NONE ((uint32_t)0x00000000U) /*!< No error */ -#define HAL_SPDIFRX_ERROR_TIMEOUT ((uint32_t)0x00000001U) /*!< Timeout error */ -#define HAL_SPDIFRX_ERROR_OVR ((uint32_t)0x00000002U) /*!< OVR error */ -#define HAL_SPDIFRX_ERROR_PE ((uint32_t)0x00000004U) /*!< Parity error */ -#define HAL_SPDIFRX_ERROR_DMA ((uint32_t)0x00000008U) /*!< DMA transfer error */ -#define HAL_SPDIFRX_ERROR_UNKNOWN ((uint32_t)0x00000010U) /*!< Unknown Error error */ -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -#define HAL_SPDIFRX_ERROR_INVALID_CALLBACK ((uint32_t)0x00000020U) /*!< Invalid Callback error */ -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SPDIFRX_Input_Selection SPDIFRX Input Selection - * @{ - */ -#define SPDIFRX_INPUT_IN0 ((uint32_t)0x00000000U) -#define SPDIFRX_INPUT_IN1 ((uint32_t)0x00010000U) -#define SPDIFRX_INPUT_IN2 ((uint32_t)0x00020000U) -#define SPDIFRX_INPUT_IN3 ((uint32_t)0x00030000U) -/** - * @} - */ - -/** @defgroup SPDIFRX_Max_Retries SPDIFRX Maximum Retries - * @{ - */ -#define SPDIFRX_MAXRETRIES_NONE ((uint32_t)0x00000000U) -#define SPDIFRX_MAXRETRIES_3 ((uint32_t)0x00001000U) -#define SPDIFRX_MAXRETRIES_15 ((uint32_t)0x00002000U) -#define SPDIFRX_MAXRETRIES_63 ((uint32_t)0x00003000U) -/** - * @} - */ - -/** @defgroup SPDIFRX_Wait_For_Activity SPDIFRX Wait For Activity - * @{ - */ -#define SPDIFRX_WAITFORACTIVITY_OFF ((uint32_t)0x00000000U) -#define SPDIFRX_WAITFORACTIVITY_ON ((uint32_t)SPDIFRX_CR_WFA) -/** - * @} - */ - -/** @defgroup SPDIFRX_PT_Mask SPDIFRX Preamble Type Mask - * @{ - */ -#define SPDIFRX_PREAMBLETYPEMASK_OFF ((uint32_t)0x00000000U) -#define SPDIFRX_PREAMBLETYPEMASK_ON ((uint32_t)SPDIFRX_CR_PTMSK) -/** - * @} - */ - -/** @defgroup SPDIFRX_ChannelStatus_Mask SPDIFRX Channel Status Mask - * @{ - */ -#define SPDIFRX_CHANNELSTATUS_OFF ((uint32_t)0x00000000U) /* The channel status and user bits are copied into the SPDIF_DR */ -#define SPDIFRX_CHANNELSTATUS_ON ((uint32_t)SPDIFRX_CR_CUMSK) /* The channel status and user bits are not copied into the SPDIF_DR, zeros are written instead*/ -/** - * @} - */ - -/** @defgroup SPDIFRX_V_Mask SPDIFRX Validity Mask -* @{ -*/ -#define SPDIFRX_VALIDITYMASK_OFF ((uint32_t)0x00000000U) -#define SPDIFRX_VALIDITYMASK_ON ((uint32_t)SPDIFRX_CR_VMSK) -/** - * @} - */ - -/** @defgroup SPDIFRX_PE_Mask SPDIFRX Parity Error Mask - * @{ - */ -#define SPDIFRX_PARITYERRORMASK_OFF ((uint32_t)0x00000000U) -#define SPDIFRX_PARITYERRORMASK_ON ((uint32_t)SPDIFRX_CR_PMSK) -/** - * @} - */ - -/** @defgroup SPDIFRX_Channel_Selection SPDIFRX Channel Selection - * @{ - */ -#define SPDIFRX_CHANNEL_A ((uint32_t)0x00000000U) -#define SPDIFRX_CHANNEL_B ((uint32_t)SPDIFRX_CR_CHSEL) -/** - * @} - */ - -/** @defgroup SPDIFRX_Data_Format SPDIFRX Data Format - * @{ - */ -#define SPDIFRX_DATAFORMAT_LSB ((uint32_t)0x00000000U) -#define SPDIFRX_DATAFORMAT_MSB ((uint32_t)0x00000010U) -#define SPDIFRX_DATAFORMAT_32BITS ((uint32_t)0x00000020U) -/** - * @} - */ - -/** @defgroup SPDIFRX_Stereo_Mode SPDIFRX Stereo Mode - * @{ - */ -#define SPDIFRX_STEREOMODE_DISABLE ((uint32_t)0x00000000U) -#define SPDIFRX_STEREOMODE_ENABLE ((uint32_t)SPDIFRX_CR_RXSTEO) -/** - * @} - */ - -/** @defgroup SPDIFRX_State SPDIFRX State - * @{ - */ - -#define SPDIFRX_STATE_IDLE ((uint32_t)0xFFFFFFFCU) -#define SPDIFRX_STATE_SYNC ((uint32_t)0x00000001U) -#define SPDIFRX_STATE_RCV ((uint32_t)SPDIFRX_CR_SPDIFEN) -/** - * @} - */ - -/** @defgroup SPDIFRX_Interrupts_Definition SPDIFRX Interrupts Definition - * @{ - */ -#define SPDIFRX_IT_RXNE ((uint32_t)SPDIFRX_IMR_RXNEIE) -#define SPDIFRX_IT_CSRNE ((uint32_t)SPDIFRX_IMR_CSRNEIE) -#define SPDIFRX_IT_PERRIE ((uint32_t)SPDIFRX_IMR_PERRIE) -#define SPDIFRX_IT_OVRIE ((uint32_t)SPDIFRX_IMR_OVRIE) -#define SPDIFRX_IT_SBLKIE ((uint32_t)SPDIFRX_IMR_SBLKIE) -#define SPDIFRX_IT_SYNCDIE ((uint32_t)SPDIFRX_IMR_SYNCDIE) -#define SPDIFRX_IT_IFEIE ((uint32_t)SPDIFRX_IMR_IFEIE ) -/** - * @} - */ - -/** @defgroup SPDIFRX_Flags_Definition SPDIFRX Flags Definition - * @{ - */ -#define SPDIFRX_FLAG_RXNE ((uint32_t)SPDIFRX_SR_RXNE) -#define SPDIFRX_FLAG_CSRNE ((uint32_t)SPDIFRX_SR_CSRNE) -#define SPDIFRX_FLAG_PERR ((uint32_t)SPDIFRX_SR_PERR) -#define SPDIFRX_FLAG_OVR ((uint32_t)SPDIFRX_SR_OVR) -#define SPDIFRX_FLAG_SBD ((uint32_t)SPDIFRX_SR_SBD) -#define SPDIFRX_FLAG_SYNCD ((uint32_t)SPDIFRX_SR_SYNCD) -#define SPDIFRX_FLAG_FERR ((uint32_t)SPDIFRX_SR_FERR) -#define SPDIFRX_FLAG_SERR ((uint32_t)SPDIFRX_SR_SERR) -#define SPDIFRX_FLAG_TERR ((uint32_t)SPDIFRX_SR_TERR) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup SPDIFRX_Exported_macros SPDIFRX Exported Macros - * @{ - */ - -/** @brief Reset SPDIFRX handle state - * @param __HANDLE__ SPDIFRX handle. - * @retval None - */ -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -#define __HAL_SPDIFRX_RESET_HANDLE_STATE(__HANDLE__) do{\ - (__HANDLE__)->State = HAL_SPDIFRX_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL;\ - (__HANDLE__)->MspDeInitCallback = NULL;\ - }while(0) -#else -#define __HAL_SPDIFRX_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SPDIFRX_STATE_RESET) -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - -/** @brief Disable the specified SPDIFRX peripheral (IDLE State). - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @retval None - */ -#define __HAL_SPDIFRX_IDLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= SPDIFRX_STATE_IDLE) - -/** @brief Enable the specified SPDIFRX peripheral (SYNC State). - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @retval None - */ -#define __HAL_SPDIFRX_SYNC(__HANDLE__) ((__HANDLE__)->Instance->CR |= SPDIFRX_STATE_SYNC) - - -/** @brief Enable the specified SPDIFRX peripheral (RCV State). - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @retval None - */ -#define __HAL_SPDIFRX_RCV(__HANDLE__) ((__HANDLE__)->Instance->CR |= SPDIFRX_STATE_RCV) - - -/** @brief Enable or disable the specified SPDIFRX interrupts. - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg SPDIFRX_IT_RXNE - * @arg SPDIFRX_IT_CSRNE - * @arg SPDIFRX_IT_PERRIE - * @arg SPDIFRX_IT_OVRIE - * @arg SPDIFRX_IT_SBLKIE - * @arg SPDIFRX_IT_SYNCDIE - * @arg SPDIFRX_IT_IFEIE - * @retval None - */ -#define __HAL_SPDIFRX_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IMR |= (__INTERRUPT__)) -#define __HAL_SPDIFRX_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IMR &= (uint16_t)(~(__INTERRUPT__))) - -/** @brief Checks if the specified SPDIFRX interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @param __INTERRUPT__ specifies the SPDIFRX interrupt source to check. - * This parameter can be one of the following values: - * @arg SPDIFRX_IT_RXNE - * @arg SPDIFRX_IT_CSRNE - * @arg SPDIFRX_IT_PERRIE - * @arg SPDIFRX_IT_OVRIE - * @arg SPDIFRX_IT_SBLKIE - * @arg SPDIFRX_IT_SYNCDIE - * @arg SPDIFRX_IT_IFEIE - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_SPDIFRX_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IMR & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified SPDIFRX flag is set or not. - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SPDIFRX_FLAG_RXNE - * @arg SPDIFRX_FLAG_CSRNE - * @arg SPDIFRX_FLAG_PERR - * @arg SPDIFRX_FLAG_OVR - * @arg SPDIFRX_FLAG_SBD - * @arg SPDIFRX_FLAG_SYNCD - * @arg SPDIFRX_FLAG_FERR - * @arg SPDIFRX_FLAG_SERR - * @arg SPDIFRX_FLAG_TERR - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SPDIFRX_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) ? SET : RESET) - -/** @brief Clears the specified SPDIFRX SR flag, in setting the proper IFCR register bit. - * @param __HANDLE__ specifies the USART Handle. - * @param __IT_CLEAR__ specifies the interrupt clear register flag that needs to be set - * to clear the corresponding interrupt - * This parameter can be one of the following values: - * @arg SPDIFRX_FLAG_PERR - * @arg SPDIFRX_FLAG_OVR - * @arg SPDIFRX_SR_SBD - * @arg SPDIFRX_SR_SYNCD - * @retval None - */ -#define __HAL_SPDIFRX_CLEAR_IT(__HANDLE__, __IT_CLEAR__) ((__HANDLE__)->Instance->IFCR = (uint32_t)(__IT_CLEAR__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SPDIFRX_Exported_Functions - * @{ - */ - -/** @addtogroup SPDIFRX_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_SPDIFRX_Init(SPDIFRX_HandleTypeDef *hspdif); -HAL_StatusTypeDef HAL_SPDIFRX_DeInit (SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_MspInit(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_MspDeInit(SPDIFRX_HandleTypeDef *hspdif); -HAL_StatusTypeDef HAL_SPDIFRX_SetDataFormat(SPDIFRX_HandleTypeDef *hspdif, SPDIFRX_SetDataFormatTypeDef sDataFormat); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_SPDIFRX_RegisterCallback(SPDIFRX_HandleTypeDef *hspdif, HAL_SPDIFRX_CallbackIDTypeDef CallbackID, pSPDIFRX_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SPDIFRX_UnRegisterCallback(SPDIFRX_HandleTypeDef *hspdif, HAL_SPDIFRX_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup SPDIFRX_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ - /* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size, uint32_t Timeout); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size); -void HAL_SPDIFRX_IRQHandler(SPDIFRX_HandleTypeDef *hspdif); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow_DMA(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow_DMA(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPDIFRX_DMAStop(SPDIFRX_HandleTypeDef *hspdif); - -/* Callbacks used in non blocking modes (Interrupt and DMA) *******************/ -void HAL_SPDIFRX_RxHalfCpltCallback(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_RxCpltCallback(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_ErrorCallback(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_CxHalfCpltCallback(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_CxCpltCallback(SPDIFRX_HandleTypeDef *hspdif); -/** - * @} - */ - -/** @addtogroup SPDIFRX_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control and State functions ************************************/ -HAL_SPDIFRX_StateTypeDef HAL_SPDIFRX_GetState(SPDIFRX_HandleTypeDef const * const hspdif); -uint32_t HAL_SPDIFRX_GetError(SPDIFRX_HandleTypeDef const * const hspdif); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SPDIFRX_Private_Macros SPDIFRX Private Macros - * @{ - */ -#define IS_SPDIFRX_INPUT_SELECT(INPUT) (((INPUT) == SPDIFRX_INPUT_IN1) || \ - ((INPUT) == SPDIFRX_INPUT_IN2) || \ - ((INPUT) == SPDIFRX_INPUT_IN3) || \ - ((INPUT) == SPDIFRX_INPUT_IN0)) - -#define IS_SPDIFRX_MAX_RETRIES(RET) (((RET) == SPDIFRX_MAXRETRIES_NONE) || \ - ((RET) == SPDIFRX_MAXRETRIES_3) || \ - ((RET) == SPDIFRX_MAXRETRIES_15) || \ - ((RET) == SPDIFRX_MAXRETRIES_63)) - -#define IS_SPDIFRX_WAIT_FOR_ACTIVITY(VAL) (((VAL) == SPDIFRX_WAITFORACTIVITY_ON) || \ - ((VAL) == SPDIFRX_WAITFORACTIVITY_OFF)) - -#define IS_PREAMBLE_TYPE_MASK(VAL) (((VAL) == SPDIFRX_PREAMBLETYPEMASK_ON) || \ - ((VAL) == SPDIFRX_PREAMBLETYPEMASK_OFF)) - -#define IS_VALIDITY_MASK(VAL) (((VAL) == SPDIFRX_VALIDITYMASK_OFF) || \ - ((VAL) == SPDIFRX_VALIDITYMASK_ON)) - -#define IS_PARITY_ERROR_MASK(VAL) (((VAL) == SPDIFRX_PARITYERRORMASK_OFF) || \ - ((VAL) == SPDIFRX_PARITYERRORMASK_ON)) - -#define IS_SPDIFRX_CHANNEL(CHANNEL) (((CHANNEL) == SPDIFRX_CHANNEL_A) || \ - ((CHANNEL) == SPDIFRX_CHANNEL_B)) - -#define IS_SPDIFRX_DATA_FORMAT(FORMAT) (((FORMAT) == SPDIFRX_DATAFORMAT_LSB) || \ - ((FORMAT) == SPDIFRX_DATAFORMAT_MSB) || \ - ((FORMAT) == SPDIFRX_DATAFORMAT_32BITS)) - -#define IS_STEREO_MODE(MODE) (((MODE) == SPDIFRX_STEREOMODE_DISABLE) || \ - ((MODE) == SPDIFRX_STEREOMODE_ENABLE)) - -#define IS_CHANNEL_STATUS_MASK(VAL) (((VAL) == SPDIFRX_CHANNELSTATUS_ON) || \ - ((VAL) == SPDIFRX_CHANNELSTATUS_OFF)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SPDIFRX_Private_Functions SPDIFRX Private Functions - * @{ - */ -/** - * @} - */ - -/** - * @} - */ -#endif /* SPDIFRX */ -/** - * @} - */ -#endif /* STM32F446xx */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_SPDIFRX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h deleted file mode 100644 index f2e07c2c0f6aea4..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h +++ /dev/null @@ -1,730 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_spi.h - * @author MCD Application Team - * @brief Header file of SPI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_SPI_H -#define STM32F4xx_HAL_SPI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SPI - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SPI_Exported_Types SPI Exported Types - * @{ - */ - -/** - * @brief SPI Configuration Structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Specifies the SPI operating mode. - This parameter can be a value of @ref SPI_Mode */ - - uint32_t Direction; /*!< Specifies the SPI bidirectional mode state. - This parameter can be a value of @ref SPI_Direction */ - - uint32_t DataSize; /*!< Specifies the SPI data size. - This parameter can be a value of @ref SPI_Data_Size */ - - uint32_t CLKPolarity; /*!< Specifies the serial clock steady state. - This parameter can be a value of @ref SPI_Clock_Polarity */ - - uint32_t CLKPhase; /*!< Specifies the clock active edge for the bit capture. - This parameter can be a value of @ref SPI_Clock_Phase */ - - uint32_t NSS; /*!< Specifies whether the NSS signal is managed by - hardware (NSS pin) or by software using the SSI bit. - This parameter can be a value of @ref SPI_Slave_Select_management */ - - uint32_t BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be - used to configure the transmit and receive SCK clock. - This parameter can be a value of @ref SPI_BaudRate_Prescaler - @note The communication clock is derived from the master - clock. The slave clock does not need to be set. */ - - uint32_t FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. - This parameter can be a value of @ref SPI_MSB_LSB_transmission */ - - uint32_t TIMode; /*!< Specifies if the TI mode is enabled or not. - This parameter can be a value of @ref SPI_TI_mode */ - - uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not. - This parameter can be a value of @ref SPI_CRC_Calculation */ - - uint32_t CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. - This parameter must be an odd number between Min_Data = 1 and Max_Data = 65535 */ -} SPI_InitTypeDef; - -/** - * @brief HAL SPI State structure definition - */ -typedef enum -{ - HAL_SPI_STATE_RESET = 0x00U, /*!< Peripheral not Initialized */ - HAL_SPI_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_SPI_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */ - HAL_SPI_STATE_BUSY_TX = 0x03U, /*!< Data Transmission process is ongoing */ - HAL_SPI_STATE_BUSY_RX = 0x04U, /*!< Data Reception process is ongoing */ - HAL_SPI_STATE_BUSY_TX_RX = 0x05U, /*!< Data Transmission and Reception process is ongoing */ - HAL_SPI_STATE_ERROR = 0x06U, /*!< SPI error state */ - HAL_SPI_STATE_ABORT = 0x07U /*!< SPI abort is ongoing */ -} HAL_SPI_StateTypeDef; - -/** - * @brief SPI handle Structure definition - */ -typedef struct __SPI_HandleTypeDef -{ - SPI_TypeDef *Instance; /*!< SPI registers base address */ - - SPI_InitTypeDef Init; /*!< SPI communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to SPI Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< SPI Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< SPI Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to SPI Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< SPI Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< SPI Rx Transfer Counter */ - - void (*RxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Rx ISR */ - - void (*TxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Tx ISR */ - - DMA_HandleTypeDef *hdmatx; /*!< SPI Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SPI Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_SPI_StateTypeDef State; /*!< SPI communication state */ - - __IO uint32_t ErrorCode; /*!< SPI Error code */ - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Completed callback */ - void (* RxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Completed callback */ - void (* TxRxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Completed callback */ - void (* TxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Half Completed callback */ - void (* RxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Half Completed callback */ - void (* TxRxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Half Completed callback */ - void (* ErrorCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Error callback */ - void (* AbortCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Abort callback */ - void (* MspInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp Init callback */ - void (* MspDeInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp DeInit callback */ - -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} SPI_HandleTypeDef; - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL SPI Callback ID enumeration definition - */ -typedef enum -{ - HAL_SPI_TX_COMPLETE_CB_ID = 0x00U, /*!< SPI Tx Completed callback ID */ - HAL_SPI_RX_COMPLETE_CB_ID = 0x01U, /*!< SPI Rx Completed callback ID */ - HAL_SPI_TX_RX_COMPLETE_CB_ID = 0x02U, /*!< SPI TxRx Completed callback ID */ - HAL_SPI_TX_HALF_COMPLETE_CB_ID = 0x03U, /*!< SPI Tx Half Completed callback ID */ - HAL_SPI_RX_HALF_COMPLETE_CB_ID = 0x04U, /*!< SPI Rx Half Completed callback ID */ - HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID = 0x05U, /*!< SPI TxRx Half Completed callback ID */ - HAL_SPI_ERROR_CB_ID = 0x06U, /*!< SPI Error callback ID */ - HAL_SPI_ABORT_CB_ID = 0x07U, /*!< SPI Abort callback ID */ - HAL_SPI_MSPINIT_CB_ID = 0x08U, /*!< SPI Msp Init callback ID */ - HAL_SPI_MSPDEINIT_CB_ID = 0x09U /*!< SPI Msp DeInit callback ID */ - -} HAL_SPI_CallbackIDTypeDef; - -/** - * @brief HAL SPI Callback pointer definition - */ -typedef void (*pSPI_CallbackTypeDef)(SPI_HandleTypeDef *hspi); /*!< pointer to an SPI callback function */ - -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SPI_Exported_Constants SPI Exported Constants - * @{ - */ - -/** @defgroup SPI_Error_Code SPI Error Code - * @{ - */ -#define HAL_SPI_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_SPI_ERROR_MODF (0x00000001U) /*!< MODF error */ -#define HAL_SPI_ERROR_CRC (0x00000002U) /*!< CRC error */ -#define HAL_SPI_ERROR_OVR (0x00000004U) /*!< OVR error */ -#define HAL_SPI_ERROR_FRE (0x00000008U) /*!< FRE error */ -#define HAL_SPI_ERROR_DMA (0x00000010U) /*!< DMA transfer error */ -#define HAL_SPI_ERROR_FLAG (0x00000020U) /*!< Error on RXNE/TXE/BSY Flag */ -#define HAL_SPI_ERROR_ABORT (0x00000040U) /*!< Error during SPI Abort procedure */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -#define HAL_SPI_ERROR_INVALID_CALLBACK (0x00000080U) /*!< Invalid Callback error */ -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SPI_Mode SPI Mode - * @{ - */ -#define SPI_MODE_SLAVE (0x00000000U) -#define SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI) -/** - * @} - */ - -/** @defgroup SPI_Direction SPI Direction Mode - * @{ - */ -#define SPI_DIRECTION_2LINES (0x00000000U) -#define SPI_DIRECTION_2LINES_RXONLY SPI_CR1_RXONLY -#define SPI_DIRECTION_1LINE SPI_CR1_BIDIMODE -/** - * @} - */ - -/** @defgroup SPI_Data_Size SPI Data Size - * @{ - */ -#define SPI_DATASIZE_8BIT (0x00000000U) -#define SPI_DATASIZE_16BIT SPI_CR1_DFF -/** - * @} - */ - -/** @defgroup SPI_Clock_Polarity SPI Clock Polarity - * @{ - */ -#define SPI_POLARITY_LOW (0x00000000U) -#define SPI_POLARITY_HIGH SPI_CR1_CPOL -/** - * @} - */ - -/** @defgroup SPI_Clock_Phase SPI Clock Phase - * @{ - */ -#define SPI_PHASE_1EDGE (0x00000000U) -#define SPI_PHASE_2EDGE SPI_CR1_CPHA -/** - * @} - */ - -/** @defgroup SPI_Slave_Select_management SPI Slave Select Management - * @{ - */ -#define SPI_NSS_SOFT SPI_CR1_SSM -#define SPI_NSS_HARD_INPUT (0x00000000U) -#define SPI_NSS_HARD_OUTPUT (SPI_CR2_SSOE << 16U) -/** - * @} - */ - -/** @defgroup SPI_BaudRate_Prescaler SPI BaudRate Prescaler - * @{ - */ -#define SPI_BAUDRATEPRESCALER_2 (0x00000000U) -#define SPI_BAUDRATEPRESCALER_4 (SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_8 (SPI_CR1_BR_1) -#define SPI_BAUDRATEPRESCALER_16 (SPI_CR1_BR_1 | SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_32 (SPI_CR1_BR_2) -#define SPI_BAUDRATEPRESCALER_64 (SPI_CR1_BR_2 | SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_128 (SPI_CR1_BR_2 | SPI_CR1_BR_1) -#define SPI_BAUDRATEPRESCALER_256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0) -/** - * @} - */ - -/** @defgroup SPI_MSB_LSB_transmission SPI MSB LSB Transmission - * @{ - */ -#define SPI_FIRSTBIT_MSB (0x00000000U) -#define SPI_FIRSTBIT_LSB SPI_CR1_LSBFIRST -/** - * @} - */ - -/** @defgroup SPI_TI_mode SPI TI Mode - * @{ - */ -#define SPI_TIMODE_DISABLE (0x00000000U) -#define SPI_TIMODE_ENABLE SPI_CR2_FRF -/** - * @} - */ - -/** @defgroup SPI_CRC_Calculation SPI CRC Calculation - * @{ - */ -#define SPI_CRCCALCULATION_DISABLE (0x00000000U) -#define SPI_CRCCALCULATION_ENABLE SPI_CR1_CRCEN -/** - * @} - */ - -/** @defgroup SPI_Interrupt_definition SPI Interrupt Definition - * @{ - */ -#define SPI_IT_TXE SPI_CR2_TXEIE -#define SPI_IT_RXNE SPI_CR2_RXNEIE -#define SPI_IT_ERR SPI_CR2_ERRIE -/** - * @} - */ - -/** @defgroup SPI_Flags_definition SPI Flags Definition - * @{ - */ -#define SPI_FLAG_RXNE SPI_SR_RXNE /* SPI status flag: Rx buffer not empty flag */ -#define SPI_FLAG_TXE SPI_SR_TXE /* SPI status flag: Tx buffer empty flag */ -#define SPI_FLAG_BSY SPI_SR_BSY /* SPI status flag: Busy flag */ -#define SPI_FLAG_CRCERR SPI_SR_CRCERR /* SPI Error flag: CRC error flag */ -#define SPI_FLAG_MODF SPI_SR_MODF /* SPI Error flag: Mode fault flag */ -#define SPI_FLAG_OVR SPI_SR_OVR /* SPI Error flag: Overrun flag */ -#define SPI_FLAG_FRE SPI_SR_FRE /* SPI Error flag: TI mode frame format error flag */ -#define SPI_FLAG_MASK (SPI_SR_RXNE | SPI_SR_TXE | SPI_SR_BSY | SPI_SR_CRCERR\ - | SPI_SR_MODF | SPI_SR_OVR | SPI_SR_FRE) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup SPI_Exported_Macros SPI Exported Macros - * @{ - */ - -/** @brief Reset SPI handle state. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_SPI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SPI_STATE_RESET) -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - -/** @brief Enable the specified SPI interrupts. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the interrupt source to enable. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_SPI_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Disable the specified SPI interrupts. - * @param __HANDLE__ specifies the SPI handle. - * This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the interrupt source to disable. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_SPI_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Check whether the specified SPI interrupt source is enabled or not. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the SPI interrupt source to check. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_SPI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified SPI flag is set or not. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SPI_FLAG_RXNE: Receive buffer not empty flag - * @arg SPI_FLAG_TXE: Transmit buffer empty flag - * @arg SPI_FLAG_CRCERR: CRC error flag - * @arg SPI_FLAG_MODF: Mode fault flag - * @arg SPI_FLAG_OVR: Overrun flag - * @arg SPI_FLAG_BSY: Busy flag - * @arg SPI_FLAG_FRE: Frame format error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SPI_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the SPI CRCERR pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_CRCERRFLAG(__HANDLE__) ((__HANDLE__)->Instance->SR = (uint16_t)(~SPI_FLAG_CRCERR)) - -/** @brief Clear the SPI MODF pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_MODFFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_modf = 0x00U; \ - tmpreg_modf = (__HANDLE__)->Instance->SR; \ - CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE); \ - UNUSED(tmpreg_modf); \ - } while(0U) - -/** @brief Clear the SPI OVR pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_OVRFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_ovr = 0x00U; \ - tmpreg_ovr = (__HANDLE__)->Instance->DR; \ - tmpreg_ovr = (__HANDLE__)->Instance->SR; \ - UNUSED(tmpreg_ovr); \ - } while(0U) - -/** @brief Clear the SPI FRE pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_FREFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_fre = 0x00U; \ - tmpreg_fre = (__HANDLE__)->Instance->SR; \ - UNUSED(tmpreg_fre); \ - }while(0U) - -/** @brief Enable the SPI peripheral. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE) - -/** @brief Disable the SPI peripheral. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE) - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SPI_Private_Macros SPI Private Macros - * @{ - */ - -/** @brief Set the SPI transmit-only mode. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_1LINE_TX(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE) - -/** @brief Set the SPI receive-only mode. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_1LINE_RX(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE) - -/** @brief Reset the CRC calculation of the SPI. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_RESET_CRC(__HANDLE__) do{CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);\ - SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);}while(0U) - -/** @brief Check whether the specified SPI flag is set or not. - * @param __SR__ copy of SPI SR register. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SPI_FLAG_RXNE: Receive buffer not empty flag - * @arg SPI_FLAG_TXE: Transmit buffer empty flag - * @arg SPI_FLAG_CRCERR: CRC error flag - * @arg SPI_FLAG_MODF: Mode fault flag - * @arg SPI_FLAG_OVR: Overrun flag - * @arg SPI_FLAG_BSY: Busy flag - * @arg SPI_FLAG_FRE: Frame format error flag - * @retval SET or RESET. - */ -#define SPI_CHECK_FLAG(__SR__, __FLAG__) ((((__SR__) & ((__FLAG__) & SPI_FLAG_MASK)) == \ - ((__FLAG__) & SPI_FLAG_MASK)) ? SET : RESET) - -/** @brief Check whether the specified SPI Interrupt is set or not. - * @param __CR2__ copy of SPI CR2 register. - * @param __INTERRUPT__ specifies the SPI interrupt source to check. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval SET or RESET. - */ -#define SPI_CHECK_IT_SOURCE(__CR2__, __INTERRUPT__) ((((__CR2__) & (__INTERRUPT__)) == \ - (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks if SPI Mode parameter is in allowed range. - * @param __MODE__ specifies the SPI Mode. - * This parameter can be a value of @ref SPI_Mode - * @retval None - */ -#define IS_SPI_MODE(__MODE__) (((__MODE__) == SPI_MODE_SLAVE) || \ - ((__MODE__) == SPI_MODE_MASTER)) - -/** @brief Checks if SPI Direction Mode parameter is in allowed range. - * @param __MODE__ specifies the SPI Direction Mode. - * This parameter can be a value of @ref SPI_Direction - * @retval None - */ -#define IS_SPI_DIRECTION(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \ - ((__MODE__) == SPI_DIRECTION_2LINES_RXONLY) || \ - ((__MODE__) == SPI_DIRECTION_1LINE)) - -/** @brief Checks if SPI Direction Mode parameter is 2 lines. - * @param __MODE__ specifies the SPI Direction Mode. - * @retval None - */ -#define IS_SPI_DIRECTION_2LINES(__MODE__) ((__MODE__) == SPI_DIRECTION_2LINES) - -/** @brief Checks if SPI Direction Mode parameter is 1 or 2 lines. - * @param __MODE__ specifies the SPI Direction Mode. - * @retval None - */ -#define IS_SPI_DIRECTION_2LINES_OR_1LINE(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \ - ((__MODE__) == SPI_DIRECTION_1LINE)) - -/** @brief Checks if SPI Data Size parameter is in allowed range. - * @param __DATASIZE__ specifies the SPI Data Size. - * This parameter can be a value of @ref SPI_Data_Size - * @retval None - */ -#define IS_SPI_DATASIZE(__DATASIZE__) (((__DATASIZE__) == SPI_DATASIZE_16BIT) || \ - ((__DATASIZE__) == SPI_DATASIZE_8BIT)) - -/** @brief Checks if SPI Serial clock steady state parameter is in allowed range. - * @param __CPOL__ specifies the SPI serial clock steady state. - * This parameter can be a value of @ref SPI_Clock_Polarity - * @retval None - */ -#define IS_SPI_CPOL(__CPOL__) (((__CPOL__) == SPI_POLARITY_LOW) || \ - ((__CPOL__) == SPI_POLARITY_HIGH)) - -/** @brief Checks if SPI Clock Phase parameter is in allowed range. - * @param __CPHA__ specifies the SPI Clock Phase. - * This parameter can be a value of @ref SPI_Clock_Phase - * @retval None - */ -#define IS_SPI_CPHA(__CPHA__) (((__CPHA__) == SPI_PHASE_1EDGE) || \ - ((__CPHA__) == SPI_PHASE_2EDGE)) - -/** @brief Checks if SPI Slave Select parameter is in allowed range. - * @param __NSS__ specifies the SPI Slave Select management parameter. - * This parameter can be a value of @ref SPI_Slave_Select_management - * @retval None - */ -#define IS_SPI_NSS(__NSS__) (((__NSS__) == SPI_NSS_SOFT) || \ - ((__NSS__) == SPI_NSS_HARD_INPUT) || \ - ((__NSS__) == SPI_NSS_HARD_OUTPUT)) - -/** @brief Checks if SPI Baudrate prescaler parameter is in allowed range. - * @param __PRESCALER__ specifies the SPI Baudrate prescaler. - * This parameter can be a value of @ref SPI_BaudRate_Prescaler - * @retval None - */ -#define IS_SPI_BAUDRATE_PRESCALER(__PRESCALER__) (((__PRESCALER__) == SPI_BAUDRATEPRESCALER_2) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_4) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_8) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_16) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_32) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_64) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_128) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_256)) - -/** @brief Checks if SPI MSB LSB transmission parameter is in allowed range. - * @param __BIT__ specifies the SPI MSB LSB transmission (whether data transfer starts from MSB or LSB bit). - * This parameter can be a value of @ref SPI_MSB_LSB_transmission - * @retval None - */ -#define IS_SPI_FIRST_BIT(__BIT__) (((__BIT__) == SPI_FIRSTBIT_MSB) || \ - ((__BIT__) == SPI_FIRSTBIT_LSB)) - -/** @brief Checks if SPI TI mode parameter is in allowed range. - * @param __MODE__ specifies the SPI TI mode. - * This parameter can be a value of @ref SPI_TI_mode - * @retval None - */ -#define IS_SPI_TIMODE(__MODE__) (((__MODE__) == SPI_TIMODE_DISABLE) || \ - ((__MODE__) == SPI_TIMODE_ENABLE)) - -/** @brief Checks if SPI CRC calculation enabled state is in allowed range. - * @param __CALCULATION__ specifies the SPI CRC calculation enable state. - * This parameter can be a value of @ref SPI_CRC_Calculation - * @retval None - */ -#define IS_SPI_CRC_CALCULATION(__CALCULATION__) (((__CALCULATION__) == SPI_CRCCALCULATION_DISABLE) || \ - ((__CALCULATION__) == SPI_CRCCALCULATION_ENABLE)) - -/** @brief Checks if SPI polynomial value to be used for the CRC calculation, is in allowed range. - * @param __POLYNOMIAL__ specifies the SPI polynomial value to be used for the CRC calculation. - * This parameter must be a number between Min_Data = 0 and Max_Data = 65535 - * @retval None - */ -#define IS_SPI_CRC_POLYNOMIAL(__POLYNOMIAL__) (((__POLYNOMIAL__) >= 0x1U) && \ - ((__POLYNOMIAL__) <= 0xFFFFU) && \ - (((__POLYNOMIAL__)&0x1U) != 0U)) - -/** @brief Checks if DMA handle is valid. - * @param __HANDLE__ specifies a DMA Handle. - * @retval None - */ -#define IS_SPI_DMA_HANDLE(__HANDLE__) ((__HANDLE__) != NULL) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SPI_Exported_Functions - * @{ - */ - -/** @addtogroup SPI_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi); -void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi); -void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, pSPI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup SPI_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, - uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi); - -void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi); -/** - * @} - */ - -/** @addtogroup SPI_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State and Error functions ***************************************/ -HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi); -uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_SPI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sram.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sram.h deleted file mode 100644 index 0c7b08dba72067a..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sram.h +++ /dev/null @@ -1,232 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sram.h - * @author MCD Application Team - * @brief Header file of SRAM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SRAM_H -#define __STM32F4xx_HAL_SRAM_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - #include "stm32f4xx_ll_fsmc.h" -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #include "stm32f4xx_ll_fmc.h" -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - -/** @addtogroup SRAM - * @{ - */ - -/* Exported typedef ----------------------------------------------------------*/ - -/** @defgroup SRAM_Exported_Types SRAM Exported Types - * @{ - */ -/** - * @brief HAL SRAM State structures definition - */ -typedef enum -{ - HAL_SRAM_STATE_RESET = 0x00U, /*!< SRAM not yet initialized or disabled */ - HAL_SRAM_STATE_READY = 0x01U, /*!< SRAM initialized and ready for use */ - HAL_SRAM_STATE_BUSY = 0x02U, /*!< SRAM internal process is ongoing */ - HAL_SRAM_STATE_ERROR = 0x03U, /*!< SRAM error state */ - HAL_SRAM_STATE_PROTECTED = 0x04U /*!< SRAM peripheral NORSRAM device write protected */ - -} HAL_SRAM_StateTypeDef; - -/** - * @brief SRAM handle Structure definition - */ -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -typedef struct __SRAM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_SRAM_REGISTER_CALLBACKS */ -{ - FMC_NORSRAM_TypeDef *Instance; /*!< Register base address */ - - FMC_NORSRAM_EXTENDED_TypeDef *Extended; /*!< Extended mode register base address */ - - FMC_NORSRAM_InitTypeDef Init; /*!< SRAM device control configuration parameters */ - - HAL_LockTypeDef Lock; /*!< SRAM locking object */ - - __IO HAL_SRAM_StateTypeDef State; /*!< SRAM device access state */ - - DMA_HandleTypeDef *hdma; /*!< Pointer DMA handler */ - -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) - void (* MspInitCallback) ( struct __SRAM_HandleTypeDef * hsram); /*!< SRAM Msp Init callback */ - void (* MspDeInitCallback) ( struct __SRAM_HandleTypeDef * hsram); /*!< SRAM Msp DeInit callback */ - void (* DmaXferCpltCallback) ( DMA_HandleTypeDef * hdma); /*!< SRAM DMA Xfer Complete callback */ - void (* DmaXferErrorCallback) ( DMA_HandleTypeDef * hdma); /*!< SRAM DMA Xfer Error callback */ -#endif -} SRAM_HandleTypeDef; - -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SRAM Callback ID enumeration definition - */ -typedef enum -{ - HAL_SRAM_MSP_INIT_CB_ID = 0x00U, /*!< SRAM MspInit Callback ID */ - HAL_SRAM_MSP_DEINIT_CB_ID = 0x01U, /*!< SRAM MspDeInit Callback ID */ - HAL_SRAM_DMA_XFER_CPLT_CB_ID = 0x02U, /*!< SRAM DMA Xfer Complete Callback ID */ - HAL_SRAM_DMA_XFER_ERR_CB_ID = 0x03U /*!< SRAM DMA Xfer Complete Callback ID */ -}HAL_SRAM_CallbackIDTypeDef; - -/** - * @brief HAL SRAM Callback pointer definition - */ -typedef void (*pSRAM_CallbackTypeDef)(SRAM_HandleTypeDef *hsram); -typedef void (*pSRAM_DmaCallbackTypeDef)(DMA_HandleTypeDef *hdma); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ - -/** @defgroup SRAM_Exported_Macros SRAM Exported Macros - * @{ - */ -/** @brief Reset SRAM handle state - * @param __HANDLE__ SRAM handle - * @retval None - */ -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -#define __HAL_SRAM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_SRAM_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SRAM_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SRAM_STATE_RESET) -#endif - -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup SRAM_Exported_Functions - * @{ - */ - -/** @addtogroup SRAM_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_SRAM_Init(SRAM_HandleTypeDef *hsram, FMC_NORSRAM_TimingTypeDef *Timing, FMC_NORSRAM_TimingTypeDef *ExtTiming); -HAL_StatusTypeDef HAL_SRAM_DeInit(SRAM_HandleTypeDef *hsram); -void HAL_SRAM_MspInit(SRAM_HandleTypeDef *hsram); -void HAL_SRAM_MspDeInit(SRAM_HandleTypeDef *hsram); - -void HAL_SRAM_DMA_XferCpltCallback(DMA_HandleTypeDef *hdma); -void HAL_SRAM_DMA_XferErrorCallback(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** @addtogroup SRAM_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions *****************************************************/ -HAL_StatusTypeDef HAL_SRAM_Read_8b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint8_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Write_8b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint8_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Read_16b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint16_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Write_16b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint16_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Read_32b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Write_32b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Read_DMA(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Write_DMA(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize); -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -/* SRAM callback registering/unregistering */ -HAL_StatusTypeDef HAL_SRAM_RegisterCallback(SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId, pSRAM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SRAM_UnRegisterCallback(SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId); -HAL_StatusTypeDef HAL_SRAM_RegisterDmaCallback(SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId, pSRAM_DmaCallbackTypeDef pCallback); -#endif -/** - * @} - */ - -/** @addtogroup SRAM_Exported_Functions_Group3 - * @{ - */ -/* SRAM Control functions ******************************************************/ -HAL_StatusTypeDef HAL_SRAM_WriteOperation_Enable(SRAM_HandleTypeDef *hsram); -HAL_StatusTypeDef HAL_SRAM_WriteOperation_Disable(SRAM_HandleTypeDef *hsram); -/** - * @} - */ - -/** @addtogroup SRAM_Exported_Functions_Group4 - * @{ - */ -/* SRAM State functions *********************************************************/ -HAL_SRAM_StateTypeDef HAL_SRAM_GetState(SRAM_HandleTypeDef *hsram); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SRAM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h deleted file mode 100644 index 2322bf0999c2c5d..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h +++ /dev/null @@ -1,2129 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim.h - * @author MCD Application Team - * @brief Header file of TIM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_TIM_H -#define STM32F4xx_HAL_TIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup TIM - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup TIM_Exported_Types TIM Exported Types - * @{ - */ - -/** - * @brief TIM Time base Configuration Structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t CounterMode; /*!< Specifies the counter mode. - This parameter can be a value of @ref TIM_Counter_Mode */ - - uint32_t Period; /*!< Specifies the period value to be loaded into the active - Auto-Reload Register at the next update event. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t ClockDivision; /*!< Specifies the clock division. - This parameter can be a value of @ref TIM_ClockDivision */ - - uint32_t RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter - reaches zero, an update event is generated and counting restarts - from the RCR value (N). - This means in PWM mode that (N+1) corresponds to: - - the number of PWM periods in edge-aligned mode - - the number of half PWM period in center-aligned mode - GP timers: this parameter must be a number between Min_Data = 0x00 and - Max_Data = 0xFF. - Advanced timers: this parameter must be a number between Min_Data = 0x0000 and - Max_Data = 0xFFFF. */ - - uint32_t AutoReloadPreload; /*!< Specifies the auto-reload preload. - This parameter can be a value of @ref TIM_AutoReloadPreload */ -} TIM_Base_InitTypeDef; - -/** - * @brief TIM Output Compare Configuration Structure definition - */ -typedef struct -{ - uint32_t OCMode; /*!< Specifies the TIM mode. - This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ - - uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_Output_Compare_Polarity */ - - uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_Output_Compare_N_Polarity - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCFastMode; /*!< Specifies the Fast mode state. - This parameter can be a value of @ref TIM_Output_Fast_State - @note This parameter is valid only in PWM1 and PWM2 mode. */ - - - uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ -} TIM_OC_InitTypeDef; - -/** - * @brief TIM One Pulse Mode Configuration Structure definition - */ -typedef struct -{ - uint32_t OCMode; /*!< Specifies the TIM mode. - This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ - - uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_Output_Compare_Polarity */ - - uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_Output_Compare_N_Polarity - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t ICSelection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t ICFilter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_OnePulse_InitTypeDef; - -/** - * @brief TIM Input Capture Configuration Structure definition - */ -typedef struct -{ - uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t ICSelection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t ICPrescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t ICFilter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_IC_InitTypeDef; - -/** - * @brief TIM Encoder Configuration Structure definition - */ -typedef struct -{ - uint32_t EncoderMode; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Mode */ - - uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Input_Polarity */ - - uint32_t IC1Selection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC1Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t IC2Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Input_Polarity */ - - uint32_t IC2Selection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t IC2Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC2Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_Encoder_InitTypeDef; - -/** - * @brief Clock Configuration Handle Structure definition - */ -typedef struct -{ - uint32_t ClockSource; /*!< TIM clock sources - This parameter can be a value of @ref TIM_Clock_Source */ - uint32_t ClockPolarity; /*!< TIM clock polarity - This parameter can be a value of @ref TIM_Clock_Polarity */ - uint32_t ClockPrescaler; /*!< TIM clock prescaler - This parameter can be a value of @ref TIM_Clock_Prescaler */ - uint32_t ClockFilter; /*!< TIM clock filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_ClockConfigTypeDef; - -/** - * @brief TIM Clear Input Configuration Handle Structure definition - */ -typedef struct -{ - uint32_t ClearInputState; /*!< TIM clear Input state - This parameter can be ENABLE or DISABLE */ - uint32_t ClearInputSource; /*!< TIM clear Input sources - This parameter can be a value of @ref TIM_ClearInput_Source */ - uint32_t ClearInputPolarity; /*!< TIM Clear Input polarity - This parameter can be a value of @ref TIM_ClearInput_Polarity */ - uint32_t ClearInputPrescaler; /*!< TIM Clear Input prescaler - This parameter must be 0: When OCRef clear feature is used with ETR source, - ETR prescaler must be off */ - uint32_t ClearInputFilter; /*!< TIM Clear Input filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_ClearInputConfigTypeDef; - -/** - * @brief TIM Master configuration Structure definition - */ -typedef struct -{ - uint32_t MasterOutputTrigger; /*!< Trigger output (TRGO) selection - This parameter can be a value of @ref TIM_Master_Mode_Selection */ - uint32_t MasterSlaveMode; /*!< Master/slave mode selection - This parameter can be a value of @ref TIM_Master_Slave_Mode - @note When the Master/slave mode is enabled, the effect of - an event on the trigger input (TRGI) is delayed to allow a - perfect synchronization between the current timer and its - slaves (through TRGO). It is not mandatory in case of timer - synchronization mode. */ -} TIM_MasterConfigTypeDef; - -/** - * @brief TIM Slave configuration Structure definition - */ -typedef struct -{ - uint32_t SlaveMode; /*!< Slave mode selection - This parameter can be a value of @ref TIM_Slave_Mode */ - uint32_t InputTrigger; /*!< Input Trigger source - This parameter can be a value of @ref TIM_Trigger_Selection */ - uint32_t TriggerPolarity; /*!< Input Trigger polarity - This parameter can be a value of @ref TIM_Trigger_Polarity */ - uint32_t TriggerPrescaler; /*!< Input trigger prescaler - This parameter can be a value of @ref TIM_Trigger_Prescaler */ - uint32_t TriggerFilter; /*!< Input trigger filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - -} TIM_SlaveConfigTypeDef; - -/** - * @brief TIM Break input(s) and Dead time configuration Structure definition - * @note 2 break inputs can be configured (BKIN and BKIN2) with configurable - * filter and polarity. - */ -typedef struct -{ - uint32_t OffStateRunMode; /*!< TIM off state in run mode, This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */ - - uint32_t OffStateIDLEMode; /*!< TIM off state in IDLE mode, This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */ - - uint32_t LockLevel; /*!< TIM Lock level, This parameter can be a value of @ref TIM_Lock_level */ - - uint32_t DeadTime; /*!< TIM dead Time, This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF */ - - uint32_t BreakState; /*!< TIM Break State, This parameter can be a value of @ref TIM_Break_Input_enable_disable */ - - uint32_t BreakPolarity; /*!< TIM Break input polarity, This parameter can be a value of @ref TIM_Break_Polarity */ - - uint32_t BreakFilter; /*!< Specifies the break input filter.This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t AutomaticOutput; /*!< TIM Automatic Output Enable state, This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ - -} TIM_BreakDeadTimeConfigTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_TIM_STATE_RESET = 0x00U, /*!< Peripheral not yet initialized or disabled */ - HAL_TIM_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_TIM_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */ - HAL_TIM_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_TIM_STATE_ERROR = 0x04U /*!< Reception process is ongoing */ -} HAL_TIM_StateTypeDef; - -/** - * @brief TIM Channel States definition - */ -typedef enum -{ - HAL_TIM_CHANNEL_STATE_RESET = 0x00U, /*!< TIM Channel initial state */ - HAL_TIM_CHANNEL_STATE_READY = 0x01U, /*!< TIM Channel ready for use */ - HAL_TIM_CHANNEL_STATE_BUSY = 0x02U, /*!< An internal process is ongoing on the TIM channel */ -} HAL_TIM_ChannelStateTypeDef; - -/** - * @brief DMA Burst States definition - */ -typedef enum -{ - HAL_DMA_BURST_STATE_RESET = 0x00U, /*!< DMA Burst initial state */ - HAL_DMA_BURST_STATE_READY = 0x01U, /*!< DMA Burst ready for use */ - HAL_DMA_BURST_STATE_BUSY = 0x02U, /*!< Ongoing DMA Burst */ -} HAL_TIM_DMABurstStateTypeDef; - -/** - * @brief HAL Active channel structures definition - */ -typedef enum -{ - HAL_TIM_ACTIVE_CHANNEL_1 = 0x01U, /*!< The active channel is 1 */ - HAL_TIM_ACTIVE_CHANNEL_2 = 0x02U, /*!< The active channel is 2 */ - HAL_TIM_ACTIVE_CHANNEL_3 = 0x04U, /*!< The active channel is 3 */ - HAL_TIM_ACTIVE_CHANNEL_4 = 0x08U, /*!< The active channel is 4 */ - HAL_TIM_ACTIVE_CHANNEL_CLEARED = 0x00U /*!< All active channels cleared */ -} HAL_TIM_ActiveChannel; - -/** - * @brief TIM Time Base Handle Structure definition - */ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -typedef struct __TIM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -{ - TIM_TypeDef *Instance; /*!< Register base address */ - TIM_Base_InitTypeDef Init; /*!< TIM Time Base required parameters */ - HAL_TIM_ActiveChannel Channel; /*!< Active channel */ - DMA_HandleTypeDef *hdma[7]; /*!< DMA Handlers array - This array is accessed by a @ref DMA_Handle_index */ - HAL_LockTypeDef Lock; /*!< Locking object */ - __IO HAL_TIM_StateTypeDef State; /*!< TIM operation state */ - __IO HAL_TIM_ChannelStateTypeDef ChannelState[4]; /*!< TIM channel operation state */ - __IO HAL_TIM_ChannelStateTypeDef ChannelNState[4]; /*!< TIM complementary channel operation state */ - __IO HAL_TIM_DMABurstStateTypeDef DMABurstState; /*!< DMA burst operation state */ - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - void (* Base_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp Init Callback */ - void (* Base_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp DeInit Callback */ - void (* IC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp Init Callback */ - void (* IC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp DeInit Callback */ - void (* OC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp Init Callback */ - void (* OC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp DeInit Callback */ - void (* PWM_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp Init Callback */ - void (* PWM_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp DeInit Callback */ - void (* OnePulse_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp Init Callback */ - void (* OnePulse_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp DeInit Callback */ - void (* Encoder_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp Init Callback */ - void (* Encoder_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp DeInit Callback */ - void (* HallSensor_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp Init Callback */ - void (* HallSensor_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp DeInit Callback */ - void (* PeriodElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed Callback */ - void (* PeriodElapsedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed half complete Callback */ - void (* TriggerCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger Callback */ - void (* TriggerHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger half complete Callback */ - void (* IC_CaptureCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture Callback */ - void (* IC_CaptureHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture half complete Callback */ - void (* OC_DelayElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Output Compare Delay Elapsed Callback */ - void (* PWM_PulseFinishedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished Callback */ - void (* PWM_PulseFinishedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished half complete Callback */ - void (* ErrorCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Error Callback */ - void (* CommutationCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation Callback */ - void (* CommutationHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation half complete Callback */ - void (* BreakCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Break Callback */ -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} TIM_HandleTypeDef; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL TIM Callback ID enumeration definition - */ -typedef enum -{ - HAL_TIM_BASE_MSPINIT_CB_ID = 0x00U /*!< TIM Base MspInit Callback ID */ - , HAL_TIM_BASE_MSPDEINIT_CB_ID = 0x01U /*!< TIM Base MspDeInit Callback ID */ - , HAL_TIM_IC_MSPINIT_CB_ID = 0x02U /*!< TIM IC MspInit Callback ID */ - , HAL_TIM_IC_MSPDEINIT_CB_ID = 0x03U /*!< TIM IC MspDeInit Callback ID */ - , HAL_TIM_OC_MSPINIT_CB_ID = 0x04U /*!< TIM OC MspInit Callback ID */ - , HAL_TIM_OC_MSPDEINIT_CB_ID = 0x05U /*!< TIM OC MspDeInit Callback ID */ - , HAL_TIM_PWM_MSPINIT_CB_ID = 0x06U /*!< TIM PWM MspInit Callback ID */ - , HAL_TIM_PWM_MSPDEINIT_CB_ID = 0x07U /*!< TIM PWM MspDeInit Callback ID */ - , HAL_TIM_ONE_PULSE_MSPINIT_CB_ID = 0x08U /*!< TIM One Pulse MspInit Callback ID */ - , HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID = 0x09U /*!< TIM One Pulse MspDeInit Callback ID */ - , HAL_TIM_ENCODER_MSPINIT_CB_ID = 0x0AU /*!< TIM Encoder MspInit Callback ID */ - , HAL_TIM_ENCODER_MSPDEINIT_CB_ID = 0x0BU /*!< TIM Encoder MspDeInit Callback ID */ - , HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID = 0x0CU /*!< TIM Hall Sensor MspDeInit Callback ID */ - , HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID = 0x0DU /*!< TIM Hall Sensor MspDeInit Callback ID */ - , HAL_TIM_PERIOD_ELAPSED_CB_ID = 0x0EU /*!< TIM Period Elapsed Callback ID */ - , HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID = 0x0FU /*!< TIM Period Elapsed half complete Callback ID */ - , HAL_TIM_TRIGGER_CB_ID = 0x10U /*!< TIM Trigger Callback ID */ - , HAL_TIM_TRIGGER_HALF_CB_ID = 0x11U /*!< TIM Trigger half complete Callback ID */ - - , HAL_TIM_IC_CAPTURE_CB_ID = 0x12U /*!< TIM Input Capture Callback ID */ - , HAL_TIM_IC_CAPTURE_HALF_CB_ID = 0x13U /*!< TIM Input Capture half complete Callback ID */ - , HAL_TIM_OC_DELAY_ELAPSED_CB_ID = 0x14U /*!< TIM Output Compare Delay Elapsed Callback ID */ - , HAL_TIM_PWM_PULSE_FINISHED_CB_ID = 0x15U /*!< TIM PWM Pulse Finished Callback ID */ - , HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID = 0x16U /*!< TIM PWM Pulse Finished half complete Callback ID */ - , HAL_TIM_ERROR_CB_ID = 0x17U /*!< TIM Error Callback ID */ - , HAL_TIM_COMMUTATION_CB_ID = 0x18U /*!< TIM Commutation Callback ID */ - , HAL_TIM_COMMUTATION_HALF_CB_ID = 0x19U /*!< TIM Commutation half complete Callback ID */ - , HAL_TIM_BREAK_CB_ID = 0x1AU /*!< TIM Break Callback ID */ -} HAL_TIM_CallbackIDTypeDef; - -/** - * @brief HAL TIM Callback pointer definition - */ -typedef void (*pTIM_CallbackTypeDef)(TIM_HandleTypeDef *htim); /*!< pointer to the TIM callback function */ - -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* End of exported types -----------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup TIM_Exported_Constants TIM Exported Constants - * @{ - */ - -/** @defgroup TIM_ClearInput_Source TIM Clear Input Source - * @{ - */ -#define TIM_CLEARINPUTSOURCE_NONE 0x00000000U /*!< OCREF_CLR is disabled */ -#define TIM_CLEARINPUTSOURCE_ETR 0x00000001U /*!< OCREF_CLR is connected to ETRF input */ -/** - * @} - */ - -/** @defgroup TIM_DMA_Base_address TIM DMA Base Address - * @{ - */ -#define TIM_DMABASE_CR1 0x00000000U -#define TIM_DMABASE_CR2 0x00000001U -#define TIM_DMABASE_SMCR 0x00000002U -#define TIM_DMABASE_DIER 0x00000003U -#define TIM_DMABASE_SR 0x00000004U -#define TIM_DMABASE_EGR 0x00000005U -#define TIM_DMABASE_CCMR1 0x00000006U -#define TIM_DMABASE_CCMR2 0x00000007U -#define TIM_DMABASE_CCER 0x00000008U -#define TIM_DMABASE_CNT 0x00000009U -#define TIM_DMABASE_PSC 0x0000000AU -#define TIM_DMABASE_ARR 0x0000000BU -#define TIM_DMABASE_RCR 0x0000000CU -#define TIM_DMABASE_CCR1 0x0000000DU -#define TIM_DMABASE_CCR2 0x0000000EU -#define TIM_DMABASE_CCR3 0x0000000FU -#define TIM_DMABASE_CCR4 0x00000010U -#define TIM_DMABASE_BDTR 0x00000011U -#define TIM_DMABASE_DCR 0x00000012U -#define TIM_DMABASE_DMAR 0x00000013U -/** - * @} - */ - -/** @defgroup TIM_Event_Source TIM Event Source - * @{ - */ -#define TIM_EVENTSOURCE_UPDATE TIM_EGR_UG /*!< Reinitialize the counter and generates an update of the registers */ -#define TIM_EVENTSOURCE_CC1 TIM_EGR_CC1G /*!< A capture/compare event is generated on channel 1 */ -#define TIM_EVENTSOURCE_CC2 TIM_EGR_CC2G /*!< A capture/compare event is generated on channel 2 */ -#define TIM_EVENTSOURCE_CC3 TIM_EGR_CC3G /*!< A capture/compare event is generated on channel 3 */ -#define TIM_EVENTSOURCE_CC4 TIM_EGR_CC4G /*!< A capture/compare event is generated on channel 4 */ -#define TIM_EVENTSOURCE_COM TIM_EGR_COMG /*!< A commutation event is generated */ -#define TIM_EVENTSOURCE_TRIGGER TIM_EGR_TG /*!< A trigger event is generated */ -#define TIM_EVENTSOURCE_BREAK TIM_EGR_BG /*!< A break event is generated */ -/** - * @} - */ - -/** @defgroup TIM_Input_Channel_Polarity TIM Input Channel polarity - * @{ - */ -#define TIM_INPUTCHANNELPOLARITY_RISING 0x00000000U /*!< Polarity for TIx source */ -#define TIM_INPUTCHANNELPOLARITY_FALLING TIM_CCER_CC1P /*!< Polarity for TIx source */ -#define TIM_INPUTCHANNELPOLARITY_BOTHEDGE (TIM_CCER_CC1P | TIM_CCER_CC1NP) /*!< Polarity for TIx source */ -/** - * @} - */ - -/** @defgroup TIM_ETR_Polarity TIM ETR Polarity - * @{ - */ -#define TIM_ETRPOLARITY_INVERTED TIM_SMCR_ETP /*!< Polarity for ETR source */ -#define TIM_ETRPOLARITY_NONINVERTED 0x00000000U /*!< Polarity for ETR source */ -/** - * @} - */ - -/** @defgroup TIM_ETR_Prescaler TIM ETR Prescaler - * @{ - */ -#define TIM_ETRPRESCALER_DIV1 0x00000000U /*!< No prescaler is used */ -#define TIM_ETRPRESCALER_DIV2 TIM_SMCR_ETPS_0 /*!< ETR input source is divided by 2 */ -#define TIM_ETRPRESCALER_DIV4 TIM_SMCR_ETPS_1 /*!< ETR input source is divided by 4 */ -#define TIM_ETRPRESCALER_DIV8 TIM_SMCR_ETPS /*!< ETR input source is divided by 8 */ -/** - * @} - */ - -/** @defgroup TIM_Counter_Mode TIM Counter Mode - * @{ - */ -#define TIM_COUNTERMODE_UP 0x00000000U /*!< Counter used as up-counter */ -#define TIM_COUNTERMODE_DOWN TIM_CR1_DIR /*!< Counter used as down-counter */ -#define TIM_COUNTERMODE_CENTERALIGNED1 TIM_CR1_CMS_0 /*!< Center-aligned mode 1 */ -#define TIM_COUNTERMODE_CENTERALIGNED2 TIM_CR1_CMS_1 /*!< Center-aligned mode 2 */ -#define TIM_COUNTERMODE_CENTERALIGNED3 TIM_CR1_CMS /*!< Center-aligned mode 3 */ -/** - * @} - */ - -/** @defgroup TIM_ClockDivision TIM Clock Division - * @{ - */ -#define TIM_CLOCKDIVISION_DIV1 0x00000000U /*!< Clock division: tDTS=tCK_INT */ -#define TIM_CLOCKDIVISION_DIV2 TIM_CR1_CKD_0 /*!< Clock division: tDTS=2*tCK_INT */ -#define TIM_CLOCKDIVISION_DIV4 TIM_CR1_CKD_1 /*!< Clock division: tDTS=4*tCK_INT */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_State TIM Output Compare State - * @{ - */ -#define TIM_OUTPUTSTATE_DISABLE 0x00000000U /*!< Capture/Compare 1 output disabled */ -#define TIM_OUTPUTSTATE_ENABLE TIM_CCER_CC1E /*!< Capture/Compare 1 output enabled */ -/** - * @} - */ - -/** @defgroup TIM_AutoReloadPreload TIM Auto-Reload Preload - * @{ - */ -#define TIM_AUTORELOAD_PRELOAD_DISABLE 0x00000000U /*!< TIMx_ARR register is not buffered */ -#define TIM_AUTORELOAD_PRELOAD_ENABLE TIM_CR1_ARPE /*!< TIMx_ARR register is buffered */ - -/** - * @} - */ - -/** @defgroup TIM_Output_Fast_State TIM Output Fast State - * @{ - */ -#define TIM_OCFAST_DISABLE 0x00000000U /*!< Output Compare fast disable */ -#define TIM_OCFAST_ENABLE TIM_CCMR1_OC1FE /*!< Output Compare fast enable */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_State TIM Complementary Output Compare State - * @{ - */ -#define TIM_OUTPUTNSTATE_DISABLE 0x00000000U /*!< OCxN is disabled */ -#define TIM_OUTPUTNSTATE_ENABLE TIM_CCER_CC1NE /*!< OCxN is enabled */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_Polarity TIM Output Compare Polarity - * @{ - */ -#define TIM_OCPOLARITY_HIGH 0x00000000U /*!< Capture/Compare output polarity */ -#define TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< Capture/Compare output polarity */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_Polarity TIM Complementary Output Compare Polarity - * @{ - */ -#define TIM_OCNPOLARITY_HIGH 0x00000000U /*!< Capture/Compare complementary output polarity */ -#define TIM_OCNPOLARITY_LOW TIM_CCER_CC1NP /*!< Capture/Compare complementary output polarity */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_Idle_State TIM Output Compare Idle State - * @{ - */ -#define TIM_OCIDLESTATE_SET TIM_CR2_OIS1 /*!< Output Idle state: OCx=1 when MOE=0 */ -#define TIM_OCIDLESTATE_RESET 0x00000000U /*!< Output Idle state: OCx=0 when MOE=0 */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_Idle_State TIM Complementary Output Compare Idle State - * @{ - */ -#define TIM_OCNIDLESTATE_SET TIM_CR2_OIS1N /*!< Complementary output Idle state: OCxN=1 when MOE=0 */ -#define TIM_OCNIDLESTATE_RESET 0x00000000U /*!< Complementary output Idle state: OCxN=0 when MOE=0 */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Polarity TIM Input Capture Polarity - * @{ - */ -#define TIM_ICPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Capture triggered by rising edge on timer input */ -#define TIM_ICPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Capture triggered by falling edge on timer input */ -#define TIM_ICPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Capture triggered by both rising and falling edges on timer input*/ -/** - * @} - */ - -/** @defgroup TIM_Encoder_Input_Polarity TIM Encoder Input Polarity - * @{ - */ -#define TIM_ENCODERINPUTPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Encoder input with rising edge polarity */ -#define TIM_ENCODERINPUTPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Encoder input with falling edge polarity */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Selection TIM Input Capture Selection - * @{ - */ -#define TIM_ICSELECTION_DIRECTTI TIM_CCMR1_CC1S_0 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC1, IC2, IC3 or IC4, respectively */ -#define TIM_ICSELECTION_INDIRECTTI TIM_CCMR1_CC1S_1 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC2, IC1, IC4 or IC3, respectively */ -#define TIM_ICSELECTION_TRC TIM_CCMR1_CC1S /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Prescaler TIM Input Capture Prescaler - * @{ - */ -#define TIM_ICPSC_DIV1 0x00000000U /*!< Capture performed each time an edge is detected on the capture input */ -#define TIM_ICPSC_DIV2 TIM_CCMR1_IC1PSC_0 /*!< Capture performed once every 2 events */ -#define TIM_ICPSC_DIV4 TIM_CCMR1_IC1PSC_1 /*!< Capture performed once every 4 events */ -#define TIM_ICPSC_DIV8 TIM_CCMR1_IC1PSC /*!< Capture performed once every 8 events */ -/** - * @} - */ - -/** @defgroup TIM_One_Pulse_Mode TIM One Pulse Mode - * @{ - */ -#define TIM_OPMODE_SINGLE TIM_CR1_OPM /*!< Counter stops counting at the next update event */ -#define TIM_OPMODE_REPETITIVE 0x00000000U /*!< Counter is not stopped at update event */ -/** - * @} - */ - -/** @defgroup TIM_Encoder_Mode TIM Encoder Mode - * @{ - */ -#define TIM_ENCODERMODE_TI1 TIM_SMCR_SMS_0 /*!< Quadrature encoder mode 1, x2 mode, counts up/down on TI1FP1 edge depending on TI2FP2 level */ -#define TIM_ENCODERMODE_TI2 TIM_SMCR_SMS_1 /*!< Quadrature encoder mode 2, x2 mode, counts up/down on TI2FP2 edge depending on TI1FP1 level. */ -#define TIM_ENCODERMODE_TI12 (TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< Quadrature encoder mode 3, x4 mode, counts up/down on both TI1FP1 and TI2FP2 edges depending on the level of the other input. */ -/** - * @} - */ - -/** @defgroup TIM_Interrupt_definition TIM interrupt Definition - * @{ - */ -#define TIM_IT_UPDATE TIM_DIER_UIE /*!< Update interrupt */ -#define TIM_IT_CC1 TIM_DIER_CC1IE /*!< Capture/Compare 1 interrupt */ -#define TIM_IT_CC2 TIM_DIER_CC2IE /*!< Capture/Compare 2 interrupt */ -#define TIM_IT_CC3 TIM_DIER_CC3IE /*!< Capture/Compare 3 interrupt */ -#define TIM_IT_CC4 TIM_DIER_CC4IE /*!< Capture/Compare 4 interrupt */ -#define TIM_IT_COM TIM_DIER_COMIE /*!< Commutation interrupt */ -#define TIM_IT_TRIGGER TIM_DIER_TIE /*!< Trigger interrupt */ -#define TIM_IT_BREAK TIM_DIER_BIE /*!< Break interrupt */ -/** - * @} - */ - -/** @defgroup TIM_Commutation_Source TIM Commutation Source - * @{ - */ -#define TIM_COMMUTATION_TRGI TIM_CR2_CCUS /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit or when an rising edge occurs on trigger input */ -#define TIM_COMMUTATION_SOFTWARE 0x00000000U /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit */ -/** - * @} - */ - -/** @defgroup TIM_DMA_sources TIM DMA Sources - * @{ - */ -#define TIM_DMA_UPDATE TIM_DIER_UDE /*!< DMA request is triggered by the update event */ -#define TIM_DMA_CC1 TIM_DIER_CC1DE /*!< DMA request is triggered by the capture/compare macth 1 event */ -#define TIM_DMA_CC2 TIM_DIER_CC2DE /*!< DMA request is triggered by the capture/compare macth 2 event event */ -#define TIM_DMA_CC3 TIM_DIER_CC3DE /*!< DMA request is triggered by the capture/compare macth 3 event event */ -#define TIM_DMA_CC4 TIM_DIER_CC4DE /*!< DMA request is triggered by the capture/compare macth 4 event event */ -#define TIM_DMA_COM TIM_DIER_COMDE /*!< DMA request is triggered by the commutation event */ -#define TIM_DMA_TRIGGER TIM_DIER_TDE /*!< DMA request is triggered by the trigger event */ -/** - * @} - */ - -/** @defgroup TIM_Flag_definition TIM Flag Definition - * @{ - */ -#define TIM_FLAG_UPDATE TIM_SR_UIF /*!< Update interrupt flag */ -#define TIM_FLAG_CC1 TIM_SR_CC1IF /*!< Capture/Compare 1 interrupt flag */ -#define TIM_FLAG_CC2 TIM_SR_CC2IF /*!< Capture/Compare 2 interrupt flag */ -#define TIM_FLAG_CC3 TIM_SR_CC3IF /*!< Capture/Compare 3 interrupt flag */ -#define TIM_FLAG_CC4 TIM_SR_CC4IF /*!< Capture/Compare 4 interrupt flag */ -#define TIM_FLAG_COM TIM_SR_COMIF /*!< Commutation interrupt flag */ -#define TIM_FLAG_TRIGGER TIM_SR_TIF /*!< Trigger interrupt flag */ -#define TIM_FLAG_BREAK TIM_SR_BIF /*!< Break interrupt flag */ -#define TIM_FLAG_CC1OF TIM_SR_CC1OF /*!< Capture 1 overcapture flag */ -#define TIM_FLAG_CC2OF TIM_SR_CC2OF /*!< Capture 2 overcapture flag */ -#define TIM_FLAG_CC3OF TIM_SR_CC3OF /*!< Capture 3 overcapture flag */ -#define TIM_FLAG_CC4OF TIM_SR_CC4OF /*!< Capture 4 overcapture flag */ -/** - * @} - */ - -/** @defgroup TIM_Channel TIM Channel - * @{ - */ -#define TIM_CHANNEL_1 0x00000000U /*!< Capture/compare channel 1 identifier */ -#define TIM_CHANNEL_2 0x00000004U /*!< Capture/compare channel 2 identifier */ -#define TIM_CHANNEL_3 0x00000008U /*!< Capture/compare channel 3 identifier */ -#define TIM_CHANNEL_4 0x0000000CU /*!< Capture/compare channel 4 identifier */ -#define TIM_CHANNEL_ALL 0x0000003CU /*!< Global Capture/compare channel identifier */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Source TIM Clock Source - * @{ - */ -#define TIM_CLOCKSOURCE_ETRMODE2 TIM_SMCR_ETPS_1 /*!< External clock source mode 2 */ -#define TIM_CLOCKSOURCE_INTERNAL TIM_SMCR_ETPS_0 /*!< Internal clock source */ -#define TIM_CLOCKSOURCE_ITR0 TIM_TS_ITR0 /*!< External clock source mode 1 (ITR0) */ -#define TIM_CLOCKSOURCE_ITR1 TIM_TS_ITR1 /*!< External clock source mode 1 (ITR1) */ -#define TIM_CLOCKSOURCE_ITR2 TIM_TS_ITR2 /*!< External clock source mode 1 (ITR2) */ -#define TIM_CLOCKSOURCE_ITR3 TIM_TS_ITR3 /*!< External clock source mode 1 (ITR3) */ -#define TIM_CLOCKSOURCE_TI1ED TIM_TS_TI1F_ED /*!< External clock source mode 1 (TTI1FP1 + edge detect.) */ -#define TIM_CLOCKSOURCE_TI1 TIM_TS_TI1FP1 /*!< External clock source mode 1 (TTI1FP1) */ -#define TIM_CLOCKSOURCE_TI2 TIM_TS_TI2FP2 /*!< External clock source mode 1 (TTI2FP2) */ -#define TIM_CLOCKSOURCE_ETRMODE1 TIM_TS_ETRF /*!< External clock source mode 1 (ETRF) */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Polarity TIM Clock Polarity - * @{ - */ -#define TIM_CLOCKPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx clock sources */ -#define TIM_CLOCKPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx clock sources */ -#define TIM_CLOCKPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIx clock sources */ -#define TIM_CLOCKPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIx clock sources */ -#define TIM_CLOCKPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIx clock sources */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Prescaler TIM Clock Prescaler - * @{ - */ -#define TIM_CLOCKPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_CLOCKPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Clock: Capture performed once every 2 events. */ -#define TIM_CLOCKPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Clock: Capture performed once every 4 events. */ -#define TIM_CLOCKPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Clock: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_ClearInput_Polarity TIM Clear Input Polarity - * @{ - */ -#define TIM_CLEARINPUTPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx pin */ -#define TIM_CLEARINPUTPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx pin */ -/** - * @} - */ - -/** @defgroup TIM_ClearInput_Prescaler TIM Clear Input Prescaler - * @{ - */ -#define TIM_CLEARINPUTPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_CLEARINPUTPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR pin: Capture performed once every 2 events. */ -#define TIM_CLEARINPUTPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR pin: Capture performed once every 4 events. */ -#define TIM_CLEARINPUTPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR pin: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_OSSR_Off_State_Selection_for_Run_mode_state TIM OSSR OffState Selection for Run mode state - * @{ - */ -#define TIM_OSSR_ENABLE TIM_BDTR_OSSR /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */ -#define TIM_OSSR_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */ -/** - * @} - */ - -/** @defgroup TIM_OSSI_Off_State_Selection_for_Idle_mode_state TIM OSSI OffState Selection for Idle mode state - * @{ - */ -#define TIM_OSSI_ENABLE TIM_BDTR_OSSI /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */ -#define TIM_OSSI_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */ -/** - * @} - */ -/** @defgroup TIM_Lock_level TIM Lock level - * @{ - */ -#define TIM_LOCKLEVEL_OFF 0x00000000U /*!< LOCK OFF */ -#define TIM_LOCKLEVEL_1 TIM_BDTR_LOCK_0 /*!< LOCK Level 1 */ -#define TIM_LOCKLEVEL_2 TIM_BDTR_LOCK_1 /*!< LOCK Level 2 */ -#define TIM_LOCKLEVEL_3 TIM_BDTR_LOCK /*!< LOCK Level 3 */ -/** - * @} - */ - -/** @defgroup TIM_Break_Input_enable_disable TIM Break Input Enable - * @{ - */ -#define TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break input BRK is enabled */ -#define TIM_BREAK_DISABLE 0x00000000U /*!< Break input BRK is disabled */ -/** - * @} - */ - -/** @defgroup TIM_Break_Polarity TIM Break Input Polarity - * @{ - */ -#define TIM_BREAKPOLARITY_LOW 0x00000000U /*!< Break input BRK is active low */ -#define TIM_BREAKPOLARITY_HIGH TIM_BDTR_BKP /*!< Break input BRK is active high */ -/** - * @} - */ - -/** @defgroup TIM_AOE_Bit_Set_Reset TIM Automatic Output Enable - * @{ - */ -#define TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */ -#define TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event (if none of the break inputs BRK and BRK2 is active) */ -/** - * @} - */ - -/** @defgroup TIM_Master_Mode_Selection TIM Master Mode Selection - * @{ - */ -#define TIM_TRGO_RESET 0x00000000U /*!< TIMx_EGR.UG bit is used as trigger output (TRGO) */ -#define TIM_TRGO_ENABLE TIM_CR2_MMS_0 /*!< TIMx_CR1.CEN bit is used as trigger output (TRGO) */ -#define TIM_TRGO_UPDATE TIM_CR2_MMS_1 /*!< Update event is used as trigger output (TRGO) */ -#define TIM_TRGO_OC1 (TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< Capture or a compare match 1 is used as trigger output (TRGO) */ -#define TIM_TRGO_OC1REF TIM_CR2_MMS_2 /*!< OC1REF signal is used as trigger output (TRGO) */ -#define TIM_TRGO_OC2REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_0) /*!< OC2REF signal is used as trigger output(TRGO) */ -#define TIM_TRGO_OC3REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1) /*!< OC3REF signal is used as trigger output(TRGO) */ -#define TIM_TRGO_OC4REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< OC4REF signal is used as trigger output(TRGO) */ -/** - * @} - */ - -/** @defgroup TIM_Master_Slave_Mode TIM Master/Slave Mode - * @{ - */ -#define TIM_MASTERSLAVEMODE_ENABLE TIM_SMCR_MSM /*!< No action */ -#define TIM_MASTERSLAVEMODE_DISABLE 0x00000000U /*!< Master/slave mode is selected */ -/** - * @} - */ - -/** @defgroup TIM_Slave_Mode TIM Slave mode - * @{ - */ -#define TIM_SLAVEMODE_DISABLE 0x00000000U /*!< Slave mode disabled */ -#define TIM_SLAVEMODE_RESET TIM_SMCR_SMS_2 /*!< Reset Mode */ -#define TIM_SLAVEMODE_GATED (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_0) /*!< Gated Mode */ -#define TIM_SLAVEMODE_TRIGGER (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1) /*!< Trigger Mode */ -#define TIM_SLAVEMODE_EXTERNAL1 (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< External Clock Mode 1 */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_and_PWM_modes TIM Output Compare and PWM Modes - * @{ - */ -#define TIM_OCMODE_TIMING 0x00000000U /*!< Frozen */ -#define TIM_OCMODE_ACTIVE TIM_CCMR1_OC1M_0 /*!< Set channel to active level on match */ -#define TIM_OCMODE_INACTIVE TIM_CCMR1_OC1M_1 /*!< Set channel to inactive level on match */ -#define TIM_OCMODE_TOGGLE (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< Toggle */ -#define TIM_OCMODE_PWM1 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1) /*!< PWM mode 1 */ -#define TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< PWM mode 2 */ -#define TIM_OCMODE_FORCED_ACTIVE (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_0) /*!< Force active level */ -#define TIM_OCMODE_FORCED_INACTIVE TIM_CCMR1_OC1M_2 /*!< Force inactive level */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Selection TIM Trigger Selection - * @{ - */ -#define TIM_TS_ITR0 0x00000000U /*!< Internal Trigger 0 (ITR0) */ -#define TIM_TS_ITR1 TIM_SMCR_TS_0 /*!< Internal Trigger 1 (ITR1) */ -#define TIM_TS_ITR2 TIM_SMCR_TS_1 /*!< Internal Trigger 2 (ITR2) */ -#define TIM_TS_ITR3 (TIM_SMCR_TS_0 | TIM_SMCR_TS_1) /*!< Internal Trigger 3 (ITR3) */ -#define TIM_TS_TI1F_ED TIM_SMCR_TS_2 /*!< TI1 Edge Detector (TI1F_ED) */ -#define TIM_TS_TI1FP1 (TIM_SMCR_TS_0 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 1 (TI1FP1) */ -#define TIM_TS_TI2FP2 (TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 2 (TI2FP2) */ -#define TIM_TS_ETRF (TIM_SMCR_TS_0 | TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered External Trigger input (ETRF) */ -#define TIM_TS_NONE 0x0000FFFFU /*!< No trigger selected */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Polarity TIM Trigger Polarity - * @{ - */ -#define TIM_TRIGGERPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx trigger sources */ -#define TIM_TRIGGERPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx trigger sources */ -#define TIM_TRIGGERPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -#define TIM_TRIGGERPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -#define TIM_TRIGGERPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Prescaler TIM Trigger Prescaler - * @{ - */ -#define TIM_TRIGGERPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_TRIGGERPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Trigger: Capture performed once every 2 events. */ -#define TIM_TRIGGERPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Trigger: Capture performed once every 4 events. */ -#define TIM_TRIGGERPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Trigger: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_TI1_Selection TIM TI1 Input Selection - * @{ - */ -#define TIM_TI1SELECTION_CH1 0x00000000U /*!< The TIMx_CH1 pin is connected to TI1 input */ -#define TIM_TI1SELECTION_XORCOMBINATION TIM_CR2_TI1S /*!< The TIMx_CH1, CH2 and CH3 pins are connected to the TI1 input (XOR combination) */ -/** - * @} - */ - -/** @defgroup TIM_DMA_Burst_Length TIM DMA Burst Length - * @{ - */ -#define TIM_DMABURSTLENGTH_1TRANSFER 0x00000000U /*!< The transfer is done to 1 register starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_2TRANSFERS 0x00000100U /*!< The transfer is done to 2 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_3TRANSFERS 0x00000200U /*!< The transfer is done to 3 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_4TRANSFERS 0x00000300U /*!< The transfer is done to 4 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_5TRANSFERS 0x00000400U /*!< The transfer is done to 5 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_6TRANSFERS 0x00000500U /*!< The transfer is done to 6 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_7TRANSFERS 0x00000600U /*!< The transfer is done to 7 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_8TRANSFERS 0x00000700U /*!< The transfer is done to 8 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_9TRANSFERS 0x00000800U /*!< The transfer is done to 9 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_10TRANSFERS 0x00000900U /*!< The transfer is done to 10 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_11TRANSFERS 0x00000A00U /*!< The transfer is done to 11 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_12TRANSFERS 0x00000B00U /*!< The transfer is done to 12 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_13TRANSFERS 0x00000C00U /*!< The transfer is done to 13 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_14TRANSFERS 0x00000D00U /*!< The transfer is done to 14 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_15TRANSFERS 0x00000E00U /*!< The transfer is done to 15 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_16TRANSFERS 0x00000F00U /*!< The transfer is done to 16 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_17TRANSFERS 0x00001000U /*!< The transfer is done to 17 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_18TRANSFERS 0x00001100U /*!< The transfer is done to 18 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -/** - * @} - */ - -/** @defgroup DMA_Handle_index TIM DMA Handle Index - * @{ - */ -#define TIM_DMA_ID_UPDATE ((uint16_t) 0x0000) /*!< Index of the DMA handle used for Update DMA requests */ -#define TIM_DMA_ID_CC1 ((uint16_t) 0x0001) /*!< Index of the DMA handle used for Capture/Compare 1 DMA requests */ -#define TIM_DMA_ID_CC2 ((uint16_t) 0x0002) /*!< Index of the DMA handle used for Capture/Compare 2 DMA requests */ -#define TIM_DMA_ID_CC3 ((uint16_t) 0x0003) /*!< Index of the DMA handle used for Capture/Compare 3 DMA requests */ -#define TIM_DMA_ID_CC4 ((uint16_t) 0x0004) /*!< Index of the DMA handle used for Capture/Compare 4 DMA requests */ -#define TIM_DMA_ID_COMMUTATION ((uint16_t) 0x0005) /*!< Index of the DMA handle used for Commutation DMA requests */ -#define TIM_DMA_ID_TRIGGER ((uint16_t) 0x0006) /*!< Index of the DMA handle used for Trigger DMA requests */ -/** - * @} - */ - -/** @defgroup Channel_CC_State TIM Capture/Compare Channel State - * @{ - */ -#define TIM_CCx_ENABLE 0x00000001U /*!< Input or output channel is enabled */ -#define TIM_CCx_DISABLE 0x00000000U /*!< Input or output channel is disabled */ -#define TIM_CCxN_ENABLE 0x00000004U /*!< Complementary output channel is enabled */ -#define TIM_CCxN_DISABLE 0x00000000U /*!< Complementary output channel is enabled */ -/** - * @} - */ - -/** - * @} - */ -/* End of exported constants -------------------------------------------------*/ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup TIM_Exported_Macros TIM Exported Macros - * @{ - */ - -/** @brief Reset TIM handle state. - * @param __HANDLE__ TIM handle. - * @retval None - */ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_TIM_STATE_RESET; \ - (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \ - (__HANDLE__)->Base_MspInitCallback = NULL; \ - (__HANDLE__)->Base_MspDeInitCallback = NULL; \ - (__HANDLE__)->IC_MspInitCallback = NULL; \ - (__HANDLE__)->IC_MspDeInitCallback = NULL; \ - (__HANDLE__)->OC_MspInitCallback = NULL; \ - (__HANDLE__)->OC_MspDeInitCallback = NULL; \ - (__HANDLE__)->PWM_MspInitCallback = NULL; \ - (__HANDLE__)->PWM_MspDeInitCallback = NULL; \ - (__HANDLE__)->OnePulse_MspInitCallback = NULL; \ - (__HANDLE__)->OnePulse_MspDeInitCallback = NULL; \ - (__HANDLE__)->Encoder_MspInitCallback = NULL; \ - (__HANDLE__)->Encoder_MspDeInitCallback = NULL; \ - (__HANDLE__)->HallSensor_MspInitCallback = NULL; \ - (__HANDLE__)->HallSensor_MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_TIM_STATE_RESET; \ - (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \ - } while(0) -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @brief Enable the TIM peripheral. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|=(TIM_CR1_CEN)) - -/** - * @brief Enable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_MOE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->BDTR|=(TIM_BDTR_MOE)) - -/** - * @brief Disable the TIM peripheral. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_DISABLE(__HANDLE__) \ - do { \ - if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \ - { \ - if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \ - { \ - (__HANDLE__)->Instance->CR1 &= ~(TIM_CR1_CEN); \ - } \ - } \ - } while(0) - -/** - * @brief Disable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - * @note The Main Output Enable of a timer instance is disabled only if all the CCx and CCxN channels have been - * disabled - */ -#define __HAL_TIM_MOE_DISABLE(__HANDLE__) \ - do { \ - if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \ - { \ - if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \ - { \ - (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE); \ - } \ - } \ - } while(0) - -/** - * @brief Disable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - * @note The Main Output Enable of a timer instance is disabled unconditionally - */ -#define __HAL_TIM_MOE_DISABLE_UNCONDITIONALLY(__HANDLE__) (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE) - -/** @brief Enable the specified TIM interrupt. - * @param __HANDLE__ specifies the TIM Handle. - * @param __INTERRUPT__ specifies the TIM interrupt source to enable. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER |= (__INTERRUPT__)) - -/** @brief Disable the specified TIM interrupt. - * @param __HANDLE__ specifies the TIM Handle. - * @param __INTERRUPT__ specifies the TIM interrupt source to disable. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER &= ~(__INTERRUPT__)) - -/** @brief Enable the specified DMA request. - * @param __HANDLE__ specifies the TIM Handle. - * @param __DMA__ specifies the TIM DMA request to enable. - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: Update DMA request - * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request - * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request - * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request - * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request - * @arg TIM_DMA_COM: Commutation DMA request - * @arg TIM_DMA_TRIGGER: Trigger DMA request - * @retval None - */ -#define __HAL_TIM_ENABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER |= (__DMA__)) - -/** @brief Disable the specified DMA request. - * @param __HANDLE__ specifies the TIM Handle. - * @param __DMA__ specifies the TIM DMA request to disable. - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: Update DMA request - * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request - * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request - * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request - * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request - * @arg TIM_DMA_COM: Commutation DMA request - * @arg TIM_DMA_TRIGGER: Trigger DMA request - * @retval None - */ -#define __HAL_TIM_DISABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER &= ~(__DMA__)) - -/** @brief Check whether the specified TIM interrupt flag is set or not. - * @param __HANDLE__ specifies the TIM Handle. - * @param __FLAG__ specifies the TIM interrupt flag to check. - * This parameter can be one of the following values: - * @arg TIM_FLAG_UPDATE: Update interrupt flag - * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag - * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag - * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag - * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag - * @arg TIM_FLAG_COM: Commutation interrupt flag - * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag - * @arg TIM_FLAG_BREAK: Break interrupt flag - * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag - * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag - * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag - * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_TIM_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR &(__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified TIM interrupt flag. - * @param __HANDLE__ specifies the TIM Handle. - * @param __FLAG__ specifies the TIM interrupt flag to clear. - * This parameter can be one of the following values: - * @arg TIM_FLAG_UPDATE: Update interrupt flag - * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag - * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag - * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag - * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag - * @arg TIM_FLAG_COM: Commutation interrupt flag - * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag - * @arg TIM_FLAG_BREAK: Break interrupt flag - * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag - * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag - * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag - * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_TIM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** - * @brief Check whether the specified TIM interrupt source is enabled or not. - * @param __HANDLE__ TIM handle - * @param __INTERRUPT__ specifies the TIM interrupt source to check. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval The state of TIM_IT (SET or RESET). - */ -#define __HAL_TIM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->DIER & (__INTERRUPT__)) \ - == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Clear the TIM interrupt pending bits. - * @param __HANDLE__ TIM handle - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_CLEAR_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->SR = ~(__INTERRUPT__)) - -/** - * @brief Indicates whether or not the TIM Counter is used as downcounter. - * @param __HANDLE__ TIM handle. - * @retval False (Counter used as upcounter) or True (Counter used as downcounter) - * @note This macro is particularly useful to get the counting mode when the timer operates in Center-aligned mode - * or Encoder mode. - */ -#define __HAL_TIM_IS_TIM_COUNTING_DOWN(__HANDLE__) (((__HANDLE__)->Instance->CR1 &(TIM_CR1_DIR)) == (TIM_CR1_DIR)) - -/** - * @brief Set the TIM Prescaler on runtime. - * @param __HANDLE__ TIM handle. - * @param __PRESC__ specifies the Prescaler new value. - * @retval None - */ -#define __HAL_TIM_SET_PRESCALER(__HANDLE__, __PRESC__) ((__HANDLE__)->Instance->PSC = (__PRESC__)) - -/** - * @brief Set the TIM Counter Register value on runtime. - * @param __HANDLE__ TIM handle. - * @param __COUNTER__ specifies the Counter register new value. - * @retval None - */ -#define __HAL_TIM_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNT = (__COUNTER__)) - -/** - * @brief Get the TIM Counter Register value on runtime. - * @param __HANDLE__ TIM handle. - * @retval 16-bit or 32-bit value of the timer counter register (TIMx_CNT) - */ -#define __HAL_TIM_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->CNT) - -/** - * @brief Set the TIM Autoreload Register value on runtime without calling another time any Init function. - * @param __HANDLE__ TIM handle. - * @param __AUTORELOAD__ specifies the Counter register new value. - * @retval None - */ -#define __HAL_TIM_SET_AUTORELOAD(__HANDLE__, __AUTORELOAD__) \ - do{ \ - (__HANDLE__)->Instance->ARR = (__AUTORELOAD__); \ - (__HANDLE__)->Init.Period = (__AUTORELOAD__); \ - } while(0) - -/** - * @brief Get the TIM Autoreload Register value on runtime. - * @param __HANDLE__ TIM handle. - * @retval 16-bit or 32-bit value of the timer auto-reload register(TIMx_ARR) - */ -#define __HAL_TIM_GET_AUTORELOAD(__HANDLE__) ((__HANDLE__)->Instance->ARR) - -/** - * @brief Set the TIM Clock Division value on runtime without calling another time any Init function. - * @param __HANDLE__ TIM handle. - * @param __CKD__ specifies the clock division value. - * This parameter can be one of the following value: - * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT - * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT - * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT - * @retval None - */ -#define __HAL_TIM_SET_CLOCKDIVISION(__HANDLE__, __CKD__) \ - do{ \ - (__HANDLE__)->Instance->CR1 &= (~TIM_CR1_CKD); \ - (__HANDLE__)->Instance->CR1 |= (__CKD__); \ - (__HANDLE__)->Init.ClockDivision = (__CKD__); \ - } while(0) - -/** - * @brief Get the TIM Clock Division value on runtime. - * @param __HANDLE__ TIM handle. - * @retval The clock division can be one of the following values: - * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT - * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT - * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT - */ -#define __HAL_TIM_GET_CLOCKDIVISION(__HANDLE__) ((__HANDLE__)->Instance->CR1 & TIM_CR1_CKD) - -/** - * @brief Set the TIM Input Capture prescaler on runtime without calling another time HAL_TIM_IC_ConfigChannel() - * function. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __ICPSC__ specifies the Input Capture4 prescaler new value. - * This parameter can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - * @retval None - */ -#define __HAL_TIM_SET_ICPRESCALER(__HANDLE__, __CHANNEL__, __ICPSC__) \ - do{ \ - TIM_RESET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__)); \ - TIM_SET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__), (__ICPSC__)); \ - } while(0) - -/** - * @brief Get the TIM Input Capture prescaler on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: get input capture 1 prescaler value - * @arg TIM_CHANNEL_2: get input capture 2 prescaler value - * @arg TIM_CHANNEL_3: get input capture 3 prescaler value - * @arg TIM_CHANNEL_4: get input capture 4 prescaler value - * @retval The input capture prescaler can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - */ -#define __HAL_TIM_GET_ICPRESCALER(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC1PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC2PSC) >> 8U) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC3PSC) :\ - (((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC4PSC)) >> 8U) - -/** - * @brief Set the TIM Capture Compare Register value on runtime without calling another time ConfigChannel function. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __COMPARE__ specifies the Capture Compare register new value. - * @retval None - */ -#define __HAL_TIM_SET_COMPARE(__HANDLE__, __CHANNEL__, __COMPARE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1 = (__COMPARE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2 = (__COMPARE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3 = (__COMPARE__)) :\ - ((__HANDLE__)->Instance->CCR4 = (__COMPARE__))) - -/** - * @brief Get the TIM Capture Compare Register value on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channel associated with the capture compare register - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: get capture/compare 1 register value - * @arg TIM_CHANNEL_2: get capture/compare 2 register value - * @arg TIM_CHANNEL_3: get capture/compare 3 register value - * @arg TIM_CHANNEL_4: get capture/compare 4 register value - * @retval 16-bit or 32-bit value of the capture/compare register (TIMx_CCRy) - */ -#define __HAL_TIM_GET_COMPARE(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3) :\ - ((__HANDLE__)->Instance->CCR4)) - -/** - * @brief Set the TIM Output compare preload. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval None - */ -#define __HAL_TIM_ENABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3PE) :\ - ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4PE)) - -/** - * @brief Reset the TIM Output compare preload. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval None - */ -#define __HAL_TIM_DISABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3PE) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4PE)) - -/** - * @brief Enable fast mode for a given channel. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @note When fast mode is enabled an active edge on the trigger input acts - * like a compare match on CCx output. Delay to sample the trigger - * input and to activate CCx output is reduced to 3 clock cycles. - * @note Fast mode acts only if the channel is configured in PWM1 or PWM2 mode. - * @retval None - */ -#define __HAL_TIM_ENABLE_OCxFAST(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3FE) :\ - ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4FE)) - -/** - * @brief Disable fast mode for a given channel. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @note When fast mode is disabled CCx output behaves normally depending - * on counter and CCRx values even when the trigger is ON. The minimum - * delay to activate CCx output when an active edge occurs on the - * trigger input is 5 clock cycles. - * @retval None - */ -#define __HAL_TIM_DISABLE_OCxFAST(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE)) - -/** - * @brief Set the Update Request Source (URS) bit of the TIMx_CR1 register. - * @param __HANDLE__ TIM handle. - * @note When the URS bit of the TIMx_CR1 register is set, only counter - * overflow/underflow generates an update interrupt or DMA request (if - * enabled) - * @retval None - */ -#define __HAL_TIM_URS_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|= TIM_CR1_URS) - -/** - * @brief Reset the Update Request Source (URS) bit of the TIMx_CR1 register. - * @param __HANDLE__ TIM handle. - * @note When the URS bit of the TIMx_CR1 register is reset, any of the - * following events generate an update interrupt or DMA request (if - * enabled): - * _ Counter overflow underflow - * _ Setting the UG bit - * _ Update generation through the slave mode controller - * @retval None - */ -#define __HAL_TIM_URS_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1&=~TIM_CR1_URS) - -/** - * @brief Set the TIM Capture x input polarity on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __POLARITY__ Polarity for TIx source - * @arg TIM_INPUTCHANNELPOLARITY_RISING: Rising Edge - * @arg TIM_INPUTCHANNELPOLARITY_FALLING: Falling Edge - * @arg TIM_INPUTCHANNELPOLARITY_BOTHEDGE: Rising and Falling Edge - * @retval None - */ -#define __HAL_TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \ - do{ \ - TIM_RESET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__)); \ - TIM_SET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__), (__POLARITY__)); \ - }while(0) - -/** - * @} - */ -/* End of exported macros ----------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup TIM_Private_Constants TIM Private Constants - * @{ - */ -/* The counter of a timer instance is disabled only if all the CCx and CCxN - channels have been disabled */ -#define TIM_CCER_CCxE_MASK ((uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E)) -#define TIM_CCER_CCxNE_MASK ((uint32_t)(TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) -/** - * @} - */ -/* End of private constants --------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup TIM_Private_Macros TIM Private Macros - * @{ - */ -#define IS_TIM_CLEARINPUT_SOURCE(__MODE__) (((__MODE__) == TIM_CLEARINPUTSOURCE_NONE) || \ - ((__MODE__) == TIM_CLEARINPUTSOURCE_ETR)) - -#define IS_TIM_DMA_BASE(__BASE__) (((__BASE__) == TIM_DMABASE_CR1) || \ - ((__BASE__) == TIM_DMABASE_CR2) || \ - ((__BASE__) == TIM_DMABASE_SMCR) || \ - ((__BASE__) == TIM_DMABASE_DIER) || \ - ((__BASE__) == TIM_DMABASE_SR) || \ - ((__BASE__) == TIM_DMABASE_EGR) || \ - ((__BASE__) == TIM_DMABASE_CCMR1) || \ - ((__BASE__) == TIM_DMABASE_CCMR2) || \ - ((__BASE__) == TIM_DMABASE_CCER) || \ - ((__BASE__) == TIM_DMABASE_CNT) || \ - ((__BASE__) == TIM_DMABASE_PSC) || \ - ((__BASE__) == TIM_DMABASE_ARR) || \ - ((__BASE__) == TIM_DMABASE_RCR) || \ - ((__BASE__) == TIM_DMABASE_CCR1) || \ - ((__BASE__) == TIM_DMABASE_CCR2) || \ - ((__BASE__) == TIM_DMABASE_CCR3) || \ - ((__BASE__) == TIM_DMABASE_CCR4) || \ - ((__BASE__) == TIM_DMABASE_BDTR)) - -#define IS_TIM_EVENT_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFFFF00U) == 0x00000000U) && ((__SOURCE__) != 0x00000000U)) - -#define IS_TIM_COUNTER_MODE(__MODE__) (((__MODE__) == TIM_COUNTERMODE_UP) || \ - ((__MODE__) == TIM_COUNTERMODE_DOWN) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED1) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED2) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED3)) - -#define IS_TIM_CLOCKDIVISION_DIV(__DIV__) (((__DIV__) == TIM_CLOCKDIVISION_DIV1) || \ - ((__DIV__) == TIM_CLOCKDIVISION_DIV2) || \ - ((__DIV__) == TIM_CLOCKDIVISION_DIV4)) - -#define IS_TIM_AUTORELOAD_PRELOAD(PRELOAD) (((PRELOAD) == TIM_AUTORELOAD_PRELOAD_DISABLE) || \ - ((PRELOAD) == TIM_AUTORELOAD_PRELOAD_ENABLE)) - -#define IS_TIM_FAST_STATE(__STATE__) (((__STATE__) == TIM_OCFAST_DISABLE) || \ - ((__STATE__) == TIM_OCFAST_ENABLE)) - -#define IS_TIM_OC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCPOLARITY_HIGH) || \ - ((__POLARITY__) == TIM_OCPOLARITY_LOW)) - -#define IS_TIM_OCN_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCNPOLARITY_HIGH) || \ - ((__POLARITY__) == TIM_OCNPOLARITY_LOW)) - -#define IS_TIM_OCIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCIDLESTATE_SET) || \ - ((__STATE__) == TIM_OCIDLESTATE_RESET)) - -#define IS_TIM_OCNIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCNIDLESTATE_SET) || \ - ((__STATE__) == TIM_OCNIDLESTATE_RESET)) - -#define IS_TIM_ENCODERINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_FALLING)) - -#define IS_TIM_IC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ICPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_ICPOLARITY_FALLING) || \ - ((__POLARITY__) == TIM_ICPOLARITY_BOTHEDGE)) - -#define IS_TIM_IC_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_ICSELECTION_DIRECTTI) || \ - ((__SELECTION__) == TIM_ICSELECTION_INDIRECTTI) || \ - ((__SELECTION__) == TIM_ICSELECTION_TRC)) - -#define IS_TIM_IC_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_ICPSC_DIV1) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV2) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV4) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV8)) - -#define IS_TIM_OPM_MODE(__MODE__) (((__MODE__) == TIM_OPMODE_SINGLE) || \ - ((__MODE__) == TIM_OPMODE_REPETITIVE)) - -#define IS_TIM_ENCODER_MODE(__MODE__) (((__MODE__) == TIM_ENCODERMODE_TI1) || \ - ((__MODE__) == TIM_ENCODERMODE_TI2) || \ - ((__MODE__) == TIM_ENCODERMODE_TI12)) - -#define IS_TIM_DMA_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFF80FFU) == 0x00000000U) && ((__SOURCE__) != 0x00000000U)) - -#define IS_TIM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2) || \ - ((__CHANNEL__) == TIM_CHANNEL_3) || \ - ((__CHANNEL__) == TIM_CHANNEL_4) || \ - ((__CHANNEL__) == TIM_CHANNEL_ALL)) - -#define IS_TIM_OPM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2)) - -#define IS_TIM_COMPLEMENTARY_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2) || \ - ((__CHANNEL__) == TIM_CHANNEL_3)) - -#define IS_TIM_CLOCKSOURCE(__CLOCK__) (((__CLOCK__) == TIM_CLOCKSOURCE_INTERNAL) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR0) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR1) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR3) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI1ED) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI1) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE1)) - -#define IS_TIM_CLOCKPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLOCKPOLARITY_INVERTED) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_NONINVERTED) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_FALLING) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_BOTHEDGE)) - -#define IS_TIM_CLOCKPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV8)) - -#define IS_TIM_CLOCKFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_CLEARINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLEARINPUTPOLARITY_INVERTED) || \ - ((__POLARITY__) == TIM_CLEARINPUTPOLARITY_NONINVERTED)) - -#define IS_TIM_CLEARINPUT_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV8)) - -#define IS_TIM_CLEARINPUT_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_OSSR_STATE(__STATE__) (((__STATE__) == TIM_OSSR_ENABLE) || \ - ((__STATE__) == TIM_OSSR_DISABLE)) - -#define IS_TIM_OSSI_STATE(__STATE__) (((__STATE__) == TIM_OSSI_ENABLE) || \ - ((__STATE__) == TIM_OSSI_DISABLE)) - -#define IS_TIM_LOCK_LEVEL(__LEVEL__) (((__LEVEL__) == TIM_LOCKLEVEL_OFF) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_1) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_2) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_3)) - -#define IS_TIM_BREAK_FILTER(__BRKFILTER__) ((__BRKFILTER__) <= 0xFUL) - - -#define IS_TIM_BREAK_STATE(__STATE__) (((__STATE__) == TIM_BREAK_ENABLE) || \ - ((__STATE__) == TIM_BREAK_DISABLE)) - -#define IS_TIM_BREAK_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_BREAKPOLARITY_LOW) || \ - ((__POLARITY__) == TIM_BREAKPOLARITY_HIGH)) - -#define IS_TIM_AUTOMATIC_OUTPUT_STATE(__STATE__) (((__STATE__) == TIM_AUTOMATICOUTPUT_ENABLE) || \ - ((__STATE__) == TIM_AUTOMATICOUTPUT_DISABLE)) - -#define IS_TIM_TRGO_SOURCE(__SOURCE__) (((__SOURCE__) == TIM_TRGO_RESET) || \ - ((__SOURCE__) == TIM_TRGO_ENABLE) || \ - ((__SOURCE__) == TIM_TRGO_UPDATE) || \ - ((__SOURCE__) == TIM_TRGO_OC1) || \ - ((__SOURCE__) == TIM_TRGO_OC1REF) || \ - ((__SOURCE__) == TIM_TRGO_OC2REF) || \ - ((__SOURCE__) == TIM_TRGO_OC3REF) || \ - ((__SOURCE__) == TIM_TRGO_OC4REF)) - -#define IS_TIM_MSM_STATE(__STATE__) (((__STATE__) == TIM_MASTERSLAVEMODE_ENABLE) || \ - ((__STATE__) == TIM_MASTERSLAVEMODE_DISABLE)) - -#define IS_TIM_SLAVE_MODE(__MODE__) (((__MODE__) == TIM_SLAVEMODE_DISABLE) || \ - ((__MODE__) == TIM_SLAVEMODE_RESET) || \ - ((__MODE__) == TIM_SLAVEMODE_GATED) || \ - ((__MODE__) == TIM_SLAVEMODE_TRIGGER) || \ - ((__MODE__) == TIM_SLAVEMODE_EXTERNAL1)) - -#define IS_TIM_PWM_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_PWM1) || \ - ((__MODE__) == TIM_OCMODE_PWM2)) - -#define IS_TIM_OC_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_TIMING) || \ - ((__MODE__) == TIM_OCMODE_ACTIVE) || \ - ((__MODE__) == TIM_OCMODE_INACTIVE) || \ - ((__MODE__) == TIM_OCMODE_TOGGLE) || \ - ((__MODE__) == TIM_OCMODE_FORCED_ACTIVE) || \ - ((__MODE__) == TIM_OCMODE_FORCED_INACTIVE)) - -#define IS_TIM_TRIGGER_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \ - ((__SELECTION__) == TIM_TS_ITR1) || \ - ((__SELECTION__) == TIM_TS_ITR2) || \ - ((__SELECTION__) == TIM_TS_ITR3) || \ - ((__SELECTION__) == TIM_TS_TI1F_ED) || \ - ((__SELECTION__) == TIM_TS_TI1FP1) || \ - ((__SELECTION__) == TIM_TS_TI2FP2) || \ - ((__SELECTION__) == TIM_TS_ETRF)) - -#define IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \ - ((__SELECTION__) == TIM_TS_ITR1) || \ - ((__SELECTION__) == TIM_TS_ITR2) || \ - ((__SELECTION__) == TIM_TS_ITR3) || \ - ((__SELECTION__) == TIM_TS_NONE)) - -#define IS_TIM_TRIGGERPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_TRIGGERPOLARITY_INVERTED ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_NONINVERTED) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_RISING ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_FALLING ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_BOTHEDGE )) - -#define IS_TIM_TRIGGERPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV8)) - -#define IS_TIM_TRIGGERFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_TI1SELECTION(__TI1SELECTION__) (((__TI1SELECTION__) == TIM_TI1SELECTION_CH1) || \ - ((__TI1SELECTION__) == TIM_TI1SELECTION_XORCOMBINATION)) - -#define IS_TIM_DMA_LENGTH(__LENGTH__) (((__LENGTH__) == TIM_DMABURSTLENGTH_1TRANSFER) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_2TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_3TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_4TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_5TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_6TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_7TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_8TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_9TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_10TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_11TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_12TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_13TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_14TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_15TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_16TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_17TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_18TRANSFERS)) - -#define IS_TIM_DMA_DATA_LENGTH(LENGTH) (((LENGTH) >= 0x1U) && ((LENGTH) < 0x10000U)) - -#define IS_TIM_IC_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_DEADTIME(__DEADTIME__) ((__DEADTIME__) <= 0xFFU) - -#define IS_TIM_SLAVEMODE_TRIGGER_ENABLED(__TRIGGER__) ((__TRIGGER__) == TIM_SLAVEMODE_TRIGGER) - -#define TIM_SET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__, __ICPSC__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= (__ICPSC__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= ((__ICPSC__) << 8U)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= (__ICPSC__)) :\ - ((__HANDLE__)->Instance->CCMR2 |= ((__ICPSC__) << 8U))) - -#define TIM_RESET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC)) - -#define TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER |= (__POLARITY__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 4U)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 8U)) :\ - ((__HANDLE__)->Instance->CCER |= (((__POLARITY__) << 12U)))) - -#define TIM_RESET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP)) :\ - ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP))) - -#define TIM_CHANNEL_STATE_GET(__HANDLE__, __CHANNEL__)\ - (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelState[0] :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelState[1] :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelState[2] :\ - (__HANDLE__)->ChannelState[3]) - -#define TIM_CHANNEL_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__)) :\ - ((__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__))) - -#define TIM_CHANNEL_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \ - (__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__); \ - } while(0) - -#define TIM_CHANNEL_N_STATE_GET(__HANDLE__, __CHANNEL__)\ - (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelNState[0] :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelNState[1] :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelNState[2] :\ - (__HANDLE__)->ChannelNState[3]) - -#define TIM_CHANNEL_N_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelNState[0] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelNState[1] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelNState[2] = (__CHANNEL_STATE__)) :\ - ((__HANDLE__)->ChannelNState[3] = (__CHANNEL_STATE__))) - -#define TIM_CHANNEL_N_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \ - (__HANDLE__)->ChannelNState[0] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[1] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[2] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[3] = \ - (__CHANNEL_STATE__); \ - } while(0) - -/** - * @} - */ -/* End of private macros -----------------------------------------------------*/ - -/* Include TIM HAL Extended module */ -#include "stm32f4xx_hal_tim_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup TIM_Exported_Functions TIM Exported Functions - * @{ - */ - -/** @addtogroup TIM_Exported_Functions_Group1 TIM Time Base functions - * @brief Time Base functions - * @{ - */ -/* Time Base functions ********************************************************/ -HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group2 TIM Output Compare functions - * @brief TIM Output Compare functions - * @{ - */ -/* Timer Output Compare functions *********************************************/ -HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group3 TIM PWM functions - * @brief TIM PWM functions - * @{ - */ -/* Timer PWM functions ********************************************************/ -HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group4 TIM Input Capture functions - * @brief TIM Input Capture functions - * @{ - */ -/* Timer Input Capture functions **********************************************/ -HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group5 TIM One Pulse functions - * @brief TIM One Pulse functions - * @{ - */ -/* Timer One Pulse functions **************************************************/ -HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode); -HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group6 TIM Encoder functions - * @brief TIM Encoder functions - * @{ - */ -/* Timer Encoder functions ****************************************************/ -HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig); -HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1, - uint32_t *pData2, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group7 TIM IRQ handler management - * @brief IRQ handler management - * @{ - */ -/* Interrupt Handler functions ***********************************************/ -void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions - * @brief Peripheral Control functions - * @{ - */ -/* Control functions *********************************************************/ -HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig, - uint32_t OutputChannel, uint32_t InputChannel); -HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, TIM_ClearInputConfigTypeDef *sClearInputConfig, - uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig); -HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection); -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig); -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig); -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc); -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc); -HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource); -uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions - * @brief TIM Callbacks functions - * @{ - */ -/* Callback in non blocking modes (Interrupt and DMA) *************************/ -void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID, - pTIM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions - * @brief Peripheral State functions - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim); - -/* Peripheral Channel state functions ************************************************/ -HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim); -HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private functions----------------------------------------------------------*/ -/** @defgroup TIM_Private_Functions TIM Private Functions - * @{ - */ -void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure); -void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, uint32_t TIM_ICFilter); -void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, - uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter); - -void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma); -void TIM_DMAError(DMA_HandleTypeDef *hdma); -void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma); -void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma); -void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -void TIM_ResetCallback(TIM_HandleTypeDef *htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* End of private functions --------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_TIM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h deleted file mode 100644 index 737fdc4e5e11655..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h +++ /dev/null @@ -1,357 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim_ex.h - * @author MCD Application Team - * @brief Header file of TIM HAL Extended module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_TIM_EX_H -#define STM32F4xx_HAL_TIM_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup TIMEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Types TIM Extended Exported Types - * @{ - */ - -/** - * @brief TIM Hall sensor Configuration Structure definition - */ - -typedef struct -{ - uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC1Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t Commutation_Delay; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ -} TIM_HallSensor_InitTypeDef; -/** - * @} - */ -/* End of exported types -----------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Constants TIM Extended Exported Constants - * @{ - */ - -/** @defgroup TIMEx_Remap TIM Extended Remapping - * @{ - */ -#if defined (TIM2) -#if defined(TIM8) -#define TIM_TIM2_TIM8_TRGO 0x00000000U /*!< TIM2 ITR1 is connected to TIM8 TRGO */ -#else -#define TIM_TIM2_ETH_PTP TIM_OR_ITR1_RMP_0 /*!< TIM2 ITR1 is connected to PTP trigger output */ -#endif /* TIM8 */ -#define TIM_TIM2_USBFS_SOF TIM_OR_ITR1_RMP_1 /*!< TIM2 ITR1 is connected to OTG FS SOF */ -#define TIM_TIM2_USBHS_SOF (TIM_OR_ITR1_RMP_1 | TIM_OR_ITR1_RMP_0) /*!< TIM2 ITR1 is connected to OTG HS SOF */ -#endif /* TIM2 */ - -#define TIM_TIM5_GPIO 0x00000000U /*!< TIM5 TI4 is connected to GPIO */ -#define TIM_TIM5_LSI TIM_OR_TI4_RMP_0 /*!< TIM5 TI4 is connected to LSI */ -#define TIM_TIM5_LSE TIM_OR_TI4_RMP_1 /*!< TIM5 TI4 is connected to LSE */ -#define TIM_TIM5_RTC (TIM_OR_TI4_RMP_1 | TIM_OR_TI4_RMP_0) /*!< TIM5 TI4 is connected to the RTC wakeup interrupt */ - -#define TIM_TIM11_GPIO 0x00000000U /*!< TIM11 TI1 is connected to GPIO */ -#define TIM_TIM11_HSE TIM_OR_TI1_RMP_1 /*!< TIM11 TI1 is connected to HSE_RTC clock */ -#if defined(SPDIFRX) -#define TIM_TIM11_SPDIFRX TIM_OR_TI1_RMP_0 /*!< TIM11 TI1 is connected to SPDIFRX_FRAME_SYNC */ -#endif /* SPDIFRX*/ - -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) -#define LPTIM_REMAP_MASK 0x10000000U - -#define TIM_TIM9_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM9 ITR1 is connected to TIM3 TRGO */ -#define TIM_TIM9_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM9_ITR1_RMP) /*!< TIM9 ITR1 is connected to LPTIM1 output */ - -#define TIM_TIM5_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM5 ITR1 is connected to TIM3 TRGO */ -#define TIM_TIM5_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM5_ITR1_RMP) /*!< TIM5 ITR1 is connected to LPTIM1 output */ - -#define TIM_TIM1_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM1 ITR2 is connected to TIM3 TRGO */ -#define TIM_TIM1_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM1_ITR2_RMP) /*!< TIM1 ITR2 is connected to LPTIM1 output */ -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM5_ITR1_RMP */ -/** - * @} - */ - -/** - * @} - */ -/* End of exported constants -------------------------------------------------*/ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Macros TIM Extended Exported Macros - * @{ - */ - -/** - * @} - */ -/* End of exported macro -----------------------------------------------------*/ - -/* Private macro -------------------------------------------------------------*/ -/** @defgroup TIMEx_Private_Macros TIM Extended Private Macros - * @{ - */ -#if defined(SPDIFRX) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_SPDIFRX) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#elif defined(TIM2) -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE))) || \ - (((INSTANCE) == TIM1) && (((TIM_REMAP) == TIM_TIM1_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM1_LPTIM))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM5_LPTIM))) || \ - (((INSTANCE) == TIM9) && (((TIM_REMAP) == TIM_TIM9_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM9_LPTIM)))) -#elif defined(TIM8) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#else -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_ETH_PTP) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM5_ITR1_RMP */ -#else -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#endif /* SPDIFRX */ - -/** - * @} - */ -/* End of private macro ------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup TIMEx_Exported_Functions TIM Extended Exported Functions - * @{ - */ - -/** @addtogroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions - * @brief Timer Hall Sensor functions - * @{ - */ -/* Timer Hall Sensor functions **********************************************/ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim); - -void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim); - -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions - * @brief Timer Complementary Output Compare functions - * @{ - */ -/* Timer Complementary Output Compare functions *****************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions - * @brief Timer Complementary PWM functions - * @{ - */ -/* Timer Complementary PWM functions ****************************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions - * @brief Timer Complementary One Pulse functions - * @{ - */ -/* Timer Complementary One Pulse functions **********************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions - * @brief Peripheral Control functions - * @{ - */ -/* Extended Control functions ************************************************/ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, - TIM_MasterConfigTypeDef *sMasterConfig); -HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim, - TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig); -HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions - * @brief Extended Callbacks functions - * @{ - */ -/* Extended Callback **********************************************************/ -void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim); -void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions - * @brief Extended Peripheral State functions - * @{ - */ -/* Extended Peripheral State functions ***************************************/ -HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN); -/** - * @} - */ - -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private functions----------------------------------------------------------*/ -/** @addtogroup TIMEx_Private_Functions TIMEx Private Functions - * @{ - */ -void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma); -void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma); -/** - * @} - */ -/* End of private functions --------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_TIM_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h deleted file mode 100644 index 14526e816bad50b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h +++ /dev/null @@ -1,886 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_uart.h - * @author MCD Application Team - * @brief Header file of UART HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_UART_H -#define __STM32F4xx_HAL_UART_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup UART - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup UART_Exported_Types UART Exported Types - * @{ - */ - -/** - * @brief UART Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the UART communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (8 * (OVR8+1) * (huart->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8 * (OVR8+1)) + 0.5 - Where OVR8 is the "oversampling by 8 mode" configuration bit in the CR1 register. */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref UART_Word_Length */ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref UART_Stop_Bits */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref UART_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits). */ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref UART_Mode */ - - uint32_t HwFlowCtl; /*!< Specifies whether the hardware flow control mode is enabled or disabled. - This parameter can be a value of @ref UART_Hardware_Flow_Control */ - - uint32_t OverSampling; /*!< Specifies whether the Over sampling 8 is enabled or disabled, to achieve higher speed (up to fPCLK/8). - This parameter can be a value of @ref UART_Over_Sampling */ -} UART_InitTypeDef; - -/** - * @brief HAL UART State structures definition - * @note HAL UART State value is a combination of 2 different substates: gState and RxState. - * - gState contains UART state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : (Not Used) - * 10 : Timeout - * 11 : Error - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized. HAL UART Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (Peripheral busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef enum -{ - HAL_UART_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ - HAL_UART_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ - HAL_UART_STATE_BUSY = 0x24U, /*!< an internal process is ongoing - Value is allowed for gState only */ - HAL_UART_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing - Value is allowed for gState only */ - HAL_UART_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing - Value is allowed for RxState only */ - HAL_UART_STATE_BUSY_TX_RX = 0x23U, /*!< Data Transmission and Reception process is ongoing - Not to be used for neither gState nor RxState. - Value is result of combination (Or) between gState and RxState values */ - HAL_UART_STATE_TIMEOUT = 0xA0U, /*!< Timeout state - Value is allowed for gState only */ - HAL_UART_STATE_ERROR = 0xE0U /*!< Error - Value is allowed for gState only */ -} HAL_UART_StateTypeDef; - -/** - * @brief HAL UART Reception type definition - * @note HAL UART Reception type value aims to identify which type of Reception is ongoing. - * It is expected to admit following values : - * HAL_UART_RECEPTION_STANDARD = 0x00U, - * HAL_UART_RECEPTION_TOIDLE = 0x01U, - */ -typedef uint32_t HAL_UART_RxTypeTypeDef; - -/** - * @brief UART handle Structure definition - */ -typedef struct __UART_HandleTypeDef -{ - USART_TypeDef *Instance; /*!< UART registers base address */ - - UART_InitTypeDef Init; /*!< UART communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to UART Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< UART Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< UART Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to UART Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< UART Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< UART Rx Transfer Counter */ - - __IO HAL_UART_RxTypeTypeDef ReceptionType; /*!< Type of ongoing reception */ - - DMA_HandleTypeDef *hdmatx; /*!< UART Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< UART Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_UART_StateTypeDef gState; /*!< UART state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_UART_StateTypeDef */ - - __IO HAL_UART_StateTypeDef RxState; /*!< UART state information related to Rx operations. - This parameter can be a value of @ref HAL_UART_StateTypeDef */ - - __IO uint32_t ErrorCode; /*!< UART Error code */ - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - void (* TxHalfCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Tx Half Complete Callback */ - void (* TxCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Tx Complete Callback */ - void (* RxHalfCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Rx Half Complete Callback */ - void (* RxCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Rx Complete Callback */ - void (* ErrorCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Error Callback */ - void (* AbortCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Complete Callback */ - void (* AbortTransmitCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Transmit Complete Callback */ - void (* AbortReceiveCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Receive Complete Callback */ - void (* WakeupCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Wakeup Callback */ - void (* RxEventCallback)(struct __UART_HandleTypeDef *huart, uint16_t Pos); /*!< UART Reception Event Callback */ - - void (* MspInitCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Msp Init callback */ - void (* MspDeInitCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Msp DeInit callback */ -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -} UART_HandleTypeDef; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -/** - * @brief HAL UART Callback ID enumeration definition - */ -typedef enum -{ - HAL_UART_TX_HALFCOMPLETE_CB_ID = 0x00U, /*!< UART Tx Half Complete Callback ID */ - HAL_UART_TX_COMPLETE_CB_ID = 0x01U, /*!< UART Tx Complete Callback ID */ - HAL_UART_RX_HALFCOMPLETE_CB_ID = 0x02U, /*!< UART Rx Half Complete Callback ID */ - HAL_UART_RX_COMPLETE_CB_ID = 0x03U, /*!< UART Rx Complete Callback ID */ - HAL_UART_ERROR_CB_ID = 0x04U, /*!< UART Error Callback ID */ - HAL_UART_ABORT_COMPLETE_CB_ID = 0x05U, /*!< UART Abort Complete Callback ID */ - HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID = 0x06U, /*!< UART Abort Transmit Complete Callback ID */ - HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID = 0x07U, /*!< UART Abort Receive Complete Callback ID */ - HAL_UART_WAKEUP_CB_ID = 0x08U, /*!< UART Wakeup Callback ID */ - - HAL_UART_MSPINIT_CB_ID = 0x0BU, /*!< UART MspInit callback ID */ - HAL_UART_MSPDEINIT_CB_ID = 0x0CU /*!< UART MspDeInit callback ID */ - -} HAL_UART_CallbackIDTypeDef; - -/** - * @brief HAL UART Callback pointer definition - */ -typedef void (*pUART_CallbackTypeDef)(UART_HandleTypeDef *huart); /*!< pointer to an UART callback function */ -typedef void (*pUART_RxEventCallbackTypeDef)(struct __UART_HandleTypeDef *huart, uint16_t Pos); /*!< pointer to a UART Rx Event specific callback function */ - -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup UART_Exported_Constants UART Exported Constants - * @{ - */ - -/** @defgroup UART_Error_Code UART Error Code - * @{ - */ -#define HAL_UART_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_UART_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_UART_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_UART_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_UART_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_UART_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -#define HAL_UART_ERROR_INVALID_CALLBACK 0x00000020U /*!< Invalid Callback error */ -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup UART_Word_Length UART Word Length - * @{ - */ -#define UART_WORDLENGTH_8B 0x00000000U -#define UART_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup UART_Stop_Bits UART Number of Stop Bits - * @{ - */ -#define UART_STOPBITS_1 0x00000000U -#define UART_STOPBITS_2 ((uint32_t)USART_CR2_STOP_1) -/** - * @} - */ - -/** @defgroup UART_Parity UART Parity - * @{ - */ -#define UART_PARITY_NONE 0x00000000U -#define UART_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define UART_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup UART_Hardware_Flow_Control UART Hardware Flow Control - * @{ - */ -#define UART_HWCONTROL_NONE 0x00000000U -#define UART_HWCONTROL_RTS ((uint32_t)USART_CR3_RTSE) -#define UART_HWCONTROL_CTS ((uint32_t)USART_CR3_CTSE) -#define UART_HWCONTROL_RTS_CTS ((uint32_t)(USART_CR3_RTSE | USART_CR3_CTSE)) -/** - * @} - */ - -/** @defgroup UART_Mode UART Transfer Mode - * @{ - */ -#define UART_MODE_RX ((uint32_t)USART_CR1_RE) -#define UART_MODE_TX ((uint32_t)USART_CR1_TE) -#define UART_MODE_TX_RX ((uint32_t)(USART_CR1_TE | USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup UART_State UART State - * @{ - */ -#define UART_STATE_DISABLE 0x00000000U -#define UART_STATE_ENABLE ((uint32_t)USART_CR1_UE) -/** - * @} - */ - -/** @defgroup UART_Over_Sampling UART Over Sampling - * @{ - */ -#define UART_OVERSAMPLING_16 0x00000000U -#define UART_OVERSAMPLING_8 ((uint32_t)USART_CR1_OVER8) -/** - * @} - */ - -/** @defgroup UART_LIN_Break_Detection_Length UART LIN Break Detection Length - * @{ - */ -#define UART_LINBREAKDETECTLENGTH_10B 0x00000000U -#define UART_LINBREAKDETECTLENGTH_11B ((uint32_t)USART_CR2_LBDL) -/** - * @} - */ - -/** @defgroup UART_WakeUp_functions UART Wakeup Functions - * @{ - */ -#define UART_WAKEUPMETHOD_IDLELINE 0x00000000U -#define UART_WAKEUPMETHOD_ADDRESSMARK ((uint32_t)USART_CR1_WAKE) -/** - * @} - */ - -/** @defgroup UART_Flags UART FLags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define UART_FLAG_CTS ((uint32_t)USART_SR_CTS) -#define UART_FLAG_LBD ((uint32_t)USART_SR_LBD) -#define UART_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define UART_FLAG_TC ((uint32_t)USART_SR_TC) -#define UART_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define UART_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define UART_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define UART_FLAG_NE ((uint32_t)USART_SR_NE) -#define UART_FLAG_FE ((uint32_t)USART_SR_FE) -#define UART_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup UART_Interrupt_definition UART Interrupt Definitions - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask (16 bits) in the Y register - * - Y : Interrupt source register (2bits) - * - 0001: CR1 register - * - 0010: CR2 register - * - 0011: CR3 register - * @{ - */ - -#define UART_IT_PE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define UART_IT_TXE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define UART_IT_TC ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define UART_IT_RXNE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define UART_IT_IDLE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) - -#define UART_IT_LBD ((uint32_t)(UART_CR2_REG_INDEX << 28U | USART_CR2_LBDIE)) - -#define UART_IT_CTS ((uint32_t)(UART_CR3_REG_INDEX << 28U | USART_CR3_CTSIE)) -#define UART_IT_ERR ((uint32_t)(UART_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** @defgroup UART_RECEPTION_TYPE_Values UART Reception type values - * @{ - */ -#define HAL_UART_RECEPTION_STANDARD (0x00000000U) /*!< Standard reception */ -#define HAL_UART_RECEPTION_TOIDLE (0x00000001U) /*!< Reception till completion or IDLE event */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup UART_Exported_Macros UART Exported Macros - * @{ - */ - -/** @brief Reset UART handle gstate & RxState - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_UART_STATE_RESET; \ - } while(0U) -#endif /*USE_HAL_UART_REGISTER_CALLBACKS */ - -/** @brief Flushes the UART DR register - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - */ -#define __HAL_UART_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) - -/** @brief Checks whether the specified UART flag is set or not. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) - * @arg UART_FLAG_LBD: LIN Break detection flag - * @arg UART_FLAG_TXE: Transmit data register empty flag - * @arg UART_FLAG_TC: Transmission Complete flag - * @arg UART_FLAG_RXNE: Receive data register not empty flag - * @arg UART_FLAG_IDLE: Idle Line detection flag - * @arg UART_FLAG_ORE: Overrun Error flag - * @arg UART_FLAG_NE: Noise Error flag - * @arg UART_FLAG_FE: Framing Error flag - * @arg UART_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_UART_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clears the specified UART pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). - * @arg UART_FLAG_LBD: LIN Break detection flag. - * @arg UART_FLAG_TC: Transmission Complete flag. - * @arg UART_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (Overrun - * error) and IDLE (Idle line detected) flags are cleared by software - * sequence: a read operation to USART_SR register followed by a read - * operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * - * @retval None - */ -#define __HAL_UART_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clears the UART PE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clears the UART FE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_FEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART NE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_NEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART ORE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_OREFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART IDLE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_IDLEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enable the specified UART interrupt. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the UART interrupt source to enable. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_PE: Parity Error interrupt - * @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_UART_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & UART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & UART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & UART_IT_MASK))) - -/** @brief Disable the specified UART interrupt. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the UART interrupt source to disable. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_PE: Parity Error interrupt - * @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_UART_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & UART_IT_MASK))) - -/** @brief Checks whether the specified UART interrupt source is enabled or not. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __IT__ specifies the UART interrupt source to check. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_ERR: Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_UART_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == UART_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == UART_CR2_REG_INDEX)? \ - (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & UART_IT_MASK)) - -/** @brief Enable CTS flow control - * @note This macro allows to enable CTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_CTS_ENABLE(__HANDLE__) \ - do{ \ - ATOMIC_SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ - (__HANDLE__)->Init.HwFlowCtl |= USART_CR3_CTSE; \ - } while(0U) - -/** @brief Disable CTS flow control - * @note This macro allows to disable CTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_CTS_DISABLE(__HANDLE__) \ - do{ \ - ATOMIC_CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ - (__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_CTSE); \ - } while(0U) - -/** @brief Enable RTS flow control - * This macro allows to enable RTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_RTS_ENABLE(__HANDLE__) \ - do{ \ - ATOMIC_SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE); \ - (__HANDLE__)->Init.HwFlowCtl |= USART_CR3_RTSE; \ - } while(0U) - -/** @brief Disable RTS flow control - * This macro allows to disable RTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_RTS_DISABLE(__HANDLE__) \ - do{ \ - ATOMIC_CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE);\ - (__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_RTSE); \ - } while(0U) - -/** @brief Macro to enable the UART's one bit sample method - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3|= USART_CR3_ONEBIT) - -/** @brief Macro to disable the UART's one bit sample method - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3\ - &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable UART - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) - -/** @brief Disable UART - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup UART_Exported_Functions - * @{ - */ - -/** @addtogroup UART_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength); -HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod); -HAL_StatusTypeDef HAL_UART_DeInit(UART_HandleTypeDef *huart); -void HAL_UART_MspInit(UART_HandleTypeDef *huart); -void HAL_UART_MspDeInit(UART_HandleTypeDef *huart); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_UART_RegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID, - pUART_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_UART_UnRegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pUART_RxEventCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group2 IO operation functions - * @{ - */ - -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart); - -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen, - uint32_t Timeout); -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); - -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_UART_Abort(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortTransmit(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortReceive(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_Abort_IT(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortTransmit_IT(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortReceive_IT(UART_HandleTypeDef *huart); - -void HAL_UART_IRQHandler(UART_HandleTypeDef *huart); -void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortTransmitCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortReceiveCpltCallback(UART_HandleTypeDef *huart); - -void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size); - -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions ************************************************/ -HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart); -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State functions **************************************************/ -HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart); -uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup UART_Private_Constants UART Private Constants - * @{ - */ -/** @brief UART interruptions flag mask - * - */ -#define UART_IT_MASK 0x0000FFFFU - -#define UART_CR1_REG_INDEX 1U -#define UART_CR2_REG_INDEX 2U -#define UART_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup UART_Private_Macros UART Private Macros - * @{ - */ -#define IS_UART_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B) || \ - ((LENGTH) == UART_WORDLENGTH_9B)) -#define IS_UART_LIN_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B)) -#define IS_UART_STOPBITS(STOPBITS) (((STOPBITS) == UART_STOPBITS_1) || \ - ((STOPBITS) == UART_STOPBITS_2)) -#define IS_UART_PARITY(PARITY) (((PARITY) == UART_PARITY_NONE) || \ - ((PARITY) == UART_PARITY_EVEN) || \ - ((PARITY) == UART_PARITY_ODD)) -#define IS_UART_HARDWARE_FLOW_CONTROL(CONTROL)\ - (((CONTROL) == UART_HWCONTROL_NONE) || \ - ((CONTROL) == UART_HWCONTROL_RTS) || \ - ((CONTROL) == UART_HWCONTROL_CTS) || \ - ((CONTROL) == UART_HWCONTROL_RTS_CTS)) -#define IS_UART_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x00U)) -#define IS_UART_STATE(STATE) (((STATE) == UART_STATE_DISABLE) || \ - ((STATE) == UART_STATE_ENABLE)) -#define IS_UART_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16) || \ - ((SAMPLING) == UART_OVERSAMPLING_8)) -#define IS_UART_LIN_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16)) -#define IS_UART_LIN_BREAK_DETECT_LENGTH(LENGTH) (((LENGTH) == UART_LINBREAKDETECTLENGTH_10B) || \ - ((LENGTH) == UART_LINBREAKDETECTLENGTH_11B)) -#define IS_UART_WAKEUPMETHOD(WAKEUP) (((WAKEUP) == UART_WAKEUPMETHOD_IDLELINE) || \ - ((WAKEUP) == UART_WAKEUPMETHOD_ADDRESSMARK)) -#define IS_UART_BAUDRATE(BAUDRATE) ((BAUDRATE) <= 10500000U) -#define IS_UART_ADDRESS(ADDRESS) ((ADDRESS) <= 0x0FU) - -#define UART_DIV_SAMPLING16(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(4U*((uint64_t)(_BAUD_))))) -#define UART_DIVMANT_SAMPLING16(_PCLK_, _BAUD_) (UART_DIV_SAMPLING16((_PCLK_), (_BAUD_))/100U) -#define UART_DIVFRAQ_SAMPLING16(_PCLK_, _BAUD_) ((((UART_DIV_SAMPLING16((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) * 100U)) * 16U)\ - + 50U) / 100U) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + (UART DIVFRAQ & 0xF0) + (UART DIVFRAQ & 0x0FU) */ -#define UART_BRR_SAMPLING16(_PCLK_, _BAUD_) ((UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) << 4U) + \ - (UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0xF0U) + \ - (UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0x0FU)) - -#define UART_DIV_SAMPLING8(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(2U*((uint64_t)(_BAUD_))))) -#define UART_DIVMANT_SAMPLING8(_PCLK_, _BAUD_) (UART_DIV_SAMPLING8((_PCLK_), (_BAUD_))/100U) -#define UART_DIVFRAQ_SAMPLING8(_PCLK_, _BAUD_) ((((UART_DIV_SAMPLING8((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) * 100U)) * 8U)\ - + 50U) / 100U) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07U) */ -#define UART_BRR_SAMPLING8(_PCLK_, _BAUD_) ((UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) << 4U) + \ - ((UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0xF8U) << 1U) + \ - (UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0x07U)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup UART_Private_Functions UART Private Functions - * @{ - */ - -HAL_StatusTypeDef UART_Start_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef UART_Start_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_UART_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_usart.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_usart.h deleted file mode 100644 index 5b8375371e49ba2..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_usart.h +++ /dev/null @@ -1,650 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_usart.h - * @author MCD Application Team - * @brief Header file of USART HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_USART_H -#define __STM32F4xx_HAL_USART_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup USART - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup USART_Exported_Types USART Exported Types - * @{ - */ - -/** - * @brief USART Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the Usart communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (8 * (husart->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8) + 0.5 */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref USART_Word_Length */ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref USART_Stop_Bits */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref USART_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits). */ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref USART_Mode */ - - uint32_t CLKPolarity; /*!< Specifies the steady state of the serial clock. - This parameter can be a value of @ref USART_Clock_Polarity */ - - uint32_t CLKPhase; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref USART_Clock_Phase */ - - uint32_t CLKLastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted - data bit (MSB) has to be output on the SCLK pin in synchronous mode. - This parameter can be a value of @ref USART_Last_Bit */ -} USART_InitTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_USART_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_USART_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_USART_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */ - HAL_USART_STATE_BUSY_TX = 0x12U, /*!< Data Transmission process is ongoing */ - HAL_USART_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_USART_STATE_BUSY_TX_RX = 0x32U, /*!< Data Transmission Reception process is ongoing */ - HAL_USART_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_USART_STATE_ERROR = 0x04U /*!< Error */ -} HAL_USART_StateTypeDef; - -/** - * @brief USART handle Structure definition - */ -typedef struct __USART_HandleTypeDef -{ - USART_TypeDef *Instance; /*!< USART registers base address */ - - USART_InitTypeDef Init; /*!< Usart communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to Usart Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< Usart Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< Usart Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to Usart Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< Usart Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< Usart Rx Transfer Counter */ - - DMA_HandleTypeDef *hdmatx; /*!< Usart Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< Usart Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_USART_StateTypeDef State; /*!< Usart communication state */ - - __IO uint32_t ErrorCode; /*!< USART Error code */ - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - void (* TxHalfCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Tx Half Complete Callback */ - void (* TxCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Tx Complete Callback */ - void (* RxHalfCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Rx Half Complete Callback */ - void (* RxCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Rx Complete Callback */ - void (* TxRxCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Tx Rx Complete Callback */ - void (* ErrorCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Error Callback */ - void (* AbortCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Abort Complete Callback */ - - void (* MspInitCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Msp Init callback */ - void (* MspDeInitCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Msp DeInit callback */ -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -} USART_HandleTypeDef; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -/** - * @brief HAL USART Callback ID enumeration definition - */ -typedef enum -{ - HAL_USART_TX_HALFCOMPLETE_CB_ID = 0x00U, /*!< USART Tx Half Complete Callback ID */ - HAL_USART_TX_COMPLETE_CB_ID = 0x01U, /*!< USART Tx Complete Callback ID */ - HAL_USART_RX_HALFCOMPLETE_CB_ID = 0x02U, /*!< USART Rx Half Complete Callback ID */ - HAL_USART_RX_COMPLETE_CB_ID = 0x03U, /*!< USART Rx Complete Callback ID */ - HAL_USART_TX_RX_COMPLETE_CB_ID = 0x04U, /*!< USART Tx Rx Complete Callback ID */ - HAL_USART_ERROR_CB_ID = 0x05U, /*!< USART Error Callback ID */ - HAL_USART_ABORT_COMPLETE_CB_ID = 0x06U, /*!< USART Abort Complete Callback ID */ - - HAL_USART_MSPINIT_CB_ID = 0x07U, /*!< USART MspInit callback ID */ - HAL_USART_MSPDEINIT_CB_ID = 0x08U /*!< USART MspDeInit callback ID */ - -} HAL_USART_CallbackIDTypeDef; - -/** - * @brief HAL USART Callback pointer definition - */ -typedef void (*pUSART_CallbackTypeDef)(USART_HandleTypeDef *husart); /*!< pointer to an USART callback function */ - -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup USART_Exported_Constants USART Exported Constants - * @{ - */ - -/** @defgroup USART_Error_Code USART Error Code - * @brief USART Error Code - * @{ - */ -#define HAL_USART_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_USART_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_USART_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_USART_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_USART_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_USART_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -#define HAL_USART_ERROR_INVALID_CALLBACK 0x00000020U /*!< Invalid Callback error */ -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup USART_Word_Length USART Word Length - * @{ - */ -#define USART_WORDLENGTH_8B 0x00000000U -#define USART_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup USART_Stop_Bits USART Number of Stop Bits - * @{ - */ -#define USART_STOPBITS_1 0x00000000U -#define USART_STOPBITS_0_5 ((uint32_t)USART_CR2_STOP_0) -#define USART_STOPBITS_2 ((uint32_t)USART_CR2_STOP_1) -#define USART_STOPBITS_1_5 ((uint32_t)(USART_CR2_STOP_0 | USART_CR2_STOP_1)) -/** - * @} - */ - -/** @defgroup USART_Parity USART Parity - * @{ - */ -#define USART_PARITY_NONE 0x00000000U -#define USART_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define USART_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup USART_Mode USART Mode - * @{ - */ -#define USART_MODE_RX ((uint32_t)USART_CR1_RE) -#define USART_MODE_TX ((uint32_t)USART_CR1_TE) -#define USART_MODE_TX_RX ((uint32_t)(USART_CR1_TE | USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup USART_Clock USART Clock - * @{ - */ -#define USART_CLOCK_DISABLE 0x00000000U -#define USART_CLOCK_ENABLE ((uint32_t)USART_CR2_CLKEN) -/** - * @} - */ - -/** @defgroup USART_Clock_Polarity USART Clock Polarity - * @{ - */ -#define USART_POLARITY_LOW 0x00000000U -#define USART_POLARITY_HIGH ((uint32_t)USART_CR2_CPOL) -/** - * @} - */ - -/** @defgroup USART_Clock_Phase USART Clock Phase - * @{ - */ -#define USART_PHASE_1EDGE 0x00000000U -#define USART_PHASE_2EDGE ((uint32_t)USART_CR2_CPHA) -/** - * @} - */ - -/** @defgroup USART_Last_Bit USART Last Bit - * @{ - */ -#define USART_LASTBIT_DISABLE 0x00000000U -#define USART_LASTBIT_ENABLE ((uint32_t)USART_CR2_LBCL) -/** - * @} - */ - -/** @defgroup USART_NACK_State USART NACK State - * @{ - */ -#define USART_NACK_ENABLE ((uint32_t)USART_CR3_NACK) -#define USART_NACK_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup USART_Flags USART Flags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define USART_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define USART_FLAG_TC ((uint32_t)USART_SR_TC) -#define USART_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define USART_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define USART_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define USART_FLAG_NE ((uint32_t)USART_SR_NE) -#define USART_FLAG_FE ((uint32_t)USART_SR_FE) -#define USART_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup USART_Interrupt_definition USART Interrupts Definition - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask in the XX register - * - Y : Interrupt source register (2bits) - * - 01: CR1 register - * - 10: CR2 register - * - 11: CR3 register - * @{ - */ -#define USART_IT_PE ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define USART_IT_TXE ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define USART_IT_TC ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define USART_IT_RXNE ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define USART_IT_IDLE ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) -#define USART_IT_ERR ((uint32_t)(USART_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup USART_Exported_Macros USART Exported Macros - * @{ - */ - -/** @brief Reset USART handle state - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -#define __HAL_USART_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_USART_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_USART_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_USART_STATE_RESET) -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -/** @brief Check whether the specified USART flag is set or not. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg USART_FLAG_TXE: Transmit data register empty flag - * @arg USART_FLAG_TC: Transmission Complete flag - * @arg USART_FLAG_RXNE: Receive data register not empty flag - * @arg USART_FLAG_IDLE: Idle Line detection flag - * @arg USART_FLAG_ORE: Overrun Error flag - * @arg USART_FLAG_NE: Noise Error flag - * @arg USART_FLAG_FE: Framing Error flag - * @arg USART_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_USART_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified USART pending flags. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg USART_FLAG_TC: Transmission Complete flag. - * @arg USART_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (Overrun - * error) and IDLE (Idle line detected) flags are cleared by software - * sequence: a read operation to USART_SR register followed by a read - * operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * - * @retval None - */ -#define __HAL_USART_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clear the USART PE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clear the USART FE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_FEFLAG(__HANDLE__) __HAL_USART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the USART NE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_NEFLAG(__HANDLE__) __HAL_USART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the USART ORE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_OREFLAG(__HANDLE__) __HAL_USART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the USART IDLE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_IDLEFLAG(__HANDLE__) __HAL_USART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enables or disables the specified USART interrupts. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __INTERRUPT__ specifies the USART interrupt source to check. - * This parameter can be one of the following values: - * @arg USART_IT_TXE: Transmit Data Register empty interrupt - * @arg USART_IT_TC: Transmission complete interrupt - * @arg USART_IT_RXNE: Receive Data register not empty interrupt - * @arg USART_IT_IDLE: Idle line detection interrupt - * @arg USART_IT_PE: Parity Error interrupt - * @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_USART_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == USART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & USART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == USART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & USART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & USART_IT_MASK))) -#define __HAL_USART_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == USART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & USART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == USART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & USART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & USART_IT_MASK))) - -/** @brief Checks whether the specified USART interrupt has occurred or not. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __IT__ specifies the USART interrupt source to check. - * This parameter can be one of the following values: - * @arg USART_IT_TXE: Transmit Data Register empty interrupt - * @arg USART_IT_TC: Transmission complete interrupt - * @arg USART_IT_RXNE: Receive Data register not empty interrupt - * @arg USART_IT_IDLE: Idle line detection interrupt - * @arg USART_IT_ERR: Error interrupt - * @arg USART_IT_PE: Parity Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_USART_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == USART_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == USART_CR2_REG_INDEX)? \ - (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & USART_IT_MASK)) - -/** @brief Macro to enable the USART's one bit sample method - * @param __HANDLE__ specifies the USART Handle. - * @retval None - */ -#define __HAL_USART_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 |= USART_CR3_ONEBIT) - -/** @brief Macro to disable the USART's one bit sample method - * @param __HANDLE__ specifies the USART Handle. - * @retval None - */ -#define __HAL_USART_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3\ - &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable USART - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) - -/** @brief Disable USART - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) - -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup USART_Exported_Functions - * @{ - */ - -/** @addtogroup USART_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_USART_Init(USART_HandleTypeDef *husart); -HAL_StatusTypeDef HAL_USART_DeInit(USART_HandleTypeDef *husart); -void HAL_USART_MspInit(USART_HandleTypeDef *husart); -void HAL_USART_MspDeInit(USART_HandleTypeDef *husart); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_USART_RegisterCallback(USART_HandleTypeDef *husart, HAL_USART_CallbackIDTypeDef CallbackID, - pUSART_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_USART_UnRegisterCallback(USART_HandleTypeDef *husart, HAL_USART_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup USART_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_USART_Transmit(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_USART_Receive(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_USART_TransmitReceive(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_USART_Transmit_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size); -HAL_StatusTypeDef HAL_USART_Receive_IT(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size); -HAL_StatusTypeDef HAL_USART_TransmitReceive_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_USART_Transmit_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size); -HAL_StatusTypeDef HAL_USART_Receive_DMA(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size); -HAL_StatusTypeDef HAL_USART_TransmitReceive_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_USART_DMAPause(USART_HandleTypeDef *husart); -HAL_StatusTypeDef HAL_USART_DMAResume(USART_HandleTypeDef *husart); -HAL_StatusTypeDef HAL_USART_DMAStop(USART_HandleTypeDef *husart); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_USART_Abort(USART_HandleTypeDef *husart); -HAL_StatusTypeDef HAL_USART_Abort_IT(USART_HandleTypeDef *husart); - -void HAL_USART_IRQHandler(USART_HandleTypeDef *husart); -void HAL_USART_TxCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_TxHalfCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_RxCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_RxHalfCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_TxRxCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_ErrorCallback(USART_HandleTypeDef *husart); -void HAL_USART_AbortCpltCallback(USART_HandleTypeDef *husart); -/** - * @} - */ - -/** @addtogroup USART_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_USART_StateTypeDef HAL_USART_GetState(USART_HandleTypeDef *husart); -uint32_t HAL_USART_GetError(USART_HandleTypeDef *husart); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup USART_Private_Constants USART Private Constants - * @{ - */ -/** @brief USART interruptions flag mask - * - */ -#define USART_IT_MASK ((uint32_t) USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RXNEIE | \ - USART_CR1_IDLEIE | USART_CR2_LBDIE | USART_CR3_CTSIE | USART_CR3_EIE ) - -#define USART_CR1_REG_INDEX 1U -#define USART_CR2_REG_INDEX 2U -#define USART_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup USART_Private_Macros USART Private Macros - * @{ - */ -#define IS_USART_NACK_STATE(NACK) (((NACK) == USART_NACK_ENABLE) || \ - ((NACK) == USART_NACK_DISABLE)) - -#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LASTBIT_DISABLE) || \ - ((LASTBIT) == USART_LASTBIT_ENABLE)) - -#define IS_USART_PHASE(CPHA) (((CPHA) == USART_PHASE_1EDGE) || \ - ((CPHA) == USART_PHASE_2EDGE)) - -#define IS_USART_POLARITY(CPOL) (((CPOL) == USART_POLARITY_LOW) || \ - ((CPOL) == USART_POLARITY_HIGH)) - -#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_CLOCK_DISABLE) || \ - ((CLOCK) == USART_CLOCK_ENABLE)) - -#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WORDLENGTH_8B) || \ - ((LENGTH) == USART_WORDLENGTH_9B)) - -#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_STOPBITS_1) || \ - ((STOPBITS) == USART_STOPBITS_0_5) || \ - ((STOPBITS) == USART_STOPBITS_1_5) || \ - ((STOPBITS) == USART_STOPBITS_2)) - -#define IS_USART_PARITY(PARITY) (((PARITY) == USART_PARITY_NONE) || \ - ((PARITY) == USART_PARITY_EVEN) || \ - ((PARITY) == USART_PARITY_ODD)) - -#define IS_USART_MODE(MODE) ((((MODE) & (~((uint32_t)USART_MODE_TX_RX))) == 0x00U) && ((MODE) != 0x00U)) - -#define IS_USART_BAUDRATE(BAUDRATE) ((BAUDRATE) <= 12500000U) - -#define USART_DIV(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(2U*((uint64_t)(_BAUD_))))) - -#define USART_DIVMANT(_PCLK_, _BAUD_) (USART_DIV((_PCLK_), (_BAUD_))/100U) - -#define USART_DIVFRAQ(_PCLK_, _BAUD_) ((((USART_DIV((_PCLK_), (_BAUD_)) - (USART_DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 8U) + 50U) / 100U) - - /* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07U) */ - -#define USART_BRR(_PCLK_, _BAUD_) (((USART_DIVMANT((_PCLK_), (_BAUD_)) << 4U) + \ - ((USART_DIVFRAQ((_PCLK_), (_BAUD_)) & 0xF8U) << 1U)) + \ - (USART_DIVFRAQ((_PCLK_), (_BAUD_)) & 0x07U)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup USART_Private_Functions USART Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_USART_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_wwdg.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_wwdg.h deleted file mode 100644 index 017b34df4bf6399..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_wwdg.h +++ /dev/null @@ -1,301 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_wwdg.h - * @author MCD Application Team - * @brief Header file of WWDG HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_WWDG_H -#define STM32F4xx_HAL_WWDG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup WWDG - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup WWDG_Exported_Types WWDG Exported Types - * @{ - */ - -/** - * @brief WWDG Init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the prescaler value of the WWDG. - This parameter can be a value of @ref WWDG_Prescaler */ - - uint32_t Window; /*!< Specifies the WWDG window value to be compared to the downcounter. - This parameter must be a number Min_Data = 0x40 and Max_Data = 0x7F */ - - uint32_t Counter; /*!< Specifies the WWDG free-running downcounter value. - This parameter must be a number between Min_Data = 0x40 and Max_Data = 0x7F */ - - uint32_t EWIMode ; /*!< Specifies if WWDG Early Wakeup Interrupt is enable or not. - This parameter can be a value of @ref WWDG_EWI_Mode */ - -} WWDG_InitTypeDef; - -/** - * @brief WWDG handle Structure definition - */ -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) -typedef struct __WWDG_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ -{ - WWDG_TypeDef *Instance; /*!< Register base address */ - - WWDG_InitTypeDef Init; /*!< WWDG required parameters */ - -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) - void (* EwiCallback)(struct __WWDG_HandleTypeDef *hwwdg); /*!< WWDG Early WakeUp Interrupt callback */ - - void (* MspInitCallback)(struct __WWDG_HandleTypeDef *hwwdg); /*!< WWDG Msp Init callback */ -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ -} WWDG_HandleTypeDef; - -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) -/** - * @brief HAL WWDG common Callback ID enumeration definition - */ -typedef enum -{ - HAL_WWDG_EWI_CB_ID = 0x00U, /*!< WWDG EWI callback ID */ - HAL_WWDG_MSPINIT_CB_ID = 0x01U, /*!< WWDG MspInit callback ID */ -} HAL_WWDG_CallbackIDTypeDef; - -/** - * @brief HAL WWDG Callback pointer definition - */ -typedef void (*pWWDG_CallbackTypeDef)(WWDG_HandleTypeDef *hppp); /*!< pointer to a WWDG common callback functions */ - -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup WWDG_Exported_Constants WWDG Exported Constants - * @{ - */ - -/** @defgroup WWDG_Interrupt_definition WWDG Interrupt definition - * @{ - */ -#define WWDG_IT_EWI WWDG_CFR_EWI /*!< Early wakeup interrupt */ -/** - * @} - */ - -/** @defgroup WWDG_Flag_definition WWDG Flag definition - * @brief WWDG Flag definition - * @{ - */ -#define WWDG_FLAG_EWIF WWDG_SR_EWIF /*!< Early wakeup interrupt flag */ -/** - * @} - */ - -/** @defgroup WWDG_Prescaler WWDG Prescaler - * @{ - */ -#define WWDG_PRESCALER_1 0x00000000u /*!< WWDG counter clock = (PCLK1/4096)/1 */ -#define WWDG_PRESCALER_2 WWDG_CFR_WDGTB_0 /*!< WWDG counter clock = (PCLK1/4096)/2 */ -#define WWDG_PRESCALER_4 WWDG_CFR_WDGTB_1 /*!< WWDG counter clock = (PCLK1/4096)/4 */ -#define WWDG_PRESCALER_8 (WWDG_CFR_WDGTB_1 | WWDG_CFR_WDGTB_0) /*!< WWDG counter clock = (PCLK1/4096)/8 */ -/** - * @} - */ - -/** @defgroup WWDG_EWI_Mode WWDG Early Wakeup Interrupt Mode - * @{ - */ -#define WWDG_EWI_DISABLE 0x00000000u /*!< EWI Disable */ -#define WWDG_EWI_ENABLE WWDG_CFR_EWI /*!< EWI Enable */ -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ - -/** @defgroup WWDG_Private_Macros WWDG Private Macros - * @{ - */ -#define IS_WWDG_PRESCALER(__PRESCALER__) (((__PRESCALER__) == WWDG_PRESCALER_1) || \ - ((__PRESCALER__) == WWDG_PRESCALER_2) || \ - ((__PRESCALER__) == WWDG_PRESCALER_4) || \ - ((__PRESCALER__) == WWDG_PRESCALER_8)) - -#define IS_WWDG_WINDOW(__WINDOW__) (((__WINDOW__) >= WWDG_CFR_W_6) && ((__WINDOW__) <= WWDG_CFR_W)) - -#define IS_WWDG_COUNTER(__COUNTER__) (((__COUNTER__) >= WWDG_CR_T_6) && ((__COUNTER__) <= WWDG_CR_T)) - -#define IS_WWDG_EWI_MODE(__MODE__) (((__MODE__) == WWDG_EWI_ENABLE) || \ - ((__MODE__) == WWDG_EWI_DISABLE)) -/** - * @} - */ - - -/* Exported macros ------------------------------------------------------------*/ - -/** @defgroup WWDG_Exported_Macros WWDG Exported Macros - * @{ - */ - -/** - * @brief Enable the WWDG peripheral. - * @param __HANDLE__ WWDG handle - * @retval None - */ -#define __HAL_WWDG_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR, WWDG_CR_WDGA) - -/** - * @brief Enable the WWDG early wakeup interrupt. - * @param __HANDLE__: WWDG handle - * @param __INTERRUPT__ specifies the interrupt to enable. - * This parameter can be one of the following values: - * @arg WWDG_IT_EWI: Early wakeup interrupt - * @note Once enabled this interrupt cannot be disabled except by a system reset. - * @retval None - */ -#define __HAL_WWDG_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CFR, (__INTERRUPT__)) - -/** - * @brief Check whether the selected WWDG interrupt has occurred or not. - * @param __HANDLE__ WWDG handle - * @param __INTERRUPT__ specifies the it to check. - * This parameter can be one of the following values: - * @arg WWDG_FLAG_EWIF: Early wakeup interrupt IT - * @retval The new state of WWDG_FLAG (SET or RESET). - */ -#define __HAL_WWDG_GET_IT(__HANDLE__, __INTERRUPT__) __HAL_WWDG_GET_FLAG((__HANDLE__),(__INTERRUPT__)) - -/** @brief Clear the WWDG interrupt pending bits. - * bits to clear the selected interrupt pending bits. - * @param __HANDLE__ WWDG handle - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. - * This parameter can be one of the following values: - * @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag - */ -#define __HAL_WWDG_CLEAR_IT(__HANDLE__, __INTERRUPT__) __HAL_WWDG_CLEAR_FLAG((__HANDLE__), (__INTERRUPT__)) - -/** - * @brief Check whether the specified WWDG flag is set or not. - * @param __HANDLE__ WWDG handle - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag - * @retval The new state of WWDG_FLAG (SET or RESET). - */ -#define __HAL_WWDG_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear the WWDG's pending flags. - * @param __HANDLE__ WWDG handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be one of the following values: - * @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag - * @retval None - */ -#define __HAL_WWDG_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Check whether the specified WWDG interrupt source is enabled or not. - * @param __HANDLE__ WWDG Handle. - * @param __INTERRUPT__ specifies the WWDG interrupt source to check. - * This parameter can be one of the following values: - * @arg WWDG_IT_EWI: Early Wakeup Interrupt - * @retval state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_WWDG_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CFR\ - & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup WWDG_Exported_Functions - * @{ - */ - -/** @addtogroup WWDG_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_WWDG_Init(WWDG_HandleTypeDef *hwwdg); -void HAL_WWDG_MspInit(WWDG_HandleTypeDef *hwwdg); -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_WWDG_RegisterCallback(WWDG_HandleTypeDef *hwwdg, HAL_WWDG_CallbackIDTypeDef CallbackID, - pWWDG_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_WWDG_UnRegisterCallback(WWDG_HandleTypeDef *hwwdg, HAL_WWDG_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup WWDG_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ******************************************************/ -HAL_StatusTypeDef HAL_WWDG_Refresh(WWDG_HandleTypeDef *hwwdg); -void HAL_WWDG_IRQHandler(WWDG_HandleTypeDef *hwwdg); -void HAL_WWDG_EarlyWakeupCallback(WWDG_HandleTypeDef *hwwdg); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_WWDG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h deleted file mode 100644 index 8375c4f1511f68a..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h +++ /dev/null @@ -1,4783 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_adc.h - * @author MCD Application Team - * @brief Header file of ADC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_ADC_H -#define __STM32F4xx_LL_ADC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (ADC1) || defined (ADC2) || defined (ADC3) - -/** @defgroup ADC_LL ADC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup ADC_LL_Private_Constants ADC Private Constants - * @{ - */ - -/* Internal mask for ADC group regular sequencer: */ -/* To select into literal LL_ADC_REG_RANK_x the relevant bits for: */ -/* - sequencer register offset */ -/* - sequencer rank bits position into the selected register */ - -/* Internal register offset for ADC group regular sequencer configuration */ -/* (offset placed into a spare area of literal definition) */ -#define ADC_SQR1_REGOFFSET 0x00000000UL -#define ADC_SQR2_REGOFFSET 0x00000100UL -#define ADC_SQR3_REGOFFSET 0x00000200UL -#define ADC_SQR4_REGOFFSET 0x00000300UL - -#define ADC_REG_SQRX_REGOFFSET_MASK (ADC_SQR1_REGOFFSET | ADC_SQR2_REGOFFSET | ADC_SQR3_REGOFFSET | ADC_SQR4_REGOFFSET) -#define ADC_REG_RANK_ID_SQRX_MASK (ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0) - -/* Definition of ADC group regular sequencer bits information to be inserted */ -/* into ADC group regular sequencer ranks literals definition. */ -#define ADC_REG_RANK_1_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ1) */ -#define ADC_REG_RANK_2_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ2) */ -#define ADC_REG_RANK_3_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ3) */ -#define ADC_REG_RANK_4_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ4) */ -#define ADC_REG_RANK_5_SQRX_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ5) */ -#define ADC_REG_RANK_6_SQRX_BITOFFSET_POS (25UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ6) */ -#define ADC_REG_RANK_7_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ7) */ -#define ADC_REG_RANK_8_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ8) */ -#define ADC_REG_RANK_9_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ9) */ -#define ADC_REG_RANK_10_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ10) */ -#define ADC_REG_RANK_11_SQRX_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ11) */ -#define ADC_REG_RANK_12_SQRX_BITOFFSET_POS (25UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ12) */ -#define ADC_REG_RANK_13_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ13) */ -#define ADC_REG_RANK_14_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ14) */ -#define ADC_REG_RANK_15_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ15) */ -#define ADC_REG_RANK_16_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ16) */ - -/* Internal mask for ADC group injected sequencer: */ -/* To select into literal LL_ADC_INJ_RANK_x the relevant bits for: */ -/* - data register offset */ -/* - offset register offset */ -/* - sequencer rank bits position into the selected register */ - -/* Internal register offset for ADC group injected data register */ -/* (offset placed into a spare area of literal definition) */ -#define ADC_JDR1_REGOFFSET 0x00000000UL -#define ADC_JDR2_REGOFFSET 0x00000100UL -#define ADC_JDR3_REGOFFSET 0x00000200UL -#define ADC_JDR4_REGOFFSET 0x00000300UL - -/* Internal register offset for ADC group injected offset configuration */ -/* (offset placed into a spare area of literal definition) */ -#define ADC_JOFR1_REGOFFSET 0x00000000UL -#define ADC_JOFR2_REGOFFSET 0x00001000UL -#define ADC_JOFR3_REGOFFSET 0x00002000UL -#define ADC_JOFR4_REGOFFSET 0x00003000UL - -#define ADC_INJ_JDRX_REGOFFSET_MASK (ADC_JDR1_REGOFFSET | ADC_JDR2_REGOFFSET | ADC_JDR3_REGOFFSET | ADC_JDR4_REGOFFSET) -#define ADC_INJ_JOFRX_REGOFFSET_MASK (ADC_JOFR1_REGOFFSET | ADC_JOFR2_REGOFFSET | ADC_JOFR3_REGOFFSET | ADC_JOFR4_REGOFFSET) -#define ADC_INJ_RANK_ID_JSQR_MASK (ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0) - -/* Internal mask for ADC group regular trigger: */ -/* To select into literal LL_ADC_REG_TRIG_x the relevant bits for: */ -/* - regular trigger source */ -/* - regular trigger edge */ -#define ADC_REG_TRIG_EXT_EDGE_DEFAULT (ADC_CR2_EXTEN_0) /* Trigger edge set to rising edge (default setting for compatibility with some ADC on other STM32 families having this setting set by HW default value) */ - -/* Mask containing trigger source masks for each of possible */ -/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ -/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ -#define ADC_REG_TRIG_SOURCE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTSEL) >> (4UL * 0UL)) | \ - ((ADC_CR2_EXTSEL) >> (4UL * 1UL)) | \ - ((ADC_CR2_EXTSEL) >> (4UL * 2UL)) | \ - ((ADC_CR2_EXTSEL) >> (4UL * 3UL))) - -/* Mask containing trigger edge masks for each of possible */ -/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ -/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ -#define ADC_REG_TRIG_EDGE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTEN) >> (4UL * 0UL)) | \ - ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 1UL)) | \ - ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 2UL)) | \ - ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 3UL))) - -/* Definition of ADC group regular trigger bits information. */ -#define ADC_REG_TRIG_EXTSEL_BITOFFSET_POS (24UL) /* Value equivalent to POSITION_VAL(ADC_CR2_EXTSEL) */ -#define ADC_REG_TRIG_EXTEN_BITOFFSET_POS (28UL) /* Value equivalent to POSITION_VAL(ADC_CR2_EXTEN) */ - - - -/* Internal mask for ADC group injected trigger: */ -/* To select into literal LL_ADC_INJ_TRIG_x the relevant bits for: */ -/* - injected trigger source */ -/* - injected trigger edge */ -#define ADC_INJ_TRIG_EXT_EDGE_DEFAULT (ADC_CR2_JEXTEN_0) /* Trigger edge set to rising edge (default setting for compatibility with some ADC on other STM32 families having this setting set by HW default value) */ - -/* Mask containing trigger source masks for each of possible */ -/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ -/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ -#define ADC_INJ_TRIG_SOURCE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_JEXTSEL) >> (4UL * 0UL)) | \ - ((ADC_CR2_JEXTSEL) >> (4UL * 1UL)) | \ - ((ADC_CR2_JEXTSEL) >> (4UL * 2UL)) | \ - ((ADC_CR2_JEXTSEL) >> (4UL * 3UL))) - -/* Mask containing trigger edge masks for each of possible */ -/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ -/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ -#define ADC_INJ_TRIG_EDGE_MASK (((LL_ADC_INJ_TRIG_SOFTWARE & ADC_CR2_JEXTEN) >> (4UL * 0UL)) | \ - ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 1UL)) | \ - ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 2UL)) | \ - ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 3UL))) - -/* Definition of ADC group injected trigger bits information. */ -#define ADC_INJ_TRIG_EXTSEL_BITOFFSET_POS (16UL) /* Value equivalent to POSITION_VAL(ADC_CR2_JEXTSEL) */ -#define ADC_INJ_TRIG_EXTEN_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_CR2_JEXTEN) */ - -/* Internal mask for ADC channel: */ -/* To select into literal LL_ADC_CHANNEL_x the relevant bits for: */ -/* - channel identifier defined by number */ -/* - channel differentiation between external channels (connected to */ -/* GPIO pins) and internal channels (connected to internal paths) */ -/* - channel sampling time defined by SMPRx register offset */ -/* and SMPx bits positions into SMPRx register */ -#define ADC_CHANNEL_ID_NUMBER_MASK (ADC_CR1_AWDCH) -#define ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS ( 0UL)/* Value equivalent to POSITION_VAL(ADC_CHANNEL_ID_NUMBER_MASK) */ -#define ADC_CHANNEL_ID_MASK (ADC_CHANNEL_ID_NUMBER_MASK | ADC_CHANNEL_ID_INTERNAL_CH_MASK) -/* Equivalent mask of ADC_CHANNEL_NUMBER_MASK aligned on register LSB (bit 0) */ -#define ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0 0x0000001FU /* Equivalent to shift: (ADC_CHANNEL_NUMBER_MASK >> POSITION_VAL(ADC_CHANNEL_NUMBER_MASK)) */ - -/* Channel differentiation between external and internal channels */ -#define ADC_CHANNEL_ID_INTERNAL_CH 0x80000000UL /* Marker of internal channel */ -#define ADC_CHANNEL_ID_INTERNAL_CH_2 0x40000000UL /* Marker of internal channel for other ADC instances, in case of different ADC internal channels mapped on same channel number on different ADC instances */ -#define ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT 0x10000000U /* Dummy bit for driver internal usage, not used in ADC channel setting registers CR1 or SQRx */ -#define ADC_CHANNEL_ID_INTERNAL_CH_MASK (ADC_CHANNEL_ID_INTERNAL_CH | ADC_CHANNEL_ID_INTERNAL_CH_2 | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) - -/* Internal register offset for ADC channel sampling time configuration */ -/* (offset placed into a spare area of literal definition) */ -#define ADC_SMPR1_REGOFFSET 0x00000000UL -#define ADC_SMPR2_REGOFFSET 0x02000000UL -#define ADC_CHANNEL_SMPRX_REGOFFSET_MASK (ADC_SMPR1_REGOFFSET | ADC_SMPR2_REGOFFSET) - -#define ADC_CHANNEL_SMPx_BITOFFSET_MASK 0x01F00000UL -#define ADC_CHANNEL_SMPx_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_CHANNEL_SMPx_BITOFFSET_MASK) */ - -/* Definition of channels ID number information to be inserted into */ -/* channels literals definition. */ -#define ADC_CHANNEL_0_NUMBER 0x00000000UL -#define ADC_CHANNEL_1_NUMBER ( ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_2_NUMBER ( ADC_CR1_AWDCH_1 ) -#define ADC_CHANNEL_3_NUMBER ( ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_4_NUMBER ( ADC_CR1_AWDCH_2 ) -#define ADC_CHANNEL_5_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_6_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 ) -#define ADC_CHANNEL_7_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_8_NUMBER ( ADC_CR1_AWDCH_3 ) -#define ADC_CHANNEL_9_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_10_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 ) -#define ADC_CHANNEL_11_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_12_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 ) -#define ADC_CHANNEL_13_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_14_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 ) -#define ADC_CHANNEL_15_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_16_NUMBER (ADC_CR1_AWDCH_4 ) -#define ADC_CHANNEL_17_NUMBER (ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_18_NUMBER (ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_1 ) - -/* Definition of channels sampling time information to be inserted into */ -/* channels literals definition. */ -#define ADC_CHANNEL_0_SMP (ADC_SMPR2_REGOFFSET | (( 0UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP0) */ -#define ADC_CHANNEL_1_SMP (ADC_SMPR2_REGOFFSET | (( 3UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP1) */ -#define ADC_CHANNEL_2_SMP (ADC_SMPR2_REGOFFSET | (( 6UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP2) */ -#define ADC_CHANNEL_3_SMP (ADC_SMPR2_REGOFFSET | (( 9UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP3) */ -#define ADC_CHANNEL_4_SMP (ADC_SMPR2_REGOFFSET | ((12UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP4) */ -#define ADC_CHANNEL_5_SMP (ADC_SMPR2_REGOFFSET | ((15UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP5) */ -#define ADC_CHANNEL_6_SMP (ADC_SMPR2_REGOFFSET | ((18UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP6) */ -#define ADC_CHANNEL_7_SMP (ADC_SMPR2_REGOFFSET | ((21UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP7) */ -#define ADC_CHANNEL_8_SMP (ADC_SMPR2_REGOFFSET | ((24UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP8) */ -#define ADC_CHANNEL_9_SMP (ADC_SMPR2_REGOFFSET | ((27UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP9) */ -#define ADC_CHANNEL_10_SMP (ADC_SMPR1_REGOFFSET | (( 0UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP10) */ -#define ADC_CHANNEL_11_SMP (ADC_SMPR1_REGOFFSET | (( 3UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP11) */ -#define ADC_CHANNEL_12_SMP (ADC_SMPR1_REGOFFSET | (( 6UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP12) */ -#define ADC_CHANNEL_13_SMP (ADC_SMPR1_REGOFFSET | (( 9UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP13) */ -#define ADC_CHANNEL_14_SMP (ADC_SMPR1_REGOFFSET | ((12UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP14) */ -#define ADC_CHANNEL_15_SMP (ADC_SMPR1_REGOFFSET | ((15UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP15) */ -#define ADC_CHANNEL_16_SMP (ADC_SMPR1_REGOFFSET | ((18UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP16) */ -#define ADC_CHANNEL_17_SMP (ADC_SMPR1_REGOFFSET | ((21UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP17) */ -#define ADC_CHANNEL_18_SMP (ADC_SMPR1_REGOFFSET | ((24UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP18) */ - -/* Internal mask for ADC analog watchdog: */ -/* To select into literals LL_ADC_AWD_CHANNELx_xxx the relevant bits for: */ -/* (concatenation of multiple bits used in different analog watchdogs, */ -/* (feature of several watchdogs not available on all STM32 families)). */ -/* - analog watchdog 1: monitored channel defined by number, */ -/* selection of ADC group (ADC groups regular and-or injected). */ - -/* Internal register offset for ADC analog watchdog channel configuration */ -#define ADC_AWD_CR1_REGOFFSET 0x00000000UL - -#define ADC_AWD_CRX_REGOFFSET_MASK (ADC_AWD_CR1_REGOFFSET) - -#define ADC_AWD_CR1_CHANNEL_MASK (ADC_CR1_AWDCH | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) -#define ADC_AWD_CR_ALL_CHANNEL_MASK (ADC_AWD_CR1_CHANNEL_MASK) - -/* Internal register offset for ADC analog watchdog threshold configuration */ -#define ADC_AWD_TR1_HIGH_REGOFFSET 0x00000000UL -#define ADC_AWD_TR1_LOW_REGOFFSET 0x00000001UL -#define ADC_AWD_TRX_REGOFFSET_MASK (ADC_AWD_TR1_HIGH_REGOFFSET | ADC_AWD_TR1_LOW_REGOFFSET) - -/* ADC registers bits positions */ -#define ADC_CR1_RES_BITOFFSET_POS (24UL) /* Value equivalent to POSITION_VAL(ADC_CR1_RES) */ -#define ADC_TR_HT_BITOFFSET_POS (16UL) /* Value equivalent to POSITION_VAL(ADC_TR_HT) */ - -/* ADC internal channels related definitions */ -/* Internal voltage reference VrefInt */ -#define VREFINT_CAL_ADDR ((uint16_t*) (0x1FFF7A2AU)) /* Internal voltage reference, address of parameter VREFINT_CAL: VrefInt ADC raw data acquired at temperature 30 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ -#define VREFINT_CAL_VREF ( 3300UL) /* Analog voltage reference (Vref+) value with which temperature sensor has been calibrated in production (tolerance: +-10 mV) (unit: mV). */ -/* Temperature sensor */ -#define TEMPSENSOR_CAL1_ADDR ((uint16_t*) (0x1FFF7A2CU)) /* Internal temperature sensor, address of parameter TS_CAL1: On STM32F4, temperature sensor ADC raw data acquired at temperature 30 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ -#define TEMPSENSOR_CAL2_ADDR ((uint16_t*) (0x1FFF7A2EU)) /* Internal temperature sensor, address of parameter TS_CAL2: On STM32F4, temperature sensor ADC raw data acquired at temperature 110 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ -#define TEMPSENSOR_CAL1_TEMP (( int32_t) 30) /* Internal temperature sensor, temperature at which temperature sensor has been calibrated in production for data into TEMPSENSOR_CAL1_ADDR (tolerance: +-5 DegC) (unit: DegC). */ -#define TEMPSENSOR_CAL2_TEMP (( int32_t) 110) /* Internal temperature sensor, temperature at which temperature sensor has been calibrated in production for data into TEMPSENSOR_CAL2_ADDR (tolerance: +-5 DegC) (unit: DegC). */ -#define TEMPSENSOR_CAL_VREFANALOG ( 3300UL) /* Analog voltage reference (Vref+) voltage with which temperature sensor has been calibrated in production (+-10 mV) (unit: mV). */ - -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup ADC_LL_Private_Macros ADC Private Macros - * @{ - */ - -/** - * @brief Driver macro reserved for internal use: isolate bits with the - * selected mask and shift them to the register LSB - * (shift mask on register position bit 0). - * @param __BITS__ Bits in register 32 bits - * @param __MASK__ Mask in register 32 bits - * @retval Bits in register 32 bits - */ -#define __ADC_MASK_SHIFT(__BITS__, __MASK__) \ - (((__BITS__) & (__MASK__)) >> POSITION_VAL((__MASK__))) - -/** - * @brief Driver macro reserved for internal use: set a pointer to - * a register from a register basis from which an offset - * is applied. - * @param __REG__ Register basis from which the offset is applied. - * @param __REG_OFFFSET__ Offset to be applied (unit number of registers). - * @retval Pointer to register address - */ -#define __ADC_PTR_REG_OFFSET(__REG__, __REG_OFFFSET__) \ - ((__IO uint32_t *)((uint32_t) ((uint32_t)(&(__REG__)) + ((__REG_OFFFSET__) << 2UL)))) - -/** - * @} - */ - - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup ADC_LL_ES_INIT ADC Exported Init structure - * @{ - */ - -/** - * @brief Structure definition of some features of ADC common parameters - * and multimode - * (all ADC instances belonging to the same ADC common instance). - * @note The setting of these parameters by function @ref LL_ADC_CommonInit() - * is conditioned to ADC instances state (all ADC instances - * sharing the same ADC common instance): - * All ADC instances sharing the same ADC common instance must be - * disabled. - */ -typedef struct -{ - uint32_t CommonClock; /*!< Set parameter common to several ADC: Clock source and prescaler. - This parameter can be a value of @ref ADC_LL_EC_COMMON_CLOCK_SOURCE - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetCommonClock(). */ - -#if defined(ADC_MULTIMODE_SUPPORT) - uint32_t Multimode; /*!< Set ADC multimode configuration to operate in independent mode or multimode (for devices with several ADC instances). - This parameter can be a value of @ref ADC_LL_EC_MULTI_MODE - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultimode(). */ - - uint32_t MultiDMATransfer; /*!< Set ADC multimode conversion data transfer: no transfer or transfer by DMA. - This parameter can be a value of @ref ADC_LL_EC_MULTI_DMA_TRANSFER - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultiDMATransfer(). */ - - uint32_t MultiTwoSamplingDelay; /*!< Set ADC multimode delay between 2 sampling phases. - This parameter can be a value of @ref ADC_LL_EC_MULTI_TWOSMP_DELAY - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultiTwoSamplingDelay(). */ -#endif /* ADC_MULTIMODE_SUPPORT */ - -} LL_ADC_CommonInitTypeDef; - -/** - * @brief Structure definition of some features of ADC instance. - * @note These parameters have an impact on ADC scope: ADC instance. - * Affects both group regular and group injected (availability - * of ADC group injected depends on STM32 families). - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Instance . - * @note The setting of these parameters by function @ref LL_ADC_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - */ -typedef struct -{ - uint32_t Resolution; /*!< Set ADC resolution. - This parameter can be a value of @ref ADC_LL_EC_RESOLUTION - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetResolution(). */ - - uint32_t DataAlignment; /*!< Set ADC conversion data alignment. - This parameter can be a value of @ref ADC_LL_EC_DATA_ALIGN - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetDataAlignment(). */ - - uint32_t SequencersScanMode; /*!< Set ADC scan selection. - This parameter can be a value of @ref ADC_LL_EC_SCAN_SELECTION - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetSequencersScanMode(). */ - -} LL_ADC_InitTypeDef; - -/** - * @brief Structure definition of some features of ADC group regular. - * @note These parameters have an impact on ADC scope: ADC group regular. - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Group_Regular - * (functions with prefix "REG"). - * @note The setting of these parameters by function @ref LL_ADC_REG_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - */ -typedef struct -{ - uint32_t TriggerSource; /*!< Set ADC group regular conversion trigger source: internal (SW start) or from external IP (timer event, external interrupt line). - This parameter can be a value of @ref ADC_LL_EC_REG_TRIGGER_SOURCE - @note On this STM32 series, setting of external trigger edge is performed - using function @ref LL_ADC_REG_StartConversionExtTrig(). - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetTriggerSource(). */ - - uint32_t SequencerLength; /*!< Set ADC group regular sequencer length. - This parameter can be a value of @ref ADC_LL_EC_REG_SEQ_SCAN_LENGTH - @note This parameter is discarded if scan mode is disabled (refer to parameter 'ADC_SequencersScanMode'). - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetSequencerLength(). */ - - uint32_t SequencerDiscont; /*!< Set ADC group regular sequencer discontinuous mode: sequence subdivided and scan conversions interrupted every selected number of ranks. - This parameter can be a value of @ref ADC_LL_EC_REG_SEQ_DISCONT_MODE - @note This parameter has an effect only if group regular sequencer is enabled - (scan length of 2 ranks or more). - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetSequencerDiscont(). */ - - uint32_t ContinuousMode; /*!< Set ADC continuous conversion mode on ADC group regular, whether ADC conversions are performed in single mode (one conversion per trigger) or in continuous mode (after the first trigger, following conversions launched successively automatically). - This parameter can be a value of @ref ADC_LL_EC_REG_CONTINUOUS_MODE - Note: It is not possible to enable both ADC group regular continuous mode and discontinuous mode. - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetContinuousMode(). */ - - uint32_t DMATransfer; /*!< Set ADC group regular conversion data transfer: no transfer or transfer by DMA, and DMA requests mode. - This parameter can be a value of @ref ADC_LL_EC_REG_DMA_TRANSFER - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetDMATransfer(). */ - -} LL_ADC_REG_InitTypeDef; - -/** - * @brief Structure definition of some features of ADC group injected. - * @note These parameters have an impact on ADC scope: ADC group injected. - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Group_Regular - * (functions with prefix "INJ"). - * @note The setting of these parameters by function @ref LL_ADC_INJ_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - */ -typedef struct -{ - uint32_t TriggerSource; /*!< Set ADC group injected conversion trigger source: internal (SW start) or from external IP (timer event, external interrupt line). - This parameter can be a value of @ref ADC_LL_EC_INJ_TRIGGER_SOURCE - @note On this STM32 series, setting of external trigger edge is performed - using function @ref LL_ADC_INJ_StartConversionExtTrig(). - - This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetTriggerSource(). */ - - uint32_t SequencerLength; /*!< Set ADC group injected sequencer length. - This parameter can be a value of @ref ADC_LL_EC_INJ_SEQ_SCAN_LENGTH - @note This parameter is discarded if scan mode is disabled (refer to parameter 'ADC_SequencersScanMode'). - - This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetSequencerLength(). */ - - uint32_t SequencerDiscont; /*!< Set ADC group injected sequencer discontinuous mode: sequence subdivided and scan conversions interrupted every selected number of ranks. - This parameter can be a value of @ref ADC_LL_EC_INJ_SEQ_DISCONT_MODE - @note This parameter has an effect only if group injected sequencer is enabled - (scan length of 2 ranks or more). - - This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetSequencerDiscont(). */ - - uint32_t TrigAuto; /*!< Set ADC group injected conversion trigger: independent or from ADC group regular. - This parameter can be a value of @ref ADC_LL_EC_INJ_TRIG_AUTO - Note: This parameter must be set to set to independent trigger if injected trigger source is set to an external trigger. - - This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetTrigAuto(). */ - -} LL_ADC_INJ_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup ADC_LL_Exported_Constants ADC Exported Constants - * @{ - */ - -/** @defgroup ADC_LL_EC_FLAG ADC flags - * @brief Flags defines which can be used with LL_ADC_ReadReg function - * @{ - */ -#define LL_ADC_FLAG_STRT ADC_SR_STRT /*!< ADC flag ADC group regular conversion start */ -#define LL_ADC_FLAG_EOCS ADC_SR_EOC /*!< ADC flag ADC group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_FLAG_OVR ADC_SR_OVR /*!< ADC flag ADC group regular overrun */ -#define LL_ADC_FLAG_JSTRT ADC_SR_JSTRT /*!< ADC flag ADC group injected conversion start */ -#define LL_ADC_FLAG_JEOS ADC_SR_JEOC /*!< ADC flag ADC group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_FLAG_AWD1 ADC_SR_AWD /*!< ADC flag ADC analog watchdog 1 */ -#if defined(ADC_MULTIMODE_SUPPORT) -#define LL_ADC_FLAG_EOCS_MST ADC_CSR_EOC1 /*!< ADC flag ADC multimode master group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_FLAG_EOCS_SLV1 ADC_CSR_EOC2 /*!< ADC flag ADC multimode slave 1 group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_FLAG_EOCS_SLV2 ADC_CSR_EOC3 /*!< ADC flag ADC multimode slave 2 group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_FLAG_OVR_MST ADC_CSR_OVR1 /*!< ADC flag ADC multimode master group regular overrun */ -#define LL_ADC_FLAG_OVR_SLV1 ADC_CSR_OVR2 /*!< ADC flag ADC multimode slave 1 group regular overrun */ -#define LL_ADC_FLAG_OVR_SLV2 ADC_CSR_OVR3 /*!< ADC flag ADC multimode slave 2 group regular overrun */ -#define LL_ADC_FLAG_JEOS_MST ADC_CSR_JEOC1 /*!< ADC flag ADC multimode master group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_FLAG_JEOS_SLV1 ADC_CSR_JEOC2 /*!< ADC flag ADC multimode slave 1 group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_FLAG_JEOS_SLV2 ADC_CSR_JEOC3 /*!< ADC flag ADC multimode slave 2 group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_FLAG_AWD1_MST ADC_CSR_AWD1 /*!< ADC flag ADC multimode master analog watchdog 1 of the ADC master */ -#define LL_ADC_FLAG_AWD1_SLV1 ADC_CSR_AWD2 /*!< ADC flag ADC multimode slave 1 analog watchdog 1 */ -#define LL_ADC_FLAG_AWD1_SLV2 ADC_CSR_AWD3 /*!< ADC flag ADC multimode slave 2 analog watchdog 1 */ -#endif -/** - * @} - */ - -/** @defgroup ADC_LL_EC_IT ADC interruptions for configuration (interruption enable or disable) - * @brief IT defines which can be used with LL_ADC_ReadReg and LL_ADC_WriteReg functions - * @{ - */ -#define LL_ADC_IT_EOCS ADC_CR1_EOCIE /*!< ADC interruption ADC group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_IT_OVR ADC_CR1_OVRIE /*!< ADC interruption ADC group regular overrun */ -#define LL_ADC_IT_JEOS ADC_CR1_JEOCIE /*!< ADC interruption ADC group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_IT_AWD1 ADC_CR1_AWDIE /*!< ADC interruption ADC analog watchdog 1 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REGISTERS ADC registers compliant with specific purpose - * @{ - */ -/* List of ADC registers intended to be used (most commonly) with */ -/* DMA transfer. */ -/* Refer to function @ref LL_ADC_DMA_GetRegAddr(). */ -#define LL_ADC_DMA_REG_REGULAR_DATA 0x00000000UL /* ADC group regular conversion data register (corresponding to register DR) to be used with ADC configured in independent mode. Without DMA transfer, register accessed by LL function @ref LL_ADC_REG_ReadConversionData32() and other functions @ref LL_ADC_REG_ReadConversionDatax() */ -#if defined(ADC_MULTIMODE_SUPPORT) -#define LL_ADC_DMA_REG_REGULAR_DATA_MULTI 0x00000001UL /* ADC group regular conversion data register (corresponding to register CDR) to be used with ADC configured in multimode (available on STM32 devices with several ADC instances). Without DMA transfer, register accessed by LL function @ref LL_ADC_REG_ReadMultiConversionData32() */ -#endif -/** - * @} - */ - -/** @defgroup ADC_LL_EC_COMMON_CLOCK_SOURCE ADC common - Clock source - * @{ - */ -#define LL_ADC_CLOCK_SYNC_PCLK_DIV2 0x00000000UL /*!< ADC synchronous clock derived from AHB clock with prescaler division by 2 */ -#define LL_ADC_CLOCK_SYNC_PCLK_DIV4 ( ADC_CCR_ADCPRE_0) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 4 */ -#define LL_ADC_CLOCK_SYNC_PCLK_DIV6 (ADC_CCR_ADCPRE_1 ) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 6 */ -#define LL_ADC_CLOCK_SYNC_PCLK_DIV8 (ADC_CCR_ADCPRE_1 | ADC_CCR_ADCPRE_0) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 8 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_COMMON_PATH_INTERNAL ADC common - Measurement path to internal channels - * @{ - */ -/* Note: Other measurement paths to internal channels may be available */ -/* (connections to other peripherals). */ -/* If they are not listed below, they do not require any specific */ -/* path enable. In this case, Access to measurement path is done */ -/* only by selecting the corresponding ADC internal channel. */ -#define LL_ADC_PATH_INTERNAL_NONE 0x00000000UL /*!< ADC measurement paths all disabled */ -#define LL_ADC_PATH_INTERNAL_VREFINT (ADC_CCR_TSVREFE) /*!< ADC measurement path to internal channel VrefInt */ -#define LL_ADC_PATH_INTERNAL_TEMPSENSOR (ADC_CCR_TSVREFE) /*!< ADC measurement path to internal channel temperature sensor */ -#define LL_ADC_PATH_INTERNAL_VBAT (ADC_CCR_VBATE) /*!< ADC measurement path to internal channel Vbat */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_RESOLUTION ADC instance - Resolution - * @{ - */ -#define LL_ADC_RESOLUTION_12B 0x00000000UL /*!< ADC resolution 12 bits */ -#define LL_ADC_RESOLUTION_10B ( ADC_CR1_RES_0) /*!< ADC resolution 10 bits */ -#define LL_ADC_RESOLUTION_8B (ADC_CR1_RES_1 ) /*!< ADC resolution 8 bits */ -#define LL_ADC_RESOLUTION_6B (ADC_CR1_RES_1 | ADC_CR1_RES_0) /*!< ADC resolution 6 bits */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_DATA_ALIGN ADC instance - Data alignment - * @{ - */ -#define LL_ADC_DATA_ALIGN_RIGHT 0x00000000UL /*!< ADC conversion data alignment: right aligned (alignment on data register LSB bit 0)*/ -#define LL_ADC_DATA_ALIGN_LEFT (ADC_CR2_ALIGN) /*!< ADC conversion data alignment: left aligned (alignment on data register MSB bit 15)*/ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_SCAN_SELECTION ADC instance - Scan selection - * @{ - */ -#define LL_ADC_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC conversion is performed in unitary conversion mode (one channel converted, that defined in rank 1). Configuration of both groups regular and injected sequencers (sequence length, ...) is discarded: equivalent to length of 1 rank.*/ -#define LL_ADC_SEQ_SCAN_ENABLE (ADC_CR1_SCAN) /*!< ADC conversions are performed in sequence conversions mode, according to configuration of both groups regular and injected sequencers (sequence length, ...). */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_GROUPS ADC instance - Groups - * @{ - */ -#define LL_ADC_GROUP_REGULAR 0x00000001UL /*!< ADC group regular (available on all STM32 devices) */ -#define LL_ADC_GROUP_INJECTED 0x00000002UL /*!< ADC group injected (not available on all STM32 devices)*/ -#define LL_ADC_GROUP_REGULAR_INJECTED 0x00000003UL /*!< ADC both groups regular and injected */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_CHANNEL ADC instance - Channel number - * @{ - */ -#define LL_ADC_CHANNEL_0 (ADC_CHANNEL_0_NUMBER | ADC_CHANNEL_0_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN0 */ -#define LL_ADC_CHANNEL_1 (ADC_CHANNEL_1_NUMBER | ADC_CHANNEL_1_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN1 */ -#define LL_ADC_CHANNEL_2 (ADC_CHANNEL_2_NUMBER | ADC_CHANNEL_2_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN2 */ -#define LL_ADC_CHANNEL_3 (ADC_CHANNEL_3_NUMBER | ADC_CHANNEL_3_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN3 */ -#define LL_ADC_CHANNEL_4 (ADC_CHANNEL_4_NUMBER | ADC_CHANNEL_4_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN4 */ -#define LL_ADC_CHANNEL_5 (ADC_CHANNEL_5_NUMBER | ADC_CHANNEL_5_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN5 */ -#define LL_ADC_CHANNEL_6 (ADC_CHANNEL_6_NUMBER | ADC_CHANNEL_6_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN6 */ -#define LL_ADC_CHANNEL_7 (ADC_CHANNEL_7_NUMBER | ADC_CHANNEL_7_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN7 */ -#define LL_ADC_CHANNEL_8 (ADC_CHANNEL_8_NUMBER | ADC_CHANNEL_8_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN8 */ -#define LL_ADC_CHANNEL_9 (ADC_CHANNEL_9_NUMBER | ADC_CHANNEL_9_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN9 */ -#define LL_ADC_CHANNEL_10 (ADC_CHANNEL_10_NUMBER | ADC_CHANNEL_10_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN10 */ -#define LL_ADC_CHANNEL_11 (ADC_CHANNEL_11_NUMBER | ADC_CHANNEL_11_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN11 */ -#define LL_ADC_CHANNEL_12 (ADC_CHANNEL_12_NUMBER | ADC_CHANNEL_12_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN12 */ -#define LL_ADC_CHANNEL_13 (ADC_CHANNEL_13_NUMBER | ADC_CHANNEL_13_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN13 */ -#define LL_ADC_CHANNEL_14 (ADC_CHANNEL_14_NUMBER | ADC_CHANNEL_14_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN14 */ -#define LL_ADC_CHANNEL_15 (ADC_CHANNEL_15_NUMBER | ADC_CHANNEL_15_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN15 */ -#define LL_ADC_CHANNEL_16 (ADC_CHANNEL_16_NUMBER | ADC_CHANNEL_16_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN16 */ -#define LL_ADC_CHANNEL_17 (ADC_CHANNEL_17_NUMBER | ADC_CHANNEL_17_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN17 */ -#define LL_ADC_CHANNEL_18 (ADC_CHANNEL_18_NUMBER | ADC_CHANNEL_18_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN18 */ -#define LL_ADC_CHANNEL_VREFINT (LL_ADC_CHANNEL_17 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to VrefInt: Internal voltage reference. On STM32F4, ADC channel available only on ADC instance: ADC1. */ -#define LL_ADC_CHANNEL_VBAT (LL_ADC_CHANNEL_18 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda. On STM32F4, ADC channel available only on ADC instance: ADC1. */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F415xx) || defined(STM32F417xx) -#define LL_ADC_CHANNEL_TEMPSENSOR (LL_ADC_CHANNEL_16 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to Temperature sensor. On STM32F4, ADC channel available only on ADC instance: ADC1. */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx */ -#if defined(STM32F411xE) || defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define LL_ADC_CHANNEL_TEMPSENSOR (LL_ADC_CHANNEL_18 | ADC_CHANNEL_ID_INTERNAL_CH | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) /*!< ADC internal channel connected to Temperature sensor. On STM32F4, ADC channel available only on ADC instance: ADC1. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ -#endif /* STM32F411xE || STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_TRIGGER_SOURCE ADC group regular - Trigger source - * @{ - */ -#define LL_ADC_REG_TRIG_SOFTWARE 0x00000000UL /*!< ADC group regular conversion trigger internal: SW start. */ -#define LL_ADC_REG_TRIG_EXT_TIM1_CH1 (ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM1_CH2 (ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM1_CH3 (ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM2_CH2 (ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM2_CH3 (ADC_CR2_EXTSEL_2 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM2_CH4 (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM2_TRGO (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM3_CH1 (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM3 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM3_TRGO (ADC_CR2_EXTSEL_3 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM3 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM4_CH4 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM4 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM5_CH1 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM5_CH2 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM5_CH3 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM8_CH1 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM8 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM8_TRGO (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM8 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_EXTI_LINE11 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: external interrupt line 11. Trigger edge set to rising edge (default setting). */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_TRIGGER_EDGE ADC group regular - Trigger edge - * @{ - */ -#define LL_ADC_REG_TRIG_EXT_RISING ( ADC_CR2_EXTEN_0) /*!< ADC group regular conversion trigger polarity set to rising edge */ -#define LL_ADC_REG_TRIG_EXT_FALLING (ADC_CR2_EXTEN_1 ) /*!< ADC group regular conversion trigger polarity set to falling edge */ -#define LL_ADC_REG_TRIG_EXT_RISINGFALLING (ADC_CR2_EXTEN_1 | ADC_CR2_EXTEN_0) /*!< ADC group regular conversion trigger polarity set to both rising and falling edges */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_CONTINUOUS_MODE ADC group regular - Continuous mode -* @{ -*/ -#define LL_ADC_REG_CONV_SINGLE 0x00000000UL /*!< ADC conversions are performed in single mode: one conversion per trigger */ -#define LL_ADC_REG_CONV_CONTINUOUS (ADC_CR2_CONT) /*!< ADC conversions are performed in continuous mode: after the first trigger, following conversions launched successively automatically */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_DMA_TRANSFER ADC group regular - DMA transfer of ADC conversion data - * @{ - */ -#define LL_ADC_REG_DMA_TRANSFER_NONE 0x00000000UL /*!< ADC conversions are not transferred by DMA */ -#define LL_ADC_REG_DMA_TRANSFER_LIMITED ( ADC_CR2_DMA) /*!< ADC conversion data are transferred by DMA, in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. */ -#define LL_ADC_REG_DMA_TRANSFER_UNLIMITED (ADC_CR2_DDS | ADC_CR2_DMA) /*!< ADC conversion data are transferred by DMA, in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions). This ADC mode is intended to be used with DMA mode circular. */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_FLAG_EOC_SELECTION ADC group regular - Flag EOC selection (unitary or sequence conversions) - * @{ - */ -#define LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV 0x00000000UL /*!< ADC flag EOC (end of unitary conversion) selected */ -#define LL_ADC_REG_FLAG_EOC_UNITARY_CONV (ADC_CR2_EOCS) /*!< ADC flag EOS (end of sequence conversions) selected */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_SEQ_SCAN_LENGTH ADC group regular - Sequencer scan length - * @{ - */ -#define LL_ADC_REG_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC group regular sequencer disable (equivalent to sequencer of 1 rank: ADC conversion on only 1 channel) */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS ( ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 2 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS ( ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 3 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS ( ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 4 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS ( ADC_SQR1_L_2 ) /*!< ADC group regular sequencer enable with 5 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 6 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 7 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 8 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS (ADC_SQR1_L_3 ) /*!< ADC group regular sequencer enable with 9 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 10 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 11 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 12 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 ) /*!< ADC group regular sequencer enable with 13 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 14 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 15 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 16 ranks in the sequence */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_SEQ_DISCONT_MODE ADC group regular - Sequencer discontinuous mode - * @{ - */ -#define LL_ADC_REG_SEQ_DISCONT_DISABLE 0x00000000UL /*!< ADC group regular sequencer discontinuous mode disable */ -#define LL_ADC_REG_SEQ_DISCONT_1RANK ( ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every rank */ -#define LL_ADC_REG_SEQ_DISCONT_2RANKS ( ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enabled with sequence interruption every 2 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_3RANKS ( ADC_CR1_DISCNUM_1 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 3 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_4RANKS ( ADC_CR1_DISCNUM_1 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 4 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_5RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 5 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_6RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 6 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_7RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_1 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 7 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_8RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_1 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 8 ranks */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_SEQ_RANKS ADC group regular - Sequencer ranks - * @{ - */ -#define LL_ADC_REG_RANK_1 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_1_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 1 */ -#define LL_ADC_REG_RANK_2 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_2_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 2 */ -#define LL_ADC_REG_RANK_3 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_3_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 3 */ -#define LL_ADC_REG_RANK_4 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_4_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 4 */ -#define LL_ADC_REG_RANK_5 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_5_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 5 */ -#define LL_ADC_REG_RANK_6 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_6_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 6 */ -#define LL_ADC_REG_RANK_7 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_7_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 7 */ -#define LL_ADC_REG_RANK_8 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_8_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 8 */ -#define LL_ADC_REG_RANK_9 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_9_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 9 */ -#define LL_ADC_REG_RANK_10 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_10_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 10 */ -#define LL_ADC_REG_RANK_11 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_11_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 11 */ -#define LL_ADC_REG_RANK_12 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_12_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 12 */ -#define LL_ADC_REG_RANK_13 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_13_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 13 */ -#define LL_ADC_REG_RANK_14 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_14_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 14 */ -#define LL_ADC_REG_RANK_15 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_15_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 15 */ -#define LL_ADC_REG_RANK_16 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_16_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 16 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_TRIGGER_SOURCE ADC group injected - Trigger source - * @{ - */ -#define LL_ADC_INJ_TRIG_SOFTWARE 0x00000000UL /*!< ADC group injected conversion trigger internal: SW start. */ -#define LL_ADC_INJ_TRIG_EXT_TIM1_CH4 (ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM1 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM1_TRGO (ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM1 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM2_CH1 (ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM2 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM2_TRGO (ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM2 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM3_CH2 (ADC_CR2_JEXTSEL_2 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM3 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM3_CH4 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM3 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM4_CH1 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM4_CH2 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM4_CH3 (ADC_CR2_JEXTSEL_3 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM4_TRGO (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM5_CH4 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM5 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM5_TRGO (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM5 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM8_CH2 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM8_CH3 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM8_CH4 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: external interrupt line 15. Trigger edge set to rising edge (default setting). */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_TRIGGER_EDGE ADC group injected - Trigger edge - * @{ - */ -#define LL_ADC_INJ_TRIG_EXT_RISING ( ADC_CR2_JEXTEN_0) /*!< ADC group injected conversion trigger polarity set to rising edge */ -#define LL_ADC_INJ_TRIG_EXT_FALLING (ADC_CR2_JEXTEN_1 ) /*!< ADC group injected conversion trigger polarity set to falling edge */ -#define LL_ADC_INJ_TRIG_EXT_RISINGFALLING (ADC_CR2_JEXTEN_1 | ADC_CR2_JEXTEN_0) /*!< ADC group injected conversion trigger polarity set to both rising and falling edges */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_TRIG_AUTO ADC group injected - Automatic trigger mode -* @{ -*/ -#define LL_ADC_INJ_TRIG_INDEPENDENT 0x00000000UL /*!< ADC group injected conversion trigger independent. Setting mandatory if ADC group injected injected trigger source is set to an external trigger. */ -#define LL_ADC_INJ_TRIG_FROM_GRP_REGULAR (ADC_CR1_JAUTO) /*!< ADC group injected conversion trigger from ADC group regular. Setting compliant only with group injected trigger source set to SW start, without any further action on ADC group injected conversion start or stop: in this case, ADC group injected is controlled only from ADC group regular. */ -/** - * @} - */ - - -/** @defgroup ADC_LL_EC_INJ_SEQ_SCAN_LENGTH ADC group injected - Sequencer scan length - * @{ - */ -#define LL_ADC_INJ_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC group injected sequencer disable (equivalent to sequencer of 1 rank: ADC conversion on only 1 channel) */ -#define LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS ( ADC_JSQR_JL_0) /*!< ADC group injected sequencer enable with 2 ranks in the sequence */ -#define LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS (ADC_JSQR_JL_1 ) /*!< ADC group injected sequencer enable with 3 ranks in the sequence */ -#define LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS (ADC_JSQR_JL_1 | ADC_JSQR_JL_0) /*!< ADC group injected sequencer enable with 4 ranks in the sequence */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_SEQ_DISCONT_MODE ADC group injected - Sequencer discontinuous mode - * @{ - */ -#define LL_ADC_INJ_SEQ_DISCONT_DISABLE 0x00000000UL /*!< ADC group injected sequencer discontinuous mode disable */ -#define LL_ADC_INJ_SEQ_DISCONT_1RANK (ADC_CR1_JDISCEN) /*!< ADC group injected sequencer discontinuous mode enable with sequence interruption every rank */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_SEQ_RANKS ADC group injected - Sequencer ranks - * @{ - */ -#define LL_ADC_INJ_RANK_1 (ADC_JDR1_REGOFFSET | ADC_JOFR1_REGOFFSET | 0x00000001UL) /*!< ADC group injected sequencer rank 1 */ -#define LL_ADC_INJ_RANK_2 (ADC_JDR2_REGOFFSET | ADC_JOFR2_REGOFFSET | 0x00000002UL) /*!< ADC group injected sequencer rank 2 */ -#define LL_ADC_INJ_RANK_3 (ADC_JDR3_REGOFFSET | ADC_JOFR3_REGOFFSET | 0x00000003UL) /*!< ADC group injected sequencer rank 3 */ -#define LL_ADC_INJ_RANK_4 (ADC_JDR4_REGOFFSET | ADC_JOFR4_REGOFFSET | 0x00000004UL) /*!< ADC group injected sequencer rank 4 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_CHANNEL_SAMPLINGTIME Channel - Sampling time - * @{ - */ -#define LL_ADC_SAMPLINGTIME_3CYCLES 0x00000000UL /*!< Sampling time 3 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_15CYCLES (ADC_SMPR1_SMP10_0) /*!< Sampling time 15 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_28CYCLES (ADC_SMPR1_SMP10_1) /*!< Sampling time 28 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_56CYCLES (ADC_SMPR1_SMP10_1 | ADC_SMPR1_SMP10_0) /*!< Sampling time 56 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_84CYCLES (ADC_SMPR1_SMP10_2) /*!< Sampling time 84 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_112CYCLES (ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_0) /*!< Sampling time 112 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_144CYCLES (ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_1) /*!< Sampling time 144 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_480CYCLES (ADC_SMPR1_SMP10) /*!< Sampling time 480 ADC clock cycles */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_AWD_NUMBER Analog watchdog - Analog watchdog number - * @{ - */ -#define LL_ADC_AWD1 (ADC_AWD_CR1_CHANNEL_MASK | ADC_AWD_CR1_REGOFFSET) /*!< ADC analog watchdog number 1 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_AWD_CHANNELS Analog watchdog - Monitored channels - * @{ - */ -#define LL_ADC_AWD_DISABLE 0x00000000UL /*!< ADC analog watchdog monitoring disabled */ -#define LL_ADC_AWD_ALL_CHANNELS_REG ( ADC_CR1_AWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by group regular only */ -#define LL_ADC_AWD_ALL_CHANNELS_INJ ( ADC_CR1_JAWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by group injected only */ -#define LL_ADC_AWD_ALL_CHANNELS_REG_INJ ( ADC_CR1_JAWDEN | ADC_CR1_AWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_0_REG ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_0_INJ ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_0_REG_INJ ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_1_REG ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_1_INJ ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_1_REG_INJ ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_2_REG ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_2_INJ ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_2_REG_INJ ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_3_REG ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_3_INJ ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_3_REG_INJ ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_4_REG ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_4_INJ ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_4_REG_INJ ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_5_REG ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_5_INJ ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_5_REG_INJ ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_6_REG ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_6_INJ ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_6_REG_INJ ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_7_REG ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_7_INJ ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_7_REG_INJ ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_8_REG ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_8_INJ ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_8_REG_INJ ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_9_REG ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_9_INJ ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_9_REG_INJ ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_10_REG ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_10_INJ ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_10_REG_INJ ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_11_REG ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_11_INJ ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_11_REG_INJ ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_12_REG ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_12_INJ ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_12_REG_INJ ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_13_REG ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_13_INJ ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_13_REG_INJ ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_14_REG ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_14_INJ ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_14_REG_INJ ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_15_REG ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_15_INJ ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_15_REG_INJ ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_16_REG ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_16_INJ ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_16_REG_INJ ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_17_REG ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_17_INJ ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_17_REG_INJ ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_18_REG ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_18_INJ ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_18_REG_INJ ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by either group regular or injected */ -#define LL_ADC_AWD_CH_VREFINT_REG ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by group regular only */ -#define LL_ADC_AWD_CH_VREFINT_INJ ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by group injected only */ -#define LL_ADC_AWD_CH_VREFINT_REG_INJ ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by either group regular or injected */ -#define LL_ADC_AWD_CH_VBAT_REG ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda, converted by group regular only */ -#define LL_ADC_AWD_CH_VBAT_INJ ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda, converted by group injected only */ -#define LL_ADC_AWD_CH_VBAT_REG_INJ ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F415xx) || defined(STM32F417xx) -#define LL_ADC_AWD_CH_TEMPSENSOR_REG ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group regular only */ -#define LL_ADC_AWD_CH_TEMPSENSOR_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group injected only */ -#define LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by either group regular or injected */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx */ -#if defined(STM32F411xE) || defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define LL_ADC_AWD_CH_TEMPSENSOR_REG ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group regular only. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ -#define LL_ADC_AWD_CH_TEMPSENSOR_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group injected only. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ -#define LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by either group regular or injected. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ -#endif /* STM32F411xE || STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_AWD_THRESHOLDS Analog watchdog - Thresholds - * @{ - */ -#define LL_ADC_AWD_THRESHOLD_HIGH (ADC_AWD_TR1_HIGH_REGOFFSET) /*!< ADC analog watchdog threshold high */ -#define LL_ADC_AWD_THRESHOLD_LOW (ADC_AWD_TR1_LOW_REGOFFSET) /*!< ADC analog watchdog threshold low */ -/** - * @} - */ - -#if defined(ADC_MULTIMODE_SUPPORT) -/** @defgroup ADC_LL_EC_MULTI_MODE Multimode - Mode - * @{ - */ -#define LL_ADC_MULTI_INDEPENDENT 0x00000000UL /*!< ADC dual mode disabled (ADC independent mode) */ -#define LL_ADC_MULTI_DUAL_REG_SIMULT ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 ) /*!< ADC dual mode enabled: group regular simultaneous */ -#define LL_ADC_MULTI_DUAL_REG_INTERL ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular interleaved */ -#define LL_ADC_MULTI_DUAL_INJ_SIMULT ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: group injected simultaneous */ -#define LL_ADC_MULTI_DUAL_INJ_ALTERN (ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: group injected alternate trigger. Works only with external triggers (not internal SW start) */ -#define LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM ( ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular simultaneous + group injected simultaneous */ -#define LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT ( ADC_CCR_MULTI_1 ) /*!< ADC dual mode enabled: Combined group regular simultaneous + group injected alternate trigger */ -#define LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM ( ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular interleaved + group injected simultaneous */ -#if defined(ADC3) -#define LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: Combined group regular simultaneous + group injected simultaneous */ -#define LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_1 ) /*!< ADC triple mode enabled: Combined group regular simultaneous + group injected alternate trigger */ -#define LL_ADC_MULTI_TRIPLE_INJ_SIMULT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: group injected simultaneous */ -#define LL_ADC_MULTI_TRIPLE_REG_SIMULT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 ) /*!< ADC triple mode enabled: group regular simultaneous */ -#define LL_ADC_MULTI_TRIPLE_REG_INTERL (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: Combined group regular interleaved */ -#define LL_ADC_MULTI_TRIPLE_INJ_ALTERN (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: group injected alternate trigger. Works only with external triggers (not internal SW start) */ -#endif -/** - * @} - */ - -/** @defgroup ADC_LL_EC_MULTI_DMA_TRANSFER Multimode - DMA transfer - * @{ - */ -#define LL_ADC_MULTI_REG_DMA_EACH_ADC 0x00000000UL /*!< ADC multimode group regular conversions are transferred by DMA: each ADC uses its own DMA channel, with its individual DMA transfer settings */ -#define LL_ADC_MULTI_REG_DMA_LIMIT_1 ( ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 1: 2 or 3 (dual or triple mode) half-words one by one, ADC1 then ADC2 then ADC3. */ -#define LL_ADC_MULTI_REG_DMA_LIMIT_2 ( ADC_CCR_DMA_1 ) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 2: 2 or 3 (dual or triple mode) half-words one by one, ADC2&1 then ADC1&3 then ADC3&2. */ -#define LL_ADC_MULTI_REG_DMA_LIMIT_3 ( ADC_CCR_DMA_1 | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 3: 2 or 3 (dual or triple mode) bytes one by one, ADC2&1 then ADC1&3 then ADC3&2. */ -#define LL_ADC_MULTI_REG_DMA_UNLMT_1 (ADC_CCR_DDS | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 1: 2 or 3 (dual or triple mode) half-words one by one, ADC1 then ADC2 then ADC3. */ -#define LL_ADC_MULTI_REG_DMA_UNLMT_2 (ADC_CCR_DDS | ADC_CCR_DMA_1 ) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 2: 2 or 3 (dual or triple mode) half-words by pairs, ADC2&1 then ADC1&3 then ADC3&2. */ -#define LL_ADC_MULTI_REG_DMA_UNLMT_3 (ADC_CCR_DDS | ADC_CCR_DMA_1 | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 3: 2 or 3 (dual or triple mode) bytes one by one, ADC2&1 then ADC1&3 then ADC3&2. */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_MULTI_TWOSMP_DELAY Multimode - Delay between two sampling phases - * @{ - */ -#define LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES 0x00000000UL /*!< ADC multimode delay between two sampling phases: 5 ADC clock cycles*/ -#define LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES ( ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 6 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES ( ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 7 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES ( ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 8 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES ( ADC_CCR_DELAY_2 ) /*!< ADC multimode delay between two sampling phases: 9 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 10 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 11 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 12 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES (ADC_CCR_DELAY_3 ) /*!< ADC multimode delay between two sampling phases: 13 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 14 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 15 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 16 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 ) /*!< ADC multimode delay between two sampling phases: 17 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 18 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 19 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 20 ADC clock cycles */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_MULTI_MASTER_SLAVE Multimode - ADC master or slave - * @{ - */ -#define LL_ADC_MULTI_MASTER ( ADC_CDR_RDATA_MST) /*!< In multimode, selection among several ADC instances: ADC master */ -#define LL_ADC_MULTI_SLAVE (ADC_CDR_RDATA_SLV ) /*!< In multimode, selection among several ADC instances: ADC slave */ -#define LL_ADC_MULTI_MASTER_SLAVE (ADC_CDR_RDATA_SLV | ADC_CDR_RDATA_MST) /*!< In multimode, selection among several ADC instances: both ADC master and ADC slave */ -/** - * @} - */ - -#endif /* ADC_MULTIMODE_SUPPORT */ - - -/** @defgroup ADC_LL_EC_HW_DELAYS Definitions of ADC hardware constraints delays - * @note Only ADC IP HW delays are defined in ADC LL driver driver, - * not timeout values. - * For details on delays values, refer to descriptions in source code - * above each literal definition. - * @{ - */ - -/* Note: Only ADC IP HW delays are defined in ADC LL driver driver, */ -/* not timeout values. */ -/* Timeout values for ADC operations are dependent to device clock */ -/* configuration (system clock versus ADC clock), */ -/* and therefore must be defined in user application. */ -/* Indications for estimation of ADC timeout delays, for this */ -/* STM32 series: */ -/* - ADC enable time: maximum delay is 2us */ -/* (refer to device datasheet, parameter "tSTAB") */ -/* - ADC conversion time: duration depending on ADC clock and ADC */ -/* configuration. */ -/* (refer to device reference manual, section "Timing") */ - -/* Delay for internal voltage reference stabilization time. */ -/* Delay set to maximum value (refer to device datasheet, */ -/* parameter "tSTART"). */ -/* Unit: us */ -#define LL_ADC_DELAY_VREFINT_STAB_US ( 10UL) /*!< Delay for internal voltage reference stabilization time */ - -/* Delay for temperature sensor stabilization time. */ -/* Literal set to maximum value (refer to device datasheet, */ -/* parameter "tSTART"). */ -/* Unit: us */ -#define LL_ADC_DELAY_TEMPSENSOR_STAB_US ( 10UL) /*!< Delay for internal voltage reference stabilization time */ - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup ADC_LL_Exported_Macros ADC Exported Macros - * @{ - */ - -/** @defgroup ADC_LL_EM_WRITE_READ Common write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in ADC register - * @param __INSTANCE__ ADC Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_ADC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in ADC register - * @param __INSTANCE__ ADC Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_ADC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup ADC_LL_EM_HELPER_MACRO ADC helper macro - * @{ - */ - -/** - * @brief Helper macro to get ADC channel number in decimal format - * from literals LL_ADC_CHANNEL_x. - * @note Example: - * __LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_CHANNEL_4) - * will return decimal number "4". - * @note The input can be a value from functions where a channel - * number is returned, either defined with number - * or with bitfield (only one bit must be set). - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Value between Min_Data=0 and Max_Data=18 - */ -#define __LL_ADC_CHANNEL_TO_DECIMAL_NB(__CHANNEL__) \ - (((__CHANNEL__) & ADC_CHANNEL_ID_NUMBER_MASK) >> ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) - -/** - * @brief Helper macro to get ADC channel in literal format LL_ADC_CHANNEL_x - * from number in decimal format. - * @note Example: - * __LL_ADC_DECIMAL_NB_TO_CHANNEL(4) - * will return a data equivalent to "LL_ADC_CHANNEL_4". - * @param __DECIMAL_NB__ Value between Min_Data=0 and Max_Data=18 - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n - * (1) For ADC channel read back from ADC register, - * comparison with internal channel parameter to be done - * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). - */ -#define __LL_ADC_DECIMAL_NB_TO_CHANNEL(__DECIMAL_NB__) \ - (((__DECIMAL_NB__) <= 9UL) \ - ? ( \ - ((__DECIMAL_NB__) << ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) | \ - (ADC_SMPR2_REGOFFSET | (((uint32_t) (3UL * (__DECIMAL_NB__))) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) \ - ) \ - : \ - ( \ - ((__DECIMAL_NB__) << ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) | \ - (ADC_SMPR1_REGOFFSET | (((uint32_t) (3UL * ((__DECIMAL_NB__) - 10UL))) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) \ - ) \ - ) - -/** - * @brief Helper macro to determine whether the selected channel - * corresponds to literal definitions of driver. - * @note The different literal definitions of ADC channels are: - * - ADC internal channel: - * LL_ADC_CHANNEL_VREFINT, LL_ADC_CHANNEL_TEMPSENSOR, ... - * - ADC external channel (channel connected to a GPIO pin): - * LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ... - * @note The channel parameter must be a value defined from literal - * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, - * LL_ADC_CHANNEL_TEMPSENSOR, ...), - * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...), - * must not be a value from functions where a channel number is - * returned from ADC registers, - * because internal and external channels share the same channel - * number in ADC registers. The differentiation is made only with - * parameters definitions of driver. - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Value "0" if the channel corresponds to a parameter definition of a ADC external channel (channel connected to a GPIO pin). - * Value "1" if the channel corresponds to a parameter definition of a ADC internal channel. - */ -#define __LL_ADC_IS_CHANNEL_INTERNAL(__CHANNEL__) \ - (((__CHANNEL__) & ADC_CHANNEL_ID_INTERNAL_CH_MASK) != 0UL) - -/** - * @brief Helper macro to convert a channel defined from parameter - * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, - * LL_ADC_CHANNEL_TEMPSENSOR, ...), - * to its equivalent parameter definition of a ADC external channel - * (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...). - * @note The channel parameter can be, additionally to a value - * defined from parameter definition of a ADC internal channel - * (LL_ADC_CHANNEL_VREFINT, LL_ADC_CHANNEL_TEMPSENSOR, ...), - * a value defined from parameter definition of - * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...) - * or a value from functions where a channel number is returned - * from ADC registers. - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - */ -#define __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(__CHANNEL__) \ - ((__CHANNEL__) & ~ADC_CHANNEL_ID_INTERNAL_CH_MASK) - -/** - * @brief Helper macro to determine whether the internal channel - * selected is available on the ADC instance selected. - * @note The channel parameter must be a value defined from parameter - * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, - * LL_ADC_CHANNEL_TEMPSENSOR, ...), - * must not be a value defined from parameter definition of - * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...) - * or a value from functions where a channel number is - * returned from ADC registers, - * because internal and external channels share the same channel - * number in ADC registers. The differentiation is made only with - * parameters definitions of driver. - * @param __ADC_INSTANCE__ ADC instance - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1. - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Value "0" if the internal channel selected is not available on the ADC instance selected. - * Value "1" if the internal channel selected is available on the ADC instance selected. - */ -#define __LL_ADC_IS_CHANNEL_INTERNAL_AVAILABLE(__ADC_INSTANCE__, __CHANNEL__) \ - ( \ - ((__CHANNEL__) == LL_ADC_CHANNEL_VREFINT) || \ - ((__CHANNEL__) == LL_ADC_CHANNEL_TEMPSENSOR) || \ - ((__CHANNEL__) == LL_ADC_CHANNEL_VBAT) \ - ) -/** - * @brief Helper macro to define ADC analog watchdog parameter: - * define a single channel to monitor with analog watchdog - * from sequencer channel and groups definition. - * @note To be used with function @ref LL_ADC_SetAnalogWDMonitChannels(). - * Example: - * LL_ADC_SetAnalogWDMonitChannels( - * ADC1, LL_ADC_AWD1, - * __LL_ADC_ANALOGWD_CHANNEL_GROUP(LL_ADC_CHANNEL4, LL_ADC_GROUP_REGULAR)) - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n - * (1) For ADC channel read back from ADC register, - * comparison with internal channel parameter to be done - * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). - * @param __GROUP__ This parameter can be one of the following values: - * @arg @ref LL_ADC_GROUP_REGULAR - * @arg @ref LL_ADC_GROUP_INJECTED - * @arg @ref LL_ADC_GROUP_REGULAR_INJECTED - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_AWD_DISABLE - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG - * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG - * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG - * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG - * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG - * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG - * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG - * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG - * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG - * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG - * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG - * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG - * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG - * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG - * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG - * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG - * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG - * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG - * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG - * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ - * @arg @ref LL_ADC_AWD_CH_VREFINT_REG (1) - * @arg @ref LL_ADC_AWD_CH_VREFINT_INJ (1) - * @arg @ref LL_ADC_AWD_CH_VREFINT_REG_INJ (1) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG (1)(2) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_INJ (1)(2) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ (1)(2) - * @arg @ref LL_ADC_AWD_CH_VBAT_REG (1) - * @arg @ref LL_ADC_AWD_CH_VBAT_INJ (1) - * @arg @ref LL_ADC_AWD_CH_VBAT_REG_INJ (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - */ -#define __LL_ADC_ANALOGWD_CHANNEL_GROUP(__CHANNEL__, __GROUP__) \ - (((__GROUP__) == LL_ADC_GROUP_REGULAR) \ - ? (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) \ - : \ - ((__GROUP__) == LL_ADC_GROUP_INJECTED) \ - ? (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) \ - : \ - (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) \ - ) - -/** - * @brief Helper macro to set the value of ADC analog watchdog threshold high - * or low in function of ADC resolution, when ADC resolution is - * different of 12 bits. - * @note To be used with function @ref LL_ADC_SetAnalogWDThresholds(). - * Example, with a ADC resolution of 8 bits, to set the value of - * analog watchdog threshold high (on 8 bits): - * LL_ADC_SetAnalogWDThresholds - * (< ADCx param >, - * __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(LL_ADC_RESOLUTION_8B, ) - * ); - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @param __AWD_THRESHOLD__ Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -#define __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(__ADC_RESOLUTION__, __AWD_THRESHOLD__) \ - ((__AWD_THRESHOLD__) << ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL ))) - -/** - * @brief Helper macro to get the value of ADC analog watchdog threshold high - * or low in function of ADC resolution, when ADC resolution is - * different of 12 bits. - * @note To be used with function @ref LL_ADC_GetAnalogWDThresholds(). - * Example, with a ADC resolution of 8 bits, to get the value of - * analog watchdog threshold high (on 8 bits): - * < threshold_value_6_bits > = __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION - * (LL_ADC_RESOLUTION_8B, - * LL_ADC_GetAnalogWDThresholds(, LL_ADC_AWD_THRESHOLD_HIGH) - * ); - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @param __AWD_THRESHOLD_12_BITS__ Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -#define __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION(__ADC_RESOLUTION__, __AWD_THRESHOLD_12_BITS__) \ - ((__AWD_THRESHOLD_12_BITS__) >> ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL ))) - -#if defined(ADC_MULTIMODE_SUPPORT) -/** - * @brief Helper macro to get the ADC multimode conversion data of ADC master - * or ADC slave from raw value with both ADC conversion data concatenated. - * @note This macro is intended to be used when multimode transfer by DMA - * is enabled: refer to function @ref LL_ADC_SetMultiDMATransfer(). - * In this case the transferred data need to processed with this macro - * to separate the conversion data of ADC master and ADC slave. - * @param __ADC_MULTI_MASTER_SLAVE__ This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_MASTER - * @arg @ref LL_ADC_MULTI_SLAVE - * @param __ADC_MULTI_CONV_DATA__ Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -#define __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(__ADC_MULTI_MASTER_SLAVE__, __ADC_MULTI_CONV_DATA__) \ - (((__ADC_MULTI_CONV_DATA__) >> POSITION_VAL((__ADC_MULTI_MASTER_SLAVE__))) & ADC_CDR_RDATA_MST) -#endif - -/** - * @brief Helper macro to select the ADC common instance - * to which is belonging the selected ADC instance. - * @note ADC common register instance can be used for: - * - Set parameters common to several ADC instances - * - Multimode (for devices with several ADC instances) - * Refer to functions having argument "ADCxy_COMMON" as parameter. - * @param __ADCx__ ADC instance - * @retval ADC common register instance - */ -#if defined(ADC1) && defined(ADC2) && defined(ADC3) -#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ - (ADC123_COMMON) -#elif defined(ADC1) && defined(ADC2) -#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ - (ADC12_COMMON) -#else -#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ - (ADC1_COMMON) -#endif - -/** - * @brief Helper macro to check if all ADC instances sharing the same - * ADC common instance are disabled. - * @note This check is required by functions with setting conditioned to - * ADC state: - * All ADC instances of the ADC common group must be disabled. - * Refer to functions having argument "ADCxy_COMMON" as parameter. - * @note On devices with only 1 ADC common instance, parameter of this macro - * is useless and can be ignored (parameter kept for compatibility - * with devices featuring several ADC common instances). - * @param __ADCXY_COMMON__ ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Value "0" if all ADC instances sharing the same ADC common instance - * are disabled. - * Value "1" if at least one ADC instance sharing the same ADC common instance - * is enabled. - */ -#if defined(ADC1) && defined(ADC2) && defined(ADC3) -#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ - (LL_ADC_IsEnabled(ADC1) | \ - LL_ADC_IsEnabled(ADC2) | \ - LL_ADC_IsEnabled(ADC3) ) -#elif defined(ADC1) && defined(ADC2) -#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ - (LL_ADC_IsEnabled(ADC1) | \ - LL_ADC_IsEnabled(ADC2) ) -#else -#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ - (LL_ADC_IsEnabled(ADC1)) -#endif - -/** - * @brief Helper macro to define the ADC conversion data full-scale digital - * value corresponding to the selected ADC resolution. - * @note ADC conversion data full-scale corresponds to voltage range - * determined by analog voltage references Vref+ and Vref- - * (refer to reference manual). - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval ADC conversion data equivalent voltage value (unit: mVolt) - */ -#define __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__) \ - (0xFFFU >> ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL))) - -/** - * @brief Helper macro to convert the ADC conversion data from - * a resolution to another resolution. - * @param __DATA__ ADC conversion data to be converted - * @param __ADC_RESOLUTION_CURRENT__ Resolution of to the data to be converted - * This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @param __ADC_RESOLUTION_TARGET__ Resolution of the data after conversion - * This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval ADC conversion data to the requested resolution - */ -#define __LL_ADC_CONVERT_DATA_RESOLUTION(__DATA__, __ADC_RESOLUTION_CURRENT__, __ADC_RESOLUTION_TARGET__) \ - (((__DATA__) \ - << ((__ADC_RESOLUTION_CURRENT__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL))) \ - >> ((__ADC_RESOLUTION_TARGET__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL)) \ - ) - -/** - * @brief Helper macro to calculate the voltage (unit: mVolt) - * corresponding to a ADC conversion data (unit: digital value). - * @note Analog reference voltage (Vref+) must be either known from - * user board environment or can be calculated using ADC measurement - * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). - * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit mV) - * @param __ADC_DATA__ ADC conversion data (resolution 12 bits) - * (unit: digital value). - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval ADC conversion data equivalent voltage value (unit: mVolt) - */ -#define __LL_ADC_CALC_DATA_TO_VOLTAGE(__VREFANALOG_VOLTAGE__,\ - __ADC_DATA__,\ - __ADC_RESOLUTION__) \ - ((__ADC_DATA__) * (__VREFANALOG_VOLTAGE__) \ - / __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__) \ - ) - -/** - * @brief Helper macro to calculate analog reference voltage (Vref+) - * (unit: mVolt) from ADC conversion data of internal voltage - * reference VrefInt. - * @note Computation is using VrefInt calibration value - * stored in system memory for each device during production. - * @note This voltage depends on user board environment: voltage level - * connected to pin Vref+. - * On devices with small package, the pin Vref+ is not present - * and internally bonded to pin Vdda. - * @note On this STM32 series, calibration data of internal voltage reference - * VrefInt corresponds to a resolution of 12 bits, - * this is the recommended ADC resolution to convert voltage of - * internal voltage reference VrefInt. - * Otherwise, this macro performs the processing to scale - * ADC conversion data to 12 bits. - * @param __VREFINT_ADC_DATA__ ADC conversion data (resolution 12 bits) - * of internal voltage reference VrefInt (unit: digital value). - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval Analog reference voltage (unit: mV) - */ -#define __LL_ADC_CALC_VREFANALOG_VOLTAGE(__VREFINT_ADC_DATA__,\ - __ADC_RESOLUTION__) \ - (((uint32_t)(*VREFINT_CAL_ADDR) * VREFINT_CAL_VREF) \ - / __LL_ADC_CONVERT_DATA_RESOLUTION((__VREFINT_ADC_DATA__), \ - (__ADC_RESOLUTION__), \ - LL_ADC_RESOLUTION_12B)) - -/* Note: On device STM32F4x9, calibration parameter TS_CAL2 is not available. */ -/* Therefore, helper macro __LL_ADC_CALC_TEMPERATURE() is not available.*/ -/* Use helper macro @ref __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(). */ -#if !defined(STM32F469) && !defined(STM32F479xx) && !defined(STM32F429xx) && !defined(STM32F439xx) -/** - * @brief Helper macro to calculate the temperature (unit: degree Celsius) - * from ADC conversion data of internal temperature sensor. - * @note Computation is using temperature sensor calibration values - * stored in system memory for each device during production. - * @note Calculation formula: - * Temperature = ((TS_ADC_DATA - TS_CAL1) - * * (TS_CAL2_TEMP - TS_CAL1_TEMP)) - * / (TS_CAL2 - TS_CAL1) + TS_CAL1_TEMP - * with TS_ADC_DATA = temperature sensor raw data measured by ADC - * Avg_Slope = (TS_CAL2 - TS_CAL1) - * / (TS_CAL2_TEMP - TS_CAL1_TEMP) - * TS_CAL1 = equivalent TS_ADC_DATA at temperature - * TEMP_DEGC_CAL1 (calibrated in factory) - * TS_CAL2 = equivalent TS_ADC_DATA at temperature - * TEMP_DEGC_CAL2 (calibrated in factory) - * Caution: Calculation relevancy under reserve that calibration - * parameters are correct (address and data). - * To calculate temperature using temperature sensor - * datasheet typical values (generic values less, therefore - * less accurate than calibrated values), - * use helper macro @ref __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(). - * @note As calculation input, the analog reference voltage (Vref+) must be - * defined as it impacts the ADC LSB equivalent voltage. - * @note Analog reference voltage (Vref+) must be either known from - * user board environment or can be calculated using ADC measurement - * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). - * @note On this STM32 series, calibration data of temperature sensor - * corresponds to a resolution of 12 bits, - * this is the recommended ADC resolution to convert voltage of - * temperature sensor. - * Otherwise, this macro performs the processing to scale - * ADC conversion data to 12 bits. - * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit mV) - * @param __TEMPSENSOR_ADC_DATA__ ADC conversion data of internal - * temperature sensor (unit: digital value). - * @param __ADC_RESOLUTION__ ADC resolution at which internal temperature - * sensor voltage has been measured. - * This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval Temperature (unit: degree Celsius) - */ -#define __LL_ADC_CALC_TEMPERATURE(__VREFANALOG_VOLTAGE__,\ - __TEMPSENSOR_ADC_DATA__,\ - __ADC_RESOLUTION__) \ - (((( ((int32_t)((__LL_ADC_CONVERT_DATA_RESOLUTION((__TEMPSENSOR_ADC_DATA__), \ - (__ADC_RESOLUTION__), \ - LL_ADC_RESOLUTION_12B) \ - * (__VREFANALOG_VOLTAGE__)) \ - / TEMPSENSOR_CAL_VREFANALOG) \ - - (int32_t) *TEMPSENSOR_CAL1_ADDR) \ - ) * (int32_t)(TEMPSENSOR_CAL2_TEMP - TEMPSENSOR_CAL1_TEMP) \ - ) / (int32_t)((int32_t)*TEMPSENSOR_CAL2_ADDR - (int32_t)*TEMPSENSOR_CAL1_ADDR) \ - ) + TEMPSENSOR_CAL1_TEMP \ - ) -#endif - -/** - * @brief Helper macro to calculate the temperature (unit: degree Celsius) - * from ADC conversion data of internal temperature sensor. - * @note Computation is using temperature sensor typical values - * (refer to device datasheet). - * @note Calculation formula: - * Temperature = (TS_TYP_CALx_VOLT(uV) - TS_ADC_DATA * Conversion_uV) - * / Avg_Slope + CALx_TEMP - * with TS_ADC_DATA = temperature sensor raw data measured by ADC - * (unit: digital value) - * Avg_Slope = temperature sensor slope - * (unit: uV/Degree Celsius) - * TS_TYP_CALx_VOLT = temperature sensor digital value at - * temperature CALx_TEMP (unit: mV) - * Caution: Calculation relevancy under reserve the temperature sensor - * of the current device has characteristics in line with - * datasheet typical values. - * If temperature sensor calibration values are available on - * on this device (presence of macro __LL_ADC_CALC_TEMPERATURE()), - * temperature calculation will be more accurate using - * helper macro @ref __LL_ADC_CALC_TEMPERATURE(). - * @note As calculation input, the analog reference voltage (Vref+) must be - * defined as it impacts the ADC LSB equivalent voltage. - * @note Analog reference voltage (Vref+) must be either known from - * user board environment or can be calculated using ADC measurement - * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). - * @note ADC measurement data must correspond to a resolution of 12bits - * (full scale digital value 4095). If not the case, the data must be - * preliminarily rescaled to an equivalent resolution of 12 bits. - * @param __TEMPSENSOR_TYP_AVGSLOPE__ Device datasheet data Temperature sensor slope typical value (unit uV/DegCelsius). - * On STM32F4, refer to device datasheet parameter "Avg_Slope". - * @param __TEMPSENSOR_TYP_CALX_V__ Device datasheet data Temperature sensor voltage typical value (at temperature and Vref+ defined in parameters below) (unit mV). - * On STM32F4, refer to device datasheet parameter "V25". - * @param __TEMPSENSOR_CALX_TEMP__ Device datasheet data Temperature at which temperature sensor voltage (see parameter above) is corresponding (unit mV) - * @param __VREFANALOG_VOLTAGE__ Analog voltage reference (Vref+) voltage (unit mV) - * @param __TEMPSENSOR_ADC_DATA__ ADC conversion data of internal temperature sensor (unit digital value). - * @param __ADC_RESOLUTION__ ADC resolution at which internal temperature sensor voltage has been measured. - * This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval Temperature (unit: degree Celsius) - */ -#define __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(__TEMPSENSOR_TYP_AVGSLOPE__,\ - __TEMPSENSOR_TYP_CALX_V__,\ - __TEMPSENSOR_CALX_TEMP__,\ - __VREFANALOG_VOLTAGE__,\ - __TEMPSENSOR_ADC_DATA__,\ - __ADC_RESOLUTION__) \ - ((( ( \ - (int32_t)(((__TEMPSENSOR_TYP_CALX_V__)) \ - * 1000) \ - - \ - (int32_t)((((__TEMPSENSOR_ADC_DATA__) * (__VREFANALOG_VOLTAGE__)) \ - / __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__)) \ - * 1000) \ - ) \ - ) / (__TEMPSENSOR_TYP_AVGSLOPE__) \ - ) + (__TEMPSENSOR_CALX_TEMP__) \ - ) - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup ADC_LL_Exported_Functions ADC Exported Functions - * @{ - */ - -/** @defgroup ADC_LL_EF_DMA_Management ADC DMA management - * @{ - */ -/* Note: LL ADC functions to set DMA transfer are located into sections of */ -/* configuration of ADC instance, groups and multimode (if available): */ -/* @ref LL_ADC_REG_SetDMATransfer(), ... */ - -/** - * @brief Function to help to configure DMA transfer from ADC: retrieve the - * ADC register address from ADC instance and a list of ADC registers - * intended to be used (most commonly) with DMA transfer. - * @note These ADC registers are data registers: - * when ADC conversion data is available in ADC data registers, - * ADC generates a DMA transfer request. - * @note This macro is intended to be used with LL DMA driver, refer to - * function "LL_DMA_ConfigAddresses()". - * Example: - * LL_DMA_ConfigAddresses(DMA1, - * LL_DMA_CHANNEL_1, - * LL_ADC_DMA_GetRegAddr(ADC1, LL_ADC_DMA_REG_REGULAR_DATA), - * (uint32_t)&< array or variable >, - * LL_DMA_DIRECTION_PERIPH_TO_MEMORY); - * @note For devices with several ADC: in multimode, some devices - * use a different data register outside of ADC instance scope - * (common data register). This macro manages this register difference, - * only ADC instance has to be set as parameter. - * @rmtoll DR RDATA LL_ADC_DMA_GetRegAddr\n - * CDR RDATA_MST LL_ADC_DMA_GetRegAddr\n - * CDR RDATA_SLV LL_ADC_DMA_GetRegAddr - * @param ADCx ADC instance - * @param Register This parameter can be one of the following values: - * @arg @ref LL_ADC_DMA_REG_REGULAR_DATA - * @arg @ref LL_ADC_DMA_REG_REGULAR_DATA_MULTI (1) - * - * (1) Available on devices with several ADC instances. - * @retval ADC register address - */ -#if defined(ADC_MULTIMODE_SUPPORT) -__STATIC_INLINE uint32_t LL_ADC_DMA_GetRegAddr(ADC_TypeDef *ADCx, uint32_t Register) -{ - uint32_t data_reg_addr = 0UL; - UNUSED(Register); - - if (Register == LL_ADC_DMA_REG_REGULAR_DATA) - { - /* Retrieve address of register DR */ - data_reg_addr = (uint32_t)&(ADCx->DR); - } - else /* (Register == LL_ADC_DMA_REG_REGULAR_DATA_MULTI) */ - { - /* Retrieve address of register CDR */ - data_reg_addr = (uint32_t)&((__LL_ADC_COMMON_INSTANCE(ADCx))->CDR); - } - - return data_reg_addr; -} -#else -__STATIC_INLINE uint32_t LL_ADC_DMA_GetRegAddr(ADC_TypeDef *ADCx, uint32_t Register) -{ - UNUSED(Register); - /* Retrieve address of register DR */ - return (uint32_t)&(ADCx->DR); -} -#endif - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Common Configuration of ADC hierarchical scope: common to several ADC instances - * @{ - */ - -/** - * @brief Set parameter common to several ADC: Clock source and prescaler. - * @rmtoll CCR ADCPRE LL_ADC_SetCommonClock - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param CommonClock This parameter can be one of the following values: - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV2 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV4 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV6 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV8 - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetCommonClock(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t CommonClock) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_ADCPRE, CommonClock); -} - -/** - * @brief Get parameter common to several ADC: Clock source and prescaler. - * @rmtoll CCR ADCPRE LL_ADC_GetCommonClock - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV2 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV4 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV6 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV8 - */ -__STATIC_INLINE uint32_t LL_ADC_GetCommonClock(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_ADCPRE)); -} - -/** - * @brief Set parameter common to several ADC: measurement path to internal - * channels (VrefInt, temperature sensor, ...). - * @note One or several values can be selected. - * Example: (LL_ADC_PATH_INTERNAL_VREFINT | - * LL_ADC_PATH_INTERNAL_TEMPSENSOR) - * @note Stabilization time of measurement path to internal channel: - * After enabling internal paths, before starting ADC conversion, - * a delay is required for internal voltage reference and - * temperature sensor stabilization time. - * Refer to device datasheet. - * Refer to literal @ref LL_ADC_DELAY_VREFINT_STAB_US. - * Refer to literal @ref LL_ADC_DELAY_TEMPSENSOR_STAB_US. - * @note ADC internal channel sampling time constraint: - * For ADC conversion of internal channels, - * a sampling time minimum value is required. - * Refer to device datasheet. - * @rmtoll CCR TSVREFE LL_ADC_SetCommonPathInternalCh\n - * CCR VBATE LL_ADC_SetCommonPathInternalCh - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param PathInternal This parameter can be a combination of the following values: - * @arg @ref LL_ADC_PATH_INTERNAL_NONE - * @arg @ref LL_ADC_PATH_INTERNAL_VREFINT - * @arg @ref LL_ADC_PATH_INTERNAL_TEMPSENSOR - * @arg @ref LL_ADC_PATH_INTERNAL_VBAT - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetCommonPathInternalCh(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t PathInternal) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_TSVREFE | ADC_CCR_VBATE, PathInternal); -} - -/** - * @brief Get parameter common to several ADC: measurement path to internal - * channels (VrefInt, temperature sensor, ...). - * @note One or several values can be selected. - * Example: (LL_ADC_PATH_INTERNAL_VREFINT | - * LL_ADC_PATH_INTERNAL_TEMPSENSOR) - * @rmtoll CCR TSVREFE LL_ADC_GetCommonPathInternalCh\n - * CCR VBATE LL_ADC_GetCommonPathInternalCh - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be a combination of the following values: - * @arg @ref LL_ADC_PATH_INTERNAL_NONE - * @arg @ref LL_ADC_PATH_INTERNAL_VREFINT - * @arg @ref LL_ADC_PATH_INTERNAL_TEMPSENSOR - * @arg @ref LL_ADC_PATH_INTERNAL_VBAT - */ -__STATIC_INLINE uint32_t LL_ADC_GetCommonPathInternalCh(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_TSVREFE | ADC_CCR_VBATE)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Instance Configuration of ADC hierarchical scope: ADC instance - * @{ - */ - -/** - * @brief Set ADC resolution. - * Refer to reference manual for alignments formats - * dependencies to ADC resolutions. - * @rmtoll CR1 RES LL_ADC_SetResolution - * @param ADCx ADC instance - * @param Resolution This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetResolution(ADC_TypeDef *ADCx, uint32_t Resolution) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_RES, Resolution); -} - -/** - * @brief Get ADC resolution. - * Refer to reference manual for alignments formats - * dependencies to ADC resolutions. - * @rmtoll CR1 RES LL_ADC_GetResolution - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - */ -__STATIC_INLINE uint32_t LL_ADC_GetResolution(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_RES)); -} - -/** - * @brief Set ADC conversion data alignment. - * @note Refer to reference manual for alignments formats - * dependencies to ADC resolutions. - * @rmtoll CR2 ALIGN LL_ADC_SetDataAlignment - * @param ADCx ADC instance - * @param DataAlignment This parameter can be one of the following values: - * @arg @ref LL_ADC_DATA_ALIGN_RIGHT - * @arg @ref LL_ADC_DATA_ALIGN_LEFT - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetDataAlignment(ADC_TypeDef *ADCx, uint32_t DataAlignment) -{ - MODIFY_REG(ADCx->CR2, ADC_CR2_ALIGN, DataAlignment); -} - -/** - * @brief Get ADC conversion data alignment. - * @note Refer to reference manual for alignments formats - * dependencies to ADC resolutions. - * @rmtoll CR2 ALIGN LL_ADC_SetDataAlignment - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_DATA_ALIGN_RIGHT - * @arg @ref LL_ADC_DATA_ALIGN_LEFT - */ -__STATIC_INLINE uint32_t LL_ADC_GetDataAlignment(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_ALIGN)); -} - -/** - * @brief Set ADC sequencers scan mode, for all ADC groups - * (group regular, group injected). - * @note According to sequencers scan mode : - * - If disabled: ADC conversion is performed in unitary conversion - * mode (one channel converted, that defined in rank 1). - * Configuration of sequencers of all ADC groups - * (sequencer scan length, ...) is discarded: equivalent to - * scan length of 1 rank. - * - If enabled: ADC conversions are performed in sequence conversions - * mode, according to configuration of sequencers of - * each ADC group (sequencer scan length, ...). - * Refer to function @ref LL_ADC_REG_SetSequencerLength() - * and to function @ref LL_ADC_INJ_SetSequencerLength(). - * @rmtoll CR1 SCAN LL_ADC_SetSequencersScanMode - * @param ADCx ADC instance - * @param ScanMode This parameter can be one of the following values: - * @arg @ref LL_ADC_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_SEQ_SCAN_ENABLE - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetSequencersScanMode(ADC_TypeDef *ADCx, uint32_t ScanMode) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_SCAN, ScanMode); -} - -/** - * @brief Get ADC sequencers scan mode, for all ADC groups - * (group regular, group injected). - * @note According to sequencers scan mode : - * - If disabled: ADC conversion is performed in unitary conversion - * mode (one channel converted, that defined in rank 1). - * Configuration of sequencers of all ADC groups - * (sequencer scan length, ...) is discarded: equivalent to - * scan length of 1 rank. - * - If enabled: ADC conversions are performed in sequence conversions - * mode, according to configuration of sequencers of - * each ADC group (sequencer scan length, ...). - * Refer to function @ref LL_ADC_REG_SetSequencerLength() - * and to function @ref LL_ADC_INJ_SetSequencerLength(). - * @rmtoll CR1 SCAN LL_ADC_GetSequencersScanMode - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_SEQ_SCAN_ENABLE - */ -__STATIC_INLINE uint32_t LL_ADC_GetSequencersScanMode(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_SCAN)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Group_Regular Configuration of ADC hierarchical scope: group regular - * @{ - */ - -/** - * @brief Set ADC group regular conversion trigger source: - * internal (SW start) or from external IP (timer event, - * external interrupt line). - * @note On this STM32 series, setting of external trigger edge is performed - * using function @ref LL_ADC_REG_StartConversionExtTrig(). - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR2 EXTSEL LL_ADC_REG_SetTriggerSource\n - * CR2 EXTEN LL_ADC_REG_SetTriggerSource - * @param ADCx ADC instance - * @param TriggerSource This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_TRIG_SOFTWARE - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH4 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM4_CH4 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_EXTI_LINE11 - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetTriggerSource(ADC_TypeDef *ADCx, uint32_t TriggerSource) -{ -/* Note: On this STM32 series, ADC group regular external trigger edge */ -/* is used to perform a ADC conversion start. */ -/* This function does not set external trigger edge. */ -/* This feature is set using function */ -/* @ref LL_ADC_REG_StartConversionExtTrig(). */ - MODIFY_REG(ADCx->CR2, ADC_CR2_EXTSEL, (TriggerSource & ADC_CR2_EXTSEL)); -} - -/** - * @brief Get ADC group regular conversion trigger source: - * internal (SW start) or from external IP (timer event, - * external interrupt line). - * @note To determine whether group regular trigger source is - * internal (SW start) or external, without detail - * of which peripheral is selected as external trigger, - * (equivalent to - * "if(LL_ADC_REG_GetTriggerSource(ADC1) == LL_ADC_REG_TRIG_SOFTWARE)") - * use function @ref LL_ADC_REG_IsTriggerSourceSWStart. - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR2 EXTSEL LL_ADC_REG_GetTriggerSource\n - * CR2 EXTEN LL_ADC_REG_GetTriggerSource - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_TRIG_SOFTWARE - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH4 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM4_CH4 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_EXTI_LINE11 - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetTriggerSource(ADC_TypeDef *ADCx) -{ - uint32_t TriggerSource = READ_BIT(ADCx->CR2, ADC_CR2_EXTSEL | ADC_CR2_EXTEN); - - /* Value for shift of {0; 4; 8; 12} depending on value of bitfield */ - /* corresponding to ADC_CR2_EXTEN {0; 1; 2; 3}. */ - uint32_t ShiftExten = ((TriggerSource & ADC_CR2_EXTEN) >> (ADC_REG_TRIG_EXTEN_BITOFFSET_POS - 2UL)); - - /* Set bitfield corresponding to ADC_CR2_EXTEN and ADC_CR2_EXTSEL */ - /* to match with triggers literals definition. */ - return ((TriggerSource - & (ADC_REG_TRIG_SOURCE_MASK << ShiftExten) & ADC_CR2_EXTSEL) - | ((ADC_REG_TRIG_EDGE_MASK << ShiftExten) & ADC_CR2_EXTEN) - ); -} - -/** - * @brief Get ADC group regular conversion trigger source internal (SW start) - or external. - * @note In case of group regular trigger source set to external trigger, - * to determine which peripheral is selected as external trigger, - * use function @ref LL_ADC_REG_GetTriggerSource(). - * @rmtoll CR2 EXTEN LL_ADC_REG_IsTriggerSourceSWStart - * @param ADCx ADC instance - * @retval Value "0" if trigger source external trigger - * Value "1" if trigger source SW start. - */ -__STATIC_INLINE uint32_t LL_ADC_REG_IsTriggerSourceSWStart(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR2, ADC_CR2_EXTEN) == (LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTEN)); -} - -/** - * @brief Get ADC group regular conversion trigger polarity. - * @note Applicable only for trigger source set to external trigger. - * @note On this STM32 series, setting of external trigger edge is performed - * using function @ref LL_ADC_REG_StartConversionExtTrig(). - * @rmtoll CR2 EXTEN LL_ADC_REG_GetTriggerEdge - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_TRIG_EXT_RISING - * @arg @ref LL_ADC_REG_TRIG_EXT_FALLING - * @arg @ref LL_ADC_REG_TRIG_EXT_RISINGFALLING - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetTriggerEdge(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_EXTEN)); -} - - -/** - * @brief Set ADC group regular sequencer length and scan direction. - * @note Description of ADC group regular sequencer features: - * - For devices with sequencer fully configurable - * (function "LL_ADC_REG_SetSequencerRanks()" available): - * sequencer length and each rank affectation to a channel - * are configurable. - * This function performs configuration of: - * - Sequence length: Number of ranks in the scan sequence. - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from rank 1 to rank n). - * Sequencer ranks are selected using - * function "LL_ADC_REG_SetSequencerRanks()". - * - For devices with sequencer not fully configurable - * (function "LL_ADC_REG_SetSequencerChannels()" available): - * sequencer length and each rank affectation to a channel - * are defined by channel number. - * This function performs configuration of: - * - Sequence length: Number of ranks in the scan sequence is - * defined by number of channels set in the sequence, - * rank of each channel is fixed by channel HW number. - * (channel 0 fixed on rank 0, channel 1 fixed on rank1, ...). - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from lowest channel number to - * highest channel number). - * Sequencer ranks are selected using - * function "LL_ADC_REG_SetSequencerChannels()". - * @note On this STM32 series, group regular sequencer configuration - * is conditioned to ADC instance sequencer mode. - * If ADC instance sequencer mode is disabled, sequencers of - * all groups (group regular, group injected) can be configured - * but their execution is disabled (limited to rank 1). - * Refer to function @ref LL_ADC_SetSequencersScanMode(). - * @note Sequencer disabled is equivalent to sequencer of 1 rank: - * ADC conversion on only 1 channel. - * @rmtoll SQR1 L LL_ADC_REG_SetSequencerLength - * @param ADCx ADC instance - * @param SequencerNbRanks This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetSequencerLength(ADC_TypeDef *ADCx, uint32_t SequencerNbRanks) -{ - MODIFY_REG(ADCx->SQR1, ADC_SQR1_L, SequencerNbRanks); -} - -/** - * @brief Get ADC group regular sequencer length and scan direction. - * @note Description of ADC group regular sequencer features: - * - For devices with sequencer fully configurable - * (function "LL_ADC_REG_SetSequencerRanks()" available): - * sequencer length and each rank affectation to a channel - * are configurable. - * This function retrieves: - * - Sequence length: Number of ranks in the scan sequence. - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from rank 1 to rank n). - * Sequencer ranks are selected using - * function "LL_ADC_REG_SetSequencerRanks()". - * - For devices with sequencer not fully configurable - * (function "LL_ADC_REG_SetSequencerChannels()" available): - * sequencer length and each rank affectation to a channel - * are defined by channel number. - * This function retrieves: - * - Sequence length: Number of ranks in the scan sequence is - * defined by number of channels set in the sequence, - * rank of each channel is fixed by channel HW number. - * (channel 0 fixed on rank 0, channel 1 fixed on rank1, ...). - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from lowest channel number to - * highest channel number). - * Sequencer ranks are selected using - * function "LL_ADC_REG_SetSequencerChannels()". - * @note On this STM32 series, group regular sequencer configuration - * is conditioned to ADC instance sequencer mode. - * If ADC instance sequencer mode is disabled, sequencers of - * all groups (group regular, group injected) can be configured - * but their execution is disabled (limited to rank 1). - * Refer to function @ref LL_ADC_SetSequencersScanMode(). - * @note Sequencer disabled is equivalent to sequencer of 1 rank: - * ADC conversion on only 1 channel. - * @rmtoll SQR1 L LL_ADC_REG_SetSequencerLength - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerLength(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->SQR1, ADC_SQR1_L)); -} - -/** - * @brief Set ADC group regular sequencer discontinuous mode: - * sequence subdivided and scan conversions interrupted every selected - * number of ranks. - * @note It is not possible to enable both ADC group regular - * continuous mode and sequencer discontinuous mode. - * @note It is not possible to enable both ADC auto-injected mode - * and ADC group regular sequencer discontinuous mode. - * @rmtoll CR1 DISCEN LL_ADC_REG_SetSequencerDiscont\n - * CR1 DISCNUM LL_ADC_REG_SetSequencerDiscont - * @param ADCx ADC instance - * @param SeqDiscont This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_SEQ_DISCONT_DISABLE - * @arg @ref LL_ADC_REG_SEQ_DISCONT_1RANK - * @arg @ref LL_ADC_REG_SEQ_DISCONT_2RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_3RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_4RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_5RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_6RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_7RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_8RANKS - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetSequencerDiscont(ADC_TypeDef *ADCx, uint32_t SeqDiscont) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_DISCEN | ADC_CR1_DISCNUM, SeqDiscont); -} - -/** - * @brief Get ADC group regular sequencer discontinuous mode: - * sequence subdivided and scan conversions interrupted every selected - * number of ranks. - * @rmtoll CR1 DISCEN LL_ADC_REG_GetSequencerDiscont\n - * CR1 DISCNUM LL_ADC_REG_GetSequencerDiscont - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_SEQ_DISCONT_DISABLE - * @arg @ref LL_ADC_REG_SEQ_DISCONT_1RANK - * @arg @ref LL_ADC_REG_SEQ_DISCONT_2RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_3RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_4RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_5RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_6RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_7RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_8RANKS - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerDiscont(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_DISCEN | ADC_CR1_DISCNUM)); -} - -/** - * @brief Set ADC group regular sequence: channel on the selected - * scan sequence rank. - * @note This function performs configuration of: - * - Channels ordering into each rank of scan sequence: - * whatever channel can be placed into whatever rank. - * @note On this STM32 series, ADC group regular sequencer is - * fully configurable: sequencer length and each rank - * affectation to a channel are configurable. - * Refer to description of function @ref LL_ADC_REG_SetSequencerLength(). - * @note Depending on devices and packages, some channels may not be available. - * Refer to device datasheet for channels availability. - * @note On this STM32 series, to measure internal channels (VrefInt, - * TempSensor, ...), measurement paths to internal channels must be - * enabled separately. - * This can be done using function @ref LL_ADC_SetCommonPathInternalCh(). - * @rmtoll SQR3 SQ1 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ2 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ3 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ4 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ5 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ6 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ7 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ8 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ9 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ10 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ11 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ12 LL_ADC_REG_SetSequencerRanks\n - * SQR1 SQ13 LL_ADC_REG_SetSequencerRanks\n - * SQR1 SQ14 LL_ADC_REG_SetSequencerRanks\n - * SQR1 SQ15 LL_ADC_REG_SetSequencerRanks\n - * SQR1 SQ16 LL_ADC_REG_SetSequencerRanks - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_RANK_1 - * @arg @ref LL_ADC_REG_RANK_2 - * @arg @ref LL_ADC_REG_RANK_3 - * @arg @ref LL_ADC_REG_RANK_4 - * @arg @ref LL_ADC_REG_RANK_5 - * @arg @ref LL_ADC_REG_RANK_6 - * @arg @ref LL_ADC_REG_RANK_7 - * @arg @ref LL_ADC_REG_RANK_8 - * @arg @ref LL_ADC_REG_RANK_9 - * @arg @ref LL_ADC_REG_RANK_10 - * @arg @ref LL_ADC_REG_RANK_11 - * @arg @ref LL_ADC_REG_RANK_12 - * @arg @ref LL_ADC_REG_RANK_13 - * @arg @ref LL_ADC_REG_RANK_14 - * @arg @ref LL_ADC_REG_RANK_15 - * @arg @ref LL_ADC_REG_RANK_16 - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t Channel) -{ - /* Set bits with content of parameter "Channel" with bits position */ - /* in register and register position depending on parameter "Rank". */ - /* Parameters "Rank" and "Channel" are used with masks because containing */ - /* other bits reserved for other purpose. */ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SQR1, __ADC_MASK_SHIFT(Rank, ADC_REG_SQRX_REGOFFSET_MASK)); - - MODIFY_REG(*preg, - ADC_CHANNEL_ID_NUMBER_MASK << (Rank & ADC_REG_RANK_ID_SQRX_MASK), - (Channel & ADC_CHANNEL_ID_NUMBER_MASK) << (Rank & ADC_REG_RANK_ID_SQRX_MASK)); -} - -/** - * @brief Get ADC group regular sequence: channel on the selected - * scan sequence rank. - * @note On this STM32 series, ADC group regular sequencer is - * fully configurable: sequencer length and each rank - * affectation to a channel are configurable. - * Refer to description of function @ref LL_ADC_REG_SetSequencerLength(). - * @note Depending on devices and packages, some channels may not be available. - * Refer to device datasheet for channels availability. - * @note Usage of the returned channel number: - * - To reinject this channel into another function LL_ADC_xxx: - * the returned channel number is only partly formatted on definition - * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared - * with parts of literals LL_ADC_CHANNEL_x or using - * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * Then the selected literal LL_ADC_CHANNEL_x can be used - * as parameter for another function. - * - To get the channel number in decimal format: - * process the returned value with the helper macro - * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * @rmtoll SQR3 SQ1 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ2 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ3 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ4 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ5 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ6 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ7 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ8 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ9 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ10 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ11 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ12 LL_ADC_REG_GetSequencerRanks\n - * SQR1 SQ13 LL_ADC_REG_GetSequencerRanks\n - * SQR1 SQ14 LL_ADC_REG_GetSequencerRanks\n - * SQR1 SQ15 LL_ADC_REG_GetSequencerRanks\n - * SQR1 SQ16 LL_ADC_REG_GetSequencerRanks - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_RANK_1 - * @arg @ref LL_ADC_REG_RANK_2 - * @arg @ref LL_ADC_REG_RANK_3 - * @arg @ref LL_ADC_REG_RANK_4 - * @arg @ref LL_ADC_REG_RANK_5 - * @arg @ref LL_ADC_REG_RANK_6 - * @arg @ref LL_ADC_REG_RANK_7 - * @arg @ref LL_ADC_REG_RANK_8 - * @arg @ref LL_ADC_REG_RANK_9 - * @arg @ref LL_ADC_REG_RANK_10 - * @arg @ref LL_ADC_REG_RANK_11 - * @arg @ref LL_ADC_REG_RANK_12 - * @arg @ref LL_ADC_REG_RANK_13 - * @arg @ref LL_ADC_REG_RANK_14 - * @arg @ref LL_ADC_REG_RANK_15 - * @arg @ref LL_ADC_REG_RANK_16 - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n - * (1) For ADC channel read back from ADC register, - * comparison with internal channel parameter to be done - * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SQR1, __ADC_MASK_SHIFT(Rank, ADC_REG_SQRX_REGOFFSET_MASK)); - - return (uint32_t) (READ_BIT(*preg, - ADC_CHANNEL_ID_NUMBER_MASK << (Rank & ADC_REG_RANK_ID_SQRX_MASK)) - >> (Rank & ADC_REG_RANK_ID_SQRX_MASK) - ); -} - -/** - * @brief Set ADC continuous conversion mode on ADC group regular. - * @note Description of ADC continuous conversion mode: - * - single mode: one conversion per trigger - * - continuous mode: after the first trigger, following - * conversions launched successively automatically. - * @note It is not possible to enable both ADC group regular - * continuous mode and sequencer discontinuous mode. - * @rmtoll CR2 CONT LL_ADC_REG_SetContinuousMode - * @param ADCx ADC instance - * @param Continuous This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_CONV_SINGLE - * @arg @ref LL_ADC_REG_CONV_CONTINUOUS - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetContinuousMode(ADC_TypeDef *ADCx, uint32_t Continuous) -{ - MODIFY_REG(ADCx->CR2, ADC_CR2_CONT, Continuous); -} - -/** - * @brief Get ADC continuous conversion mode on ADC group regular. - * @note Description of ADC continuous conversion mode: - * - single mode: one conversion per trigger - * - continuous mode: after the first trigger, following - * conversions launched successively automatically. - * @rmtoll CR2 CONT LL_ADC_REG_GetContinuousMode - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_CONV_SINGLE - * @arg @ref LL_ADC_REG_CONV_CONTINUOUS - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetContinuousMode(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_CONT)); -} - -/** - * @brief Set ADC group regular conversion data transfer: no transfer or - * transfer by DMA, and DMA requests mode. - * @note If transfer by DMA selected, specifies the DMA requests - * mode: - * - Limited mode (One shot mode): DMA transfer requests are stopped - * when number of DMA data transfers (number of - * ADC conversions) is reached. - * This ADC mode is intended to be used with DMA mode non-circular. - * - Unlimited mode: DMA transfer requests are unlimited, - * whatever number of DMA data transfers (number of - * ADC conversions). - * This ADC mode is intended to be used with DMA mode circular. - * @note If ADC DMA requests mode is set to unlimited and DMA is set to - * mode non-circular: - * when DMA transfers size will be reached, DMA will stop transfers of - * ADC conversions data ADC will raise an overrun error - * (overrun flag and interruption if enabled). - * @note For devices with several ADC instances: ADC multimode DMA - * settings are available using function @ref LL_ADC_SetMultiDMATransfer(). - * @note To configure DMA source address (peripheral address), - * use function @ref LL_ADC_DMA_GetRegAddr(). - * @rmtoll CR2 DMA LL_ADC_REG_SetDMATransfer\n - * CR2 DDS LL_ADC_REG_SetDMATransfer - * @param ADCx ADC instance - * @param DMATransfer This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_DMA_TRANSFER_NONE - * @arg @ref LL_ADC_REG_DMA_TRANSFER_LIMITED - * @arg @ref LL_ADC_REG_DMA_TRANSFER_UNLIMITED - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetDMATransfer(ADC_TypeDef *ADCx, uint32_t DMATransfer) -{ - MODIFY_REG(ADCx->CR2, ADC_CR2_DMA | ADC_CR2_DDS, DMATransfer); -} - -/** - * @brief Get ADC group regular conversion data transfer: no transfer or - * transfer by DMA, and DMA requests mode. - * @note If transfer by DMA selected, specifies the DMA requests - * mode: - * - Limited mode (One shot mode): DMA transfer requests are stopped - * when number of DMA data transfers (number of - * ADC conversions) is reached. - * This ADC mode is intended to be used with DMA mode non-circular. - * - Unlimited mode: DMA transfer requests are unlimited, - * whatever number of DMA data transfers (number of - * ADC conversions). - * This ADC mode is intended to be used with DMA mode circular. - * @note If ADC DMA requests mode is set to unlimited and DMA is set to - * mode non-circular: - * when DMA transfers size will be reached, DMA will stop transfers of - * ADC conversions data ADC will raise an overrun error - * (overrun flag and interruption if enabled). - * @note For devices with several ADC instances: ADC multimode DMA - * settings are available using function @ref LL_ADC_GetMultiDMATransfer(). - * @note To configure DMA source address (peripheral address), - * use function @ref LL_ADC_DMA_GetRegAddr(). - * @rmtoll CR2 DMA LL_ADC_REG_GetDMATransfer\n - * CR2 DDS LL_ADC_REG_GetDMATransfer - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_DMA_TRANSFER_NONE - * @arg @ref LL_ADC_REG_DMA_TRANSFER_LIMITED - * @arg @ref LL_ADC_REG_DMA_TRANSFER_UNLIMITED - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetDMATransfer(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_DMA | ADC_CR2_DDS)); -} - -/** - * @brief Specify which ADC flag between EOC (end of unitary conversion) - * or EOS (end of sequence conversions) is used to indicate - * the end of conversion. - * @note This feature is aimed to be set when using ADC with - * programming model by polling or interruption - * (programming model by DMA usually uses DMA interruptions - * to indicate end of conversion and data transfer). - * @note For ADC group injected, end of conversion (flag&IT) is raised - * only at the end of the sequence. - * @rmtoll CR2 EOCS LL_ADC_REG_SetFlagEndOfConversion - * @param ADCx ADC instance - * @param EocSelection This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV - * @arg @ref LL_ADC_REG_FLAG_EOC_UNITARY_CONV - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetFlagEndOfConversion(ADC_TypeDef *ADCx, uint32_t EocSelection) -{ - MODIFY_REG(ADCx->CR2, ADC_CR2_EOCS, EocSelection); -} - -/** - * @brief Get which ADC flag between EOC (end of unitary conversion) - * or EOS (end of sequence conversions) is used to indicate - * the end of conversion. - * @rmtoll CR2 EOCS LL_ADC_REG_GetFlagEndOfConversion - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV - * @arg @ref LL_ADC_REG_FLAG_EOC_UNITARY_CONV - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetFlagEndOfConversion(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_EOCS)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Group_Injected Configuration of ADC hierarchical scope: group injected - * @{ - */ - -/** - * @brief Set ADC group injected conversion trigger source: - * internal (SW start) or from external IP (timer event, - * external interrupt line). - * @note On this STM32 series, setting of external trigger edge is performed - * using function @ref LL_ADC_INJ_StartConversionExtTrig(). - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR2 JEXTSEL LL_ADC_INJ_SetTriggerSource\n - * CR2 JEXTEN LL_ADC_INJ_SetTriggerSource - * @param ADCx ADC instance - * @param TriggerSource This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_SOFTWARE - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_CH1 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH1 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH3 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH3 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetTriggerSource(ADC_TypeDef *ADCx, uint32_t TriggerSource) -{ -/* Note: On this STM32 series, ADC group injected external trigger edge */ -/* is used to perform a ADC conversion start. */ -/* This function does not set external trigger edge. */ -/* This feature is set using function */ -/* @ref LL_ADC_INJ_StartConversionExtTrig(). */ - MODIFY_REG(ADCx->CR2, ADC_CR2_JEXTSEL, (TriggerSource & ADC_CR2_JEXTSEL)); -} - -/** - * @brief Get ADC group injected conversion trigger source: - * internal (SW start) or from external IP (timer event, - * external interrupt line). - * @note To determine whether group injected trigger source is - * internal (SW start) or external, without detail - * of which peripheral is selected as external trigger, - * (equivalent to - * "if(LL_ADC_INJ_GetTriggerSource(ADC1) == LL_ADC_INJ_TRIG_SOFTWARE)") - * use function @ref LL_ADC_INJ_IsTriggerSourceSWStart. - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR2 JEXTSEL LL_ADC_INJ_GetTriggerSource\n - * CR2 JEXTEN LL_ADC_INJ_GetTriggerSource - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_SOFTWARE - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_CH1 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH1 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH3 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH3 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetTriggerSource(ADC_TypeDef *ADCx) -{ - uint32_t TriggerSource = READ_BIT(ADCx->CR2, ADC_CR2_JEXTSEL | ADC_CR2_JEXTEN); - - /* Value for shift of {0; 4; 8; 12} depending on value of bitfield */ - /* corresponding to ADC_CR2_JEXTEN {0; 1; 2; 3}. */ - uint32_t ShiftExten = ((TriggerSource & ADC_CR2_JEXTEN) >> (ADC_INJ_TRIG_EXTEN_BITOFFSET_POS - 2UL)); - - /* Set bitfield corresponding to ADC_CR2_JEXTEN and ADC_CR2_JEXTSEL */ - /* to match with triggers literals definition. */ - return ((TriggerSource - & (ADC_INJ_TRIG_SOURCE_MASK << ShiftExten) & ADC_CR2_JEXTSEL) - | ((ADC_INJ_TRIG_EDGE_MASK << ShiftExten) & ADC_CR2_JEXTEN) - ); -} - -/** - * @brief Get ADC group injected conversion trigger source internal (SW start) - or external - * @note In case of group injected trigger source set to external trigger, - * to determine which peripheral is selected as external trigger, - * use function @ref LL_ADC_INJ_GetTriggerSource. - * @rmtoll CR2 JEXTEN LL_ADC_INJ_IsTriggerSourceSWStart - * @param ADCx ADC instance - * @retval Value "0" if trigger source external trigger - * Value "1" if trigger source SW start. - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_IsTriggerSourceSWStart(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR2, ADC_CR2_JEXTEN) == (LL_ADC_INJ_TRIG_SOFTWARE & ADC_CR2_JEXTEN)); -} - -/** - * @brief Get ADC group injected conversion trigger polarity. - * Applicable only for trigger source set to external trigger. - * @rmtoll CR2 JEXTEN LL_ADC_INJ_GetTriggerEdge - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_EXT_RISING - * @arg @ref LL_ADC_INJ_TRIG_EXT_FALLING - * @arg @ref LL_ADC_INJ_TRIG_EXT_RISINGFALLING - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetTriggerEdge(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_JEXTEN)); -} - -/** - * @brief Set ADC group injected sequencer length and scan direction. - * @note This function performs configuration of: - * - Sequence length: Number of ranks in the scan sequence. - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from rank 1 to rank n). - * @note On this STM32 series, group injected sequencer configuration - * is conditioned to ADC instance sequencer mode. - * If ADC instance sequencer mode is disabled, sequencers of - * all groups (group regular, group injected) can be configured - * but their execution is disabled (limited to rank 1). - * Refer to function @ref LL_ADC_SetSequencersScanMode(). - * @note Sequencer disabled is equivalent to sequencer of 1 rank: - * ADC conversion on only 1 channel. - * @rmtoll JSQR JL LL_ADC_INJ_SetSequencerLength - * @param ADCx ADC instance - * @param SequencerNbRanks This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetSequencerLength(ADC_TypeDef *ADCx, uint32_t SequencerNbRanks) -{ - MODIFY_REG(ADCx->JSQR, ADC_JSQR_JL, SequencerNbRanks); -} - -/** - * @brief Get ADC group injected sequencer length and scan direction. - * @note This function retrieves: - * - Sequence length: Number of ranks in the scan sequence. - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from rank 1 to rank n). - * @note On this STM32 series, group injected sequencer configuration - * is conditioned to ADC instance sequencer mode. - * If ADC instance sequencer mode is disabled, sequencers of - * all groups (group regular, group injected) can be configured - * but their execution is disabled (limited to rank 1). - * Refer to function @ref LL_ADC_SetSequencersScanMode(). - * @note Sequencer disabled is equivalent to sequencer of 1 rank: - * ADC conversion on only 1 channel. - * @rmtoll JSQR JL LL_ADC_INJ_GetSequencerLength - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerLength(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->JSQR, ADC_JSQR_JL)); -} - -/** - * @brief Set ADC group injected sequencer discontinuous mode: - * sequence subdivided and scan conversions interrupted every selected - * number of ranks. - * @note It is not possible to enable both ADC group injected - * auto-injected mode and sequencer discontinuous mode. - * @rmtoll CR1 DISCEN LL_ADC_INJ_SetSequencerDiscont - * @param ADCx ADC instance - * @param SeqDiscont This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_SEQ_DISCONT_DISABLE - * @arg @ref LL_ADC_INJ_SEQ_DISCONT_1RANK - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetSequencerDiscont(ADC_TypeDef *ADCx, uint32_t SeqDiscont) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_JDISCEN, SeqDiscont); -} - -/** - * @brief Get ADC group injected sequencer discontinuous mode: - * sequence subdivided and scan conversions interrupted every selected - * number of ranks. - * @rmtoll CR1 DISCEN LL_ADC_REG_GetSequencerDiscont - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_SEQ_DISCONT_DISABLE - * @arg @ref LL_ADC_INJ_SEQ_DISCONT_1RANK - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerDiscont(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_JDISCEN)); -} - -/** - * @brief Set ADC group injected sequence: channel on the selected - * sequence rank. - * @note Depending on devices and packages, some channels may not be available. - * Refer to device datasheet for channels availability. - * @note On this STM32 series, to measure internal channels (VrefInt, - * TempSensor, ...), measurement paths to internal channels must be - * enabled separately. - * This can be done using function @ref LL_ADC_SetCommonPathInternalCh(). - * @rmtoll JSQR JSQ1 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ2 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ3 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ4 LL_ADC_INJ_SetSequencerRanks - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t Channel) -{ - /* Set bits with content of parameter "Channel" with bits position */ - /* in register depending on parameter "Rank". */ - /* Parameters "Rank" and "Channel" are used with masks because containing */ - /* other bits reserved for other purpose. */ - uint32_t tmpreg1 = (READ_BIT(ADCx->JSQR, ADC_JSQR_JL) >> ADC_JSQR_JL_Pos) + 1UL; - - MODIFY_REG(ADCx->JSQR, - ADC_CHANNEL_ID_NUMBER_MASK << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1))), - (Channel & ADC_CHANNEL_ID_NUMBER_MASK) << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1)))); -} - -/** - * @brief Get ADC group injected sequence: channel on the selected - * sequence rank. - * @note Depending on devices and packages, some channels may not be available. - * Refer to device datasheet for channels availability. - * @note Usage of the returned channel number: - * - To reinject this channel into another function LL_ADC_xxx: - * the returned channel number is only partly formatted on definition - * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared - * with parts of literals LL_ADC_CHANNEL_x or using - * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * Then the selected literal LL_ADC_CHANNEL_x can be used - * as parameter for another function. - * - To get the channel number in decimal format: - * process the returned value with the helper macro - * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * @rmtoll JSQR JSQ1 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ2 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ3 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ4 LL_ADC_INJ_SetSequencerRanks - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n - * (1) For ADC channel read back from ADC register, - * comparison with internal channel parameter to be done - * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank) -{ - uint32_t tmpreg1 = (READ_BIT(ADCx->JSQR, ADC_JSQR_JL) >> ADC_JSQR_JL_Pos) + 1UL; - - return (uint32_t)(READ_BIT(ADCx->JSQR, - ADC_CHANNEL_ID_NUMBER_MASK << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1)))) - >> (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1))) - ); -} - -/** - * @brief Set ADC group injected conversion trigger: - * independent or from ADC group regular. - * @note This mode can be used to extend number of data registers - * updated after one ADC conversion trigger and with data - * permanently kept (not erased by successive conversions of scan of - * ADC sequencer ranks), up to 5 data registers: - * 1 data register on ADC group regular, 4 data registers - * on ADC group injected. - * @note If ADC group injected injected trigger source is set to an - * external trigger, this feature must be must be set to - * independent trigger. - * ADC group injected automatic trigger is compliant only with - * group injected trigger source set to SW start, without any - * further action on ADC group injected conversion start or stop: - * in this case, ADC group injected is controlled only - * from ADC group regular. - * @note It is not possible to enable both ADC group injected - * auto-injected mode and sequencer discontinuous mode. - * @rmtoll CR1 JAUTO LL_ADC_INJ_SetTrigAuto - * @param ADCx ADC instance - * @param TrigAuto This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_INDEPENDENT - * @arg @ref LL_ADC_INJ_TRIG_FROM_GRP_REGULAR - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetTrigAuto(ADC_TypeDef *ADCx, uint32_t TrigAuto) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_JAUTO, TrigAuto); -} - -/** - * @brief Get ADC group injected conversion trigger: - * independent or from ADC group regular. - * @rmtoll CR1 JAUTO LL_ADC_INJ_GetTrigAuto - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_INDEPENDENT - * @arg @ref LL_ADC_INJ_TRIG_FROM_GRP_REGULAR - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetTrigAuto(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_JAUTO)); -} - -/** - * @brief Set ADC group injected offset. - * @note It sets: - * - ADC group injected rank to which the offset programmed - * will be applied - * - Offset level (offset to be subtracted from the raw - * converted data). - * Caution: Offset format is dependent to ADC resolution: - * offset has to be left-aligned on bit 11, the LSB (right bits) - * are set to 0. - * @note Offset cannot be enabled or disabled. - * To emulate offset disabled, set an offset value equal to 0. - * @rmtoll JOFR1 JOFFSET1 LL_ADC_INJ_SetOffset\n - * JOFR2 JOFFSET2 LL_ADC_INJ_SetOffset\n - * JOFR3 JOFFSET3 LL_ADC_INJ_SetOffset\n - * JOFR4 JOFFSET4 LL_ADC_INJ_SetOffset - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @param OffsetLevel Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetOffset(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t OffsetLevel) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JOFR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JOFRX_REGOFFSET_MASK)); - - MODIFY_REG(*preg, - ADC_JOFR1_JOFFSET1, - OffsetLevel); -} - -/** - * @brief Get ADC group injected offset. - * @note It gives offset level (offset to be subtracted from the raw converted data). - * Caution: Offset format is dependent to ADC resolution: - * offset has to be left-aligned on bit 11, the LSB (right bits) - * are set to 0. - * @rmtoll JOFR1 JOFFSET1 LL_ADC_INJ_GetOffset\n - * JOFR2 JOFFSET2 LL_ADC_INJ_GetOffset\n - * JOFR3 JOFFSET3 LL_ADC_INJ_GetOffset\n - * JOFR4 JOFFSET4 LL_ADC_INJ_GetOffset - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetOffset(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JOFR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JOFRX_REGOFFSET_MASK)); - - return (uint32_t)(READ_BIT(*preg, - ADC_JOFR1_JOFFSET1) - ); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_Channels Configuration of ADC hierarchical scope: channels - * @{ - */ - -/** - * @brief Set sampling time of the selected ADC channel - * Unit: ADC clock cycles. - * @note On this device, sampling time is on channel scope: independently - * of channel mapped on ADC group regular or injected. - * @note In case of internal channel (VrefInt, TempSensor, ...) to be - * converted: - * sampling time constraints must be respected (sampling time can be - * adjusted in function of ADC clock frequency and sampling time - * setting). - * Refer to device datasheet for timings values (parameters TS_vrefint, - * TS_temp, ...). - * @note Conversion time is the addition of sampling time and processing time. - * Refer to reference manual for ADC processing time of - * this STM32 series. - * @note In case of ADC conversion of internal channel (VrefInt, - * temperature sensor, ...), a sampling time minimum value - * is required. - * Refer to device datasheet. - * @rmtoll SMPR1 SMP18 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP17 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP16 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP15 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP14 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP13 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP12 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP11 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP10 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP9 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP8 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP7 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP6 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP5 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP4 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP3 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP2 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP1 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP0 LL_ADC_SetChannelSamplingTime - * @param ADCx ADC instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @param SamplingTime This parameter can be one of the following values: - * @arg @ref LL_ADC_SAMPLINGTIME_3CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_15CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_28CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_56CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_84CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_112CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_144CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_480CYCLES - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetChannelSamplingTime(ADC_TypeDef *ADCx, uint32_t Channel, uint32_t SamplingTime) -{ - /* Set bits with content of parameter "SamplingTime" with bits position */ - /* in register and register position depending on parameter "Channel". */ - /* Parameter "Channel" is used with masks because containing */ - /* other bits reserved for other purpose. */ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SMPR1, __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPRX_REGOFFSET_MASK)); - - MODIFY_REG(*preg, - ADC_SMPR2_SMP0 << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK), - SamplingTime << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK)); -} - -/** - * @brief Get sampling time of the selected ADC channel - * Unit: ADC clock cycles. - * @note On this device, sampling time is on channel scope: independently - * of channel mapped on ADC group regular or injected. - * @note Conversion time is the addition of sampling time and processing time. - * Refer to reference manual for ADC processing time of - * this STM32 series. - * @rmtoll SMPR1 SMP18 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP17 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP16 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP15 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP14 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP13 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP12 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP11 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP10 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP9 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP8 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP7 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP6 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP5 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP4 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP3 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP2 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP1 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP0 LL_ADC_GetChannelSamplingTime - * @param ADCx ADC instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_SAMPLINGTIME_3CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_15CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_28CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_56CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_84CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_112CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_144CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_480CYCLES - */ -__STATIC_INLINE uint32_t LL_ADC_GetChannelSamplingTime(ADC_TypeDef *ADCx, uint32_t Channel) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SMPR1, __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPRX_REGOFFSET_MASK)); - - return (uint32_t)(READ_BIT(*preg, - ADC_SMPR2_SMP0 << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK)) - >> __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK) - ); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_AnalogWatchdog Configuration of ADC transversal scope: analog watchdog - * @{ - */ - -/** - * @brief Set ADC analog watchdog monitored channels: - * a single channel or all channels, - * on ADC groups regular and-or injected. - * @note Once monitored channels are selected, analog watchdog - * is enabled. - * @note In case of need to define a single channel to monitor - * with analog watchdog from sequencer channel definition, - * use helper macro @ref __LL_ADC_ANALOGWD_CHANNEL_GROUP(). - * @note On this STM32 series, there is only 1 kind of analog watchdog - * instance: - * - AWD standard (instance AWD1): - * - channels monitored: can monitor 1 channel or all channels. - * - groups monitored: ADC groups regular and-or injected. - * - resolution: resolution is not limited (corresponds to - * ADC resolution configured). - * @rmtoll CR1 AWD1CH LL_ADC_SetAnalogWDMonitChannels\n - * CR1 AWD1SGL LL_ADC_SetAnalogWDMonitChannels\n - * CR1 AWD1EN LL_ADC_SetAnalogWDMonitChannels - * @param ADCx ADC instance - * @param AWDChannelGroup This parameter can be one of the following values: - * @arg @ref LL_ADC_AWD_DISABLE - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG - * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG - * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG - * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG - * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG - * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG - * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG - * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG - * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG - * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG - * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG - * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG - * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG - * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG - * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG - * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG - * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG - * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG - * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG - * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ - * @arg @ref LL_ADC_AWD_CH_VREFINT_REG (1) - * @arg @ref LL_ADC_AWD_CH_VREFINT_INJ (1) - * @arg @ref LL_ADC_AWD_CH_VREFINT_REG_INJ (1) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG (1)(2) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_INJ (1)(2) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ (1)(2) - * @arg @ref LL_ADC_AWD_CH_VBAT_REG (1) - * @arg @ref LL_ADC_AWD_CH_VBAT_INJ (1) - * @arg @ref LL_ADC_AWD_CH_VBAT_REG_INJ (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetAnalogWDMonitChannels(ADC_TypeDef *ADCx, uint32_t AWDChannelGroup) -{ - MODIFY_REG(ADCx->CR1, - (ADC_CR1_AWDEN | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDCH), - AWDChannelGroup); -} - -/** - * @brief Get ADC analog watchdog monitored channel. - * @note Usage of the returned channel number: - * - To reinject this channel into another function LL_ADC_xxx: - * the returned channel number is only partly formatted on definition - * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared - * with parts of literals LL_ADC_CHANNEL_x or using - * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * Then the selected literal LL_ADC_CHANNEL_x can be used - * as parameter for another function. - * - To get the channel number in decimal format: - * process the returned value with the helper macro - * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * Applicable only when the analog watchdog is set to monitor - * one channel. - * @note On this STM32 series, there is only 1 kind of analog watchdog - * instance: - * - AWD standard (instance AWD1): - * - channels monitored: can monitor 1 channel or all channels. - * - groups monitored: ADC groups regular and-or injected. - * - resolution: resolution is not limited (corresponds to - * ADC resolution configured). - * @rmtoll CR1 AWD1CH LL_ADC_GetAnalogWDMonitChannels\n - * CR1 AWD1SGL LL_ADC_GetAnalogWDMonitChannels\n - * CR1 AWD1EN LL_ADC_GetAnalogWDMonitChannels - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_AWD_DISABLE - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG - * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG - * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG - * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG - * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG - * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG - * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG - * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG - * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG - * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG - * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG - * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG - * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG - * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG - * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG - * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG - * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG - * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG - * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG - * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ - */ -__STATIC_INLINE uint32_t LL_ADC_GetAnalogWDMonitChannels(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, (ADC_CR1_AWDEN | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDCH))); -} - -/** - * @brief Set ADC analog watchdog threshold value of threshold - * high or low. - * @note In case of ADC resolution different of 12 bits, - * analog watchdog thresholds data require a specific shift. - * Use helper macro @ref __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(). - * @note On this STM32 series, there is only 1 kind of analog watchdog - * instance: - * - AWD standard (instance AWD1): - * - channels monitored: can monitor 1 channel or all channels. - * - groups monitored: ADC groups regular and-or injected. - * - resolution: resolution is not limited (corresponds to - * ADC resolution configured). - * @rmtoll HTR HT LL_ADC_SetAnalogWDThresholds\n - * LTR LT LL_ADC_SetAnalogWDThresholds - * @param ADCx ADC instance - * @param AWDThresholdsHighLow This parameter can be one of the following values: - * @arg @ref LL_ADC_AWD_THRESHOLD_HIGH - * @arg @ref LL_ADC_AWD_THRESHOLD_LOW - * @param AWDThresholdValue Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetAnalogWDThresholds(ADC_TypeDef *ADCx, uint32_t AWDThresholdsHighLow, uint32_t AWDThresholdValue) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->HTR, AWDThresholdsHighLow); - - MODIFY_REG(*preg, - ADC_HTR_HT, - AWDThresholdValue); -} - -/** - * @brief Get ADC analog watchdog threshold value of threshold high or - * threshold low. - * @note In case of ADC resolution different of 12 bits, - * analog watchdog thresholds data require a specific shift. - * Use helper macro @ref __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION(). - * @rmtoll HTR HT LL_ADC_GetAnalogWDThresholds\n - * LTR LT LL_ADC_GetAnalogWDThresholds - * @param ADCx ADC instance - * @param AWDThresholdsHighLow This parameter can be one of the following values: - * @arg @ref LL_ADC_AWD_THRESHOLD_HIGH - * @arg @ref LL_ADC_AWD_THRESHOLD_LOW - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF -*/ -__STATIC_INLINE uint32_t LL_ADC_GetAnalogWDThresholds(ADC_TypeDef *ADCx, uint32_t AWDThresholdsHighLow) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->HTR, AWDThresholdsHighLow); - - return (uint32_t)(READ_BIT(*preg, ADC_HTR_HT)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Multimode Configuration of ADC hierarchical scope: multimode - * @{ - */ - -#if defined(ADC_MULTIMODE_SUPPORT) -/** - * @brief Set ADC multimode configuration to operate in independent mode - * or multimode (for devices with several ADC instances). - * @note If multimode configuration: the selected ADC instance is - * either master or slave depending on hardware. - * Refer to reference manual. - * @rmtoll CCR MULTI LL_ADC_SetMultimode - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param Multimode This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_INDEPENDENT - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIMULT - * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL - * @arg @ref LL_ADC_MULTI_DUAL_INJ_SIMULT - * @arg @ref LL_ADC_MULTI_DUAL_INJ_ALTERN - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT - * @arg @ref LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT - * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_SIMULT - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIMULT - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_INTERL - * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_ALTERN - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetMultimode(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t Multimode) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_MULTI, Multimode); -} - -/** - * @brief Get ADC multimode configuration to operate in independent mode - * or multimode (for devices with several ADC instances). - * @note If multimode configuration: the selected ADC instance is - * either master or slave depending on hardware. - * Refer to reference manual. - * @rmtoll CCR MULTI LL_ADC_GetMultimode - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_MULTI_INDEPENDENT - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIMULT - * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL - * @arg @ref LL_ADC_MULTI_DUAL_INJ_SIMULT - * @arg @ref LL_ADC_MULTI_DUAL_INJ_ALTERN - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT - * @arg @ref LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT - * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_SIMULT - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIMULT - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_INTERL - * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_ALTERN - */ -__STATIC_INLINE uint32_t LL_ADC_GetMultimode(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_MULTI)); -} - -/** - * @brief Set ADC multimode conversion data transfer: no transfer - * or transfer by DMA. - * @note If ADC multimode transfer by DMA is not selected: - * each ADC uses its own DMA channel, with its individual - * DMA transfer settings. - * If ADC multimode transfer by DMA is selected: - * One DMA channel is used for both ADC (DMA of ADC master) - * Specifies the DMA requests mode: - * - Limited mode (One shot mode): DMA transfer requests are stopped - * when number of DMA data transfers (number of - * ADC conversions) is reached. - * This ADC mode is intended to be used with DMA mode non-circular. - * - Unlimited mode: DMA transfer requests are unlimited, - * whatever number of DMA data transfers (number of - * ADC conversions). - * This ADC mode is intended to be used with DMA mode circular. - * @note If ADC DMA requests mode is set to unlimited and DMA is set to - * mode non-circular: - * when DMA transfers size will be reached, DMA will stop transfers of - * ADC conversions data ADC will raise an overrun error - * (overrun flag and interruption if enabled). - * @note How to retrieve multimode conversion data: - * Whatever multimode transfer by DMA setting: using function - * @ref LL_ADC_REG_ReadMultiConversionData32(). - * If ADC multimode transfer by DMA is selected: conversion data - * is a raw data with ADC master and slave concatenated. - * A macro is available to get the conversion data of - * ADC master or ADC slave: see helper macro - * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). - * @rmtoll CCR MDMA LL_ADC_SetMultiDMATransfer\n - * CCR DDS LL_ADC_SetMultiDMATransfer - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param MultiDMATransfer This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_REG_DMA_EACH_ADC - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_1 - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_2 - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_3 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_1 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_2 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_3 - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetMultiDMATransfer(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t MultiDMATransfer) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_DMA | ADC_CCR_DDS, MultiDMATransfer); -} - -/** - * @brief Get ADC multimode conversion data transfer: no transfer - * or transfer by DMA. - * @note If ADC multimode transfer by DMA is not selected: - * each ADC uses its own DMA channel, with its individual - * DMA transfer settings. - * If ADC multimode transfer by DMA is selected: - * One DMA channel is used for both ADC (DMA of ADC master) - * Specifies the DMA requests mode: - * - Limited mode (One shot mode): DMA transfer requests are stopped - * when number of DMA data transfers (number of - * ADC conversions) is reached. - * This ADC mode is intended to be used with DMA mode non-circular. - * - Unlimited mode: DMA transfer requests are unlimited, - * whatever number of DMA data transfers (number of - * ADC conversions). - * This ADC mode is intended to be used with DMA mode circular. - * @note If ADC DMA requests mode is set to unlimited and DMA is set to - * mode non-circular: - * when DMA transfers size will be reached, DMA will stop transfers of - * ADC conversions data ADC will raise an overrun error - * (overrun flag and interruption if enabled). - * @note How to retrieve multimode conversion data: - * Whatever multimode transfer by DMA setting: using function - * @ref LL_ADC_REG_ReadMultiConversionData32(). - * If ADC multimode transfer by DMA is selected: conversion data - * is a raw data with ADC master and slave concatenated. - * A macro is available to get the conversion data of - * ADC master or ADC slave: see helper macro - * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). - * @rmtoll CCR MDMA LL_ADC_GetMultiDMATransfer\n - * CCR DDS LL_ADC_GetMultiDMATransfer - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_MULTI_REG_DMA_EACH_ADC - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_1 - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_2 - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_3 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_1 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_2 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_3 - */ -__STATIC_INLINE uint32_t LL_ADC_GetMultiDMATransfer(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_DMA | ADC_CCR_DDS)); -} - -/** - * @brief Set ADC multimode delay between 2 sampling phases. - * @note The sampling delay range depends on ADC resolution: - * - ADC resolution 12 bits can have maximum delay of 12 cycles. - * - ADC resolution 10 bits can have maximum delay of 10 cycles. - * - ADC resolution 8 bits can have maximum delay of 8 cycles. - * - ADC resolution 6 bits can have maximum delay of 6 cycles. - * @rmtoll CCR DELAY LL_ADC_SetMultiTwoSamplingDelay - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param MultiTwoSamplingDelay This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetMultiTwoSamplingDelay(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t MultiTwoSamplingDelay) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_DELAY, MultiTwoSamplingDelay); -} - -/** - * @brief Get ADC multimode delay between 2 sampling phases. - * @rmtoll CCR DELAY LL_ADC_GetMultiTwoSamplingDelay - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES - */ -__STATIC_INLINE uint32_t LL_ADC_GetMultiTwoSamplingDelay(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_DELAY)); -} -#endif /* ADC_MULTIMODE_SUPPORT */ - -/** - * @} - */ -/** @defgroup ADC_LL_EF_Operation_ADC_Instance Operation on ADC hierarchical scope: ADC instance - * @{ - */ - -/** - * @brief Enable the selected ADC instance. - * @note On this STM32 series, after ADC enable, a delay for - * ADC internal analog stabilization is required before performing a - * ADC conversion start. - * Refer to device datasheet, parameter tSTAB. - * @rmtoll CR2 ADON LL_ADC_Enable - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_Enable(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR2, ADC_CR2_ADON); -} - -/** - * @brief Disable the selected ADC instance. - * @rmtoll CR2 ADON LL_ADC_Disable - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_Disable(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR2, ADC_CR2_ADON); -} - -/** - * @brief Get the selected ADC instance enable state. - * @rmtoll CR2 ADON LL_ADC_IsEnabled - * @param ADCx ADC instance - * @retval 0: ADC is disabled, 1: ADC is enabled. - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabled(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR2, ADC_CR2_ADON) == (ADC_CR2_ADON)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Operation_ADC_Group_Regular Operation on ADC hierarchical scope: group regular - * @{ - */ - -/** - * @brief Start ADC group regular conversion. - * @note On this STM32 series, this function is relevant only for - * internal trigger (SW start), not for external trigger: - * - If ADC trigger has been set to software start, ADC conversion - * starts immediately. - * - If ADC trigger has been set to external trigger, ADC conversion - * start must be performed using function - * @ref LL_ADC_REG_StartConversionExtTrig(). - * (if external trigger edge would have been set during ADC other - * settings, ADC conversion would start at trigger event - * as soon as ADC is enabled). - * @rmtoll CR2 SWSTART LL_ADC_REG_StartConversionSWStart - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_StartConversionSWStart(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR2, ADC_CR2_SWSTART); -} - -/** - * @brief Start ADC group regular conversion from external trigger. - * @note ADC conversion will start at next trigger event (on the selected - * trigger edge) following the ADC start conversion command. - * @note On this STM32 series, this function is relevant for - * ADC conversion start from external trigger. - * If internal trigger (SW start) is needed, perform ADC conversion - * start using function @ref LL_ADC_REG_StartConversionSWStart(). - * @rmtoll CR2 EXTEN LL_ADC_REG_StartConversionExtTrig - * @param ExternalTriggerEdge This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_TRIG_EXT_RISING - * @arg @ref LL_ADC_REG_TRIG_EXT_FALLING - * @arg @ref LL_ADC_REG_TRIG_EXT_RISINGFALLING - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_StartConversionExtTrig(ADC_TypeDef *ADCx, uint32_t ExternalTriggerEdge) -{ - SET_BIT(ADCx->CR2, ExternalTriggerEdge); -} - -/** - * @brief Stop ADC group regular conversion from external trigger. - * @note No more ADC conversion will start at next trigger event - * following the ADC stop conversion command. - * If a conversion is on-going, it will be completed. - * @note On this STM32 series, there is no specific command - * to stop a conversion on-going or to stop ADC converting - * in continuous mode. These actions can be performed - * using function @ref LL_ADC_Disable(). - * @rmtoll CR2 EXTEN LL_ADC_REG_StopConversionExtTrig - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_StopConversionExtTrig(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR2, ADC_CR2_EXTEN); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * all ADC configurations: all ADC resolutions and - * all oversampling increased data width (for devices - * with feature oversampling). - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData32 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_ADC_REG_ReadConversionData32(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * ADC resolution 12 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_REG_ReadConversionData32. - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData12 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -__STATIC_INLINE uint16_t LL_ADC_REG_ReadConversionData12(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * ADC resolution 10 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_REG_ReadConversionData32. - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData10 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x000 and Max_Data=0x3FF - */ -__STATIC_INLINE uint16_t LL_ADC_REG_ReadConversionData10(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * ADC resolution 8 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_REG_ReadConversionData32. - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData8 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_ADC_REG_ReadConversionData8(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * ADC resolution 6 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_REG_ReadConversionData32. - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData6 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x00 and Max_Data=0x3F - */ -__STATIC_INLINE uint8_t LL_ADC_REG_ReadConversionData6(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -#if defined(ADC_MULTIMODE_SUPPORT) -/** - * @brief Get ADC multimode conversion data of ADC master, ADC slave - * or raw data with ADC master and slave concatenated. - * @note If raw data with ADC master and slave concatenated is retrieved, - * a macro is available to get the conversion data of - * ADC master or ADC slave: see helper macro - * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). - * (however this macro is mainly intended for multimode - * transfer by DMA, because this function can do the same - * by getting multimode conversion data of ADC master or ADC slave - * separately). - * @rmtoll CDR DATA1 LL_ADC_REG_ReadMultiConversionData32\n - * CDR DATA2 LL_ADC_REG_ReadMultiConversionData32 - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param ConversionData This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_MASTER - * @arg @ref LL_ADC_MULTI_SLAVE - * @arg @ref LL_ADC_MULTI_MASTER_SLAVE - * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_ADC_REG_ReadMultiConversionData32(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t ConversionData) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CDR, - ADC_DR_ADC2DATA) - >> POSITION_VAL(ConversionData) - ); -} -#endif /* ADC_MULTIMODE_SUPPORT */ - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Operation_ADC_Group_Injected Operation on ADC hierarchical scope: group injected - * @{ - */ - -/** - * @brief Start ADC group injected conversion. - * @note On this STM32 series, this function is relevant only for - * internal trigger (SW start), not for external trigger: - * - If ADC trigger has been set to software start, ADC conversion - * starts immediately. - * - If ADC trigger has been set to external trigger, ADC conversion - * start must be performed using function - * @ref LL_ADC_INJ_StartConversionExtTrig(). - * (if external trigger edge would have been set during ADC other - * settings, ADC conversion would start at trigger event - * as soon as ADC is enabled). - * @rmtoll CR2 JSWSTART LL_ADC_INJ_StartConversionSWStart - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_StartConversionSWStart(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR2, ADC_CR2_JSWSTART); -} - -/** - * @brief Start ADC group injected conversion from external trigger. - * @note ADC conversion will start at next trigger event (on the selected - * trigger edge) following the ADC start conversion command. - * @note On this STM32 series, this function is relevant for - * ADC conversion start from external trigger. - * If internal trigger (SW start) is needed, perform ADC conversion - * start using function @ref LL_ADC_INJ_StartConversionSWStart(). - * @rmtoll CR2 JEXTEN LL_ADC_INJ_StartConversionExtTrig - * @param ExternalTriggerEdge This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_EXT_RISING - * @arg @ref LL_ADC_INJ_TRIG_EXT_FALLING - * @arg @ref LL_ADC_INJ_TRIG_EXT_RISINGFALLING - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_StartConversionExtTrig(ADC_TypeDef *ADCx, uint32_t ExternalTriggerEdge) -{ - SET_BIT(ADCx->CR2, ExternalTriggerEdge); -} - -/** - * @brief Stop ADC group injected conversion from external trigger. - * @note No more ADC conversion will start at next trigger event - * following the ADC stop conversion command. - * If a conversion is on-going, it will be completed. - * @note On this STM32 series, there is no specific command - * to stop a conversion on-going or to stop ADC converting - * in continuous mode. These actions can be performed - * using function @ref LL_ADC_Disable(). - * @rmtoll CR2 JEXTEN LL_ADC_INJ_StopConversionExtTrig - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_StopConversionExtTrig(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR2, ADC_CR2_JEXTEN); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * all ADC configurations: all ADC resolutions and - * all oversampling increased data width (for devices - * with feature oversampling). - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData32\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData32\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData32\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData32 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_ReadConversionData32(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint32_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @brief Get ADC group injected conversion data, range fit for - * ADC resolution 12 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_INJ_ReadConversionData32. - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData12\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData12\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData12\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData12 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -__STATIC_INLINE uint16_t LL_ADC_INJ_ReadConversionData12(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint16_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @brief Get ADC group injected conversion data, range fit for - * ADC resolution 10 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_INJ_ReadConversionData32. - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData10\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData10\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData10\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData10 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x000 and Max_Data=0x3FF - */ -__STATIC_INLINE uint16_t LL_ADC_INJ_ReadConversionData10(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint16_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @brief Get ADC group injected conversion data, range fit for - * ADC resolution 8 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_INJ_ReadConversionData32. - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData8\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData8\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData8\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData8 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_ADC_INJ_ReadConversionData8(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint8_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @brief Get ADC group injected conversion data, range fit for - * ADC resolution 6 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_INJ_ReadConversionData32. - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData6\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData6\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData6\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData6 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x00 and Max_Data=0x3F - */ -__STATIC_INLINE uint8_t LL_ADC_INJ_ReadConversionData6(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint8_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_FLAG_Management ADC flag management - * @{ - */ - -/** - * @brief Get flag ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll SR EOC LL_ADC_IsActiveFlag_EOCS - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_EOCS(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->SR, LL_ADC_FLAG_EOCS) == (LL_ADC_FLAG_EOCS)); -} - -/** - * @brief Get flag ADC group regular overrun. - * @rmtoll SR OVR LL_ADC_IsActiveFlag_OVR - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_OVR(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->SR, LL_ADC_FLAG_OVR) == (LL_ADC_FLAG_OVR)); -} - - -/** - * @brief Get flag ADC group injected end of sequence conversions. - * @rmtoll SR JEOC LL_ADC_IsActiveFlag_JEOS - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCx->SR, LL_ADC_FLAG_JEOS) == (LL_ADC_FLAG_JEOS)); -} - -/** - * @brief Get flag ADC analog watchdog 1 flag - * @rmtoll SR AWD LL_ADC_IsActiveFlag_AWD1 - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_AWD1(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->SR, LL_ADC_FLAG_AWD1) == (LL_ADC_FLAG_AWD1)); -} - -/** - * @brief Clear flag ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll SR EOC LL_ADC_ClearFlag_EOCS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_ClearFlag_EOCS(ADC_TypeDef *ADCx) -{ - WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_EOCS); -} - -/** - * @brief Clear flag ADC group regular overrun. - * @rmtoll SR OVR LL_ADC_ClearFlag_OVR - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_ClearFlag_OVR(ADC_TypeDef *ADCx) -{ - WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_OVR); -} - - -/** - * @brief Clear flag ADC group injected end of sequence conversions. - * @rmtoll SR JEOC LL_ADC_ClearFlag_JEOS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_ClearFlag_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_JEOS); -} - -/** - * @brief Clear flag ADC analog watchdog 1. - * @rmtoll SR AWD LL_ADC_ClearFlag_AWD1 - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_ClearFlag_AWD1(ADC_TypeDef *ADCx) -{ - WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_AWD1); -} - -#if defined(ADC_MULTIMODE_SUPPORT) -/** - * @brief Get flag multimode ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration, of the ADC master. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CSR EOC1 LL_ADC_IsActiveFlag_MST_EOCS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADC1->SR, LL_ADC_FLAG_EOCS) == (LL_ADC_FLAG_EOCS)); -} - -/** - * @brief Get flag multimode ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration, of the ADC slave 1. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CSR EOC2 LL_ADC_IsActiveFlag_SLV1_EOCS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_EOCS_SLV1) == (LL_ADC_FLAG_EOCS_SLV1)); -} - -/** - * @brief Get flag multimode ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration, of the ADC slave 2. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CSR EOC3 LL_ADC_IsActiveFlag_SLV2_EOCS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_EOCS_SLV2) == (LL_ADC_FLAG_EOCS_SLV2)); -} -/** - * @brief Get flag multimode ADC group regular overrun of the ADC master. - * @rmtoll CSR OVR1 LL_ADC_IsActiveFlag_MST_OVR - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_OVR(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_MST) == (LL_ADC_FLAG_OVR_MST)); -} - -/** - * @brief Get flag multimode ADC group regular overrun of the ADC slave 1. - * @rmtoll CSR OVR2 LL_ADC_IsActiveFlag_SLV1_OVR - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_OVR(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_SLV1) == (LL_ADC_FLAG_OVR_SLV1)); -} - -/** - * @brief Get flag multimode ADC group regular overrun of the ADC slave 2. - * @rmtoll CSR OVR3 LL_ADC_IsActiveFlag_SLV2_OVR - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_OVR(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_SLV2) == (LL_ADC_FLAG_OVR_SLV2)); -} - - -/** - * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC master. - * @rmtoll CSR JEOC LL_ADC_IsActiveFlag_MST_EOCS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC1) == (ADC_CSR_JEOC1)); -} - -/** - * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC slave 1. - * @rmtoll CSR JEOC2 LL_ADC_IsActiveFlag_SLV1_JEOS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC2) == (ADC_CSR_JEOC2)); -} - -/** - * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC slave 2. - * @rmtoll CSR JEOC3 LL_ADC_IsActiveFlag_SLV2_JEOS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC3) == (ADC_CSR_JEOC3)); -} - -/** - * @brief Get flag multimode ADC analog watchdog 1 of the ADC master. - * @rmtoll CSR AWD1 LL_ADC_IsActiveFlag_MST_AWD1 - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_MST) == (LL_ADC_FLAG_AWD1_MST)); -} - -/** - * @brief Get flag multimode analog watchdog 1 of the ADC slave 1. - * @rmtoll CSR AWD2 LL_ADC_IsActiveFlag_SLV1_AWD1 - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_SLV1) == (LL_ADC_FLAG_AWD1_SLV1)); -} - -/** - * @brief Get flag multimode analog watchdog 1 of the ADC slave 2. - * @rmtoll CSR AWD3 LL_ADC_IsActiveFlag_SLV2_AWD1 - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_SLV2) == (LL_ADC_FLAG_AWD1_SLV2)); -} - -#endif /* ADC_MULTIMODE_SUPPORT */ - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_IT_Management ADC IT management - * @{ - */ - -/** - * @brief Enable interruption ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CR1 EOCIE LL_ADC_EnableIT_EOCS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_EnableIT_EOCS(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR1, LL_ADC_IT_EOCS); -} - -/** - * @brief Enable ADC group regular interruption overrun. - * @rmtoll CR1 OVRIE LL_ADC_EnableIT_OVR - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_EnableIT_OVR(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR1, LL_ADC_IT_OVR); -} - - -/** - * @brief Enable interruption ADC group injected end of sequence conversions. - * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_EnableIT_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - SET_BIT(ADCx->CR1, LL_ADC_IT_JEOS); -} - -/** - * @brief Enable interruption ADC analog watchdog 1. - * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_EnableIT_AWD1(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR1, LL_ADC_IT_AWD1); -} - -/** - * @brief Disable interruption ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CR1 EOCIE LL_ADC_DisableIT_EOCS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_DisableIT_EOCS(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR1, LL_ADC_IT_EOCS); -} - -/** - * @brief Disable interruption ADC group regular overrun. - * @rmtoll CR1 OVRIE LL_ADC_DisableIT_OVR - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_DisableIT_OVR(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR1, LL_ADC_IT_OVR); -} - - -/** - * @brief Disable interruption ADC group injected end of sequence conversions. - * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_DisableIT_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - CLEAR_BIT(ADCx->CR1, LL_ADC_IT_JEOS); -} - -/** - * @brief Disable interruption ADC analog watchdog 1. - * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_DisableIT_AWD1(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR1, LL_ADC_IT_AWD1); -} - -/** - * @brief Get state of interruption ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * (0: interrupt disabled, 1: interrupt enabled) - * @rmtoll CR1 EOCIE LL_ADC_IsEnabledIT_EOCS - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_EOCS(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR1, LL_ADC_IT_EOCS) == (LL_ADC_IT_EOCS)); -} - -/** - * @brief Get state of interruption ADC group regular overrun - * (0: interrupt disabled, 1: interrupt enabled). - * @rmtoll CR1 OVRIE LL_ADC_IsEnabledIT_OVR - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_OVR(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR1, LL_ADC_IT_OVR) == (LL_ADC_IT_OVR)); -} - - -/** - * @brief Get state of interruption ADC group injected end of sequence conversions - * (0: interrupt disabled, 1: interrupt enabled). - * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCx->CR1, LL_ADC_IT_JEOS) == (LL_ADC_IT_JEOS)); -} - -/** - * @brief Get state of interruption ADC analog watchdog 1 - * (0: interrupt disabled, 1: interrupt enabled). - * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_AWD1(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR1, LL_ADC_IT_AWD1) == (LL_ADC_IT_AWD1)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup ADC_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -/* Initialization of some features of ADC common parameters and multimode */ -ErrorStatus LL_ADC_CommonDeInit(ADC_Common_TypeDef *ADCxy_COMMON); -ErrorStatus LL_ADC_CommonInit(ADC_Common_TypeDef *ADCxy_COMMON, LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct); -void LL_ADC_CommonStructInit(LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct); - -/* De-initialization of ADC instance, ADC group regular and ADC group injected */ -/* (availability of ADC group injected depends on STM32 families) */ -ErrorStatus LL_ADC_DeInit(ADC_TypeDef *ADCx); - -/* Initialization of some features of ADC instance */ -ErrorStatus LL_ADC_Init(ADC_TypeDef *ADCx, LL_ADC_InitTypeDef *ADC_InitStruct); -void LL_ADC_StructInit(LL_ADC_InitTypeDef *ADC_InitStruct); - -/* Initialization of some features of ADC instance and ADC group regular */ -ErrorStatus LL_ADC_REG_Init(ADC_TypeDef *ADCx, LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct); -void LL_ADC_REG_StructInit(LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct); - -/* Initialization of some features of ADC instance and ADC group injected */ -ErrorStatus LL_ADC_INJ_Init(ADC_TypeDef *ADCx, LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct); -void LL_ADC_INJ_StructInit(LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* ADC1 || ADC2 || ADC3 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_ADC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h deleted file mode 100644 index 66da28fe2419f98..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h +++ /dev/null @@ -1,2108 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_bus.h - * @author MCD Application Team - * @brief Header file of BUS LL module. - - @verbatim - ##### RCC Limitations ##### - ============================================================================== - [..] - A delay between an RCC peripheral clock enable and the effective peripheral - enabling should be taken into account in order to manage the peripheral read/write - from/to registers. - (+) This delay depends on the peripheral mapping. - (++) AHB & APB peripherals, 1 dummy read is necessary - - [..] - Workarounds: - (#) For AHB & APB peripherals, a dummy read to the peripheral register has been - inserted in each LL_{BUS}_GRP{x}_EnableClock() function. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_BUS_H -#define __STM32F4xx_LL_BUS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RCC) - -/** @defgroup BUS_LL BUS - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup BUS_LL_Exported_Constants BUS Exported Constants - * @{ - */ - -/** @defgroup BUS_LL_EC_AHB1_GRP1_PERIPH AHB1 GRP1 PERIPH - * @{ - */ -#define LL_AHB1_GRP1_PERIPH_ALL 0xFFFFFFFFU -#define LL_AHB1_GRP1_PERIPH_GPIOA RCC_AHB1ENR_GPIOAEN -#define LL_AHB1_GRP1_PERIPH_GPIOB RCC_AHB1ENR_GPIOBEN -#define LL_AHB1_GRP1_PERIPH_GPIOC RCC_AHB1ENR_GPIOCEN -#if defined(GPIOD) -#define LL_AHB1_GRP1_PERIPH_GPIOD RCC_AHB1ENR_GPIODEN -#endif /* GPIOD */ -#if defined(GPIOE) -#define LL_AHB1_GRP1_PERIPH_GPIOE RCC_AHB1ENR_GPIOEEN -#endif /* GPIOE */ -#if defined(GPIOF) -#define LL_AHB1_GRP1_PERIPH_GPIOF RCC_AHB1ENR_GPIOFEN -#endif /* GPIOF */ -#if defined(GPIOG) -#define LL_AHB1_GRP1_PERIPH_GPIOG RCC_AHB1ENR_GPIOGEN -#endif /* GPIOG */ -#if defined(GPIOH) -#define LL_AHB1_GRP1_PERIPH_GPIOH RCC_AHB1ENR_GPIOHEN -#endif /* GPIOH */ -#if defined(GPIOI) -#define LL_AHB1_GRP1_PERIPH_GPIOI RCC_AHB1ENR_GPIOIEN -#endif /* GPIOI */ -#if defined(GPIOJ) -#define LL_AHB1_GRP1_PERIPH_GPIOJ RCC_AHB1ENR_GPIOJEN -#endif /* GPIOJ */ -#if defined(GPIOK) -#define LL_AHB1_GRP1_PERIPH_GPIOK RCC_AHB1ENR_GPIOKEN -#endif /* GPIOK */ -#define LL_AHB1_GRP1_PERIPH_CRC RCC_AHB1ENR_CRCEN -#if defined(RCC_AHB1ENR_BKPSRAMEN) -#define LL_AHB1_GRP1_PERIPH_BKPSRAM RCC_AHB1ENR_BKPSRAMEN -#endif /* RCC_AHB1ENR_BKPSRAMEN */ -#if defined(RCC_AHB1ENR_CCMDATARAMEN) -#define LL_AHB1_GRP1_PERIPH_CCMDATARAM RCC_AHB1ENR_CCMDATARAMEN -#endif /* RCC_AHB1ENR_CCMDATARAMEN */ -#define LL_AHB1_GRP1_PERIPH_DMA1 RCC_AHB1ENR_DMA1EN -#define LL_AHB1_GRP1_PERIPH_DMA2 RCC_AHB1ENR_DMA2EN -#if defined(RCC_AHB1ENR_RNGEN) -#define LL_AHB1_GRP1_PERIPH_RNG RCC_AHB1ENR_RNGEN -#endif /* RCC_AHB1ENR_RNGEN */ -#if defined(DMA2D) -#define LL_AHB1_GRP1_PERIPH_DMA2D RCC_AHB1ENR_DMA2DEN -#endif /* DMA2D */ -#if defined(ETH) -#define LL_AHB1_GRP1_PERIPH_ETHMAC RCC_AHB1ENR_ETHMACEN -#define LL_AHB1_GRP1_PERIPH_ETHMACTX RCC_AHB1ENR_ETHMACTXEN -#define LL_AHB1_GRP1_PERIPH_ETHMACRX RCC_AHB1ENR_ETHMACRXEN -#define LL_AHB1_GRP1_PERIPH_ETHMACPTP RCC_AHB1ENR_ETHMACPTPEN -#endif /* ETH */ -#if defined(USB_OTG_HS) -#define LL_AHB1_GRP1_PERIPH_OTGHS RCC_AHB1ENR_OTGHSEN -#define LL_AHB1_GRP1_PERIPH_OTGHSULPI RCC_AHB1ENR_OTGHSULPIEN -#endif /* USB_OTG_HS */ -#define LL_AHB1_GRP1_PERIPH_FLITF RCC_AHB1LPENR_FLITFLPEN -#define LL_AHB1_GRP1_PERIPH_SRAM1 RCC_AHB1LPENR_SRAM1LPEN -#if defined(RCC_AHB1LPENR_SRAM2LPEN) -#define LL_AHB1_GRP1_PERIPH_SRAM2 RCC_AHB1LPENR_SRAM2LPEN -#endif /* RCC_AHB1LPENR_SRAM2LPEN */ -#if defined(RCC_AHB1LPENR_SRAM3LPEN) -#define LL_AHB1_GRP1_PERIPH_SRAM3 RCC_AHB1LPENR_SRAM3LPEN -#endif /* RCC_AHB1LPENR_SRAM3LPEN */ -/** - * @} - */ - -#if defined(RCC_AHB2_SUPPORT) -/** @defgroup BUS_LL_EC_AHB2_GRP1_PERIPH AHB2 GRP1 PERIPH - * @{ - */ -#define LL_AHB2_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(DCMI) -#define LL_AHB2_GRP1_PERIPH_DCMI RCC_AHB2ENR_DCMIEN -#endif /* DCMI */ -#if defined(CRYP) -#define LL_AHB2_GRP1_PERIPH_CRYP RCC_AHB2ENR_CRYPEN -#endif /* CRYP */ -#if defined(AES) -#define LL_AHB2_GRP1_PERIPH_AES RCC_AHB2ENR_AESEN -#endif /* AES */ -#if defined(HASH) -#define LL_AHB2_GRP1_PERIPH_HASH RCC_AHB2ENR_HASHEN -#endif /* HASH */ -#if defined(RCC_AHB2ENR_RNGEN) -#define LL_AHB2_GRP1_PERIPH_RNG RCC_AHB2ENR_RNGEN -#endif /* RCC_AHB2ENR_RNGEN */ -#if defined(USB_OTG_FS) -#define LL_AHB2_GRP1_PERIPH_OTGFS RCC_AHB2ENR_OTGFSEN -#endif /* USB_OTG_FS */ -/** - * @} - */ -#endif /* RCC_AHB2_SUPPORT */ - -#if defined(RCC_AHB3_SUPPORT) -/** @defgroup BUS_LL_EC_AHB3_GRP1_PERIPH AHB3 GRP1 PERIPH - * @{ - */ -#define LL_AHB3_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(FSMC_Bank1) -#define LL_AHB3_GRP1_PERIPH_FSMC RCC_AHB3ENR_FSMCEN -#endif /* FSMC_Bank1 */ -#if defined(FMC_Bank1) -#define LL_AHB3_GRP1_PERIPH_FMC RCC_AHB3ENR_FMCEN -#endif /* FMC_Bank1 */ -#if defined(QUADSPI) -#define LL_AHB3_GRP1_PERIPH_QSPI RCC_AHB3ENR_QSPIEN -#endif /* QUADSPI */ -/** - * @} - */ -#endif /* RCC_AHB3_SUPPORT */ - -/** @defgroup BUS_LL_EC_APB1_GRP1_PERIPH APB1 GRP1 PERIPH - * @{ - */ -#define LL_APB1_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(TIM2) -#define LL_APB1_GRP1_PERIPH_TIM2 RCC_APB1ENR_TIM2EN -#endif /* TIM2 */ -#if defined(TIM3) -#define LL_APB1_GRP1_PERIPH_TIM3 RCC_APB1ENR_TIM3EN -#endif /* TIM3 */ -#if defined(TIM4) -#define LL_APB1_GRP1_PERIPH_TIM4 RCC_APB1ENR_TIM4EN -#endif /* TIM4 */ -#define LL_APB1_GRP1_PERIPH_TIM5 RCC_APB1ENR_TIM5EN -#if defined(TIM6) -#define LL_APB1_GRP1_PERIPH_TIM6 RCC_APB1ENR_TIM6EN -#endif /* TIM6 */ -#if defined(TIM7) -#define LL_APB1_GRP1_PERIPH_TIM7 RCC_APB1ENR_TIM7EN -#endif /* TIM7 */ -#if defined(TIM12) -#define LL_APB1_GRP1_PERIPH_TIM12 RCC_APB1ENR_TIM12EN -#endif /* TIM12 */ -#if defined(TIM13) -#define LL_APB1_GRP1_PERIPH_TIM13 RCC_APB1ENR_TIM13EN -#endif /* TIM13 */ -#if defined(TIM14) -#define LL_APB1_GRP1_PERIPH_TIM14 RCC_APB1ENR_TIM14EN -#endif /* TIM14 */ -#if defined(LPTIM1) -#define LL_APB1_GRP1_PERIPH_LPTIM1 RCC_APB1ENR_LPTIM1EN -#endif /* LPTIM1 */ -#if defined(RCC_APB1ENR_RTCAPBEN) -#define LL_APB1_GRP1_PERIPH_RTCAPB RCC_APB1ENR_RTCAPBEN -#endif /* RCC_APB1ENR_RTCAPBEN */ -#define LL_APB1_GRP1_PERIPH_WWDG RCC_APB1ENR_WWDGEN -#if defined(SPI2) -#define LL_APB1_GRP1_PERIPH_SPI2 RCC_APB1ENR_SPI2EN -#endif /* SPI2 */ -#if defined(SPI3) -#define LL_APB1_GRP1_PERIPH_SPI3 RCC_APB1ENR_SPI3EN -#endif /* SPI3 */ -#if defined(SPDIFRX) -#define LL_APB1_GRP1_PERIPH_SPDIFRX RCC_APB1ENR_SPDIFRXEN -#endif /* SPDIFRX */ -#define LL_APB1_GRP1_PERIPH_USART2 RCC_APB1ENR_USART2EN -#if defined(USART3) -#define LL_APB1_GRP1_PERIPH_USART3 RCC_APB1ENR_USART3EN -#endif /* USART3 */ -#if defined(UART4) -#define LL_APB1_GRP1_PERIPH_UART4 RCC_APB1ENR_UART4EN -#endif /* UART4 */ -#if defined(UART5) -#define LL_APB1_GRP1_PERIPH_UART5 RCC_APB1ENR_UART5EN -#endif /* UART5 */ -#define LL_APB1_GRP1_PERIPH_I2C1 RCC_APB1ENR_I2C1EN -#define LL_APB1_GRP1_PERIPH_I2C2 RCC_APB1ENR_I2C2EN -#if defined(I2C3) -#define LL_APB1_GRP1_PERIPH_I2C3 RCC_APB1ENR_I2C3EN -#endif /* I2C3 */ -#if defined(FMPI2C1) -#define LL_APB1_GRP1_PERIPH_FMPI2C1 RCC_APB1ENR_FMPI2C1EN -#endif /* FMPI2C1 */ -#if defined(CAN1) -#define LL_APB1_GRP1_PERIPH_CAN1 RCC_APB1ENR_CAN1EN -#endif /* CAN1 */ -#if defined(CAN2) -#define LL_APB1_GRP1_PERIPH_CAN2 RCC_APB1ENR_CAN2EN -#endif /* CAN2 */ -#if defined(CAN3) -#define LL_APB1_GRP1_PERIPH_CAN3 RCC_APB1ENR_CAN3EN -#endif /* CAN3 */ -#if defined(CEC) -#define LL_APB1_GRP1_PERIPH_CEC RCC_APB1ENR_CECEN -#endif /* CEC */ -#define LL_APB1_GRP1_PERIPH_PWR RCC_APB1ENR_PWREN -#if defined(DAC1) -#define LL_APB1_GRP1_PERIPH_DAC1 RCC_APB1ENR_DACEN -#endif /* DAC1 */ -#if defined(UART7) -#define LL_APB1_GRP1_PERIPH_UART7 RCC_APB1ENR_UART7EN -#endif /* UART7 */ -#if defined(UART8) -#define LL_APB1_GRP1_PERIPH_UART8 RCC_APB1ENR_UART8EN -#endif /* UART8 */ -/** - * @} - */ - -/** @defgroup BUS_LL_EC_APB2_GRP1_PERIPH APB2 GRP1 PERIPH - * @{ - */ -#define LL_APB2_GRP1_PERIPH_ALL 0xFFFFFFFFU -#define LL_APB2_GRP1_PERIPH_TIM1 RCC_APB2ENR_TIM1EN -#if defined(TIM8) -#define LL_APB2_GRP1_PERIPH_TIM8 RCC_APB2ENR_TIM8EN -#endif /* TIM8 */ -#define LL_APB2_GRP1_PERIPH_USART1 RCC_APB2ENR_USART1EN -#if defined(USART6) -#define LL_APB2_GRP1_PERIPH_USART6 RCC_APB2ENR_USART6EN -#endif /* USART6 */ -#if defined(UART9) -#define LL_APB2_GRP1_PERIPH_UART9 RCC_APB2ENR_UART9EN -#endif /* UART9 */ -#if defined(UART10) -#define LL_APB2_GRP1_PERIPH_UART10 RCC_APB2ENR_UART10EN -#endif /* UART10 */ -#define LL_APB2_GRP1_PERIPH_ADC1 RCC_APB2ENR_ADC1EN -#if defined(ADC2) -#define LL_APB2_GRP1_PERIPH_ADC2 RCC_APB2ENR_ADC2EN -#endif /* ADC2 */ -#if defined(ADC3) -#define LL_APB2_GRP1_PERIPH_ADC3 RCC_APB2ENR_ADC3EN -#endif /* ADC3 */ -#if defined(SDIO) -#define LL_APB2_GRP1_PERIPH_SDIO RCC_APB2ENR_SDIOEN -#endif /* SDIO */ -#define LL_APB2_GRP1_PERIPH_SPI1 RCC_APB2ENR_SPI1EN -#if defined(SPI4) -#define LL_APB2_GRP1_PERIPH_SPI4 RCC_APB2ENR_SPI4EN -#endif /* SPI4 */ -#define LL_APB2_GRP1_PERIPH_SYSCFG RCC_APB2ENR_SYSCFGEN -#if defined(RCC_APB2ENR_EXTITEN) -#define LL_APB2_GRP1_PERIPH_EXTI RCC_APB2ENR_EXTITEN -#endif /* RCC_APB2ENR_EXTITEN */ -#define LL_APB2_GRP1_PERIPH_TIM9 RCC_APB2ENR_TIM9EN -#if defined(TIM10) -#define LL_APB2_GRP1_PERIPH_TIM10 RCC_APB2ENR_TIM10EN -#endif /* TIM10 */ -#define LL_APB2_GRP1_PERIPH_TIM11 RCC_APB2ENR_TIM11EN -#if defined(SPI5) -#define LL_APB2_GRP1_PERIPH_SPI5 RCC_APB2ENR_SPI5EN -#endif /* SPI5 */ -#if defined(SPI6) -#define LL_APB2_GRP1_PERIPH_SPI6 RCC_APB2ENR_SPI6EN -#endif /* SPI6 */ -#if defined(SAI1) -#define LL_APB2_GRP1_PERIPH_SAI1 RCC_APB2ENR_SAI1EN -#endif /* SAI1 */ -#if defined(SAI2) -#define LL_APB2_GRP1_PERIPH_SAI2 RCC_APB2ENR_SAI2EN -#endif /* SAI2 */ -#if defined(LTDC) -#define LL_APB2_GRP1_PERIPH_LTDC RCC_APB2ENR_LTDCEN -#endif /* LTDC */ -#if defined(DSI) -#define LL_APB2_GRP1_PERIPH_DSI RCC_APB2ENR_DSIEN -#endif /* DSI */ -#if defined(DFSDM1_Channel0) -#define LL_APB2_GRP1_PERIPH_DFSDM1 RCC_APB2ENR_DFSDM1EN -#endif /* DFSDM1_Channel0 */ -#if defined(DFSDM2_Channel0) -#define LL_APB2_GRP1_PERIPH_DFSDM2 RCC_APB2ENR_DFSDM2EN -#endif /* DFSDM2_Channel0 */ -#define LL_APB2_GRP1_PERIPH_ADC RCC_APB2RSTR_ADCRST -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup BUS_LL_Exported_Functions BUS Exported Functions - * @{ - */ - -/** @defgroup BUS_LL_EF_AHB1 AHB1 - * @{ - */ - -/** - * @brief Enable AHB1 peripherals clock. - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB1ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB1ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB1 peripheral clock is enabled or not - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB1_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB1ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB1 peripherals clock. - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1ENR, Periphs); -} - -/** - * @brief Force AHB1 peripherals reset. - * @rmtoll AHB1RSTR GPIOARST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOBRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOCRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIODRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOERST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOFRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOGRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOHRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOIRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOJRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOKRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR CRCRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA1RST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA2RST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR RNGRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA2DRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR ETHMACRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR OTGHSRST LL_AHB1_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_ALL - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB1RSTR, Periphs); -} - -/** - * @brief Release AHB1 peripherals reset. - * @rmtoll AHB1RSTR GPIOARST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOBRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOCRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIODRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOERST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOFRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOGRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOHRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOIRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOJRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOKRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR CRCRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA1RST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA2RST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR RNGRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA2DRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR ETHMACRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR OTGHSRST LL_AHB1_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_ALL - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1RSTR, Periphs); -} - -/** - * @brief Enable AHB1 peripheral clocks in low-power mode - * @rmtoll AHB1LPENR GPIOALPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOBLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOCLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIODLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOELPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOFLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOGLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOHLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOILPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOJLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOKLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR CRCLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR FLITFLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM1LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM2LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM3LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA1LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA2LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA2DLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR RNGLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACTXLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACRXLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACPTPLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR OTGHSLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR OTGHSULPILPEN LL_AHB1_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_FLITF - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM1 - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM2 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM3 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB1LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB1LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB1 peripheral clocks in low-power mode - * @rmtoll AHB1LPENR GPIOALPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOBLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOCLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIODLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOELPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOFLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOGLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOHLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOILPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOJLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOKLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR CRCLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR FLITFLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM1LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM2LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM3LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA1LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA2LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA2DLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR RNGLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACTXLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACRXLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACPTPLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR OTGHSLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR OTGHSULPILPEN LL_AHB1_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_FLITF - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM1 - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM2 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM3 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1LPENR, Periphs); -} - -/** - * @} - */ - -#if defined(RCC_AHB2_SUPPORT) -/** @defgroup BUS_LL_EF_AHB2 AHB2 - * @{ - */ - -/** - * @brief Enable AHB2 peripherals clock. - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB2ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB2ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB2 peripheral clock is enabled or not - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB2_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB2ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB2 peripherals clock. - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2ENR, Periphs); -} - -/** - * @brief Force AHB2 peripherals reset. - * @rmtoll AHB2RSTR DCMIRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR CRYPRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR AESRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR HASHRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR RNGRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR OTGFSRST LL_AHB2_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB2RSTR, Periphs); -} - -/** - * @brief Release AHB2 peripherals reset. - * @rmtoll AHB2RSTR DCMIRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR CRYPRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR AESRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR HASHRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR RNGRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR OTGFSRST LL_AHB2_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2RSTR, Periphs); -} - -/** - * @brief Enable AHB2 peripheral clocks in low-power mode - * @rmtoll AHB2LPENR DCMILPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR CRYPLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR AESLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR HASHLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR RNGLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR OTGFSLPEN LL_AHB2_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB2LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB2LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB2 peripheral clocks in low-power mode - * @rmtoll AHB2LPENR DCMILPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR CRYPLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR AESLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR HASHLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR RNGLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR OTGFSLPEN LL_AHB2_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2LPENR, Periphs); -} - -/** - * @} - */ -#endif /* RCC_AHB2_SUPPORT */ - -#if defined(RCC_AHB3_SUPPORT) -/** @defgroup BUS_LL_EF_AHB3 AHB3 - * @{ - */ - -/** - * @brief Enable AHB3 peripherals clock. - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_EnableClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_EnableClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB3ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB3ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB3 peripheral clock is enabled or not - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_IsEnabledClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_IsEnabledClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB3_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB3ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB3 peripherals clock. - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_DisableClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_DisableClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3ENR, Periphs); -} - -/** - * @brief Force AHB3 peripherals reset. - * @rmtoll AHB3RSTR FMCRST LL_AHB3_GRP1_ForceReset\n - * AHB3RSTR FSMCRST LL_AHB3_GRP1_ForceReset\n - * AHB3RSTR QSPIRST LL_AHB3_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_ALL - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB3RSTR, Periphs); -} - -/** - * @brief Release AHB3 peripherals reset. - * @rmtoll AHB3RSTR FMCRST LL_AHB3_GRP1_ReleaseReset\n - * AHB3RSTR FSMCRST LL_AHB3_GRP1_ReleaseReset\n - * AHB3RSTR QSPIRST LL_AHB3_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3RSTR, Periphs); -} - -/** - * @brief Enable AHB3 peripheral clocks in low-power mode - * @rmtoll AHB3LPENR FMCLPEN LL_AHB3_GRP1_EnableClockLowPower\n - * AHB3LPENR FSMCLPEN LL_AHB3_GRP1_EnableClockLowPower\n - * AHB3LPENR QSPILPEN LL_AHB3_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB3LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB3LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB3 peripheral clocks in low-power mode - * @rmtoll AHB3LPENR FMCLPEN LL_AHB3_GRP1_DisableClockLowPower\n - * AHB3LPENR FSMCLPEN LL_AHB3_GRP1_DisableClockLowPower\n - * AHB3LPENR QSPILPEN LL_AHB3_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3LPENR, Periphs); -} - -/** - * @} - */ -#endif /* RCC_AHB3_SUPPORT */ - -/** @defgroup BUS_LL_EF_APB1 APB1 - * @{ - */ - -/** - * @brief Enable APB1 peripherals clock. - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_EnableClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_EnableClock\n - * APB1ENR USART2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR USART3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART4EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART5EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CECEN LL_APB1_GRP1_EnableClock\n - * APB1ENR PWREN LL_APB1_GRP1_EnableClock\n - * APB1ENR DACEN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART7EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART8EN LL_APB1_GRP1_EnableClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB1ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB1ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if APB1 peripheral clock is enabled or not - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR USART2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR USART3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART4EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART5EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CECEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR PWREN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR DACEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART7EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART8EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_APB1_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->APB1ENR, Periphs) == Periphs); -} - -/** - * @brief Disable APB1 peripherals clock. - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_DisableClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_DisableClock\n - * APB1ENR USART2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR USART3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART4EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART5EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CECEN LL_APB1_GRP1_DisableClock\n - * APB1ENR PWREN LL_APB1_GRP1_DisableClock\n - * APB1ENR DACEN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART7EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART8EN LL_APB1_GRP1_DisableClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1ENR, Periphs); -} - -/** - * @brief Force APB1 peripherals reset. - * @rmtoll APB1RSTR TIM2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM4RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM5RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM6RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM7RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM12RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM13RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM14RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR LPTIM1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR WWDGRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPI2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPI3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPDIFRXRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR USART2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR USART3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART4RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART5RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR FMPI2C1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CECRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR PWRRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR DACRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART7RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART8RST LL_APB1_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->APB1RSTR, Periphs); -} - -/** - * @brief Release APB1 peripherals reset. - * @rmtoll APB1RSTR TIM2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM4RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM5RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM6RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM7RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM12RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM13RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM14RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR LPTIM1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR WWDGRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPI2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPI3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPDIFRXRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR USART2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR USART3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART4RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART5RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR FMPI2C1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CECRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR PWRRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR DACRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART7RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART8RST LL_APB1_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1RSTR, Periphs); -} - -/** - * @brief Enable APB1 peripheral clocks in low-power mode - * @rmtoll APB1LPENR TIM2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM4LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM5LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM6LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM7LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM12LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM13LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM14LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR LPTIM1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR WWDGLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPI2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPI3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPDIFRXLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR USART2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR USART3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART4LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART5LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR FMPI2C1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CECLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR PWRLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR DACLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART7LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART8LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR RTCAPBLPEN LL_APB1_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB1LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB1LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable APB1 peripheral clocks in low-power mode - * @rmtoll APB1LPENR TIM2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM4LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM5LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM6LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM7LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM12LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM13LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM14LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR LPTIM1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR WWDGLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPI2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPI3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPDIFRXLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR USART2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR USART3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART4LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART5LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR FMPI2C1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CECLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR PWRLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR DACLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART7LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART8LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR RTCAPBLPEN LL_APB1_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1LPENR, Periphs); -} - -/** - * @} - */ - -/** @defgroup BUS_LL_EF_APB2 APB2 - * @{ - */ - -/** - * @brief Enable APB2 peripherals clock. - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_EnableClock\n - * APB2ENR USART1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR USART6EN LL_APB2_GRP1_EnableClock\n - * APB2ENR UART9EN LL_APB2_GRP1_EnableClock\n - * APB2ENR UART10EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_EnableClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_EnableClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_EnableClock\n - * APB2ENR DSIEN LL_APB2_GRP1_EnableClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB2ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB2ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if APB2 peripheral clock is enabled or not - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR USART1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR USART6EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR UART9EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR UART10EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DSIEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_APB2_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->APB2ENR, Periphs) == Periphs); -} - -/** - * @brief Disable APB2 peripherals clock. - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_DisableClock\n - * APB2ENR USART1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR USART6EN LL_APB2_GRP1_DisableClock\n - * APB2ENR UART9EN LL_APB2_GRP1_DisableClock\n - * APB2ENR UART10EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_DisableClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_DisableClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_DisableClock\n - * APB2ENR DSIEN LL_APB2_GRP1_DisableClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2ENR, Periphs); -} - -/** - * @brief Force APB2 peripherals reset. - * @rmtoll APB2RSTR TIM1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM8RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR USART1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR USART6RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR UART9RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR UART10RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR ADCRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SDIORST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI4RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SYSCFGRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM9RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM10RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM11RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI5RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI6RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SAI1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SAI2RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR LTDCRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DSIRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DFSDM1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DFSDM2RST LL_APB2_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_ALL - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->APB2RSTR, Periphs); -} - -/** - * @brief Release APB2 peripherals reset. - * @rmtoll APB2RSTR TIM1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM8RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR USART1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR USART6RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR UART9RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR UART10RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR ADCRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SDIORST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI4RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SYSCFGRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM9RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM10RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM11RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI5RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI6RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SAI1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SAI2RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR LTDCRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DSIRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DFSDM1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DFSDM2RST LL_APB2_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_ALL - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2RSTR, Periphs); -} - -/** - * @brief Enable APB2 peripheral clocks in low-power mode - * @rmtoll APB2LPENR TIM1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM8LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR USART1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR USART6LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR UART9LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR UART10LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC2LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC3LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SDIOLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI4LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SYSCFGLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR EXTITLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM9LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM10LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM11LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI5LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI6LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SAI1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SAI2LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR LTDCLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DFSDM1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DFSDM2LPEN LL_APB2_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB2LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB2LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable APB2 peripheral clocks in low-power mode - * @rmtoll APB2LPENR TIM1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM8LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR USART1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR USART6LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR UART9LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR UART10LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC2LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC3LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SDIOLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI4LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SYSCFGLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR EXTITLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM9LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM10LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM11LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI5LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI6LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SAI1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SAI2LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR LTDCLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DFSDM1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DFSDM2LPEN LL_APB2_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2LPENR, Periphs); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RCC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_BUS_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h deleted file mode 100644 index eddcc97aea62413..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h +++ /dev/null @@ -1,640 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_cortex.h - * @author MCD Application Team - * @brief Header file of CORTEX LL module. - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL CORTEX driver contains a set of generic APIs that can be - used by user: - (+) SYSTICK configuration used by LL_mDelay and LL_Init1msTick - functions - (+) Low power mode configuration (SCB register of Cortex-MCU) - (+) MPU API to configure and enable regions - (MPU services provided only on some devices) - (+) API to access to MCU info (CPUID register) - (+) API to enable fault handler (SHCSR accesses) - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_CORTEX_H -#define __STM32F4xx_LL_CORTEX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -/** @defgroup CORTEX_LL CORTEX - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CORTEX_LL_Exported_Constants CORTEX Exported Constants - * @{ - */ - -/** @defgroup CORTEX_LL_EC_CLKSOURCE_HCLK SYSTICK Clock Source - * @{ - */ -#define LL_SYSTICK_CLKSOURCE_HCLK_DIV8 0x00000000U /*!< AHB clock divided by 8 selected as SysTick clock source.*/ -#define LL_SYSTICK_CLKSOURCE_HCLK SysTick_CTRL_CLKSOURCE_Msk /*!< AHB clock selected as SysTick clock source. */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_FAULT Handler Fault type - * @{ - */ -#define LL_HANDLER_FAULT_USG SCB_SHCSR_USGFAULTENA_Msk /*!< Usage fault */ -#define LL_HANDLER_FAULT_BUS SCB_SHCSR_BUSFAULTENA_Msk /*!< Bus fault */ -#define LL_HANDLER_FAULT_MEM SCB_SHCSR_MEMFAULTENA_Msk /*!< Memory management fault */ -/** - * @} - */ - -#if __MPU_PRESENT - -/** @defgroup CORTEX_LL_EC_CTRL_HFNMI_PRIVDEF MPU Control - * @{ - */ -#define LL_MPU_CTRL_HFNMI_PRIVDEF_NONE 0x00000000U /*!< Disable NMI and privileged SW access */ -#define LL_MPU_CTRL_HARDFAULT_NMI MPU_CTRL_HFNMIENA_Msk /*!< Enables the operation of MPU during hard fault, NMI, and FAULTMASK handlers */ -#define LL_MPU_CTRL_PRIVILEGED_DEFAULT MPU_CTRL_PRIVDEFENA_Msk /*!< Enable privileged software access to default memory map */ -#define LL_MPU_CTRL_HFNMI_PRIVDEF (MPU_CTRL_HFNMIENA_Msk | MPU_CTRL_PRIVDEFENA_Msk) /*!< Enable NMI and privileged SW access */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION MPU Region Number - * @{ - */ -#define LL_MPU_REGION_NUMBER0 0x00U /*!< REGION Number 0 */ -#define LL_MPU_REGION_NUMBER1 0x01U /*!< REGION Number 1 */ -#define LL_MPU_REGION_NUMBER2 0x02U /*!< REGION Number 2 */ -#define LL_MPU_REGION_NUMBER3 0x03U /*!< REGION Number 3 */ -#define LL_MPU_REGION_NUMBER4 0x04U /*!< REGION Number 4 */ -#define LL_MPU_REGION_NUMBER5 0x05U /*!< REGION Number 5 */ -#define LL_MPU_REGION_NUMBER6 0x06U /*!< REGION Number 6 */ -#define LL_MPU_REGION_NUMBER7 0x07U /*!< REGION Number 7 */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION_SIZE MPU Region Size - * @{ - */ -#define LL_MPU_REGION_SIZE_32B (0x04U << MPU_RASR_SIZE_Pos) /*!< 32B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64B (0x05U << MPU_RASR_SIZE_Pos) /*!< 64B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128B (0x06U << MPU_RASR_SIZE_Pos) /*!< 128B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256B (0x07U << MPU_RASR_SIZE_Pos) /*!< 256B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512B (0x08U << MPU_RASR_SIZE_Pos) /*!< 512B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1KB (0x09U << MPU_RASR_SIZE_Pos) /*!< 1KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2KB (0x0AU << MPU_RASR_SIZE_Pos) /*!< 2KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4KB (0x0BU << MPU_RASR_SIZE_Pos) /*!< 4KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_8KB (0x0CU << MPU_RASR_SIZE_Pos) /*!< 8KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_16KB (0x0DU << MPU_RASR_SIZE_Pos) /*!< 16KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_32KB (0x0EU << MPU_RASR_SIZE_Pos) /*!< 32KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64KB (0x0FU << MPU_RASR_SIZE_Pos) /*!< 64KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128KB (0x10U << MPU_RASR_SIZE_Pos) /*!< 128KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256KB (0x11U << MPU_RASR_SIZE_Pos) /*!< 256KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512KB (0x12U << MPU_RASR_SIZE_Pos) /*!< 512KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1MB (0x13U << MPU_RASR_SIZE_Pos) /*!< 1MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2MB (0x14U << MPU_RASR_SIZE_Pos) /*!< 2MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4MB (0x15U << MPU_RASR_SIZE_Pos) /*!< 4MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_8MB (0x16U << MPU_RASR_SIZE_Pos) /*!< 8MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_16MB (0x17U << MPU_RASR_SIZE_Pos) /*!< 16MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_32MB (0x18U << MPU_RASR_SIZE_Pos) /*!< 32MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64MB (0x19U << MPU_RASR_SIZE_Pos) /*!< 64MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128MB (0x1AU << MPU_RASR_SIZE_Pos) /*!< 128MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256MB (0x1BU << MPU_RASR_SIZE_Pos) /*!< 256MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512MB (0x1CU << MPU_RASR_SIZE_Pos) /*!< 512MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1GB (0x1DU << MPU_RASR_SIZE_Pos) /*!< 1GB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2GB (0x1EU << MPU_RASR_SIZE_Pos) /*!< 2GB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4GB (0x1FU << MPU_RASR_SIZE_Pos) /*!< 4GB Size of the MPU protection region */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION_PRIVILEDGES MPU Region Privileges - * @{ - */ -#define LL_MPU_REGION_NO_ACCESS (0x00U << MPU_RASR_AP_Pos) /*!< No access*/ -#define LL_MPU_REGION_PRIV_RW (0x01U << MPU_RASR_AP_Pos) /*!< RW privileged (privileged access only)*/ -#define LL_MPU_REGION_PRIV_RW_URO (0x02U << MPU_RASR_AP_Pos) /*!< RW privileged - RO user (Write in a user program generates a fault) */ -#define LL_MPU_REGION_FULL_ACCESS (0x03U << MPU_RASR_AP_Pos) /*!< RW privileged & user (Full access) */ -#define LL_MPU_REGION_PRIV_RO (0x05U << MPU_RASR_AP_Pos) /*!< RO privileged (privileged read only)*/ -#define LL_MPU_REGION_PRIV_RO_URO (0x06U << MPU_RASR_AP_Pos) /*!< RO privileged & user (read only) */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_TEX MPU TEX Level - * @{ - */ -#define LL_MPU_TEX_LEVEL0 (0x00U << MPU_RASR_TEX_Pos) /*!< b000 for TEX bits */ -#define LL_MPU_TEX_LEVEL1 (0x01U << MPU_RASR_TEX_Pos) /*!< b001 for TEX bits */ -#define LL_MPU_TEX_LEVEL2 (0x02U << MPU_RASR_TEX_Pos) /*!< b010 for TEX bits */ -#define LL_MPU_TEX_LEVEL4 (0x04U << MPU_RASR_TEX_Pos) /*!< b100 for TEX bits */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_INSTRUCTION_ACCESS MPU Instruction Access - * @{ - */ -#define LL_MPU_INSTRUCTION_ACCESS_ENABLE 0x00U /*!< Instruction fetches enabled */ -#define LL_MPU_INSTRUCTION_ACCESS_DISABLE MPU_RASR_XN_Msk /*!< Instruction fetches disabled*/ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_SHAREABLE_ACCESS MPU Shareable Access - * @{ - */ -#define LL_MPU_ACCESS_SHAREABLE MPU_RASR_S_Msk /*!< Shareable memory attribute */ -#define LL_MPU_ACCESS_NOT_SHAREABLE 0x00U /*!< Not Shareable memory attribute */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_CACHEABLE_ACCESS MPU Cacheable Access - * @{ - */ -#define LL_MPU_ACCESS_CACHEABLE MPU_RASR_C_Msk /*!< Cacheable memory attribute */ -#define LL_MPU_ACCESS_NOT_CACHEABLE 0x00U /*!< Not Cacheable memory attribute */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_BUFFERABLE_ACCESS MPU Bufferable Access - * @{ - */ -#define LL_MPU_ACCESS_BUFFERABLE MPU_RASR_B_Msk /*!< Bufferable memory attribute */ -#define LL_MPU_ACCESS_NOT_BUFFERABLE 0x00U /*!< Not Bufferable memory attribute */ -/** - * @} - */ -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CORTEX_LL_Exported_Functions CORTEX Exported Functions - * @{ - */ - -/** @defgroup CORTEX_LL_EF_SYSTICK SYSTICK - * @{ - */ - -/** - * @brief This function checks if the Systick counter flag is active or not. - * @note It can be used in timeout function on application side. - * @rmtoll STK_CTRL COUNTFLAG LL_SYSTICK_IsActiveCounterFlag - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSTICK_IsActiveCounterFlag(void) -{ - return ((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) == (SysTick_CTRL_COUNTFLAG_Msk)); -} - -/** - * @brief Configures the SysTick clock source - * @rmtoll STK_CTRL CLKSOURCE LL_SYSTICK_SetClkSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK_DIV8 - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_SetClkSource(uint32_t Source) -{ - if (Source == LL_SYSTICK_CLKSOURCE_HCLK) - { - SET_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); - } - else - { - CLEAR_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); - } -} - -/** - * @brief Get the SysTick clock source - * @rmtoll STK_CTRL CLKSOURCE LL_SYSTICK_GetClkSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK_DIV8 - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK - */ -__STATIC_INLINE uint32_t LL_SYSTICK_GetClkSource(void) -{ - return READ_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); -} - -/** - * @brief Enable SysTick exception request - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_EnableIT - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_EnableIT(void) -{ - SET_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk); -} - -/** - * @brief Disable SysTick exception request - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_DisableIT - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_DisableIT(void) -{ - CLEAR_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk); -} - -/** - * @brief Checks if the SYSTICK interrupt is enabled or disabled. - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_IsEnabledIT - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSTICK_IsEnabledIT(void) -{ - return (READ_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk) == (SysTick_CTRL_TICKINT_Msk)); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_LOW_POWER_MODE LOW POWER MODE - * @{ - */ - -/** - * @brief Processor uses sleep as its low power mode - * @rmtoll SCB_SCR SLEEPDEEP LL_LPM_EnableSleep - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableSleep(void) -{ - /* Clear SLEEPDEEP bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); -} - -/** - * @brief Processor uses deep sleep as its low power mode - * @rmtoll SCB_SCR SLEEPDEEP LL_LPM_EnableDeepSleep - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableDeepSleep(void) -{ - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); -} - -/** - * @brief Configures sleep-on-exit when returning from Handler mode to Thread mode. - * @note Setting this bit to 1 enables an interrupt-driven application to avoid returning to an - * empty main application. - * @rmtoll SCB_SCR SLEEPONEXIT LL_LPM_EnableSleepOnExit - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableSleepOnExit(void) -{ - /* Set SLEEPONEXIT bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Do not sleep when returning to Thread mode. - * @rmtoll SCB_SCR SLEEPONEXIT LL_LPM_DisableSleepOnExit - * @retval None - */ -__STATIC_INLINE void LL_LPM_DisableSleepOnExit(void) -{ - /* Clear SLEEPONEXIT bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Enabled events and all interrupts, including disabled interrupts, can wakeup the - * processor. - * @rmtoll SCB_SCR SEVEONPEND LL_LPM_EnableEventOnPend - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableEventOnPend(void) -{ - /* Set SEVEONPEND bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @brief Only enabled interrupts or events can wakeup the processor, disabled interrupts are - * excluded - * @rmtoll SCB_SCR SEVEONPEND LL_LPM_DisableEventOnPend - * @retval None - */ -__STATIC_INLINE void LL_LPM_DisableEventOnPend(void) -{ - /* Clear SEVEONPEND bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_HANDLER HANDLER - * @{ - */ - -/** - * @brief Enable a fault in System handler control register (SHCSR) - * @rmtoll SCB_SHCSR MEMFAULTENA LL_HANDLER_EnableFault - * @param Fault This parameter can be a combination of the following values: - * @arg @ref LL_HANDLER_FAULT_USG - * @arg @ref LL_HANDLER_FAULT_BUS - * @arg @ref LL_HANDLER_FAULT_MEM - * @retval None - */ -__STATIC_INLINE void LL_HANDLER_EnableFault(uint32_t Fault) -{ - /* Enable the system handler fault */ - SET_BIT(SCB->SHCSR, Fault); -} - -/** - * @brief Disable a fault in System handler control register (SHCSR) - * @rmtoll SCB_SHCSR MEMFAULTENA LL_HANDLER_DisableFault - * @param Fault This parameter can be a combination of the following values: - * @arg @ref LL_HANDLER_FAULT_USG - * @arg @ref LL_HANDLER_FAULT_BUS - * @arg @ref LL_HANDLER_FAULT_MEM - * @retval None - */ -__STATIC_INLINE void LL_HANDLER_DisableFault(uint32_t Fault) -{ - /* Disable the system handler fault */ - CLEAR_BIT(SCB->SHCSR, Fault); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_MCU_INFO MCU INFO - * @{ - */ - -/** - * @brief Get Implementer code - * @rmtoll SCB_CPUID IMPLEMENTER LL_CPUID_GetImplementer - * @retval Value should be equal to 0x41 for ARM - */ -__STATIC_INLINE uint32_t LL_CPUID_GetImplementer(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_IMPLEMENTER_Msk) >> SCB_CPUID_IMPLEMENTER_Pos); -} - -/** - * @brief Get Variant number (The r value in the rnpn product revision identifier) - * @rmtoll SCB_CPUID VARIANT LL_CPUID_GetVariant - * @retval Value between 0 and 255 (0x0: revision 0) - */ -__STATIC_INLINE uint32_t LL_CPUID_GetVariant(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_VARIANT_Msk) >> SCB_CPUID_VARIANT_Pos); -} - -/** - * @brief Get Constant number - * @rmtoll SCB_CPUID ARCHITECTURE LL_CPUID_GetConstant - * @retval Value should be equal to 0xF for Cortex-M4 devices - */ -__STATIC_INLINE uint32_t LL_CPUID_GetConstant(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_ARCHITECTURE_Msk) >> SCB_CPUID_ARCHITECTURE_Pos); -} - -/** - * @brief Get Part number - * @rmtoll SCB_CPUID PARTNO LL_CPUID_GetParNo - * @retval Value should be equal to 0xC24 for Cortex-M4 - */ -__STATIC_INLINE uint32_t LL_CPUID_GetParNo(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_PARTNO_Msk) >> SCB_CPUID_PARTNO_Pos); -} - -/** - * @brief Get Revision number (The p value in the rnpn product revision identifier, indicates patch release) - * @rmtoll SCB_CPUID REVISION LL_CPUID_GetRevision - * @retval Value between 0 and 255 (0x1: patch 1) - */ -__STATIC_INLINE uint32_t LL_CPUID_GetRevision(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_REVISION_Msk) >> SCB_CPUID_REVISION_Pos); -} - -/** - * @} - */ - -#if __MPU_PRESENT -/** @defgroup CORTEX_LL_EF_MPU MPU - * @{ - */ - -/** - * @brief Enable MPU with input options - * @rmtoll MPU_CTRL ENABLE LL_MPU_Enable - * @param Options This parameter can be one of the following values: - * @arg @ref LL_MPU_CTRL_HFNMI_PRIVDEF_NONE - * @arg @ref LL_MPU_CTRL_HARDFAULT_NMI - * @arg @ref LL_MPU_CTRL_PRIVILEGED_DEFAULT - * @arg @ref LL_MPU_CTRL_HFNMI_PRIVDEF - * @retval None - */ -__STATIC_INLINE void LL_MPU_Enable(uint32_t Options) -{ - /* Enable the MPU*/ - WRITE_REG(MPU->CTRL, (MPU_CTRL_ENABLE_Msk | Options)); - /* Ensure MPU settings take effects */ - __DSB(); - /* Sequence instruction fetches using update settings */ - __ISB(); -} - -/** - * @brief Disable MPU - * @rmtoll MPU_CTRL ENABLE LL_MPU_Disable - * @retval None - */ -__STATIC_INLINE void LL_MPU_Disable(void) -{ - /* Make sure outstanding transfers are done */ - __DMB(); - /* Disable MPU*/ - WRITE_REG(MPU->CTRL, 0U); -} - -/** - * @brief Check if MPU is enabled or not - * @rmtoll MPU_CTRL ENABLE LL_MPU_IsEnabled - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_MPU_IsEnabled(void) -{ - return (READ_BIT(MPU->CTRL, MPU_CTRL_ENABLE_Msk) == (MPU_CTRL_ENABLE_Msk)); -} - -/** - * @brief Enable a MPU region - * @rmtoll MPU_RASR ENABLE LL_MPU_EnableRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @retval None - */ -__STATIC_INLINE void LL_MPU_EnableRegion(uint32_t Region) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Enable the MPU region */ - SET_BIT(MPU->RASR, MPU_RASR_ENABLE_Msk); -} - -/** - * @brief Configure and enable a region - * @rmtoll MPU_RNR REGION LL_MPU_ConfigRegion\n - * MPU_RBAR REGION LL_MPU_ConfigRegion\n - * MPU_RBAR ADDR LL_MPU_ConfigRegion\n - * MPU_RASR XN LL_MPU_ConfigRegion\n - * MPU_RASR AP LL_MPU_ConfigRegion\n - * MPU_RASR S LL_MPU_ConfigRegion\n - * MPU_RASR C LL_MPU_ConfigRegion\n - * MPU_RASR B LL_MPU_ConfigRegion\n - * MPU_RASR SIZE LL_MPU_ConfigRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @param Address Value of region base address - * @param SubRegionDisable Sub-region disable value between Min_Data = 0x00 and Max_Data = 0xFF - * @param Attributes This parameter can be a combination of the following values: - * @arg @ref LL_MPU_REGION_SIZE_32B or @ref LL_MPU_REGION_SIZE_64B or @ref LL_MPU_REGION_SIZE_128B or @ref LL_MPU_REGION_SIZE_256B or @ref LL_MPU_REGION_SIZE_512B - * or @ref LL_MPU_REGION_SIZE_1KB or @ref LL_MPU_REGION_SIZE_2KB or @ref LL_MPU_REGION_SIZE_4KB or @ref LL_MPU_REGION_SIZE_8KB or @ref LL_MPU_REGION_SIZE_16KB - * or @ref LL_MPU_REGION_SIZE_32KB or @ref LL_MPU_REGION_SIZE_64KB or @ref LL_MPU_REGION_SIZE_128KB or @ref LL_MPU_REGION_SIZE_256KB or @ref LL_MPU_REGION_SIZE_512KB - * or @ref LL_MPU_REGION_SIZE_1MB or @ref LL_MPU_REGION_SIZE_2MB or @ref LL_MPU_REGION_SIZE_4MB or @ref LL_MPU_REGION_SIZE_8MB or @ref LL_MPU_REGION_SIZE_16MB - * or @ref LL_MPU_REGION_SIZE_32MB or @ref LL_MPU_REGION_SIZE_64MB or @ref LL_MPU_REGION_SIZE_128MB or @ref LL_MPU_REGION_SIZE_256MB or @ref LL_MPU_REGION_SIZE_512MB - * or @ref LL_MPU_REGION_SIZE_1GB or @ref LL_MPU_REGION_SIZE_2GB or @ref LL_MPU_REGION_SIZE_4GB - * @arg @ref LL_MPU_REGION_NO_ACCESS or @ref LL_MPU_REGION_PRIV_RW or @ref LL_MPU_REGION_PRIV_RW_URO or @ref LL_MPU_REGION_FULL_ACCESS - * or @ref LL_MPU_REGION_PRIV_RO or @ref LL_MPU_REGION_PRIV_RO_URO - * @arg @ref LL_MPU_TEX_LEVEL0 or @ref LL_MPU_TEX_LEVEL1 or @ref LL_MPU_TEX_LEVEL2 or @ref LL_MPU_TEX_LEVEL4 - * @arg @ref LL_MPU_INSTRUCTION_ACCESS_ENABLE or @ref LL_MPU_INSTRUCTION_ACCESS_DISABLE - * @arg @ref LL_MPU_ACCESS_SHAREABLE or @ref LL_MPU_ACCESS_NOT_SHAREABLE - * @arg @ref LL_MPU_ACCESS_CACHEABLE or @ref LL_MPU_ACCESS_NOT_CACHEABLE - * @arg @ref LL_MPU_ACCESS_BUFFERABLE or @ref LL_MPU_ACCESS_NOT_BUFFERABLE - * @retval None - */ -__STATIC_INLINE void LL_MPU_ConfigRegion(uint32_t Region, uint32_t SubRegionDisable, uint32_t Address, uint32_t Attributes) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Set base address */ - WRITE_REG(MPU->RBAR, (Address & 0xFFFFFFE0U)); - /* Configure MPU */ - WRITE_REG(MPU->RASR, (MPU_RASR_ENABLE_Msk | Attributes | SubRegionDisable << MPU_RASR_SRD_Pos)); -} - -/** - * @brief Disable a region - * @rmtoll MPU_RNR REGION LL_MPU_DisableRegion\n - * MPU_RASR ENABLE LL_MPU_DisableRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @retval None - */ -__STATIC_INLINE void LL_MPU_DisableRegion(uint32_t Region) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Disable the MPU region */ - CLEAR_BIT(MPU->RASR, MPU_RASR_ENABLE_Msk); -} - -/** - * @} - */ - -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_CORTEX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_crc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_crc.h deleted file mode 100644 index 2d05b679495b0a4..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_crc.h +++ /dev/null @@ -1,204 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_crc.h - * @author MCD Application Team - * @brief Header file of CRC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_CRC_H -#define STM32F4xx_LL_CRC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(CRC) - -/** @defgroup CRC_LL CRC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CRC_LL_Exported_Constants CRC Exported Constants - * @{ - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup CRC_LL_Exported_Macros CRC Exported Macros - * @{ - */ - -/** @defgroup CRC_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in CRC register - * @param __INSTANCE__ CRC Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_CRC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, __VALUE__) - -/** - * @brief Read a value in CRC register - * @param __INSTANCE__ CRC Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_CRC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CRC_LL_Exported_Functions CRC Exported Functions - * @{ - */ - -/** @defgroup CRC_LL_EF_Configuration CRC Configuration functions - * @{ - */ - -/** - * @brief Reset the CRC calculation unit. - * @note If Programmable Initial CRC value feature - * is available, also set the Data Register to the value stored in the - * CRC_INIT register, otherwise, reset Data Register to its default value. - * @rmtoll CR RESET LL_CRC_ResetCRCCalculationUnit - * @param CRCx CRC Instance - * @retval None - */ -__STATIC_INLINE void LL_CRC_ResetCRCCalculationUnit(CRC_TypeDef *CRCx) -{ - SET_BIT(CRCx->CR, CRC_CR_RESET); -} - -/** - * @} - */ - -/** @defgroup CRC_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Write given 32-bit data to the CRC calculator - * @rmtoll DR DR LL_CRC_FeedData32 - * @param CRCx CRC Instance - * @param InData value to be provided to CRC calculator between between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_CRC_FeedData32(CRC_TypeDef *CRCx, uint32_t InData) -{ - WRITE_REG(CRCx->DR, InData); -} - -/** - * @brief Return current CRC calculation result. 32 bits value is returned. - * @rmtoll DR DR LL_CRC_ReadData32 - * @param CRCx CRC Instance - * @retval Current CRC calculation result as stored in CRC_DR register (32 bits). - */ -__STATIC_INLINE uint32_t LL_CRC_ReadData32(CRC_TypeDef *CRCx) -{ - return (uint32_t)(READ_REG(CRCx->DR)); -} - -/** - * @brief Return data stored in the Independent Data(IDR) register. - * @note This register can be used as a temporary storage location for one byte. - * @rmtoll IDR IDR LL_CRC_Read_IDR - * @param CRCx CRC Instance - * @retval Value stored in CRC_IDR register (General-purpose 8-bit data register). - */ -__STATIC_INLINE uint32_t LL_CRC_Read_IDR(CRC_TypeDef *CRCx) -{ - return (uint32_t)(READ_REG(CRCx->IDR)); -} - -/** - * @brief Store data in the Independent Data(IDR) register. - * @note This register can be used as a temporary storage location for one byte. - * @rmtoll IDR IDR LL_CRC_Write_IDR - * @param CRCx CRC Instance - * @param InData value to be stored in CRC_IDR register (8-bit) between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_CRC_Write_IDR(CRC_TypeDef *CRCx, uint32_t InData) -{ - *((uint8_t __IO *)(&CRCx->IDR)) = (uint8_t) InData; -} -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup CRC_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_CRC_DeInit(CRC_TypeDef *CRCx); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(CRC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_CRC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dac.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dac.h deleted file mode 100644 index 98bf40b71cb4857..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dac.h +++ /dev/null @@ -1,1457 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dac.h - * @author MCD Application Team - * @brief Header file of DAC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_DAC_H -#define STM32F4xx_LL_DAC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(DAC) - -/** @defgroup DAC_LL DAC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DAC_LL_Private_Constants DAC Private Constants - * @{ - */ - -/* Internal masks for DAC channels definition */ -/* To select into literal LL_DAC_CHANNEL_x the relevant bits for: */ -/* - channel bits position into registers CR, MCR, CCR, SHHR, SHRR */ -/* - channel bits position into register SWTRIG */ -/* - channel register offset of data holding register DHRx */ -/* - channel register offset of data output register DORx */ -#define DAC_CR_CH1_BITOFFSET 0UL /* Position of channel bits into registers - CR, MCR, CCR, SHHR, SHRR of channel 1 */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_CR_CH2_BITOFFSET 16UL /* Position of channel bits into registers - CR, MCR, CCR, SHHR, SHRR of channel 2 */ -#define DAC_CR_CHX_BITOFFSET_MASK (DAC_CR_CH1_BITOFFSET | DAC_CR_CH2_BITOFFSET) -#else -#define DAC_CR_CHX_BITOFFSET_MASK (DAC_CR_CH1_BITOFFSET) -#endif /* DAC_CHANNEL2_SUPPORT */ - -#define DAC_SWTR_CH1 (DAC_SWTRIGR_SWTRIG1) /* Channel bit into register SWTRIGR of channel 1. */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_SWTR_CH2 (DAC_SWTRIGR_SWTRIG2) /* Channel bit into register SWTRIGR of channel 2. */ -#define DAC_SWTR_CHX_MASK (DAC_SWTR_CH1 | DAC_SWTR_CH2) -#else -#define DAC_SWTR_CHX_MASK (DAC_SWTR_CH1) -#endif /* DAC_CHANNEL2_SUPPORT */ - -#define DAC_REG_DHR12R1_REGOFFSET 0x00000000UL /* Register DHR12Rx channel 1 taken as reference */ -#define DAC_REG_DHR12L1_REGOFFSET 0x00100000UL /* Register offset of DHR12Lx channel 1 versus - DHR12Rx channel 1 (shifted left of 20 bits) */ -#define DAC_REG_DHR8R1_REGOFFSET 0x02000000UL /* Register offset of DHR8Rx channel 1 versus - DHR12Rx channel 1 (shifted left of 24 bits) */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_REG_DHR12R2_REGOFFSET 0x00030000UL /* Register offset of DHR12Rx channel 2 versus - DHR12Rx channel 1 (shifted left of 16 bits) */ -#define DAC_REG_DHR12L2_REGOFFSET 0x00400000UL /* Register offset of DHR12Lx channel 2 versus - DHR12Rx channel 1 (shifted left of 20 bits) */ -#define DAC_REG_DHR8R2_REGOFFSET 0x05000000UL /* Register offset of DHR8Rx channel 2 versus - DHR12Rx channel 1 (shifted left of 24 bits) */ -#endif /* DAC_CHANNEL2_SUPPORT */ -#define DAC_REG_DHR12RX_REGOFFSET_MASK 0x000F0000UL -#define DAC_REG_DHR12LX_REGOFFSET_MASK 0x00F00000UL -#define DAC_REG_DHR8RX_REGOFFSET_MASK 0x0F000000UL -#define DAC_REG_DHRX_REGOFFSET_MASK (DAC_REG_DHR12RX_REGOFFSET_MASK\ - | DAC_REG_DHR12LX_REGOFFSET_MASK | DAC_REG_DHR8RX_REGOFFSET_MASK) - -#define DAC_REG_DOR1_REGOFFSET 0x00000000UL /* Register DORx channel 1 taken as reference */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_REG_DOR2_REGOFFSET 0x10000000UL /* Register offset of DORx channel 1 versus - DORx channel 2 (shifted left of 28 bits) */ -#define DAC_REG_DORX_REGOFFSET_MASK (DAC_REG_DOR1_REGOFFSET | DAC_REG_DOR2_REGOFFSET) -#endif /* DAC_CHANNEL2_SUPPORT */ - - -#define DAC_REG_DHR_REGOFFSET_MASK_POSBIT0 0x0000000FUL /* Mask of data hold registers offset (DHR12Rx, - DHR12Lx, DHR8Rx, ...) when shifted to position 0 */ -#define DAC_REG_DORX_REGOFFSET_MASK_POSBIT0 0x00000001UL /* Mask of DORx registers offset when shifted - to position 0 */ -#define DAC_REG_SHSRX_REGOFFSET_MASK_POSBIT0 0x00000001UL /* Mask of SHSRx registers offset when shifted - to position 0 */ - -#define DAC_REG_DHR12RX_REGOFFSET_BITOFFSET_POS 16UL /* Position of bits register offset of DHR12Rx - channel 1 or 2 versus DHR12Rx channel 1 - (shifted left of 16 bits) */ -#define DAC_REG_DHR12LX_REGOFFSET_BITOFFSET_POS 20UL /* Position of bits register offset of DHR12Lx - channel 1 or 2 versus DHR12Rx channel 1 - (shifted left of 20 bits) */ -#define DAC_REG_DHR8RX_REGOFFSET_BITOFFSET_POS 24UL /* Position of bits register offset of DHR8Rx - channel 1 or 2 versus DHR12Rx channel 1 - (shifted left of 24 bits) */ -#define DAC_REG_DORX_REGOFFSET_BITOFFSET_POS 28UL /* Position of bits register offset of DORx - channel 1 or 2 versus DORx channel 1 - (shifted left of 28 bits) */ - -/* DAC registers bits positions */ -#if defined(DAC_CHANNEL2_SUPPORT) -#endif -#define DAC_DHR12RD_DACC2DHR_BITOFFSET_POS DAC_DHR12RD_DACC2DHR_Pos -#define DAC_DHR12LD_DACC2DHR_BITOFFSET_POS DAC_DHR12LD_DACC2DHR_Pos -#define DAC_DHR8RD_DACC2DHR_BITOFFSET_POS DAC_DHR8RD_DACC2DHR_Pos - -/* Miscellaneous data */ -#define DAC_DIGITAL_SCALE_12BITS 4095UL /* Full-scale digital value with a resolution of 12 - bits (voltage range determined by analog voltage - references Vref+ and Vref-, refer to reference manual) */ - -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DAC_LL_Private_Macros DAC Private Macros - * @{ - */ - -/** - * @brief Driver macro reserved for internal use: set a pointer to - * a register from a register basis from which an offset - * is applied. - * @param __REG__ Register basis from which the offset is applied. - * @param __REG_OFFFSET__ Offset to be applied (unit: number of registers). - * @retval Pointer to register address - */ -#define __DAC_PTR_REG_OFFSET(__REG__, __REG_OFFFSET__) \ - ((uint32_t *)((uint32_t) ((uint32_t)(&(__REG__)) + ((__REG_OFFFSET__) << 2UL)))) - -/** - * @} - */ - - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DAC_LL_ES_INIT DAC Exported Init structure - * @{ - */ - -/** - * @brief Structure definition of some features of DAC instance. - */ -typedef struct -{ - uint32_t TriggerSource; /*!< Set the conversion trigger source for the selected DAC channel: - internal (SW start) or from external peripheral - (timer event, external interrupt line). - This parameter can be a value of @ref DAC_LL_EC_TRIGGER_SOURCE - - This feature can be modified afterwards using unitary - function @ref LL_DAC_SetTriggerSource(). */ - - uint32_t WaveAutoGeneration; /*!< Set the waveform automatic generation mode for the selected DAC channel. - This parameter can be a value of @ref DAC_LL_EC_WAVE_AUTO_GENERATION_MODE - - This feature can be modified afterwards using unitary - function @ref LL_DAC_SetWaveAutoGeneration(). */ - - uint32_t WaveAutoGenerationConfig; /*!< Set the waveform automatic generation mode for the selected DAC channel. - If waveform automatic generation mode is set to noise, this parameter - can be a value of @ref DAC_LL_EC_WAVE_NOISE_LFSR_UNMASK_BITS - If waveform automatic generation mode is set to triangle, - this parameter can be a value of @ref DAC_LL_EC_WAVE_TRIANGLE_AMPLITUDE - @note If waveform automatic generation mode is disabled, - this parameter is discarded. - - This feature can be modified afterwards using unitary - function @ref LL_DAC_SetWaveNoiseLFSR(), - @ref LL_DAC_SetWaveTriangleAmplitude() - depending on the wave automatic generation selected. */ - - uint32_t OutputBuffer; /*!< Set the output buffer for the selected DAC channel. - This parameter can be a value of @ref DAC_LL_EC_OUTPUT_BUFFER - - This feature can be modified afterwards using unitary - function @ref LL_DAC_SetOutputBuffer(). */ -} LL_DAC_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DAC_LL_Exported_Constants DAC Exported Constants - * @{ - */ - -/** @defgroup DAC_LL_EC_GET_FLAG DAC flags - * @brief Flags defines which can be used with LL_DAC_ReadReg function - * @{ - */ -/* DAC channel 1 flags */ -#define LL_DAC_FLAG_DMAUDR1 (DAC_SR_DMAUDR1) /*!< DAC channel 1 flag DMA underrun */ -#if defined(DAC_CHANNEL2_SUPPORT) -/* DAC channel 2 flags */ -#define LL_DAC_FLAG_DMAUDR2 (DAC_SR_DMAUDR2) /*!< DAC channel 2 flag DMA underrun */ -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_IT DAC interruptions - * @brief IT defines which can be used with LL_DAC_ReadReg and LL_DAC_WriteReg functions - * @{ - */ -#define LL_DAC_IT_DMAUDRIE1 (DAC_CR_DMAUDRIE1) /*!< DAC channel 1 interruption DMA underrun */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define LL_DAC_IT_DMAUDRIE2 (DAC_CR_DMAUDRIE2) /*!< DAC channel 2 interruption DMA underrun */ -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_CHANNEL DAC channels - * @{ - */ -#define LL_DAC_CHANNEL_1 (DAC_REG_DOR1_REGOFFSET | DAC_REG_DHR12R1_REGOFFSET | DAC_REG_DHR12L1_REGOFFSET | DAC_REG_DHR8R1_REGOFFSET | DAC_CR_CH1_BITOFFSET | DAC_SWTR_CH1) /*!< DAC channel 1 */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define LL_DAC_CHANNEL_2 (DAC_REG_DOR2_REGOFFSET | DAC_REG_DHR12R2_REGOFFSET | DAC_REG_DHR12L2_REGOFFSET | DAC_REG_DHR8R2_REGOFFSET | DAC_CR_CH2_BITOFFSET | DAC_SWTR_CH2) /*!< DAC channel 2 */ -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_TRIGGER_SOURCE DAC trigger source - * @{ - */ -#define LL_DAC_TRIG_SOFTWARE (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_1 | DAC_CR_TSEL1_0) /*!< DAC channel conversion trigger internal (SW start) */ -#define LL_DAC_TRIG_EXT_TIM2_TRGO (DAC_CR_TSEL1_2 ) /*!< DAC channel conversion trigger from external peripheral: TIM2 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM8_TRGO ( DAC_CR_TSEL1_0) /*!< DAC channel conversion trigger from external peripheral: TIM8 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM4_TRGO (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_0) /*!< DAC channel conversion trigger from external peripheral: TIM4 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM6_TRGO 0x00000000UL /*!< DAC channel conversion trigger from external peripheral: TIM6 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM7_TRGO ( DAC_CR_TSEL1_1 ) /*!< DAC channel conversion trigger from external peripheral: TIM7 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM5_TRGO ( DAC_CR_TSEL1_1 | DAC_CR_TSEL1_0) /*!< DAC channel conversion trigger from external peripheral: TIM5 TRGO. */ -#define LL_DAC_TRIG_EXT_EXTI_LINE9 (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_1 ) /*!< DAC channel conversion trigger from external peripheral: external interrupt line 9. */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_WAVE_AUTO_GENERATION_MODE DAC waveform automatic generation mode - * @{ - */ -#define LL_DAC_WAVE_AUTO_GENERATION_NONE 0x00000000UL /*!< DAC channel wave auto generation mode disabled. */ -#define LL_DAC_WAVE_AUTO_GENERATION_NOISE ( DAC_CR_WAVE1_0) /*!< DAC channel wave auto generation mode enabled, set generated noise waveform. */ -#define LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE (DAC_CR_WAVE1_1 ) /*!< DAC channel wave auto generation mode enabled, set generated triangle waveform. */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_WAVE_NOISE_LFSR_UNMASK_BITS DAC wave generation - Noise LFSR unmask bits - * @{ - */ -#define LL_DAC_NOISE_LFSR_UNMASK_BIT0 0x00000000UL /*!< Noise wave generation, unmask LFSR bit0, for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS1_0 ( DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[1:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS2_0 ( DAC_CR_MAMP1_1 ) /*!< Noise wave generation, unmask LFSR bits[2:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS3_0 ( DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[3:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS4_0 ( DAC_CR_MAMP1_2 ) /*!< Noise wave generation, unmask LFSR bits[4:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS5_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[5:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS6_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 ) /*!< Noise wave generation, unmask LFSR bits[6:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS7_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[7:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS8_0 (DAC_CR_MAMP1_3 ) /*!< Noise wave generation, unmask LFSR bits[8:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS9_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[9:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS10_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 ) /*!< Noise wave generation, unmask LFSR bits[10:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS11_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[11:0], for the selected DAC channel */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_WAVE_TRIANGLE_AMPLITUDE DAC wave generation - Triangle amplitude - * @{ - */ -#define LL_DAC_TRIANGLE_AMPLITUDE_1 0x00000000UL /*!< Triangle wave generation, amplitude of 1 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_3 ( DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 3 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_7 ( DAC_CR_MAMP1_1 ) /*!< Triangle wave generation, amplitude of 7 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_15 ( DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 15 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_31 ( DAC_CR_MAMP1_2 ) /*!< Triangle wave generation, amplitude of 31 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_63 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 63 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_127 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 ) /*!< Triangle wave generation, amplitude of 127 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_255 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 255 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_511 (DAC_CR_MAMP1_3 ) /*!< Triangle wave generation, amplitude of 512 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_1023 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 1023 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_2047 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 ) /*!< Triangle wave generation, amplitude of 2047 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_4095 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 4095 LSB of DAC output range, for the selected DAC channel */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_OUTPUT_BUFFER DAC channel output buffer - * @{ - */ -#define LL_DAC_OUTPUT_BUFFER_ENABLE 0x00000000UL /*!< The selected DAC channel output is buffered: higher drive current capability, but also higher current consumption */ -#define LL_DAC_OUTPUT_BUFFER_DISABLE (DAC_CR_BOFF1) /*!< The selected DAC channel output is not buffered: lower drive current capability, but also lower current consumption */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_RESOLUTION DAC channel output resolution - * @{ - */ -#define LL_DAC_RESOLUTION_12B 0x00000000UL /*!< DAC channel resolution 12 bits */ -#define LL_DAC_RESOLUTION_8B 0x00000002UL /*!< DAC channel resolution 8 bits */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_REGISTERS DAC registers compliant with specific purpose - * @{ - */ -/* List of DAC registers intended to be used (most commonly) with */ -/* DMA transfer. */ -/* Refer to function @ref LL_DAC_DMA_GetRegAddr(). */ -#define LL_DAC_DMA_REG_DATA_12BITS_RIGHT_ALIGNED DAC_REG_DHR12RX_REGOFFSET_BITOFFSET_POS /*!< DAC channel data holding register 12 bits right aligned */ -#define LL_DAC_DMA_REG_DATA_12BITS_LEFT_ALIGNED DAC_REG_DHR12LX_REGOFFSET_BITOFFSET_POS /*!< DAC channel data holding register 12 bits left aligned */ -#define LL_DAC_DMA_REG_DATA_8BITS_RIGHT_ALIGNED DAC_REG_DHR8RX_REGOFFSET_BITOFFSET_POS /*!< DAC channel data holding register 8 bits right aligned */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_HW_DELAYS Definitions of DAC hardware constraints delays - * @note Only DAC peripheral HW delays are defined in DAC LL driver driver, - * not timeout values. - * For details on delays values, refer to descriptions in source code - * above each literal definition. - * @{ - */ - -/* Delay for DAC channel voltage settling time from DAC channel startup */ -/* (transition from disable to enable). */ -/* Note: DAC channel startup time depends on board application environment: */ -/* impedance connected to DAC channel output. */ -/* The delay below is specified under conditions: */ -/* - voltage maximum transition (lowest to highest value) */ -/* - until voltage reaches final value +-1LSB */ -/* - DAC channel output buffer enabled */ -/* - load impedance of 5kOhm (min), 50pF (max) */ -/* Literal set to maximum value (refer to device datasheet, */ -/* parameter "tWAKEUP"). */ -/* Unit: us */ -#define LL_DAC_DELAY_STARTUP_VOLTAGE_SETTLING_US 15UL /*!< Delay for DAC channel voltage settling time from DAC channel startup (transition from disable to enable) */ - -/* Delay for DAC channel voltage settling time. */ -/* Note: DAC channel startup time depends on board application environment: */ -/* impedance connected to DAC channel output. */ -/* The delay below is specified under conditions: */ -/* - voltage maximum transition (lowest to highest value) */ -/* - until voltage reaches final value +-1LSB */ -/* - DAC channel output buffer enabled */ -/* - load impedance of 5kOhm min, 50pF max */ -/* Literal set to maximum value (refer to device datasheet, */ -/* parameter "tSETTLING"). */ -/* Unit: us */ -#define LL_DAC_DELAY_VOLTAGE_SETTLING_US 12UL /*!< Delay for DAC channel voltage settling time */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DAC_LL_Exported_Macros DAC Exported Macros - * @{ - */ - -/** @defgroup DAC_LL_EM_WRITE_READ Common write and read registers macros - * @{ - */ - -/** - * @brief Write a value in DAC register - * @param __INSTANCE__ DAC Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_DAC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in DAC register - * @param __INSTANCE__ DAC Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_DAC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) - -/** - * @} - */ - -/** @defgroup DAC_LL_EM_HELPER_MACRO DAC helper macro - * @{ - */ - -/** - * @brief Helper macro to get DAC channel number in decimal format - * from literals LL_DAC_CHANNEL_x. - * Example: - * __LL_DAC_CHANNEL_TO_DECIMAL_NB(LL_DAC_CHANNEL_1) - * will return decimal number "1". - * @note The input can be a value from functions where a channel - * number is returned. - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval 1...2 (value "2" depending on DAC channel 2 availability) - */ -#define __LL_DAC_CHANNEL_TO_DECIMAL_NB(__CHANNEL__) \ - ((__CHANNEL__) & DAC_SWTR_CHX_MASK) - -/** - * @brief Helper macro to get DAC channel in literal format LL_DAC_CHANNEL_x - * from number in decimal format. - * Example: - * __LL_DAC_DECIMAL_NB_TO_CHANNEL(1) - * will return a data equivalent to "LL_DAC_CHANNEL_1". - * @note If the input parameter does not correspond to a DAC channel, - * this macro returns value '0'. - * @param __DECIMAL_NB__ 1...2 (value "2" depending on DAC channel 2 availability) - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define __LL_DAC_DECIMAL_NB_TO_CHANNEL(__DECIMAL_NB__) \ - (((__DECIMAL_NB__) == 1UL) \ - ? ( \ - LL_DAC_CHANNEL_1 \ - ) \ - : \ - (((__DECIMAL_NB__) == 2UL) \ - ? ( \ - LL_DAC_CHANNEL_2 \ - ) \ - : \ - ( \ - 0UL \ - ) \ - ) \ - ) -#else -#define __LL_DAC_DECIMAL_NB_TO_CHANNEL(__DECIMAL_NB__) \ - (((__DECIMAL_NB__) == 1UL) \ - ? ( \ - LL_DAC_CHANNEL_1 \ - ) \ - : \ - ( \ - 0UL \ - ) \ - ) -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Helper macro to define the DAC conversion data full-scale digital - * value corresponding to the selected DAC resolution. - * @note DAC conversion data full-scale corresponds to voltage range - * determined by analog voltage references Vref+ and Vref- - * (refer to reference manual). - * @param __DAC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_DAC_RESOLUTION_12B - * @arg @ref LL_DAC_RESOLUTION_8B - * @retval ADC conversion data equivalent voltage value (unit: mVolt) - */ -#define __LL_DAC_DIGITAL_SCALE(__DAC_RESOLUTION__) \ - ((0x00000FFFUL) >> ((__DAC_RESOLUTION__) << 1UL)) - -/** - * @brief Helper macro to calculate the DAC conversion data (unit: digital - * value) corresponding to a voltage (unit: mVolt). - * @note This helper macro is intended to provide input data in voltage - * rather than digital value, - * to be used with LL DAC functions such as - * @ref LL_DAC_ConvertData12RightAligned(). - * @note Analog reference voltage (Vref+) must be either known from - * user board environment or can be calculated using ADC measurement - * and ADC helper macro __LL_ADC_CALC_VREFANALOG_VOLTAGE(). - * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit: mV) - * @param __DAC_VOLTAGE__ Voltage to be generated by DAC channel - * (unit: mVolt). - * @param __DAC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_DAC_RESOLUTION_12B - * @arg @ref LL_DAC_RESOLUTION_8B - * @retval DAC conversion data (unit: digital value) - */ -#define __LL_DAC_CALC_VOLTAGE_TO_DATA(__VREFANALOG_VOLTAGE__,\ - __DAC_VOLTAGE__,\ - __DAC_RESOLUTION__) \ -((__DAC_VOLTAGE__) * __LL_DAC_DIGITAL_SCALE(__DAC_RESOLUTION__) \ - / (__VREFANALOG_VOLTAGE__) \ -) - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DAC_LL_Exported_Functions DAC Exported Functions - * @{ - */ -/** - * @brief Set the conversion trigger source for the selected DAC channel. - * @note For conversion trigger source to be effective, DAC trigger - * must be enabled using function @ref LL_DAC_EnableTrigger(). - * @note To set conversion trigger source, DAC channel must be disabled. - * Otherwise, the setting is discarded. - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR TSEL1 LL_DAC_SetTriggerSource\n - * CR TSEL2 LL_DAC_SetTriggerSource - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param TriggerSource This parameter can be one of the following values: - * @arg @ref LL_DAC_TRIG_SOFTWARE - * @arg @ref LL_DAC_TRIG_EXT_TIM8_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM7_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM6_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM5_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM4_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_DAC_TRIG_EXT_EXTI_LINE9 - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetTriggerSource(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t TriggerSource) -{ - MODIFY_REG(DACx->CR, - DAC_CR_TSEL1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - TriggerSource << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the conversion trigger source for the selected DAC channel. - * @note For conversion trigger source to be effective, DAC trigger - * must be enabled using function @ref LL_DAC_EnableTrigger(). - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR TSEL1 LL_DAC_GetTriggerSource\n - * CR TSEL2 LL_DAC_GetTriggerSource - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_TRIG_SOFTWARE - * @arg @ref LL_DAC_TRIG_EXT_TIM8_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM7_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM6_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM5_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM4_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_DAC_TRIG_EXT_EXTI_LINE9 - */ -__STATIC_INLINE uint32_t LL_DAC_GetTriggerSource(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_TSEL1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @brief Set the waveform automatic generation mode - * for the selected DAC channel. - * @rmtoll CR WAVE1 LL_DAC_SetWaveAutoGeneration\n - * CR WAVE2 LL_DAC_SetWaveAutoGeneration - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param WaveAutoGeneration This parameter can be one of the following values: - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_NONE - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_NOISE - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetWaveAutoGeneration(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t WaveAutoGeneration) -{ - MODIFY_REG(DACx->CR, - DAC_CR_WAVE1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - WaveAutoGeneration << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the waveform automatic generation mode - * for the selected DAC channel. - * @rmtoll CR WAVE1 LL_DAC_GetWaveAutoGeneration\n - * CR WAVE2 LL_DAC_GetWaveAutoGeneration - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_NONE - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_NOISE - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE - */ -__STATIC_INLINE uint32_t LL_DAC_GetWaveAutoGeneration(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_WAVE1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @brief Set the noise waveform generation for the selected DAC channel: - * Noise mode and parameters LFSR (linear feedback shift register). - * @note For wave generation to be effective, DAC channel - * wave generation mode must be enabled using - * function @ref LL_DAC_SetWaveAutoGeneration(). - * @note This setting can be set when the selected DAC channel is disabled - * (otherwise, the setting operation is ignored). - * @rmtoll CR MAMP1 LL_DAC_SetWaveNoiseLFSR\n - * CR MAMP2 LL_DAC_SetWaveNoiseLFSR - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param NoiseLFSRMask This parameter can be one of the following values: - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BIT0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS1_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS2_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS3_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS4_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS5_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS6_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS7_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS8_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS9_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS10_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS11_0 - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetWaveNoiseLFSR(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t NoiseLFSRMask) -{ - MODIFY_REG(DACx->CR, - DAC_CR_MAMP1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - NoiseLFSRMask << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the noise waveform generation for the selected DAC channel: - * Noise mode and parameters LFSR (linear feedback shift register). - * @rmtoll CR MAMP1 LL_DAC_GetWaveNoiseLFSR\n - * CR MAMP2 LL_DAC_GetWaveNoiseLFSR - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BIT0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS1_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS2_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS3_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS4_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS5_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS6_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS7_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS8_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS9_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS10_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS11_0 - */ -__STATIC_INLINE uint32_t LL_DAC_GetWaveNoiseLFSR(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_MAMP1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @brief Set the triangle waveform generation for the selected DAC channel: - * triangle mode and amplitude. - * @note For wave generation to be effective, DAC channel - * wave generation mode must be enabled using - * function @ref LL_DAC_SetWaveAutoGeneration(). - * @note This setting can be set when the selected DAC channel is disabled - * (otherwise, the setting operation is ignored). - * @rmtoll CR MAMP1 LL_DAC_SetWaveTriangleAmplitude\n - * CR MAMP2 LL_DAC_SetWaveTriangleAmplitude - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param TriangleAmplitude This parameter can be one of the following values: - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_1 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_3 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_7 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_15 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_31 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_63 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_127 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_255 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_511 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_1023 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_2047 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_4095 - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetWaveTriangleAmplitude(DAC_TypeDef *DACx, uint32_t DAC_Channel, - uint32_t TriangleAmplitude) -{ - MODIFY_REG(DACx->CR, - DAC_CR_MAMP1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - TriangleAmplitude << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the triangle waveform generation for the selected DAC channel: - * triangle mode and amplitude. - * @rmtoll CR MAMP1 LL_DAC_GetWaveTriangleAmplitude\n - * CR MAMP2 LL_DAC_GetWaveTriangleAmplitude - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_1 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_3 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_7 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_15 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_31 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_63 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_127 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_255 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_511 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_1023 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_2047 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_4095 - */ -__STATIC_INLINE uint32_t LL_DAC_GetWaveTriangleAmplitude(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_MAMP1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @brief Set the output buffer for the selected DAC channel. - * @rmtoll CR BOFF1 LL_DAC_SetOutputBuffer\n - * CR BOFF2 LL_DAC_SetOutputBuffer - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param OutputBuffer This parameter can be one of the following values: - * @arg @ref LL_DAC_OUTPUT_BUFFER_ENABLE - * @arg @ref LL_DAC_OUTPUT_BUFFER_DISABLE - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetOutputBuffer(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t OutputBuffer) -{ - MODIFY_REG(DACx->CR, - DAC_CR_BOFF1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - OutputBuffer << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the output buffer state for the selected DAC channel. - * @rmtoll CR BOFF1 LL_DAC_GetOutputBuffer\n - * CR BOFF2 LL_DAC_GetOutputBuffer - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_OUTPUT_BUFFER_ENABLE - * @arg @ref LL_DAC_OUTPUT_BUFFER_DISABLE - */ -__STATIC_INLINE uint32_t LL_DAC_GetOutputBuffer(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_BOFF1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @} - */ - -/** @defgroup DAC_LL_EF_DMA_Management DMA Management - * @{ - */ - -/** - * @brief Enable DAC DMA transfer request of the selected channel. - * @note To configure DMA source address (peripheral address), - * use function @ref LL_DAC_DMA_GetRegAddr(). - * @rmtoll CR DMAEN1 LL_DAC_EnableDMAReq\n - * CR DMAEN2 LL_DAC_EnableDMAReq - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_EnableDMAReq(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - SET_BIT(DACx->CR, - DAC_CR_DMAEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Disable DAC DMA transfer request of the selected channel. - * @note To configure DMA source address (peripheral address), - * use function @ref LL_DAC_DMA_GetRegAddr(). - * @rmtoll CR DMAEN1 LL_DAC_DisableDMAReq\n - * CR DMAEN2 LL_DAC_DisableDMAReq - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_DisableDMAReq(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - CLEAR_BIT(DACx->CR, - DAC_CR_DMAEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get DAC DMA transfer request state of the selected channel. - * (0: DAC DMA transfer request is disabled, 1: DAC DMA transfer request is enabled) - * @rmtoll CR DMAEN1 LL_DAC_IsDMAReqEnabled\n - * CR DMAEN2 LL_DAC_IsDMAReqEnabled - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsDMAReqEnabled(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return ((READ_BIT(DACx->CR, - DAC_CR_DMAEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - == (DAC_CR_DMAEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK))) ? 1UL : 0UL); -} - -/** - * @brief Function to help to configure DMA transfer to DAC: retrieve the - * DAC register address from DAC instance and a list of DAC registers - * intended to be used (most commonly) with DMA transfer. - * @note These DAC registers are data holding registers: - * when DAC conversion is requested, DAC generates a DMA transfer - * request to have data available in DAC data holding registers. - * @note This macro is intended to be used with LL DMA driver, refer to - * function "LL_DMA_ConfigAddresses()". - * Example: - * LL_DMA_ConfigAddresses(DMA1, - * LL_DMA_CHANNEL_1, - * (uint32_t)&< array or variable >, - * LL_DAC_DMA_GetRegAddr(DAC1, LL_DAC_CHANNEL_1, - * LL_DAC_DMA_REG_DATA_12BITS_RIGHT_ALIGNED), - * LL_DMA_DIRECTION_MEMORY_TO_PERIPH); - * @rmtoll DHR12R1 DACC1DHR LL_DAC_DMA_GetRegAddr\n - * DHR12L1 DACC1DHR LL_DAC_DMA_GetRegAddr\n - * DHR8R1 DACC1DHR LL_DAC_DMA_GetRegAddr\n - * DHR12R2 DACC2DHR LL_DAC_DMA_GetRegAddr\n - * DHR12L2 DACC2DHR LL_DAC_DMA_GetRegAddr\n - * DHR8R2 DACC2DHR LL_DAC_DMA_GetRegAddr - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param Register This parameter can be one of the following values: - * @arg @ref LL_DAC_DMA_REG_DATA_12BITS_RIGHT_ALIGNED - * @arg @ref LL_DAC_DMA_REG_DATA_12BITS_LEFT_ALIGNED - * @arg @ref LL_DAC_DMA_REG_DATA_8BITS_RIGHT_ALIGNED - * @retval DAC register address - */ -__STATIC_INLINE uint32_t LL_DAC_DMA_GetRegAddr(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t Register) -{ - /* Retrieve address of register DHR12Rx, DHR12Lx or DHR8Rx depending on */ - /* DAC channel selected. */ - return ((uint32_t)(__DAC_PTR_REG_OFFSET((DACx)->DHR12R1, ((DAC_Channel >> (Register & 0x1FUL)) - & DAC_REG_DHR_REGOFFSET_MASK_POSBIT0)))); -} -/** - * @} - */ - -/** @defgroup DAC_LL_EF_Operation Operation on DAC channels - * @{ - */ - -/** - * @brief Enable DAC selected channel. - * @rmtoll CR EN1 LL_DAC_Enable\n - * CR EN2 LL_DAC_Enable - * @note After enable from off state, DAC channel requires a delay - * for output voltage to reach accuracy +/- 1 LSB. - * Refer to device datasheet, parameter "tWAKEUP". - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_Enable(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - SET_BIT(DACx->CR, - DAC_CR_EN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Disable DAC selected channel. - * @rmtoll CR EN1 LL_DAC_Disable\n - * CR EN2 LL_DAC_Disable - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_Disable(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - CLEAR_BIT(DACx->CR, - DAC_CR_EN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get DAC enable state of the selected channel. - * (0: DAC channel is disabled, 1: DAC channel is enabled) - * @rmtoll CR EN1 LL_DAC_IsEnabled\n - * CR EN2 LL_DAC_IsEnabled - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsEnabled(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return ((READ_BIT(DACx->CR, - DAC_CR_EN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - == (DAC_CR_EN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK))) ? 1UL : 0UL); -} - -/** - * @brief Enable DAC trigger of the selected channel. - * @note - If DAC trigger is disabled, DAC conversion is performed - * automatically once the data holding register is updated, - * using functions "LL_DAC_ConvertData{8; 12}{Right; Left} Aligned()": - * @ref LL_DAC_ConvertData12RightAligned(), ... - * - If DAC trigger is enabled, DAC conversion is performed - * only when a hardware of software trigger event is occurring. - * Select trigger source using - * function @ref LL_DAC_SetTriggerSource(). - * @rmtoll CR TEN1 LL_DAC_EnableTrigger\n - * CR TEN2 LL_DAC_EnableTrigger - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_EnableTrigger(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - SET_BIT(DACx->CR, - DAC_CR_TEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Disable DAC trigger of the selected channel. - * @rmtoll CR TEN1 LL_DAC_DisableTrigger\n - * CR TEN2 LL_DAC_DisableTrigger - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_DisableTrigger(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - CLEAR_BIT(DACx->CR, - DAC_CR_TEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get DAC trigger state of the selected channel. - * (0: DAC trigger is disabled, 1: DAC trigger is enabled) - * @rmtoll CR TEN1 LL_DAC_IsTriggerEnabled\n - * CR TEN2 LL_DAC_IsTriggerEnabled - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsTriggerEnabled(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return ((READ_BIT(DACx->CR, - DAC_CR_TEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - == (DAC_CR_TEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK))) ? 1UL : 0UL); -} - -/** - * @brief Trig DAC conversion by software for the selected DAC channel. - * @note Preliminarily, DAC trigger must be set to software trigger - * using function - * @ref LL_DAC_Init() - * @ref LL_DAC_SetTriggerSource() - * with parameter "LL_DAC_TRIGGER_SOFTWARE". - * and DAC trigger must be enabled using - * function @ref LL_DAC_EnableTrigger(). - * @note For devices featuring DAC with 2 channels: this function - * can perform a SW start of both DAC channels simultaneously. - * Two channels can be selected as parameter. - * Example: (LL_DAC_CHANNEL_1 | LL_DAC_CHANNEL_2) - * @rmtoll SWTRIGR SWTRIG1 LL_DAC_TrigSWConversion\n - * SWTRIGR SWTRIG2 LL_DAC_TrigSWConversion - * @param DACx DAC instance - * @param DAC_Channel This parameter can a combination of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_TrigSWConversion(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - SET_BIT(DACx->SWTRIGR, - (DAC_Channel & DAC_SWTR_CHX_MASK)); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 12 bits left alignment (LSB aligned on bit 0), - * for the selected DAC channel. - * @rmtoll DHR12R1 DACC1DHR LL_DAC_ConvertData12RightAligned\n - * DHR12R2 DACC2DHR LL_DAC_ConvertData12RightAligned - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param Data Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertData12RightAligned(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t Data) -{ - __IO uint32_t *preg = __DAC_PTR_REG_OFFSET(DACx->DHR12R1, (DAC_Channel >> DAC_REG_DHR12RX_REGOFFSET_BITOFFSET_POS) - & DAC_REG_DHR_REGOFFSET_MASK_POSBIT0); - - MODIFY_REG(*preg, DAC_DHR12R1_DACC1DHR, Data); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 12 bits left alignment (MSB aligned on bit 15), - * for the selected DAC channel. - * @rmtoll DHR12L1 DACC1DHR LL_DAC_ConvertData12LeftAligned\n - * DHR12L2 DACC2DHR LL_DAC_ConvertData12LeftAligned - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param Data Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertData12LeftAligned(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t Data) -{ - __IO uint32_t *preg = __DAC_PTR_REG_OFFSET(DACx->DHR12R1, (DAC_Channel >> DAC_REG_DHR12LX_REGOFFSET_BITOFFSET_POS) - & DAC_REG_DHR_REGOFFSET_MASK_POSBIT0); - - MODIFY_REG(*preg, DAC_DHR12L1_DACC1DHR, Data); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 8 bits left alignment (LSB aligned on bit 0), - * for the selected DAC channel. - * @rmtoll DHR8R1 DACC1DHR LL_DAC_ConvertData8RightAligned\n - * DHR8R2 DACC2DHR LL_DAC_ConvertData8RightAligned - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param Data Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertData8RightAligned(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t Data) -{ - __IO uint32_t *preg = __DAC_PTR_REG_OFFSET(DACx->DHR12R1, (DAC_Channel >> DAC_REG_DHR8RX_REGOFFSET_BITOFFSET_POS) - & DAC_REG_DHR_REGOFFSET_MASK_POSBIT0); - - MODIFY_REG(*preg, DAC_DHR8R1_DACC1DHR, Data); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Set the data to be loaded in the data holding register - * in format 12 bits left alignment (LSB aligned on bit 0), - * for both DAC channels. - * @rmtoll DHR12RD DACC1DHR LL_DAC_ConvertDualData12RightAligned\n - * DHR12RD DACC2DHR LL_DAC_ConvertDualData12RightAligned - * @param DACx DAC instance - * @param DataChannel1 Value between Min_Data=0x000 and Max_Data=0xFFF - * @param DataChannel2 Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertDualData12RightAligned(DAC_TypeDef *DACx, uint32_t DataChannel1, - uint32_t DataChannel2) -{ - MODIFY_REG(DACx->DHR12RD, - (DAC_DHR12RD_DACC2DHR | DAC_DHR12RD_DACC1DHR), - ((DataChannel2 << DAC_DHR12RD_DACC2DHR_BITOFFSET_POS) | DataChannel1)); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 12 bits left alignment (MSB aligned on bit 15), - * for both DAC channels. - * @rmtoll DHR12LD DACC1DHR LL_DAC_ConvertDualData12LeftAligned\n - * DHR12LD DACC2DHR LL_DAC_ConvertDualData12LeftAligned - * @param DACx DAC instance - * @param DataChannel1 Value between Min_Data=0x000 and Max_Data=0xFFF - * @param DataChannel2 Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertDualData12LeftAligned(DAC_TypeDef *DACx, uint32_t DataChannel1, - uint32_t DataChannel2) -{ - /* Note: Data of DAC channel 2 shift value subtracted of 4 because */ - /* data on 16 bits and DAC channel 2 bits field is on the 12 MSB, */ - /* the 4 LSB must be taken into account for the shift value. */ - MODIFY_REG(DACx->DHR12LD, - (DAC_DHR12LD_DACC2DHR | DAC_DHR12LD_DACC1DHR), - ((DataChannel2 << (DAC_DHR12LD_DACC2DHR_BITOFFSET_POS - 4U)) | DataChannel1)); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 8 bits left alignment (LSB aligned on bit 0), - * for both DAC channels. - * @rmtoll DHR8RD DACC1DHR LL_DAC_ConvertDualData8RightAligned\n - * DHR8RD DACC2DHR LL_DAC_ConvertDualData8RightAligned - * @param DACx DAC instance - * @param DataChannel1 Value between Min_Data=0x00 and Max_Data=0xFF - * @param DataChannel2 Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertDualData8RightAligned(DAC_TypeDef *DACx, uint32_t DataChannel1, - uint32_t DataChannel2) -{ - MODIFY_REG(DACx->DHR8RD, - (DAC_DHR8RD_DACC2DHR | DAC_DHR8RD_DACC1DHR), - ((DataChannel2 << DAC_DHR8RD_DACC2DHR_BITOFFSET_POS) | DataChannel1)); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Retrieve output data currently generated for the selected DAC channel. - * @note Whatever alignment and resolution settings - * (using functions "LL_DAC_ConvertData{8; 12}{Right; Left} Aligned()": - * @ref LL_DAC_ConvertData12RightAligned(), ...), - * output data format is 12 bits right aligned (LSB aligned on bit 0). - * @rmtoll DOR1 DACC1DOR LL_DAC_RetrieveOutputData\n - * DOR2 DACC2DOR LL_DAC_RetrieveOutputData - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_DAC_RetrieveOutputData(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - __IO uint32_t const *preg = __DAC_PTR_REG_OFFSET(DACx->DOR1, (DAC_Channel >> DAC_REG_DORX_REGOFFSET_BITOFFSET_POS) - & DAC_REG_DORX_REGOFFSET_MASK_POSBIT0); - - return (uint16_t) READ_BIT(*preg, DAC_DOR1_DACC1DOR); -} - -/** - * @} - */ - -/** @defgroup DAC_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Get DAC underrun flag for DAC channel 1 - * @rmtoll SR DMAUDR1 LL_DAC_IsActiveFlag_DMAUDR1 - * @param DACx DAC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsActiveFlag_DMAUDR1(DAC_TypeDef *DACx) -{ - return ((READ_BIT(DACx->SR, LL_DAC_FLAG_DMAUDR1) == (LL_DAC_FLAG_DMAUDR1)) ? 1UL : 0UL); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Get DAC underrun flag for DAC channel 2 - * @rmtoll SR DMAUDR2 LL_DAC_IsActiveFlag_DMAUDR2 - * @param DACx DAC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsActiveFlag_DMAUDR2(DAC_TypeDef *DACx) -{ - return ((READ_BIT(DACx->SR, LL_DAC_FLAG_DMAUDR2) == (LL_DAC_FLAG_DMAUDR2)) ? 1UL : 0UL); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Clear DAC underrun flag for DAC channel 1 - * @rmtoll SR DMAUDR1 LL_DAC_ClearFlag_DMAUDR1 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_ClearFlag_DMAUDR1(DAC_TypeDef *DACx) -{ - WRITE_REG(DACx->SR, LL_DAC_FLAG_DMAUDR1); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Clear DAC underrun flag for DAC channel 2 - * @rmtoll SR DMAUDR2 LL_DAC_ClearFlag_DMAUDR2 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_ClearFlag_DMAUDR2(DAC_TypeDef *DACx) -{ - WRITE_REG(DACx->SR, LL_DAC_FLAG_DMAUDR2); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -/** @defgroup DAC_LL_EF_IT_Management IT management - * @{ - */ - -/** - * @brief Enable DMA underrun interrupt for DAC channel 1 - * @rmtoll CR DMAUDRIE1 LL_DAC_EnableIT_DMAUDR1 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_EnableIT_DMAUDR1(DAC_TypeDef *DACx) -{ - SET_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE1); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Enable DMA underrun interrupt for DAC channel 2 - * @rmtoll CR DMAUDRIE2 LL_DAC_EnableIT_DMAUDR2 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_EnableIT_DMAUDR2(DAC_TypeDef *DACx) -{ - SET_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE2); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Disable DMA underrun interrupt for DAC channel 1 - * @rmtoll CR DMAUDRIE1 LL_DAC_DisableIT_DMAUDR1 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_DisableIT_DMAUDR1(DAC_TypeDef *DACx) -{ - CLEAR_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE1); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Disable DMA underrun interrupt for DAC channel 2 - * @rmtoll CR DMAUDRIE2 LL_DAC_DisableIT_DMAUDR2 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_DisableIT_DMAUDR2(DAC_TypeDef *DACx) -{ - CLEAR_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE2); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Get DMA underrun interrupt for DAC channel 1 - * @rmtoll CR DMAUDRIE1 LL_DAC_IsEnabledIT_DMAUDR1 - * @param DACx DAC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsEnabledIT_DMAUDR1(DAC_TypeDef *DACx) -{ - return ((READ_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE1) == (LL_DAC_IT_DMAUDRIE1)) ? 1UL : 0UL); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Get DMA underrun interrupt for DAC channel 2 - * @rmtoll CR DMAUDRIE2 LL_DAC_IsEnabledIT_DMAUDR2 - * @param DACx DAC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsEnabledIT_DMAUDR2(DAC_TypeDef *DACx) -{ - return ((READ_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE2) == (LL_DAC_IT_DMAUDRIE2)) ? 1UL : 0UL); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DAC_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_DAC_DeInit(DAC_TypeDef *DACx); -ErrorStatus LL_DAC_Init(DAC_TypeDef *DACx, uint32_t DAC_Channel, LL_DAC_InitTypeDef *DAC_InitStruct); -void LL_DAC_StructInit(LL_DAC_InitTypeDef *DAC_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_DAC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h deleted file mode 100644 index 63264e614d0e49b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h +++ /dev/null @@ -1,2870 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dma.h - * @author MCD Application Team - * @brief Header file of DMA LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_DMA_H -#define __STM32F4xx_LL_DMA_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (DMA1) || defined (DMA2) - -/** @defgroup DMA_LL DMA - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup DMA_LL_Private_Variables DMA Private Variables - * @{ - */ -/* Array used to get the DMA stream register offset versus stream index LL_DMA_STREAM_x */ -static const uint8_t STREAM_OFFSET_TAB[] = -{ - (uint8_t)(DMA1_Stream0_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream1_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream2_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream3_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream4_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream5_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream6_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream7_BASE - DMA1_BASE) -}; - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DMA_LL_Private_Constants DMA Private Constants - * @{ - */ -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA_LL_ES_INIT DMA Exported Init structure - * @{ - */ -typedef struct -{ - uint32_t PeriphOrM2MSrcAddress; /*!< Specifies the peripheral base address for DMA transfer - or as Source base address in case of memory to memory transfer direction. - - This parameter must be a value between Min_Data = 0 and Max_Data = 0xFFFFFFFF. */ - - uint32_t MemoryOrM2MDstAddress; /*!< Specifies the memory base address for DMA transfer - or as Destination base address in case of memory to memory transfer direction. - - This parameter must be a value between Min_Data = 0 and Max_Data = 0xFFFFFFFF. */ - - uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral, - from memory to memory or from peripheral to memory. - This parameter can be a value of @ref DMA_LL_EC_DIRECTION - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetDataTransferDirection(). */ - - uint32_t Mode; /*!< Specifies the normal or circular operation mode. - This parameter can be a value of @ref DMA_LL_EC_MODE - @note The circular buffer mode cannot be used if the memory to memory - data transfer direction is configured on the selected Stream - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMode(). */ - - uint32_t PeriphOrM2MSrcIncMode; /*!< Specifies whether the Peripheral address or Source address in case of memory to memory transfer direction - is incremented or not. - This parameter can be a value of @ref DMA_LL_EC_PERIPH - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphIncMode(). */ - - uint32_t MemoryOrM2MDstIncMode; /*!< Specifies whether the Memory address or Destination address in case of memory to memory transfer direction - is incremented or not. - This parameter can be a value of @ref DMA_LL_EC_MEMORY - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemoryIncMode(). */ - - uint32_t PeriphOrM2MSrcDataSize; /*!< Specifies the Peripheral data size alignment or Source data size alignment (byte, half word, word) - in case of memory to memory transfer direction. - This parameter can be a value of @ref DMA_LL_EC_PDATAALIGN - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphSize(). */ - - uint32_t MemoryOrM2MDstDataSize; /*!< Specifies the Memory data size alignment or Destination data size alignment (byte, half word, word) - in case of memory to memory transfer direction. - This parameter can be a value of @ref DMA_LL_EC_MDATAALIGN - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemorySize(). */ - - uint32_t NbData; /*!< Specifies the number of data to transfer, in data unit. - The data unit is equal to the source buffer configuration set in PeripheralSize - or MemorySize parameters depending in the transfer direction. - This parameter must be a value between Min_Data = 0 and Max_Data = 0x0000FFFF - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetDataLength(). */ - - uint32_t Channel; /*!< Specifies the peripheral channel. - This parameter can be a value of @ref DMA_LL_EC_CHANNEL - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetChannelSelection(). */ - - uint32_t Priority; /*!< Specifies the channel priority level. - This parameter can be a value of @ref DMA_LL_EC_PRIORITY - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetStreamPriorityLevel(). */ - - uint32_t FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified stream. - This parameter can be a value of @ref DMA_LL_FIFOMODE - @note The Direct mode (FIFO mode disabled) cannot be used if the - memory-to-memory data transfer is configured on the selected stream - - This feature can be modified afterwards using unitary functions @ref LL_DMA_EnableFifoMode() or @ref LL_DMA_EnableFifoMode() . */ - - uint32_t FIFOThreshold; /*!< Specifies the FIFO threshold level. - This parameter can be a value of @ref DMA_LL_EC_FIFOTHRESHOLD - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetFIFOThreshold(). */ - - uint32_t MemBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_LL_EC_MBURST - @note The burst mode is possible only if the address Increment mode is enabled. - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemoryBurstxfer(). */ - - uint32_t PeriphBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_LL_EC_PBURST - @note The burst mode is possible only if the address Increment mode is enabled. - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphBurstxfer(). */ - -} LL_DMA_InitTypeDef; -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DMA_LL_Exported_Constants DMA Exported Constants - * @{ - */ - -/** @defgroup DMA_LL_EC_STREAM STREAM - * @{ - */ -#define LL_DMA_STREAM_0 0x00000000U -#define LL_DMA_STREAM_1 0x00000001U -#define LL_DMA_STREAM_2 0x00000002U -#define LL_DMA_STREAM_3 0x00000003U -#define LL_DMA_STREAM_4 0x00000004U -#define LL_DMA_STREAM_5 0x00000005U -#define LL_DMA_STREAM_6 0x00000006U -#define LL_DMA_STREAM_7 0x00000007U -#define LL_DMA_STREAM_ALL 0xFFFF0000U -/** - * @} - */ - -/** @defgroup DMA_LL_EC_DIRECTION DIRECTION - * @{ - */ -#define LL_DMA_DIRECTION_PERIPH_TO_MEMORY 0x00000000U /*!< Peripheral to memory direction */ -#define LL_DMA_DIRECTION_MEMORY_TO_PERIPH DMA_SxCR_DIR_0 /*!< Memory to peripheral direction */ -#define LL_DMA_DIRECTION_MEMORY_TO_MEMORY DMA_SxCR_DIR_1 /*!< Memory to memory direction */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MODE MODE - * @{ - */ -#define LL_DMA_MODE_NORMAL 0x00000000U /*!< Normal Mode */ -#define LL_DMA_MODE_CIRCULAR DMA_SxCR_CIRC /*!< Circular Mode */ -#define LL_DMA_MODE_PFCTRL DMA_SxCR_PFCTRL /*!< Peripheral flow control mode */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_DOUBLEBUFFER_MODE DOUBLEBUFFER MODE - * @{ - */ -#define LL_DMA_DOUBLEBUFFER_MODE_DISABLE 0x00000000U /*!< Disable double buffering mode */ -#define LL_DMA_DOUBLEBUFFER_MODE_ENABLE DMA_SxCR_DBM /*!< Enable double buffering mode */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PERIPH PERIPH - * @{ - */ -#define LL_DMA_PERIPH_NOINCREMENT 0x00000000U /*!< Peripheral increment mode Disable */ -#define LL_DMA_PERIPH_INCREMENT DMA_SxCR_PINC /*!< Peripheral increment mode Enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MEMORY MEMORY - * @{ - */ -#define LL_DMA_MEMORY_NOINCREMENT 0x00000000U /*!< Memory increment mode Disable */ -#define LL_DMA_MEMORY_INCREMENT DMA_SxCR_MINC /*!< Memory increment mode Enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PDATAALIGN PDATAALIGN - * @{ - */ -#define LL_DMA_PDATAALIGN_BYTE 0x00000000U /*!< Peripheral data alignment : Byte */ -#define LL_DMA_PDATAALIGN_HALFWORD DMA_SxCR_PSIZE_0 /*!< Peripheral data alignment : HalfWord */ -#define LL_DMA_PDATAALIGN_WORD DMA_SxCR_PSIZE_1 /*!< Peripheral data alignment : Word */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MDATAALIGN MDATAALIGN - * @{ - */ -#define LL_DMA_MDATAALIGN_BYTE 0x00000000U /*!< Memory data alignment : Byte */ -#define LL_DMA_MDATAALIGN_HALFWORD DMA_SxCR_MSIZE_0 /*!< Memory data alignment : HalfWord */ -#define LL_DMA_MDATAALIGN_WORD DMA_SxCR_MSIZE_1 /*!< Memory data alignment : Word */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_OFFSETSIZE OFFSETSIZE - * @{ - */ -#define LL_DMA_OFFSETSIZE_PSIZE 0x00000000U /*!< Peripheral increment offset size is linked to the PSIZE */ -#define LL_DMA_OFFSETSIZE_FIXEDTO4 DMA_SxCR_PINCOS /*!< Peripheral increment offset size is fixed to 4 (32-bit alignment) */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PRIORITY PRIORITY - * @{ - */ -#define LL_DMA_PRIORITY_LOW 0x00000000U /*!< Priority level : Low */ -#define LL_DMA_PRIORITY_MEDIUM DMA_SxCR_PL_0 /*!< Priority level : Medium */ -#define LL_DMA_PRIORITY_HIGH DMA_SxCR_PL_1 /*!< Priority level : High */ -#define LL_DMA_PRIORITY_VERYHIGH DMA_SxCR_PL /*!< Priority level : Very_High */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_CHANNEL CHANNEL - * @{ - */ -#define LL_DMA_CHANNEL_0 0x00000000U /* Select Channel0 of DMA Instance */ -#define LL_DMA_CHANNEL_1 DMA_SxCR_CHSEL_0 /* Select Channel1 of DMA Instance */ -#define LL_DMA_CHANNEL_2 DMA_SxCR_CHSEL_1 /* Select Channel2 of DMA Instance */ -#define LL_DMA_CHANNEL_3 (DMA_SxCR_CHSEL_0 | DMA_SxCR_CHSEL_1) /* Select Channel3 of DMA Instance */ -#define LL_DMA_CHANNEL_4 DMA_SxCR_CHSEL_2 /* Select Channel4 of DMA Instance */ -#define LL_DMA_CHANNEL_5 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_0) /* Select Channel5 of DMA Instance */ -#define LL_DMA_CHANNEL_6 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1) /* Select Channel6 of DMA Instance */ -#define LL_DMA_CHANNEL_7 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel7 of DMA Instance */ -#if defined (DMA_SxCR_CHSEL_3) -#define LL_DMA_CHANNEL_8 DMA_SxCR_CHSEL_3 /* Select Channel8 of DMA Instance */ -#define LL_DMA_CHANNEL_9 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_0) /* Select Channel9 of DMA Instance */ -#define LL_DMA_CHANNEL_10 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_1) /* Select Channel10 of DMA Instance */ -#define LL_DMA_CHANNEL_11 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel11 of DMA Instance */ -#define LL_DMA_CHANNEL_12 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2) /* Select Channel12 of DMA Instance */ -#define LL_DMA_CHANNEL_13 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_0) /* Select Channel13 of DMA Instance */ -#define LL_DMA_CHANNEL_14 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1) /* Select Channel14 of DMA Instance */ -#define LL_DMA_CHANNEL_15 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel15 of DMA Instance */ -#endif /* DMA_SxCR_CHSEL_3 */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MBURST MBURST - * @{ - */ -#define LL_DMA_MBURST_SINGLE 0x00000000U /*!< Memory burst single transfer configuration */ -#define LL_DMA_MBURST_INC4 DMA_SxCR_MBURST_0 /*!< Memory burst of 4 beats transfer configuration */ -#define LL_DMA_MBURST_INC8 DMA_SxCR_MBURST_1 /*!< Memory burst of 8 beats transfer configuration */ -#define LL_DMA_MBURST_INC16 (DMA_SxCR_MBURST_0 | DMA_SxCR_MBURST_1) /*!< Memory burst of 16 beats transfer configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PBURST PBURST - * @{ - */ -#define LL_DMA_PBURST_SINGLE 0x00000000U /*!< Peripheral burst single transfer configuration */ -#define LL_DMA_PBURST_INC4 DMA_SxCR_PBURST_0 /*!< Peripheral burst of 4 beats transfer configuration */ -#define LL_DMA_PBURST_INC8 DMA_SxCR_PBURST_1 /*!< Peripheral burst of 8 beats transfer configuration */ -#define LL_DMA_PBURST_INC16 (DMA_SxCR_PBURST_0 | DMA_SxCR_PBURST_1) /*!< Peripheral burst of 16 beats transfer configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_FIFOMODE DMA_LL_FIFOMODE - * @{ - */ -#define LL_DMA_FIFOMODE_DISABLE 0x00000000U /*!< FIFO mode disable (direct mode is enabled) */ -#define LL_DMA_FIFOMODE_ENABLE DMA_SxFCR_DMDIS /*!< FIFO mode enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_FIFOSTATUS_0 FIFOSTATUS 0 - * @{ - */ -#define LL_DMA_FIFOSTATUS_0_25 0x00000000U /*!< 0 < fifo_level < 1/4 */ -#define LL_DMA_FIFOSTATUS_25_50 DMA_SxFCR_FS_0 /*!< 1/4 < fifo_level < 1/2 */ -#define LL_DMA_FIFOSTATUS_50_75 DMA_SxFCR_FS_1 /*!< 1/2 < fifo_level < 3/4 */ -#define LL_DMA_FIFOSTATUS_75_100 (DMA_SxFCR_FS_1 | DMA_SxFCR_FS_0) /*!< 3/4 < fifo_level < full */ -#define LL_DMA_FIFOSTATUS_EMPTY DMA_SxFCR_FS_2 /*!< FIFO is empty */ -#define LL_DMA_FIFOSTATUS_FULL (DMA_SxFCR_FS_2 | DMA_SxFCR_FS_0) /*!< FIFO is full */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_FIFOTHRESHOLD FIFOTHRESHOLD - * @{ - */ -#define LL_DMA_FIFOTHRESHOLD_1_4 0x00000000U /*!< FIFO threshold 1 quart full configuration */ -#define LL_DMA_FIFOTHRESHOLD_1_2 DMA_SxFCR_FTH_0 /*!< FIFO threshold half full configuration */ -#define LL_DMA_FIFOTHRESHOLD_3_4 DMA_SxFCR_FTH_1 /*!< FIFO threshold 3 quarts full configuration */ -#define LL_DMA_FIFOTHRESHOLD_FULL DMA_SxFCR_FTH /*!< FIFO threshold full configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_CURRENTTARGETMEM CURRENTTARGETMEM - * @{ - */ -#define LL_DMA_CURRENTTARGETMEM0 0x00000000U /*!< Set CurrentTarget Memory to Memory 0 */ -#define LL_DMA_CURRENTTARGETMEM1 DMA_SxCR_CT /*!< Set CurrentTarget Memory to Memory 1 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DMA_LL_Exported_Macros DMA Exported Macros - * @{ - */ - -/** @defgroup DMA_LL_EM_WRITE_READ Common Write and read registers macros - * @{ - */ -/** - * @brief Write a value in DMA register - * @param __INSTANCE__ DMA Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_DMA_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in DMA register - * @param __INSTANCE__ DMA Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_DMA_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup DMA_LL_EM_CONVERT_DMAxCHANNELy Convert DMAxStreamy - * @{ - */ -/** - * @brief Convert DMAx_Streamy into DMAx - * @param __STREAM_INSTANCE__ DMAx_Streamy - * @retval DMAx - */ -#define __LL_DMA_GET_INSTANCE(__STREAM_INSTANCE__) \ -(((uint32_t)(__STREAM_INSTANCE__) > ((uint32_t)DMA1_Stream7)) ? DMA2 : DMA1) - -/** - * @brief Convert DMAx_Streamy into LL_DMA_STREAM_y - * @param __STREAM_INSTANCE__ DMAx_Streamy - * @retval LL_DMA_CHANNEL_y - */ -#define __LL_DMA_GET_STREAM(__STREAM_INSTANCE__) \ -(((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream0)) ? LL_DMA_STREAM_0 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream0)) ? LL_DMA_STREAM_0 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream1)) ? LL_DMA_STREAM_1 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream1)) ? LL_DMA_STREAM_1 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream2)) ? LL_DMA_STREAM_2 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream2)) ? LL_DMA_STREAM_2 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream3)) ? LL_DMA_STREAM_3 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream3)) ? LL_DMA_STREAM_3 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream4)) ? LL_DMA_STREAM_4 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream4)) ? LL_DMA_STREAM_4 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream5)) ? LL_DMA_STREAM_5 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream5)) ? LL_DMA_STREAM_5 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream6)) ? LL_DMA_STREAM_6 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream6)) ? LL_DMA_STREAM_6 : \ - LL_DMA_STREAM_7) - -/** - * @brief Convert DMA Instance DMAx and LL_DMA_STREAM_y into DMAx_Streamy - * @param __DMA_INSTANCE__ DMAx - * @param __STREAM__ LL_DMA_STREAM_y - * @retval DMAx_Streamy - */ -#define __LL_DMA_GET_STREAM_INSTANCE(__DMA_INSTANCE__, __STREAM__) \ -((((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_0))) ? DMA1_Stream0 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_0))) ? DMA2_Stream0 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_1))) ? DMA1_Stream1 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_1))) ? DMA2_Stream1 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_2))) ? DMA1_Stream2 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_2))) ? DMA2_Stream2 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_3))) ? DMA1_Stream3 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_3))) ? DMA2_Stream3 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_4))) ? DMA1_Stream4 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_4))) ? DMA2_Stream4 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_5))) ? DMA1_Stream5 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_5))) ? DMA2_Stream5 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_6))) ? DMA1_Stream6 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_6))) ? DMA2_Stream6 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_7))) ? DMA1_Stream7 : \ - DMA2_Stream7) - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ - /** @defgroup DMA_LL_Exported_Functions DMA Exported Functions - * @{ - */ - -/** @defgroup DMA_LL_EF_Configuration Configuration - * @{ - */ -/** - * @brief Enable DMA stream. - * @rmtoll CR EN LL_DMA_EnableStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN); -} - -/** - * @brief Disable DMA stream. - * @rmtoll CR EN LL_DMA_DisableStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN); -} - -/** - * @brief Check if DMA stream is enabled or disabled. - * @rmtoll CR EN LL_DMA_IsEnabledStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN) == (DMA_SxCR_EN)); -} - -/** - * @brief Configure all parameters linked to DMA transfer. - * @rmtoll CR DIR LL_DMA_ConfigTransfer\n - * CR CIRC LL_DMA_ConfigTransfer\n - * CR PINC LL_DMA_ConfigTransfer\n - * CR MINC LL_DMA_ConfigTransfer\n - * CR PSIZE LL_DMA_ConfigTransfer\n - * CR MSIZE LL_DMA_ConfigTransfer\n - * CR PL LL_DMA_ConfigTransfer\n - * CR PFCTRL LL_DMA_ConfigTransfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Configuration This parameter must be a combination of all the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY or @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH or @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @arg @ref LL_DMA_MODE_NORMAL or @ref LL_DMA_MODE_CIRCULAR or @ref LL_DMA_MODE_PFCTRL - * @arg @ref LL_DMA_PERIPH_INCREMENT or @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT or @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_PDATAALIGN_BYTE or @ref LL_DMA_PDATAALIGN_HALFWORD or @ref LL_DMA_PDATAALIGN_WORD - * @arg @ref LL_DMA_MDATAALIGN_BYTE or @ref LL_DMA_MDATAALIGN_HALFWORD or @ref LL_DMA_MDATAALIGN_WORD - * @arg @ref LL_DMA_PRIORITY_LOW or @ref LL_DMA_PRIORITY_MEDIUM or @ref LL_DMA_PRIORITY_HIGH or @ref LL_DMA_PRIORITY_VERYHIGH - *@retval None - */ -__STATIC_INLINE void LL_DMA_ConfigTransfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Configuration) -{ - MODIFY_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, - DMA_SxCR_DIR | DMA_SxCR_CIRC | DMA_SxCR_PINC | DMA_SxCR_MINC | DMA_SxCR_PSIZE | DMA_SxCR_MSIZE | DMA_SxCR_PL | DMA_SxCR_PFCTRL, - Configuration); -} - -/** - * @brief Set Data transfer direction (read from peripheral or from memory). - * @rmtoll CR DIR LL_DMA_SetDataTransferDirection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Direction This parameter can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetDataTransferDirection(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Direction) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DIR, Direction); -} - -/** - * @brief Get Data transfer direction (read from peripheral or from memory). - * @rmtoll CR DIR LL_DMA_GetDataTransferDirection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - */ -__STATIC_INLINE uint32_t LL_DMA_GetDataTransferDirection(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DIR)); -} - -/** - * @brief Set DMA mode normal, circular or peripheral flow control. - * @rmtoll CR CIRC LL_DMA_SetMode\n - * CR PFCTRL LL_DMA_SetMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_DMA_MODE_NORMAL - * @arg @ref LL_DMA_MODE_CIRCULAR - * @arg @ref LL_DMA_MODE_PFCTRL - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Mode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CIRC | DMA_SxCR_PFCTRL, Mode); -} - -/** - * @brief Get DMA mode normal, circular or peripheral flow control. - * @rmtoll CR CIRC LL_DMA_GetMode\n - * CR PFCTRL LL_DMA_GetMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MODE_NORMAL - * @arg @ref LL_DMA_MODE_CIRCULAR - * @arg @ref LL_DMA_MODE_PFCTRL - */ -__STATIC_INLINE uint32_t LL_DMA_GetMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CIRC | DMA_SxCR_PFCTRL)); -} - -/** - * @brief Set Peripheral increment mode. - * @rmtoll CR PINC LL_DMA_SetPeriphIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param IncrementMode This parameter can be one of the following values: - * @arg @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_PERIPH_INCREMENT - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphIncMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t IncrementMode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINC, IncrementMode); -} - -/** - * @brief Get Peripheral increment mode. - * @rmtoll CR PINC LL_DMA_GetPeriphIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_PERIPH_INCREMENT - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphIncMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINC)); -} - -/** - * @brief Set Memory increment mode. - * @rmtoll CR MINC LL_DMA_SetMemoryIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param IncrementMode This parameter can be one of the following values: - * @arg @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryIncMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t IncrementMode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MINC, IncrementMode); -} - -/** - * @brief Get Memory increment mode. - * @rmtoll CR MINC LL_DMA_GetMemoryIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryIncMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MINC)); -} - -/** - * @brief Set Peripheral size. - * @rmtoll CR PSIZE LL_DMA_SetPeriphSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Size This parameter can be one of the following values: - * @arg @ref LL_DMA_PDATAALIGN_BYTE - * @arg @ref LL_DMA_PDATAALIGN_HALFWORD - * @arg @ref LL_DMA_PDATAALIGN_WORD - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphSize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Size) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PSIZE, Size); -} - -/** - * @brief Get Peripheral size. - * @rmtoll CR PSIZE LL_DMA_GetPeriphSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PDATAALIGN_BYTE - * @arg @ref LL_DMA_PDATAALIGN_HALFWORD - * @arg @ref LL_DMA_PDATAALIGN_WORD - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphSize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PSIZE)); -} - -/** - * @brief Set Memory size. - * @rmtoll CR MSIZE LL_DMA_SetMemorySize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Size This parameter can be one of the following values: - * @arg @ref LL_DMA_MDATAALIGN_BYTE - * @arg @ref LL_DMA_MDATAALIGN_HALFWORD - * @arg @ref LL_DMA_MDATAALIGN_WORD - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemorySize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Size) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MSIZE, Size); -} - -/** - * @brief Get Memory size. - * @rmtoll CR MSIZE LL_DMA_GetMemorySize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MDATAALIGN_BYTE - * @arg @ref LL_DMA_MDATAALIGN_HALFWORD - * @arg @ref LL_DMA_MDATAALIGN_WORD - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemorySize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MSIZE)); -} - -/** - * @brief Set Peripheral increment offset size. - * @rmtoll CR PINCOS LL_DMA_SetIncOffsetSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param OffsetSize This parameter can be one of the following values: - * @arg @ref LL_DMA_OFFSETSIZE_PSIZE - * @arg @ref LL_DMA_OFFSETSIZE_FIXEDTO4 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetIncOffsetSize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t OffsetSize) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINCOS, OffsetSize); -} - -/** - * @brief Get Peripheral increment offset size. - * @rmtoll CR PINCOS LL_DMA_GetIncOffsetSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_OFFSETSIZE_PSIZE - * @arg @ref LL_DMA_OFFSETSIZE_FIXEDTO4 - */ -__STATIC_INLINE uint32_t LL_DMA_GetIncOffsetSize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINCOS)); -} - -/** - * @brief Set Stream priority level. - * @rmtoll CR PL LL_DMA_SetStreamPriorityLevel - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Priority This parameter can be one of the following values: - * @arg @ref LL_DMA_PRIORITY_LOW - * @arg @ref LL_DMA_PRIORITY_MEDIUM - * @arg @ref LL_DMA_PRIORITY_HIGH - * @arg @ref LL_DMA_PRIORITY_VERYHIGH - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetStreamPriorityLevel(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Priority) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PL, Priority); -} - -/** - * @brief Get Stream priority level. - * @rmtoll CR PL LL_DMA_GetStreamPriorityLevel - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PRIORITY_LOW - * @arg @ref LL_DMA_PRIORITY_MEDIUM - * @arg @ref LL_DMA_PRIORITY_HIGH - * @arg @ref LL_DMA_PRIORITY_VERYHIGH - */ -__STATIC_INLINE uint32_t LL_DMA_GetStreamPriorityLevel(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PL)); -} - -/** - * @brief Set Number of data to transfer. - * @rmtoll NDTR NDT LL_DMA_SetDataLength - * @note This action has no effect if - * stream is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param NbData Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetDataLength(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t NbData) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->NDTR, DMA_SxNDT, NbData); -} - -/** - * @brief Get Number of data to transfer. - * @rmtoll NDTR NDT LL_DMA_GetDataLength - * @note Once the stream is enabled, the return value indicate the - * remaining bytes to be transmitted. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetDataLength(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->NDTR, DMA_SxNDT)); -} - -/** - * @brief Select Channel number associated to the Stream. - * @rmtoll CR CHSEL LL_DMA_SetChannelSelection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_DMA_CHANNEL_0 - * @arg @ref LL_DMA_CHANNEL_1 - * @arg @ref LL_DMA_CHANNEL_2 - * @arg @ref LL_DMA_CHANNEL_3 - * @arg @ref LL_DMA_CHANNEL_4 - * @arg @ref LL_DMA_CHANNEL_5 - * @arg @ref LL_DMA_CHANNEL_6 - * @arg @ref LL_DMA_CHANNEL_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetChannelSelection(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Channel) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CHSEL, Channel); -} - -/** - * @brief Get the Channel number associated to the Stream. - * @rmtoll CR CHSEL LL_DMA_GetChannelSelection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_CHANNEL_0 - * @arg @ref LL_DMA_CHANNEL_1 - * @arg @ref LL_DMA_CHANNEL_2 - * @arg @ref LL_DMA_CHANNEL_3 - * @arg @ref LL_DMA_CHANNEL_4 - * @arg @ref LL_DMA_CHANNEL_5 - * @arg @ref LL_DMA_CHANNEL_6 - * @arg @ref LL_DMA_CHANNEL_7 - */ -__STATIC_INLINE uint32_t LL_DMA_GetChannelSelection(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CHSEL)); -} - -/** - * @brief Set Memory burst transfer configuration. - * @rmtoll CR MBURST LL_DMA_SetMemoryBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Mburst This parameter can be one of the following values: - * @arg @ref LL_DMA_MBURST_SINGLE - * @arg @ref LL_DMA_MBURST_INC4 - * @arg @ref LL_DMA_MBURST_INC8 - * @arg @ref LL_DMA_MBURST_INC16 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Mburst) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MBURST, Mburst); -} - -/** - * @brief Get Memory burst transfer configuration. - * @rmtoll CR MBURST LL_DMA_GetMemoryBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MBURST_SINGLE - * @arg @ref LL_DMA_MBURST_INC4 - * @arg @ref LL_DMA_MBURST_INC8 - * @arg @ref LL_DMA_MBURST_INC16 - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MBURST)); -} - -/** - * @brief Set Peripheral burst transfer configuration. - * @rmtoll CR PBURST LL_DMA_SetPeriphBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Pburst This parameter can be one of the following values: - * @arg @ref LL_DMA_PBURST_SINGLE - * @arg @ref LL_DMA_PBURST_INC4 - * @arg @ref LL_DMA_PBURST_INC8 - * @arg @ref LL_DMA_PBURST_INC16 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Pburst) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PBURST, Pburst); -} - -/** - * @brief Get Peripheral burst transfer configuration. - * @rmtoll CR PBURST LL_DMA_GetPeriphBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PBURST_SINGLE - * @arg @ref LL_DMA_PBURST_INC4 - * @arg @ref LL_DMA_PBURST_INC8 - * @arg @ref LL_DMA_PBURST_INC16 - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PBURST)); -} - -/** - * @brief Set Current target (only in double buffer mode) to Memory 1 or Memory 0. - * @rmtoll CR CT LL_DMA_SetCurrentTargetMem - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param CurrentMemory This parameter can be one of the following values: - * @arg @ref LL_DMA_CURRENTTARGETMEM0 - * @arg @ref LL_DMA_CURRENTTARGETMEM1 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetCurrentTargetMem(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t CurrentMemory) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CT, CurrentMemory); -} - -/** - * @brief Set Current target (only in double buffer mode) to Memory 1 or Memory 0. - * @rmtoll CR CT LL_DMA_GetCurrentTargetMem - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_CURRENTTARGETMEM0 - * @arg @ref LL_DMA_CURRENTTARGETMEM1 - */ -__STATIC_INLINE uint32_t LL_DMA_GetCurrentTargetMem(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CT)); -} - -/** - * @brief Enable the double buffer mode. - * @rmtoll CR DBM LL_DMA_EnableDoubleBufferMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableDoubleBufferMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DBM); -} - -/** - * @brief Disable the double buffer mode. - * @rmtoll CR DBM LL_DMA_DisableDoubleBufferMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableDoubleBufferMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DBM); -} - -/** - * @brief Get FIFO status. - * @rmtoll FCR FS LL_DMA_GetFIFOStatus - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_FIFOSTATUS_0_25 - * @arg @ref LL_DMA_FIFOSTATUS_25_50 - * @arg @ref LL_DMA_FIFOSTATUS_50_75 - * @arg @ref LL_DMA_FIFOSTATUS_75_100 - * @arg @ref LL_DMA_FIFOSTATUS_EMPTY - * @arg @ref LL_DMA_FIFOSTATUS_FULL - */ -__STATIC_INLINE uint32_t LL_DMA_GetFIFOStatus(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FS)); -} - -/** - * @brief Disable Fifo mode. - * @rmtoll FCR DMDIS LL_DMA_DisableFifoMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableFifoMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_DMDIS); -} - -/** - * @brief Enable Fifo mode. - * @rmtoll FCR DMDIS LL_DMA_EnableFifoMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableFifoMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_DMDIS); -} - -/** - * @brief Select FIFO threshold. - * @rmtoll FCR FTH LL_DMA_SetFIFOThreshold - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Threshold This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetFIFOThreshold(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Threshold) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH, Threshold); -} - -/** - * @brief Get FIFO threshold. - * @rmtoll FCR FTH LL_DMA_GetFIFOThreshold - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - */ -__STATIC_INLINE uint32_t LL_DMA_GetFIFOThreshold(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH)); -} - -/** - * @brief Configure the FIFO . - * @rmtoll FCR FTH LL_DMA_ConfigFifo\n - * FCR DMDIS LL_DMA_ConfigFifo - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param FifoMode This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOMODE_ENABLE - * @arg @ref LL_DMA_FIFOMODE_DISABLE - * @param FifoThreshold This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - * @retval None - */ -__STATIC_INLINE void LL_DMA_ConfigFifo(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t FifoMode, uint32_t FifoThreshold) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH|DMA_SxFCR_DMDIS, FifoMode|FifoThreshold); -} - -/** - * @brief Configure the Source and Destination addresses. - * @note This API must not be called when the DMA stream is enabled. - * @rmtoll M0AR M0A LL_DMA_ConfigAddresses\n - * PAR PA LL_DMA_ConfigAddresses - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param SrcAddress Between 0 to 0xFFFFFFFF - * @param DstAddress Between 0 to 0xFFFFFFFF - * @param Direction This parameter can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @retval None - */ -__STATIC_INLINE void LL_DMA_ConfigAddresses(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t SrcAddress, uint32_t DstAddress, uint32_t Direction) -{ - /* Direction Memory to Periph */ - if (Direction == LL_DMA_DIRECTION_MEMORY_TO_PERIPH) - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, SrcAddress); - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, DstAddress); - } - /* Direction Periph to Memory and Memory to Memory */ - else - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, SrcAddress); - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, DstAddress); - } -} - -/** - * @brief Set the Memory address. - * @rmtoll M0AR M0A LL_DMA_SetMemoryAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, MemoryAddress); -} - -/** - * @brief Set the Peripheral address. - * @rmtoll PAR PA LL_DMA_SetPeriphAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param PeriphAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t PeriphAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, PeriphAddress); -} - -/** - * @brief Get the Memory address. - * @rmtoll M0AR M0A LL_DMA_GetMemoryAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR)); -} - -/** - * @brief Get the Peripheral address. - * @rmtoll PAR PA LL_DMA_GetPeriphAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR)); -} - -/** - * @brief Set the Memory to Memory Source address. - * @rmtoll PAR PA LL_DMA_SetM2MSrcAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetM2MSrcAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, MemoryAddress); -} - -/** - * @brief Set the Memory to Memory Destination address. - * @rmtoll M0AR M0A LL_DMA_SetM2MDstAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetM2MDstAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, MemoryAddress); - } - -/** - * @brief Get the Memory to Memory Source address. - * @rmtoll PAR PA LL_DMA_GetM2MSrcAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetM2MSrcAddress(DMA_TypeDef* DMAx, uint32_t Stream) - { - return (READ_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR)); - } - -/** - * @brief Get the Memory to Memory Destination address. - * @rmtoll M0AR M0A LL_DMA_GetM2MDstAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetM2MDstAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR)); -} - -/** - * @brief Set Memory 1 address (used in case of Double buffer mode). - * @rmtoll M1AR M1A LL_DMA_SetMemory1Address - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Address Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemory1Address(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Address) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M1AR, DMA_SxM1AR_M1A, Address); -} - -/** - * @brief Get Memory 1 address (used in case of Double buffer mode). - * @rmtoll M1AR M1A LL_DMA_GetMemory1Address - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemory1Address(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M1AR); -} - -/** - * @} - */ - -/** @defgroup DMA_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Get Stream 0 half transfer flag. - * @rmtoll LISR HTIF0 LL_DMA_IsActiveFlag_HT0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF0)==(DMA_LISR_HTIF0)); -} - -/** - * @brief Get Stream 1 half transfer flag. - * @rmtoll LISR HTIF1 LL_DMA_IsActiveFlag_HT1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF1)==(DMA_LISR_HTIF1)); -} - -/** - * @brief Get Stream 2 half transfer flag. - * @rmtoll LISR HTIF2 LL_DMA_IsActiveFlag_HT2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF2)==(DMA_LISR_HTIF2)); -} - -/** - * @brief Get Stream 3 half transfer flag. - * @rmtoll LISR HTIF3 LL_DMA_IsActiveFlag_HT3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF3)==(DMA_LISR_HTIF3)); -} - -/** - * @brief Get Stream 4 half transfer flag. - * @rmtoll HISR HTIF4 LL_DMA_IsActiveFlag_HT4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF4)==(DMA_HISR_HTIF4)); -} - -/** - * @brief Get Stream 5 half transfer flag. - * @rmtoll HISR HTIF0 LL_DMA_IsActiveFlag_HT5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF5)==(DMA_HISR_HTIF5)); -} - -/** - * @brief Get Stream 6 half transfer flag. - * @rmtoll HISR HTIF6 LL_DMA_IsActiveFlag_HT6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF6)==(DMA_HISR_HTIF6)); -} - -/** - * @brief Get Stream 7 half transfer flag. - * @rmtoll HISR HTIF7 LL_DMA_IsActiveFlag_HT7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF7)==(DMA_HISR_HTIF7)); -} - -/** - * @brief Get Stream 0 transfer complete flag. - * @rmtoll LISR TCIF0 LL_DMA_IsActiveFlag_TC0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF0)==(DMA_LISR_TCIF0)); -} - -/** - * @brief Get Stream 1 transfer complete flag. - * @rmtoll LISR TCIF1 LL_DMA_IsActiveFlag_TC1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF1)==(DMA_LISR_TCIF1)); -} - -/** - * @brief Get Stream 2 transfer complete flag. - * @rmtoll LISR TCIF2 LL_DMA_IsActiveFlag_TC2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF2)==(DMA_LISR_TCIF2)); -} - -/** - * @brief Get Stream 3 transfer complete flag. - * @rmtoll LISR TCIF3 LL_DMA_IsActiveFlag_TC3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF3)==(DMA_LISR_TCIF3)); -} - -/** - * @brief Get Stream 4 transfer complete flag. - * @rmtoll HISR TCIF4 LL_DMA_IsActiveFlag_TC4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF4)==(DMA_HISR_TCIF4)); -} - -/** - * @brief Get Stream 5 transfer complete flag. - * @rmtoll HISR TCIF0 LL_DMA_IsActiveFlag_TC5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF5)==(DMA_HISR_TCIF5)); -} - -/** - * @brief Get Stream 6 transfer complete flag. - * @rmtoll HISR TCIF6 LL_DMA_IsActiveFlag_TC6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF6)==(DMA_HISR_TCIF6)); -} - -/** - * @brief Get Stream 7 transfer complete flag. - * @rmtoll HISR TCIF7 LL_DMA_IsActiveFlag_TC7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF7)==(DMA_HISR_TCIF7)); -} - -/** - * @brief Get Stream 0 transfer error flag. - * @rmtoll LISR TEIF0 LL_DMA_IsActiveFlag_TE0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF0)==(DMA_LISR_TEIF0)); -} - -/** - * @brief Get Stream 1 transfer error flag. - * @rmtoll LISR TEIF1 LL_DMA_IsActiveFlag_TE1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF1)==(DMA_LISR_TEIF1)); -} - -/** - * @brief Get Stream 2 transfer error flag. - * @rmtoll LISR TEIF2 LL_DMA_IsActiveFlag_TE2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF2)==(DMA_LISR_TEIF2)); -} - -/** - * @brief Get Stream 3 transfer error flag. - * @rmtoll LISR TEIF3 LL_DMA_IsActiveFlag_TE3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF3)==(DMA_LISR_TEIF3)); -} - -/** - * @brief Get Stream 4 transfer error flag. - * @rmtoll HISR TEIF4 LL_DMA_IsActiveFlag_TE4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF4)==(DMA_HISR_TEIF4)); -} - -/** - * @brief Get Stream 5 transfer error flag. - * @rmtoll HISR TEIF0 LL_DMA_IsActiveFlag_TE5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF5)==(DMA_HISR_TEIF5)); -} - -/** - * @brief Get Stream 6 transfer error flag. - * @rmtoll HISR TEIF6 LL_DMA_IsActiveFlag_TE6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF6)==(DMA_HISR_TEIF6)); -} - -/** - * @brief Get Stream 7 transfer error flag. - * @rmtoll HISR TEIF7 LL_DMA_IsActiveFlag_TE7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF7)==(DMA_HISR_TEIF7)); -} - -/** - * @brief Get Stream 0 direct mode error flag. - * @rmtoll LISR DMEIF0 LL_DMA_IsActiveFlag_DME0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF0)==(DMA_LISR_DMEIF0)); -} - -/** - * @brief Get Stream 1 direct mode error flag. - * @rmtoll LISR DMEIF1 LL_DMA_IsActiveFlag_DME1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF1)==(DMA_LISR_DMEIF1)); -} - -/** - * @brief Get Stream 2 direct mode error flag. - * @rmtoll LISR DMEIF2 LL_DMA_IsActiveFlag_DME2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF2)==(DMA_LISR_DMEIF2)); -} - -/** - * @brief Get Stream 3 direct mode error flag. - * @rmtoll LISR DMEIF3 LL_DMA_IsActiveFlag_DME3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF3)==(DMA_LISR_DMEIF3)); -} - -/** - * @brief Get Stream 4 direct mode error flag. - * @rmtoll HISR DMEIF4 LL_DMA_IsActiveFlag_DME4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF4)==(DMA_HISR_DMEIF4)); -} - -/** - * @brief Get Stream 5 direct mode error flag. - * @rmtoll HISR DMEIF0 LL_DMA_IsActiveFlag_DME5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF5)==(DMA_HISR_DMEIF5)); -} - -/** - * @brief Get Stream 6 direct mode error flag. - * @rmtoll HISR DMEIF6 LL_DMA_IsActiveFlag_DME6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF6)==(DMA_HISR_DMEIF6)); -} - -/** - * @brief Get Stream 7 direct mode error flag. - * @rmtoll HISR DMEIF7 LL_DMA_IsActiveFlag_DME7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF7)==(DMA_HISR_DMEIF7)); -} - -/** - * @brief Get Stream 0 FIFO error flag. - * @rmtoll LISR FEIF0 LL_DMA_IsActiveFlag_FE0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF0)==(DMA_LISR_FEIF0)); -} - -/** - * @brief Get Stream 1 FIFO error flag. - * @rmtoll LISR FEIF1 LL_DMA_IsActiveFlag_FE1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF1)==(DMA_LISR_FEIF1)); -} - -/** - * @brief Get Stream 2 FIFO error flag. - * @rmtoll LISR FEIF2 LL_DMA_IsActiveFlag_FE2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF2)==(DMA_LISR_FEIF2)); -} - -/** - * @brief Get Stream 3 FIFO error flag. - * @rmtoll LISR FEIF3 LL_DMA_IsActiveFlag_FE3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF3)==(DMA_LISR_FEIF3)); -} - -/** - * @brief Get Stream 4 FIFO error flag. - * @rmtoll HISR FEIF4 LL_DMA_IsActiveFlag_FE4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF4)==(DMA_HISR_FEIF4)); -} - -/** - * @brief Get Stream 5 FIFO error flag. - * @rmtoll HISR FEIF0 LL_DMA_IsActiveFlag_FE5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF5)==(DMA_HISR_FEIF5)); -} - -/** - * @brief Get Stream 6 FIFO error flag. - * @rmtoll HISR FEIF6 LL_DMA_IsActiveFlag_FE6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF6)==(DMA_HISR_FEIF6)); -} - -/** - * @brief Get Stream 7 FIFO error flag. - * @rmtoll HISR FEIF7 LL_DMA_IsActiveFlag_FE7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF7)==(DMA_HISR_FEIF7)); -} - -/** - * @brief Clear Stream 0 half transfer flag. - * @rmtoll LIFCR CHTIF0 LL_DMA_ClearFlag_HT0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF0); -} - -/** - * @brief Clear Stream 1 half transfer flag. - * @rmtoll LIFCR CHTIF1 LL_DMA_ClearFlag_HT1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF1); -} - -/** - * @brief Clear Stream 2 half transfer flag. - * @rmtoll LIFCR CHTIF2 LL_DMA_ClearFlag_HT2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF2); -} - -/** - * @brief Clear Stream 3 half transfer flag. - * @rmtoll LIFCR CHTIF3 LL_DMA_ClearFlag_HT3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF3); -} - -/** - * @brief Clear Stream 4 half transfer flag. - * @rmtoll HIFCR CHTIF4 LL_DMA_ClearFlag_HT4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF4); -} - -/** - * @brief Clear Stream 5 half transfer flag. - * @rmtoll HIFCR CHTIF5 LL_DMA_ClearFlag_HT5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF5); -} - -/** - * @brief Clear Stream 6 half transfer flag. - * @rmtoll HIFCR CHTIF6 LL_DMA_ClearFlag_HT6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF6); -} - -/** - * @brief Clear Stream 7 half transfer flag. - * @rmtoll HIFCR CHTIF7 LL_DMA_ClearFlag_HT7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF7); -} - -/** - * @brief Clear Stream 0 transfer complete flag. - * @rmtoll LIFCR CTCIF0 LL_DMA_ClearFlag_TC0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF0); -} - -/** - * @brief Clear Stream 1 transfer complete flag. - * @rmtoll LIFCR CTCIF1 LL_DMA_ClearFlag_TC1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF1); -} - -/** - * @brief Clear Stream 2 transfer complete flag. - * @rmtoll LIFCR CTCIF2 LL_DMA_ClearFlag_TC2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF2); -} - -/** - * @brief Clear Stream 3 transfer complete flag. - * @rmtoll LIFCR CTCIF3 LL_DMA_ClearFlag_TC3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF3); -} - -/** - * @brief Clear Stream 4 transfer complete flag. - * @rmtoll HIFCR CTCIF4 LL_DMA_ClearFlag_TC4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF4); -} - -/** - * @brief Clear Stream 5 transfer complete flag. - * @rmtoll HIFCR CTCIF5 LL_DMA_ClearFlag_TC5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF5); -} - -/** - * @brief Clear Stream 6 transfer complete flag. - * @rmtoll HIFCR CTCIF6 LL_DMA_ClearFlag_TC6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF6); -} - -/** - * @brief Clear Stream 7 transfer complete flag. - * @rmtoll HIFCR CTCIF7 LL_DMA_ClearFlag_TC7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF7); -} - -/** - * @brief Clear Stream 0 transfer error flag. - * @rmtoll LIFCR CTEIF0 LL_DMA_ClearFlag_TE0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF0); -} - -/** - * @brief Clear Stream 1 transfer error flag. - * @rmtoll LIFCR CTEIF1 LL_DMA_ClearFlag_TE1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF1); -} - -/** - * @brief Clear Stream 2 transfer error flag. - * @rmtoll LIFCR CTEIF2 LL_DMA_ClearFlag_TE2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF2); -} - -/** - * @brief Clear Stream 3 transfer error flag. - * @rmtoll LIFCR CTEIF3 LL_DMA_ClearFlag_TE3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF3); -} - -/** - * @brief Clear Stream 4 transfer error flag. - * @rmtoll HIFCR CTEIF4 LL_DMA_ClearFlag_TE4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF4); -} - -/** - * @brief Clear Stream 5 transfer error flag. - * @rmtoll HIFCR CTEIF5 LL_DMA_ClearFlag_TE5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF5); -} - -/** - * @brief Clear Stream 6 transfer error flag. - * @rmtoll HIFCR CTEIF6 LL_DMA_ClearFlag_TE6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF6); -} - -/** - * @brief Clear Stream 7 transfer error flag. - * @rmtoll HIFCR CTEIF7 LL_DMA_ClearFlag_TE7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF7); -} - -/** - * @brief Clear Stream 0 direct mode error flag. - * @rmtoll LIFCR CDMEIF0 LL_DMA_ClearFlag_DME0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF0); -} - -/** - * @brief Clear Stream 1 direct mode error flag. - * @rmtoll LIFCR CDMEIF1 LL_DMA_ClearFlag_DME1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF1); -} - -/** - * @brief Clear Stream 2 direct mode error flag. - * @rmtoll LIFCR CDMEIF2 LL_DMA_ClearFlag_DME2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF2); -} - -/** - * @brief Clear Stream 3 direct mode error flag. - * @rmtoll LIFCR CDMEIF3 LL_DMA_ClearFlag_DME3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF3); -} - -/** - * @brief Clear Stream 4 direct mode error flag. - * @rmtoll HIFCR CDMEIF4 LL_DMA_ClearFlag_DME4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF4); -} - -/** - * @brief Clear Stream 5 direct mode error flag. - * @rmtoll HIFCR CDMEIF5 LL_DMA_ClearFlag_DME5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF5); -} - -/** - * @brief Clear Stream 6 direct mode error flag. - * @rmtoll HIFCR CDMEIF6 LL_DMA_ClearFlag_DME6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF6); -} - -/** - * @brief Clear Stream 7 direct mode error flag. - * @rmtoll HIFCR CDMEIF7 LL_DMA_ClearFlag_DME7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF7); -} - -/** - * @brief Clear Stream 0 FIFO error flag. - * @rmtoll LIFCR CFEIF0 LL_DMA_ClearFlag_FE0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF0); -} - -/** - * @brief Clear Stream 1 FIFO error flag. - * @rmtoll LIFCR CFEIF1 LL_DMA_ClearFlag_FE1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF1); -} - -/** - * @brief Clear Stream 2 FIFO error flag. - * @rmtoll LIFCR CFEIF2 LL_DMA_ClearFlag_FE2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF2); -} - -/** - * @brief Clear Stream 3 FIFO error flag. - * @rmtoll LIFCR CFEIF3 LL_DMA_ClearFlag_FE3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF3); -} - -/** - * @brief Clear Stream 4 FIFO error flag. - * @rmtoll HIFCR CFEIF4 LL_DMA_ClearFlag_FE4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF4); -} - -/** - * @brief Clear Stream 5 FIFO error flag. - * @rmtoll HIFCR CFEIF5 LL_DMA_ClearFlag_FE5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF5); -} - -/** - * @brief Clear Stream 6 FIFO error flag. - * @rmtoll HIFCR CFEIF6 LL_DMA_ClearFlag_FE6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF6); -} - -/** - * @brief Clear Stream 7 FIFO error flag. - * @rmtoll HIFCR CFEIF7 LL_DMA_ClearFlag_FE7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF7); -} - -/** - * @} - */ - -/** @defgroup DMA_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable Half transfer interrupt. - * @rmtoll CR HTIE LL_DMA_EnableIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE); -} - -/** - * @brief Enable Transfer error interrupt. - * @rmtoll CR TEIE LL_DMA_EnableIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE); -} - -/** - * @brief Enable Transfer complete interrupt. - * @rmtoll CR TCIE LL_DMA_EnableIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE); -} - -/** - * @brief Enable Direct mode error interrupt. - * @rmtoll CR DMEIE LL_DMA_EnableIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE); -} - -/** - * @brief Enable FIFO error interrupt. - * @rmtoll FCR FEIE LL_DMA_EnableIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE); -} - -/** - * @brief Disable Half transfer interrupt. - * @rmtoll CR HTIE LL_DMA_DisableIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE); -} - -/** - * @brief Disable Transfer error interrupt. - * @rmtoll CR TEIE LL_DMA_DisableIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE); -} - -/** - * @brief Disable Transfer complete interrupt. - * @rmtoll CR TCIE LL_DMA_DisableIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE); -} - -/** - * @brief Disable Direct mode error interrupt. - * @rmtoll CR DMEIE LL_DMA_DisableIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE); -} - -/** - * @brief Disable FIFO error interrupt. - * @rmtoll FCR FEIE LL_DMA_DisableIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE); -} - -/** - * @brief Check if Half transfer interrup is enabled. - * @rmtoll CR HTIE LL_DMA_IsEnabledIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE) == DMA_SxCR_HTIE); -} - -/** - * @brief Check if Transfer error nterrup is enabled. - * @rmtoll CR TEIE LL_DMA_IsEnabledIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE) == DMA_SxCR_TEIE); -} - -/** - * @brief Check if Transfer complete interrup is enabled. - * @rmtoll CR TCIE LL_DMA_IsEnabledIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE) == DMA_SxCR_TCIE); -} - -/** - * @brief Check if Direct mode error interrupt is enabled. - * @rmtoll CR DMEIE LL_DMA_IsEnabledIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE) == DMA_SxCR_DMEIE); -} - -/** - * @brief Check if FIFO error interrup is enabled. - * @rmtoll FCR FEIE LL_DMA_IsEnabledIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE) == DMA_SxFCR_FEIE); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_DMA_Init(DMA_TypeDef *DMAx, uint32_t Stream, LL_DMA_InitTypeDef *DMA_InitStruct); -uint32_t LL_DMA_DeInit(DMA_TypeDef *DMAx, uint32_t Stream); -void LL_DMA_StructInit(LL_DMA_InitTypeDef *DMA_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DMA1 || DMA2 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_DMA_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma2d.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma2d.h deleted file mode 100644 index a783d058aff8930..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma2d.h +++ /dev/null @@ -1,1904 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dma2d.h - * @author MCD Application Team - * @brief Header file of DMA2D LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_DMA2D_H -#define STM32F4xx_LL_DMA2D_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (DMA2D) - -/** @defgroup DMA2D_LL DMA2D - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA2D_LL_Private_Macros DMA2D Private Macros - * @{ - */ - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA2D_LL_ES_Init_Struct DMA2D Exported Init structures - * @{ - */ - -/** - * @brief LL DMA2D Init Structure Definition - */ -typedef struct -{ - uint32_t Mode; /*!< Specifies the DMA2D transfer mode. - - This parameter can be one value of @ref DMA2D_LL_EC_MODE. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetMode(). */ - - uint32_t ColorMode; /*!< Specifies the color format of the output image. - - This parameter can be one value of @ref DMA2D_LL_EC_OUTPUT_COLOR_MODE. - - This parameter can be modified afterwards using, - unitary function @ref LL_DMA2D_SetOutputColorMode(). */ - - uint32_t OutputBlue; /*!< Specifies the Blue value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputGreen; /*!< Specifies the Green value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x3F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputRed; /*!< Specifies the Red value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputAlpha; /*!< Specifies the Alpha channel of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x01 if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter is not considered if RGB888 or RGB565 color mode is selected. - - This parameter can be modified afterwards using, - unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputMemoryAddress; /*!< Specifies the memory address. - - This parameter must be a number between: - Min_Data = 0x0000 and Max_Data = 0xFFFFFFFF. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputMemAddr(). */ - - - - uint32_t LineOffset; /*!< Specifies the output line offset value. - - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x3FFF. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetLineOffset(). */ - - uint32_t NbrOfLines; /*!< Specifies the number of lines of the area to be transferred. - - This parameter must be a number between: - Min_Data = 0x0000 and Max_Data = 0xFFFF. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetNbrOfLines(). */ - - uint32_t NbrOfPixelsPerLines; /*!< Specifies the number of pixels per lines of the area to be transferred. - - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x3FFF. - - This parameter can be modified afterwards using, - unitary function @ref LL_DMA2D_SetNbrOfPixelsPerLines(). */ - - -} LL_DMA2D_InitTypeDef; - -/** - * @brief LL DMA2D Layer Configuration Structure Definition - */ -typedef struct -{ - uint32_t MemoryAddress; /*!< Specifies the foreground or background memory address. - - This parameter must be a number between: - Min_Data = 0x0000 and Max_Data = 0xFFFFFFFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetMemAddr() for foreground layer, - - @ref LL_DMA2D_BGND_SetMemAddr() for background layer. */ - - uint32_t LineOffset; /*!< Specifies the foreground or background line offset value. - - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x3FFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetLineOffset() for foreground layer, - - @ref LL_DMA2D_BGND_SetLineOffset() for background layer. */ - - uint32_t ColorMode; /*!< Specifies the foreground or background color mode. - - This parameter can be one value of @ref DMA2D_LL_EC_INPUT_COLOR_MODE. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetColorMode() for foreground layer, - - @ref LL_DMA2D_BGND_SetColorMode() for background layer. */ - - uint32_t CLUTColorMode; /*!< Specifies the foreground or background CLUT color mode. - - This parameter can be one value of @ref DMA2D_LL_EC_CLUT_COLOR_MODE. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetCLUTColorMode() for foreground layer, - - @ref LL_DMA2D_BGND_SetCLUTColorMode() for background layer. */ - - uint32_t CLUTSize; /*!< Specifies the foreground or background CLUT size. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetCLUTSize() for foreground layer, - - @ref LL_DMA2D_BGND_SetCLUTSize() for background layer. */ - - uint32_t AlphaMode; /*!< Specifies the foreground or background alpha mode. - - This parameter can be one value of @ref DMA2D_LL_EC_ALPHA_MODE. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetAlphaMode() for foreground layer, - - @ref LL_DMA2D_BGND_SetAlphaMode() for background layer. */ - - uint32_t Alpha; /*!< Specifies the foreground or background Alpha value. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetAlpha() for foreground layer, - - @ref LL_DMA2D_BGND_SetAlpha() for background layer. */ - - uint32_t Blue; /*!< Specifies the foreground or background Blue color value. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetBlueColor() for foreground layer, - - @ref LL_DMA2D_BGND_SetBlueColor() for background layer. */ - - uint32_t Green; /*!< Specifies the foreground or background Green color value. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetGreenColor() for foreground layer, - - @ref LL_DMA2D_BGND_SetGreenColor() for background layer. */ - - uint32_t Red; /*!< Specifies the foreground or background Red color value. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetRedColor() for foreground layer, - - @ref LL_DMA2D_BGND_SetRedColor() for background layer. */ - - uint32_t CLUTMemoryAddress; /*!< Specifies the foreground or background CLUT memory address. - - This parameter must be a number between: - Min_Data = 0x0000 and Max_Data = 0xFFFFFFFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetCLUTMemAddr() for foreground layer, - - @ref LL_DMA2D_BGND_SetCLUTMemAddr() for background layer. */ - - - -} LL_DMA2D_LayerCfgTypeDef; - -/** - * @brief LL DMA2D Output Color Structure Definition - */ -typedef struct -{ - uint32_t ColorMode; /*!< Specifies the color format of the output image. - - This parameter can be one value of @ref DMA2D_LL_EC_OUTPUT_COLOR_MODE. - - This parameter can be modified afterwards using - unitary function @ref LL_DMA2D_SetOutputColorMode(). */ - - uint32_t OutputBlue; /*!< Specifies the Blue value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards using, - unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputGreen; /*!< Specifies the Green value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x3F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputRed; /*!< Specifies the Red value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputAlpha; /*!< Specifies the Alpha channel of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x01 if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter is not considered if RGB888 or RGB565 color mode is selected. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - -} LL_DMA2D_ColorTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DMA2D_LL_Exported_Constants DMA2D Exported Constants - * @{ - */ - -/** @defgroup DMA2D_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_DMA2D_ReadReg function - * @{ - */ -#define LL_DMA2D_FLAG_CEIF DMA2D_ISR_CEIF /*!< Configuration Error Interrupt Flag */ -#define LL_DMA2D_FLAG_CTCIF DMA2D_ISR_CTCIF /*!< CLUT Transfer Complete Interrupt Flag */ -#define LL_DMA2D_FLAG_CAEIF DMA2D_ISR_CAEIF /*!< CLUT Access Error Interrupt Flag */ -#define LL_DMA2D_FLAG_TWIF DMA2D_ISR_TWIF /*!< Transfer Watermark Interrupt Flag */ -#define LL_DMA2D_FLAG_TCIF DMA2D_ISR_TCIF /*!< Transfer Complete Interrupt Flag */ -#define LL_DMA2D_FLAG_TEIF DMA2D_ISR_TEIF /*!< Transfer Error Interrupt Flag */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_DMA2D_ReadReg and LL_DMA2D_WriteReg functions - * @{ - */ -#define LL_DMA2D_IT_CEIE DMA2D_CR_CEIE /*!< Configuration Error Interrupt */ -#define LL_DMA2D_IT_CTCIE DMA2D_CR_CTCIE /*!< CLUT Transfer Complete Interrupt */ -#define LL_DMA2D_IT_CAEIE DMA2D_CR_CAEIE /*!< CLUT Access Error Interrupt */ -#define LL_DMA2D_IT_TWIE DMA2D_CR_TWIE /*!< Transfer Watermark Interrupt */ -#define LL_DMA2D_IT_TCIE DMA2D_CR_TCIE /*!< Transfer Complete Interrupt */ -#define LL_DMA2D_IT_TEIE DMA2D_CR_TEIE /*!< Transfer Error Interrupt */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_MODE Mode - * @{ - */ -#define LL_DMA2D_MODE_M2M 0x00000000U /*!< DMA2D memory to memory transfer mode */ -#define LL_DMA2D_MODE_M2M_PFC DMA2D_CR_MODE_0 /*!< DMA2D memory to memory with pixel format conversion transfer mode */ -#define LL_DMA2D_MODE_M2M_BLEND DMA2D_CR_MODE_1 /*!< DMA2D memory to memory with blending transfer mode */ -#define LL_DMA2D_MODE_R2M DMA2D_CR_MODE /*!< DMA2D register to memory transfer mode */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_OUTPUT_COLOR_MODE Output Color Mode - * @{ - */ -#define LL_DMA2D_OUTPUT_MODE_ARGB8888 0x00000000U /*!< ARGB8888 */ -#define LL_DMA2D_OUTPUT_MODE_RGB888 DMA2D_OPFCCR_CM_0 /*!< RGB888 */ -#define LL_DMA2D_OUTPUT_MODE_RGB565 DMA2D_OPFCCR_CM_1 /*!< RGB565 */ -#define LL_DMA2D_OUTPUT_MODE_ARGB1555 (DMA2D_OPFCCR_CM_0|DMA2D_OPFCCR_CM_1) /*!< ARGB1555 */ -#define LL_DMA2D_OUTPUT_MODE_ARGB4444 DMA2D_OPFCCR_CM_2 /*!< ARGB4444 */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_INPUT_COLOR_MODE Input Color Mode - * @{ - */ -#define LL_DMA2D_INPUT_MODE_ARGB8888 0x00000000U /*!< ARGB8888 */ -#define LL_DMA2D_INPUT_MODE_RGB888 DMA2D_FGPFCCR_CM_0 /*!< RGB888 */ -#define LL_DMA2D_INPUT_MODE_RGB565 DMA2D_FGPFCCR_CM_1 /*!< RGB565 */ -#define LL_DMA2D_INPUT_MODE_ARGB1555 (DMA2D_FGPFCCR_CM_0|DMA2D_FGPFCCR_CM_1) /*!< ARGB1555 */ -#define LL_DMA2D_INPUT_MODE_ARGB4444 DMA2D_FGPFCCR_CM_2 /*!< ARGB4444 */ -#define LL_DMA2D_INPUT_MODE_L8 (DMA2D_FGPFCCR_CM_0|DMA2D_FGPFCCR_CM_2) /*!< L8 */ -#define LL_DMA2D_INPUT_MODE_AL44 (DMA2D_FGPFCCR_CM_1|DMA2D_FGPFCCR_CM_2) /*!< AL44 */ -#define LL_DMA2D_INPUT_MODE_AL88 (DMA2D_FGPFCCR_CM_0|DMA2D_FGPFCCR_CM_1|DMA2D_FGPFCCR_CM_2) /*!< AL88 */ -#define LL_DMA2D_INPUT_MODE_L4 DMA2D_FGPFCCR_CM_3 /*!< L4 */ -#define LL_DMA2D_INPUT_MODE_A8 (DMA2D_FGPFCCR_CM_0|DMA2D_FGPFCCR_CM_3) /*!< A8 */ -#define LL_DMA2D_INPUT_MODE_A4 (DMA2D_FGPFCCR_CM_1|DMA2D_FGPFCCR_CM_3) /*!< A4 */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_ALPHA_MODE Alpha Mode - * @{ - */ -#define LL_DMA2D_ALPHA_MODE_NO_MODIF 0x00000000U /*!< No modification of the alpha channel value */ -#define LL_DMA2D_ALPHA_MODE_REPLACE DMA2D_FGPFCCR_AM_0 /*!< Replace original alpha channel value by - programmed alpha value */ -#define LL_DMA2D_ALPHA_MODE_COMBINE DMA2D_FGPFCCR_AM_1 /*!< Replace original alpha channel value by - programmed alpha value with, - original alpha channel value */ -/** - * @} - */ - - - - -/** @defgroup DMA2D_LL_EC_CLUT_COLOR_MODE CLUT Color Mode - * @{ - */ -#define LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 0x00000000U /*!< ARGB8888 */ -#define LL_DMA2D_CLUT_COLOR_MODE_RGB888 DMA2D_FGPFCCR_CCM /*!< RGB888 */ -/** - * @} - */ - - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DMA2D_LL_Exported_Macros DMA2D Exported Macros - * @{ - */ - -/** @defgroup DMA2D_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in DMA2D register. - * @param __INSTANCE__ DMA2D Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_DMA2D_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG((__INSTANCE__)->__REG__, (__VALUE__)) - -/** - * @brief Read a value in DMA2D register. - * @param __INSTANCE__ DMA2D Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_DMA2D_ReadReg(__INSTANCE__, __REG__) READ_REG((__INSTANCE__)->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DMA2D_LL_Exported_Functions DMA2D Exported Functions - * @{ - */ - -/** @defgroup DMA2D_LL_EF_Configuration Configuration Functions - * @{ - */ - -/** - * @brief Start a DMA2D transfer. - * @rmtoll CR START LL_DMA2D_Start - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_Start(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_START); -} - -/** - * @brief Indicate if a DMA2D transfer is ongoing. - * @rmtoll CR START LL_DMA2D_IsTransferOngoing - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsTransferOngoing(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_START) == (DMA2D_CR_START)) ? 1UL : 0UL); -} - -/** - * @brief Suspend DMA2D transfer. - * @note This API can be used to suspend automatic foreground or background CLUT loading. - * @rmtoll CR SUSP LL_DMA2D_Suspend - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_Suspend(DMA2D_TypeDef *DMA2Dx) -{ - MODIFY_REG(DMA2Dx->CR, DMA2D_CR_SUSP | DMA2D_CR_START, DMA2D_CR_SUSP); -} - -/** - * @brief Resume DMA2D transfer. - * @note This API can be used to resume automatic foreground or background CLUT loading. - * @rmtoll CR SUSP LL_DMA2D_Resume - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_Resume(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_SUSP | DMA2D_CR_START); -} - -/** - * @brief Indicate if DMA2D transfer is suspended. - * @note This API can be used to indicate whether or not automatic foreground or - * background CLUT loading is suspended. - * @rmtoll CR SUSP LL_DMA2D_IsSuspended - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsSuspended(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_SUSP) == (DMA2D_CR_SUSP)) ? 1UL : 0UL); -} - -/** - * @brief Abort DMA2D transfer. - * @note This API can be used to abort automatic foreground or background CLUT loading. - * @rmtoll CR ABORT LL_DMA2D_Abort - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_Abort(DMA2D_TypeDef *DMA2Dx) -{ - MODIFY_REG(DMA2Dx->CR, DMA2D_CR_ABORT | DMA2D_CR_START, DMA2D_CR_ABORT); -} - -/** - * @brief Indicate if DMA2D transfer is aborted. - * @note This API can be used to indicate whether or not automatic foreground or - * background CLUT loading is aborted. - * @rmtoll CR ABORT LL_DMA2D_IsAborted - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsAborted(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_ABORT) == (DMA2D_CR_ABORT)) ? 1UL : 0UL); -} - -/** - * @brief Set DMA2D mode. - * @rmtoll CR MODE LL_DMA2D_SetMode - * @param DMA2Dx DMA2D Instance - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_MODE_M2M - * @arg @ref LL_DMA2D_MODE_M2M_PFC - * @arg @ref LL_DMA2D_MODE_M2M_BLEND - * @arg @ref LL_DMA2D_MODE_R2M - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetMode(DMA2D_TypeDef *DMA2Dx, uint32_t Mode) -{ - MODIFY_REG(DMA2Dx->CR, DMA2D_CR_MODE, Mode); -} - -/** - * @brief Return DMA2D mode - * @rmtoll CR MODE LL_DMA2D_GetMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_MODE_M2M - * @arg @ref LL_DMA2D_MODE_M2M_PFC - * @arg @ref LL_DMA2D_MODE_M2M_BLEND - * @arg @ref LL_DMA2D_MODE_R2M - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->CR, DMA2D_CR_MODE)); -} - -/** - * @brief Set DMA2D output color mode. - * @rmtoll OPFCCR CM LL_DMA2D_SetOutputColorMode - * @param DMA2Dx DMA2D Instance - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetOutputColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - MODIFY_REG(DMA2Dx->OPFCCR, DMA2D_OPFCCR_CM, ColorMode); -} - -/** - * @brief Return DMA2D output color mode. - * @rmtoll OPFCCR CM LL_DMA2D_GetOutputColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetOutputColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->OPFCCR, DMA2D_OPFCCR_CM)); -} - - - - -/** - * @brief Set DMA2D line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll OOR LO LL_DMA2D_SetLineOffset - * @param DMA2Dx DMA2D Instance - * @param LineOffset Value between Min_Data=0 and Max_Data=0x3FFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetLineOffset(DMA2D_TypeDef *DMA2Dx, uint32_t LineOffset) -{ - MODIFY_REG(DMA2Dx->OOR, DMA2D_OOR_LO, LineOffset); -} - -/** - * @brief Return DMA2D line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll OOR LO LL_DMA2D_GetLineOffset - * @param DMA2Dx DMA2D Instance - * @retval Line offset value between Min_Data=0 and Max_Data=0x3FFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetLineOffset(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->OOR, DMA2D_OOR_LO)); -} - -/** - * @brief Set DMA2D number of pixels per lines, expressed on 14 bits ([13:0] bits). - * @rmtoll NLR PL LL_DMA2D_SetNbrOfPixelsPerLines - * @param DMA2Dx DMA2D Instance - * @param NbrOfPixelsPerLines Value between Min_Data=0 and Max_Data=0x3FFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetNbrOfPixelsPerLines(DMA2D_TypeDef *DMA2Dx, uint32_t NbrOfPixelsPerLines) -{ - MODIFY_REG(DMA2Dx->NLR, DMA2D_NLR_PL, (NbrOfPixelsPerLines << DMA2D_NLR_PL_Pos)); -} - -/** - * @brief Return DMA2D number of pixels per lines, expressed on 14 bits ([13:0] bits) - * @rmtoll NLR PL LL_DMA2D_GetNbrOfPixelsPerLines - * @param DMA2Dx DMA2D Instance - * @retval Number of pixels per lines value between Min_Data=0 and Max_Data=0x3FFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetNbrOfPixelsPerLines(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->NLR, DMA2D_NLR_PL) >> DMA2D_NLR_PL_Pos); -} - -/** - * @brief Set DMA2D number of lines, expressed on 16 bits ([15:0] bits). - * @rmtoll NLR NL LL_DMA2D_SetNbrOfLines - * @param DMA2Dx DMA2D Instance - * @param NbrOfLines Value between Min_Data=0 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetNbrOfLines(DMA2D_TypeDef *DMA2Dx, uint32_t NbrOfLines) -{ - MODIFY_REG(DMA2Dx->NLR, DMA2D_NLR_NL, NbrOfLines); -} - -/** - * @brief Return DMA2D number of lines, expressed on 16 bits ([15:0] bits). - * @rmtoll NLR NL LL_DMA2D_GetNbrOfLines - * @param DMA2Dx DMA2D Instance - * @retval Number of lines value between Min_Data=0 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetNbrOfLines(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->NLR, DMA2D_NLR_NL)); -} - -/** - * @brief Set DMA2D output memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll OMAR MA LL_DMA2D_SetOutputMemAddr - * @param DMA2Dx DMA2D Instance - * @param OutputMemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetOutputMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t OutputMemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, OMAR, OutputMemoryAddress); -} - -/** - * @brief Get DMA2D output memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll OMAR MA LL_DMA2D_GetOutputMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Output memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetOutputMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, OMAR)); -} - -/** - * @brief Set DMA2D output color, expressed on 32 bits ([31:0] bits). - * @note Output color format depends on output color mode, ARGB8888, RGB888, - * RGB565, ARGB1555 or ARGB4444. - * @note LL_DMA2D_ConfigOutputColor() API may be used instead if colors values formatting - * with respect to color mode is not done by the user code. - * @rmtoll OCOLR BLUE LL_DMA2D_SetOutputColor\n - * OCOLR GREEN LL_DMA2D_SetOutputColor\n - * OCOLR RED LL_DMA2D_SetOutputColor\n - * OCOLR ALPHA LL_DMA2D_SetOutputColor - * @param DMA2Dx DMA2D Instance - * @param OutputColor Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetOutputColor(DMA2D_TypeDef *DMA2Dx, uint32_t OutputColor) -{ - MODIFY_REG(DMA2Dx->OCOLR, (DMA2D_OCOLR_BLUE_1 | DMA2D_OCOLR_GREEN_1 | DMA2D_OCOLR_RED_1 | DMA2D_OCOLR_ALPHA_1), \ - OutputColor); -} - -/** - * @brief Get DMA2D output color, expressed on 32 bits ([31:0] bits). - * @note Alpha channel and red, green, blue color values must be retrieved from the returned - * value based on the output color mode (ARGB8888, RGB888, RGB565, ARGB1555 or ARGB4444) - * as set by @ref LL_DMA2D_SetOutputColorMode. - * @rmtoll OCOLR BLUE LL_DMA2D_GetOutputColor\n - * OCOLR GREEN LL_DMA2D_GetOutputColor\n - * OCOLR RED LL_DMA2D_GetOutputColor\n - * OCOLR ALPHA LL_DMA2D_GetOutputColor - * @param DMA2Dx DMA2D Instance - * @retval Output color value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetOutputColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->OCOLR, \ - (DMA2D_OCOLR_BLUE_1 | DMA2D_OCOLR_GREEN_1 | DMA2D_OCOLR_RED_1 | DMA2D_OCOLR_ALPHA_1))); -} - -/** - * @brief Set DMA2D line watermark, expressed on 16 bits ([15:0] bits). - * @rmtoll LWR LW LL_DMA2D_SetLineWatermark - * @param DMA2Dx DMA2D Instance - * @param LineWatermark Value between Min_Data=0 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetLineWatermark(DMA2D_TypeDef *DMA2Dx, uint32_t LineWatermark) -{ - MODIFY_REG(DMA2Dx->LWR, DMA2D_LWR_LW, LineWatermark); -} - -/** - * @brief Return DMA2D line watermark, expressed on 16 bits ([15:0] bits). - * @rmtoll LWR LW LL_DMA2D_GetLineWatermark - * @param DMA2Dx DMA2D Instance - * @retval Line watermark value between Min_Data=0 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetLineWatermark(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->LWR, DMA2D_LWR_LW)); -} - -/** - * @brief Set DMA2D dead time, expressed on 8 bits ([7:0] bits). - * @rmtoll AMTCR DT LL_DMA2D_SetDeadTime - * @param DMA2Dx DMA2D Instance - * @param DeadTime Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetDeadTime(DMA2D_TypeDef *DMA2Dx, uint32_t DeadTime) -{ - MODIFY_REG(DMA2Dx->AMTCR, DMA2D_AMTCR_DT, (DeadTime << DMA2D_AMTCR_DT_Pos)); -} - -/** - * @brief Return DMA2D dead time, expressed on 8 bits ([7:0] bits). - * @rmtoll AMTCR DT LL_DMA2D_GetDeadTime - * @param DMA2Dx DMA2D Instance - * @retval Dead time value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetDeadTime(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->AMTCR, DMA2D_AMTCR_DT) >> DMA2D_AMTCR_DT_Pos); -} - -/** - * @brief Enable DMA2D dead time functionality. - * @rmtoll AMTCR EN LL_DMA2D_EnableDeadTime - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableDeadTime(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->AMTCR, DMA2D_AMTCR_EN); -} - -/** - * @brief Disable DMA2D dead time functionality. - * @rmtoll AMTCR EN LL_DMA2D_DisableDeadTime - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableDeadTime(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->AMTCR, DMA2D_AMTCR_EN); -} - -/** - * @brief Indicate if DMA2D dead time functionality is enabled. - * @rmtoll AMTCR EN LL_DMA2D_IsEnabledDeadTime - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledDeadTime(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->AMTCR, DMA2D_AMTCR_EN) == (DMA2D_AMTCR_EN)) ? 1UL : 0UL); -} - -/** @defgroup DMA2D_LL_EF_FGND_Configuration Foreground Configuration Functions - * @{ - */ - -/** - * @brief Set DMA2D foreground memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll FGMAR MA LL_DMA2D_FGND_SetMemAddr - * @param DMA2Dx DMA2D Instance - * @param MemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t MemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, FGMAR, MemoryAddress); -} - -/** - * @brief Get DMA2D foreground memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll FGMAR MA LL_DMA2D_FGND_GetMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Foreground memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, FGMAR)); -} - -/** - * @brief Enable DMA2D foreground CLUT loading. - * @rmtoll FGPFCCR START LL_DMA2D_FGND_EnableCLUTLoad - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_EnableCLUTLoad(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_START); -} - -/** - * @brief Indicate if DMA2D foreground CLUT loading is enabled. - * @rmtoll FGPFCCR START LL_DMA2D_FGND_IsEnabledCLUTLoad - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_IsEnabledCLUTLoad(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_START) == (DMA2D_FGPFCCR_START)) ? 1UL : 0UL); -} - -/** - * @brief Set DMA2D foreground color mode. - * @rmtoll FGPFCCR CM LL_DMA2D_FGND_SetColorMode - * @param DMA2Dx DMA2D Instance - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB4444 - * @arg @ref LL_DMA2D_INPUT_MODE_L8 - * @arg @ref LL_DMA2D_INPUT_MODE_AL44 - * @arg @ref LL_DMA2D_INPUT_MODE_AL88 - * @arg @ref LL_DMA2D_INPUT_MODE_L4 - * @arg @ref LL_DMA2D_INPUT_MODE_A8 - * @arg @ref LL_DMA2D_INPUT_MODE_A4 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CM, ColorMode); -} - -/** - * @brief Return DMA2D foreground color mode. - * @rmtoll FGPFCCR CM LL_DMA2D_FGND_GetColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB4444 - * @arg @ref LL_DMA2D_INPUT_MODE_L8 - * @arg @ref LL_DMA2D_INPUT_MODE_AL44 - * @arg @ref LL_DMA2D_INPUT_MODE_AL88 - * @arg @ref LL_DMA2D_INPUT_MODE_L4 - * @arg @ref LL_DMA2D_INPUT_MODE_A8 - * @arg @ref LL_DMA2D_INPUT_MODE_A4 - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CM)); -} - -/** - * @brief Set DMA2D foreground alpha mode. - * @rmtoll FGPFCCR AM LL_DMA2D_FGND_SetAlphaMode - * @param DMA2Dx DMA2D Instance - * @param AphaMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_ALPHA_MODE_NO_MODIF - * @arg @ref LL_DMA2D_ALPHA_MODE_REPLACE - * @arg @ref LL_DMA2D_ALPHA_MODE_COMBINE - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetAlphaMode(DMA2D_TypeDef *DMA2Dx, uint32_t AphaMode) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_AM, AphaMode); -} - -/** - * @brief Return DMA2D foreground alpha mode. - * @rmtoll FGPFCCR AM LL_DMA2D_FGND_GetAlphaMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_ALPHA_MODE_NO_MODIF - * @arg @ref LL_DMA2D_ALPHA_MODE_REPLACE - * @arg @ref LL_DMA2D_ALPHA_MODE_COMBINE - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetAlphaMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_AM)); -} - -/** - * @brief Set DMA2D foreground alpha value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGPFCCR ALPHA LL_DMA2D_FGND_SetAlpha - * @param DMA2Dx DMA2D Instance - * @param Alpha Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetAlpha(DMA2D_TypeDef *DMA2Dx, uint32_t Alpha) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_ALPHA, (Alpha << DMA2D_FGPFCCR_ALPHA_Pos)); -} - -/** - * @brief Return DMA2D foreground alpha value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGPFCCR ALPHA LL_DMA2D_FGND_GetAlpha - * @param DMA2Dx DMA2D Instance - * @retval Alpha value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetAlpha(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_ALPHA) >> DMA2D_FGPFCCR_ALPHA_Pos); -} - - -/** - * @brief Set DMA2D foreground line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll FGOR LO LL_DMA2D_FGND_SetLineOffset - * @param DMA2Dx DMA2D Instance - * @param LineOffset Value between Min_Data=0 and Max_Data=0x3FF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetLineOffset(DMA2D_TypeDef *DMA2Dx, uint32_t LineOffset) -{ - MODIFY_REG(DMA2Dx->FGOR, DMA2D_FGOR_LO, LineOffset); -} - -/** - * @brief Return DMA2D foreground line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll FGOR LO LL_DMA2D_FGND_GetLineOffset - * @param DMA2Dx DMA2D Instance - * @retval Foreground line offset value between Min_Data=0 and Max_Data=0x3FF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetLineOffset(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGOR, DMA2D_FGOR_LO)); -} - -/** - * @brief Set DMA2D foreground color values, expressed on 24 bits ([23:0] bits). - * @rmtoll FGCOLR RED LL_DMA2D_FGND_SetColor - * @rmtoll FGCOLR GREEN LL_DMA2D_FGND_SetColor - * @rmtoll FGCOLR BLUE LL_DMA2D_FGND_SetColor - * @param DMA2Dx DMA2D Instance - * @param Red Value between Min_Data=0 and Max_Data=0xFF - * @param Green Value between Min_Data=0 and Max_Data=0xFF - * @param Blue Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetColor(DMA2D_TypeDef *DMA2Dx, uint32_t Red, uint32_t Green, uint32_t Blue) -{ - MODIFY_REG(DMA2Dx->FGCOLR, (DMA2D_FGCOLR_RED | DMA2D_FGCOLR_GREEN | DMA2D_FGCOLR_BLUE), \ - ((Red << DMA2D_FGCOLR_RED_Pos) | (Green << DMA2D_FGCOLR_GREEN_Pos) | Blue)); -} - -/** - * @brief Set DMA2D foreground red color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR RED LL_DMA2D_FGND_SetRedColor - * @param DMA2Dx DMA2D Instance - * @param Red Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetRedColor(DMA2D_TypeDef *DMA2Dx, uint32_t Red) -{ - MODIFY_REG(DMA2Dx->FGCOLR, DMA2D_FGCOLR_RED, (Red << DMA2D_FGCOLR_RED_Pos)); -} - -/** - * @brief Return DMA2D foreground red color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR RED LL_DMA2D_FGND_GetRedColor - * @param DMA2Dx DMA2D Instance - * @retval Red color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetRedColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGCOLR, DMA2D_FGCOLR_RED) >> DMA2D_FGCOLR_RED_Pos); -} - -/** - * @brief Set DMA2D foreground green color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR GREEN LL_DMA2D_FGND_SetGreenColor - * @param DMA2Dx DMA2D Instance - * @param Green Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetGreenColor(DMA2D_TypeDef *DMA2Dx, uint32_t Green) -{ - MODIFY_REG(DMA2Dx->FGCOLR, DMA2D_FGCOLR_GREEN, (Green << DMA2D_FGCOLR_GREEN_Pos)); -} - -/** - * @brief Return DMA2D foreground green color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR GREEN LL_DMA2D_FGND_GetGreenColor - * @param DMA2Dx DMA2D Instance - * @retval Green color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetGreenColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGCOLR, DMA2D_FGCOLR_GREEN) >> DMA2D_FGCOLR_GREEN_Pos); -} - -/** - * @brief Set DMA2D foreground blue color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR BLUE LL_DMA2D_FGND_SetBlueColor - * @param DMA2Dx DMA2D Instance - * @param Blue Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetBlueColor(DMA2D_TypeDef *DMA2Dx, uint32_t Blue) -{ - MODIFY_REG(DMA2Dx->FGCOLR, DMA2D_FGCOLR_BLUE, Blue); -} - -/** - * @brief Return DMA2D foreground blue color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR BLUE LL_DMA2D_FGND_GetBlueColor - * @param DMA2Dx DMA2D Instance - * @retval Blue color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetBlueColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGCOLR, DMA2D_FGCOLR_BLUE)); -} - -/** - * @brief Set DMA2D foreground CLUT memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll FGCMAR MA LL_DMA2D_FGND_SetCLUTMemAddr - * @param DMA2Dx DMA2D Instance - * @param CLUTMemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetCLUTMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTMemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, FGCMAR, CLUTMemoryAddress); -} - -/** - * @brief Get DMA2D foreground CLUT memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll FGCMAR MA LL_DMA2D_FGND_GetCLUTMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Foreground CLUT memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetCLUTMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, FGCMAR)); -} - -/** - * @brief Set DMA2D foreground CLUT size, expressed on 8 bits ([7:0] bits). - * @rmtoll FGPFCCR CS LL_DMA2D_FGND_SetCLUTSize - * @param DMA2Dx DMA2D Instance - * @param CLUTSize Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetCLUTSize(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTSize) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CS, (CLUTSize << DMA2D_FGPFCCR_CS_Pos)); -} - -/** - * @brief Get DMA2D foreground CLUT size, expressed on 8 bits ([7:0] bits). - * @rmtoll FGPFCCR CS LL_DMA2D_FGND_GetCLUTSize - * @param DMA2Dx DMA2D Instance - * @retval Foreground CLUT size value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetCLUTSize(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CS) >> DMA2D_FGPFCCR_CS_Pos); -} - -/** - * @brief Set DMA2D foreground CLUT color mode. - * @rmtoll FGPFCCR CCM LL_DMA2D_FGND_SetCLUTColorMode - * @param DMA2Dx DMA2D Instance - * @param CLUTColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_RGB888 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetCLUTColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTColorMode) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CCM, CLUTColorMode); -} - -/** - * @brief Return DMA2D foreground CLUT color mode. - * @rmtoll FGPFCCR CCM LL_DMA2D_FGND_GetCLUTColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_RGB888 - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetCLUTColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CCM)); -} - -/** - * @} - */ - -/** @defgroup DMA2D_LL_EF_BGND_Configuration Background Configuration Functions - * @{ - */ - -/** - * @brief Set DMA2D background memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll BGMAR MA LL_DMA2D_BGND_SetMemAddr - * @param DMA2Dx DMA2D Instance - * @param MemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t MemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, BGMAR, MemoryAddress); -} - -/** - * @brief Get DMA2D background memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll BGMAR MA LL_DMA2D_BGND_GetMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Background memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, BGMAR)); -} - -/** - * @brief Enable DMA2D background CLUT loading. - * @rmtoll BGPFCCR START LL_DMA2D_BGND_EnableCLUTLoad - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_EnableCLUTLoad(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_START); -} - -/** - * @brief Indicate if DMA2D background CLUT loading is enabled. - * @rmtoll BGPFCCR START LL_DMA2D_BGND_IsEnabledCLUTLoad - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_IsEnabledCLUTLoad(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_START) == (DMA2D_BGPFCCR_START)) ? 1UL : 0UL); -} - -/** - * @brief Set DMA2D background color mode. - * @rmtoll BGPFCCR CM LL_DMA2D_BGND_SetColorMode - * @param DMA2Dx DMA2D Instance - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB4444 - * @arg @ref LL_DMA2D_INPUT_MODE_L8 - * @arg @ref LL_DMA2D_INPUT_MODE_AL44 - * @arg @ref LL_DMA2D_INPUT_MODE_AL88 - * @arg @ref LL_DMA2D_INPUT_MODE_L4 - * @arg @ref LL_DMA2D_INPUT_MODE_A8 - * @arg @ref LL_DMA2D_INPUT_MODE_A4 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CM, ColorMode); -} - -/** - * @brief Return DMA2D background color mode. - * @rmtoll BGPFCCR CM LL_DMA2D_BGND_GetColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB4444 - * @arg @ref LL_DMA2D_INPUT_MODE_L8 - * @arg @ref LL_DMA2D_INPUT_MODE_AL44 - * @arg @ref LL_DMA2D_INPUT_MODE_AL88 - * @arg @ref LL_DMA2D_INPUT_MODE_L4 - * @arg @ref LL_DMA2D_INPUT_MODE_A8 - * @arg @ref LL_DMA2D_INPUT_MODE_A4 - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CM)); -} - -/** - * @brief Set DMA2D background alpha mode. - * @rmtoll BGPFCCR AM LL_DMA2D_BGND_SetAlphaMode - * @param DMA2Dx DMA2D Instance - * @param AphaMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_ALPHA_MODE_NO_MODIF - * @arg @ref LL_DMA2D_ALPHA_MODE_REPLACE - * @arg @ref LL_DMA2D_ALPHA_MODE_COMBINE - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetAlphaMode(DMA2D_TypeDef *DMA2Dx, uint32_t AphaMode) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_AM, AphaMode); -} - -/** - * @brief Return DMA2D background alpha mode. - * @rmtoll BGPFCCR AM LL_DMA2D_BGND_GetAlphaMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_ALPHA_MODE_NO_MODIF - * @arg @ref LL_DMA2D_ALPHA_MODE_REPLACE - * @arg @ref LL_DMA2D_ALPHA_MODE_COMBINE - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetAlphaMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_AM)); -} - -/** - * @brief Set DMA2D background alpha value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGPFCCR ALPHA LL_DMA2D_BGND_SetAlpha - * @param DMA2Dx DMA2D Instance - * @param Alpha Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetAlpha(DMA2D_TypeDef *DMA2Dx, uint32_t Alpha) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_ALPHA, (Alpha << DMA2D_BGPFCCR_ALPHA_Pos)); -} - -/** - * @brief Return DMA2D background alpha value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGPFCCR ALPHA LL_DMA2D_BGND_GetAlpha - * @param DMA2Dx DMA2D Instance - * @retval Alpha value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetAlpha(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_ALPHA) >> DMA2D_BGPFCCR_ALPHA_Pos); -} - - -/** - * @brief Set DMA2D background line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll BGOR LO LL_DMA2D_BGND_SetLineOffset - * @param DMA2Dx DMA2D Instance - * @param LineOffset Value between Min_Data=0 and Max_Data=0x3FF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetLineOffset(DMA2D_TypeDef *DMA2Dx, uint32_t LineOffset) -{ - MODIFY_REG(DMA2Dx->BGOR, DMA2D_BGOR_LO, LineOffset); -} - -/** - * @brief Return DMA2D background line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll BGOR LO LL_DMA2D_BGND_GetLineOffset - * @param DMA2Dx DMA2D Instance - * @retval Background line offset value between Min_Data=0 and Max_Data=0x3FF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetLineOffset(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGOR, DMA2D_BGOR_LO)); -} - -/** - * @brief Set DMA2D background color values, expressed on 24 bits ([23:0] bits). - * @rmtoll BGCOLR RED LL_DMA2D_BGND_SetColor - * @rmtoll BGCOLR GREEN LL_DMA2D_BGND_SetColor - * @rmtoll BGCOLR BLUE LL_DMA2D_BGND_SetColor - * @param DMA2Dx DMA2D Instance - * @param Red Value between Min_Data=0 and Max_Data=0xFF - * @param Green Value between Min_Data=0 and Max_Data=0xFF - * @param Blue Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetColor(DMA2D_TypeDef *DMA2Dx, uint32_t Red, uint32_t Green, uint32_t Blue) -{ - MODIFY_REG(DMA2Dx->BGCOLR, (DMA2D_BGCOLR_RED | DMA2D_BGCOLR_GREEN | DMA2D_BGCOLR_BLUE), \ - ((Red << DMA2D_BGCOLR_RED_Pos) | (Green << DMA2D_BGCOLR_GREEN_Pos) | Blue)); -} - -/** - * @brief Set DMA2D background red color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR RED LL_DMA2D_BGND_SetRedColor - * @param DMA2Dx DMA2D Instance - * @param Red Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetRedColor(DMA2D_TypeDef *DMA2Dx, uint32_t Red) -{ - MODIFY_REG(DMA2Dx->BGCOLR, DMA2D_BGCOLR_RED, (Red << DMA2D_BGCOLR_RED_Pos)); -} - -/** - * @brief Return DMA2D background red color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR RED LL_DMA2D_BGND_GetRedColor - * @param DMA2Dx DMA2D Instance - * @retval Red color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetRedColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGCOLR, DMA2D_BGCOLR_RED) >> DMA2D_BGCOLR_RED_Pos); -} - -/** - * @brief Set DMA2D background green color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR GREEN LL_DMA2D_BGND_SetGreenColor - * @param DMA2Dx DMA2D Instance - * @param Green Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetGreenColor(DMA2D_TypeDef *DMA2Dx, uint32_t Green) -{ - MODIFY_REG(DMA2Dx->BGCOLR, DMA2D_BGCOLR_GREEN, (Green << DMA2D_BGCOLR_GREEN_Pos)); -} - -/** - * @brief Return DMA2D background green color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR GREEN LL_DMA2D_BGND_GetGreenColor - * @param DMA2Dx DMA2D Instance - * @retval Green color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetGreenColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGCOLR, DMA2D_BGCOLR_GREEN) >> DMA2D_BGCOLR_GREEN_Pos); -} - -/** - * @brief Set DMA2D background blue color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR BLUE LL_DMA2D_BGND_SetBlueColor - * @param DMA2Dx DMA2D Instance - * @param Blue Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetBlueColor(DMA2D_TypeDef *DMA2Dx, uint32_t Blue) -{ - MODIFY_REG(DMA2Dx->BGCOLR, DMA2D_BGCOLR_BLUE, Blue); -} - -/** - * @brief Return DMA2D background blue color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR BLUE LL_DMA2D_BGND_GetBlueColor - * @param DMA2Dx DMA2D Instance - * @retval Blue color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetBlueColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGCOLR, DMA2D_BGCOLR_BLUE)); -} - -/** - * @brief Set DMA2D background CLUT memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll BGCMAR MA LL_DMA2D_BGND_SetCLUTMemAddr - * @param DMA2Dx DMA2D Instance - * @param CLUTMemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetCLUTMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTMemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, BGCMAR, CLUTMemoryAddress); -} - -/** - * @brief Get DMA2D background CLUT memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll BGCMAR MA LL_DMA2D_BGND_GetCLUTMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Background CLUT memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetCLUTMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, BGCMAR)); -} - -/** - * @brief Set DMA2D background CLUT size, expressed on 8 bits ([7:0] bits). - * @rmtoll BGPFCCR CS LL_DMA2D_BGND_SetCLUTSize - * @param DMA2Dx DMA2D Instance - * @param CLUTSize Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetCLUTSize(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTSize) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CS, (CLUTSize << DMA2D_BGPFCCR_CS_Pos)); -} - -/** - * @brief Get DMA2D background CLUT size, expressed on 8 bits ([7:0] bits). - * @rmtoll BGPFCCR CS LL_DMA2D_BGND_GetCLUTSize - * @param DMA2Dx DMA2D Instance - * @retval Background CLUT size value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetCLUTSize(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CS) >> DMA2D_BGPFCCR_CS_Pos); -} - -/** - * @brief Set DMA2D background CLUT color mode. - * @rmtoll BGPFCCR CCM LL_DMA2D_BGND_SetCLUTColorMode - * @param DMA2Dx DMA2D Instance - * @param CLUTColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_RGB888 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetCLUTColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTColorMode) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CCM, CLUTColorMode); -} - -/** - * @brief Return DMA2D background CLUT color mode. - * @rmtoll BGPFCCR CCM LL_DMA2D_BGND_GetCLUTColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_RGB888 - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetCLUTColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CCM)); -} - -/** - * @} - */ - -/** - * @} - */ - - -/** @defgroup DMA2D_LL_EF_FLAG_MANAGEMENT Flag Management - * @{ - */ - -/** - * @brief Check if the DMA2D Configuration Error Interrupt Flag is set or not - * @rmtoll ISR CEIF LL_DMA2D_IsActiveFlag_CE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_CE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_CEIF) == (DMA2D_ISR_CEIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D CLUT Transfer Complete Interrupt Flag is set or not - * @rmtoll ISR CTCIF LL_DMA2D_IsActiveFlag_CTC - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_CTC(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_CTCIF) == (DMA2D_ISR_CTCIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D CLUT Access Error Interrupt Flag is set or not - * @rmtoll ISR CAEIF LL_DMA2D_IsActiveFlag_CAE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_CAE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_CAEIF) == (DMA2D_ISR_CAEIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Watermark Interrupt Flag is set or not - * @rmtoll ISR TWIF LL_DMA2D_IsActiveFlag_TW - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_TW(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_TWIF) == (DMA2D_ISR_TWIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Complete Interrupt Flag is set or not - * @rmtoll ISR TCIF LL_DMA2D_IsActiveFlag_TC - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_TC(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_TCIF) == (DMA2D_ISR_TCIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Error Interrupt Flag is set or not - * @rmtoll ISR TEIF LL_DMA2D_IsActiveFlag_TE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_TE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_TEIF) == (DMA2D_ISR_TEIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear DMA2D Configuration Error Interrupt Flag - * @rmtoll IFCR CCEIF LL_DMA2D_ClearFlag_CE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_CE(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CCEIF); -} - -/** - * @brief Clear DMA2D CLUT Transfer Complete Interrupt Flag - * @rmtoll IFCR CCTCIF LL_DMA2D_ClearFlag_CTC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_CTC(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CCTCIF); -} - -/** - * @brief Clear DMA2D CLUT Access Error Interrupt Flag - * @rmtoll IFCR CAECIF LL_DMA2D_ClearFlag_CAE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_CAE(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CAECIF); -} - -/** - * @brief Clear DMA2D Transfer Watermark Interrupt Flag - * @rmtoll IFCR CTWIF LL_DMA2D_ClearFlag_TW - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_TW(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CTWIF); -} - -/** - * @brief Clear DMA2D Transfer Complete Interrupt Flag - * @rmtoll IFCR CTCIF LL_DMA2D_ClearFlag_TC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_TC(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CTCIF); -} - -/** - * @brief Clear DMA2D Transfer Error Interrupt Flag - * @rmtoll IFCR CTEIF LL_DMA2D_ClearFlag_TE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_TE(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CTEIF); -} - -/** - * @} - */ - -/** @defgroup DMA2D_LL_EF_IT_MANAGEMENT Interruption Management - * @{ - */ - -/** - * @brief Enable Configuration Error Interrupt - * @rmtoll CR CEIE LL_DMA2D_EnableIT_CE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_CE(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_CEIE); -} - -/** - * @brief Enable CLUT Transfer Complete Interrupt - * @rmtoll CR CTCIE LL_DMA2D_EnableIT_CTC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_CTC(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_CTCIE); -} - -/** - * @brief Enable CLUT Access Error Interrupt - * @rmtoll CR CAEIE LL_DMA2D_EnableIT_CAE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_CAE(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_CAEIE); -} - -/** - * @brief Enable Transfer Watermark Interrupt - * @rmtoll CR TWIE LL_DMA2D_EnableIT_TW - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_TW(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_TWIE); -} - -/** - * @brief Enable Transfer Complete Interrupt - * @rmtoll CR TCIE LL_DMA2D_EnableIT_TC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_TC(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_TCIE); -} - -/** - * @brief Enable Transfer Error Interrupt - * @rmtoll CR TEIE LL_DMA2D_EnableIT_TE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_TE(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_TEIE); -} - -/** - * @brief Disable Configuration Error Interrupt - * @rmtoll CR CEIE LL_DMA2D_DisableIT_CE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_CE(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_CEIE); -} - -/** - * @brief Disable CLUT Transfer Complete Interrupt - * @rmtoll CR CTCIE LL_DMA2D_DisableIT_CTC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_CTC(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_CTCIE); -} - -/** - * @brief Disable CLUT Access Error Interrupt - * @rmtoll CR CAEIE LL_DMA2D_DisableIT_CAE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_CAE(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_CAEIE); -} - -/** - * @brief Disable Transfer Watermark Interrupt - * @rmtoll CR TWIE LL_DMA2D_DisableIT_TW - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_TW(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_TWIE); -} - -/** - * @brief Disable Transfer Complete Interrupt - * @rmtoll CR TCIE LL_DMA2D_DisableIT_TC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_TC(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_TCIE); -} - -/** - * @brief Disable Transfer Error Interrupt - * @rmtoll CR TEIE LL_DMA2D_DisableIT_TE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_TE(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_TEIE); -} - -/** - * @brief Check if the DMA2D Configuration Error interrupt source is enabled or disabled. - * @rmtoll CR CEIE LL_DMA2D_IsEnabledIT_CE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_CE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_CEIE) == (DMA2D_CR_CEIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D CLUT Transfer Complete interrupt source is enabled or disabled. - * @rmtoll CR CTCIE LL_DMA2D_IsEnabledIT_CTC - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_CTC(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_CTCIE) == (DMA2D_CR_CTCIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D CLUT Access Error interrupt source is enabled or disabled. - * @rmtoll CR CAEIE LL_DMA2D_IsEnabledIT_CAE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_CAE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_CAEIE) == (DMA2D_CR_CAEIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Watermark interrupt source is enabled or disabled. - * @rmtoll CR TWIE LL_DMA2D_IsEnabledIT_TW - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_TW(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_TWIE) == (DMA2D_CR_TWIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Complete interrupt source is enabled or disabled. - * @rmtoll CR TCIE LL_DMA2D_IsEnabledIT_TC - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_TC(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_TCIE) == (DMA2D_CR_TCIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Error interrupt source is enabled or disabled. - * @rmtoll CR TEIE LL_DMA2D_IsEnabledIT_TE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_TE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_TEIE) == (DMA2D_CR_TEIE)) ? 1UL : 0UL); -} - - - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA2D_LL_EF_Init_Functions Initialization and De-initialization Functions - * @{ - */ - -ErrorStatus LL_DMA2D_DeInit(DMA2D_TypeDef *DMA2Dx); -ErrorStatus LL_DMA2D_Init(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_InitTypeDef *DMA2D_InitStruct); -void LL_DMA2D_StructInit(LL_DMA2D_InitTypeDef *DMA2D_InitStruct); -void LL_DMA2D_ConfigLayer(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_LayerCfgTypeDef *DMA2D_LayerCfg, uint32_t LayerIdx); -void LL_DMA2D_LayerCfgStructInit(LL_DMA2D_LayerCfgTypeDef *DMA2D_LayerCfg); -void LL_DMA2D_ConfigOutputColor(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_ColorTypeDef *DMA2D_ColorStruct); -uint32_t LL_DMA2D_GetOutputBlueColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode); -uint32_t LL_DMA2D_GetOutputGreenColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode); -uint32_t LL_DMA2D_GetOutputRedColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode); -uint32_t LL_DMA2D_GetOutputAlphaColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode); -void LL_DMA2D_ConfigSize(DMA2D_TypeDef *DMA2Dx, uint32_t NbrOfLines, uint32_t NbrOfPixelsPerLines); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (DMA2D) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_DMA2D_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h deleted file mode 100644 index c816e266efa32a7..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h +++ /dev/null @@ -1,956 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_exti.h - * @author MCD Application Team - * @brief Header file of EXTI LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_EXTI_H -#define __STM32F4xx_LL_EXTI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (EXTI) - -/** @defgroup EXTI_LL EXTI - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private Macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_Private_Macros EXTI Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_ES_INIT EXTI Exported Init structure - * @{ - */ -typedef struct -{ - - uint32_t Line_0_31; /*!< Specifies the EXTI lines to be enabled or disabled for Lines in range 0 to 31 - This parameter can be any combination of @ref EXTI_LL_EC_LINE */ - - FunctionalState LineCommand; /*!< Specifies the new state of the selected EXTI lines. - This parameter can be set either to ENABLE or DISABLE */ - - uint8_t Mode; /*!< Specifies the mode for the EXTI lines. - This parameter can be a value of @ref EXTI_LL_EC_MODE. */ - - uint8_t Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. - This parameter can be a value of @ref EXTI_LL_EC_TRIGGER. */ -} LL_EXTI_InitTypeDef; - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Constants EXTI Exported Constants - * @{ - */ - -/** @defgroup EXTI_LL_EC_LINE LINE - * @{ - */ -#define LL_EXTI_LINE_0 EXTI_IMR_IM0 /*!< Extended line 0 */ -#define LL_EXTI_LINE_1 EXTI_IMR_IM1 /*!< Extended line 1 */ -#define LL_EXTI_LINE_2 EXTI_IMR_IM2 /*!< Extended line 2 */ -#define LL_EXTI_LINE_3 EXTI_IMR_IM3 /*!< Extended line 3 */ -#define LL_EXTI_LINE_4 EXTI_IMR_IM4 /*!< Extended line 4 */ -#define LL_EXTI_LINE_5 EXTI_IMR_IM5 /*!< Extended line 5 */ -#define LL_EXTI_LINE_6 EXTI_IMR_IM6 /*!< Extended line 6 */ -#define LL_EXTI_LINE_7 EXTI_IMR_IM7 /*!< Extended line 7 */ -#define LL_EXTI_LINE_8 EXTI_IMR_IM8 /*!< Extended line 8 */ -#define LL_EXTI_LINE_9 EXTI_IMR_IM9 /*!< Extended line 9 */ -#define LL_EXTI_LINE_10 EXTI_IMR_IM10 /*!< Extended line 10 */ -#define LL_EXTI_LINE_11 EXTI_IMR_IM11 /*!< Extended line 11 */ -#define LL_EXTI_LINE_12 EXTI_IMR_IM12 /*!< Extended line 12 */ -#define LL_EXTI_LINE_13 EXTI_IMR_IM13 /*!< Extended line 13 */ -#define LL_EXTI_LINE_14 EXTI_IMR_IM14 /*!< Extended line 14 */ -#define LL_EXTI_LINE_15 EXTI_IMR_IM15 /*!< Extended line 15 */ -#if defined(EXTI_IMR_IM16) -#define LL_EXTI_LINE_16 EXTI_IMR_IM16 /*!< Extended line 16 */ -#endif -#define LL_EXTI_LINE_17 EXTI_IMR_IM17 /*!< Extended line 17 */ -#if defined(EXTI_IMR_IM18) -#define LL_EXTI_LINE_18 EXTI_IMR_IM18 /*!< Extended line 18 */ -#endif -#define LL_EXTI_LINE_19 EXTI_IMR_IM19 /*!< Extended line 19 */ -#if defined(EXTI_IMR_IM20) -#define LL_EXTI_LINE_20 EXTI_IMR_IM20 /*!< Extended line 20 */ -#endif -#if defined(EXTI_IMR_IM21) -#define LL_EXTI_LINE_21 EXTI_IMR_IM21 /*!< Extended line 21 */ -#endif -#if defined(EXTI_IMR_IM22) -#define LL_EXTI_LINE_22 EXTI_IMR_IM22 /*!< Extended line 22 */ -#endif -#if defined(EXTI_IMR_IM23) -#define LL_EXTI_LINE_23 EXTI_IMR_IM23 /*!< Extended line 23 */ -#endif -#if defined(EXTI_IMR_IM24) -#define LL_EXTI_LINE_24 EXTI_IMR_IM24 /*!< Extended line 24 */ -#endif -#if defined(EXTI_IMR_IM25) -#define LL_EXTI_LINE_25 EXTI_IMR_IM25 /*!< Extended line 25 */ -#endif -#if defined(EXTI_IMR_IM26) -#define LL_EXTI_LINE_26 EXTI_IMR_IM26 /*!< Extended line 26 */ -#endif -#if defined(EXTI_IMR_IM27) -#define LL_EXTI_LINE_27 EXTI_IMR_IM27 /*!< Extended line 27 */ -#endif -#if defined(EXTI_IMR_IM28) -#define LL_EXTI_LINE_28 EXTI_IMR_IM28 /*!< Extended line 28 */ -#endif -#if defined(EXTI_IMR_IM29) -#define LL_EXTI_LINE_29 EXTI_IMR_IM29 /*!< Extended line 29 */ -#endif -#if defined(EXTI_IMR_IM30) -#define LL_EXTI_LINE_30 EXTI_IMR_IM30 /*!< Extended line 30 */ -#endif -#if defined(EXTI_IMR_IM31) -#define LL_EXTI_LINE_31 EXTI_IMR_IM31 /*!< Extended line 31 */ -#endif -#define LL_EXTI_LINE_ALL_0_31 EXTI_IMR_IM /*!< All Extended line not reserved*/ - - -#define LL_EXTI_LINE_ALL ((uint32_t)0xFFFFFFFFU) /*!< All Extended line */ - -#if defined(USE_FULL_LL_DRIVER) -#define LL_EXTI_LINE_NONE ((uint32_t)0x00000000U) /*!< None Extended line */ -#endif /*USE_FULL_LL_DRIVER*/ - -/** - * @} - */ -#if defined(USE_FULL_LL_DRIVER) - -/** @defgroup EXTI_LL_EC_MODE Mode - * @{ - */ -#define LL_EXTI_MODE_IT ((uint8_t)0x00U) /*!< Interrupt Mode */ -#define LL_EXTI_MODE_EVENT ((uint8_t)0x01U) /*!< Event Mode */ -#define LL_EXTI_MODE_IT_EVENT ((uint8_t)0x02U) /*!< Interrupt & Event Mode */ -/** - * @} - */ - -/** @defgroup EXTI_LL_EC_TRIGGER Edge Trigger - * @{ - */ -#define LL_EXTI_TRIGGER_NONE ((uint8_t)0x00U) /*!< No Trigger Mode */ -#define LL_EXTI_TRIGGER_RISING ((uint8_t)0x01U) /*!< Trigger Rising Mode */ -#define LL_EXTI_TRIGGER_FALLING ((uint8_t)0x02U) /*!< Trigger Falling Mode */ -#define LL_EXTI_TRIGGER_RISING_FALLING ((uint8_t)0x03U) /*!< Trigger Rising & Falling Mode */ - -/** - * @} - */ - - -#endif /*USE_FULL_LL_DRIVER*/ - - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Macros EXTI Exported Macros - * @{ - */ - -/** @defgroup EXTI_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in EXTI register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_EXTI_WriteReg(__REG__, __VALUE__) WRITE_REG(EXTI->__REG__, (__VALUE__)) - -/** - * @brief Read a value in EXTI register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_EXTI_ReadReg(__REG__) READ_REG(EXTI->__REG__) -/** - * @} - */ - - -/** - * @} - */ - - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Functions EXTI Exported Functions - * @{ - */ -/** @defgroup EXTI_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Interrupt request for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_EnableIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableIT_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->IMR, ExtiLine); -} - -/** - * @brief Disable ExtiLine Interrupt request for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_DisableIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableIT_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->IMR, ExtiLine); -} - - -/** - * @brief Indicate if ExtiLine Interrupt request is enabled for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_IsEnabledIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledIT_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->IMR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Event_Management Event_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Event request for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_EnableEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableEvent_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->EMR, ExtiLine); - -} - - -/** - * @brief Disable ExtiLine Event request for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_DisableEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableEvent_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->EMR, ExtiLine); -} - - -/** - * @brief Indicate if ExtiLine Event request is enabled for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_IsEnabledEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledEvent_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->EMR, ExtiLine) == (ExtiLine)); - -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Rising_Trigger_Management Rising_Trigger_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Rising Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a rising edge on a configurable interrupt - * line occurs during a write operation in the EXTI_RTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll RTSR RTx LL_EXTI_EnableRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableRisingTrig_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->RTSR, ExtiLine); - -} - - -/** - * @brief Disable ExtiLine Rising Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a rising edge on a configurable interrupt - * line occurs during a write operation in the EXTI_RTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll RTSR RTx LL_EXTI_DisableRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableRisingTrig_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->RTSR, ExtiLine); - -} - - -/** - * @brief Check if rising edge trigger is enabled for Lines in range 0 to 31 - * @rmtoll RTSR RTx LL_EXTI_IsEnabledRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledRisingTrig_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->RTSR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Falling_Trigger_Management Falling_Trigger_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Falling Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a falling edge on a configurable interrupt - * line occurs during a write operation in the EXTI_FTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll FTSR FTx LL_EXTI_EnableFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableFallingTrig_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->FTSR, ExtiLine); -} - - -/** - * @brief Disable ExtiLine Falling Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a Falling edge on a configurable interrupt - * line occurs during a write operation in the EXTI_FTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for the same interrupt line. - * In this case, both generate a trigger condition. - * @rmtoll FTSR FTx LL_EXTI_DisableFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableFallingTrig_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->FTSR, ExtiLine); -} - - -/** - * @brief Check if falling edge trigger is enabled for Lines in range 0 to 31 - * @rmtoll FTSR FTx LL_EXTI_IsEnabledFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledFallingTrig_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->FTSR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Software_Interrupt_Management Software_Interrupt_Management - * @{ - */ - -/** - * @brief Generate a software Interrupt Event for Lines in range 0 to 31 - * @note If the interrupt is enabled on this line in the EXTI_IMR, writing a 1 to - * this bit when it is at '0' sets the corresponding pending bit in EXTI_PR - * resulting in an interrupt request generation. - * This bit is cleared by clearing the corresponding bit in the EXTI_PR - * register (by writing a 1 into the bit) - * @rmtoll SWIER SWIx LL_EXTI_GenerateSWI_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_GenerateSWI_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->SWIER, ExtiLine); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Flag_Management Flag_Management - * @{ - */ - -/** - * @brief Check if the ExtLine Flag is set or not for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_IsActiveFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsActiveFlag_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->PR, ExtiLine) == (ExtiLine)); -} - - -/** - * @brief Read ExtLine Combination Flag for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_ReadFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval @note This bit is set when the selected edge event arrives on the interrupt - */ -__STATIC_INLINE uint32_t LL_EXTI_ReadFlag_0_31(uint32_t ExtiLine) -{ - return (uint32_t)(READ_BIT(EXTI->PR, ExtiLine)); -} - - -/** - * @brief Clear ExtLine Flags for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_ClearFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_ClearFlag_0_31(uint32_t ExtiLine) -{ - WRITE_REG(EXTI->PR, ExtiLine); -} - - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_EXTI_Init(LL_EXTI_InitTypeDef *EXTI_InitStruct); -uint32_t LL_EXTI_DeInit(void); -void LL_EXTI_StructInit(LL_EXTI_InitTypeDef *EXTI_InitStruct); - - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* EXTI */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_EXTI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmc.h deleted file mode 100644 index 71e7c7425e911e8..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmc.h +++ /dev/null @@ -1,1403 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fmc.h - * @author MCD Application Team - * @brief Header file of FMC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_FMC_H -#define __STM32F4xx_LL_FMC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMC_LL - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/* Private types -------------------------------------------------------------*/ -/** @defgroup FMC_LL_Private_Types FMC Private Types - * @{ - */ - -/** - * @brief FMC NORSRAM Configuration Structure definition - */ -typedef struct -{ - uint32_t NSBank; /*!< Specifies the NORSRAM memory device that will be used. - This parameter can be a value of @ref FMC_NORSRAM_Bank */ - - uint32_t DataAddressMux; /*!< Specifies whether the address and data values are - multiplexed on the data bus or not. - This parameter can be a value of @ref FMC_Data_Address_Bus_Multiplexing */ - - uint32_t MemoryType; /*!< Specifies the type of external memory attached to - the corresponding memory device. - This parameter can be a value of @ref FMC_Memory_Type */ - - uint32_t MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be a value of @ref FMC_NORSRAM_Data_Width */ - - uint32_t BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, - valid only with synchronous burst Flash memories. - This parameter can be a value of @ref FMC_Burst_Access_Mode */ - - uint32_t WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing - the Flash memory in burst mode. - This parameter can be a value of @ref FMC_Wait_Signal_Polarity */ - - uint32_t WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash - memory, valid only when accessing Flash memories in burst mode. - This parameter can be a value of @ref FMC_Wrap_Mode - This mode is not available for the STM32F446/467/479xx devices */ - - uint32_t WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one - clock cycle before the wait state or during the wait state, - valid only when accessing memories in burst mode. - This parameter can be a value of @ref FMC_Wait_Timing */ - - uint32_t WriteOperation; /*!< Enables or disables the write operation in the selected device by the FMC. - This parameter can be a value of @ref FMC_Write_Operation */ - - uint32_t WaitSignal; /*!< Enables or disables the wait state insertion via wait - signal, valid for Flash memory access in burst mode. - This parameter can be a value of @ref FMC_Wait_Signal */ - - uint32_t ExtendedMode; /*!< Enables or disables the extended mode. - This parameter can be a value of @ref FMC_Extended_Mode */ - - uint32_t AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, - valid only with asynchronous Flash memories. - This parameter can be a value of @ref FMC_AsynchronousWait */ - - uint32_t WriteBurst; /*!< Enables or disables the write burst operation. - This parameter can be a value of @ref FMC_Write_Burst */ - - uint32_t ContinuousClock; /*!< Enables or disables the FMC clock output to external memory devices. - This parameter is only enabled through the FMC_BCR1 register, and don't care - through FMC_BCR2..4 registers. - This parameter can be a value of @ref FMC_Continous_Clock */ - - uint32_t WriteFifo; /*!< Enables or disables the write FIFO used by the FMC controller. - This parameter is only enabled through the FMC_BCR1 register, and don't care - through FMC_BCR2..4 registers. - This parameter can be a value of @ref FMC_Write_FIFO - This mode is available only for the STM32F446/469/479xx devices */ - - uint32_t PageSize; /*!< Specifies the memory page size. - This parameter can be a value of @ref FMC_Page_Size */ -}FMC_NORSRAM_InitTypeDef; - -/** - * @brief FMC NORSRAM Timing parameters structure definition - */ -typedef struct -{ - uint32_t AddressSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address setup time. - This parameter can be a value between Min_Data = 0 and Max_Data = 15. - @note This parameter is not used with synchronous NOR Flash memories. */ - - uint32_t AddressHoldTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address hold time. - This parameter can be a value between Min_Data = 1 and Max_Data = 15. - @note This parameter is not used with synchronous NOR Flash memories. */ - - uint32_t DataSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the data setup time. - This parameter can be a value between Min_Data = 1 and Max_Data = 255. - @note This parameter is used for SRAMs, ROMs and asynchronous multiplexed - NOR Flash memories. */ - - uint32_t BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure - the duration of the bus turnaround. - This parameter can be a value between Min_Data = 0 and Max_Data = 15. - @note This parameter is only used for multiplexed NOR Flash memories. */ - - uint32_t CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of - HCLK cycles. This parameter can be a value between Min_Data = 2 and Max_Data = 16. - @note This parameter is not used for asynchronous NOR Flash, SRAM or ROM - accesses. */ - - uint32_t DataLatency; /*!< Defines the number of memory clock cycles to issue - to the memory before getting the first data. - The parameter value depends on the memory type as shown below: - - It must be set to 0 in case of a CRAM - - It is don't care in asynchronous NOR, SRAM or ROM accesses - - It may assume a value between Min_Data = 2 and Max_Data = 17 in NOR Flash memories - with synchronous burst mode enable */ - - uint32_t AccessMode; /*!< Specifies the asynchronous access mode. - This parameter can be a value of @ref FMC_Access_Mode */ -}FMC_NORSRAM_TimingTypeDef; - -/** - * @brief FMC NAND Configuration Structure definition - */ -typedef struct -{ - uint32_t NandBank; /*!< Specifies the NAND memory device that will be used. - This parameter can be a value of @ref FMC_NAND_Bank */ - - uint32_t Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory device. - This parameter can be any value of @ref FMC_Wait_feature */ - - uint32_t MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be any value of @ref FMC_NAND_Data_Width */ - - uint32_t EccComputation; /*!< Enables or disables the ECC computation. - This parameter can be any value of @ref FMC_ECC */ - - uint32_t ECCPageSize; /*!< Defines the page size for the extended ECC. - This parameter can be any value of @ref FMC_ECC_Page_Size */ - - uint32_t TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ -}FMC_NAND_InitTypeDef; - -/** - * @brief FMC NAND/PCCARD Timing parameters structure definition - */ -typedef struct -{ - uint32_t SetupTime; /*!< Defines the number of HCLK cycles to setup address before - the command assertion for NAND-Flash read or write access - to common/Attribute or I/O memory space (depending on - the memory space timing to be configured). - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the - command for NAND-Flash read or write access to - common/Attribute or I/O memory space (depending on the - memory space timing to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - - uint32_t HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address - (and data for write access) after the command de-assertion - for NAND-Flash read or write access to common/Attribute - or I/O memory space (depending on the memory space timing - to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - - uint32_t HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the - data bus is kept in HiZ after the start of a NAND-Flash - write access to common/Attribute or I/O memory space (depending - on the memory space timing to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ -}FMC_NAND_PCC_TimingTypeDef; - -/** - * @brief FMC NAND Configuration Structure definition - */ -typedef struct -{ - uint32_t Waitfeature; /*!< Enables or disables the Wait feature for the PCCARD Memory device. - This parameter can be any value of @ref FMC_Wait_feature */ - - uint32_t TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ -}FMC_PCCARD_InitTypeDef; - -/** - * @brief FMC SDRAM Configuration Structure definition - */ -typedef struct -{ - uint32_t SDBank; /*!< Specifies the SDRAM memory device that will be used. - This parameter can be a value of @ref FMC_SDRAM_Bank */ - - uint32_t ColumnBitsNumber; /*!< Defines the number of bits of column address. - This parameter can be a value of @ref FMC_SDRAM_Column_Bits_number. */ - - uint32_t RowBitsNumber; /*!< Defines the number of bits of column address. - This parameter can be a value of @ref FMC_SDRAM_Row_Bits_number. */ - - uint32_t MemoryDataWidth; /*!< Defines the memory device width. - This parameter can be a value of @ref FMC_SDRAM_Memory_Bus_Width. */ - - uint32_t InternalBankNumber; /*!< Defines the number of the device's internal banks. - This parameter can be of @ref FMC_SDRAM_Internal_Banks_Number. */ - - uint32_t CASLatency; /*!< Defines the SDRAM CAS latency in number of memory clock cycles. - This parameter can be a value of @ref FMC_SDRAM_CAS_Latency. */ - - uint32_t WriteProtection; /*!< Enables the SDRAM device to be accessed in write mode. - This parameter can be a value of @ref FMC_SDRAM_Write_Protection. */ - - uint32_t SDClockPeriod; /*!< Define the SDRAM Clock Period for both SDRAM devices and they allow - to disable the clock before changing frequency. - This parameter can be a value of @ref FMC_SDRAM_Clock_Period. */ - - uint32_t ReadBurst; /*!< This bit enable the SDRAM controller to anticipate the next read - commands during the CAS latency and stores data in the Read FIFO. - This parameter can be a value of @ref FMC_SDRAM_Read_Burst. */ - - uint32_t ReadPipeDelay; /*!< Define the delay in system clock cycles on read data path. - This parameter can be a value of @ref FMC_SDRAM_Read_Pipe_Delay. */ -}FMC_SDRAM_InitTypeDef; - -/** - * @brief FMC SDRAM Timing parameters structure definition - */ -typedef struct -{ - uint32_t LoadToActiveDelay; /*!< Defines the delay between a Load Mode Register command and - an active or Refresh command in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t ExitSelfRefreshDelay; /*!< Defines the delay from releasing the self refresh command to - issuing the Activate command in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t SelfRefreshTime; /*!< Defines the minimum Self Refresh period in number of memory clock - cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t RowCycleDelay; /*!< Defines the delay between the Refresh command and the Activate command - and the delay between two consecutive Refresh commands in number of - memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t WriteRecoveryTime; /*!< Defines the Write recovery Time in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t RPDelay; /*!< Defines the delay between a Precharge Command and an other command - in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t RCDDelay; /*!< Defines the delay between the Activate Command and a Read/Write - command in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ -}FMC_SDRAM_TimingTypeDef; - -/** - * @brief SDRAM command parameters structure definition - */ -typedef struct -{ - uint32_t CommandMode; /*!< Defines the command issued to the SDRAM device. - This parameter can be a value of @ref FMC_SDRAM_Command_Mode. */ - - uint32_t CommandTarget; /*!< Defines which device (1 or 2) the command will be issued to. - This parameter can be a value of @ref FMC_SDRAM_Command_Target. */ - - uint32_t AutoRefreshNumber; /*!< Defines the number of consecutive auto refresh command issued - in auto refresh mode. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - uint32_t ModeRegisterDefinition; /*!< Defines the SDRAM Mode register content */ -}FMC_SDRAM_CommandTypeDef; -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMC_LL_Private_Constants FMC Private Constants - * @{ - */ - -/** @defgroup FMC_LL_NOR_SRAM_Controller FMC NOR/SRAM Controller - * @{ - */ -/** @defgroup FMC_NORSRAM_Bank FMC NOR/SRAM Bank - * @{ - */ -#define FMC_NORSRAM_BANK1 0x00000000U -#define FMC_NORSRAM_BANK2 0x00000002U -#define FMC_NORSRAM_BANK3 0x00000004U -#define FMC_NORSRAM_BANK4 0x00000006U -/** - * @} - */ - -/** @defgroup FMC_Data_Address_Bus_Multiplexing FMC Data Address Bus Multiplexing - * @{ - */ -#define FMC_DATA_ADDRESS_MUX_DISABLE 0x00000000U -#define FMC_DATA_ADDRESS_MUX_ENABLE 0x00000002U -/** - * @} - */ - -/** @defgroup FMC_Memory_Type FMC Memory Type - * @{ - */ -#define FMC_MEMORY_TYPE_SRAM 0x00000000U -#define FMC_MEMORY_TYPE_PSRAM 0x00000004U -#define FMC_MEMORY_TYPE_NOR 0x00000008U -/** - * @} - */ - -/** @defgroup FMC_NORSRAM_Data_Width FMC NORSRAM Data Width - * @{ - */ -#define FMC_NORSRAM_MEM_BUS_WIDTH_8 0x00000000U -#define FMC_NORSRAM_MEM_BUS_WIDTH_16 0x00000010U -#define FMC_NORSRAM_MEM_BUS_WIDTH_32 0x00000020U -/** - * @} - */ - -/** @defgroup FMC_NORSRAM_Flash_Access FMC NOR/SRAM Flash Access - * @{ - */ -#define FMC_NORSRAM_FLASH_ACCESS_ENABLE 0x00000040U -#define FMC_NORSRAM_FLASH_ACCESS_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup FMC_Burst_Access_Mode FMC Burst Access Mode - * @{ - */ -#define FMC_BURST_ACCESS_MODE_DISABLE 0x00000000U -#define FMC_BURST_ACCESS_MODE_ENABLE 0x00000100U -/** - * @} - */ - -/** @defgroup FMC_Wait_Signal_Polarity FMC Wait Signal Polarity - * @{ - */ -#define FMC_WAIT_SIGNAL_POLARITY_LOW 0x00000000U -#define FMC_WAIT_SIGNAL_POLARITY_HIGH 0x00000200U -/** - * @} - */ - -/** @defgroup FMC_Wrap_Mode FMC Wrap Mode - * @{ - */ -/** @note This mode is not available for the STM32F446/469/479xx devices - */ -#define FMC_WRAP_MODE_DISABLE 0x00000000U -#define FMC_WRAP_MODE_ENABLE 0x00000400U -/** - * @} - */ - -/** @defgroup FMC_Wait_Timing FMC Wait Timing - * @{ - */ -#define FMC_WAIT_TIMING_BEFORE_WS 0x00000000U -#define FMC_WAIT_TIMING_DURING_WS 0x00000800U -/** - * @} - */ - -/** @defgroup FMC_Write_Operation FMC Write Operation - * @{ - */ -#define FMC_WRITE_OPERATION_DISABLE 0x00000000U -#define FMC_WRITE_OPERATION_ENABLE 0x00001000U -/** - * @} - */ - -/** @defgroup FMC_Wait_Signal FMC Wait Signal - * @{ - */ -#define FMC_WAIT_SIGNAL_DISABLE 0x00000000U -#define FMC_WAIT_SIGNAL_ENABLE 0x00002000U -/** - * @} - */ - -/** @defgroup FMC_Extended_Mode FMC Extended Mode - * @{ - */ -#define FMC_EXTENDED_MODE_DISABLE 0x00000000U -#define FMC_EXTENDED_MODE_ENABLE 0x00004000U -/** - * @} - */ - -/** @defgroup FMC_AsynchronousWait FMC Asynchronous Wait - * @{ - */ -#define FMC_ASYNCHRONOUS_WAIT_DISABLE 0x00000000U -#define FMC_ASYNCHRONOUS_WAIT_ENABLE 0x00008000U -/** - * @} - */ - -/** @defgroup FMC_Page_Size FMC Page Size - * @{ - */ -#define FMC_PAGE_SIZE_NONE 0x00000000U -#define FMC_PAGE_SIZE_128 ((uint32_t)FMC_BCR1_CPSIZE_0) -#define FMC_PAGE_SIZE_256 ((uint32_t)FMC_BCR1_CPSIZE_1) -#define FMC_PAGE_SIZE_512 ((uint32_t)(FMC_BCR1_CPSIZE_0 | FMC_BCR1_CPSIZE_1)) -#define FMC_PAGE_SIZE_1024 ((uint32_t)FMC_BCR1_CPSIZE_2) -/** - * @} - */ - -/** @defgroup FMC_Write_FIFO FMC Write FIFO - * @note These values are available only for the STM32F446/469/479xx devices. - * @{ - */ -#define FMC_WRITE_FIFO_DISABLE ((uint32_t)FMC_BCR1_WFDIS) -#define FMC_WRITE_FIFO_ENABLE 0x00000000U -/** - * @} - */ - -/** @defgroup FMC_Write_Burst FMC Write Burst - * @{ - */ -#define FMC_WRITE_BURST_DISABLE 0x00000000U -#define FMC_WRITE_BURST_ENABLE 0x00080000U -/** - * @} - */ - -/** @defgroup FMC_Continous_Clock FMC Continuous Clock - * @{ - */ -#define FMC_CONTINUOUS_CLOCK_SYNC_ONLY 0x00000000U -#define FMC_CONTINUOUS_CLOCK_SYNC_ASYNC 0x00100000U -/** - * @} - */ - -/** @defgroup FMC_Access_Mode FMC Access Mode - * @{ - */ -#define FMC_ACCESS_MODE_A 0x00000000U -#define FMC_ACCESS_MODE_B 0x10000000U -#define FMC_ACCESS_MODE_C 0x20000000U -#define FMC_ACCESS_MODE_D 0x30000000U -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup FMC_LL_NAND_Controller FMC NAND Controller - * @{ - */ -/** @defgroup FMC_NAND_Bank FMC NAND Bank - * @{ - */ -#define FMC_NAND_BANK2 0x00000010U -#define FMC_NAND_BANK3 0x00000100U -/** - * @} - */ - -/** @defgroup FMC_Wait_feature FMC Wait feature - * @{ - */ -#define FMC_NAND_PCC_WAIT_FEATURE_DISABLE 0x00000000U -#define FMC_NAND_PCC_WAIT_FEATURE_ENABLE 0x00000002U -/** - * @} - */ - -/** @defgroup FMC_PCR_Memory_Type FMC PCR Memory Type - * @{ - */ -#define FMC_PCR_MEMORY_TYPE_PCCARD 0x00000000U -#define FMC_PCR_MEMORY_TYPE_NAND 0x00000008U -/** - * @} - */ - -/** @defgroup FMC_NAND_Data_Width FMC NAND Data Width - * @{ - */ -#define FMC_NAND_PCC_MEM_BUS_WIDTH_8 0x00000000U -#define FMC_NAND_PCC_MEM_BUS_WIDTH_16 0x00000010U -/** - * @} - */ - -/** @defgroup FMC_ECC FMC ECC - * @{ - */ -#define FMC_NAND_ECC_DISABLE 0x00000000U -#define FMC_NAND_ECC_ENABLE 0x00000040U -/** - * @} - */ - -/** @defgroup FMC_ECC_Page_Size FMC ECC Page Size - * @{ - */ -#define FMC_NAND_ECC_PAGE_SIZE_256BYTE 0x00000000U -#define FMC_NAND_ECC_PAGE_SIZE_512BYTE 0x00020000U -#define FMC_NAND_ECC_PAGE_SIZE_1024BYTE 0x00040000U -#define FMC_NAND_ECC_PAGE_SIZE_2048BYTE 0x00060000U -#define FMC_NAND_ECC_PAGE_SIZE_4096BYTE 0x00080000U -#define FMC_NAND_ECC_PAGE_SIZE_8192BYTE 0x000A0000U -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup FMC_LL_SDRAM_Controller FMC SDRAM Controller - * @{ - */ -/** @defgroup FMC_SDRAM_Bank FMC SDRAM Bank - * @{ - */ -#define FMC_SDRAM_BANK1 0x00000000U -#define FMC_SDRAM_BANK2 0x00000001U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Column_Bits_number FMC SDRAM Column Bits number - * @{ - */ -#define FMC_SDRAM_COLUMN_BITS_NUM_8 0x00000000U -#define FMC_SDRAM_COLUMN_BITS_NUM_9 0x00000001U -#define FMC_SDRAM_COLUMN_BITS_NUM_10 0x00000002U -#define FMC_SDRAM_COLUMN_BITS_NUM_11 0x00000003U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Row_Bits_number FMC SDRAM Row Bits number - * @{ - */ -#define FMC_SDRAM_ROW_BITS_NUM_11 0x00000000U -#define FMC_SDRAM_ROW_BITS_NUM_12 0x00000004U -#define FMC_SDRAM_ROW_BITS_NUM_13 0x00000008U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Memory_Bus_Width FMC SDRAM Memory Bus Width - * @{ - */ -#define FMC_SDRAM_MEM_BUS_WIDTH_8 0x00000000U -#define FMC_SDRAM_MEM_BUS_WIDTH_16 0x00000010U -#define FMC_SDRAM_MEM_BUS_WIDTH_32 0x00000020U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Internal_Banks_Number FMC SDRAM Internal Banks Number - * @{ - */ -#define FMC_SDRAM_INTERN_BANKS_NUM_2 0x00000000U -#define FMC_SDRAM_INTERN_BANKS_NUM_4 0x00000040U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_CAS_Latency FMC SDRAM CAS Latency - * @{ - */ -#define FMC_SDRAM_CAS_LATENCY_1 0x00000080U -#define FMC_SDRAM_CAS_LATENCY_2 0x00000100U -#define FMC_SDRAM_CAS_LATENCY_3 0x00000180U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Write_Protection FMC SDRAM Write Protection - * @{ - */ -#define FMC_SDRAM_WRITE_PROTECTION_DISABLE 0x00000000U -#define FMC_SDRAM_WRITE_PROTECTION_ENABLE 0x00000200U - -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Clock_Period FMC SDRAM Clock Period - * @{ - */ -#define FMC_SDRAM_CLOCK_DISABLE 0x00000000U -#define FMC_SDRAM_CLOCK_PERIOD_2 0x00000800U -#define FMC_SDRAM_CLOCK_PERIOD_3 0x00000C00U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Read_Burst FMC SDRAM Read Burst - * @{ - */ -#define FMC_SDRAM_RBURST_DISABLE 0x00000000U -#define FMC_SDRAM_RBURST_ENABLE 0x00001000U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Read_Pipe_Delay FMC SDRAM Read Pipe Delay - * @{ - */ -#define FMC_SDRAM_RPIPE_DELAY_0 0x00000000U -#define FMC_SDRAM_RPIPE_DELAY_1 0x00002000U -#define FMC_SDRAM_RPIPE_DELAY_2 0x00004000U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Command_Mode FMC SDRAM Command Mode - * @{ - */ -#define FMC_SDRAM_CMD_NORMAL_MODE 0x00000000U -#define FMC_SDRAM_CMD_CLK_ENABLE 0x00000001U -#define FMC_SDRAM_CMD_PALL 0x00000002U -#define FMC_SDRAM_CMD_AUTOREFRESH_MODE 0x00000003U -#define FMC_SDRAM_CMD_LOAD_MODE 0x00000004U -#define FMC_SDRAM_CMD_SELFREFRESH_MODE 0x00000005U -#define FMC_SDRAM_CMD_POWERDOWN_MODE 0x00000006U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Command_Target FMC SDRAM Command Target - * @{ - */ -#define FMC_SDRAM_CMD_TARGET_BANK2 FMC_SDCMR_CTB2 -#define FMC_SDRAM_CMD_TARGET_BANK1 FMC_SDCMR_CTB1 -#define FMC_SDRAM_CMD_TARGET_BANK1_2 0x00000018U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Mode_Status FMC SDRAM Mode Status - * @{ - */ -#define FMC_SDRAM_NORMAL_MODE 0x00000000U -#define FMC_SDRAM_SELF_REFRESH_MODE FMC_SDSR_MODES1_0 -#define FMC_SDRAM_POWER_DOWN_MODE FMC_SDSR_MODES1_1 -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup FMC_LL_Interrupt_definition FMC Interrupt definition - * @{ - */ -#define FMC_IT_RISING_EDGE 0x00000008U -#define FMC_IT_LEVEL 0x00000010U -#define FMC_IT_FALLING_EDGE 0x00000020U -#define FMC_IT_REFRESH_ERROR 0x00004000U -/** - * @} - */ - -/** @defgroup FMC_LL_Flag_definition FMC Flag definition - * @{ - */ -#define FMC_FLAG_RISING_EDGE 0x00000001U -#define FMC_FLAG_LEVEL 0x00000002U -#define FMC_FLAG_FALLING_EDGE 0x00000004U -#define FMC_FLAG_FEMPT 0x00000040U -#define FMC_SDRAM_FLAG_REFRESH_IT FMC_SDSR_RE -#define FMC_SDRAM_FLAG_BUSY FMC_SDSR_BUSY -#define FMC_SDRAM_FLAG_REFRESH_ERROR FMC_SDRTR_CRE -/** - * @} - */ - -/** @defgroup FMC_LL_Alias_definition FMC Alias definition - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #define FMC_NAND_TypeDef FMC_Bank3_TypeDef -#else - #define FMC_NAND_TypeDef FMC_Bank2_3_TypeDef - #define FMC_PCCARD_TypeDef FMC_Bank4_TypeDef -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - #define FMC_NORSRAM_TypeDef FMC_Bank1_TypeDef - #define FMC_NORSRAM_EXTENDED_TypeDef FMC_Bank1E_TypeDef - #define FMC_SDRAM_TypeDef FMC_Bank5_6_TypeDef - - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #define FMC_NAND_DEVICE FMC_Bank3 -#else - #define FMC_NAND_DEVICE FMC_Bank2_3 - #define FMC_PCCARD_DEVICE FMC_Bank4 -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - #define FMC_NORSRAM_DEVICE FMC_Bank1 - #define FMC_NORSRAM_EXTENDED_DEVICE FMC_Bank1E - #define FMC_SDRAM_DEVICE FMC_Bank5_6 -/** - * @} - */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/** @defgroup FMC_LL_Private_Macros FMC Private Macros - * @{ - */ - -/** @defgroup FMC_LL_NOR_Macros FMC NOR/SRAM Macros - * @brief macros to handle NOR device enable/disable and read/write operations - * @{ - */ -/** - * @brief Enable the NORSRAM device access. - * @param __INSTANCE__ FMC_NORSRAM Instance - * @param __BANK__ FMC_NORSRAM Bank - * @retval None - */ -#define __FMC_NORSRAM_ENABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->BTCR[(__BANK__)] |= FMC_BCR1_MBKEN) - -/** - * @brief Disable the NORSRAM device access. - * @param __INSTANCE__ FMC_NORSRAM Instance - * @param __BANK__ FMC_NORSRAM Bank - * @retval None - */ -#define __FMC_NORSRAM_DISABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->BTCR[(__BANK__)] &= ~FMC_BCR1_MBKEN) -/** - * @} - */ - -/** @defgroup FMC_LL_NAND_Macros FMC NAND Macros - * @brief macros to handle NAND device enable/disable - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Enable the NAND device access. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @retval None - */ -#define __FMC_NAND_ENABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->PCR |= FMC_PCR_PBKEN) - -/** - * @brief Disable the NAND device access. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @retval None - */ -#define __FMC_NAND_DISABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->PCR &= ~FMC_PCR_PBKEN) -#else /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ -/** - * @brief Enable the NAND device access. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @retval None - */ -#define __FMC_NAND_ENABLE(__INSTANCE__, __BANK__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->PCR2 |= FMC_PCR2_PBKEN): \ - ((__INSTANCE__)->PCR3 |= FMC_PCR3_PBKEN)) - -/** - * @brief Disable the NAND device access. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @retval None - */ -#define __FMC_NAND_DISABLE(__INSTANCE__, __BANK__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->PCR2 &= ~FMC_PCR2_PBKEN): \ - ((__INSTANCE__)->PCR3 &= ~FMC_PCR3_PBKEN)) - -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */ -/** - * @} - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @defgroup FMC_LL_PCCARD_Macros FMC PCCARD Macros - * @brief macros to handle SRAM read/write operations - * @{ - */ -/** - * @brief Enable the PCCARD device access. - * @param __INSTANCE__ FMC_PCCARD Instance - * @retval None - */ -#define __FMC_PCCARD_ENABLE(__INSTANCE__) ((__INSTANCE__)->PCR4 |= FMC_PCR4_PBKEN) - -/** - * @brief Disable the PCCARD device access. - * @param __INSTANCE__ FMC_PCCARD Instance - * @retval None - */ -#define __FMC_PCCARD_DISABLE(__INSTANCE__) ((__INSTANCE__)->PCR4 &= ~FMC_PCR4_PBKEN) -/** - * @} - */ -#endif /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ - -/** @defgroup FMC_LL_Flag_Interrupt_Macros FMC Flag&Interrupt Macros - * @brief macros to handle FMC flags and interrupts - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Enable the NAND device interrupt. - * @param __INSTANCE__ FMC_NAND instance - * @param __BANK__ FMC_NAND Bank - * @param __INTERRUPT__ FMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_NAND_ENABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) ((__INSTANCE__)->SR |= (__INTERRUPT__)) - -/** - * @brief Disable the NAND device interrupt. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __INTERRUPT__ FMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_NAND_DISABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) ((__INSTANCE__)->SR &= ~(__INTERRUPT__)) - -/** - * @brief Get flag status of the NAND device. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __FLAG__ FMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FMC_NAND_GET_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__INSTANCE__)->SR &(__FLAG__)) == (__FLAG__)) -/** - * @brief Clear flag status of the NAND device. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __FLAG__ FMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FMC_NAND_CLEAR_FLAG(__INSTANCE__, __BANK__, __FLAG__) ((__INSTANCE__)->SR &= ~(__FLAG__)) -#else /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ -/** - * @brief Enable the NAND device interrupt. - * @param __INSTANCE__ FMC_NAND instance - * @param __BANK__ FMC_NAND Bank - * @param __INTERRUPT__ FMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_NAND_ENABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->SR2 |= (__INTERRUPT__)): \ - ((__INSTANCE__)->SR3 |= (__INTERRUPT__))) - -/** - * @brief Disable the NAND device interrupt. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __INTERRUPT__ FMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_NAND_DISABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->SR2 &= ~(__INTERRUPT__)): \ - ((__INSTANCE__)->SR3 &= ~(__INTERRUPT__))) - -/** - * @brief Get flag status of the NAND device. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __FLAG__ FMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FMC_NAND_GET_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__BANK__) == FMC_NAND_BANK2)? (((__INSTANCE__)->SR2 &(__FLAG__)) == (__FLAG__)): \ - (((__INSTANCE__)->SR3 &(__FLAG__)) == (__FLAG__))) -/** - * @brief Clear flag status of the NAND device. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __FLAG__ FMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FMC_NAND_CLEAR_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->SR2 &= ~(__FLAG__)): \ - ((__INSTANCE__)->SR3 &= ~(__FLAG__))) -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief Enable the PCCARD device interrupt. - * @param __INSTANCE__ FMC_PCCARD instance - * @param __INTERRUPT__ FMC_PCCARD interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_PCCARD_ENABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SR4 |= (__INTERRUPT__)) - -/** - * @brief Disable the PCCARD device interrupt. - * @param __INSTANCE__ FMC_PCCARD instance - * @param __INTERRUPT__ FMC_PCCARD interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_PCCARD_DISABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SR4 &= ~(__INTERRUPT__)) - -/** - * @brief Get flag status of the PCCARD device. - * @param __INSTANCE__ FMC_PCCARD instance - * @param __FLAG__ FMC_PCCARD flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FMC_PCCARD_GET_FLAG(__INSTANCE__, __FLAG__) (((__INSTANCE__)->SR4 &(__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear flag status of the PCCARD device. - * @param __INSTANCE__ FMC_PCCARD instance - * @param __FLAG__ FMC_PCCARD flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FMC_PCCARD_CLEAR_FLAG(__INSTANCE__, __FLAG__) ((__INSTANCE__)->SR4 &= ~(__FLAG__)) -#endif /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ - -/** - * @brief Enable the SDRAM device interrupt. - * @param __INSTANCE__ FMC_SDRAM instance - * @param __INTERRUPT__ FMC_SDRAM interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_REFRESH_ERROR: Interrupt refresh error - * @retval None - */ -#define __FMC_SDRAM_ENABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SDRTR |= (__INTERRUPT__)) - -/** - * @brief Disable the SDRAM device interrupt. - * @param __INSTANCE__ FMC_SDRAM instance - * @param __INTERRUPT__ FMC_SDRAM interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_REFRESH_ERROR: Interrupt refresh error - * @retval None - */ -#define __FMC_SDRAM_DISABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SDRTR &= ~(__INTERRUPT__)) - -/** - * @brief Get flag status of the SDRAM device. - * @param __INSTANCE__ FMC_SDRAM instance - * @param __FLAG__ FMC_SDRAM flag - * This parameter can be any combination of the following values: - * @arg FMC_SDRAM_FLAG_REFRESH_IT: Interrupt refresh error. - * @arg FMC_SDRAM_FLAG_BUSY: SDRAM busy flag. - * @arg FMC_SDRAM_FLAG_REFRESH_ERROR: Refresh error flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FMC_SDRAM_GET_FLAG(__INSTANCE__, __FLAG__) (((__INSTANCE__)->SDSR &(__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear flag status of the SDRAM device. - * @param __INSTANCE__ FMC_SDRAM instance - * @param __FLAG__ FMC_SDRAM flag - * This parameter can be any combination of the following values: - * @arg FMC_SDRAM_FLAG_REFRESH_ERROR - * @retval None - */ -#define __FMC_SDRAM_CLEAR_FLAG(__INSTANCE__, __FLAG__) ((__INSTANCE__)->SDRTR |= (__FLAG__)) -/** - * @} - */ - -/** @defgroup FSMC_LL_Assert_Macros FSMC Assert Macros - * @{ - */ -#define IS_FMC_NORSRAM_BANK(BANK) (((BANK) == FMC_NORSRAM_BANK1) || \ - ((BANK) == FMC_NORSRAM_BANK2) || \ - ((BANK) == FMC_NORSRAM_BANK3) || \ - ((BANK) == FMC_NORSRAM_BANK4)) - -#define IS_FMC_MUX(__MUX__) (((__MUX__) == FMC_DATA_ADDRESS_MUX_DISABLE) || \ - ((__MUX__) == FMC_DATA_ADDRESS_MUX_ENABLE)) - -#define IS_FMC_MEMORY(__MEMORY__) (((__MEMORY__) == FMC_MEMORY_TYPE_SRAM) || \ - ((__MEMORY__) == FMC_MEMORY_TYPE_PSRAM)|| \ - ((__MEMORY__) == FMC_MEMORY_TYPE_NOR)) - -#define IS_FMC_NORSRAM_MEMORY_WIDTH(__WIDTH__) (((__WIDTH__) == FMC_NORSRAM_MEM_BUS_WIDTH_8) || \ - ((__WIDTH__) == FMC_NORSRAM_MEM_BUS_WIDTH_16) || \ - ((__WIDTH__) == FMC_NORSRAM_MEM_BUS_WIDTH_32)) - -#define IS_FMC_ACCESS_MODE(__MODE__) (((__MODE__) == FMC_ACCESS_MODE_A) || \ - ((__MODE__) == FMC_ACCESS_MODE_B) || \ - ((__MODE__) == FMC_ACCESS_MODE_C) || \ - ((__MODE__) == FMC_ACCESS_MODE_D)) - -#define IS_FMC_NAND_BANK(BANK) (((BANK) == FMC_NAND_BANK2) || \ - ((BANK) == FMC_NAND_BANK3)) - -#define IS_FMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FMC_NAND_PCC_WAIT_FEATURE_DISABLE) || \ - ((FEATURE) == FMC_NAND_PCC_WAIT_FEATURE_ENABLE)) - -#define IS_FMC_NAND_MEMORY_WIDTH(WIDTH) (((WIDTH) == FMC_NAND_PCC_MEM_BUS_WIDTH_8) || \ - ((WIDTH) == FMC_NAND_PCC_MEM_BUS_WIDTH_16)) - -#define IS_FMC_ECC_STATE(STATE) (((STATE) == FMC_NAND_ECC_DISABLE) || \ - ((STATE) == FMC_NAND_ECC_ENABLE)) - -#define IS_FMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FMC_NAND_ECC_PAGE_SIZE_256BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_512BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_1024BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_2048BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_4096BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_8192BYTE)) - -#define IS_FMC_TCLR_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_TAR_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_SETUP_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_WAIT_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_HOLD_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_HIZ_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_NORSRAM_DEVICE(__INSTANCE__) ((__INSTANCE__) == FMC_NORSRAM_DEVICE) - -#define IS_FMC_NORSRAM_EXTENDED_DEVICE(__INSTANCE__) ((__INSTANCE__) == FMC_NORSRAM_EXTENDED_DEVICE) - -#define IS_FMC_NAND_DEVICE(__INSTANCE__) ((__INSTANCE__) == FMC_NAND_DEVICE) - -#define IS_FMC_PCCARD_DEVICE(__INSTANCE__) ((__INSTANCE__) == FMC_PCCARD_DEVICE) - -#define IS_FMC_BURSTMODE(__STATE__) (((__STATE__) == FMC_BURST_ACCESS_MODE_DISABLE) || \ - ((__STATE__) == FMC_BURST_ACCESS_MODE_ENABLE)) - -#define IS_FMC_WAIT_POLARITY(__POLARITY__) (((__POLARITY__) == FMC_WAIT_SIGNAL_POLARITY_LOW) || \ - ((__POLARITY__) == FMC_WAIT_SIGNAL_POLARITY_HIGH)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -#define IS_FMC_WRAP_MODE(__MODE__) (((__MODE__) == FMC_WRAP_MODE_DISABLE) || \ - ((__MODE__) == FMC_WRAP_MODE_ENABLE)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#define IS_FMC_WAIT_SIGNAL_ACTIVE(__ACTIVE__) (((__ACTIVE__) == FMC_WAIT_TIMING_BEFORE_WS) || \ - ((__ACTIVE__) == FMC_WAIT_TIMING_DURING_WS)) - -#define IS_FMC_WRITE_OPERATION(__OPERATION__) (((__OPERATION__) == FMC_WRITE_OPERATION_DISABLE) || \ - ((__OPERATION__) == FMC_WRITE_OPERATION_ENABLE)) - -#define IS_FMC_WAITE_SIGNAL(__SIGNAL__) (((__SIGNAL__) == FMC_WAIT_SIGNAL_DISABLE) || \ - ((__SIGNAL__) == FMC_WAIT_SIGNAL_ENABLE)) - -#define IS_FMC_EXTENDED_MODE(__MODE__) (((__MODE__) == FMC_EXTENDED_MODE_DISABLE) || \ - ((__MODE__) == FMC_EXTENDED_MODE_ENABLE)) - -#define IS_FMC_ASYNWAIT(__STATE__) (((__STATE__) == FMC_ASYNCHRONOUS_WAIT_DISABLE) || \ - ((__STATE__) == FMC_ASYNCHRONOUS_WAIT_ENABLE)) - -#define IS_FMC_WRITE_BURST(__BURST__) (((__BURST__) == FMC_WRITE_BURST_DISABLE) || \ - ((__BURST__) == FMC_WRITE_BURST_ENABLE)) - -#define IS_FMC_CONTINOUS_CLOCK(CCLOCK) (((CCLOCK) == FMC_CONTINUOUS_CLOCK_SYNC_ONLY) || \ - ((CCLOCK) == FMC_CONTINUOUS_CLOCK_SYNC_ASYNC)) - -#define IS_FMC_ADDRESS_SETUP_TIME(__TIME__) ((__TIME__) <= 15U) - -#define IS_FMC_ADDRESS_HOLD_TIME(__TIME__) (((__TIME__) > 0U) && ((__TIME__) <= 15U)) - -#define IS_FMC_DATASETUP_TIME(__TIME__) (((__TIME__) > 0U) && ((__TIME__) <= 255U)) - -#define IS_FMC_TURNAROUND_TIME(__TIME__) ((__TIME__) <= 15U) - -#define IS_FMC_DATA_LATENCY(__LATENCY__) (((__LATENCY__) > 1U) && ((__LATENCY__) <= 17U)) - -#define IS_FMC_CLK_DIV(DIV) (((DIV) > 1U) && ((DIV) <= 16U)) - -#define IS_FMC_SDRAM_BANK(BANK) (((BANK) == FMC_SDRAM_BANK1) || \ - ((BANK) == FMC_SDRAM_BANK2)) - -#define IS_FMC_COLUMNBITS_NUMBER(COLUMN) (((COLUMN) == FMC_SDRAM_COLUMN_BITS_NUM_8) || \ - ((COLUMN) == FMC_SDRAM_COLUMN_BITS_NUM_9) || \ - ((COLUMN) == FMC_SDRAM_COLUMN_BITS_NUM_10) || \ - ((COLUMN) == FMC_SDRAM_COLUMN_BITS_NUM_11)) - -#define IS_FMC_ROWBITS_NUMBER(ROW) (((ROW) == FMC_SDRAM_ROW_BITS_NUM_11) || \ - ((ROW) == FMC_SDRAM_ROW_BITS_NUM_12) || \ - ((ROW) == FMC_SDRAM_ROW_BITS_NUM_13)) - -#define IS_FMC_SDMEMORY_WIDTH(WIDTH) (((WIDTH) == FMC_SDRAM_MEM_BUS_WIDTH_8) || \ - ((WIDTH) == FMC_SDRAM_MEM_BUS_WIDTH_16) || \ - ((WIDTH) == FMC_SDRAM_MEM_BUS_WIDTH_32)) - -#define IS_FMC_INTERNALBANK_NUMBER(NUMBER) (((NUMBER) == FMC_SDRAM_INTERN_BANKS_NUM_2) || \ - ((NUMBER) == FMC_SDRAM_INTERN_BANKS_NUM_4)) - - -#define IS_FMC_CAS_LATENCY(LATENCY) (((LATENCY) == FMC_SDRAM_CAS_LATENCY_1) || \ - ((LATENCY) == FMC_SDRAM_CAS_LATENCY_2) || \ - ((LATENCY) == FMC_SDRAM_CAS_LATENCY_3)) - -#define IS_FMC_SDCLOCK_PERIOD(PERIOD) (((PERIOD) == FMC_SDRAM_CLOCK_DISABLE) || \ - ((PERIOD) == FMC_SDRAM_CLOCK_PERIOD_2) || \ - ((PERIOD) == FMC_SDRAM_CLOCK_PERIOD_3)) - -#define IS_FMC_READ_BURST(RBURST) (((RBURST) == FMC_SDRAM_RBURST_DISABLE) || \ - ((RBURST) == FMC_SDRAM_RBURST_ENABLE)) - - -#define IS_FMC_READPIPE_DELAY(DELAY) (((DELAY) == FMC_SDRAM_RPIPE_DELAY_0) || \ - ((DELAY) == FMC_SDRAM_RPIPE_DELAY_1) || \ - ((DELAY) == FMC_SDRAM_RPIPE_DELAY_2)) - -#define IS_FMC_LOADTOACTIVE_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_EXITSELFREFRESH_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_SELFREFRESH_TIME(TIME) (((TIME) > 0U) && ((TIME) <= 16U)) - -#define IS_FMC_ROWCYCLE_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_WRITE_RECOVERY_TIME(TIME) (((TIME) > 0U) && ((TIME) <= 16U)) - -#define IS_FMC_RP_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_RCD_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_COMMAND_MODE(COMMAND) (((COMMAND) == FMC_SDRAM_CMD_NORMAL_MODE) || \ - ((COMMAND) == FMC_SDRAM_CMD_CLK_ENABLE) || \ - ((COMMAND) == FMC_SDRAM_CMD_PALL) || \ - ((COMMAND) == FMC_SDRAM_CMD_AUTOREFRESH_MODE) || \ - ((COMMAND) == FMC_SDRAM_CMD_LOAD_MODE) || \ - ((COMMAND) == FMC_SDRAM_CMD_SELFREFRESH_MODE) || \ - ((COMMAND) == FMC_SDRAM_CMD_POWERDOWN_MODE)) - -#define IS_FMC_COMMAND_TARGET(TARGET) (((TARGET) == FMC_SDRAM_CMD_TARGET_BANK1) || \ - ((TARGET) == FMC_SDRAM_CMD_TARGET_BANK2) || \ - ((TARGET) == FMC_SDRAM_CMD_TARGET_BANK1_2)) - -#define IS_FMC_AUTOREFRESH_NUMBER(NUMBER) (((NUMBER) > 0U) && ((NUMBER) <= 16U)) - -#define IS_FMC_MODE_REGISTER(CONTENT) ((CONTENT) <= 8191U) - -#define IS_FMC_REFRESH_RATE(RATE) ((RATE) <= 8191U) - -#define IS_FMC_SDRAM_DEVICE(INSTANCE) ((INSTANCE) == FMC_SDRAM_DEVICE) - -#define IS_FMC_WRITE_PROTECTION(WRITE) (((WRITE) == FMC_SDRAM_WRITE_PROTECTION_DISABLE) || \ - ((WRITE) == FMC_SDRAM_WRITE_PROTECTION_ENABLE)) - -#define IS_FMC_PAGESIZE(SIZE) (((SIZE) == FMC_PAGE_SIZE_NONE) || \ - ((SIZE) == FMC_PAGE_SIZE_128) || \ - ((SIZE) == FMC_PAGE_SIZE_256) || \ - ((SIZE) == FMC_PAGE_SIZE_512) || \ - ((SIZE) == FMC_PAGE_SIZE_1024)) - -#if defined (STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_FMC_WRITE_FIFO(FIFO) (((FIFO) == FMC_WRITE_FIFO_DISABLE) || \ - ((FIFO) == FMC_WRITE_FIFO_ENABLE)) -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FMC_LL_Private_Functions FMC LL Private Functions - * @{ - */ - -/** @defgroup FMC_LL_NORSRAM NOR SRAM - * @{ - */ -/** @defgroup FMC_LL_NORSRAM_Private_Functions_Group1 NOR SRAM Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FMC_NORSRAM_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_InitTypeDef *Init); -HAL_StatusTypeDef FMC_NORSRAM_Timing_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FMC_NORSRAM_Extended_Timing_Init(FMC_NORSRAM_EXTENDED_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode); -HAL_StatusTypeDef FMC_NORSRAM_DeInit(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FMC_LL_NORSRAM_Private_Functions_Group2 NOR SRAM Control functions - * @{ - */ -HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Enable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Disable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank); -/** - * @} - */ -/** - * @} - */ - -/** @defgroup FMC_LL_NAND NAND - * @{ - */ -/** @defgroup FMC_LL_NAND_Private_Functions_Group1 NAND Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FMC_NAND_Init(FMC_NAND_TypeDef *Device, FMC_NAND_InitTypeDef *Init); -HAL_StatusTypeDef FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FMC_NAND_DeInit(FMC_NAND_TypeDef *Device, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FMC_LL_NAND_Private_Functions_Group2 NAND Control functions - * @{ - */ -HAL_StatusTypeDef FMC_NAND_ECC_Enable(FMC_NAND_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_NAND_ECC_Disable(FMC_NAND_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_NAND_GetECC(FMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout); - -/** - * @} - */ -/** - * @} - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @defgroup FMC_LL_PCCARD PCCARD - * @{ - */ -/** @defgroup FMC_LL_PCCARD_Private_Functions_Group1 PCCARD Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FMC_PCCARD_Init(FMC_PCCARD_TypeDef *Device, FMC_PCCARD_InitTypeDef *Init); -HAL_StatusTypeDef FMC_PCCARD_CommonSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FMC_PCCARD_AttributeSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FMC_PCCARD_IOSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FMC_PCCARD_DeInit(FMC_PCCARD_TypeDef *Device); -/** - * @} - */ -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -/** @defgroup FMC_LL_SDRAM SDRAM - * @{ - */ -/** @defgroup FMC_LL_SDRAM_Private_Functions_Group1 SDRAM Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FMC_SDRAM_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_InitTypeDef *Init); -HAL_StatusTypeDef FMC_SDRAM_Timing_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FMC_SDRAM_DeInit(FMC_SDRAM_TypeDef *Device, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FMC_LL_SDRAM_Private_Functions_Group2 SDRAM Control functions - * @{ - */ -HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Enable(FMC_SDRAM_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Disable(FMC_SDRAM_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_SDRAM_SendCommand(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout); -HAL_StatusTypeDef FMC_SDRAM_ProgramRefreshRate(FMC_SDRAM_TypeDef *Device, uint32_t RefreshRate); -HAL_StatusTypeDef FMC_SDRAM_SetAutoRefreshNumber(FMC_SDRAM_TypeDef *Device, uint32_t AutoRefreshNumber); -uint32_t FMC_SDRAM_GetModeStatus(FMC_SDRAM_TypeDef *Device, uint32_t Bank); -/** - * @} - */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_FMC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmpi2c.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmpi2c.h deleted file mode 100644 index dd08b77c36e3a16..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmpi2c.h +++ /dev/null @@ -1,2237 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fmpi2c.h - * @author MCD Application Team - * @brief Header file of FMPI2C LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_FMPI2C_H -#define STM32F4xx_LL_FMPI2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (FMPI2C1) - -/** @defgroup FMPI2C_LL FMPI2C - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPI2C_LL_Private_Constants FMPI2C Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup FMPI2C_LL_Private_Macros FMPI2C Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup FMPI2C_LL_ES_INIT FMPI2C Exported Init structure - * @{ - */ -typedef struct -{ - uint32_t PeripheralMode; /*!< Specifies the peripheral mode. - This parameter can be a value of @ref FMPI2C_LL_EC_PERIPHERAL_MODE. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetMode(). */ - - uint32_t Timing; /*!< Specifies the SDA setup, hold time and the SCL high, low period values. - This parameter must be set by referring to the STM32CubeMX Tool and - the helper macro @ref __LL_FMPI2C_CONVERT_TIMINGS(). - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetTiming(). */ - - uint32_t AnalogFilter; /*!< Enables or disables analog noise filter. - This parameter can be a value of @ref FMPI2C_LL_EC_ANALOGFILTER_SELECTION. - - This feature can be modified afterwards using unitary functions - @ref LL_FMPI2C_EnableAnalogFilter() or LL_FMPI2C_DisableAnalogFilter(). */ - - uint32_t DigitalFilter; /*!< Configures the digital noise filter. - This parameter can be a number between Min_Data = 0x00 and Max_Data = 0x0F. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetDigitalFilter(). */ - - uint32_t OwnAddress1; /*!< Specifies the device own address 1. - This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetOwnAddress1(). */ - - uint32_t TypeAcknowledge; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive - match code or next received byte. - This parameter can be a value of @ref FMPI2C_LL_EC_I2C_ACKNOWLEDGE. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_AcknowledgeNextData(). */ - - uint32_t OwnAddrSize; /*!< Specifies the device own address 1 size (7-bit or 10-bit). - This parameter can be a value of @ref FMPI2C_LL_EC_OWNADDRESS1. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetOwnAddress1(). */ -} LL_FMPI2C_InitTypeDef; -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FMPI2C_LL_Exported_Constants FMPI2C Exported Constants - * @{ - */ - -/** @defgroup FMPI2C_LL_EC_CLEAR_FLAG Clear Flags Defines - * @brief Flags defines which can be used with LL_FMPI2C_WriteReg function - * @{ - */ -#define LL_FMPI2C_ICR_ADDRCF FMPI2C_ICR_ADDRCF /*!< Address Matched flag */ -#define LL_FMPI2C_ICR_NACKCF FMPI2C_ICR_NACKCF /*!< Not Acknowledge flag */ -#define LL_FMPI2C_ICR_STOPCF FMPI2C_ICR_STOPCF /*!< Stop detection flag */ -#define LL_FMPI2C_ICR_BERRCF FMPI2C_ICR_BERRCF /*!< Bus error flag */ -#define LL_FMPI2C_ICR_ARLOCF FMPI2C_ICR_ARLOCF /*!< Arbitration Lost flag */ -#define LL_FMPI2C_ICR_OVRCF FMPI2C_ICR_OVRCF /*!< Overrun/Underrun flag */ -#define LL_FMPI2C_ICR_PECCF FMPI2C_ICR_PECCF /*!< PEC error flag */ -#define LL_FMPI2C_ICR_TIMOUTCF FMPI2C_ICR_TIMOUTCF /*!< Timeout detection flag */ -#define LL_FMPI2C_ICR_ALERTCF FMPI2C_ICR_ALERTCF /*!< Alert flag */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_FMPI2C_ReadReg function - * @{ - */ -#define LL_FMPI2C_ISR_TXE FMPI2C_ISR_TXE /*!< Transmit data register empty */ -#define LL_FMPI2C_ISR_TXIS FMPI2C_ISR_TXIS /*!< Transmit interrupt status */ -#define LL_FMPI2C_ISR_RXNE FMPI2C_ISR_RXNE /*!< Receive data register not empty */ -#define LL_FMPI2C_ISR_ADDR FMPI2C_ISR_ADDR /*!< Address matched (slave mode) */ -#define LL_FMPI2C_ISR_NACKF FMPI2C_ISR_NACKF /*!< Not Acknowledge received flag */ -#define LL_FMPI2C_ISR_STOPF FMPI2C_ISR_STOPF /*!< Stop detection flag */ -#define LL_FMPI2C_ISR_TC FMPI2C_ISR_TC /*!< Transfer Complete (master mode) */ -#define LL_FMPI2C_ISR_TCR FMPI2C_ISR_TCR /*!< Transfer Complete Reload */ -#define LL_FMPI2C_ISR_BERR FMPI2C_ISR_BERR /*!< Bus error */ -#define LL_FMPI2C_ISR_ARLO FMPI2C_ISR_ARLO /*!< Arbitration lost */ -#define LL_FMPI2C_ISR_OVR FMPI2C_ISR_OVR /*!< Overrun/Underrun (slave mode) */ -#define LL_FMPI2C_ISR_PECERR FMPI2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */ -#define LL_FMPI2C_ISR_TIMEOUT FMPI2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */ -#define LL_FMPI2C_ISR_ALERT FMPI2C_ISR_ALERT /*!< SMBus alert (SMBus mode) */ -#define LL_FMPI2C_ISR_BUSY FMPI2C_ISR_BUSY /*!< Bus busy */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_FMPI2C_ReadReg and LL_FMPI2C_WriteReg functions - * @{ - */ -#define LL_FMPI2C_CR1_TXIE FMPI2C_CR1_TXIE /*!< TX Interrupt enable */ -#define LL_FMPI2C_CR1_RXIE FMPI2C_CR1_RXIE /*!< RX Interrupt enable */ -#define LL_FMPI2C_CR1_ADDRIE FMPI2C_CR1_ADDRIE /*!< Address match Interrupt enable (slave only) */ -#define LL_FMPI2C_CR1_NACKIE FMPI2C_CR1_NACKIE /*!< Not acknowledge received Interrupt enable */ -#define LL_FMPI2C_CR1_STOPIE FMPI2C_CR1_STOPIE /*!< STOP detection Interrupt enable */ -#define LL_FMPI2C_CR1_TCIE FMPI2C_CR1_TCIE /*!< Transfer Complete interrupt enable */ -#define LL_FMPI2C_CR1_ERRIE FMPI2C_CR1_ERRIE /*!< Error interrupts enable */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_PERIPHERAL_MODE Peripheral Mode - * @{ - */ -#define LL_FMPI2C_MODE_I2C 0x00000000U /*!< FMPI2C Master or Slave mode */ -#define LL_FMPI2C_MODE_SMBUS_HOST FMPI2C_CR1_SMBHEN /*!< SMBus Host address acknowledge */ -#define LL_FMPI2C_MODE_SMBUS_DEVICE 0x00000000U /*!< SMBus Device default mode - (Default address not acknowledge) */ -#define LL_FMPI2C_MODE_SMBUS_DEVICE_ARP FMPI2C_CR1_SMBDEN /*!< SMBus Device Default address acknowledge */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_ANALOGFILTER_SELECTION Analog Filter Selection - * @{ - */ -#define LL_FMPI2C_ANALOGFILTER_ENABLE 0x00000000U /*!< Analog filter is enabled. */ -#define LL_FMPI2C_ANALOGFILTER_DISABLE FMPI2C_CR1_ANFOFF /*!< Analog filter is disabled. */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_ADDRESSING_MODE Master Addressing Mode - * @{ - */ -#define LL_FMPI2C_ADDRESSING_MODE_7BIT 0x00000000U /*!< Master operates in 7-bit addressing mode. */ -#define LL_FMPI2C_ADDRESSING_MODE_10BIT FMPI2C_CR2_ADD10 /*!< Master operates in 10-bit addressing mode.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_OWNADDRESS1 Own Address 1 Length - * @{ - */ -#define LL_FMPI2C_OWNADDRESS1_7BIT 0x00000000U /*!< Own address 1 is a 7-bit address. */ -#define LL_FMPI2C_OWNADDRESS1_10BIT FMPI2C_OAR1_OA1MODE /*!< Own address 1 is a 10-bit address.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_OWNADDRESS2 Own Address 2 Masks - * @{ - */ -#define LL_FMPI2C_OWNADDRESS2_NOMASK FMPI2C_OAR2_OA2NOMASK /*!< Own Address2 No mask. */ -#define LL_FMPI2C_OWNADDRESS2_MASK01 FMPI2C_OAR2_OA2MASK01 /*!< Only Address2 bits[7:2] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK02 FMPI2C_OAR2_OA2MASK02 /*!< Only Address2 bits[7:3] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK03 FMPI2C_OAR2_OA2MASK03 /*!< Only Address2 bits[7:4] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK04 FMPI2C_OAR2_OA2MASK04 /*!< Only Address2 bits[7:5] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK05 FMPI2C_OAR2_OA2MASK05 /*!< Only Address2 bits[7:6] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK06 FMPI2C_OAR2_OA2MASK06 /*!< Only Address2 bits[7] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK07 FMPI2C_OAR2_OA2MASK07 /*!< No comparison is done. - All Address2 are acknowledged. */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation - * @{ - */ -#define LL_FMPI2C_ACK 0x00000000U /*!< ACK is sent after current received byte. */ -#define LL_FMPI2C_NACK FMPI2C_CR2_NACK /*!< NACK is sent after current received byte.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_ADDRSLAVE Slave Address Length - * @{ - */ -#define LL_FMPI2C_ADDRSLAVE_7BIT 0x00000000U /*!< Slave Address in 7-bit. */ -#define LL_FMPI2C_ADDRSLAVE_10BIT FMPI2C_CR2_ADD10 /*!< Slave Address in 10-bit.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_REQUEST Transfer Request Direction - * @{ - */ -#define LL_FMPI2C_REQUEST_WRITE 0x00000000U /*!< Master request a write transfer. */ -#define LL_FMPI2C_REQUEST_READ FMPI2C_CR2_RD_WRN /*!< Master request a read transfer. */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_MODE Transfer End Mode - * @{ - */ -#define LL_FMPI2C_MODE_RELOAD FMPI2C_CR2_RELOAD /*!< Enable FMPI2C Reload mode. */ -#define LL_FMPI2C_MODE_AUTOEND FMPI2C_CR2_AUTOEND /*!< Enable FMPI2C Automatic end mode - with no HW PEC comparison. */ -#define LL_FMPI2C_MODE_SOFTEND 0x00000000U /*!< Enable FMPI2C Software end mode - with no HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_RELOAD LL_FMPI2C_MODE_RELOAD /*!< Enable FMPSMBUS Automatic end mode - with HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_AUTOEND_NO_PEC LL_FMPI2C_MODE_AUTOEND /*!< Enable FMPSMBUS Automatic end mode - with HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_SOFTEND_NO_PEC LL_FMPI2C_MODE_SOFTEND /*!< Enable FMPSMBUS Software end mode - with HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_AUTOEND_WITH_PEC (uint32_t)(LL_FMPI2C_MODE_AUTOEND | FMPI2C_CR2_PECBYTE) -/*!< Enable FMPSMBUS Automatic end mode with HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_SOFTEND_WITH_PEC (uint32_t)(LL_FMPI2C_MODE_SOFTEND | FMPI2C_CR2_PECBYTE) -/*!< Enable FMPSMBUS Software end mode with HW PEC comparison. */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_GENERATE Start And Stop Generation - * @{ - */ -#define LL_FMPI2C_GENERATE_NOSTARTSTOP 0x00000000U -/*!< Don't Generate Stop and Start condition. */ -#define LL_FMPI2C_GENERATE_STOP (uint32_t)(0x80000000U | FMPI2C_CR2_STOP) -/*!< Generate Stop condition (Size should be set to 0). */ -#define LL_FMPI2C_GENERATE_START_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | FMPI2C_CR2_RD_WRN) -/*!< Generate Start for read request. */ -#define LL_FMPI2C_GENERATE_START_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/*!< Generate Start for write request. */ -#define LL_FMPI2C_GENERATE_RESTART_7BIT_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | FMPI2C_CR2_RD_WRN) -/*!< Generate Restart for read request, slave 7Bit address. */ -#define LL_FMPI2C_GENERATE_RESTART_7BIT_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/*!< Generate Restart for write request, slave 7Bit address. */ -#define LL_FMPI2C_GENERATE_RESTART_10BIT_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | \ - FMPI2C_CR2_RD_WRN | FMPI2C_CR2_HEAD10R) -/*!< Generate Restart for read request, slave 10Bit address. */ -#define LL_FMPI2C_GENERATE_RESTART_10BIT_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/*!< Generate Restart for write request, slave 10Bit address.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_DIRECTION Read Write Direction - * @{ - */ -#define LL_FMPI2C_DIRECTION_WRITE 0x00000000U /*!< Write transfer request by master, - slave enters receiver mode. */ -#define LL_FMPI2C_DIRECTION_READ FMPI2C_ISR_DIR /*!< Read transfer request by master, - slave enters transmitter mode.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_DMA_REG_DATA DMA Register Data - * @{ - */ -#define LL_FMPI2C_DMA_REG_DATA_TRANSMIT 0x00000000U /*!< Get address of data register used for - transmission */ -#define LL_FMPI2C_DMA_REG_DATA_RECEIVE 0x00000001U /*!< Get address of data register used for - reception */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_SMBUS_TIMEOUTA_MODE SMBus TimeoutA Mode SCL SDA Timeout - * @{ - */ -#define LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SCL_LOW 0x00000000U /*!< TimeoutA is used to detect - SCL low level timeout. */ -#define LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH FMPI2C_TIMEOUTR_TIDLE /*!< TimeoutA is used to detect - both SCL and SDA high level timeout.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_SMBUS_TIMEOUT_SELECTION SMBus Timeout Selection - * @{ - */ -#define LL_FMPI2C_FMPSMBUS_TIMEOUTA FMPI2C_TIMEOUTR_TIMOUTEN /*!< TimeoutA enable bit */ -#define LL_FMPI2C_FMPSMBUS_TIMEOUTB FMPI2C_TIMEOUTR_TEXTEN /*!< TimeoutB (extended clock) - enable bit */ -#define LL_FMPI2C_FMPSMBUS_ALL_TIMEOUT (uint32_t)(FMPI2C_TIMEOUTR_TIMOUTEN | \ - FMPI2C_TIMEOUTR_TEXTEN) /*!< TimeoutA and TimeoutB -(extended clock) enable bits */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FMPI2C_LL_Exported_Macros FMPI2C Exported Macros - * @{ - */ - -/** @defgroup FMPI2C_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in FMPI2C register - * @param __INSTANCE__ FMPI2C Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_FMPI2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in FMPI2C register - * @param __INSTANCE__ FMPI2C Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_FMPI2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EM_CONVERT_TIMINGS Convert SDA SCL timings - * @{ - */ -/** - * @brief Configure the SDA setup, hold time and the SCL high, low period. - * @param __PRESCALER__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. - * @param __SETUP_TIME__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. - (tscldel = (SCLDEL+1)xtpresc) - * @param __HOLD_TIME__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. - (tsdadel = SDADELxtpresc) - * @param __SCLH_PERIOD__ This parameter must be a value between Min_Data=0 and Max_Data=0xFF. - (tsclh = (SCLH+1)xtpresc) - * @param __SCLL_PERIOD__ This parameter must be a value between Min_Data=0 and Max_Data=0xFF. - (tscll = (SCLL+1)xtpresc) - * @retval Value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -#define __LL_FMPI2C_CONVERT_TIMINGS(__PRESCALER__, __SETUP_TIME__, __HOLD_TIME__, __SCLH_PERIOD__, __SCLL_PERIOD__) \ - ((((uint32_t)(__PRESCALER__) << FMPI2C_TIMINGR_PRESC_Pos) & FMPI2C_TIMINGR_PRESC) | \ - (((uint32_t)(__SETUP_TIME__) << FMPI2C_TIMINGR_SCLDEL_Pos) & FMPI2C_TIMINGR_SCLDEL) | \ - (((uint32_t)(__HOLD_TIME__) << FMPI2C_TIMINGR_SDADEL_Pos) & FMPI2C_TIMINGR_SDADEL) | \ - (((uint32_t)(__SCLH_PERIOD__) << FMPI2C_TIMINGR_SCLH_Pos) & FMPI2C_TIMINGR_SCLH) | \ - (((uint32_t)(__SCLL_PERIOD__) << FMPI2C_TIMINGR_SCLL_Pos) & FMPI2C_TIMINGR_SCLL)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup FMPI2C_LL_Exported_Functions FMPI2C Exported Functions - * @{ - */ - -/** @defgroup FMPI2C_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Enable FMPI2C peripheral (PE = 1). - * @rmtoll CR1 PE LL_FMPI2C_Enable - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_Enable(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PE); -} - -/** - * @brief Disable FMPI2C peripheral (PE = 0). - * @note When PE = 0, the FMPI2C SCL and SDA lines are released. - * Internal state machines and status bits are put back to their reset value. - * When cleared, PE must be kept low for at least 3 APB clock cycles. - * @rmtoll CR1 PE LL_FMPI2C_Disable - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_Disable(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PE); -} - -/** - * @brief Check if the FMPI2C peripheral is enabled or disabled. - * @rmtoll CR1 PE LL_FMPI2C_IsEnabled - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabled(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PE) == (FMPI2C_CR1_PE)) ? 1UL : 0UL); -} - -/** - * @brief Configure Noise Filters (Analog and Digital). - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * The filters can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 ANFOFF LL_FMPI2C_ConfigFilters\n - * CR1 DNF LL_FMPI2C_ConfigFilters - * @param FMPI2Cx FMPI2C Instance. - * @param AnalogFilter This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_ANALOGFILTER_ENABLE - * @arg @ref LL_FMPI2C_ANALOGFILTER_DISABLE - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) - and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*tfmpi2cclk). - * This parameter is used to configure the digital noise filter on SDA and SCL input. - * The digital filter will filter spikes with a length of up to DNF[3:0]*tfmpi2cclk. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ConfigFilters(FMPI2C_TypeDef *FMPI2Cx, uint32_t AnalogFilter, uint32_t DigitalFilter) -{ - MODIFY_REG(FMPI2Cx->CR1, FMPI2C_CR1_ANFOFF | FMPI2C_CR1_DNF, AnalogFilter | (DigitalFilter << FMPI2C_CR1_DNF_Pos)); -} - -/** - * @brief Configure Digital Noise Filter. - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * This filter can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 DNF LL_FMPI2C_SetDigitalFilter - * @param FMPI2Cx FMPI2C Instance. - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) - and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*tfmpi2cclk). - * This parameter is used to configure the digital noise filter on SDA and SCL input. - * The digital filter will filter spikes with a length of up to DNF[3:0]*tfmpi2cclk. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetDigitalFilter(FMPI2C_TypeDef *FMPI2Cx, uint32_t DigitalFilter) -{ - MODIFY_REG(FMPI2Cx->CR1, FMPI2C_CR1_DNF, DigitalFilter << FMPI2C_CR1_DNF_Pos); -} - -/** - * @brief Get the current Digital Noise Filter configuration. - * @rmtoll CR1 DNF LL_FMPI2C_GetDigitalFilter - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetDigitalFilter(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_DNF) >> FMPI2C_CR1_DNF_Pos); -} - -/** - * @brief Enable Analog Noise Filter. - * @note This filter can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 ANFOFF LL_FMPI2C_EnableAnalogFilter - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableAnalogFilter(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ANFOFF); -} - -/** - * @brief Disable Analog Noise Filter. - * @note This filter can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 ANFOFF LL_FMPI2C_DisableAnalogFilter - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableAnalogFilter(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ANFOFF); -} - -/** - * @brief Check if Analog Noise Filter is enabled or disabled. - * @rmtoll CR1 ANFOFF LL_FMPI2C_IsEnabledAnalogFilter - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledAnalogFilter(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ANFOFF) != (FMPI2C_CR1_ANFOFF)) ? 1UL : 0UL); -} - -/** - * @brief Enable DMA transmission requests. - * @rmtoll CR1 TXDMAEN LL_FMPI2C_EnableDMAReq_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableDMAReq_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXDMAEN); -} - -/** - * @brief Disable DMA transmission requests. - * @rmtoll CR1 TXDMAEN LL_FMPI2C_DisableDMAReq_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableDMAReq_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXDMAEN); -} - -/** - * @brief Check if DMA transmission requests are enabled or disabled. - * @rmtoll CR1 TXDMAEN LL_FMPI2C_IsEnabledDMAReq_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledDMAReq_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXDMAEN) == (FMPI2C_CR1_TXDMAEN)) ? 1UL : 0UL); -} - -/** - * @brief Enable DMA reception requests. - * @rmtoll CR1 RXDMAEN LL_FMPI2C_EnableDMAReq_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableDMAReq_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXDMAEN); -} - -/** - * @brief Disable DMA reception requests. - * @rmtoll CR1 RXDMAEN LL_FMPI2C_DisableDMAReq_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableDMAReq_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXDMAEN); -} - -/** - * @brief Check if DMA reception requests are enabled or disabled. - * @rmtoll CR1 RXDMAEN LL_FMPI2C_IsEnabledDMAReq_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledDMAReq_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXDMAEN) == (FMPI2C_CR1_RXDMAEN)) ? 1UL : 0UL); -} - -/** - * @brief Get the data register address used for DMA transfer - * @rmtoll TXDR TXDATA LL_FMPI2C_DMA_GetRegAddr\n - * RXDR RXDATA LL_FMPI2C_DMA_GetRegAddr - * @param FMPI2Cx FMPI2C Instance - * @param Direction This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_DMA_REG_DATA_TRANSMIT - * @arg @ref LL_FMPI2C_DMA_REG_DATA_RECEIVE - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_FMPI2C_DMA_GetRegAddr(FMPI2C_TypeDef *FMPI2Cx, uint32_t Direction) -{ - uint32_t data_reg_addr; - - if (Direction == LL_FMPI2C_DMA_REG_DATA_TRANSMIT) - { - /* return address of TXDR register */ - data_reg_addr = (uint32_t) &(FMPI2Cx->TXDR); - } - else - { - /* return address of RXDR register */ - data_reg_addr = (uint32_t) &(FMPI2Cx->RXDR); - } - - return data_reg_addr; -} - -/** - * @brief Enable Clock stretching. - * @note This bit can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_FMPI2C_EnableClockStretching - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableClockStretching(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NOSTRETCH); -} - -/** - * @brief Disable Clock stretching. - * @note This bit can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_FMPI2C_DisableClockStretching - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableClockStretching(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NOSTRETCH); -} - -/** - * @brief Check if Clock stretching is enabled or disabled. - * @rmtoll CR1 NOSTRETCH LL_FMPI2C_IsEnabledClockStretching - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledClockStretching(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NOSTRETCH) != (FMPI2C_CR1_NOSTRETCH)) ? 1UL : 0UL); -} - -/** - * @brief Enable hardware byte control in slave mode. - * @rmtoll CR1 SBC LL_FMPI2C_EnableSlaveByteControl - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSlaveByteControl(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_SBC); -} - -/** - * @brief Disable hardware byte control in slave mode. - * @rmtoll CR1 SBC LL_FMPI2C_DisableSlaveByteControl - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableSlaveByteControl(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_SBC); -} - -/** - * @brief Check if hardware byte control in slave mode is enabled or disabled. - * @rmtoll CR1 SBC LL_FMPI2C_IsEnabledSlaveByteControl - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSlaveByteControl(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_SBC) == (FMPI2C_CR1_SBC)) ? 1UL : 0UL); -} - -/** - * @brief Enable General Call. - * @note When enabled the Address 0x00 is ACKed. - * @rmtoll CR1 GCEN LL_FMPI2C_EnableGeneralCall - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableGeneralCall(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_GCEN); -} - -/** - * @brief Disable General Call. - * @note When disabled the Address 0x00 is NACKed. - * @rmtoll CR1 GCEN LL_FMPI2C_DisableGeneralCall - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableGeneralCall(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_GCEN); -} - -/** - * @brief Check if General Call is enabled or disabled. - * @rmtoll CR1 GCEN LL_FMPI2C_IsEnabledGeneralCall - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledGeneralCall(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_GCEN) == (FMPI2C_CR1_GCEN)) ? 1UL : 0UL); -} - -/** - * @brief Configure the Master to operate in 7-bit or 10-bit addressing mode. - * @note Changing this bit is not allowed, when the START bit is set. - * @rmtoll CR2 ADD10 LL_FMPI2C_SetMasterAddressingMode - * @param FMPI2Cx FMPI2C Instance. - * @param AddressingMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_ADDRESSING_MODE_7BIT - * @arg @ref LL_FMPI2C_ADDRESSING_MODE_10BIT - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetMasterAddressingMode(FMPI2C_TypeDef *FMPI2Cx, uint32_t AddressingMode) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_ADD10, AddressingMode); -} - -/** - * @brief Get the Master addressing mode. - * @rmtoll CR2 ADD10 LL_FMPI2C_GetMasterAddressingMode - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_ADDRESSING_MODE_7BIT - * @arg @ref LL_FMPI2C_ADDRESSING_MODE_10BIT - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetMasterAddressingMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_ADD10)); -} - -/** - * @brief Set the Own Address1. - * @rmtoll OAR1 OA1 LL_FMPI2C_SetOwnAddress1\n - * OAR1 OA1MODE LL_FMPI2C_SetOwnAddress1 - * @param FMPI2Cx FMPI2C Instance. - * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF. - * @param OwnAddrSize This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_OWNADDRESS1_7BIT - * @arg @ref LL_FMPI2C_OWNADDRESS1_10BIT - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetOwnAddress1(FMPI2C_TypeDef *FMPI2Cx, uint32_t OwnAddress1, uint32_t OwnAddrSize) -{ - MODIFY_REG(FMPI2Cx->OAR1, FMPI2C_OAR1_OA1 | FMPI2C_OAR1_OA1MODE, OwnAddress1 | OwnAddrSize); -} - -/** - * @brief Enable acknowledge on Own Address1 match address. - * @rmtoll OAR1 OA1EN LL_FMPI2C_EnableOwnAddress1 - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableOwnAddress1(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->OAR1, FMPI2C_OAR1_OA1EN); -} - -/** - * @brief Disable acknowledge on Own Address1 match address. - * @rmtoll OAR1 OA1EN LL_FMPI2C_DisableOwnAddress1 - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableOwnAddress1(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->OAR1, FMPI2C_OAR1_OA1EN); -} - -/** - * @brief Check if Own Address1 acknowledge is enabled or disabled. - * @rmtoll OAR1 OA1EN LL_FMPI2C_IsEnabledOwnAddress1 - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledOwnAddress1(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->OAR1, FMPI2C_OAR1_OA1EN) == (FMPI2C_OAR1_OA1EN)) ? 1UL : 0UL); -} - -/** - * @brief Set the 7bits Own Address2. - * @note This action has no effect if own address2 is enabled. - * @rmtoll OAR2 OA2 LL_FMPI2C_SetOwnAddress2\n - * OAR2 OA2MSK LL_FMPI2C_SetOwnAddress2 - * @param FMPI2Cx FMPI2C Instance. - * @param OwnAddress2 Value between Min_Data=0 and Max_Data=0x7F. - * @param OwnAddrMask This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_OWNADDRESS2_NOMASK - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK01 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK02 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK03 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK04 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK05 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK06 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK07 - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetOwnAddress2(FMPI2C_TypeDef *FMPI2Cx, uint32_t OwnAddress2, uint32_t OwnAddrMask) -{ - MODIFY_REG(FMPI2Cx->OAR2, FMPI2C_OAR2_OA2 | FMPI2C_OAR2_OA2MSK, OwnAddress2 | OwnAddrMask); -} - -/** - * @brief Enable acknowledge on Own Address2 match address. - * @rmtoll OAR2 OA2EN LL_FMPI2C_EnableOwnAddress2 - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableOwnAddress2(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->OAR2, FMPI2C_OAR2_OA2EN); -} - -/** - * @brief Disable acknowledge on Own Address2 match address. - * @rmtoll OAR2 OA2EN LL_FMPI2C_DisableOwnAddress2 - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableOwnAddress2(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->OAR2, FMPI2C_OAR2_OA2EN); -} - -/** - * @brief Check if Own Address1 acknowledge is enabled or disabled. - * @rmtoll OAR2 OA2EN LL_FMPI2C_IsEnabledOwnAddress2 - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledOwnAddress2(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->OAR2, FMPI2C_OAR2_OA2EN) == (FMPI2C_OAR2_OA2EN)) ? 1UL : 0UL); -} - -/** - * @brief Configure the SDA setup, hold time and the SCL high, low period. - * @note This bit can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll TIMINGR TIMINGR LL_FMPI2C_SetTiming - * @param FMPI2Cx FMPI2C Instance. - * @param Timing This parameter must be a value between Min_Data=0 and Max_Data=0xFFFFFFFF. - * @note This parameter is computed with the STM32CubeMX Tool. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetTiming(FMPI2C_TypeDef *FMPI2Cx, uint32_t Timing) -{ - WRITE_REG(FMPI2Cx->TIMINGR, Timing); -} - -/** - * @brief Get the Timing Prescaler setting. - * @rmtoll TIMINGR PRESC LL_FMPI2C_GetTimingPrescaler - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetTimingPrescaler(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_PRESC) >> FMPI2C_TIMINGR_PRESC_Pos); -} - -/** - * @brief Get the SCL low period setting. - * @rmtoll TIMINGR SCLL LL_FMPI2C_GetClockLowPeriod - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetClockLowPeriod(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_SCLL) >> FMPI2C_TIMINGR_SCLL_Pos); -} - -/** - * @brief Get the SCL high period setting. - * @rmtoll TIMINGR SCLH LL_FMPI2C_GetClockHighPeriod - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetClockHighPeriod(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_SCLH) >> FMPI2C_TIMINGR_SCLH_Pos); -} - -/** - * @brief Get the SDA hold time. - * @rmtoll TIMINGR SDADEL LL_FMPI2C_GetDataHoldTime - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetDataHoldTime(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_SDADEL) >> FMPI2C_TIMINGR_SDADEL_Pos); -} - -/** - * @brief Get the SDA setup time. - * @rmtoll TIMINGR SCLDEL LL_FMPI2C_GetDataSetupTime - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetDataSetupTime(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_SCLDEL) >> FMPI2C_TIMINGR_SCLDEL_Pos); -} - -/** - * @brief Configure peripheral mode. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 SMBHEN LL_FMPI2C_SetMode\n - * CR1 SMBDEN LL_FMPI2C_SetMode - * @param FMPI2Cx FMPI2C Instance. - * @param PeripheralMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_MODE_I2C - * @arg @ref LL_FMPI2C_MODE_SMBUS_HOST - * @arg @ref LL_FMPI2C_MODE_SMBUS_DEVICE - * @arg @ref LL_FMPI2C_MODE_SMBUS_DEVICE_ARP - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetMode(FMPI2C_TypeDef *FMPI2Cx, uint32_t PeripheralMode) -{ - MODIFY_REG(FMPI2Cx->CR1, FMPI2C_CR1_SMBHEN | FMPI2C_CR1_SMBDEN, PeripheralMode); -} - -/** - * @brief Get peripheral mode. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 SMBHEN LL_FMPI2C_GetMode\n - * CR1 SMBDEN LL_FMPI2C_GetMode - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_MODE_I2C - * @arg @ref LL_FMPI2C_MODE_SMBUS_HOST - * @arg @ref LL_FMPI2C_MODE_SMBUS_DEVICE - * @arg @ref LL_FMPI2C_MODE_SMBUS_DEVICE_ARP - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_SMBHEN | FMPI2C_CR1_SMBDEN)); -} - -/** - * @brief Enable SMBus alert (Host or Device mode) - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is drived low and - * Alert Response Address Header acknowledge is enabled. - * SMBus Host mode: - * - SMBus Alert pin management is supported. - * @rmtoll CR1 ALERTEN LL_FMPI2C_EnableSMBusAlert - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSMBusAlert(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ALERTEN); -} - -/** - * @brief Disable SMBus alert (Host or Device mode) - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is not drived (can be used as a standard GPIO) and - * Alert Response Address Header acknowledge is disabled. - * SMBus Host mode: - * - SMBus Alert pin management is not supported. - * @rmtoll CR1 ALERTEN LL_FMPI2C_DisableSMBusAlert - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableSMBusAlert(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ALERTEN); -} - -/** - * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 ALERTEN LL_FMPI2C_IsEnabledSMBusAlert - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSMBusAlert(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ALERTEN) == (FMPI2C_CR1_ALERTEN)) ? 1UL : 0UL); -} - -/** - * @brief Enable SMBus Packet Error Calculation (PEC). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 PECEN LL_FMPI2C_EnableSMBusPEC - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSMBusPEC(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PECEN); -} - -/** - * @brief Disable SMBus Packet Error Calculation (PEC). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 PECEN LL_FMPI2C_DisableSMBusPEC - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableSMBusPEC(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PECEN); -} - -/** - * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 PECEN LL_FMPI2C_IsEnabledSMBusPEC - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSMBusPEC(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PECEN) == (FMPI2C_CR1_PECEN)) ? 1UL : 0UL); -} - -/** - * @brief Configure the SMBus Clock Timeout. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note This configuration can only be programmed when associated Timeout is disabled (TimeoutA and/orTimeoutB). - * @rmtoll TIMEOUTR TIMEOUTA LL_FMPI2C_ConfigSMBusTimeout\n - * TIMEOUTR TIDLE LL_FMPI2C_ConfigSMBusTimeout\n - * TIMEOUTR TIMEOUTB LL_FMPI2C_ConfigSMBusTimeout - * @param FMPI2Cx FMPI2C Instance. - * @param TimeoutA This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. - * @param TimeoutAMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SCL_LOW - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH - * @param TimeoutB - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ConfigSMBusTimeout(FMPI2C_TypeDef *FMPI2Cx, uint32_t TimeoutA, uint32_t TimeoutAMode, - uint32_t TimeoutB) -{ - MODIFY_REG(FMPI2Cx->TIMEOUTR, FMPI2C_TIMEOUTR_TIMEOUTA | FMPI2C_TIMEOUTR_TIDLE | FMPI2C_TIMEOUTR_TIMEOUTB, - TimeoutA | TimeoutAMode | (TimeoutB << FMPI2C_TIMEOUTR_TIMEOUTB_Pos)); -} - -/** - * @brief Configure the SMBus Clock TimeoutA (SCL low timeout or SCL and SDA high timeout depends on TimeoutA mode). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note These bits can only be programmed when TimeoutA is disabled. - * @rmtoll TIMEOUTR TIMEOUTA LL_FMPI2C_SetSMBusTimeoutA - * @param FMPI2Cx FMPI2C Instance. - * @param TimeoutA This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetSMBusTimeoutA(FMPI2C_TypeDef *FMPI2Cx, uint32_t TimeoutA) -{ - WRITE_REG(FMPI2Cx->TIMEOUTR, TimeoutA); -} - -/** - * @brief Get the SMBus Clock TimeoutA setting. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMEOUTA LL_FMPI2C_GetSMBusTimeoutA - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSMBusTimeoutA(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMEOUTR, FMPI2C_TIMEOUTR_TIMEOUTA)); -} - -/** - * @brief Set the SMBus Clock TimeoutA mode. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note This bit can only be programmed when TimeoutA is disabled. - * @rmtoll TIMEOUTR TIDLE LL_FMPI2C_SetSMBusTimeoutAMode - * @param FMPI2Cx FMPI2C Instance. - * @param TimeoutAMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SCL_LOW - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetSMBusTimeoutAMode(FMPI2C_TypeDef *FMPI2Cx, uint32_t TimeoutAMode) -{ - WRITE_REG(FMPI2Cx->TIMEOUTR, TimeoutAMode); -} - -/** - * @brief Get the SMBus Clock TimeoutA mode. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIDLE LL_FMPI2C_GetSMBusTimeoutAMode - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SCL_LOW - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSMBusTimeoutAMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMEOUTR, FMPI2C_TIMEOUTR_TIDLE)); -} - -/** - * @brief Configure the SMBus Extended Cumulative Clock TimeoutB (Master or Slave mode). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note These bits can only be programmed when TimeoutB is disabled. - * @rmtoll TIMEOUTR TIMEOUTB LL_FMPI2C_SetSMBusTimeoutB - * @param FMPI2Cx FMPI2C Instance. - * @param TimeoutB This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetSMBusTimeoutB(FMPI2C_TypeDef *FMPI2Cx, uint32_t TimeoutB) -{ - WRITE_REG(FMPI2Cx->TIMEOUTR, TimeoutB << FMPI2C_TIMEOUTR_TIMEOUTB_Pos); -} - -/** - * @brief Get the SMBus Extended Cumulative Clock TimeoutB setting. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMEOUTB LL_FMPI2C_GetSMBusTimeoutB - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSMBusTimeoutB(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMEOUTR, FMPI2C_TIMEOUTR_TIMEOUTB) >> FMPI2C_TIMEOUTR_TIMEOUTB_Pos); -} - -/** - * @brief Enable the SMBus Clock Timeout. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMOUTEN LL_FMPI2C_EnableSMBusTimeout\n - * TIMEOUTR TEXTEN LL_FMPI2C_EnableSMBusTimeout - * @param FMPI2Cx FMPI2C Instance. - * @param ClockTimeout This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTB - * @arg @ref LL_FMPI2C_FMPSMBUS_ALL_TIMEOUT - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSMBusTimeout(FMPI2C_TypeDef *FMPI2Cx, uint32_t ClockTimeout) -{ - SET_BIT(FMPI2Cx->TIMEOUTR, ClockTimeout); -} - -/** - * @brief Disable the SMBus Clock Timeout. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMOUTEN LL_FMPI2C_DisableSMBusTimeout\n - * TIMEOUTR TEXTEN LL_FMPI2C_DisableSMBusTimeout - * @param FMPI2Cx FMPI2C Instance. - * @param ClockTimeout This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTB - * @arg @ref LL_FMPI2C_FMPSMBUS_ALL_TIMEOUT - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableSMBusTimeout(FMPI2C_TypeDef *FMPI2Cx, uint32_t ClockTimeout) -{ - CLEAR_BIT(FMPI2Cx->TIMEOUTR, ClockTimeout); -} - -/** - * @brief Check if the SMBus Clock Timeout is enabled or disabled. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMOUTEN LL_FMPI2C_IsEnabledSMBusTimeout\n - * TIMEOUTR TEXTEN LL_FMPI2C_IsEnabledSMBusTimeout - * @param FMPI2Cx FMPI2C Instance. - * @param ClockTimeout This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTB - * @arg @ref LL_FMPI2C_FMPSMBUS_ALL_TIMEOUT - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSMBusTimeout(FMPI2C_TypeDef *FMPI2Cx, uint32_t ClockTimeout) -{ - return ((READ_BIT(FMPI2Cx->TIMEOUTR, (FMPI2C_TIMEOUTR_TIMOUTEN | FMPI2C_TIMEOUTR_TEXTEN)) == \ - (ClockTimeout)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable TXIS interrupt. - * @rmtoll CR1 TXIE LL_FMPI2C_EnableIT_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXIE); -} - -/** - * @brief Disable TXIS interrupt. - * @rmtoll CR1 TXIE LL_FMPI2C_DisableIT_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXIE); -} - -/** - * @brief Check if the TXIS Interrupt is enabled or disabled. - * @rmtoll CR1 TXIE LL_FMPI2C_IsEnabledIT_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXIE) == (FMPI2C_CR1_TXIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable RXNE interrupt. - * @rmtoll CR1 RXIE LL_FMPI2C_EnableIT_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXIE); -} - -/** - * @brief Disable RXNE interrupt. - * @rmtoll CR1 RXIE LL_FMPI2C_DisableIT_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXIE); -} - -/** - * @brief Check if the RXNE Interrupt is enabled or disabled. - * @rmtoll CR1 RXIE LL_FMPI2C_IsEnabledIT_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXIE) == (FMPI2C_CR1_RXIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable Address match interrupt (slave mode only). - * @rmtoll CR1 ADDRIE LL_FMPI2C_EnableIT_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ADDRIE); -} - -/** - * @brief Disable Address match interrupt (slave mode only). - * @rmtoll CR1 ADDRIE LL_FMPI2C_DisableIT_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ADDRIE); -} - -/** - * @brief Check if Address match interrupt is enabled or disabled. - * @rmtoll CR1 ADDRIE LL_FMPI2C_IsEnabledIT_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ADDRIE) == (FMPI2C_CR1_ADDRIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable Not acknowledge received interrupt. - * @rmtoll CR1 NACKIE LL_FMPI2C_EnableIT_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NACKIE); -} - -/** - * @brief Disable Not acknowledge received interrupt. - * @rmtoll CR1 NACKIE LL_FMPI2C_DisableIT_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NACKIE); -} - -/** - * @brief Check if Not acknowledge received interrupt is enabled or disabled. - * @rmtoll CR1 NACKIE LL_FMPI2C_IsEnabledIT_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NACKIE) == (FMPI2C_CR1_NACKIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable STOP detection interrupt. - * @rmtoll CR1 STOPIE LL_FMPI2C_EnableIT_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_STOPIE); -} - -/** - * @brief Disable STOP detection interrupt. - * @rmtoll CR1 STOPIE LL_FMPI2C_DisableIT_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_STOPIE); -} - -/** - * @brief Check if STOP detection interrupt is enabled or disabled. - * @rmtoll CR1 STOPIE LL_FMPI2C_IsEnabledIT_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_STOPIE) == (FMPI2C_CR1_STOPIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable Transfer Complete interrupt. - * @note Any of these events will generate interrupt : - * Transfer Complete (TC) - * Transfer Complete Reload (TCR) - * @rmtoll CR1 TCIE LL_FMPI2C_EnableIT_TC - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_TC(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TCIE); -} - -/** - * @brief Disable Transfer Complete interrupt. - * @note Any of these events will generate interrupt : - * Transfer Complete (TC) - * Transfer Complete Reload (TCR) - * @rmtoll CR1 TCIE LL_FMPI2C_DisableIT_TC - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_TC(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TCIE); -} - -/** - * @brief Check if Transfer Complete interrupt is enabled or disabled. - * @rmtoll CR1 TCIE LL_FMPI2C_IsEnabledIT_TC - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_TC(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TCIE) == (FMPI2C_CR1_TCIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable Error interrupts. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note Any of these errors will generate interrupt : - * Arbitration Loss (ARLO) - * Bus Error detection (BERR) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (ALERT) - * @rmtoll CR1 ERRIE LL_FMPI2C_EnableIT_ERR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_ERR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ERRIE); -} - -/** - * @brief Disable Error interrupts. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note Any of these errors will generate interrupt : - * Arbitration Loss (ARLO) - * Bus Error detection (BERR) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (ALERT) - * @rmtoll CR1 ERRIE LL_FMPI2C_DisableIT_ERR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_ERR(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ERRIE); -} - -/** - * @brief Check if Error interrupts are enabled or disabled. - * @rmtoll CR1 ERRIE LL_FMPI2C_IsEnabledIT_ERR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_ERR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ERRIE) == (FMPI2C_CR1_ERRIE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EF_FLAG_management FLAG_management - * @{ - */ - -/** - * @brief Indicate the status of Transmit data register empty flag. - * @note RESET: When next data is written in Transmit data register. - * SET: When Transmit data register is empty. - * @rmtoll ISR TXE LL_FMPI2C_IsActiveFlag_TXE - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_TXE(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TXE) == (FMPI2C_ISR_TXE)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Transmit interrupt flag. - * @note RESET: When next data is written in Transmit data register. - * SET: When Transmit data register is empty. - * @rmtoll ISR TXIS LL_FMPI2C_IsActiveFlag_TXIS - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_TXIS(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TXIS) == (FMPI2C_ISR_TXIS)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Receive data register not empty flag. - * @note RESET: When Receive data register is read. - * SET: When the received data is copied in Receive data register. - * @rmtoll ISR RXNE LL_FMPI2C_IsActiveFlag_RXNE - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_RXNE(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_RXNE) == (FMPI2C_ISR_RXNE)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Address matched flag (slave mode). - * @note RESET: Clear default value. - * SET: When the received slave address matched with one of the enabled slave address. - * @rmtoll ISR ADDR LL_FMPI2C_IsActiveFlag_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_ADDR) == (FMPI2C_ISR_ADDR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Not Acknowledge received flag. - * @note RESET: Clear default value. - * SET: When a NACK is received after a byte transmission. - * @rmtoll ISR NACKF LL_FMPI2C_IsActiveFlag_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_NACKF) == (FMPI2C_ISR_NACKF)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Stop detection flag. - * @note RESET: Clear default value. - * SET: When a Stop condition is detected. - * @rmtoll ISR STOPF LL_FMPI2C_IsActiveFlag_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_STOPF) == (FMPI2C_ISR_STOPF)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Transfer complete flag (master mode). - * @note RESET: Clear default value. - * SET: When RELOAD=0, AUTOEND=0 and NBYTES date have been transferred. - * @rmtoll ISR TC LL_FMPI2C_IsActiveFlag_TC - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_TC(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TC) == (FMPI2C_ISR_TC)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Transfer complete flag (master mode). - * @note RESET: Clear default value. - * SET: When RELOAD=1 and NBYTES date have been transferred. - * @rmtoll ISR TCR LL_FMPI2C_IsActiveFlag_TCR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_TCR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TCR) == (FMPI2C_ISR_TCR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Bus error flag. - * @note RESET: Clear default value. - * SET: When a misplaced Start or Stop condition is detected. - * @rmtoll ISR BERR LL_FMPI2C_IsActiveFlag_BERR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_BERR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_BERR) == (FMPI2C_ISR_BERR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Arbitration lost flag. - * @note RESET: Clear default value. - * SET: When arbitration lost. - * @rmtoll ISR ARLO LL_FMPI2C_IsActiveFlag_ARLO - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_ARLO(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_ARLO) == (FMPI2C_ISR_ARLO)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Overrun/Underrun flag (slave mode). - * @note RESET: Clear default value. - * SET: When an overrun/underrun error occurs (Clock Stretching Disabled). - * @rmtoll ISR OVR LL_FMPI2C_IsActiveFlag_OVR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_OVR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_OVR) == (FMPI2C_ISR_OVR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of SMBus PEC error flag in reception. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note RESET: Clear default value. - * SET: When the received PEC does not match with the PEC register content. - * @rmtoll ISR PECERR LL_FMPI2C_IsActiveSMBusFlag_PECERR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveSMBusFlag_PECERR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_PECERR) == (FMPI2C_ISR_PECERR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of SMBus Timeout detection flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note RESET: Clear default value. - * SET: When a timeout or extended clock timeout occurs. - * @rmtoll ISR TIMEOUT LL_FMPI2C_IsActiveSMBusFlag_TIMEOUT - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveSMBusFlag_TIMEOUT(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TIMEOUT) == (FMPI2C_ISR_TIMEOUT)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of SMBus alert flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note RESET: Clear default value. - * SET: When SMBus host configuration, SMBus alert enabled and - * a falling edge event occurs on SMBA pin. - * @rmtoll ISR ALERT LL_FMPI2C_IsActiveSMBusFlag_ALERT - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveSMBusFlag_ALERT(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_ALERT) == (FMPI2C_ISR_ALERT)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Bus Busy flag. - * @note RESET: Clear default value. - * SET: When a Start condition is detected. - * @rmtoll ISR BUSY LL_FMPI2C_IsActiveFlag_BUSY - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_BUSY(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_BUSY) == (FMPI2C_ISR_BUSY)) ? 1UL : 0UL); -} - -/** - * @brief Clear Address Matched flag. - * @rmtoll ICR ADDRCF LL_FMPI2C_ClearFlag_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_ADDRCF); -} - -/** - * @brief Clear Not Acknowledge flag. - * @rmtoll ICR NACKCF LL_FMPI2C_ClearFlag_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_NACKCF); -} - -/** - * @brief Clear Stop detection flag. - * @rmtoll ICR STOPCF LL_FMPI2C_ClearFlag_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_STOPCF); -} - -/** - * @brief Clear Transmit data register empty flag (TXE). - * @note This bit can be clear by software in order to flush the transmit data register (TXDR). - * @rmtoll ISR TXE LL_FMPI2C_ClearFlag_TXE - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_TXE(FMPI2C_TypeDef *FMPI2Cx) -{ - WRITE_REG(FMPI2Cx->ISR, FMPI2C_ISR_TXE); -} - -/** - * @brief Clear Bus error flag. - * @rmtoll ICR BERRCF LL_FMPI2C_ClearFlag_BERR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_BERR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_BERRCF); -} - -/** - * @brief Clear Arbitration lost flag. - * @rmtoll ICR ARLOCF LL_FMPI2C_ClearFlag_ARLO - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_ARLO(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_ARLOCF); -} - -/** - * @brief Clear Overrun/Underrun flag. - * @rmtoll ICR OVRCF LL_FMPI2C_ClearFlag_OVR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_OVR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_OVRCF); -} - -/** - * @brief Clear SMBus PEC error flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll ICR PECCF LL_FMPI2C_ClearSMBusFlag_PECERR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearSMBusFlag_PECERR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_PECCF); -} - -/** - * @brief Clear SMBus Timeout detection flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll ICR TIMOUTCF LL_FMPI2C_ClearSMBusFlag_TIMEOUT - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearSMBusFlag_TIMEOUT(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_TIMOUTCF); -} - -/** - * @brief Clear SMBus Alert flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll ICR ALERTCF LL_FMPI2C_ClearSMBusFlag_ALERT - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearSMBusFlag_ALERT(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_ALERTCF); -} - -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Enable automatic STOP condition generation (master mode). - * @note Automatic end mode : a STOP condition is automatically sent when NBYTES data are transferred. - * This bit has no effect in slave mode or when RELOAD bit is set. - * @rmtoll CR2 AUTOEND LL_FMPI2C_EnableAutoEndMode - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableAutoEndMode(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_AUTOEND); -} - -/** - * @brief Disable automatic STOP condition generation (master mode). - * @note Software end mode : TC flag is set when NBYTES data are transferre, stretching SCL low. - * @rmtoll CR2 AUTOEND LL_FMPI2C_DisableAutoEndMode - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableAutoEndMode(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR2, FMPI2C_CR2_AUTOEND); -} - -/** - * @brief Check if automatic STOP condition is enabled or disabled. - * @rmtoll CR2 AUTOEND LL_FMPI2C_IsEnabledAutoEndMode - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledAutoEndMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_AUTOEND) == (FMPI2C_CR2_AUTOEND)) ? 1UL : 0UL); -} - -/** - * @brief Enable reload mode (master mode). - * @note The transfer is not completed after the NBYTES data transfer, NBYTES will be reloaded when TCR flag is set. - * @rmtoll CR2 RELOAD LL_FMPI2C_EnableReloadMode - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableReloadMode(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_RELOAD); -} - -/** - * @brief Disable reload mode (master mode). - * @note The transfer is completed after the NBYTES data transfer(STOP or RESTART will follow). - * @rmtoll CR2 RELOAD LL_FMPI2C_DisableReloadMode - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableReloadMode(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR2, FMPI2C_CR2_RELOAD); -} - -/** - * @brief Check if reload mode is enabled or disabled. - * @rmtoll CR2 RELOAD LL_FMPI2C_IsEnabledReloadMode - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledReloadMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_RELOAD) == (FMPI2C_CR2_RELOAD)) ? 1UL : 0UL); -} - -/** - * @brief Configure the number of bytes for transfer. - * @note Changing these bits when START bit is set is not allowed. - * @rmtoll CR2 NBYTES LL_FMPI2C_SetTransferSize - * @param FMPI2Cx FMPI2C Instance. - * @param TransferSize This parameter must be a value between Min_Data=0x00 and Max_Data=0xFF. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetTransferSize(FMPI2C_TypeDef *FMPI2Cx, uint32_t TransferSize) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_NBYTES, TransferSize << FMPI2C_CR2_NBYTES_Pos); -} - -/** - * @brief Get the number of bytes configured for transfer. - * @rmtoll CR2 NBYTES LL_FMPI2C_GetTransferSize - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetTransferSize(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_NBYTES) >> FMPI2C_CR2_NBYTES_Pos); -} - -/** - * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code - or next received byte. - * @note Usage in Slave mode only. - * @rmtoll CR2 NACK LL_FMPI2C_AcknowledgeNextData - * @param FMPI2Cx FMPI2C Instance. - * @param TypeAcknowledge This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_ACK - * @arg @ref LL_FMPI2C_NACK - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_AcknowledgeNextData(FMPI2C_TypeDef *FMPI2Cx, uint32_t TypeAcknowledge) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_NACK, TypeAcknowledge); -} - -/** - * @brief Generate a START or RESTART condition - * @note The START bit can be set even if bus is BUSY or FMPI2C is in slave mode. - * This action has no effect when RELOAD is set. - * @rmtoll CR2 START LL_FMPI2C_GenerateStartCondition - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_GenerateStartCondition(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_START); -} - -/** - * @brief Generate a STOP condition after the current byte transfer (master mode). - * @rmtoll CR2 STOP LL_FMPI2C_GenerateStopCondition - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_GenerateStopCondition(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_STOP); -} - -/** - * @brief Enable automatic RESTART Read request condition for 10bit address header (master mode). - * @note The master sends the complete 10bit slave address read sequence : - * Start + 2 bytes 10bit address in Write direction + Restart + first 7 bits of 10bit address - in Read direction. - * @rmtoll CR2 HEAD10R LL_FMPI2C_EnableAuto10BitRead - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableAuto10BitRead(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR2, FMPI2C_CR2_HEAD10R); -} - -/** - * @brief Disable automatic RESTART Read request condition for 10bit address header (master mode). - * @note The master only sends the first 7 bits of 10bit address in Read direction. - * @rmtoll CR2 HEAD10R LL_FMPI2C_DisableAuto10BitRead - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableAuto10BitRead(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_HEAD10R); -} - -/** - * @brief Check if automatic RESTART Read request condition for 10bit address header is enabled or disabled. - * @rmtoll CR2 HEAD10R LL_FMPI2C_IsEnabledAuto10BitRead - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledAuto10BitRead(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_HEAD10R) != (FMPI2C_CR2_HEAD10R)) ? 1UL : 0UL); -} - -/** - * @brief Configure the transfer direction (master mode). - * @note Changing these bits when START bit is set is not allowed. - * @rmtoll CR2 RD_WRN LL_FMPI2C_SetTransferRequest - * @param FMPI2Cx FMPI2C Instance. - * @param TransferRequest This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_REQUEST_WRITE - * @arg @ref LL_FMPI2C_REQUEST_READ - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetTransferRequest(FMPI2C_TypeDef *FMPI2Cx, uint32_t TransferRequest) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_RD_WRN, TransferRequest); -} - -/** - * @brief Get the transfer direction requested (master mode). - * @rmtoll CR2 RD_WRN LL_FMPI2C_GetTransferRequest - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_REQUEST_WRITE - * @arg @ref LL_FMPI2C_REQUEST_READ - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetTransferRequest(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_RD_WRN)); -} - -/** - * @brief Configure the slave address for transfer (master mode). - * @note Changing these bits when START bit is set is not allowed. - * @rmtoll CR2 SADD LL_FMPI2C_SetSlaveAddr - * @param FMPI2Cx FMPI2C Instance. - * @param SlaveAddr This parameter must be a value between Min_Data=0x00 and Max_Data=0x3F. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetSlaveAddr(FMPI2C_TypeDef *FMPI2Cx, uint32_t SlaveAddr) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_SADD, SlaveAddr); -} - -/** - * @brief Get the slave address programmed for transfer. - * @rmtoll CR2 SADD LL_FMPI2C_GetSlaveAddr - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0x3F - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSlaveAddr(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_SADD)); -} - -/** - * @brief Handles FMPI2Cx communication when starting transfer or during transfer (TC or TCR flag are set). - * @rmtoll CR2 SADD LL_FMPI2C_HandleTransfer\n - * CR2 ADD10 LL_FMPI2C_HandleTransfer\n - * CR2 RD_WRN LL_FMPI2C_HandleTransfer\n - * CR2 START LL_FMPI2C_HandleTransfer\n - * CR2 STOP LL_FMPI2C_HandleTransfer\n - * CR2 RELOAD LL_FMPI2C_HandleTransfer\n - * CR2 NBYTES LL_FMPI2C_HandleTransfer\n - * CR2 AUTOEND LL_FMPI2C_HandleTransfer\n - * CR2 HEAD10R LL_FMPI2C_HandleTransfer - * @param FMPI2Cx FMPI2C Instance. - * @param SlaveAddr Specifies the slave address to be programmed. - * @param SlaveAddrSize This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_ADDRSLAVE_7BIT - * @arg @ref LL_FMPI2C_ADDRSLAVE_10BIT - * @param TransferSize Specifies the number of bytes to be programmed. - * This parameter must be a value between Min_Data=0 and Max_Data=255. - * @param EndMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_MODE_RELOAD - * @arg @ref LL_FMPI2C_MODE_AUTOEND - * @arg @ref LL_FMPI2C_MODE_SOFTEND - * @arg @ref LL_FMPI2C_MODE_SMBUS_RELOAD - * @arg @ref LL_FMPI2C_MODE_SMBUS_AUTOEND_NO_PEC - * @arg @ref LL_FMPI2C_MODE_SMBUS_SOFTEND_NO_PEC - * @arg @ref LL_FMPI2C_MODE_SMBUS_AUTOEND_WITH_PEC - * @arg @ref LL_FMPI2C_MODE_SMBUS_SOFTEND_WITH_PEC - * @param Request This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_GENERATE_NOSTARTSTOP - * @arg @ref LL_FMPI2C_GENERATE_STOP - * @arg @ref LL_FMPI2C_GENERATE_START_READ - * @arg @ref LL_FMPI2C_GENERATE_START_WRITE - * @arg @ref LL_FMPI2C_GENERATE_RESTART_7BIT_READ - * @arg @ref LL_FMPI2C_GENERATE_RESTART_7BIT_WRITE - * @arg @ref LL_FMPI2C_GENERATE_RESTART_10BIT_READ - * @arg @ref LL_FMPI2C_GENERATE_RESTART_10BIT_WRITE - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_HandleTransfer(FMPI2C_TypeDef *FMPI2Cx, uint32_t SlaveAddr, uint32_t SlaveAddrSize, - uint32_t TransferSize, uint32_t EndMode, uint32_t Request) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_SADD | FMPI2C_CR2_ADD10 | - (FMPI2C_CR2_RD_WRN & (uint32_t)(Request >> (31U - FMPI2C_CR2_RD_WRN_Pos))) | - FMPI2C_CR2_START | FMPI2C_CR2_STOP | FMPI2C_CR2_RELOAD | - FMPI2C_CR2_NBYTES | FMPI2C_CR2_AUTOEND | FMPI2C_CR2_HEAD10R, - SlaveAddr | SlaveAddrSize | (TransferSize << FMPI2C_CR2_NBYTES_Pos) | EndMode | Request); -} - -/** - * @brief Indicate the value of transfer direction (slave mode). - * @note RESET: Write transfer, Slave enters in receiver mode. - * SET: Read transfer, Slave enters in transmitter mode. - * @rmtoll ISR DIR LL_FMPI2C_GetTransferDirection - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_DIRECTION_WRITE - * @arg @ref LL_FMPI2C_DIRECTION_READ - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetTransferDirection(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_DIR)); -} - -/** - * @brief Return the slave matched address. - * @rmtoll ISR ADDCODE LL_FMPI2C_GetAddressMatchCode - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0x3F - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetAddressMatchCode(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_ADDCODE) >> FMPI2C_ISR_ADDCODE_Pos << 1); -} - -/** - * @brief Enable internal comparison of the SMBus Packet Error byte (transmission or reception mode). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note This feature is cleared by hardware when the PEC byte is transferred, or when a STOP condition - or an Address Matched is received. - * This bit has no effect when RELOAD bit is set. - * This bit has no effect in device mode when SBC bit is not set. - * @rmtoll CR2 PECBYTE LL_FMPI2C_EnableSMBusPECCompare - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSMBusPECCompare(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_PECBYTE); -} - -/** - * @brief Check if the SMBus Packet Error byte internal comparison is requested or not. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR2 PECBYTE LL_FMPI2C_IsEnabledSMBusPECCompare - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSMBusPECCompare(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_PECBYTE) == (FMPI2C_CR2_PECBYTE)) ? 1UL : 0UL); -} - -/** - * @brief Get the SMBus Packet Error byte calculated. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll PECR PEC LL_FMPI2C_GetSMBusPEC - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSMBusPEC(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->PECR, FMPI2C_PECR_PEC)); -} - -/** - * @brief Read Receive Data register. - * @rmtoll RXDR RXDATA LL_FMPI2C_ReceiveData8 - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_FMPI2C_ReceiveData8(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint8_t)(READ_BIT(FMPI2Cx->RXDR, FMPI2C_RXDR_RXDATA)); -} - -/** - * @brief Write in Transmit Data Register . - * @rmtoll TXDR TXDATA LL_FMPI2C_TransmitData8 - * @param FMPI2Cx FMPI2C Instance. - * @param Data Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_TransmitData8(FMPI2C_TypeDef *FMPI2Cx, uint8_t Data) -{ - WRITE_REG(FMPI2Cx->TXDR, Data); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup FMPI2C_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_FMPI2C_Init(FMPI2C_TypeDef *FMPI2Cx, LL_FMPI2C_InitTypeDef *FMPI2C_InitStruct); -ErrorStatus LL_FMPI2C_DeInit(FMPI2C_TypeDef *FMPI2Cx); -void LL_FMPI2C_StructInit(LL_FMPI2C_InitTypeDef *FMPI2C_InitStruct); - - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C1 */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_FMPI2C_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fsmc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fsmc.h deleted file mode 100644 index 12f3a14dfe53110..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fsmc.h +++ /dev/null @@ -1,1033 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fsmc.h - * @author MCD Application Team - * @brief Header file of FSMC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_FSMC_H -#define __STM32F4xx_LL_FSMC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FSMC_LL - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Private types -------------------------------------------------------------*/ -/** @defgroup FSMC_LL_Private_Types FSMC Private Types - * @{ - */ - -/** - * @brief FSMC NORSRAM Configuration Structure definition - */ -typedef struct -{ - uint32_t NSBank; /*!< Specifies the NORSRAM memory device that will be used. - This parameter can be a value of @ref FSMC_NORSRAM_Bank */ - - uint32_t DataAddressMux; /*!< Specifies whether the address and data values are - multiplexed on the data bus or not. - This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */ - - uint32_t MemoryType; /*!< Specifies the type of external memory attached to - the corresponding memory device. - This parameter can be a value of @ref FSMC_Memory_Type */ - - uint32_t MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be a value of @ref FSMC_NORSRAM_Data_Width */ - - uint32_t BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, - valid only with synchronous burst Flash memories. - This parameter can be a value of @ref FSMC_Burst_Access_Mode */ - - uint32_t WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing - the Flash memory in burst mode. - This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */ - - uint32_t WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash - memory, valid only when accessing Flash memories in burst mode. - This parameter can be a value of @ref FSMC_Wrap_Mode - This mode is available only for the STM32F405/407/4015/417xx devices */ - - uint32_t WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one - clock cycle before the wait state or during the wait state, - valid only when accessing memories in burst mode. - This parameter can be a value of @ref FSMC_Wait_Timing */ - - uint32_t WriteOperation; /*!< Enables or disables the write operation in the selected device by the FSMC. - This parameter can be a value of @ref FSMC_Write_Operation */ - - uint32_t WaitSignal; /*!< Enables or disables the wait state insertion via wait - signal, valid for Flash memory access in burst mode. - This parameter can be a value of @ref FSMC_Wait_Signal */ - - uint32_t ExtendedMode; /*!< Enables or disables the extended mode. - This parameter can be a value of @ref FSMC_Extended_Mode */ - - uint32_t AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, - valid only with asynchronous Flash memories. - This parameter can be a value of @ref FSMC_AsynchronousWait */ - - uint32_t WriteBurst; /*!< Enables or disables the write burst operation. - This parameter can be a value of @ref FSMC_Write_Burst */ - - uint32_t ContinuousClock; /*!< Enables or disables the FMC clock output to external memory devices. - This parameter is only enabled through the FMC_BCR1 register, and don't care - through FMC_BCR2..4 registers. - This parameter can be a value of @ref FMC_Continous_Clock - This mode is available only for the STM32F412Vx/Zx/Rx devices */ - - uint32_t WriteFifo; /*!< Enables or disables the write FIFO used by the FMC controller. - This parameter is only enabled through the FMC_BCR1 register, and don't care - through FMC_BCR2..4 registers. - This parameter can be a value of @ref FMC_Write_FIFO - This mode is available only for the STM32F412Vx/Vx devices */ - - uint32_t PageSize; /*!< Specifies the memory page size. - This parameter can be a value of @ref FMC_Page_Size */ -}FSMC_NORSRAM_InitTypeDef; - -/** - * @brief FSMC NORSRAM Timing parameters structure definition - */ -typedef struct -{ - uint32_t AddressSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address setup time. - This parameter can be a value between Min_Data = 0 and Max_Data = 15. - @note This parameter is not used with synchronous NOR Flash memories. */ - - uint32_t AddressHoldTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address hold time. - This parameter can be a value between Min_Data = 1 and Max_Data = 15. - @note This parameter is not used with synchronous NOR Flash memories. */ - - uint32_t DataSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the data setup time. - This parameter can be a value between Min_Data = 1 and Max_Data = 255. - @note This parameter is used for SRAMs, ROMs and asynchronous multiplexed - NOR Flash memories. */ - - uint32_t BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure - the duration of the bus turnaround. - This parameter can be a value between Min_Data = 0 and Max_Data = 15. - @note This parameter is only used for multiplexed NOR Flash memories. */ - - uint32_t CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of - HCLK cycles. This parameter can be a value between Min_Data = 2 and Max_Data = 16. - @note This parameter is not used for asynchronous NOR Flash, SRAM or ROM - accesses. */ - - uint32_t DataLatency; /*!< Defines the number of memory clock cycles to issue - to the memory before getting the first data. - The parameter value depends on the memory type as shown below: - - It must be set to 0 in case of a CRAM - - It is don't care in asynchronous NOR, SRAM or ROM accesses - - It may assume a value between Min_Data = 2 and Max_Data = 17 in NOR Flash memories - with synchronous burst mode enable */ - - uint32_t AccessMode; /*!< Specifies the asynchronous access mode. - This parameter can be a value of @ref FSMC_Access_Mode */ - -}FSMC_NORSRAM_TimingTypeDef; - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief FSMC NAND Configuration Structure definition - */ -typedef struct -{ - uint32_t NandBank; /*!< Specifies the NAND memory device that will be used. - This parameter can be a value of @ref FSMC_NAND_Bank */ - - uint32_t Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory device. - This parameter can be any value of @ref FSMC_Wait_feature */ - - uint32_t MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be any value of @ref FSMC_NAND_Data_Width */ - - uint32_t EccComputation; /*!< Enables or disables the ECC computation. - This parameter can be any value of @ref FSMC_ECC */ - - uint32_t ECCPageSize; /*!< Defines the page size for the extended ECC. - This parameter can be any value of @ref FSMC_ECC_Page_Size */ - - uint32_t TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - -}FSMC_NAND_InitTypeDef; - -/** - * @brief FSMC NAND/PCCARD Timing parameters structure definition - */ -typedef struct -{ - uint32_t SetupTime; /*!< Defines the number of HCLK cycles to setup address before - the command assertion for NAND-Flash read or write access - to common/Attribute or I/O memory space (depending on - the memory space timing to be configured). - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the - command for NAND-Flash read or write access to - common/Attribute or I/O memory space (depending on the - memory space timing to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - - uint32_t HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address - (and data for write access) after the command de-assertion - for NAND-Flash read or write access to common/Attribute - or I/O memory space (depending on the memory space timing - to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - - uint32_t HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the - data bus is kept in HiZ after the start of a NAND-Flash - write access to common/Attribute or I/O memory space (depending - on the memory space timing to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - -}FSMC_NAND_PCC_TimingTypeDef; - -/** - * @brief FSMC NAND Configuration Structure definition - */ -typedef struct -{ - uint32_t Waitfeature; /*!< Enables or disables the Wait feature for the PCCARD Memory device. - This parameter can be any value of @ref FSMC_Wait_feature */ - - uint32_t TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - -}FSMC_PCCARD_InitTypeDef; -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FSMC_LL_Private_Constants FSMC Private Constants - * @{ - */ - -/** @defgroup FSMC_LL_NOR_SRAM_Controller FSMC NOR/SRAM Controller - * @{ - */ -/** @defgroup FSMC_NORSRAM_Bank FSMC NOR/SRAM Bank - * @{ - */ -#define FSMC_NORSRAM_BANK1 0x00000000U -#define FSMC_NORSRAM_BANK2 0x00000002U -#define FSMC_NORSRAM_BANK3 0x00000004U -#define FSMC_NORSRAM_BANK4 0x00000006U -/** - * @} - */ - -/** @defgroup FSMC_Data_Address_Bus_Multiplexing FSMC Data Address Bus Multiplexing - * @{ - */ -#define FSMC_DATA_ADDRESS_MUX_DISABLE 0x00000000U -#define FSMC_DATA_ADDRESS_MUX_ENABLE 0x00000002U -/** - * @} - */ - -/** @defgroup FSMC_Memory_Type FSMC Memory Type - * @{ - */ -#define FSMC_MEMORY_TYPE_SRAM 0x00000000U -#define FSMC_MEMORY_TYPE_PSRAM 0x00000004U -#define FSMC_MEMORY_TYPE_NOR 0x00000008U -/** - * @} - */ - -/** @defgroup FSMC_NORSRAM_Data_Width FSMC NOR/SRAM Data Width - * @{ - */ -#define FSMC_NORSRAM_MEM_BUS_WIDTH_8 0x00000000U -#define FSMC_NORSRAM_MEM_BUS_WIDTH_16 0x00000010U -#define FSMC_NORSRAM_MEM_BUS_WIDTH_32 0x00000020U -/** - * @} - */ - -/** @defgroup FSMC_NORSRAM_Flash_Access FSMC NOR/SRAM Flash Access - * @{ - */ -#define FSMC_NORSRAM_FLASH_ACCESS_ENABLE 0x00000040U -#define FSMC_NORSRAM_FLASH_ACCESS_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup FSMC_Burst_Access_Mode FSMC Burst Access Mode - * @{ - */ -#define FSMC_BURST_ACCESS_MODE_DISABLE 0x00000000U -#define FSMC_BURST_ACCESS_MODE_ENABLE 0x00000100U -/** - * @} - */ - -/** @defgroup FSMC_Wait_Signal_Polarity FSMC Wait Signal Polarity - * @{ - */ -#define FSMC_WAIT_SIGNAL_POLARITY_LOW 0x00000000U -#define FSMC_WAIT_SIGNAL_POLARITY_HIGH 0x00000200U -/** - * @} - */ - -/** @defgroup FSMC_Wrap_Mode FSMC Wrap Mode - * @note These values are available only for the STM32F405/415/407/417xx devices. - * @{ - */ -#define FSMC_WRAP_MODE_DISABLE 0x00000000U -#define FSMC_WRAP_MODE_ENABLE 0x00000400U -/** - * @} - */ - -/** @defgroup FSMC_Wait_Timing FSMC Wait Timing - * @{ - */ -#define FSMC_WAIT_TIMING_BEFORE_WS 0x00000000U -#define FSMC_WAIT_TIMING_DURING_WS 0x00000800U -/** - * @} - */ - -/** @defgroup FSMC_Write_Operation FSMC Write Operation - * @{ - */ -#define FSMC_WRITE_OPERATION_DISABLE 0x00000000U -#define FSMC_WRITE_OPERATION_ENABLE 0x00001000U -/** - * @} - */ - -/** @defgroup FSMC_Wait_Signal FSMC Wait Signal - * @{ - */ -#define FSMC_WAIT_SIGNAL_DISABLE 0x00000000U -#define FSMC_WAIT_SIGNAL_ENABLE 0x00002000U -/** - * @} - */ - -/** @defgroup FSMC_Extended_Mode FSMC Extended Mode - * @{ - */ -#define FSMC_EXTENDED_MODE_DISABLE 0x00000000U -#define FSMC_EXTENDED_MODE_ENABLE 0x00004000U -/** - * @} - */ - -/** @defgroup FSMC_AsynchronousWait FSMC Asynchronous Wait - * @{ - */ -#define FSMC_ASYNCHRONOUS_WAIT_DISABLE 0x00000000U -#define FSMC_ASYNCHRONOUS_WAIT_ENABLE 0x00008000U -/** - * @} - */ - -/** @defgroup FSMC_Page_Size FSMC Page Size - * @{ - */ -#define FSMC_PAGE_SIZE_NONE 0x00000000U -#define FSMC_PAGE_SIZE_128 ((uint32_t)FSMC_BCR1_CPSIZE_0) -#define FSMC_PAGE_SIZE_256 ((uint32_t)FSMC_BCR1_CPSIZE_1) -#define FSMC_PAGE_SIZE_512 ((uint32_t)(FSMC_BCR1_CPSIZE_0 | FSMC_BCR1_CPSIZE_1)) -#define FSMC_PAGE_SIZE_1024 ((uint32_t)FSMC_BCR1_CPSIZE_2) -/** - * @} - */ - -/** @defgroup FSMC_Write_FIFO FSMC Write FIFO - * @note These values are available only for the STM32F412Vx/Zx/Rx devices. - * @{ - */ -#define FSMC_WRITE_FIFO_DISABLE ((uint32_t)FSMC_BCR1_WFDIS) -#define FSMC_WRITE_FIFO_ENABLE 0x00000000U -/** - * @} - */ - -/** @defgroup FSMC_Write_Burst FSMC Write Burst - * @{ - */ -#define FSMC_WRITE_BURST_DISABLE 0x00000000U -#define FSMC_WRITE_BURST_ENABLE 0x00080000U -/** - * @} - */ - -/** @defgroup FSMC_Continous_Clock FSMC Continous Clock - * @note These values are available only for the STM32F412Vx/Zx/Rx devices. - * @{ - */ -#define FSMC_CONTINUOUS_CLOCK_SYNC_ONLY 0x00000000U -#define FSMC_CONTINUOUS_CLOCK_SYNC_ASYNC 0x00100000U -/** - * @} - */ - -/** @defgroup FSMC_Access_Mode FSMC Access Mode - * @{ - */ -#define FSMC_ACCESS_MODE_A 0x00000000U -#define FSMC_ACCESS_MODE_B 0x10000000U -#define FSMC_ACCESS_MODE_C 0x20000000U -#define FSMC_ACCESS_MODE_D 0x30000000U -/** - * @} - */ -/** - * @} - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** @defgroup FSMC_LL_NAND_Controller FSMC NAND and PCCARD Controller - * @{ - */ -/** @defgroup FSMC_NAND_Bank FSMC NAND Bank - * @{ - */ -#define FSMC_NAND_BANK2 0x00000010U -#define FSMC_NAND_BANK3 0x00000100U -/** - * @} - */ - -/** @defgroup FSMC_Wait_feature FSMC Wait feature - * @{ - */ -#define FSMC_NAND_PCC_WAIT_FEATURE_DISABLE 0x00000000U -#define FSMC_NAND_PCC_WAIT_FEATURE_ENABLE 0x00000002U -/** - * @} - */ - -/** @defgroup FSMC_PCR_Memory_Type FSMC PCR Memory Type - * @{ - */ -#define FSMC_PCR_MEMORY_TYPE_PCCARD 0x00000000U -#define FSMC_PCR_MEMORY_TYPE_NAND 0x00000008U -/** - * @} - */ - -/** @defgroup FSMC_NAND_Data_Width FSMC NAND Data Width - * @{ - */ -#define FSMC_NAND_PCC_MEM_BUS_WIDTH_8 0x00000000U -#define FSMC_NAND_PCC_MEM_BUS_WIDTH_16 0x00000010U -/** - * @} - */ - -/** @defgroup FSMC_ECC FSMC ECC - * @{ - */ -#define FSMC_NAND_ECC_DISABLE 0x00000000U -#define FSMC_NAND_ECC_ENABLE 0x00000040U -/** - * @} - */ - -/** @defgroup FSMC_ECC_Page_Size FSMC ECC Page Size - * @{ - */ -#define FSMC_NAND_ECC_PAGE_SIZE_256BYTE 0x00000000U -#define FSMC_NAND_ECC_PAGE_SIZE_512BYTE 0x00020000U -#define FSMC_NAND_ECC_PAGE_SIZE_1024BYTE 0x00040000U -#define FSMC_NAND_ECC_PAGE_SIZE_2048BYTE 0x00060000U -#define FSMC_NAND_ECC_PAGE_SIZE_4096BYTE 0x00080000U -#define FSMC_NAND_ECC_PAGE_SIZE_8192BYTE 0x000A0000U -/** - * @} - */ -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/** @defgroup FSMC_LL_Interrupt_definition FSMC Interrupt definition - * @{ - */ -#define FSMC_IT_RISING_EDGE 0x00000008U -#define FSMC_IT_LEVEL 0x00000010U -#define FSMC_IT_FALLING_EDGE 0x00000020U -#define FSMC_IT_REFRESH_ERROR 0x00004000U -/** - * @} - */ - -/** @defgroup FSMC_LL_Flag_definition FSMC Flag definition - * @{ - */ -#define FSMC_FLAG_RISING_EDGE 0x00000001U -#define FSMC_FLAG_LEVEL 0x00000002U -#define FSMC_FLAG_FALLING_EDGE 0x00000004U -#define FSMC_FLAG_FEMPT 0x00000040U -/** - * @} - */ - -/** @defgroup FSMC_LL_Alias_definition FSMC Alias definition - * @{ - */ -#define FSMC_NORSRAM_TypeDef FSMC_Bank1_TypeDef -#define FSMC_NORSRAM_EXTENDED_TypeDef FSMC_Bank1E_TypeDef -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FSMC_NAND_TypeDef FSMC_Bank2_3_TypeDef -#define FSMC_PCCARD_TypeDef FSMC_Bank4_TypeDef -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FSMC_NORSRAM_DEVICE FSMC_Bank1 -#define FSMC_NORSRAM_EXTENDED_DEVICE FSMC_Bank1E -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FSMC_NAND_DEVICE FSMC_Bank2_3 -#define FSMC_PCCARD_DEVICE FSMC_Bank4 -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FMC_NORSRAM_MEM_BUS_WIDTH_8 FSMC_NORSRAM_MEM_BUS_WIDTH_8 -#define FMC_NORSRAM_MEM_BUS_WIDTH_16 FSMC_NORSRAM_MEM_BUS_WIDTH_16 -#define FMC_NORSRAM_MEM_BUS_WIDTH_32 FSMC_NORSRAM_MEM_BUS_WIDTH_32 - -#define FMC_NORSRAM_TypeDef FSMC_NORSRAM_TypeDef -#define FMC_NORSRAM_EXTENDED_TypeDef FSMC_NORSRAM_EXTENDED_TypeDef -#define FMC_NORSRAM_InitTypeDef FSMC_NORSRAM_InitTypeDef -#define FMC_NORSRAM_TimingTypeDef FSMC_NORSRAM_TimingTypeDef - -#define FMC_NORSRAM_Init FSMC_NORSRAM_Init -#define FMC_NORSRAM_Timing_Init FSMC_NORSRAM_Timing_Init -#define FMC_NORSRAM_Extended_Timing_Init FSMC_NORSRAM_Extended_Timing_Init -#define FMC_NORSRAM_DeInit FSMC_NORSRAM_DeInit -#define FMC_NORSRAM_WriteOperation_Enable FSMC_NORSRAM_WriteOperation_Enable -#define FMC_NORSRAM_WriteOperation_Disable FSMC_NORSRAM_WriteOperation_Disable - -#define __FMC_NORSRAM_ENABLE __FSMC_NORSRAM_ENABLE -#define __FMC_NORSRAM_DISABLE __FSMC_NORSRAM_DISABLE - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FMC_NAND_InitTypeDef FSMC_NAND_InitTypeDef -#define FMC_PCCARD_InitTypeDef FSMC_PCCARD_InitTypeDef -#define FMC_NAND_PCC_TimingTypeDef FSMC_NAND_PCC_TimingTypeDef - -#define FMC_NAND_Init FSMC_NAND_Init -#define FMC_NAND_CommonSpace_Timing_Init FSMC_NAND_CommonSpace_Timing_Init -#define FMC_NAND_AttributeSpace_Timing_Init FSMC_NAND_AttributeSpace_Timing_Init -#define FMC_NAND_DeInit FSMC_NAND_DeInit -#define FMC_NAND_ECC_Enable FSMC_NAND_ECC_Enable -#define FMC_NAND_ECC_Disable FSMC_NAND_ECC_Disable -#define FMC_NAND_GetECC FSMC_NAND_GetECC -#define FMC_PCCARD_Init FSMC_PCCARD_Init -#define FMC_PCCARD_CommonSpace_Timing_Init FSMC_PCCARD_CommonSpace_Timing_Init -#define FMC_PCCARD_AttributeSpace_Timing_Init FSMC_PCCARD_AttributeSpace_Timing_Init -#define FMC_PCCARD_IOSpace_Timing_Init FSMC_PCCARD_IOSpace_Timing_Init -#define FMC_PCCARD_DeInit FSMC_PCCARD_DeInit - -#define __FMC_NAND_ENABLE __FSMC_NAND_ENABLE -#define __FMC_NAND_DISABLE __FSMC_NAND_DISABLE -#define __FMC_PCCARD_ENABLE __FSMC_PCCARD_ENABLE -#define __FMC_PCCARD_DISABLE __FSMC_PCCARD_DISABLE -#define __FMC_NAND_ENABLE_IT __FSMC_NAND_ENABLE_IT -#define __FMC_NAND_DISABLE_IT __FSMC_NAND_DISABLE_IT -#define __FMC_NAND_GET_FLAG __FSMC_NAND_GET_FLAG -#define __FMC_NAND_CLEAR_FLAG __FSMC_NAND_CLEAR_FLAG -#define __FMC_PCCARD_ENABLE_IT __FSMC_PCCARD_ENABLE_IT -#define __FMC_PCCARD_DISABLE_IT __FSMC_PCCARD_DISABLE_IT -#define __FMC_PCCARD_GET_FLAG __FSMC_PCCARD_GET_FLAG -#define __FMC_PCCARD_CLEAR_FLAG __FSMC_PCCARD_CLEAR_FLAG -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FMC_NORSRAM_TypeDef FSMC_NORSRAM_TypeDef -#define FMC_NORSRAM_EXTENDED_TypeDef FSMC_NORSRAM_EXTENDED_TypeDef -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FMC_NAND_TypeDef FSMC_NAND_TypeDef -#define FMC_PCCARD_TypeDef FSMC_PCCARD_TypeDef -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FMC_NORSRAM_DEVICE FSMC_NORSRAM_DEVICE -#define FMC_NORSRAM_EXTENDED_DEVICE FSMC_NORSRAM_EXTENDED_DEVICE -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FMC_NAND_DEVICE FSMC_NAND_DEVICE -#define FMC_PCCARD_DEVICE FSMC_PCCARD_DEVICE - -#define FMC_NAND_BANK2 FSMC_NAND_BANK2 -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FMC_NORSRAM_BANK1 FSMC_NORSRAM_BANK1 -#define FMC_NORSRAM_BANK2 FSMC_NORSRAM_BANK2 -#define FMC_NORSRAM_BANK3 FSMC_NORSRAM_BANK3 - -#define FMC_IT_RISING_EDGE FSMC_IT_RISING_EDGE -#define FMC_IT_LEVEL FSMC_IT_LEVEL -#define FMC_IT_FALLING_EDGE FSMC_IT_FALLING_EDGE -#define FMC_IT_REFRESH_ERROR FSMC_IT_REFRESH_ERROR - -#define FMC_FLAG_RISING_EDGE FSMC_FLAG_RISING_EDGE -#define FMC_FLAG_LEVEL FSMC_FLAG_LEVEL -#define FMC_FLAG_FALLING_EDGE FSMC_FLAG_FALLING_EDGE -#define FMC_FLAG_FEMPT FSMC_FLAG_FEMPT -/** - * @} - */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/** @defgroup FSMC_LL_Private_Macros FSMC Private Macros - * @{ - */ - -/** @defgroup FSMC_LL_NOR_Macros FSMC NOR/SRAM Exported Macros - * @brief macros to handle NOR device enable/disable and read/write operations - * @{ - */ -/** - * @brief Enable the NORSRAM device access. - * @param __INSTANCE__ FSMC_NORSRAM Instance - * @param __BANK__ FSMC_NORSRAM Bank - * @retval none - */ -#define __FSMC_NORSRAM_ENABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->BTCR[(__BANK__)] |= FSMC_BCR1_MBKEN) - -/** - * @brief Disable the NORSRAM device access. - * @param __INSTANCE__ FSMC_NORSRAM Instance - * @param __BANK__ FSMC_NORSRAM Bank - * @retval none - */ -#define __FSMC_NORSRAM_DISABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->BTCR[(__BANK__)] &= ~FSMC_BCR1_MBKEN) -/** - * @} - */ - -/** @defgroup FSMC_LL_NAND_Macros FSMC NAND Macros - * @brief macros to handle NAND device enable/disable - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief Enable the NAND device access. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @retval none - */ -#define __FSMC_NAND_ENABLE(__INSTANCE__, __BANK__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->PCR2 |= FSMC_PCR2_PBKEN): \ - ((__INSTANCE__)->PCR3 |= FSMC_PCR3_PBKEN)) - -/** - * @brief Disable the NAND device access. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @retval none - */ -#define __FSMC_NAND_DISABLE(__INSTANCE__, __BANK__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->PCR2 &= ~FSMC_PCR2_PBKEN): \ - ((__INSTANCE__)->PCR3 &= ~FSMC_PCR3_PBKEN)) -/** - * @} - */ - -/** @defgroup FSMC_LL_PCCARD_Macros FSMC PCCARD Macros - * @brief macros to handle SRAM read/write operations - * @{ - */ -/** - * @brief Enable the PCCARD device access. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @retval none - */ -#define __FSMC_PCCARD_ENABLE(__INSTANCE__) ((__INSTANCE__)->PCR4 |= FSMC_PCR4_PBKEN) - -/** - * @brief Disable the PCCARD device access. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @retval none - */ -#define __FSMC_PCCARD_DISABLE(__INSTANCE__) ((__INSTANCE__)->PCR4 &= ~FSMC_PCR4_PBKEN) -/** - * @} - */ - -/** @defgroup FSMC_LL_Flag_Interrupt_Macros FSMC Flag&Interrupt Macros - * @brief macros to handle FSMC flags and interrupts - * @{ - */ -/** - * @brief Enable the NAND device interrupt. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @param __INTERRUPT__ FSMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FSMC_IT_LEVEL: Interrupt level. - * @arg FSMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FSMC_NAND_ENABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->SR2 |= (__INTERRUPT__)): \ - ((__INSTANCE__)->SR3 |= (__INTERRUPT__))) - -/** - * @brief Disable the NAND device interrupt. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @param __INTERRUPT__ FSMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FSMC_IT_LEVEL: Interrupt level. - * @arg FSMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FSMC_NAND_DISABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->SR2 &= ~(__INTERRUPT__)): \ - ((__INSTANCE__)->SR3 &= ~(__INTERRUPT__))) - -/** - * @brief Get flag status of the NAND device. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @param __FLAG__ FSMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FSMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FSMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FSMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FSMC_NAND_GET_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__BANK__) == FSMC_NAND_BANK2)? (((__INSTANCE__)->SR2 &(__FLAG__)) == (__FLAG__)): \ - (((__INSTANCE__)->SR3 &(__FLAG__)) == (__FLAG__))) - -/** - * @brief Clear flag status of the NAND device. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @param __FLAG__ FSMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FSMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FSMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FSMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FSMC_NAND_CLEAR_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->SR2 &= ~(__FLAG__)): \ - ((__INSTANCE__)->SR3 &= ~(__FLAG__))) - -/** - * @brief Enable the PCCARD device interrupt. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @param __INTERRUPT__ FSMC_PCCARD interrupt - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FSMC_IT_LEVEL: Interrupt level. - * @arg FSMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FSMC_PCCARD_ENABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SR4 |= (__INTERRUPT__)) - -/** - * @brief Disable the PCCARD device interrupt. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @param __INTERRUPT__ FSMC_PCCARD interrupt - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FSMC_IT_LEVEL: Interrupt level. - * @arg FSMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FSMC_PCCARD_DISABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SR4 &= ~(__INTERRUPT__)) - -/** - * @brief Get flag status of the PCCARD device. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @param __FLAG__ FSMC_PCCARD flag - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FSMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FSMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FSMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FSMC_PCCARD_GET_FLAG(__INSTANCE__, __FLAG__) (((__INSTANCE__)->SR4 &(__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear flag status of the PCCARD device. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @param __FLAG__ FSMC_PCCARD flag - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FSMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FSMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FSMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FSMC_PCCARD_CLEAR_FLAG(__INSTANCE__, __FLAG__) ((__INSTANCE__)->SR4 &= ~(__FLAG__)) -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/** @defgroup FSMC_LL_Assert_Macros FSMC Assert Macros - * @{ - */ -#define IS_FSMC_NORSRAM_BANK(__BANK__) (((__BANK__) == FSMC_NORSRAM_BANK1) || \ - ((__BANK__) == FSMC_NORSRAM_BANK2) || \ - ((__BANK__) == FSMC_NORSRAM_BANK3) || \ - ((__BANK__) == FSMC_NORSRAM_BANK4)) - -#define IS_FSMC_MUX(__MUX__) (((__MUX__) == FSMC_DATA_ADDRESS_MUX_DISABLE) || \ - ((__MUX__) == FSMC_DATA_ADDRESS_MUX_ENABLE)) - -#define IS_FSMC_MEMORY(__MEMORY__) (((__MEMORY__) == FSMC_MEMORY_TYPE_SRAM) || \ - ((__MEMORY__) == FSMC_MEMORY_TYPE_PSRAM)|| \ - ((__MEMORY__) == FSMC_MEMORY_TYPE_NOR)) - -#define IS_FSMC_NORSRAM_MEMORY_WIDTH(__WIDTH__) (((__WIDTH__) == FSMC_NORSRAM_MEM_BUS_WIDTH_8) || \ - ((__WIDTH__) == FSMC_NORSRAM_MEM_BUS_WIDTH_16) || \ - ((__WIDTH__) == FSMC_NORSRAM_MEM_BUS_WIDTH_32)) - -#define IS_FSMC_ACCESS_MODE(__MODE__) (((__MODE__) == FSMC_ACCESS_MODE_A) || \ - ((__MODE__) == FSMC_ACCESS_MODE_B) || \ - ((__MODE__) == FSMC_ACCESS_MODE_C) || \ - ((__MODE__) == FSMC_ACCESS_MODE_D)) - -#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_NAND_BANK2) || \ - ((BANK) == FSMC_NAND_BANK3)) - -#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_NAND_PCC_WAIT_FEATURE_DISABLE) || \ - ((FEATURE) == FSMC_NAND_PCC_WAIT_FEATURE_ENABLE)) - -#define IS_FSMC_NAND_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_NAND_PCC_MEM_BUS_WIDTH_8) || \ - ((WIDTH) == FSMC_NAND_PCC_MEM_BUS_WIDTH_16)) - -#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_NAND_ECC_DISABLE) || \ - ((STATE) == FSMC_NAND_ECC_ENABLE)) - -#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_256BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_512BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_1024BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_2048BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_4096BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_8192BYTE)) - -#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_NORSRAM_DEVICE(__INSTANCE__) ((__INSTANCE__) == FSMC_NORSRAM_DEVICE) - -#define IS_FSMC_NORSRAM_EXTENDED_DEVICE(__INSTANCE__) ((__INSTANCE__) == FSMC_NORSRAM_EXTENDED_DEVICE) - -#define IS_FSMC_NAND_DEVICE(INSTANCE) ((INSTANCE) == FSMC_NAND_DEVICE) - -#define IS_FSMC_PCCARD_DEVICE(INSTANCE) ((INSTANCE) == FSMC_PCCARD_DEVICE) - -#define IS_FSMC_BURSTMODE(__STATE__) (((__STATE__) == FSMC_BURST_ACCESS_MODE_DISABLE) || \ - ((__STATE__) == FSMC_BURST_ACCESS_MODE_ENABLE)) - -#define IS_FSMC_WAIT_POLARITY(__POLARITY__) (((__POLARITY__) == FSMC_WAIT_SIGNAL_POLARITY_LOW) || \ - ((__POLARITY__) == FSMC_WAIT_SIGNAL_POLARITY_HIGH)) - -#define IS_FSMC_WRAP_MODE(__MODE__) (((__MODE__) == FSMC_WRAP_MODE_DISABLE) || \ - ((__MODE__) == FSMC_WRAP_MODE_ENABLE)) - -#define IS_FSMC_WAIT_SIGNAL_ACTIVE(__ACTIVE__) (((__ACTIVE__) == FSMC_WAIT_TIMING_BEFORE_WS) || \ - ((__ACTIVE__) == FSMC_WAIT_TIMING_DURING_WS)) - -#define IS_FSMC_WRITE_OPERATION(__OPERATION__) (((__OPERATION__) == FSMC_WRITE_OPERATION_DISABLE) || \ - ((__OPERATION__) == FSMC_WRITE_OPERATION_ENABLE)) - -#define IS_FSMC_WAITE_SIGNAL(__SIGNAL__) (((__SIGNAL__) == FSMC_WAIT_SIGNAL_DISABLE) || \ - ((__SIGNAL__) == FSMC_WAIT_SIGNAL_ENABLE)) - -#define IS_FSMC_EXTENDED_MODE(__MODE__) (((__MODE__) == FSMC_EXTENDED_MODE_DISABLE) || \ - ((__MODE__) == FSMC_EXTENDED_MODE_ENABLE)) - -#define IS_FSMC_ASYNWAIT(__STATE__) (((__STATE__) == FSMC_ASYNCHRONOUS_WAIT_DISABLE) || \ - ((__STATE__) == FSMC_ASYNCHRONOUS_WAIT_ENABLE)) - -#define IS_FSMC_DATA_LATENCY(__LATENCY__) (((__LATENCY__) > 1U) && ((__LATENCY__) <= 17U)) - -#define IS_FSMC_WRITE_BURST(__BURST__) (((__BURST__) == FSMC_WRITE_BURST_DISABLE) || \ - ((__BURST__) == FSMC_WRITE_BURST_ENABLE)) - -#define IS_FSMC_ADDRESS_SETUP_TIME(__TIME__) ((__TIME__) <= 15U) - -#define IS_FSMC_ADDRESS_HOLD_TIME(__TIME__) (((__TIME__) > 0U) && ((__TIME__) <= 15U)) - -#define IS_FSMC_DATASETUP_TIME(__TIME__) (((__TIME__) > 0U) && ((__TIME__) <= 255U)) - -#define IS_FSMC_TURNAROUND_TIME(__TIME__) ((__TIME__) <= 15U) - -#define IS_FSMC_CONTINOUS_CLOCK(CCLOCK) (((CCLOCK) == FSMC_CONTINUOUS_CLOCK_SYNC_ONLY) || \ - ((CCLOCK) == FSMC_CONTINUOUS_CLOCK_SYNC_ASYNC)) - -#define IS_FSMC_CLK_DIV(DIV) (((DIV) > 1U) && ((DIV) <= 16U)) - -#define IS_FSMC_PAGESIZE(SIZE) (((SIZE) == FSMC_PAGE_SIZE_NONE) || \ - ((SIZE) == FSMC_PAGE_SIZE_128) || \ - ((SIZE) == FSMC_PAGE_SIZE_256) || \ - ((SIZE) == FSMC_PAGE_SIZE_512) || \ - ((SIZE) == FSMC_PAGE_SIZE_1024)) - -#define IS_FSMC_WRITE_FIFO(FIFO) (((FIFO) == FSMC_WRITE_FIFO_DISABLE) || \ - ((FIFO) == FSMC_WRITE_FIFO_ENABLE)) - -/** - * @} - */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FSMC_LL_Private_Functions FSMC LL Private Functions - * @{ - */ - -/** @defgroup FSMC_LL_NORSRAM NOR SRAM - * @{ - */ - -/** @defgroup FSMC_LL_NORSRAM_Private_Functions_Group1 NOR SRAM Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FSMC_NORSRAM_Init(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_InitTypeDef *Init); -HAL_StatusTypeDef FSMC_NORSRAM_Timing_Init(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FSMC_NORSRAM_Extended_Timing_Init(FSMC_NORSRAM_EXTENDED_TypeDef *Device, FSMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode); -HAL_StatusTypeDef FSMC_NORSRAM_DeInit(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FSMC_LL_NORSRAM_Private_Functions_Group2 NOR SRAM Control functions - * @{ - */ -HAL_StatusTypeDef FSMC_NORSRAM_WriteOperation_Enable(FSMC_NORSRAM_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FSMC_NORSRAM_WriteOperation_Disable(FSMC_NORSRAM_TypeDef *Device, uint32_t Bank); -/** - * @} - */ -/** - * @} - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** @defgroup FSMC_LL_NAND NAND - * @{ - */ -/** @defgroup FSMC_LL_NAND_Private_Functions_Group1 NAND Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FSMC_NAND_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_InitTypeDef *Init); -HAL_StatusTypeDef FSMC_NAND_CommonSpace_Timing_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FSMC_NAND_AttributeSpace_Timing_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FSMC_NAND_DeInit(FSMC_NAND_TypeDef *Device, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FSMC_LL_NAND_Private_Functions_Group2 NAND Control functions - * @{ - */ -HAL_StatusTypeDef FSMC_NAND_ECC_Enable(FSMC_NAND_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FSMC_NAND_ECC_Disable(FSMC_NAND_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FSMC_NAND_GetECC(FSMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout); -/** - * @} - */ -/** - * @} - */ - -/** @defgroup FSMC_LL_PCCARD PCCARD - * @{ - */ -/** @defgroup FSMC_LL_PCCARD_Private_Functions_Group1 PCCARD Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FSMC_PCCARD_Init(FSMC_PCCARD_TypeDef *Device, FSMC_PCCARD_InitTypeDef *Init); -HAL_StatusTypeDef FSMC_PCCARD_CommonSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FSMC_PCCARD_AttributeSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FSMC_PCCARD_IOSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FSMC_PCCARD_DeInit(FSMC_PCCARD_TypeDef *Device); -/** - * @} - */ -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_FSMC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h deleted file mode 100644 index 76e9170a0d92140..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h +++ /dev/null @@ -1,983 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_gpio.h - * @author MCD Application Team - * @brief Header file of GPIO LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_GPIO_H -#define __STM32F4xx_LL_GPIO_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) - -/** @defgroup GPIO_LL GPIO - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_Private_Macros GPIO Private Macros - * @{ - */ - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_ES_INIT GPIO Exported Init structures - * @{ - */ - -/** - * @brief LL GPIO Init Structure definition - */ -typedef struct -{ - uint32_t Pin; /*!< Specifies the GPIO pins to be configured. - This parameter can be any value of @ref GPIO_LL_EC_PIN */ - - uint32_t Mode; /*!< Specifies the operating mode for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_MODE. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinMode().*/ - - uint32_t Speed; /*!< Specifies the speed for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_SPEED. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinSpeed().*/ - - uint32_t OutputType; /*!< Specifies the operating output type for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_OUTPUT. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinOutputType().*/ - - uint32_t Pull; /*!< Specifies the operating Pull-up/Pull down for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_PULL. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinPull().*/ - - uint32_t Alternate; /*!< Specifies the Peripheral to be connected to the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_AF. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetAFPin_0_7() and LL_GPIO_SetAFPin_8_15().*/ -} LL_GPIO_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_LL_EC_PIN PIN - * @{ - */ -#define LL_GPIO_PIN_0 GPIO_BSRR_BS_0 /*!< Select pin 0 */ -#define LL_GPIO_PIN_1 GPIO_BSRR_BS_1 /*!< Select pin 1 */ -#define LL_GPIO_PIN_2 GPIO_BSRR_BS_2 /*!< Select pin 2 */ -#define LL_GPIO_PIN_3 GPIO_BSRR_BS_3 /*!< Select pin 3 */ -#define LL_GPIO_PIN_4 GPIO_BSRR_BS_4 /*!< Select pin 4 */ -#define LL_GPIO_PIN_5 GPIO_BSRR_BS_5 /*!< Select pin 5 */ -#define LL_GPIO_PIN_6 GPIO_BSRR_BS_6 /*!< Select pin 6 */ -#define LL_GPIO_PIN_7 GPIO_BSRR_BS_7 /*!< Select pin 7 */ -#define LL_GPIO_PIN_8 GPIO_BSRR_BS_8 /*!< Select pin 8 */ -#define LL_GPIO_PIN_9 GPIO_BSRR_BS_9 /*!< Select pin 9 */ -#define LL_GPIO_PIN_10 GPIO_BSRR_BS_10 /*!< Select pin 10 */ -#define LL_GPIO_PIN_11 GPIO_BSRR_BS_11 /*!< Select pin 11 */ -#define LL_GPIO_PIN_12 GPIO_BSRR_BS_12 /*!< Select pin 12 */ -#define LL_GPIO_PIN_13 GPIO_BSRR_BS_13 /*!< Select pin 13 */ -#define LL_GPIO_PIN_14 GPIO_BSRR_BS_14 /*!< Select pin 14 */ -#define LL_GPIO_PIN_15 GPIO_BSRR_BS_15 /*!< Select pin 15 */ -#define LL_GPIO_PIN_ALL (GPIO_BSRR_BS_0 | GPIO_BSRR_BS_1 | GPIO_BSRR_BS_2 | \ - GPIO_BSRR_BS_3 | GPIO_BSRR_BS_4 | GPIO_BSRR_BS_5 | \ - GPIO_BSRR_BS_6 | GPIO_BSRR_BS_7 | GPIO_BSRR_BS_8 | \ - GPIO_BSRR_BS_9 | GPIO_BSRR_BS_10 | GPIO_BSRR_BS_11 | \ - GPIO_BSRR_BS_12 | GPIO_BSRR_BS_13 | GPIO_BSRR_BS_14 | \ - GPIO_BSRR_BS_15) /*!< Select all pins */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_MODE Mode - * @{ - */ -#define LL_GPIO_MODE_INPUT (0x00000000U) /*!< Select input mode */ -#define LL_GPIO_MODE_OUTPUT GPIO_MODER_MODER0_0 /*!< Select output mode */ -#define LL_GPIO_MODE_ALTERNATE GPIO_MODER_MODER0_1 /*!< Select alternate function mode */ -#define LL_GPIO_MODE_ANALOG GPIO_MODER_MODER0 /*!< Select analog mode */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_OUTPUT Output Type - * @{ - */ -#define LL_GPIO_OUTPUT_PUSHPULL (0x00000000U) /*!< Select push-pull as output type */ -#define LL_GPIO_OUTPUT_OPENDRAIN GPIO_OTYPER_OT_0 /*!< Select open-drain as output type */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_SPEED Output Speed - * @{ - */ -#define LL_GPIO_SPEED_FREQ_LOW (0x00000000U) /*!< Select I/O low output speed */ -#define LL_GPIO_SPEED_FREQ_MEDIUM GPIO_OSPEEDER_OSPEEDR0_0 /*!< Select I/O medium output speed */ -#define LL_GPIO_SPEED_FREQ_HIGH GPIO_OSPEEDER_OSPEEDR0_1 /*!< Select I/O fast output speed */ -#define LL_GPIO_SPEED_FREQ_VERY_HIGH GPIO_OSPEEDER_OSPEEDR0 /*!< Select I/O high output speed */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_PULL Pull Up Pull Down - * @{ - */ -#define LL_GPIO_PULL_NO (0x00000000U) /*!< Select I/O no pull */ -#define LL_GPIO_PULL_UP GPIO_PUPDR_PUPDR0_0 /*!< Select I/O pull up */ -#define LL_GPIO_PULL_DOWN GPIO_PUPDR_PUPDR0_1 /*!< Select I/O pull down */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_AF Alternate Function - * @{ - */ -#define LL_GPIO_AF_0 (0x0000000U) /*!< Select alternate function 0 */ -#define LL_GPIO_AF_1 (0x0000001U) /*!< Select alternate function 1 */ -#define LL_GPIO_AF_2 (0x0000002U) /*!< Select alternate function 2 */ -#define LL_GPIO_AF_3 (0x0000003U) /*!< Select alternate function 3 */ -#define LL_GPIO_AF_4 (0x0000004U) /*!< Select alternate function 4 */ -#define LL_GPIO_AF_5 (0x0000005U) /*!< Select alternate function 5 */ -#define LL_GPIO_AF_6 (0x0000006U) /*!< Select alternate function 6 */ -#define LL_GPIO_AF_7 (0x0000007U) /*!< Select alternate function 7 */ -#define LL_GPIO_AF_8 (0x0000008U) /*!< Select alternate function 8 */ -#define LL_GPIO_AF_9 (0x0000009U) /*!< Select alternate function 9 */ -#define LL_GPIO_AF_10 (0x000000AU) /*!< Select alternate function 10 */ -#define LL_GPIO_AF_11 (0x000000BU) /*!< Select alternate function 11 */ -#define LL_GPIO_AF_12 (0x000000CU) /*!< Select alternate function 12 */ -#define LL_GPIO_AF_13 (0x000000DU) /*!< Select alternate function 13 */ -#define LL_GPIO_AF_14 (0x000000EU) /*!< Select alternate function 14 */ -#define LL_GPIO_AF_15 (0x000000FU) /*!< Select alternate function 15 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Macros GPIO Exported Macros - * @{ - */ - -/** @defgroup GPIO_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in GPIO register - * @param __INSTANCE__ GPIO Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_GPIO_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in GPIO register - * @param __INSTANCE__ GPIO Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_GPIO_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Functions GPIO Exported Functions - * @{ - */ - -/** @defgroup GPIO_LL_EF_Port_Configuration Port Configuration - * @{ - */ - -/** - * @brief Configure gpio mode for a dedicated pin on dedicated port. - * @note I/O mode can be Input mode, General purpose output, Alternate function mode or Analog. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll MODER MODEy LL_GPIO_SetPinMode - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_GPIO_MODE_INPUT - * @arg @ref LL_GPIO_MODE_OUTPUT - * @arg @ref LL_GPIO_MODE_ALTERNATE - * @arg @ref LL_GPIO_MODE_ANALOG - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinMode(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Mode) -{ - MODIFY_REG(GPIOx->MODER, (GPIO_MODER_MODER0 << (POSITION_VAL(Pin) * 2U)), (Mode << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio mode for a dedicated pin on dedicated port. - * @note I/O mode can be Input mode, General purpose output, Alternate function mode or Analog. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll MODER MODEy LL_GPIO_GetPinMode - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_MODE_INPUT - * @arg @ref LL_GPIO_MODE_OUTPUT - * @arg @ref LL_GPIO_MODE_ALTERNATE - * @arg @ref LL_GPIO_MODE_ANALOG - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinMode(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->MODER, - (GPIO_MODER_MODER0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio output type for several pins on dedicated port. - * @note Output type as to be set when gpio pin is in output or - * alternate modes. Possible type are Push-pull or Open-drain. - * @rmtoll OTYPER OTy LL_GPIO_SetPinOutputType - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @param OutputType This parameter can be one of the following values: - * @arg @ref LL_GPIO_OUTPUT_PUSHPULL - * @arg @ref LL_GPIO_OUTPUT_OPENDRAIN - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinOutputType(GPIO_TypeDef *GPIOx, uint32_t PinMask, uint32_t OutputType) -{ - MODIFY_REG(GPIOx->OTYPER, PinMask, (PinMask * OutputType)); -} - -/** - * @brief Return gpio output type for several pins on dedicated port. - * @note Output type as to be set when gpio pin is in output or - * alternate modes. Possible type are Push-pull or Open-drain. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll OTYPER OTy LL_GPIO_GetPinOutputType - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_OUTPUT_PUSHPULL - * @arg @ref LL_GPIO_OUTPUT_OPENDRAIN - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinOutputType(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->OTYPER, Pin) >> POSITION_VAL(Pin)); -} - -/** - * @brief Configure gpio speed for a dedicated pin on dedicated port. - * @note I/O speed can be Low, Medium, Fast or High speed. - * @note Warning: only one pin can be passed as parameter. - * @note Refer to datasheet for frequency specifications and the power - * supply and load conditions for each speed. - * @rmtoll OSPEEDR OSPEEDy LL_GPIO_SetPinSpeed - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Speed This parameter can be one of the following values: - * @arg @ref LL_GPIO_SPEED_FREQ_LOW - * @arg @ref LL_GPIO_SPEED_FREQ_MEDIUM - * @arg @ref LL_GPIO_SPEED_FREQ_HIGH - * @arg @ref LL_GPIO_SPEED_FREQ_VERY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinSpeed(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Speed) -{ - MODIFY_REG(GPIOx->OSPEEDR, (GPIO_OSPEEDER_OSPEEDR0 << (POSITION_VAL(Pin) * 2U)), - (Speed << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio speed for a dedicated pin on dedicated port. - * @note I/O speed can be Low, Medium, Fast or High speed. - * @note Warning: only one pin can be passed as parameter. - * @note Refer to datasheet for frequency specifications and the power - * supply and load conditions for each speed. - * @rmtoll OSPEEDR OSPEEDy LL_GPIO_GetPinSpeed - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_SPEED_FREQ_LOW - * @arg @ref LL_GPIO_SPEED_FREQ_MEDIUM - * @arg @ref LL_GPIO_SPEED_FREQ_HIGH - * @arg @ref LL_GPIO_SPEED_FREQ_VERY_HIGH - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinSpeed(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->OSPEEDR, - (GPIO_OSPEEDER_OSPEEDR0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio pull-up or pull-down for a dedicated pin on a dedicated port. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll PUPDR PUPDy LL_GPIO_SetPinPull - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Pull This parameter can be one of the following values: - * @arg @ref LL_GPIO_PULL_NO - * @arg @ref LL_GPIO_PULL_UP - * @arg @ref LL_GPIO_PULL_DOWN - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinPull(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Pull) -{ - MODIFY_REG(GPIOx->PUPDR, (GPIO_PUPDR_PUPDR0 << (POSITION_VAL(Pin) * 2U)), (Pull << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio pull-up or pull-down for a dedicated pin on a dedicated port - * @note Warning: only one pin can be passed as parameter. - * @rmtoll PUPDR PUPDy LL_GPIO_GetPinPull - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_PULL_NO - * @arg @ref LL_GPIO_PULL_UP - * @arg @ref LL_GPIO_PULL_DOWN - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinPull(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->PUPDR, - (GPIO_PUPDR_PUPDR0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio alternate function of a dedicated pin from 0 to 7 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll AFRL AFSELy LL_GPIO_SetAFPin_0_7 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @param Alternate This parameter can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetAFPin_0_7(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Alternate) -{ - MODIFY_REG(GPIOx->AFR[0], (GPIO_AFRL_AFSEL0 << (POSITION_VAL(Pin) * 4U)), - (Alternate << (POSITION_VAL(Pin) * 4U))); -} - -/** - * @brief Return gpio alternate function of a dedicated pin from 0 to 7 for a dedicated port. - * @rmtoll AFRL AFSELy LL_GPIO_GetAFPin_0_7 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - */ -__STATIC_INLINE uint32_t LL_GPIO_GetAFPin_0_7(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->AFR[0], - (GPIO_AFRL_AFSEL0 << (POSITION_VAL(Pin) * 4U))) >> (POSITION_VAL(Pin) * 4U)); -} - -/** - * @brief Configure gpio alternate function of a dedicated pin from 8 to 15 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll AFRH AFSELy LL_GPIO_SetAFPin_8_15 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Alternate This parameter can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetAFPin_8_15(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Alternate) -{ - MODIFY_REG(GPIOx->AFR[1], (GPIO_AFRH_AFSEL8 << (POSITION_VAL(Pin >> 8U) * 4U)), - (Alternate << (POSITION_VAL(Pin >> 8U) * 4U))); -} - -/** - * @brief Return gpio alternate function of a dedicated pin from 8 to 15 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @rmtoll AFRH AFSELy LL_GPIO_GetAFPin_8_15 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - */ -__STATIC_INLINE uint32_t LL_GPIO_GetAFPin_8_15(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->AFR[1], - (GPIO_AFRH_AFSEL8 << (POSITION_VAL(Pin >> 8U) * 4U))) >> (POSITION_VAL(Pin >> 8U) * 4U)); -} - - -/** - * @brief Lock configuration of several pins for a dedicated port. - * @note When the lock sequence has been applied on a port bit, the - * value of this port bit can no longer be modified until the - * next reset. - * @note Each lock bit freezes a specific configuration register - * (control and alternate function registers). - * @rmtoll LCKR LCKK LL_GPIO_LockPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_LockPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - __IO uint32_t temp; - WRITE_REG(GPIOx->LCKR, GPIO_LCKR_LCKK | PinMask); - WRITE_REG(GPIOx->LCKR, PinMask); - WRITE_REG(GPIOx->LCKR, GPIO_LCKR_LCKK | PinMask); - temp = READ_REG(GPIOx->LCKR); - (void) temp; -} - -/** - * @brief Return 1 if all pins passed as parameter, of a dedicated port, are locked. else Return 0. - * @rmtoll LCKR LCKy LL_GPIO_IsPinLocked - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsPinLocked(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->LCKR, PinMask) == (PinMask)); -} - -/** - * @brief Return 1 if one of the pin of a dedicated port is locked. else return 0. - * @rmtoll LCKR LCKK LL_GPIO_IsAnyPinLocked - * @param GPIOx GPIO Port - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsAnyPinLocked(GPIO_TypeDef *GPIOx) -{ - return (READ_BIT(GPIOx->LCKR, GPIO_LCKR_LCKK) == (GPIO_LCKR_LCKK)); -} - -/** - * @} - */ - -/** @defgroup GPIO_LL_EF_Data_Access Data Access - * @{ - */ - -/** - * @brief Return full input data register value for a dedicated port. - * @rmtoll IDR IDy LL_GPIO_ReadInputPort - * @param GPIOx GPIO Port - * @retval Input data register value of port - */ -__STATIC_INLINE uint32_t LL_GPIO_ReadInputPort(GPIO_TypeDef *GPIOx) -{ - return (uint32_t)(READ_REG(GPIOx->IDR)); -} - -/** - * @brief Return if input data level for several pins of dedicated port is high or low. - * @rmtoll IDR IDy LL_GPIO_IsInputPinSet - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsInputPinSet(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->IDR, PinMask) == (PinMask)); -} - -/** - * @brief Write output data register for the port. - * @rmtoll ODR ODy LL_GPIO_WriteOutputPort - * @param GPIOx GPIO Port - * @param PortValue Level value for each pin of the port - * @retval None - */ -__STATIC_INLINE void LL_GPIO_WriteOutputPort(GPIO_TypeDef *GPIOx, uint32_t PortValue) -{ - WRITE_REG(GPIOx->ODR, PortValue); -} - -/** - * @brief Return full output data register value for a dedicated port. - * @rmtoll ODR ODy LL_GPIO_ReadOutputPort - * @param GPIOx GPIO Port - * @retval Output data register value of port - */ -__STATIC_INLINE uint32_t LL_GPIO_ReadOutputPort(GPIO_TypeDef *GPIOx) -{ - return (uint32_t)(READ_REG(GPIOx->ODR)); -} - -/** - * @brief Return if input data level for several pins of dedicated port is high or low. - * @rmtoll ODR ODy LL_GPIO_IsOutputPinSet - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsOutputPinSet(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->ODR, PinMask) == (PinMask)); -} - -/** - * @brief Set several pins to high level on dedicated gpio port. - * @rmtoll BSRR BSy LL_GPIO_SetOutputPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetOutputPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - WRITE_REG(GPIOx->BSRR, PinMask); -} - -/** - * @brief Set several pins to low level on dedicated gpio port. - * @rmtoll BSRR BRy LL_GPIO_ResetOutputPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_ResetOutputPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - WRITE_REG(GPIOx->BSRR, (PinMask << 16)); -} - -/** - * @brief Toggle data value for several pin of dedicated port. - * @rmtoll ODR ODy LL_GPIO_TogglePin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_TogglePin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - uint32_t odr = READ_REG(GPIOx->ODR); - WRITE_REG(GPIOx->BSRR, ((odr & PinMask) << 16u) | (~odr & PinMask)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_GPIO_DeInit(GPIO_TypeDef *GPIOx); -ErrorStatus LL_GPIO_Init(GPIO_TypeDef *GPIOx, LL_GPIO_InitTypeDef *GPIO_InitStruct); -void LL_GPIO_StructInit(LL_GPIO_InitTypeDef *GPIO_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_GPIO_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h deleted file mode 100644 index 5a46babfdc8cfc5..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h +++ /dev/null @@ -1,1892 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_i2c.h - * @author MCD Application Team - * @brief Header file of I2C LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_I2C_H -#define __STM32F4xx_LL_I2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (I2C1) || defined (I2C2) || defined (I2C3) - -/** @defgroup I2C_LL I2C - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2C_LL_Private_Constants I2C Private Constants - * @{ - */ - -/* Defines used to perform compute and check in the macros */ -#define LL_I2C_MAX_SPEED_STANDARD 100000U -#define LL_I2C_MAX_SPEED_FAST 400000U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_Private_Macros I2C Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_ES_INIT I2C Exported Init structure - * @{ - */ -typedef struct -{ - uint32_t PeripheralMode; /*!< Specifies the peripheral mode. - This parameter can be a value of @ref I2C_LL_EC_PERIPHERAL_MODE - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetMode(). */ - - uint32_t ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 400kHz (in Hz) - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetClockPeriod() - or @ref LL_I2C_SetDutyCycle() or @ref LL_I2C_SetClockSpeedMode() or @ref LL_I2C_ConfigSpeed(). */ - - uint32_t DutyCycle; /*!< Specifies the I2C fast mode duty cycle. - This parameter can be a value of @ref I2C_LL_EC_DUTYCYCLE - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetDutyCycle(). */ - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) - uint32_t AnalogFilter; /*!< Enables or disables analog noise filter. - This parameter can be a value of @ref I2C_LL_EC_ANALOGFILTER_SELECTION - - This feature can be modified afterwards using unitary functions @ref LL_I2C_EnableAnalogFilter() or LL_I2C_DisableAnalogFilter(). */ - - uint32_t DigitalFilter; /*!< Configures the digital noise filter. - This parameter can be a number between Min_Data = 0x00 and Max_Data = 0x0F - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetDigitalFilter(). */ - -#endif - uint32_t OwnAddress1; /*!< Specifies the device own address 1. - This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */ - - uint32_t TypeAcknowledge; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte. - This parameter can be a value of @ref I2C_LL_EC_I2C_ACKNOWLEDGE - - This feature can be modified afterwards using unitary function @ref LL_I2C_AcknowledgeNextData(). */ - - uint32_t OwnAddrSize; /*!< Specifies the device own address 1 size (7-bit or 10-bit). - This parameter can be a value of @ref I2C_LL_EC_OWNADDRESS1 - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */ -} LL_I2C_InitTypeDef; -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2C_LL_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2C_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_I2C_ReadReg function - * @{ - */ -#define LL_I2C_SR1_SB I2C_SR1_SB /*!< Start Bit (master mode) */ -#define LL_I2C_SR1_ADDR I2C_SR1_ADDR /*!< Address sent (master mode) or - Address matched flag (slave mode) */ -#define LL_I2C_SR1_BTF I2C_SR1_BTF /*!< Byte Transfer Finished flag */ -#define LL_I2C_SR1_ADD10 I2C_SR1_ADD10 /*!< 10-bit header sent (master mode) */ -#define LL_I2C_SR1_STOPF I2C_SR1_STOPF /*!< Stop detection flag (slave mode) */ -#define LL_I2C_SR1_RXNE I2C_SR1_RXNE /*!< Data register not empty (receivers) */ -#define LL_I2C_SR1_TXE I2C_SR1_TXE /*!< Data register empty (transmitters) */ -#define LL_I2C_SR1_BERR I2C_SR1_BERR /*!< Bus error */ -#define LL_I2C_SR1_ARLO I2C_SR1_ARLO /*!< Arbitration lost */ -#define LL_I2C_SR1_AF I2C_SR1_AF /*!< Acknowledge failure flag */ -#define LL_I2C_SR1_OVR I2C_SR1_OVR /*!< Overrun/Underrun */ -#define LL_I2C_SR1_PECERR I2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */ -#define LL_I2C_SR1_TIMEOUT I2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */ -#define LL_I2C_SR1_SMALERT I2C_ISR_SMALERT /*!< SMBus alert (SMBus mode) */ -#define LL_I2C_SR2_MSL I2C_SR2_MSL /*!< Master/Slave flag */ -#define LL_I2C_SR2_BUSY I2C_SR2_BUSY /*!< Bus busy flag */ -#define LL_I2C_SR2_TRA I2C_SR2_TRA /*!< Transmitter/receiver direction */ -#define LL_I2C_SR2_GENCALL I2C_SR2_GENCALL /*!< General call address (Slave mode) */ -#define LL_I2C_SR2_SMBDEFAULT I2C_SR2_SMBDEFAULT /*!< SMBus Device default address (Slave mode) */ -#define LL_I2C_SR2_SMBHOST I2C_SR2_SMBHOST /*!< SMBus Host address (Slave mode) */ -#define LL_I2C_SR2_DUALF I2C_SR2_DUALF /*!< Dual flag (Slave mode) */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_I2C_ReadReg and LL_I2C_WriteReg functions - * @{ - */ -#define LL_I2C_CR2_ITEVTEN I2C_CR2_ITEVTEN /*!< Events interrupts enable */ -#define LL_I2C_CR2_ITBUFEN I2C_CR2_ITBUFEN /*!< Buffer interrupts enable */ -#define LL_I2C_CR2_ITERREN I2C_CR2_ITERREN /*!< Error interrupts enable */ -/** - * @} - */ - -#if defined(I2C_FLTR_ANOFF) -/** @defgroup I2C_LL_EC_ANALOGFILTER_SELECTION Analog Filter Selection - * @{ - */ -#define LL_I2C_ANALOGFILTER_ENABLE 0x00000000U /*!< Analog filter is enabled. */ -#define LL_I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF /*!< Analog filter is disabled.*/ -/** - * @} - */ - -#endif -/** @defgroup I2C_LL_EC_OWNADDRESS1 Own Address 1 Length - * @{ - */ -#define LL_I2C_OWNADDRESS1_7BIT 0x00004000U /*!< Own address 1 is a 7-bit address. */ -#define LL_I2C_OWNADDRESS1_10BIT (uint32_t)(I2C_OAR1_ADDMODE | 0x00004000U) /*!< Own address 1 is a 10-bit address. */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_DUTYCYCLE Fast Mode Duty Cycle - * @{ - */ -#define LL_I2C_DUTYCYCLE_2 0x00000000U /*!< I2C fast mode Tlow/Thigh = 2 */ -#define LL_I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY /*!< I2C fast mode Tlow/Thigh = 16/9 */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_CLOCK_SPEED_MODE Master Clock Speed Mode - * @{ - */ -#define LL_I2C_CLOCK_SPEED_STANDARD_MODE 0x00000000U /*!< Master clock speed range is standard mode */ -#define LL_I2C_CLOCK_SPEED_FAST_MODE I2C_CCR_FS /*!< Master clock speed range is fast mode */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_PERIPHERAL_MODE Peripheral Mode - * @{ - */ -#define LL_I2C_MODE_I2C 0x00000000U /*!< I2C Master or Slave mode */ -#define LL_I2C_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP) /*!< SMBus Host address acknowledge */ -#define LL_I2C_MODE_SMBUS_DEVICE I2C_CR1_SMBUS /*!< SMBus Device default mode (Default address not acknowledge) */ -#define LL_I2C_MODE_SMBUS_DEVICE_ARP (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_ENARP) /*!< SMBus Device Default address acknowledge */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation - * @{ - */ -#define LL_I2C_ACK I2C_CR1_ACK /*!< ACK is sent after current received byte. */ -#define LL_I2C_NACK 0x00000000U /*!< NACK is sent after current received byte.*/ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_DIRECTION Read Write Direction - * @{ - */ -#define LL_I2C_DIRECTION_WRITE I2C_SR2_TRA /*!< Bus is in write transfer */ -#define LL_I2C_DIRECTION_READ 0x00000000U /*!< Bus is in read transfer */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup I2C_LL_Exported_Macros I2C Exported Macros - * @{ - */ - -/** @defgroup I2C_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in I2C register - * @param __INSTANCE__ I2C Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_I2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in I2C register - * @param __INSTANCE__ I2C Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_I2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup I2C_LL_EM_Exported_Macros_Helper Exported_Macros_Helper - * @{ - */ - -/** - * @brief Convert Peripheral Clock Frequency in Mhz. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @retval Value of peripheral clock (in Mhz) - */ -#define __LL_I2C_FREQ_HZ_TO_MHZ(__PCLK__) (uint32_t)((__PCLK__)/1000000U) - -/** - * @brief Convert Peripheral Clock Frequency in Hz. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Mhz). - * @retval Value of peripheral clock (in Hz) - */ -#define __LL_I2C_FREQ_MHZ_TO_HZ(__PCLK__) (uint32_t)((__PCLK__)*1000000U) - -/** - * @brief Compute I2C Clock rising time. - * @param __FREQRANGE__ This parameter must be a value of peripheral clock (in Mhz). - * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz). - * @retval Value between Min_Data=0x02 and Max_Data=0x3F - */ -#define __LL_I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U)) - -/** - * @brief Compute Speed clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz). - * @param __DUTYCYCLE__ This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - */ -#define __LL_I2C_SPEED_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD)? \ - (__LL_I2C_SPEED_STANDARD_TO_CCR((__PCLK__), (__SPEED__))) : \ - (__LL_I2C_SPEED_FAST_TO_CCR((__PCLK__), (__SPEED__), (__DUTYCYCLE__)))) - -/** - * @brief Compute Speed Standard clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value lower than 100kHz (in Hz). - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF. - */ -#define __LL_I2C_SPEED_STANDARD_TO_CCR(__PCLK__, __SPEED__) (uint32_t)(((((__PCLK__)/((__SPEED__) << 1U)) & I2C_CCR_CCR) < 4U)? 4U:((__PCLK__) / ((__SPEED__) << 1U))) - -/** - * @brief Compute Speed Fast clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value between Min_Data=100Khz and Max_Data=400Khz (in Hz). - * @param __DUTYCYCLE__ This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval Value between Min_Data=0x001 and Max_Data=0xFFF - */ -#define __LL_I2C_SPEED_FAST_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__DUTYCYCLE__) == LL_I2C_DUTYCYCLE_2)? \ - (((((__PCLK__) / ((__SPEED__) * 3U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 3U))) : \ - (((((__PCLK__) / ((__SPEED__) * 25U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 25U)))) - -/** - * @brief Get the Least significant bits of a 10-Bits address. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -#define __LL_I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FF)))) - -/** - * @brief Convert a 10-Bits address to a 10-Bits header with Write direction. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0xF0 and Max_Data=0xF6 - */ -#define __LL_I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF0)))) - -/** - * @brief Convert a 10-Bits address to a 10-Bits header with Read direction. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0xF1 and Max_Data=0xF7 - */ -#define __LL_I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF1)))) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup I2C_LL_Exported_Functions I2C Exported Functions - * @{ - */ - -/** @defgroup I2C_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Enable I2C peripheral (PE = 1). - * @rmtoll CR1 PE LL_I2C_Enable - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_Enable(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Disable I2C peripheral (PE = 0). - * @rmtoll CR1 PE LL_I2C_Disable - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_Disable(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Check if the I2C peripheral is enabled or disabled. - * @rmtoll CR1 PE LL_I2C_IsEnabled - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabled(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_PE) == (I2C_CR1_PE)); -} - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/** - * @brief Configure Noise Filters (Analog and Digital). - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * The filters can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_ConfigFilters\n - * FLTR DNF LL_I2C_ConfigFilters - * @param I2Cx I2C Instance. - * @param AnalogFilter This parameter can be one of the following values: - * @arg @ref LL_I2C_ANALOGFILTER_ENABLE - * @arg @ref LL_I2C_ANALOGFILTER_DISABLE - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1) - * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ConfigFilters(I2C_TypeDef *I2Cx, uint32_t AnalogFilter, uint32_t DigitalFilter) -{ - MODIFY_REG(I2Cx->FLTR, I2C_FLTR_ANOFF | I2C_FLTR_DNF, AnalogFilter | DigitalFilter); -} -#endif -#if defined(I2C_FLTR_DNF) - -/** - * @brief Configure Digital Noise Filter. - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR DNF LL_I2C_SetDigitalFilter - * @param I2Cx I2C Instance. - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1) - * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetDigitalFilter(I2C_TypeDef *I2Cx, uint32_t DigitalFilter) -{ - MODIFY_REG(I2Cx->FLTR, I2C_FLTR_DNF, DigitalFilter); -} - -/** - * @brief Get the current Digital Noise Filter configuration. - * @rmtoll FLTR DNF LL_I2C_GetDigitalFilter - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_I2C_GetDigitalFilter(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->FLTR, I2C_FLTR_DNF)); -} -#endif -#if defined(I2C_FLTR_ANOFF) - -/** - * @brief Enable Analog Noise Filter. - * @note This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_EnableAnalogFilter - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableAnalogFilter(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF); -} - -/** - * @brief Disable Analog Noise Filter. - * @note This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_DisableAnalogFilter - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableAnalogFilter(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF); -} - -/** - * @brief Check if Analog Noise Filter is enabled or disabled. - * @rmtoll FLTR ANOFF LL_I2C_IsEnabledAnalogFilter - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledAnalogFilter(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF) == (I2C_FLTR_ANOFF)); -} -#endif - -/** - * @brief Enable DMA transmission requests. - * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableDMAReq_TX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Disable DMA transmission requests. - * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableDMAReq_TX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Check if DMA transmission requests are enabled or disabled. - * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_TX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_TX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN)); -} - -/** - * @brief Enable DMA reception requests. - * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableDMAReq_RX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Disable DMA reception requests. - * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableDMAReq_RX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Check if DMA reception requests are enabled or disabled. - * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_RX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_RX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN)); -} - -/** - * @brief Get the data register address used for DMA transfer. - * @rmtoll DR DR LL_I2C_DMA_GetRegAddr - * @param I2Cx I2C Instance. - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_I2C_DMA_GetRegAddr(I2C_TypeDef *I2Cx) -{ - return (uint32_t) & (I2Cx->DR); -} - -/** - * @brief Enable Clock stretching. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_I2C_EnableClockStretching - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableClockStretching(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); -} - -/** - * @brief Disable Clock stretching. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_I2C_DisableClockStretching - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableClockStretching(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); -} - -/** - * @brief Check if Clock stretching is enabled or disabled. - * @rmtoll CR1 NOSTRETCH LL_I2C_IsEnabledClockStretching - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledClockStretching(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH) != (I2C_CR1_NOSTRETCH)); -} - -/** - * @brief Enable General Call. - * @note When enabled the Address 0x00 is ACKed. - * @rmtoll CR1 ENGC LL_I2C_EnableGeneralCall - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableGeneralCall(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ENGC); -} - -/** - * @brief Disable General Call. - * @note When disabled the Address 0x00 is NACKed. - * @rmtoll CR1 ENGC LL_I2C_DisableGeneralCall - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableGeneralCall(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENGC); -} - -/** - * @brief Check if General Call is enabled or disabled. - * @rmtoll CR1 ENGC LL_I2C_IsEnabledGeneralCall - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledGeneralCall(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ENGC) == (I2C_CR1_ENGC)); -} - -/** - * @brief Set the Own Address1. - * @rmtoll OAR1 ADD0 LL_I2C_SetOwnAddress1\n - * OAR1 ADD1_7 LL_I2C_SetOwnAddress1\n - * OAR1 ADD8_9 LL_I2C_SetOwnAddress1\n - * OAR1 ADDMODE LL_I2C_SetOwnAddress1 - * @param I2Cx I2C Instance. - * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF. - * @param OwnAddrSize This parameter can be one of the following values: - * @arg @ref LL_I2C_OWNADDRESS1_7BIT - * @arg @ref LL_I2C_OWNADDRESS1_10BIT - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetOwnAddress1(I2C_TypeDef *I2Cx, uint32_t OwnAddress1, uint32_t OwnAddrSize) -{ - MODIFY_REG(I2Cx->OAR1, I2C_OAR1_ADD0 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD8_9 | I2C_OAR1_ADDMODE, OwnAddress1 | OwnAddrSize); -} - -/** - * @brief Set the 7bits Own Address2. - * @note This action has no effect if own address2 is enabled. - * @rmtoll OAR2 ADD2 LL_I2C_SetOwnAddress2 - * @param I2Cx I2C Instance. - * @param OwnAddress2 This parameter must be a value between Min_Data=0 and Max_Data=0x7F. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetOwnAddress2(I2C_TypeDef *I2Cx, uint32_t OwnAddress2) -{ - MODIFY_REG(I2Cx->OAR2, I2C_OAR2_ADD2, OwnAddress2); -} - -/** - * @brief Enable acknowledge on Own Address2 match address. - * @rmtoll OAR2 ENDUAL LL_I2C_EnableOwnAddress2 - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableOwnAddress2(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL); -} - -/** - * @brief Disable acknowledge on Own Address2 match address. - * @rmtoll OAR2 ENDUAL LL_I2C_DisableOwnAddress2 - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableOwnAddress2(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL); -} - -/** - * @brief Check if Own Address1 acknowledge is enabled or disabled. - * @rmtoll OAR2 ENDUAL LL_I2C_IsEnabledOwnAddress2 - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledOwnAddress2(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL) == (I2C_OAR2_ENDUAL)); -} - -/** - * @brief Configure the Peripheral clock frequency. - * @rmtoll CR2 FREQ LL_I2C_SetPeriphClock - * @param I2Cx I2C Instance. - * @param PeriphClock Peripheral Clock (in Hz) - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetPeriphClock(I2C_TypeDef *I2Cx, uint32_t PeriphClock) -{ - MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock)); -} - -/** - * @brief Get the Peripheral clock frequency. - * @rmtoll CR2 FREQ LL_I2C_GetPeriphClock - * @param I2Cx I2C Instance. - * @retval Value of Peripheral Clock (in Hz) - */ -__STATIC_INLINE uint32_t LL_I2C_GetPeriphClock(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(__LL_I2C_FREQ_MHZ_TO_HZ(READ_BIT(I2Cx->CR2, I2C_CR2_FREQ))); -} - -/** - * @brief Configure the Duty cycle (Fast mode only). - * @rmtoll CCR DUTY LL_I2C_SetDutyCycle - * @param I2Cx I2C Instance. - * @param DutyCycle This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetDutyCycle(I2C_TypeDef *I2Cx, uint32_t DutyCycle) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_DUTY, DutyCycle); -} - -/** - * @brief Get the Duty cycle (Fast mode only). - * @rmtoll CCR DUTY LL_I2C_GetDutyCycle - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - */ -__STATIC_INLINE uint32_t LL_I2C_GetDutyCycle(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_DUTY)); -} - -/** - * @brief Configure the I2C master clock speed mode. - * @rmtoll CCR FS LL_I2C_SetClockSpeedMode - * @param I2Cx I2C Instance. - * @param ClockSpeedMode This parameter can be one of the following values: - * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE - * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetClockSpeedMode(I2C_TypeDef *I2Cx, uint32_t ClockSpeedMode) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_FS, ClockSpeedMode); -} - -/** - * @brief Get the the I2C master speed mode. - * @rmtoll CCR FS LL_I2C_GetClockSpeedMode - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE - * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE - */ -__STATIC_INLINE uint32_t LL_I2C_GetClockSpeedMode(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_FS)); -} - -/** - * @brief Configure the SCL, SDA rising time. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll TRISE TRISE LL_I2C_SetRiseTime - * @param I2Cx I2C Instance. - * @param RiseTime This parameter must be a value between Min_Data=0x02 and Max_Data=0x3F. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetRiseTime(I2C_TypeDef *I2Cx, uint32_t RiseTime) -{ - MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, RiseTime); -} - -/** - * @brief Get the SCL, SDA rising time. - * @rmtoll TRISE TRISE LL_I2C_GetRiseTime - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x02 and Max_Data=0x3F - */ -__STATIC_INLINE uint32_t LL_I2C_GetRiseTime(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->TRISE, I2C_TRISE_TRISE)); -} - -/** - * @brief Configure the SCL high and low period. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CCR CCR LL_I2C_SetClockPeriod - * @param I2Cx I2C Instance. - * @param ClockPeriod This parameter must be a value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetClockPeriod(I2C_TypeDef *I2Cx, uint32_t ClockPeriod) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_CCR, ClockPeriod); -} - -/** - * @brief Get the SCL high and low period. - * @rmtoll CCR CCR LL_I2C_GetClockPeriod - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - */ -__STATIC_INLINE uint32_t LL_I2C_GetClockPeriod(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_CCR)); -} - -/** - * @brief Configure the SCL speed. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR2 FREQ LL_I2C_ConfigSpeed\n - * TRISE TRISE LL_I2C_ConfigSpeed\n - * CCR FS LL_I2C_ConfigSpeed\n - * CCR DUTY LL_I2C_ConfigSpeed\n - * CCR CCR LL_I2C_ConfigSpeed - * @param I2Cx I2C Instance. - * @param PeriphClock Peripheral Clock (in Hz) - * @param ClockSpeed This parameter must be a value lower than 400kHz (in Hz). - * @param DutyCycle This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval None - */ -__STATIC_INLINE void LL_I2C_ConfigSpeed(I2C_TypeDef *I2Cx, uint32_t PeriphClock, uint32_t ClockSpeed, - uint32_t DutyCycle) -{ - uint32_t freqrange = 0x0U; - uint32_t clockconfig = 0x0U; - - /* Compute frequency range */ - freqrange = __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock); - - /* Configure I2Cx: Frequency range register */ - MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, freqrange); - - /* Configure I2Cx: Rise Time register */ - MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, __LL_I2C_RISE_TIME(freqrange, ClockSpeed)); - - /* Configure Speed mode, Duty Cycle and Clock control register value */ - if (ClockSpeed > LL_I2C_MAX_SPEED_STANDARD) - { - /* Set Speed mode at fast and duty cycle for Clock Speed request in fast clock range */ - clockconfig = LL_I2C_CLOCK_SPEED_FAST_MODE | \ - __LL_I2C_SPEED_FAST_TO_CCR(PeriphClock, ClockSpeed, DutyCycle) | \ - DutyCycle; - } - else - { - /* Set Speed mode at standard for Clock Speed request in standard clock range */ - clockconfig = LL_I2C_CLOCK_SPEED_STANDARD_MODE | \ - __LL_I2C_SPEED_STANDARD_TO_CCR(PeriphClock, ClockSpeed); - } - - /* Configure I2Cx: Clock control register */ - MODIFY_REG(I2Cx->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), clockconfig); -} - -/** - * @brief Configure peripheral mode. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 SMBUS LL_I2C_SetMode\n - * CR1 SMBTYPE LL_I2C_SetMode\n - * CR1 ENARP LL_I2C_SetMode - * @param I2Cx I2C Instance. - * @param PeripheralMode This parameter can be one of the following values: - * @arg @ref LL_I2C_MODE_I2C - * @arg @ref LL_I2C_MODE_SMBUS_HOST - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetMode(I2C_TypeDef *I2Cx, uint32_t PeripheralMode) -{ - MODIFY_REG(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP, PeripheralMode); -} - -/** - * @brief Get peripheral mode. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 SMBUS LL_I2C_GetMode\n - * CR1 SMBTYPE LL_I2C_GetMode\n - * CR1 ENARP LL_I2C_GetMode - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_MODE_I2C - * @arg @ref LL_I2C_MODE_SMBUS_HOST - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP - */ -__STATIC_INLINE uint32_t LL_I2C_GetMode(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP)); -} - -/** - * @brief Enable SMBus alert (Host or Device mode) - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is drived low and - * Alert Response Address Header acknowledge is enabled. - * SMBus Host mode: - * - SMBus Alert pin management is supported. - * @rmtoll CR1 ALERT LL_I2C_EnableSMBusAlert - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusAlert(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ALERT); -} - -/** - * @brief Disable SMBus alert (Host or Device mode) - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is not drived (can be used as a standard GPIO) and - * Alert Response Address Header acknowledge is disabled. - * SMBus Host mode: - * - SMBus Alert pin management is not supported. - * @rmtoll CR1 ALERT LL_I2C_DisableSMBusAlert - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusAlert(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ALERT); -} - -/** - * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ALERT LL_I2C_IsEnabledSMBusAlert - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusAlert(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ALERT) == (I2C_CR1_ALERT)); -} - -/** - * @brief Enable SMBus Packet Error Calculation (PEC). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_EnableSMBusPEC - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusPEC(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ENPEC); -} - -/** - * @brief Disable SMBus Packet Error Calculation (PEC). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_DisableSMBusPEC - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusPEC(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENPEC); -} - -/** - * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_IsEnabledSMBusPEC - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPEC(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ENPEC) == (I2C_CR1_ENPEC)); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable TXE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_TX\n - * CR2 ITBUFEN LL_I2C_EnableIT_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_TX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable TXE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_TX\n - * CR2 ITBUFEN LL_I2C_DisableIT_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_TX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if the TXE Interrupt is enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_TX\n - * CR2 ITBUFEN LL_I2C_IsEnabledIT_TX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_TX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable RXNE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_RX\n - * CR2 ITBUFEN LL_I2C_EnableIT_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_RX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable RXNE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_RX\n - * CR2 ITBUFEN LL_I2C_DisableIT_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_RX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if the RXNE Interrupt is enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_RX\n - * CR2 ITBUFEN LL_I2C_IsEnabledIT_RX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_RX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable Events interrupts. - * @note Any of these events will generate interrupt : - * Start Bit (SB) - * Address sent, Address matched (ADDR) - * 10-bit header sent (ADD10) - * Stop detection (STOPF) - * Byte transfer finished (BTF) - * - * @note Any of these events will generate interrupt if Buffer interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_BUF()) : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_EVT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_EVT(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN); -} - -/** - * @brief Disable Events interrupts. - * @note Any of these events will generate interrupt : - * Start Bit (SB) - * Address sent, Address matched (ADDR) - * 10-bit header sent (ADD10) - * Stop detection (STOPF) - * Byte transfer finished (BTF) - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_EVT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_EVT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN); -} - -/** - * @brief Check if Events interrupts are enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_EVT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_EVT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN) == (I2C_CR2_ITEVTEN)); -} - -/** - * @brief Enable Buffer interrupts. - * @note Any of these Buffer events will generate interrupt if Events interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_EVT()) : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITBUFEN LL_I2C_EnableIT_BUF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_BUF(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable Buffer interrupts. - * @note Any of these Buffer events will generate interrupt : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITBUFEN LL_I2C_DisableIT_BUF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_BUF(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if Buffer interrupts are enabled or disabled. - * @rmtoll CR2 ITBUFEN LL_I2C_IsEnabledIT_BUF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_BUF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN) == (I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable Error interrupts. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note Any of these errors will generate interrupt : - * Bus Error detection (BERR) - * Arbitration Loss (ARLO) - * Acknowledge Failure(AF) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (SMBALERT) - * @rmtoll CR2 ITERREN LL_I2C_EnableIT_ERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_ERR(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITERREN); -} - -/** - * @brief Disable Error interrupts. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note Any of these errors will generate interrupt : - * Bus Error detection (BERR) - * Arbitration Loss (ARLO) - * Acknowledge Failure(AF) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (SMBALERT) - * @rmtoll CR2 ITERREN LL_I2C_DisableIT_ERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_ERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITERREN); -} - -/** - * @brief Check if Error interrupts are enabled or disabled. - * @rmtoll CR2 ITERREN LL_I2C_IsEnabledIT_ERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_ERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITERREN) == (I2C_CR2_ITERREN)); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_FLAG_management FLAG_management - * @{ - */ - -/** - * @brief Indicate the status of Transmit data register empty flag. - * @note RESET: When next data is written in Transmit data register. - * SET: When Transmit data register is empty. - * @rmtoll SR1 TXE LL_I2C_IsActiveFlag_TXE - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TXE(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_TXE) == (I2C_SR1_TXE)); -} - -/** - * @brief Indicate the status of Byte Transfer Finished flag. - * RESET: When Data byte transfer not done. - * SET: When Data byte transfer succeeded. - * @rmtoll SR1 BTF LL_I2C_IsActiveFlag_BTF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BTF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_BTF) == (I2C_SR1_BTF)); -} - -/** - * @brief Indicate the status of Receive data register not empty flag. - * @note RESET: When Receive data register is read. - * SET: When the received data is copied in Receive data register. - * @rmtoll SR1 RXNE LL_I2C_IsActiveFlag_RXNE - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_RXNE(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_RXNE) == (I2C_SR1_RXNE)); -} - -/** - * @brief Indicate the status of Start Bit (master mode). - * @note RESET: When No Start condition. - * SET: When Start condition is generated. - * @rmtoll SR1 SB LL_I2C_IsActiveFlag_SB - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_SB(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_SB) == (I2C_SR1_SB)); -} - -/** - * @brief Indicate the status of Address sent (master mode) or Address matched flag (slave mode). - * @note RESET: Clear default value. - * SET: When the address is fully sent (master mode) or when the received slave address matched with one of the enabled slave address (slave mode). - * @rmtoll SR1 ADDR LL_I2C_IsActiveFlag_ADDR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADDR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ADDR) == (I2C_SR1_ADDR)); -} - -/** - * @brief Indicate the status of 10-bit header sent (master mode). - * @note RESET: When no ADD10 event occurred. - * SET: When the master has sent the first address byte (header). - * @rmtoll SR1 ADD10 LL_I2C_IsActiveFlag_ADD10 - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADD10(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ADD10) == (I2C_SR1_ADD10)); -} - -/** - * @brief Indicate the status of Acknowledge failure flag. - * @note RESET: No acknowledge failure. - * SET: When an acknowledge failure is received after a byte transmission. - * @rmtoll SR1 AF LL_I2C_IsActiveFlag_AF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_AF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_AF) == (I2C_SR1_AF)); -} - -/** - * @brief Indicate the status of Stop detection flag (slave mode). - * @note RESET: Clear default value. - * SET: When a Stop condition is detected. - * @rmtoll SR1 STOPF LL_I2C_IsActiveFlag_STOP - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_STOP(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_STOPF) == (I2C_SR1_STOPF)); -} - -/** - * @brief Indicate the status of Bus error flag. - * @note RESET: Clear default value. - * SET: When a misplaced Start or Stop condition is detected. - * @rmtoll SR1 BERR LL_I2C_IsActiveFlag_BERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_BERR) == (I2C_SR1_BERR)); -} - -/** - * @brief Indicate the status of Arbitration lost flag. - * @note RESET: Clear default value. - * SET: When arbitration lost. - * @rmtoll SR1 ARLO LL_I2C_IsActiveFlag_ARLO - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ARLO(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ARLO) == (I2C_SR1_ARLO)); -} - -/** - * @brief Indicate the status of Overrun/Underrun flag. - * @note RESET: Clear default value. - * SET: When an overrun/underrun error occurs (Clock Stretching Disabled). - * @rmtoll SR1 OVR LL_I2C_IsActiveFlag_OVR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_OVR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_OVR) == (I2C_SR1_OVR)); -} - -/** - * @brief Indicate the status of SMBus PEC error flag in reception. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 PECERR LL_I2C_IsActiveSMBusFlag_PECERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_PECERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_PECERR) == (I2C_SR1_PECERR)); -} - -/** - * @brief Indicate the status of SMBus Timeout detection flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 TIMEOUT LL_I2C_IsActiveSMBusFlag_TIMEOUT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT) == (I2C_SR1_TIMEOUT)); -} - -/** - * @brief Indicate the status of SMBus alert flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 SMBALERT LL_I2C_IsActiveSMBusFlag_ALERT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_ALERT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_SMBALERT) == (I2C_SR1_SMBALERT)); -} - -/** - * @brief Indicate the status of Bus Busy flag. - * @note RESET: Clear default value. - * SET: When a Start condition is detected. - * @rmtoll SR2 BUSY LL_I2C_IsActiveFlag_BUSY - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BUSY(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_BUSY) == (I2C_SR2_BUSY)); -} - -/** - * @brief Indicate the status of Dual flag. - * @note RESET: Received address matched with OAR1. - * SET: Received address matched with OAR2. - * @rmtoll SR2 DUALF LL_I2C_IsActiveFlag_DUAL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_DUAL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_DUALF) == (I2C_SR2_DUALF)); -} - -/** - * @brief Indicate the status of SMBus Host address reception (Slave mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note RESET: No SMBus Host address - * SET: SMBus Host address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 SMBHOST LL_I2C_IsActiveSMBusFlag_SMBHOST - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBHOST(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBHOST) == (I2C_SR2_SMBHOST)); -} - -/** - * @brief Indicate the status of SMBus Device default address reception (Slave mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note RESET: No SMBus Device default address - * SET: SMBus Device default address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 SMBDEFAULT LL_I2C_IsActiveSMBusFlag_SMBDEFAULT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBDEFAULT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBDEFAULT) == (I2C_SR2_SMBDEFAULT)); -} - -/** - * @brief Indicate the status of General call address reception (Slave mode). - * @note RESET: No General call address - * SET: General call address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 GENCALL LL_I2C_IsActiveFlag_GENCALL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_GENCALL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_GENCALL) == (I2C_SR2_GENCALL)); -} - -/** - * @brief Indicate the status of Master/Slave flag. - * @note RESET: Slave Mode. - * SET: Master Mode. - * @rmtoll SR2 MSL LL_I2C_IsActiveFlag_MSL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_MSL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_MSL) == (I2C_SR2_MSL)); -} - -/** - * @brief Clear Address Matched flag. - * @note Clearing this flag is done by a read access to the I2Cx_SR1 - * register followed by a read access to the I2Cx_SR2 register. - * @rmtoll SR1 ADDR LL_I2C_ClearFlag_ADDR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_ADDR(I2C_TypeDef *I2Cx) -{ - __IO uint32_t tmpreg; - tmpreg = I2Cx->SR1; - (void) tmpreg; - tmpreg = I2Cx->SR2; - (void) tmpreg; -} - -/** - * @brief Clear Acknowledge failure flag. - * @rmtoll SR1 AF LL_I2C_ClearFlag_AF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_AF(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_AF); -} - -/** - * @brief Clear Stop detection flag. - * @note Clearing this flag is done by a read access to the I2Cx_SR1 - * register followed by a write access to I2Cx_CR1 register. - * @rmtoll SR1 STOPF LL_I2C_ClearFlag_STOP\n - * CR1 PE LL_I2C_ClearFlag_STOP - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_STOP(I2C_TypeDef *I2Cx) -{ - __IO uint32_t tmpreg; - tmpreg = I2Cx->SR1; - (void) tmpreg; - SET_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Clear Bus error flag. - * @rmtoll SR1 BERR LL_I2C_ClearFlag_BERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_BERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_BERR); -} - -/** - * @brief Clear Arbitration lost flag. - * @rmtoll SR1 ARLO LL_I2C_ClearFlag_ARLO - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_ARLO(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_ARLO); -} - -/** - * @brief Clear Overrun/Underrun flag. - * @rmtoll SR1 OVR LL_I2C_ClearFlag_OVR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_OVR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_OVR); -} - -/** - * @brief Clear SMBus PEC error flag. - * @rmtoll SR1 PECERR LL_I2C_ClearSMBusFlag_PECERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_PECERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_PECERR); -} - -/** - * @brief Clear SMBus Timeout detection flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 TIMEOUT LL_I2C_ClearSMBusFlag_TIMEOUT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT); -} - -/** - * @brief Clear SMBus Alert flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 SMBALERT LL_I2C_ClearSMBusFlag_ALERT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_ALERT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_SMBALERT); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Enable Reset of I2C peripheral. - * @rmtoll CR1 SWRST LL_I2C_EnableReset - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableReset(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_SWRST); -} - -/** - * @brief Disable Reset of I2C peripheral. - * @rmtoll CR1 SWRST LL_I2C_DisableReset - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableReset(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_SWRST); -} - -/** - * @brief Check if the I2C peripheral is under reset state or not. - * @rmtoll CR1 SWRST LL_I2C_IsResetEnabled - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsResetEnabled(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_SWRST) == (I2C_CR1_SWRST)); -} - -/** - * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte. - * @note Usage in Slave or Master mode. - * @rmtoll CR1 ACK LL_I2C_AcknowledgeNextData - * @param I2Cx I2C Instance. - * @param TypeAcknowledge This parameter can be one of the following values: - * @arg @ref LL_I2C_ACK - * @arg @ref LL_I2C_NACK - * @retval None - */ -__STATIC_INLINE void LL_I2C_AcknowledgeNextData(I2C_TypeDef *I2Cx, uint32_t TypeAcknowledge) -{ - MODIFY_REG(I2Cx->CR1, I2C_CR1_ACK, TypeAcknowledge); -} - -/** - * @brief Generate a START or RESTART condition - * @note The START bit can be set even if bus is BUSY or I2C is in slave mode. - * This action has no effect when RELOAD is set. - * @rmtoll CR1 START LL_I2C_GenerateStartCondition - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_GenerateStartCondition(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_START); -} - -/** - * @brief Generate a STOP condition after the current byte transfer (master mode). - * @rmtoll CR1 STOP LL_I2C_GenerateStopCondition - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_GenerateStopCondition(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_STOP); -} - -/** - * @brief Enable bit POS (master/host mode). - * @note In that case, the ACK bit controls the (N)ACK of the next byte received or the PEC bit indicates that the next byte in shift register is a PEC. - * @rmtoll CR1 POS LL_I2C_EnableBitPOS - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableBitPOS(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_POS); -} - -/** - * @brief Disable bit POS (master/host mode). - * @note In that case, the ACK bit controls the (N)ACK of the current byte received or the PEC bit indicates that the current byte in shift register is a PEC. - * @rmtoll CR1 POS LL_I2C_DisableBitPOS - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableBitPOS(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_POS); -} - -/** - * @brief Check if bit POS is enabled or disabled. - * @rmtoll CR1 POS LL_I2C_IsEnabledBitPOS - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledBitPOS(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_POS) == (I2C_CR1_POS)); -} - -/** - * @brief Indicate the value of transfer direction. - * @note RESET: Bus is in read transfer (peripheral point of view). - * SET: Bus is in write transfer (peripheral point of view). - * @rmtoll SR2 TRA LL_I2C_GetTransferDirection - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_DIRECTION_WRITE - * @arg @ref LL_I2C_DIRECTION_READ - */ -__STATIC_INLINE uint32_t LL_I2C_GetTransferDirection(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_TRA)); -} - -/** - * @brief Enable DMA last transfer. - * @note This action mean that next DMA EOT is the last transfer. - * @rmtoll CR2 LAST LL_I2C_EnableLastDMA - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableLastDMA(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_LAST); -} - -/** - * @brief Disable DMA last transfer. - * @note This action mean that next DMA EOT is not the last transfer. - * @rmtoll CR2 LAST LL_I2C_DisableLastDMA - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableLastDMA(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_LAST); -} - -/** - * @brief Check if DMA last transfer is enabled or disabled. - * @rmtoll CR2 LAST LL_I2C_IsEnabledLastDMA - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledLastDMA(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_LAST) == (I2C_CR2_LAST)); -} - -/** - * @brief Enable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note This feature is cleared by hardware when the PEC byte is transferred or compared, - * or by a START or STOP condition, it is also cleared by software. - * @rmtoll CR1 PEC LL_I2C_EnableSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_PEC); -} - -/** - * @brief Disable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 PEC LL_I2C_DisableSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_PEC); -} - -/** - * @brief Check if the SMBus Packet Error byte transfer or internal comparison is requested or not. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 PEC LL_I2C_IsEnabledSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_PEC) == (I2C_CR1_PEC)); -} - -/** - * @brief Get the SMBus Packet Error byte calculated. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR2 PEC LL_I2C_GetSMBusPEC - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_I2C_GetSMBusPEC(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_PEC) >> I2C_SR2_PEC_Pos); -} - -/** - * @brief Read Receive Data register. - * @rmtoll DR DR LL_I2C_ReceiveData8 - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_I2C_ReceiveData8(I2C_TypeDef *I2Cx) -{ - return (uint8_t)(READ_BIT(I2Cx->DR, I2C_DR_DR)); -} - -/** - * @brief Write in Transmit Data Register . - * @rmtoll DR DR LL_I2C_TransmitData8 - * @param I2Cx I2C Instance. - * @param Data Value between Min_Data=0x0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_I2C_TransmitData8(I2C_TypeDef *I2Cx, uint8_t Data) -{ - MODIFY_REG(I2Cx->DR, I2C_DR_DR, Data); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_I2C_Init(I2C_TypeDef *I2Cx, LL_I2C_InitTypeDef *I2C_InitStruct); -uint32_t LL_I2C_DeInit(I2C_TypeDef *I2Cx); -void LL_I2C_StructInit(LL_I2C_InitTypeDef *I2C_InitStruct); - - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* I2C1 || I2C2 || I2C3 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_I2C_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h deleted file mode 100644 index 2f1b844a9cea8f1..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h +++ /dev/null @@ -1,305 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_iwdg.h - * @author MCD Application Team - * @brief Header file of IWDG LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_IWDG_H -#define STM32F4xx_LL_IWDG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(IWDG) - -/** @defgroup IWDG_LL IWDG - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup IWDG_LL_Private_Constants IWDG Private Constants - * @{ - */ -#define LL_IWDG_KEY_RELOAD 0x0000AAAAU /*!< IWDG Reload Counter Enable */ -#define LL_IWDG_KEY_ENABLE 0x0000CCCCU /*!< IWDG Peripheral Enable */ -#define LL_IWDG_KEY_WR_ACCESS_ENABLE 0x00005555U /*!< IWDG KR Write Access Enable */ -#define LL_IWDG_KEY_WR_ACCESS_DISABLE 0x00000000U /*!< IWDG KR Write Access Disable */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup IWDG_LL_Exported_Constants IWDG Exported Constants - * @{ - */ - -/** @defgroup IWDG_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_IWDG_ReadReg function - * @{ - */ -#define LL_IWDG_SR_PVU IWDG_SR_PVU /*!< Watchdog prescaler value update */ -#define LL_IWDG_SR_RVU IWDG_SR_RVU /*!< Watchdog counter reload value update */ -/** - * @} - */ - -/** @defgroup IWDG_LL_EC_PRESCALER Prescaler Divider - * @{ - */ -#define LL_IWDG_PRESCALER_4 0x00000000U /*!< Divider by 4 */ -#define LL_IWDG_PRESCALER_8 (IWDG_PR_PR_0) /*!< Divider by 8 */ -#define LL_IWDG_PRESCALER_16 (IWDG_PR_PR_1) /*!< Divider by 16 */ -#define LL_IWDG_PRESCALER_32 (IWDG_PR_PR_1 | IWDG_PR_PR_0) /*!< Divider by 32 */ -#define LL_IWDG_PRESCALER_64 (IWDG_PR_PR_2) /*!< Divider by 64 */ -#define LL_IWDG_PRESCALER_128 (IWDG_PR_PR_2 | IWDG_PR_PR_0) /*!< Divider by 128 */ -#define LL_IWDG_PRESCALER_256 (IWDG_PR_PR_2 | IWDG_PR_PR_1) /*!< Divider by 256 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup IWDG_LL_Exported_Macros IWDG Exported Macros - * @{ - */ - -/** @defgroup IWDG_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in IWDG register - * @param __INSTANCE__ IWDG Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_IWDG_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in IWDG register - * @param __INSTANCE__ IWDG Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_IWDG_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup IWDG_LL_Exported_Functions IWDG Exported Functions - * @{ - */ -/** @defgroup IWDG_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Start the Independent Watchdog - * @note Except if the hardware watchdog option is selected - * @rmtoll KR KEY LL_IWDG_Enable - * @param IWDGx IWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_IWDG_Enable(IWDG_TypeDef *IWDGx) -{ - WRITE_REG(IWDGx->KR, LL_IWDG_KEY_ENABLE); -} - -/** - * @brief Reloads IWDG counter with value defined in the reload register - * @rmtoll KR KEY LL_IWDG_ReloadCounter - * @param IWDGx IWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_IWDG_ReloadCounter(IWDG_TypeDef *IWDGx) -{ - WRITE_REG(IWDGx->KR, LL_IWDG_KEY_RELOAD); -} - -/** - * @brief Enable write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers - * @rmtoll KR KEY LL_IWDG_EnableWriteAccess - * @param IWDGx IWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_IWDG_EnableWriteAccess(IWDG_TypeDef *IWDGx) -{ - WRITE_REG(IWDGx->KR, LL_IWDG_KEY_WR_ACCESS_ENABLE); -} - -/** - * @brief Disable write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers - * @rmtoll KR KEY LL_IWDG_DisableWriteAccess - * @param IWDGx IWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_IWDG_DisableWriteAccess(IWDG_TypeDef *IWDGx) -{ - WRITE_REG(IWDGx->KR, LL_IWDG_KEY_WR_ACCESS_DISABLE); -} - -/** - * @brief Select the prescaler of the IWDG - * @rmtoll PR PR LL_IWDG_SetPrescaler - * @param IWDGx IWDG Instance - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_IWDG_PRESCALER_4 - * @arg @ref LL_IWDG_PRESCALER_8 - * @arg @ref LL_IWDG_PRESCALER_16 - * @arg @ref LL_IWDG_PRESCALER_32 - * @arg @ref LL_IWDG_PRESCALER_64 - * @arg @ref LL_IWDG_PRESCALER_128 - * @arg @ref LL_IWDG_PRESCALER_256 - * @retval None - */ -__STATIC_INLINE void LL_IWDG_SetPrescaler(IWDG_TypeDef *IWDGx, uint32_t Prescaler) -{ - WRITE_REG(IWDGx->PR, IWDG_PR_PR & Prescaler); -} - -/** - * @brief Get the selected prescaler of the IWDG - * @rmtoll PR PR LL_IWDG_GetPrescaler - * @param IWDGx IWDG Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_IWDG_PRESCALER_4 - * @arg @ref LL_IWDG_PRESCALER_8 - * @arg @ref LL_IWDG_PRESCALER_16 - * @arg @ref LL_IWDG_PRESCALER_32 - * @arg @ref LL_IWDG_PRESCALER_64 - * @arg @ref LL_IWDG_PRESCALER_128 - * @arg @ref LL_IWDG_PRESCALER_256 - */ -__STATIC_INLINE uint32_t LL_IWDG_GetPrescaler(IWDG_TypeDef *IWDGx) -{ - return (READ_REG(IWDGx->PR)); -} - -/** - * @brief Specify the IWDG down-counter reload value - * @rmtoll RLR RL LL_IWDG_SetReloadCounter - * @param IWDGx IWDG Instance - * @param Counter Value between Min_Data=0 and Max_Data=0x0FFF - * @retval None - */ -__STATIC_INLINE void LL_IWDG_SetReloadCounter(IWDG_TypeDef *IWDGx, uint32_t Counter) -{ - WRITE_REG(IWDGx->RLR, IWDG_RLR_RL & Counter); -} - -/** - * @brief Get the specified IWDG down-counter reload value - * @rmtoll RLR RL LL_IWDG_GetReloadCounter - * @param IWDGx IWDG Instance - * @retval Value between Min_Data=0 and Max_Data=0x0FFF - */ -__STATIC_INLINE uint32_t LL_IWDG_GetReloadCounter(IWDG_TypeDef *IWDGx) -{ - return (READ_REG(IWDGx->RLR)); -} - -/** - * @} - */ - -/** @defgroup IWDG_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Check if flag Prescaler Value Update is set or not - * @rmtoll SR PVU LL_IWDG_IsActiveFlag_PVU - * @param IWDGx IWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_IWDG_IsActiveFlag_PVU(IWDG_TypeDef *IWDGx) -{ - return ((READ_BIT(IWDGx->SR, IWDG_SR_PVU) == (IWDG_SR_PVU)) ? 1UL : 0UL); -} - -/** - * @brief Check if flag Reload Value Update is set or not - * @rmtoll SR RVU LL_IWDG_IsActiveFlag_RVU - * @param IWDGx IWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_IWDG_IsActiveFlag_RVU(IWDG_TypeDef *IWDGx) -{ - return ((READ_BIT(IWDGx->SR, IWDG_SR_RVU) == (IWDG_SR_RVU)) ? 1UL : 0UL); -} - -/** - * @brief Check if flags Prescaler & Reload Value Update are reset or not - * @rmtoll SR PVU LL_IWDG_IsReady\n - * SR RVU LL_IWDG_IsReady - * @param IWDGx IWDG Instance - * @retval State of bits (1 or 0). - */ -__STATIC_INLINE uint32_t LL_IWDG_IsReady(IWDG_TypeDef *IWDGx) -{ - return ((READ_BIT(IWDGx->SR, IWDG_SR_PVU | IWDG_SR_RVU) == 0U) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* IWDG */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_IWDG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_lptim.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_lptim.h deleted file mode 100644 index a91bf920d0c523d..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_lptim.h +++ /dev/null @@ -1,1381 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_lptim.h - * @author MCD Application Team - * @brief Header file of LPTIM LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_LPTIM_H -#define STM32F4xx_LL_LPTIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (LPTIM1) - -/** @defgroup LPTIM_LL LPTIM - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup LPTIM_LL_Private_Macros LPTIM Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup LPTIM_LL_ES_INIT LPTIM Exported Init structure - * @{ - */ - -/** - * @brief LPTIM Init structure definition - */ -typedef struct -{ - uint32_t ClockSource; /*!< Specifies the source of the clock used by the LPTIM instance. - This parameter can be a value of @ref LPTIM_LL_EC_CLK_SOURCE. - - This feature can be modified afterwards using unitary - function @ref LL_LPTIM_SetClockSource().*/ - - uint32_t Prescaler; /*!< Specifies the prescaler division ratio. - This parameter can be a value of @ref LPTIM_LL_EC_PRESCALER. - - This feature can be modified afterwards using using unitary - function @ref LL_LPTIM_SetPrescaler().*/ - - uint32_t Waveform; /*!< Specifies the waveform shape. - This parameter can be a value of @ref LPTIM_LL_EC_OUTPUT_WAVEFORM. - - This feature can be modified afterwards using unitary - function @ref LL_LPTIM_ConfigOutput().*/ - - uint32_t Polarity; /*!< Specifies waveform polarity. - This parameter can be a value of @ref LPTIM_LL_EC_OUTPUT_POLARITY. - - This feature can be modified afterwards using unitary - function @ref LL_LPTIM_ConfigOutput().*/ -} LL_LPTIM_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup LPTIM_LL_Exported_Constants LPTIM Exported Constants - * @{ - */ - -/** @defgroup LPTIM_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_LPTIM_ReadReg function - * @{ - */ -#define LL_LPTIM_ISR_CMPM LPTIM_ISR_CMPM /*!< Compare match */ -#define LL_LPTIM_ISR_CMPOK LPTIM_ISR_CMPOK /*!< Compare register update OK */ -#define LL_LPTIM_ISR_ARRM LPTIM_ISR_ARRM /*!< Autoreload match */ -#define LL_LPTIM_ISR_EXTTRIG LPTIM_ISR_EXTTRIG /*!< External trigger edge event */ -#define LL_LPTIM_ISR_ARROK LPTIM_ISR_ARROK /*!< Autoreload register update OK */ -#define LL_LPTIM_ISR_UP LPTIM_ISR_UP /*!< Counter direction change down to up */ -#define LL_LPTIM_ISR_DOWN LPTIM_ISR_DOWN /*!< Counter direction change up to down */ -/** - * @} - */ - -/** @defgroup LPTIM_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_LPTIM_ReadReg and LL_LPTIM_WriteReg functions - * @{ - */ -#define LL_LPTIM_IER_CMPMIE LPTIM_IER_CMPMIE /*!< Compare match */ -#define LL_LPTIM_IER_CMPOKIE LPTIM_IER_CMPOKIE /*!< Compare register update OK */ -#define LL_LPTIM_IER_ARRMIE LPTIM_IER_ARRMIE /*!< Autoreload match */ -#define LL_LPTIM_IER_EXTTRIGIE LPTIM_IER_EXTTRIGIE /*!< External trigger edge event */ -#define LL_LPTIM_IER_ARROKIE LPTIM_IER_ARROKIE /*!< Autoreload register update OK */ -#define LL_LPTIM_IER_UPIE LPTIM_IER_UPIE /*!< Counter direction change down to up */ -#define LL_LPTIM_IER_DOWNIE LPTIM_IER_DOWNIE /*!< Counter direction change up to down */ -/** - * @} - */ - -/** @defgroup LPTIM_LL_EC_OPERATING_MODE Operating Mode - * @{ - */ -#define LL_LPTIM_OPERATING_MODE_CONTINUOUS LPTIM_CR_CNTSTRT /*!__REG__, (__VALUE__)) - -/** - * @brief Read a value in LPTIM register - * @param __INSTANCE__ LPTIM Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_LPTIM_ReadReg(__INSTANCE__, __REG__) READ_REG((__INSTANCE__)->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup LPTIM_LL_Exported_Functions LPTIM Exported Functions - * @{ - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup LPTIM_LL_EF_Init Initialisation and deinitialisation functions - * @{ - */ - -ErrorStatus LL_LPTIM_DeInit(LPTIM_TypeDef *LPTIMx); -void LL_LPTIM_StructInit(LL_LPTIM_InitTypeDef *LPTIM_InitStruct); -ErrorStatus LL_LPTIM_Init(LPTIM_TypeDef *LPTIMx, LL_LPTIM_InitTypeDef *LPTIM_InitStruct); -void LL_LPTIM_Disable(LPTIM_TypeDef *LPTIMx); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** @defgroup LPTIM_LL_EF_LPTIM_Configuration LPTIM Configuration - * @{ - */ - -/** - * @brief Enable the LPTIM instance - * @note After setting the ENABLE bit, a delay of two counter clock is needed - * before the LPTIM instance is actually enabled. - * @rmtoll CR ENABLE LL_LPTIM_Enable - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_Enable(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->CR, LPTIM_CR_ENABLE); -} - -/** - * @brief Indicates whether the LPTIM instance is enabled. - * @rmtoll CR ENABLE LL_LPTIM_IsEnabled - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabled(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->CR, LPTIM_CR_ENABLE) == LPTIM_CR_ENABLE) ? 1UL : 0UL)); -} - -/** - * @brief Starts the LPTIM counter in the desired mode. - * @note LPTIM instance must be enabled before starting the counter. - * @note It is possible to change on the fly from One Shot mode to - * Continuous mode. - * @rmtoll CR CNTSTRT LL_LPTIM_StartCounter\n - * CR SNGSTRT LL_LPTIM_StartCounter - * @param LPTIMx Low-Power Timer instance - * @param OperatingMode This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OPERATING_MODE_CONTINUOUS - * @arg @ref LL_LPTIM_OPERATING_MODE_ONESHOT - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_StartCounter(LPTIM_TypeDef *LPTIMx, uint32_t OperatingMode) -{ - MODIFY_REG(LPTIMx->CR, LPTIM_CR_CNTSTRT | LPTIM_CR_SNGSTRT, OperatingMode); -} - -/** - * @brief Set the LPTIM registers update mode (enable/disable register preload) - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR PRELOAD LL_LPTIM_SetUpdateMode - * @param LPTIMx Low-Power Timer instance - * @param UpdateMode This parameter can be one of the following values: - * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE - * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetUpdateMode(LPTIM_TypeDef *LPTIMx, uint32_t UpdateMode) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_PRELOAD, UpdateMode); -} - -/** - * @brief Get the LPTIM registers update mode - * @rmtoll CFGR PRELOAD LL_LPTIM_GetUpdateMode - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE - * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetUpdateMode(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_PRELOAD)); -} - -/** - * @brief Set the auto reload value - * @note The LPTIMx_ARR register content must only be modified when the LPTIM is enabled - * @note After a write to the LPTIMx_ARR register a new write operation to the - * same register can only be performed when the previous write operation - * is completed. Any successive write before the ARROK flag is set, will - * lead to unpredictable results. - * @note autoreload value be strictly greater than the compare value. - * @rmtoll ARR ARR LL_LPTIM_SetAutoReload - * @param LPTIMx Low-Power Timer instance - * @param AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetAutoReload(LPTIM_TypeDef *LPTIMx, uint32_t AutoReload) -{ - MODIFY_REG(LPTIMx->ARR, LPTIM_ARR_ARR, AutoReload); -} - -/** - * @brief Get actual auto reload value - * @rmtoll ARR ARR LL_LPTIM_GetAutoReload - * @param LPTIMx Low-Power Timer instance - * @retval AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetAutoReload(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->ARR, LPTIM_ARR_ARR)); -} - -/** - * @brief Set the compare value - * @note After a write to the LPTIMx_CMP register a new write operation to the - * same register can only be performed when the previous write operation - * is completed. Any successive write before the CMPOK flag is set, will - * lead to unpredictable results. - * @rmtoll CMP CMP LL_LPTIM_SetCompare - * @param LPTIMx Low-Power Timer instance - * @param CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetCompare(LPTIM_TypeDef *LPTIMx, uint32_t CompareValue) -{ - MODIFY_REG(LPTIMx->CMP, LPTIM_CMP_CMP, CompareValue); -} - -/** - * @brief Get actual compare value - * @rmtoll CMP CMP LL_LPTIM_GetCompare - * @param LPTIMx Low-Power Timer instance - * @retval CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetCompare(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CMP, LPTIM_CMP_CMP)); -} - -/** - * @brief Get actual counter value - * @note When the LPTIM instance is running with an asynchronous clock, reading - * the LPTIMx_CNT register may return unreliable values. So in this case - * it is necessary to perform two consecutive read accesses and verify - * that the two returned values are identical. - * @rmtoll CNT CNT LL_LPTIM_GetCounter - * @param LPTIMx Low-Power Timer instance - * @retval Counter value - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetCounter(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CNT, LPTIM_CNT_CNT)); -} - -/** - * @brief Set the counter mode (selection of the LPTIM counter clock source). - * @note The counter mode can be set only when the LPTIM instance is disabled. - * @rmtoll CFGR COUNTMODE LL_LPTIM_SetCounterMode - * @param LPTIMx Low-Power Timer instance - * @param CounterMode This parameter can be one of the following values: - * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL - * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetCounterMode(LPTIM_TypeDef *LPTIMx, uint32_t CounterMode) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_COUNTMODE, CounterMode); -} - -/** - * @brief Get the counter mode - * @rmtoll CFGR COUNTMODE LL_LPTIM_GetCounterMode - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL - * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetCounterMode(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_COUNTMODE)); -} - -/** - * @brief Configure the LPTIM instance output (LPTIMx_OUT) - * @note This function must be called when the LPTIM instance is disabled. - * @note Regarding the LPTIM output polarity the change takes effect - * immediately, so the output default value will change immediately after - * the polarity is re-configured, even before the timer is enabled. - * @rmtoll CFGR WAVE LL_LPTIM_ConfigOutput\n - * CFGR WAVPOL LL_LPTIM_ConfigOutput - * @param LPTIMx Low-Power Timer instance - * @param Waveform This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ConfigOutput(LPTIM_TypeDef *LPTIMx, uint32_t Waveform, uint32_t Polarity) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVE | LPTIM_CFGR_WAVPOL, Waveform | Polarity); -} - -/** - * @brief Set waveform shape - * @rmtoll CFGR WAVE LL_LPTIM_SetWaveform - * @param LPTIMx Low-Power Timer instance - * @param Waveform This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetWaveform(LPTIM_TypeDef *LPTIMx, uint32_t Waveform) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVE, Waveform); -} - -/** - * @brief Get actual waveform shape - * @rmtoll CFGR WAVE LL_LPTIM_GetWaveform - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetWaveform(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_WAVE)); -} - -/** - * @brief Set output polarity - * @rmtoll CFGR WAVPOL LL_LPTIM_SetPolarity - * @param LPTIMx Low-Power Timer instance - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetPolarity(LPTIM_TypeDef *LPTIMx, uint32_t Polarity) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVPOL, Polarity); -} - -/** - * @brief Get actual output polarity - * @rmtoll CFGR WAVPOL LL_LPTIM_GetPolarity - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetPolarity(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_WAVPOL)); -} - -/** - * @brief Set actual prescaler division ratio. - * @note This function must be called when the LPTIM instance is disabled. - * @note When the LPTIM is configured to be clocked by an internal clock source - * and the LPTIM counter is configured to be updated by active edges - * detected on the LPTIM external Input1, the internal clock provided to - * the LPTIM must be not be prescaled. - * @rmtoll CFGR PRESC LL_LPTIM_SetPrescaler - * @param LPTIMx Low-Power Timer instance - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_LPTIM_PRESCALER_DIV1 - * @arg @ref LL_LPTIM_PRESCALER_DIV2 - * @arg @ref LL_LPTIM_PRESCALER_DIV4 - * @arg @ref LL_LPTIM_PRESCALER_DIV8 - * @arg @ref LL_LPTIM_PRESCALER_DIV16 - * @arg @ref LL_LPTIM_PRESCALER_DIV32 - * @arg @ref LL_LPTIM_PRESCALER_DIV64 - * @arg @ref LL_LPTIM_PRESCALER_DIV128 - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetPrescaler(LPTIM_TypeDef *LPTIMx, uint32_t Prescaler) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_PRESC, Prescaler); -} - -/** - * @brief Get actual prescaler division ratio. - * @rmtoll CFGR PRESC LL_LPTIM_GetPrescaler - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_PRESCALER_DIV1 - * @arg @ref LL_LPTIM_PRESCALER_DIV2 - * @arg @ref LL_LPTIM_PRESCALER_DIV4 - * @arg @ref LL_LPTIM_PRESCALER_DIV8 - * @arg @ref LL_LPTIM_PRESCALER_DIV16 - * @arg @ref LL_LPTIM_PRESCALER_DIV32 - * @arg @ref LL_LPTIM_PRESCALER_DIV64 - * @arg @ref LL_LPTIM_PRESCALER_DIV128 - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetPrescaler(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_PRESC)); -} - -/** - * @brief Set LPTIM input 1 source (default GPIO). - * @rmtoll OR OR LL_LPTIM_SetInput1Src - * @param LPTIMx Low-Power Timer instance - * @param Src This parameter can be one of the following values: - * @arg @ref LL_LPTIM_INPUT1_SRC_PAD_AF - * @arg @ref LL_LPTIM_INPUT1_SRC_PAD_PA4 - * @arg @ref LL_LPTIM_INPUT1_SRC_PAD_PB9 - * @arg @ref LL_LPTIM_INPUT1_SRC_TIM_DAC - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetInput1Src(LPTIM_TypeDef *LPTIMx, uint32_t Src) -{ - MODIFY_REG(LPTIMx->OR, LPTIM_OR_OR, Src); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_Trigger_Configuration Trigger Configuration - * @{ - */ - -/** - * @brief Enable the timeout function - * @note This function must be called when the LPTIM instance is disabled. - * @note The first trigger event will start the timer, any successive trigger - * event will reset the counter and the timer will restart. - * @note The timeout value corresponds to the compare value; if no trigger - * occurs within the expected time frame, the MCU is waked-up by the - * compare match event. - * @rmtoll CFGR TIMOUT LL_LPTIM_EnableTimeout - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableTimeout(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT); -} - -/** - * @brief Disable the timeout function - * @note This function must be called when the LPTIM instance is disabled. - * @note A trigger event arriving when the timer is already started will be - * ignored. - * @rmtoll CFGR TIMOUT LL_LPTIM_DisableTimeout - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableTimeout(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT); -} - -/** - * @brief Indicate whether the timeout function is enabled. - * @rmtoll CFGR TIMOUT LL_LPTIM_IsEnabledTimeout - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledTimeout(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT) == LPTIM_CFGR_TIMOUT) ? 1UL : 0UL)); -} - -/** - * @brief Start the LPTIM counter - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR TRIGEN LL_LPTIM_TrigSw - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_TrigSw(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGEN); -} - -/** - * @brief Configure the external trigger used as a trigger event for the LPTIM. - * @note This function must be called when the LPTIM instance is disabled. - * @note An internal clock source must be present when a digital filter is - * required for the trigger. - * @rmtoll CFGR TRIGSEL LL_LPTIM_ConfigTrigger\n - * CFGR TRGFLT LL_LPTIM_ConfigTrigger\n - * CFGR TRIGEN LL_LPTIM_ConfigTrigger - * @param LPTIMx Low-Power Timer instance - * @param Source This parameter can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1 - * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM1_TRGO - * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM5_TRGO - * @param Filter This parameter can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_FILTER_NONE - * @arg @ref LL_LPTIM_TRIG_FILTER_2 - * @arg @ref LL_LPTIM_TRIG_FILTER_4 - * @arg @ref LL_LPTIM_TRIG_FILTER_8 - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING - * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING - * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ConfigTrigger(LPTIM_TypeDef *LPTIMx, uint32_t Source, uint32_t Filter, uint32_t Polarity) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_TRIGSEL | LPTIM_CFGR_TRGFLT | LPTIM_CFGR_TRIGEN, Source | Filter | Polarity); -} - -/** - * @brief Get actual external trigger source. - * @rmtoll CFGR TRIGSEL LL_LPTIM_GetTriggerSource - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1 - * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM1_TRGO - * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM5_TRGO - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetTriggerSource(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGSEL)); -} - -/** - * @brief Get actual external trigger filter. - * @rmtoll CFGR TRGFLT LL_LPTIM_GetTriggerFilter - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_FILTER_NONE - * @arg @ref LL_LPTIM_TRIG_FILTER_2 - * @arg @ref LL_LPTIM_TRIG_FILTER_4 - * @arg @ref LL_LPTIM_TRIG_FILTER_8 - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetTriggerFilter(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRGFLT)); -} - -/** - * @brief Get actual external trigger polarity. - * @rmtoll CFGR TRIGEN LL_LPTIM_GetTriggerPolarity - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING - * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING - * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetTriggerPolarity(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGEN)); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_Clock_Configuration Clock Configuration - * @{ - */ - -/** - * @brief Set the source of the clock used by the LPTIM instance. - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR CKSEL LL_LPTIM_SetClockSource - * @param LPTIMx Low-Power Timer instance - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL - * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetClockSource(LPTIM_TypeDef *LPTIMx, uint32_t ClockSource) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKSEL, ClockSource); -} - -/** - * @brief Get actual LPTIM instance clock source. - * @rmtoll CFGR CKSEL LL_LPTIM_GetClockSource - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL - * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetClockSource(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKSEL)); -} - -/** - * @brief Configure the active edge or edges used by the counter when - the LPTIM is clocked by an external clock source. - * @note This function must be called when the LPTIM instance is disabled. - * @note When both external clock signal edges are considered active ones, - * the LPTIM must also be clocked by an internal clock source with a - * frequency equal to at least four times the external clock frequency. - * @note An internal clock source must be present when a digital filter is - * required for external clock. - * @rmtoll CFGR CKFLT LL_LPTIM_ConfigClock\n - * CFGR CKPOL LL_LPTIM_ConfigClock - * @param LPTIMx Low-Power Timer instance - * @param ClockFilter This parameter can be one of the following values: - * @arg @ref LL_LPTIM_CLK_FILTER_NONE - * @arg @ref LL_LPTIM_CLK_FILTER_2 - * @arg @ref LL_LPTIM_CLK_FILTER_4 - * @arg @ref LL_LPTIM_CLK_FILTER_8 - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_LPTIM_CLK_POLARITY_RISING - * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING - * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ConfigClock(LPTIM_TypeDef *LPTIMx, uint32_t ClockFilter, uint32_t ClockPolarity) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKFLT | LPTIM_CFGR_CKPOL, ClockFilter | ClockPolarity); -} - -/** - * @brief Get actual clock polarity - * @rmtoll CFGR CKPOL LL_LPTIM_GetClockPolarity - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_CLK_POLARITY_RISING - * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING - * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetClockPolarity(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKPOL)); -} - -/** - * @brief Get actual clock digital filter - * @rmtoll CFGR CKFLT LL_LPTIM_GetClockFilter - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_CLK_FILTER_NONE - * @arg @ref LL_LPTIM_CLK_FILTER_2 - * @arg @ref LL_LPTIM_CLK_FILTER_4 - * @arg @ref LL_LPTIM_CLK_FILTER_8 - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetClockFilter(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKFLT)); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_Encoder_Mode Encoder Mode - * @{ - */ - -/** - * @brief Configure the encoder mode. - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR CKPOL LL_LPTIM_SetEncoderMode - * @param LPTIMx Low-Power Timer instance - * @param EncoderMode This parameter can be one of the following values: - * @arg @ref LL_LPTIM_ENCODER_MODE_RISING - * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING - * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetEncoderMode(LPTIM_TypeDef *LPTIMx, uint32_t EncoderMode) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKPOL, EncoderMode); -} - -/** - * @brief Get actual encoder mode. - * @rmtoll CFGR CKPOL LL_LPTIM_GetEncoderMode - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_ENCODER_MODE_RISING - * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING - * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetEncoderMode(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKPOL)); -} - -/** - * @brief Enable the encoder mode - * @note This function must be called when the LPTIM instance is disabled. - * @note In this mode the LPTIM instance must be clocked by an internal clock - * source. Also, the prescaler division ratio must be equal to 1. - * @note LPTIM instance must be configured in continuous mode prior enabling - * the encoder mode. - * @rmtoll CFGR ENC LL_LPTIM_EnableEncoderMode - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableEncoderMode(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC); -} - -/** - * @brief Disable the encoder mode - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR ENC LL_LPTIM_DisableEncoderMode - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableEncoderMode(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC); -} - -/** - * @brief Indicates whether the LPTIM operates in encoder mode. - * @rmtoll CFGR ENC LL_LPTIM_IsEnabledEncoderMode - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledEncoderMode(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC) == LPTIM_CFGR_ENC) ? 1UL : 0UL)); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Clear the compare match flag (CMPMCF) - * @rmtoll ICR CMPMCF LL_LPTIM_ClearFLAG_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFLAG_CMPM(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_CMPMCF); -} - -/** - * @brief Inform application whether a compare match interrupt has occurred. - * @rmtoll ISR CMPM LL_LPTIM_IsActiveFlag_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_CMPM(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_CMPM) == LPTIM_ISR_CMPM) ? 1UL : 0UL)); -} - -/** - * @brief Clear the autoreload match flag (ARRMCF) - * @rmtoll ICR ARRMCF LL_LPTIM_ClearFLAG_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFLAG_ARRM(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_ARRMCF); -} - -/** - * @brief Inform application whether a autoreload match interrupt has occurred. - * @rmtoll ISR ARRM LL_LPTIM_IsActiveFlag_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_ARRM(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_ARRM) == LPTIM_ISR_ARRM) ? 1UL : 0UL)); -} - -/** - * @brief Clear the external trigger valid edge flag(EXTTRIGCF). - * @rmtoll ICR EXTTRIGCF LL_LPTIM_ClearFlag_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_EXTTRIGCF); -} - -/** - * @brief Inform application whether a valid edge on the selected external trigger input has occurred. - * @rmtoll ISR EXTTRIG LL_LPTIM_IsActiveFlag_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_EXTTRIG) == LPTIM_ISR_EXTTRIG) ? 1UL : 0UL)); -} - -/** - * @brief Clear the compare register update interrupt flag (CMPOKCF). - * @rmtoll ICR CMPOKCF LL_LPTIM_ClearFlag_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_CMPOKCF); -} - -/** - * @brief Informs application whether the APB bus write operation to the LPTIMx_CMP register has been successfully - completed. If so, a new one can be initiated. - * @rmtoll ISR CMPOK LL_LPTIM_IsActiveFlag_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_CMPOK) == LPTIM_ISR_CMPOK) ? 1UL : 0UL)); -} - -/** - * @brief Clear the autoreload register update interrupt flag (ARROKCF). - * @rmtoll ICR ARROKCF LL_LPTIM_ClearFlag_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_ARROK(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_ARROKCF); -} - -/** - * @brief Informs application whether the APB bus write operation to the LPTIMx_ARR register has been successfully - completed. If so, a new one can be initiated. - * @rmtoll ISR ARROK LL_LPTIM_IsActiveFlag_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_ARROK(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_ARROK) == LPTIM_ISR_ARROK) ? 1UL : 0UL)); -} - -/** - * @brief Clear the counter direction change to up interrupt flag (UPCF). - * @rmtoll ICR UPCF LL_LPTIM_ClearFlag_UP - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_UP(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_UPCF); -} - -/** - * @brief Informs the application whether the counter direction has changed from down to up (when the LPTIM instance - operates in encoder mode). - * @rmtoll ISR UP LL_LPTIM_IsActiveFlag_UP - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_UP(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_UP) == LPTIM_ISR_UP) ? 1UL : 0UL)); -} - -/** - * @brief Clear the counter direction change to down interrupt flag (DOWNCF). - * @rmtoll ICR DOWNCF LL_LPTIM_ClearFlag_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_DOWN(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_DOWNCF); -} - -/** - * @brief Informs the application whether the counter direction has changed from up to down (when the LPTIM instance - operates in encoder mode). - * @rmtoll ISR DOWN LL_LPTIM_IsActiveFlag_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_DOWN(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_DOWN) == LPTIM_ISR_DOWN) ? 1UL : 0UL)); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_IT_Management Interrupt Management - * @{ - */ - -/** - * @brief Enable compare match interrupt (CMPMIE). - * @rmtoll IER CMPMIE LL_LPTIM_EnableIT_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_CMPM(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE); -} - -/** - * @brief Disable compare match interrupt (CMPMIE). - * @rmtoll IER CMPMIE LL_LPTIM_DisableIT_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_CMPM(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE); -} - -/** - * @brief Indicates whether the compare match interrupt (CMPMIE) is enabled. - * @rmtoll IER CMPMIE LL_LPTIM_IsEnabledIT_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_CMPM(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE) == LPTIM_IER_CMPMIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable autoreload match interrupt (ARRMIE). - * @rmtoll IER ARRMIE LL_LPTIM_EnableIT_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_ARRM(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE); -} - -/** - * @brief Disable autoreload match interrupt (ARRMIE). - * @rmtoll IER ARRMIE LL_LPTIM_DisableIT_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_ARRM(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE); -} - -/** - * @brief Indicates whether the autoreload match interrupt (ARRMIE) is enabled. - * @rmtoll IER ARRMIE LL_LPTIM_IsEnabledIT_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_ARRM(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE) == LPTIM_IER_ARRMIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable external trigger valid edge interrupt (EXTTRIGIE). - * @rmtoll IER EXTTRIGIE LL_LPTIM_EnableIT_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE); -} - -/** - * @brief Disable external trigger valid edge interrupt (EXTTRIGIE). - * @rmtoll IER EXTTRIGIE LL_LPTIM_DisableIT_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE); -} - -/** - * @brief Indicates external trigger valid edge interrupt (EXTTRIGIE) is enabled. - * @rmtoll IER EXTTRIGIE LL_LPTIM_IsEnabledIT_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE) == LPTIM_IER_EXTTRIGIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable compare register write completed interrupt (CMPOKIE). - * @rmtoll IER CMPOKIE LL_LPTIM_EnableIT_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE); -} - -/** - * @brief Disable compare register write completed interrupt (CMPOKIE). - * @rmtoll IER CMPOKIE LL_LPTIM_DisableIT_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE); -} - -/** - * @brief Indicates whether the compare register write completed interrupt (CMPOKIE) is enabled. - * @rmtoll IER CMPOKIE LL_LPTIM_IsEnabledIT_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE) == LPTIM_IER_CMPOKIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable autoreload register write completed interrupt (ARROKIE). - * @rmtoll IER ARROKIE LL_LPTIM_EnableIT_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_ARROK(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE); -} - -/** - * @brief Disable autoreload register write completed interrupt (ARROKIE). - * @rmtoll IER ARROKIE LL_LPTIM_DisableIT_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_ARROK(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE); -} - -/** - * @brief Indicates whether the autoreload register write completed interrupt (ARROKIE) is enabled. - * @rmtoll IER ARROKIE LL_LPTIM_IsEnabledIT_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval State of bit(1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_ARROK(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE) == LPTIM_IER_ARROKIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable direction change to up interrupt (UPIE). - * @rmtoll IER UPIE LL_LPTIM_EnableIT_UP - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_UP(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_UPIE); -} - -/** - * @brief Disable direction change to up interrupt (UPIE). - * @rmtoll IER UPIE LL_LPTIM_DisableIT_UP - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_UP(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_UPIE); -} - -/** - * @brief Indicates whether the direction change to up interrupt (UPIE) is enabled. - * @rmtoll IER UPIE LL_LPTIM_IsEnabledIT_UP - * @param LPTIMx Low-Power Timer instance - * @retval State of bit(1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_UP(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_UPIE) == LPTIM_IER_UPIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable direction change to down interrupt (DOWNIE). - * @rmtoll IER DOWNIE LL_LPTIM_EnableIT_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_DOWN(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE); -} - -/** - * @brief Disable direction change to down interrupt (DOWNIE). - * @rmtoll IER DOWNIE LL_LPTIM_DisableIT_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_DOWN(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE); -} - -/** - * @brief Indicates whether the direction change to down interrupt (DOWNIE) is enabled. - * @rmtoll IER DOWNIE LL_LPTIM_IsEnabledIT_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval State of bit(1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_DOWN(LPTIM_TypeDef *LPTIMx) -{ - return ((READ_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE) == LPTIM_IER_DOWNIE) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* LPTIM1 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_LPTIM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h deleted file mode 100644 index 03b8706e98978ae..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h +++ /dev/null @@ -1,989 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_pwr.h - * @author MCD Application Team - * @brief Header file of PWR LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_PWR_H -#define __STM32F4xx_LL_PWR_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(PWR) - -/** @defgroup PWR_LL PWR - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Constants PWR Exported Constants - * @{ - */ - -/** @defgroup PWR_LL_EC_CLEAR_FLAG Clear Flags Defines - * @brief Flags defines which can be used with LL_PWR_WriteReg function - * @{ - */ -#define LL_PWR_CR_CSBF PWR_CR_CSBF /*!< Clear standby flag */ -#define LL_PWR_CR_CWUF PWR_CR_CWUF /*!< Clear wakeup flag */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_PWR_ReadReg function - * @{ - */ -#define LL_PWR_CSR_WUF PWR_CSR_WUF /*!< Wakeup flag */ -#define LL_PWR_CSR_SBF PWR_CSR_SBF /*!< Standby flag */ -#define LL_PWR_CSR_PVDO PWR_CSR_PVDO /*!< Power voltage detector output flag */ -#define LL_PWR_CSR_VOS PWR_CSR_VOSRDY /*!< Voltage scaling select flag */ -#if defined(PWR_CSR_EWUP) -#define LL_PWR_CSR_EWUP1 PWR_CSR_EWUP /*!< Enable WKUP pin */ -#elif defined(PWR_CSR_EWUP1) -#define LL_PWR_CSR_EWUP1 PWR_CSR_EWUP1 /*!< Enable WKUP pin 1 */ -#endif /* PWR_CSR_EWUP */ -#if defined(PWR_CSR_EWUP2) -#define LL_PWR_CSR_EWUP2 PWR_CSR_EWUP2 /*!< Enable WKUP pin 2 */ -#endif /* PWR_CSR_EWUP2 */ -#if defined(PWR_CSR_EWUP3) -#define LL_PWR_CSR_EWUP3 PWR_CSR_EWUP3 /*!< Enable WKUP pin 3 */ -#endif /* PWR_CSR_EWUP3 */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_REGU_VOLTAGE Regulator Voltage - * @{ - */ -#if defined(PWR_CR_VOS_0) -#define LL_PWR_REGU_VOLTAGE_SCALE3 (PWR_CR_VOS_0) -#define LL_PWR_REGU_VOLTAGE_SCALE2 (PWR_CR_VOS_1) -#define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR_VOS_0 | PWR_CR_VOS_1) /* The SCALE1 is not available for STM32F401xx devices */ -#else -#define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR_VOS) -#define LL_PWR_REGU_VOLTAGE_SCALE2 0x00000000U -#endif /* PWR_CR_VOS_0 */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_MODE_PWR Mode Power - * @{ - */ -#define LL_PWR_MODE_STOP_MAINREGU 0x00000000U /*!< Enter Stop mode when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU (PWR_CR_LPDS) /*!< Enter Stop mode (with low power Regulator ON) when the CPU enters deepsleep */ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) -#define LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (PWR_CR_MRUDS | PWR_CR_FPDS) /*!< Enter Stop mode (with main Regulator in under-drive mode) when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (PWR_CR_LPDS | PWR_CR_LPUDS | PWR_CR_FPDS) /*!< Enter Stop mode (with low power Regulator in under-drive mode) when the CPU enters deepsleep */ -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -#if defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) -#define LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (PWR_CR_MRLVDS | PWR_CR_FPDS) /*!< Enter Stop mode (with main Regulator in Deep Sleep mode) when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (PWR_CR_LPDS | PWR_CR_LPLVDS | PWR_CR_FPDS) /*!< Enter Stop mode (with low power Regulator in Deep Sleep mode) when the CPU enters deepsleep */ -#endif /* PWR_CR_MRLVDS && PWR_CR_LPLVDS && PWR_CR_FPDS */ -#define LL_PWR_MODE_STANDBY (PWR_CR_PDDS) /*!< Enter Standby mode when the CPU enters deepsleep */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_REGU_MODE_DS_MODE Regulator Mode In Deep Sleep Mode - * @{ - */ -#define LL_PWR_REGU_DSMODE_MAIN 0x00000000U /*!< Voltage Regulator in main mode during deepsleep mode */ -#define LL_PWR_REGU_DSMODE_LOW_POWER (PWR_CR_LPDS) /*!< Voltage Regulator in low-power mode during deepsleep mode */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_PVDLEVEL Power Voltage Detector Level - * @{ - */ -#define LL_PWR_PVDLEVEL_0 (PWR_CR_PLS_LEV0) /*!< Voltage threshold detected by PVD 2.2 V */ -#define LL_PWR_PVDLEVEL_1 (PWR_CR_PLS_LEV1) /*!< Voltage threshold detected by PVD 2.3 V */ -#define LL_PWR_PVDLEVEL_2 (PWR_CR_PLS_LEV2) /*!< Voltage threshold detected by PVD 2.4 V */ -#define LL_PWR_PVDLEVEL_3 (PWR_CR_PLS_LEV3) /*!< Voltage threshold detected by PVD 2.5 V */ -#define LL_PWR_PVDLEVEL_4 (PWR_CR_PLS_LEV4) /*!< Voltage threshold detected by PVD 2.6 V */ -#define LL_PWR_PVDLEVEL_5 (PWR_CR_PLS_LEV5) /*!< Voltage threshold detected by PVD 2.7 V */ -#define LL_PWR_PVDLEVEL_6 (PWR_CR_PLS_LEV6) /*!< Voltage threshold detected by PVD 2.8 V */ -#define LL_PWR_PVDLEVEL_7 (PWR_CR_PLS_LEV7) /*!< Voltage threshold detected by PVD 2.9 V */ -/** - * @} - */ -/** @defgroup PWR_LL_EC_WAKEUP_PIN Wakeup Pins - * @{ - */ -#if defined(PWR_CSR_EWUP) -#define LL_PWR_WAKEUP_PIN1 (PWR_CSR_EWUP) /*!< WKUP pin : PA0 */ -#endif /* PWR_CSR_EWUP */ -#if defined(PWR_CSR_EWUP1) -#define LL_PWR_WAKEUP_PIN1 (PWR_CSR_EWUP1) /*!< WKUP pin 1 : PA0 */ -#endif /* PWR_CSR_EWUP1 */ -#if defined(PWR_CSR_EWUP2) -#define LL_PWR_WAKEUP_PIN2 (PWR_CSR_EWUP2) /*!< WKUP pin 2 : PC0 or PC13 according to device */ -#endif /* PWR_CSR_EWUP2 */ -#if defined(PWR_CSR_EWUP3) -#define LL_PWR_WAKEUP_PIN3 (PWR_CSR_EWUP3) /*!< WKUP pin 3 : PC1 */ -#endif /* PWR_CSR_EWUP3 */ -/** - * @} - */ - -/** - * @} - */ - - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Macros PWR Exported Macros - * @{ - */ - -/** @defgroup PWR_LL_EM_WRITE_READ Common write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in PWR register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_PWR_WriteReg(__REG__, __VALUE__) WRITE_REG(PWR->__REG__, (__VALUE__)) - -/** - * @brief Read a value in PWR register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_PWR_ReadReg(__REG__) READ_REG(PWR->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Functions PWR Exported Functions - * @{ - */ - -/** @defgroup PWR_LL_EF_Configuration Configuration - * @{ - */ -#if defined(PWR_CR_FISSR) -/** - * @brief Enable FLASH interface STOP while system Run is ON - * @rmtoll CR FISSR LL_PWR_EnableFLASHInterfaceSTOP - * @note This mode is enabled only with STOP low power mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFLASHInterfaceSTOP(void) -{ - SET_BIT(PWR->CR, PWR_CR_FISSR); -} - -/** - * @brief Disable FLASH Interface STOP while system Run is ON - * @rmtoll CR FISSR LL_PWR_DisableFLASHInterfaceSTOP - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFLASHInterfaceSTOP(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FISSR); -} - -/** - * @brief Check if FLASH Interface STOP while system Run feature is enabled - * @rmtoll CR FISSR LL_PWR_IsEnabledFLASHInterfaceSTOP - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFLASHInterfaceSTOP(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FISSR) == (PWR_CR_FISSR)); -} -#endif /* PWR_CR_FISSR */ - -#if defined(PWR_CR_FMSSR) -/** - * @brief Enable FLASH Memory STOP while system Run is ON - * @rmtoll CR FMSSR LL_PWR_EnableFLASHMemorySTOP - * @note This mode is enabled only with STOP low power mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFLASHMemorySTOP(void) -{ - SET_BIT(PWR->CR, PWR_CR_FMSSR); -} - -/** - * @brief Disable FLASH Memory STOP while system Run is ON - * @rmtoll CR FMSSR LL_PWR_DisableFLASHMemorySTOP - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFLASHMemorySTOP(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FMSSR); -} - -/** - * @brief Check if FLASH Memory STOP while system Run feature is enabled - * @rmtoll CR FMSSR LL_PWR_IsEnabledFLASHMemorySTOP - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFLASHMemorySTOP(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FMSSR) == (PWR_CR_FMSSR)); -} -#endif /* PWR_CR_FMSSR */ -#if defined(PWR_CR_UDEN) -/** - * @brief Enable Under Drive Mode - * @rmtoll CR UDEN LL_PWR_EnableUnderDriveMode - * @note This mode is enabled only with STOP low power mode. - * In this mode, the 1.2V domain is preserved in reduced leakage mode. This - * mode is only available when the main Regulator or the low power Regulator - * is in low voltage mode. - * @note If the Under-drive mode was enabled, it is automatically disabled after - * exiting Stop mode. - * When the voltage Regulator operates in Under-drive mode, an additional - * startup delay is induced when waking up from Stop mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableUnderDriveMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_UDEN); -} - -/** - * @brief Disable Under Drive Mode - * @rmtoll CR UDEN LL_PWR_DisableUnderDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableUnderDriveMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_UDEN); -} - -/** - * @brief Check if Under Drive Mode is enabled - * @rmtoll CR UDEN LL_PWR_IsEnabledUnderDriveMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledUnderDriveMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_UDEN) == (PWR_CR_UDEN)); -} -#endif /* PWR_CR_UDEN */ - -#if defined(PWR_CR_ODSWEN) -/** - * @brief Enable Over drive switching - * @rmtoll CR ODSWEN LL_PWR_EnableOverDriveSwitching - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableOverDriveSwitching(void) -{ - SET_BIT(PWR->CR, PWR_CR_ODSWEN); -} - -/** - * @brief Disable Over drive switching - * @rmtoll CR ODSWEN LL_PWR_DisableOverDriveSwitching - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableOverDriveSwitching(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_ODSWEN); -} - -/** - * @brief Check if Over drive switching is enabled - * @rmtoll CR ODSWEN LL_PWR_IsEnabledOverDriveSwitching - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledOverDriveSwitching(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_ODSWEN) == (PWR_CR_ODSWEN)); -} -#endif /* PWR_CR_ODSWEN */ -#if defined(PWR_CR_ODEN) -/** - * @brief Enable Over drive Mode - * @rmtoll CR ODEN LL_PWR_EnableOverDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableOverDriveMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_ODEN); -} - -/** - * @brief Disable Over drive Mode - * @rmtoll CR ODEN LL_PWR_DisableOverDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableOverDriveMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_ODEN); -} - -/** - * @brief Check if Over drive switching is enabled - * @rmtoll CR ODEN LL_PWR_IsEnabledOverDriveMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledOverDriveMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_ODEN) == (PWR_CR_ODEN)); -} -#endif /* PWR_CR_ODEN */ -#if defined(PWR_CR_MRUDS) -/** - * @brief Enable Main Regulator in deepsleep under-drive Mode - * @rmtoll CR MRUDS LL_PWR_EnableMainRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableMainRegulatorDeepSleepUDMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_MRUDS); -} - -/** - * @brief Disable Main Regulator in deepsleep under-drive Mode - * @rmtoll CR MRUDS LL_PWR_DisableMainRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableMainRegulatorDeepSleepUDMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_MRUDS); -} - -/** - * @brief Check if Main Regulator in deepsleep under-drive Mode is enabled - * @rmtoll CR MRUDS LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_MRUDS) == (PWR_CR_MRUDS)); -} -#endif /* PWR_CR_MRUDS */ - -#if defined(PWR_CR_LPUDS) -/** - * @brief Enable Low Power Regulator in deepsleep under-drive Mode - * @rmtoll CR LPUDS LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_LPUDS); -} - -/** - * @brief Disable Low Power Regulator in deepsleep under-drive Mode - * @rmtoll CR LPUDS LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_LPUDS); -} - -/** - * @brief Check if Low Power Regulator in deepsleep under-drive Mode is enabled - * @rmtoll CR LPUDS LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_LPUDS) == (PWR_CR_LPUDS)); -} -#endif /* PWR_CR_LPUDS */ - -#if defined(PWR_CR_MRLVDS) -/** - * @brief Enable Main Regulator low voltage Mode - * @rmtoll CR MRLVDS LL_PWR_EnableMainRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableMainRegulatorLowVoltageMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_MRLVDS); -} - -/** - * @brief Disable Main Regulator low voltage Mode - * @rmtoll CR MRLVDS LL_PWR_DisableMainRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableMainRegulatorLowVoltageMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_MRLVDS); -} - -/** - * @brief Check if Main Regulator low voltage Mode is enabled - * @rmtoll CR MRLVDS LL_PWR_IsEnabledMainRegulatorLowVoltageMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledMainRegulatorLowVoltageMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_MRLVDS) == (PWR_CR_MRLVDS)); -} -#endif /* PWR_CR_MRLVDS */ - -#if defined(PWR_CR_LPLVDS) -/** - * @brief Enable Low Power Regulator low voltage Mode - * @rmtoll CR LPLVDS LL_PWR_EnableLowPowerRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableLowPowerRegulatorLowVoltageMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_LPLVDS); -} - -/** - * @brief Disable Low Power Regulator low voltage Mode - * @rmtoll CR LPLVDS LL_PWR_DisableLowPowerRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableLowPowerRegulatorLowVoltageMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_LPLVDS); -} - -/** - * @brief Check if Low Power Regulator low voltage Mode is enabled - * @rmtoll CR LPLVDS LL_PWR_IsEnabledLowPowerRegulatorLowVoltageMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledLowPowerRegulatorLowVoltageMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_LPLVDS) == (PWR_CR_LPLVDS)); -} -#endif /* PWR_CR_LPLVDS */ -/** - * @brief Set the main internal Regulator output voltage - * @rmtoll CR VOS LL_PWR_SetRegulVoltageScaling - * @param VoltageScaling This parameter can be one of the following values: - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1 (*) - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2 - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3 - * (*) LL_PWR_REGU_VOLTAGE_SCALE1 is not available for STM32F401xx devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetRegulVoltageScaling(uint32_t VoltageScaling) -{ - MODIFY_REG(PWR->CR, PWR_CR_VOS, VoltageScaling); -} - -/** - * @brief Get the main internal Regulator output voltage - * @rmtoll CR VOS LL_PWR_GetRegulVoltageScaling - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1 (*) - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2 - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3 - * (*) LL_PWR_REGU_VOLTAGE_SCALE1 is not available for STM32F401xx devices - */ -__STATIC_INLINE uint32_t LL_PWR_GetRegulVoltageScaling(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_VOS)); -} -/** - * @brief Enable the Flash Power Down in Stop Mode - * @rmtoll CR FPDS LL_PWR_EnableFlashPowerDown - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFlashPowerDown(void) -{ - SET_BIT(PWR->CR, PWR_CR_FPDS); -} - -/** - * @brief Disable the Flash Power Down in Stop Mode - * @rmtoll CR FPDS LL_PWR_DisableFlashPowerDown - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFlashPowerDown(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FPDS); -} - -/** - * @brief Check if the Flash Power Down in Stop Mode is enabled - * @rmtoll CR FPDS LL_PWR_IsEnabledFlashPowerDown - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFlashPowerDown(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FPDS) == (PWR_CR_FPDS)); -} - -/** - * @brief Enable access to the backup domain - * @rmtoll CR DBP LL_PWR_EnableBkUpAccess - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableBkUpAccess(void) -{ - SET_BIT(PWR->CR, PWR_CR_DBP); -} - -/** - * @brief Disable access to the backup domain - * @rmtoll CR DBP LL_PWR_DisableBkUpAccess - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableBkUpAccess(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_DBP); -} - -/** - * @brief Check if the backup domain is enabled - * @rmtoll CR DBP LL_PWR_IsEnabledBkUpAccess - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledBkUpAccess(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_DBP) == (PWR_CR_DBP)); -} -/** - * @brief Enable the backup Regulator - * @rmtoll CSR BRE LL_PWR_EnableBkUpRegulator - * @note The BRE bit of the PWR_CSR register is protected against parasitic write access. - * The LL_PWR_EnableBkUpAccess() must be called before using this API. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableBkUpRegulator(void) -{ - SET_BIT(PWR->CSR, PWR_CSR_BRE); -} - -/** - * @brief Disable the backup Regulator - * @rmtoll CSR BRE LL_PWR_DisableBkUpRegulator - * @note The BRE bit of the PWR_CSR register is protected against parasitic write access. - * The LL_PWR_EnableBkUpAccess() must be called before using this API. - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableBkUpRegulator(void) -{ - CLEAR_BIT(PWR->CSR, PWR_CSR_BRE); -} - -/** - * @brief Check if the backup Regulator is enabled - * @rmtoll CSR BRE LL_PWR_IsEnabledBkUpRegulator - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledBkUpRegulator(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_BRE) == (PWR_CSR_BRE)); -} - -/** - * @brief Set voltage Regulator mode during deep sleep mode - * @rmtoll CR LPDS LL_PWR_SetRegulModeDS - * @param RegulMode This parameter can be one of the following values: - * @arg @ref LL_PWR_REGU_DSMODE_MAIN - * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetRegulModeDS(uint32_t RegulMode) -{ - MODIFY_REG(PWR->CR, PWR_CR_LPDS, RegulMode); -} - -/** - * @brief Get voltage Regulator mode during deep sleep mode - * @rmtoll CR LPDS LL_PWR_GetRegulModeDS - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_REGU_DSMODE_MAIN - * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER - */ -__STATIC_INLINE uint32_t LL_PWR_GetRegulModeDS(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_LPDS)); -} - -/** - * @brief Set Power Down mode when CPU enters deepsleep - * @rmtoll CR PDDS LL_PWR_SetPowerMode\n - * @rmtoll CR MRUDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPUDS LL_PWR_SetPowerMode\n - * @rmtoll CR FPDS LL_PWR_SetPowerMode\n - * @rmtoll CR MRLVDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPlVDS LL_PWR_SetPowerMode\n - * @rmtoll CR FPDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPDS LL_PWR_SetPowerMode - * @param PDMode This parameter can be one of the following values: - * @arg @ref LL_PWR_MODE_STOP_MAINREGU - * @arg @ref LL_PWR_MODE_STOP_LPREGU - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (*) - * - * (*) not available on all devices - * @arg @ref LL_PWR_MODE_STANDBY - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetPowerMode(uint32_t PDMode) -{ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) - MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPUDS | PWR_CR_MRUDS), PDMode); -#elif defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) - MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPLVDS | PWR_CR_MRLVDS), PDMode); -#else - MODIFY_REG(PWR->CR, (PWR_CR_PDDS| PWR_CR_LPDS), PDMode); -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -} - -/** - * @brief Get Power Down mode when CPU enters deepsleep - * @rmtoll CR PDDS LL_PWR_GetPowerMode\n - * @rmtoll CR MRUDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPUDS LL_PWR_GetPowerMode\n - * @rmtoll CR FPDS LL_PWR_GetPowerMode\n - * @rmtoll CR MRLVDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPLVDS LL_PWR_GetPowerMode\n - * @rmtoll CR FPDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPDS LL_PWR_GetPowerMode - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_MODE_STOP_MAINREGU - * @arg @ref LL_PWR_MODE_STOP_LPREGU - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (*) - * - * (*) not available on all devices - * @arg @ref LL_PWR_MODE_STANDBY - */ -__STATIC_INLINE uint32_t LL_PWR_GetPowerMode(void) -{ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPUDS | PWR_CR_MRUDS))); -#elif defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPLVDS | PWR_CR_MRLVDS))); -#else - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS| PWR_CR_LPDS))); -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -} - -/** - * @brief Configure the voltage threshold detected by the Power Voltage Detector - * @rmtoll CR PLS LL_PWR_SetPVDLevel - * @param PVDLevel This parameter can be one of the following values: - * @arg @ref LL_PWR_PVDLEVEL_0 - * @arg @ref LL_PWR_PVDLEVEL_1 - * @arg @ref LL_PWR_PVDLEVEL_2 - * @arg @ref LL_PWR_PVDLEVEL_3 - * @arg @ref LL_PWR_PVDLEVEL_4 - * @arg @ref LL_PWR_PVDLEVEL_5 - * @arg @ref LL_PWR_PVDLEVEL_6 - * @arg @ref LL_PWR_PVDLEVEL_7 - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetPVDLevel(uint32_t PVDLevel) -{ - MODIFY_REG(PWR->CR, PWR_CR_PLS, PVDLevel); -} - -/** - * @brief Get the voltage threshold detection - * @rmtoll CR PLS LL_PWR_GetPVDLevel - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_PVDLEVEL_0 - * @arg @ref LL_PWR_PVDLEVEL_1 - * @arg @ref LL_PWR_PVDLEVEL_2 - * @arg @ref LL_PWR_PVDLEVEL_3 - * @arg @ref LL_PWR_PVDLEVEL_4 - * @arg @ref LL_PWR_PVDLEVEL_5 - * @arg @ref LL_PWR_PVDLEVEL_6 - * @arg @ref LL_PWR_PVDLEVEL_7 - */ -__STATIC_INLINE uint32_t LL_PWR_GetPVDLevel(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_PLS)); -} - -/** - * @brief Enable Power Voltage Detector - * @rmtoll CR PVDE LL_PWR_EnablePVD - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnablePVD(void) -{ - SET_BIT(PWR->CR, PWR_CR_PVDE); -} - -/** - * @brief Disable Power Voltage Detector - * @rmtoll CR PVDE LL_PWR_DisablePVD - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisablePVD(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_PVDE); -} - -/** - * @brief Check if Power Voltage Detector is enabled - * @rmtoll CR PVDE LL_PWR_IsEnabledPVD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledPVD(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_PVDE) == (PWR_CR_PVDE)); -} - -/** - * @brief Enable the WakeUp PINx functionality - * @rmtoll CSR EWUP LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_EnableWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableWakeUpPin(uint32_t WakeUpPin) -{ - SET_BIT(PWR->CSR, WakeUpPin); -} - -/** - * @brief Disable the WakeUp PINx functionality - * @rmtoll CSR EWUP LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_DisableWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableWakeUpPin(uint32_t WakeUpPin) -{ - CLEAR_BIT(PWR->CSR, WakeUpPin); -} - -/** - * @brief Check if the WakeUp PINx functionality is enabled - * @rmtoll CSR EWUP LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_IsEnabledWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledWakeUpPin(uint32_t WakeUpPin) -{ - return (READ_BIT(PWR->CSR, WakeUpPin) == (WakeUpPin)); -} - - -/** - * @} - */ - -/** @defgroup PWR_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Get Wake-up Flag - * @rmtoll CSR WUF LL_PWR_IsActiveFlag_WU - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_WU(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_WUF) == (PWR_CSR_WUF)); -} - -/** - * @brief Get Standby Flag - * @rmtoll CSR SBF LL_PWR_IsActiveFlag_SB - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_SB(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_SBF) == (PWR_CSR_SBF)); -} - -/** - * @brief Get Backup Regulator ready Flag - * @rmtoll CSR BRR LL_PWR_IsActiveFlag_BRR - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_BRR(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_BRR) == (PWR_CSR_BRR)); -} -/** - * @brief Indicate whether VDD voltage is below the selected PVD threshold - * @rmtoll CSR PVDO LL_PWR_IsActiveFlag_PVDO - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_PVDO(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_PVDO) == (PWR_CSR_PVDO)); -} - -/** - * @brief Indicate whether the Regulator is ready in the selected voltage range or if its output voltage is still changing to the required voltage level - * @rmtoll CSR VOS LL_PWR_IsActiveFlag_VOS - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_VOS(void) -{ - return (READ_BIT(PWR->CSR, LL_PWR_CSR_VOS) == (LL_PWR_CSR_VOS)); -} -#if defined(PWR_CR_ODEN) -/** - * @brief Indicate whether the Over-Drive mode is ready or not - * @rmtoll CSR ODRDY LL_PWR_IsActiveFlag_OD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_OD(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_ODRDY) == (PWR_CSR_ODRDY)); -} -#endif /* PWR_CR_ODEN */ - -#if defined(PWR_CR_ODSWEN) -/** - * @brief Indicate whether the Over-Drive mode switching is ready or not - * @rmtoll CSR ODSWRDY LL_PWR_IsActiveFlag_ODSW - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_ODSW(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_ODSWRDY) == (PWR_CSR_ODSWRDY)); -} -#endif /* PWR_CR_ODSWEN */ - -#if defined(PWR_CR_UDEN) -/** - * @brief Indicate whether the Under-Drive mode is ready or not - * @rmtoll CSR UDRDY LL_PWR_IsActiveFlag_UD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_UD(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_UDRDY) == (PWR_CSR_UDRDY)); -} -#endif /* PWR_CR_UDEN */ -/** - * @brief Clear Standby Flag - * @rmtoll CR CSBF LL_PWR_ClearFlag_SB - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_SB(void) -{ - SET_BIT(PWR->CR, PWR_CR_CSBF); -} - -/** - * @brief Clear Wake-up Flags - * @rmtoll CR CWUF LL_PWR_ClearFlag_WU - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_WU(void) -{ - SET_BIT(PWR->CR, PWR_CR_CWUF); -} -#if defined(PWR_CSR_UDRDY) -/** - * @brief Clear Under-Drive ready Flag - * @rmtoll CSR UDRDY LL_PWR_ClearFlag_UD - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_UD(void) -{ - WRITE_REG(PWR->CSR, PWR_CSR_UDRDY); -} -#endif /* PWR_CSR_UDRDY */ - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup PWR_LL_EF_Init De-initialization function - * @{ - */ -ErrorStatus LL_PWR_DeInit(void); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(PWR) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_PWR_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h deleted file mode 100644 index d4c249fc31d2693..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h +++ /dev/null @@ -1,7099 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rcc.h - * @author MCD Application Team - * @brief Header file of RCC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_RCC_H -#define __STM32F4xx_LL_RCC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RCC) - -/** @defgroup RCC_LL RCC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup RCC_LL_Private_Variables RCC Private Variables - * @{ - */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -static const uint8_t aRCC_PLLSAIDIVRPrescTable[4] = {2, 4, 8, 16}; -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_Private_Macros RCC Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_Exported_Types RCC Exported Types - * @{ - */ - -/** @defgroup LL_ES_CLOCK_FREQ Clocks Frequency Structure - * @{ - */ - -/** - * @brief RCC Clocks Frequency Structure - */ -typedef struct -{ - uint32_t SYSCLK_Frequency; /*!< SYSCLK clock frequency */ - uint32_t HCLK_Frequency; /*!< HCLK clock frequency */ - uint32_t PCLK1_Frequency; /*!< PCLK1 clock frequency */ - uint32_t PCLK2_Frequency; /*!< PCLK2 clock frequency */ -} LL_RCC_ClocksTypeDef; - -/** - * @} - */ - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Constants RCC Exported Constants - * @{ - */ - -/** @defgroup RCC_LL_EC_OSC_VALUES Oscillator Values adaptation - * @brief Defines used to adapt values of different oscillators - * @note These values could be modified in the user environment according to - * HW set-up. - * @{ - */ -#if !defined (HSE_VALUE) -#define HSE_VALUE 25000000U /*!< Value of the HSE oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSI_VALUE) -#define HSI_VALUE 16000000U /*!< Value of the HSI oscillator in Hz */ -#endif /* HSI_VALUE */ - -#if !defined (LSE_VALUE) -#define LSE_VALUE 32768U /*!< Value of the LSE oscillator in Hz */ -#endif /* LSE_VALUE */ - -#if !defined (LSI_VALUE) -#define LSI_VALUE 32000U /*!< Value of the LSI oscillator in Hz */ -#endif /* LSI_VALUE */ - -#if !defined (EXTERNAL_CLOCK_VALUE) -#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the I2S_CKIN external oscillator in Hz */ -#endif /* EXTERNAL_CLOCK_VALUE */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_CLEAR_FLAG Clear Flags Defines - * @brief Flags defines which can be used with LL_RCC_WriteReg function - * @{ - */ -#define LL_RCC_CIR_LSIRDYC RCC_CIR_LSIRDYC /*!< LSI Ready Interrupt Clear */ -#define LL_RCC_CIR_LSERDYC RCC_CIR_LSERDYC /*!< LSE Ready Interrupt Clear */ -#define LL_RCC_CIR_HSIRDYC RCC_CIR_HSIRDYC /*!< HSI Ready Interrupt Clear */ -#define LL_RCC_CIR_HSERDYC RCC_CIR_HSERDYC /*!< HSE Ready Interrupt Clear */ -#define LL_RCC_CIR_PLLRDYC RCC_CIR_PLLRDYC /*!< PLL Ready Interrupt Clear */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYC RCC_CIR_PLLI2SRDYC /*!< PLLI2S Ready Interrupt Clear */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYC RCC_CIR_PLLSAIRDYC /*!< PLLSAI Ready Interrupt Clear */ -#endif /* RCC_PLLSAI_SUPPORT */ -#define LL_RCC_CIR_CSSC RCC_CIR_CSSC /*!< Clock Security System Interrupt Clear */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_RCC_ReadReg function - * @{ - */ -#define LL_RCC_CIR_LSIRDYF RCC_CIR_LSIRDYF /*!< LSI Ready Interrupt flag */ -#define LL_RCC_CIR_LSERDYF RCC_CIR_LSERDYF /*!< LSE Ready Interrupt flag */ -#define LL_RCC_CIR_HSIRDYF RCC_CIR_HSIRDYF /*!< HSI Ready Interrupt flag */ -#define LL_RCC_CIR_HSERDYF RCC_CIR_HSERDYF /*!< HSE Ready Interrupt flag */ -#define LL_RCC_CIR_PLLRDYF RCC_CIR_PLLRDYF /*!< PLL Ready Interrupt flag */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYF RCC_CIR_PLLI2SRDYF /*!< PLLI2S Ready Interrupt flag */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYF RCC_CIR_PLLSAIRDYF /*!< PLLSAI Ready Interrupt flag */ -#endif /* RCC_PLLSAI_SUPPORT */ -#define LL_RCC_CIR_CSSF RCC_CIR_CSSF /*!< Clock Security System Interrupt flag */ -#define LL_RCC_CSR_LPWRRSTF RCC_CSR_LPWRRSTF /*!< Low-Power reset flag */ -#define LL_RCC_CSR_PINRSTF RCC_CSR_PINRSTF /*!< PIN reset flag */ -#define LL_RCC_CSR_PORRSTF RCC_CSR_PORRSTF /*!< POR/PDR reset flag */ -#define LL_RCC_CSR_SFTRSTF RCC_CSR_SFTRSTF /*!< Software Reset flag */ -#define LL_RCC_CSR_IWDGRSTF RCC_CSR_IWDGRSTF /*!< Independent Watchdog reset flag */ -#define LL_RCC_CSR_WWDGRSTF RCC_CSR_WWDGRSTF /*!< Window watchdog reset flag */ -#if defined(RCC_CSR_BORRSTF) -#define LL_RCC_CSR_BORRSTF RCC_CSR_BORRSTF /*!< BOR reset flag */ -#endif /* RCC_CSR_BORRSTF */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_RCC_ReadReg and LL_RCC_WriteReg functions - * @{ - */ -#define LL_RCC_CIR_LSIRDYIE RCC_CIR_LSIRDYIE /*!< LSI Ready Interrupt Enable */ -#define LL_RCC_CIR_LSERDYIE RCC_CIR_LSERDYIE /*!< LSE Ready Interrupt Enable */ -#define LL_RCC_CIR_HSIRDYIE RCC_CIR_HSIRDYIE /*!< HSI Ready Interrupt Enable */ -#define LL_RCC_CIR_HSERDYIE RCC_CIR_HSERDYIE /*!< HSE Ready Interrupt Enable */ -#define LL_RCC_CIR_PLLRDYIE RCC_CIR_PLLRDYIE /*!< PLL Ready Interrupt Enable */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYIE RCC_CIR_PLLI2SRDYIE /*!< PLLI2S Ready Interrupt Enable */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYIE RCC_CIR_PLLSAIRDYIE /*!< PLLSAI Ready Interrupt Enable */ -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYS_CLKSOURCE System clock switch - * @{ - */ -#define LL_RCC_SYS_CLKSOURCE_HSI RCC_CFGR_SW_HSI /*!< HSI selection as system clock */ -#define LL_RCC_SYS_CLKSOURCE_HSE RCC_CFGR_SW_HSE /*!< HSE selection as system clock */ -#define LL_RCC_SYS_CLKSOURCE_PLL RCC_CFGR_SW_PLL /*!< PLL selection as system clock */ -#if defined(RCC_CFGR_SW_PLLR) -#define LL_RCC_SYS_CLKSOURCE_PLLR RCC_CFGR_SW_PLLR /*!< PLLR selection as system clock */ -#endif /* RCC_CFGR_SW_PLLR */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYS_CLKSOURCE_STATUS System clock switch status - * @{ - */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_PLL RCC_CFGR_SWS_PLL /*!< PLL used as system clock */ -#if defined(RCC_PLLR_SYSCLK_SUPPORT) -#define LL_RCC_SYS_CLKSOURCE_STATUS_PLLR RCC_CFGR_SWS_PLLR /*!< PLLR used as system clock */ -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYSCLK_DIV AHB prescaler - * @{ - */ -#define LL_RCC_SYSCLK_DIV_1 RCC_CFGR_HPRE_DIV1 /*!< SYSCLK not divided */ -#define LL_RCC_SYSCLK_DIV_2 RCC_CFGR_HPRE_DIV2 /*!< SYSCLK divided by 2 */ -#define LL_RCC_SYSCLK_DIV_4 RCC_CFGR_HPRE_DIV4 /*!< SYSCLK divided by 4 */ -#define LL_RCC_SYSCLK_DIV_8 RCC_CFGR_HPRE_DIV8 /*!< SYSCLK divided by 8 */ -#define LL_RCC_SYSCLK_DIV_16 RCC_CFGR_HPRE_DIV16 /*!< SYSCLK divided by 16 */ -#define LL_RCC_SYSCLK_DIV_64 RCC_CFGR_HPRE_DIV64 /*!< SYSCLK divided by 64 */ -#define LL_RCC_SYSCLK_DIV_128 RCC_CFGR_HPRE_DIV128 /*!< SYSCLK divided by 128 */ -#define LL_RCC_SYSCLK_DIV_256 RCC_CFGR_HPRE_DIV256 /*!< SYSCLK divided by 256 */ -#define LL_RCC_SYSCLK_DIV_512 RCC_CFGR_HPRE_DIV512 /*!< SYSCLK divided by 512 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_APB1_DIV APB low-speed prescaler (APB1) - * @{ - */ -#define LL_RCC_APB1_DIV_1 RCC_CFGR_PPRE1_DIV1 /*!< HCLK not divided */ -#define LL_RCC_APB1_DIV_2 RCC_CFGR_PPRE1_DIV2 /*!< HCLK divided by 2 */ -#define LL_RCC_APB1_DIV_4 RCC_CFGR_PPRE1_DIV4 /*!< HCLK divided by 4 */ -#define LL_RCC_APB1_DIV_8 RCC_CFGR_PPRE1_DIV8 /*!< HCLK divided by 8 */ -#define LL_RCC_APB1_DIV_16 RCC_CFGR_PPRE1_DIV16 /*!< HCLK divided by 16 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_APB2_DIV APB high-speed prescaler (APB2) - * @{ - */ -#define LL_RCC_APB2_DIV_1 RCC_CFGR_PPRE2_DIV1 /*!< HCLK not divided */ -#define LL_RCC_APB2_DIV_2 RCC_CFGR_PPRE2_DIV2 /*!< HCLK divided by 2 */ -#define LL_RCC_APB2_DIV_4 RCC_CFGR_PPRE2_DIV4 /*!< HCLK divided by 4 */ -#define LL_RCC_APB2_DIV_8 RCC_CFGR_PPRE2_DIV8 /*!< HCLK divided by 8 */ -#define LL_RCC_APB2_DIV_16 RCC_CFGR_PPRE2_DIV16 /*!< HCLK divided by 16 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_MCOxSOURCE MCO source selection - * @{ - */ -#define LL_RCC_MCO1SOURCE_HSI (uint32_t)(RCC_CFGR_MCO1|0x00000000U) /*!< HSI selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_LSE (uint32_t)(RCC_CFGR_MCO1|(RCC_CFGR_MCO1_0 >> 16U)) /*!< LSE selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_HSE (uint32_t)(RCC_CFGR_MCO1|(RCC_CFGR_MCO1_1 >> 16U)) /*!< HSE selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_PLLCLK (uint32_t)(RCC_CFGR_MCO1|((RCC_CFGR_MCO1_1|RCC_CFGR_MCO1_0) >> 16U)) /*!< PLLCLK selection as MCO1 source */ -#if defined(RCC_CFGR_MCO2) -#define LL_RCC_MCO2SOURCE_SYSCLK (uint32_t)(RCC_CFGR_MCO2|0x00000000U) /*!< SYSCLK selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_PLLI2S (uint32_t)(RCC_CFGR_MCO2|(RCC_CFGR_MCO2_0 >> 16U)) /*!< PLLI2S selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_HSE (uint32_t)(RCC_CFGR_MCO2|(RCC_CFGR_MCO2_1 >> 16U)) /*!< HSE selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_PLLCLK (uint32_t)(RCC_CFGR_MCO2|((RCC_CFGR_MCO2_1|RCC_CFGR_MCO2_0) >> 16U)) /*!< PLLCLK selection as MCO2 source */ -#endif /* RCC_CFGR_MCO2 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_MCOx_DIV MCO prescaler - * @{ - */ -#define LL_RCC_MCO1_DIV_1 (uint32_t)(RCC_CFGR_MCO1PRE|0x00000000U) /*!< MCO1 not divided */ -#define LL_RCC_MCO1_DIV_2 (uint32_t)(RCC_CFGR_MCO1PRE|(RCC_CFGR_MCO1PRE_2 >> 16U)) /*!< MCO1 divided by 2 */ -#define LL_RCC_MCO1_DIV_3 (uint32_t)(RCC_CFGR_MCO1PRE|((RCC_CFGR_MCO1PRE_2|RCC_CFGR_MCO1PRE_0) >> 16U)) /*!< MCO1 divided by 3 */ -#define LL_RCC_MCO1_DIV_4 (uint32_t)(RCC_CFGR_MCO1PRE|((RCC_CFGR_MCO1PRE_2|RCC_CFGR_MCO1PRE_1) >> 16U)) /*!< MCO1 divided by 4 */ -#define LL_RCC_MCO1_DIV_5 (uint32_t)(RCC_CFGR_MCO1PRE|(RCC_CFGR_MCO1PRE >> 16U)) /*!< MCO1 divided by 5 */ -#if defined(RCC_CFGR_MCO2PRE) -#define LL_RCC_MCO2_DIV_1 (uint32_t)(RCC_CFGR_MCO2PRE|0x00000000U) /*!< MCO2 not divided */ -#define LL_RCC_MCO2_DIV_2 (uint32_t)(RCC_CFGR_MCO2PRE|(RCC_CFGR_MCO2PRE_2 >> 16U)) /*!< MCO2 divided by 2 */ -#define LL_RCC_MCO2_DIV_3 (uint32_t)(RCC_CFGR_MCO2PRE|((RCC_CFGR_MCO2PRE_2|RCC_CFGR_MCO2PRE_0) >> 16U)) /*!< MCO2 divided by 3 */ -#define LL_RCC_MCO2_DIV_4 (uint32_t)(RCC_CFGR_MCO2PRE|((RCC_CFGR_MCO2PRE_2|RCC_CFGR_MCO2PRE_1) >> 16U)) /*!< MCO2 divided by 4 */ -#define LL_RCC_MCO2_DIV_5 (uint32_t)(RCC_CFGR_MCO2PRE|(RCC_CFGR_MCO2PRE >> 16U)) /*!< MCO2 divided by 5 */ -#endif /* RCC_CFGR_MCO2PRE */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_RTC_HSEDIV HSE prescaler for RTC clock - * @{ - */ -#define LL_RCC_RTC_NOCLOCK 0x00000000U /*!< HSE not divided */ -#define LL_RCC_RTC_HSE_DIV_2 RCC_CFGR_RTCPRE_1 /*!< HSE clock divided by 2 */ -#define LL_RCC_RTC_HSE_DIV_3 (RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 3 */ -#define LL_RCC_RTC_HSE_DIV_4 RCC_CFGR_RTCPRE_2 /*!< HSE clock divided by 4 */ -#define LL_RCC_RTC_HSE_DIV_5 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 5 */ -#define LL_RCC_RTC_HSE_DIV_6 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 6 */ -#define LL_RCC_RTC_HSE_DIV_7 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 7 */ -#define LL_RCC_RTC_HSE_DIV_8 RCC_CFGR_RTCPRE_3 /*!< HSE clock divided by 8 */ -#define LL_RCC_RTC_HSE_DIV_9 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 9 */ -#define LL_RCC_RTC_HSE_DIV_10 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 10 */ -#define LL_RCC_RTC_HSE_DIV_11 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 11 */ -#define LL_RCC_RTC_HSE_DIV_12 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 12 */ -#define LL_RCC_RTC_HSE_DIV_13 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 13 */ -#define LL_RCC_RTC_HSE_DIV_14 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 14 */ -#define LL_RCC_RTC_HSE_DIV_15 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 15 */ -#define LL_RCC_RTC_HSE_DIV_16 RCC_CFGR_RTCPRE_4 /*!< HSE clock divided by 16 */ -#define LL_RCC_RTC_HSE_DIV_17 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 17 */ -#define LL_RCC_RTC_HSE_DIV_18 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 18 */ -#define LL_RCC_RTC_HSE_DIV_19 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 19 */ -#define LL_RCC_RTC_HSE_DIV_20 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 20 */ -#define LL_RCC_RTC_HSE_DIV_21 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 21 */ -#define LL_RCC_RTC_HSE_DIV_22 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 22 */ -#define LL_RCC_RTC_HSE_DIV_23 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 23 */ -#define LL_RCC_RTC_HSE_DIV_24 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3) /*!< HSE clock divided by 24 */ -#define LL_RCC_RTC_HSE_DIV_25 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 25 */ -#define LL_RCC_RTC_HSE_DIV_26 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 26 */ -#define LL_RCC_RTC_HSE_DIV_27 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 27 */ -#define LL_RCC_RTC_HSE_DIV_28 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 28 */ -#define LL_RCC_RTC_HSE_DIV_29 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 29 */ -#define LL_RCC_RTC_HSE_DIV_30 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 30 */ -#define LL_RCC_RTC_HSE_DIV_31 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 31 */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_EC_PERIPH_FREQUENCY Peripheral clock frequency - * @{ - */ -#define LL_RCC_PERIPH_FREQUENCY_NO 0x00000000U /*!< No clock enabled for the peripheral */ -#define LL_RCC_PERIPH_FREQUENCY_NA 0xFFFFFFFFU /*!< Frequency cannot be provided as external clock */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -#if defined(FMPI2C1) -/** @defgroup RCC_LL_EC_FMPI2C1_CLKSOURCE Peripheral FMPI2C clock source selection - * @{ - */ -#define LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 0x00000000U /*!< PCLK1 clock used as FMPI2C1 clock source */ -#define LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK RCC_DCKCFGR2_FMPI2C1SEL_0 /*!< SYSCLK clock used as FMPI2C1 clock source */ -#define LL_RCC_FMPI2C1_CLKSOURCE_HSI RCC_DCKCFGR2_FMPI2C1SEL_1 /*!< HSI clock used as FMPI2C1 clock source */ -/** - * @} - */ -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** @defgroup RCC_LL_EC_LPTIM1_CLKSOURCE Peripheral LPTIM clock source selection - * @{ - */ -#define LL_RCC_LPTIM1_CLKSOURCE_PCLK1 0x00000000U /*!< PCLK1 clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_HSI RCC_DCKCFGR2_LPTIM1SEL_0 /*!< LSI oscillator clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_LSI RCC_DCKCFGR2_LPTIM1SEL_1 /*!< HSI oscillator clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_LSE (uint32_t)(RCC_DCKCFGR2_LPTIM1SEL_1 | RCC_DCKCFGR2_LPTIM1SEL_0) /*!< LSE oscillator clock used as LPTIM1 clock */ -/** - * @} - */ -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** @defgroup RCC_LL_EC_SAIx_CLKSOURCE Peripheral SAI clock source selection - * @{ - */ -#if defined(RCC_DCKCFGR_SAI1SRC) -#define LL_RCC_SAI1_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1SRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC_1 >> 16)) /*!< PLL clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC >> 16)) /*!< External pin clock used as SAI1 clock source */ -#endif /* RCC_DCKCFGR_SAI1SRC */ -#if defined(RCC_DCKCFGR_SAI2SRC) -#define LL_RCC_SAI2_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI2SRC | 0x00000000U) /*!< PLLSAI clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC_0 >> 16)) /*!< PLLI2S clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC_1 >> 16)) /*!< PLL clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC >> 16)) /*!< PLL Main clock used as SAI2 clock source */ -#endif /* RCC_DCKCFGR_SAI2SRC */ -#if defined(RCC_DCKCFGR_SAI1ASRC) -#if defined(RCC_SAI1A_PLLSOURCE_SUPPORT) -#define LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1ASRC | 0x00000000U) /*!< PLLI2S clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_0 >> 16)) /*!< External pin used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_1 >> 16)) /*!< PLL clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC >> 16)) /*!< PLL Main clock used as SAI1 block A clock source */ -#else -#define LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1ASRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_1 >> 16)) /*!< External pin clock used as SAI1 block A clock source */ -#endif /* RCC_SAI1A_PLLSOURCE_SUPPORT */ -#endif /* RCC_DCKCFGR_SAI1ASRC */ -#if defined(RCC_DCKCFGR_SAI1BSRC) -#if defined(RCC_SAI1B_PLLSOURCE_SUPPORT) -#define LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1BSRC | 0x00000000U) /*!< PLLI2S clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_0 >> 16)) /*!< External pin used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_1 >> 16)) /*!< PLL clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC >> 16)) /*!< PLL Main clock used as SAI1 block B clock source */ -#else -#define LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1BSRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_1 >> 16)) /*!< External pin clock used as SAI1 block B clock source */ -#endif /* RCC_SAI1B_PLLSOURCE_SUPPORT */ -#endif /* RCC_DCKCFGR_SAI1BSRC */ -/** - * @} - */ -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** @defgroup RCC_LL_EC_SDIOx_CLKSOURCE Peripheral SDIO clock source selection - * @{ - */ -#define LL_RCC_SDIO_CLKSOURCE_PLL48CLK 0x00000000U /*!< PLL 48M domain clock used as SDIO clock */ -#if defined(RCC_DCKCFGR_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE_SYSCLK RCC_DCKCFGR_SDIOSEL /*!< System clock clock used as SDIO clock */ -#else -#define LL_RCC_SDIO_CLKSOURCE_SYSCLK RCC_DCKCFGR2_SDIOSEL /*!< System clock clock used as SDIO clock */ -#endif /* RCC_DCKCFGR_SDIOSEL */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(DSI) -/** @defgroup RCC_LL_EC_DSI_CLKSOURCE Peripheral DSI clock source selection - * @{ - */ -#define LL_RCC_DSI_CLKSOURCE_PHY 0x00000000U /*!< DSI-PHY clock used as DSI byte lane clock source */ -#define LL_RCC_DSI_CLKSOURCE_PLL RCC_DCKCFGR_DSISEL /*!< PLL clock used as DSI byte lane clock source */ -/** - * @} - */ -#endif /* DSI */ - -#if defined(CEC) -/** @defgroup RCC_LL_EC_CEC_CLKSOURCE Peripheral CEC clock source selection - * @{ - */ -#define LL_RCC_CEC_CLKSOURCE_HSI_DIV488 0x00000000U /*!< HSI oscillator clock divided by 488 used as CEC clock */ -#define LL_RCC_CEC_CLKSOURCE_LSE RCC_DCKCFGR2_CECSEL /*!< LSE oscillator clock used as CEC clock */ -/** - * @} - */ -#endif /* CEC */ - -/** @defgroup RCC_LL_EC_I2S1_CLKSOURCE Peripheral I2S clock source selection - * @{ - */ -#if defined(RCC_CFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE_PLLI2S 0x00000000U /*!< I2S oscillator clock used as I2S1 clock */ -#define LL_RCC_I2S1_CLKSOURCE_PIN RCC_CFGR_I2SSRC /*!< External pin clock used as I2S1 clock */ -#endif /* RCC_CFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2SSRC | 0x00000000U) /*!< PLL clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2SSRC | (RCC_DCKCFGR_I2SSRC_0 >> 16)) /*!< External pin used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2SSRC | (RCC_DCKCFGR_I2SSRC_1 >> 16)) /*!< PLL Main clock used as I2S1 clock source */ -#endif /* RCC_DCKCFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2S1SRC) -#define LL_RCC_I2S1_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_I2S1SRC | 0x00000000U) /*!< PLLI2S clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC_0 >> 16)) /*!< External pin used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC_1 >> 16)) /*!< PLL clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC >> 16)) /*!< PLL Main clock used as I2S1 clock source */ -#endif /* RCC_DCKCFGR_I2S1SRC */ -#if defined(RCC_DCKCFGR_I2S2SRC) -#define LL_RCC_I2S2_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_I2S2SRC | 0x00000000U) /*!< PLLI2S clock used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC_0 >> 16)) /*!< External pin used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC_1 >> 16)) /*!< PLL clock used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC >> 16)) /*!< PLL Main clock used as I2S2 clock source */ -#endif /* RCC_DCKCFGR_I2S2SRC */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** @defgroup RCC_LL_EC_CK48M_CLKSOURCE Peripheral 48Mhz domain clock source selection - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE_PLL 0x00000000U /*!< PLL oscillator clock used as 48Mhz domain clock */ -#define LL_RCC_CK48M_CLKSOURCE_PLLSAI RCC_DCKCFGR_CK48MSEL /*!< PLLSAI oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -#if defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE_PLL 0x00000000U /*!< PLL oscillator clock used as 48Mhz domain clock */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CK48M_CLKSOURCE_PLLSAI RCC_DCKCFGR2_CK48MSEL /*!< PLLSAI oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_CK48M_CLKSOURCE_PLLI2S RCC_DCKCFGR2_CK48MSEL /*!< PLLI2S oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ - -#if defined(RNG) -/** @defgroup RCC_LL_EC_RNG_CLKSOURCE Peripheral RNG clock source selection - * @{ - */ -#define LL_RCC_RNG_CLKSOURCE_PLL LL_RCC_CK48M_CLKSOURCE_PLL /*!< PLL clock used as RNG clock source */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_RNG_CLKSOURCE_PLLSAI LL_RCC_CK48M_CLKSOURCE_PLLSAI /*!< PLLSAI clock used as RNG clock source */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_RNG_CLKSOURCE_PLLI2S LL_RCC_CK48M_CLKSOURCE_PLLI2S /*!< PLLI2S clock used as RNG clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -/** - * @} - */ -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** @defgroup RCC_LL_EC_USB_CLKSOURCE Peripheral USB clock source selection - * @{ - */ -#define LL_RCC_USB_CLKSOURCE_PLL LL_RCC_CK48M_CLKSOURCE_PLL /*!< PLL clock used as USB clock source */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_USB_CLKSOURCE_PLLSAI LL_RCC_CK48M_CLKSOURCE_PLLSAI /*!< PLLSAI clock used as USB clock source */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_USB_CLKSOURCE_PLLI2S LL_RCC_CK48M_CLKSOURCE_PLLI2S /*!< PLLI2S clock used as USB clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -/** - * @} - */ -#endif /* USB_OTG_FS || USB_OTG_HS */ - -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(DFSDM1_Channel0) || defined(DFSDM2_Channel0) -/** @defgroup RCC_LL_EC_DFSDM1_AUDIO_CLKSOURCE Peripheral DFSDM Audio clock source selection - * @{ - */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 (uint32_t)(RCC_DCKCFGR_CKDFSDM1ASEL | 0x00000000U) /*!< I2S1 clock used as DFSDM1 Audio clock source */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 (uint32_t)(RCC_DCKCFGR_CKDFSDM1ASEL | (RCC_DCKCFGR_CKDFSDM1ASEL << 16)) /*!< I2S2 clock used as DFSDM1 Audio clock source */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (uint32_t)(RCC_DCKCFGR_CKDFSDM2ASEL | 0x00000000U) /*!< I2S1 clock used as DFSDM2 Audio clock source */ -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (uint32_t)(RCC_DCKCFGR_CKDFSDM2ASEL | (RCC_DCKCFGR_CKDFSDM2ASEL << 16)) /*!< I2S2 clock used as DFSDM2 Audio clock source */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_DFSDM1_CLKSOURCE Peripheral DFSDM clock source selection - * @{ - */ -#define LL_RCC_DFSDM1_CLKSOURCE_PCLK2 0x00000000U /*!< PCLK2 clock used as DFSDM1 clock */ -#define LL_RCC_DFSDM1_CLKSOURCE_SYSCLK RCC_DCKCFGR_CKDFSDM1SEL /*!< System clock used as DFSDM1 clock */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_CLKSOURCE_PCLK2 0x00000000U /*!< PCLK2 clock used as DFSDM2 clock */ -#define LL_RCC_DFSDM2_CLKSOURCE_SYSCLK RCC_DCKCFGR_CKDFSDM1SEL /*!< System clock used as DFSDM2 clock */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ -#endif /* DFSDM1_Channel0 || DFSDM2_Channel0 */ - -#if defined(FMPI2C1) -/** @defgroup RCC_LL_EC_FMPI2C1 Peripheral FMPI2C get clock source - * @{ - */ -#define LL_RCC_FMPI2C1_CLKSOURCE RCC_DCKCFGR2_FMPI2C1SEL /*!< FMPI2C1 Clock source selection */ -/** - * @} - */ -#endif /* FMPI2C1 */ - -#if defined(SPDIFRX) -/** @defgroup RCC_LL_EC_SPDIFRX_CLKSOURCE Peripheral SPDIFRX clock source selection - * @{ - */ -#define LL_RCC_SPDIFRX1_CLKSOURCE_PLL 0x00000000U /*!< PLL clock used as SPDIFRX clock source */ -#define LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S RCC_DCKCFGR2_SPDIFRXSEL /*!< PLLI2S clock used as SPDIFRX clock source */ -/** - * @} - */ -#endif /* SPDIFRX */ - -#if defined(LPTIM1) -/** @defgroup RCC_LL_EC_LPTIM1 Peripheral LPTIM get clock source - * @{ - */ -#define LL_RCC_LPTIM1_CLKSOURCE RCC_DCKCFGR2_LPTIM1SEL /*!< LPTIM1 Clock source selection */ -/** - * @} - */ -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** @defgroup RCC_LL_EC_SAIx Peripheral SAI get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_SAI1ASRC) -#define LL_RCC_SAI1_A_CLKSOURCE RCC_DCKCFGR_SAI1ASRC /*!< SAI1 block A Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1ASRC */ -#if defined(RCC_DCKCFGR_SAI1BSRC) -#define LL_RCC_SAI1_B_CLKSOURCE RCC_DCKCFGR_SAI1BSRC /*!< SAI1 block B Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1BSRC */ -#if defined(RCC_DCKCFGR_SAI1SRC) -#define LL_RCC_SAI1_CLKSOURCE RCC_DCKCFGR_SAI1SRC /*!< SAI1 Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1SRC */ -#if defined(RCC_DCKCFGR_SAI2SRC) -#define LL_RCC_SAI2_CLKSOURCE RCC_DCKCFGR_SAI2SRC /*!< SAI2 Clock source selection */ -#endif /* RCC_DCKCFGR_SAI2SRC */ -/** - * @} - */ -#endif /* SAI1 */ - -#if defined(SDIO) -/** @defgroup RCC_LL_EC_SDIOx Peripheral SDIO get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE RCC_DCKCFGR_SDIOSEL /*!< SDIO Clock source selection */ -#elif defined(RCC_DCKCFGR2_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE RCC_DCKCFGR2_SDIOSEL /*!< SDIO Clock source selection */ -#else -#define LL_RCC_SDIO_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< SDIO Clock source selection */ -#endif -/** - * @} - */ -#endif /* SDIO */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** @defgroup RCC_LL_EC_CK48M Peripheral CK48M get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE RCC_DCKCFGR_CK48MSEL /*!< CK48M Domain clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -#if defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE RCC_DCKCFGR2_CK48MSEL /*!< CK48M Domain clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(RNG) -/** @defgroup RCC_LL_EC_RNG Peripheral RNG get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_RNG_CLKSOURCE LL_RCC_CK48M_CLKSOURCE /*!< RNG Clock source selection */ -#else -#define LL_RCC_RNG_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< RNG Clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** @defgroup RCC_LL_EC_USB Peripheral USB get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_USB_CLKSOURCE LL_RCC_CK48M_CLKSOURCE /*!< USB Clock source selection */ -#else -#define LL_RCC_USB_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< USB Clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ -#endif /* USB_OTG_FS || USB_OTG_HS */ - -#if defined(CEC) -/** @defgroup RCC_LL_EC_CEC Peripheral CEC get clock source - * @{ - */ -#define LL_RCC_CEC_CLKSOURCE RCC_DCKCFGR2_CECSEL /*!< CEC Clock source selection */ -/** - * @} - */ -#endif /* CEC */ - -/** @defgroup RCC_LL_EC_I2S1 Peripheral I2S get clock source - * @{ - */ -#if defined(RCC_CFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_CFGR_I2SSRC /*!< I2S1 Clock source selection */ -#endif /* RCC_CFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_DCKCFGR_I2SSRC /*!< I2S1 Clock source selection */ -#endif /* RCC_DCKCFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2S1SRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_DCKCFGR_I2S1SRC /*!< I2S1 Clock source selection */ -#endif /* RCC_DCKCFGR_I2S1SRC */ -#if defined(RCC_DCKCFGR_I2S2SRC) -#define LL_RCC_I2S2_CLKSOURCE RCC_DCKCFGR_I2S2SRC /*!< I2S2 Clock source selection */ -#endif /* RCC_DCKCFGR_I2S2SRC */ -/** - * @} - */ - -#if defined(DFSDM1_Channel0) || defined(DFSDM2_Channel0) -/** @defgroup RCC_LL_EC_DFSDM_AUDIO Peripheral DFSDM Audio get clock source - * @{ - */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE RCC_DCKCFGR_CKDFSDM1ASEL /*!< DFSDM1 Audio Clock source selection */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE RCC_DCKCFGR_CKDFSDM2ASEL /*!< DFSDM2 Audio Clock source selection */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_DFSDM Peripheral DFSDM get clock source - * @{ - */ -#define LL_RCC_DFSDM1_CLKSOURCE RCC_DCKCFGR_CKDFSDM1SEL /*!< DFSDM1 Clock source selection */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_CLKSOURCE RCC_DCKCFGR_CKDFSDM1SEL /*!< DFSDM2 Clock source selection */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ -#endif /* DFSDM1_Channel0 || DFSDM2_Channel0 */ - -#if defined(SPDIFRX) -/** @defgroup RCC_LL_EC_SPDIFRX Peripheral SPDIFRX get clock source - * @{ - */ -#define LL_RCC_SPDIFRX1_CLKSOURCE RCC_DCKCFGR2_SPDIFRXSEL /*!< SPDIFRX Clock source selection */ -/** - * @} - */ -#endif /* SPDIFRX */ - -#if defined(DSI) -/** @defgroup RCC_LL_EC_DSI Peripheral DSI get clock source - * @{ - */ -#define LL_RCC_DSI_CLKSOURCE RCC_DCKCFGR_DSISEL /*!< DSI Clock source selection */ -/** - * @} - */ -#endif /* DSI */ - -#if defined(LTDC) -/** @defgroup RCC_LL_EC_LTDC Peripheral LTDC get clock source - * @{ - */ -#define LL_RCC_LTDC_CLKSOURCE RCC_DCKCFGR_PLLSAIDIVR /*!< LTDC Clock source selection */ -/** - * @} - */ -#endif /* LTDC */ - - -/** @defgroup RCC_LL_EC_RTC_CLKSOURCE RTC clock source selection - * @{ - */ -#define LL_RCC_RTC_CLKSOURCE_NONE 0x00000000U /*!< No clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_LSE RCC_BDCR_RTCSEL_0 /*!< LSE oscillator clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_LSI RCC_BDCR_RTCSEL_1 /*!< LSI oscillator clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_HSE RCC_BDCR_RTCSEL /*!< HSE oscillator clock divided by HSE prescaler used as RTC clock */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_TIMPRE) -/** @defgroup RCC_LL_EC_TIM_CLKPRESCALER Timers clocks prescalers selection - * @{ - */ -#define LL_RCC_TIM_PRESCALER_TWICE 0x00000000U /*!< Timers clock to twice PCLK */ -#define LL_RCC_TIM_PRESCALER_FOUR_TIMES RCC_DCKCFGR_TIMPRE /*!< Timers clock to four time PCLK */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_TIMPRE */ - -/** @defgroup RCC_LL_EC_PLLSOURCE PLL, PLLI2S and PLLSAI entry clock source - * @{ - */ -#define LL_RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI /*!< HSI16 clock selected as PLL entry clock source */ -#define LL_RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE /*!< HSE clock selected as PLL entry clock source */ -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) -#define LL_RCC_PLLI2SSOURCE_PIN (RCC_PLLI2SCFGR_PLLI2SSRC | 0x80U) /*!< I2S External pin input clock selected as PLLI2S entry clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLM_DIV PLL, PLLI2S and PLLSAI division factor - * @{ - */ -#define LL_RCC_PLLM_DIV_2 (RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 2 */ -#define LL_RCC_PLLM_DIV_3 (RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 3 */ -#define LL_RCC_PLLM_DIV_4 (RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 4 */ -#define LL_RCC_PLLM_DIV_5 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 5 */ -#define LL_RCC_PLLM_DIV_6 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 6 */ -#define LL_RCC_PLLM_DIV_7 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 7 */ -#define LL_RCC_PLLM_DIV_8 (RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 8 */ -#define LL_RCC_PLLM_DIV_9 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 9 */ -#define LL_RCC_PLLM_DIV_10 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 10 */ -#define LL_RCC_PLLM_DIV_11 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 11 */ -#define LL_RCC_PLLM_DIV_12 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 12 */ -#define LL_RCC_PLLM_DIV_13 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 13 */ -#define LL_RCC_PLLM_DIV_14 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 14 */ -#define LL_RCC_PLLM_DIV_15 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 15 */ -#define LL_RCC_PLLM_DIV_16 (RCC_PLLCFGR_PLLM_4) /*!< PLL, PLLI2S and PLLSAI division factor by 16 */ -#define LL_RCC_PLLM_DIV_17 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 17 */ -#define LL_RCC_PLLM_DIV_18 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 18 */ -#define LL_RCC_PLLM_DIV_19 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 19 */ -#define LL_RCC_PLLM_DIV_20 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 20 */ -#define LL_RCC_PLLM_DIV_21 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 21 */ -#define LL_RCC_PLLM_DIV_22 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 22 */ -#define LL_RCC_PLLM_DIV_23 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 23 */ -#define LL_RCC_PLLM_DIV_24 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 24 */ -#define LL_RCC_PLLM_DIV_25 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 25 */ -#define LL_RCC_PLLM_DIV_26 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 26 */ -#define LL_RCC_PLLM_DIV_27 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 27 */ -#define LL_RCC_PLLM_DIV_28 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 28 */ -#define LL_RCC_PLLM_DIV_29 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 29 */ -#define LL_RCC_PLLM_DIV_30 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 30 */ -#define LL_RCC_PLLM_DIV_31 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 31 */ -#define LL_RCC_PLLM_DIV_32 (RCC_PLLCFGR_PLLM_5) /*!< PLL, PLLI2S and PLLSAI division factor by 32 */ -#define LL_RCC_PLLM_DIV_33 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 33 */ -#define LL_RCC_PLLM_DIV_34 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 34 */ -#define LL_RCC_PLLM_DIV_35 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 35 */ -#define LL_RCC_PLLM_DIV_36 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 36 */ -#define LL_RCC_PLLM_DIV_37 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 37 */ -#define LL_RCC_PLLM_DIV_38 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 38 */ -#define LL_RCC_PLLM_DIV_39 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 39 */ -#define LL_RCC_PLLM_DIV_40 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 40 */ -#define LL_RCC_PLLM_DIV_41 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 41 */ -#define LL_RCC_PLLM_DIV_42 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 42 */ -#define LL_RCC_PLLM_DIV_43 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 43 */ -#define LL_RCC_PLLM_DIV_44 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 44 */ -#define LL_RCC_PLLM_DIV_45 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 45 */ -#define LL_RCC_PLLM_DIV_46 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 46 */ -#define LL_RCC_PLLM_DIV_47 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 47 */ -#define LL_RCC_PLLM_DIV_48 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4) /*!< PLL, PLLI2S and PLLSAI division factor by 48 */ -#define LL_RCC_PLLM_DIV_49 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 49 */ -#define LL_RCC_PLLM_DIV_50 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 50 */ -#define LL_RCC_PLLM_DIV_51 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 51 */ -#define LL_RCC_PLLM_DIV_52 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 52 */ -#define LL_RCC_PLLM_DIV_53 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 53 */ -#define LL_RCC_PLLM_DIV_54 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 54 */ -#define LL_RCC_PLLM_DIV_55 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 55 */ -#define LL_RCC_PLLM_DIV_56 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 56 */ -#define LL_RCC_PLLM_DIV_57 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 57 */ -#define LL_RCC_PLLM_DIV_58 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 58 */ -#define LL_RCC_PLLM_DIV_59 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 59 */ -#define LL_RCC_PLLM_DIV_60 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 60 */ -#define LL_RCC_PLLM_DIV_61 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 61 */ -#define LL_RCC_PLLM_DIV_62 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 62 */ -#define LL_RCC_PLLM_DIV_63 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 63 */ -/** - * @} - */ - -#if defined(RCC_PLLCFGR_PLLR) -/** @defgroup RCC_LL_EC_PLLR_DIV PLL division factor (PLLR) - * @{ - */ -#define LL_RCC_PLLR_DIV_2 (RCC_PLLCFGR_PLLR_1) /*!< Main PLL division factor for PLLCLK (system clock) by 2 */ -#define LL_RCC_PLLR_DIV_3 (RCC_PLLCFGR_PLLR_1|RCC_PLLCFGR_PLLR_0) /*!< Main PLL division factor for PLLCLK (system clock) by 3 */ -#define LL_RCC_PLLR_DIV_4 (RCC_PLLCFGR_PLLR_2) /*!< Main PLL division factor for PLLCLK (system clock) by 4 */ -#define LL_RCC_PLLR_DIV_5 (RCC_PLLCFGR_PLLR_2|RCC_PLLCFGR_PLLR_0) /*!< Main PLL division factor for PLLCLK (system clock) by 5 */ -#define LL_RCC_PLLR_DIV_6 (RCC_PLLCFGR_PLLR_2|RCC_PLLCFGR_PLLR_1) /*!< Main PLL division factor for PLLCLK (system clock) by 6 */ -#define LL_RCC_PLLR_DIV_7 (RCC_PLLCFGR_PLLR) /*!< Main PLL division factor for PLLCLK (system clock) by 7 */ -/** - * @} - */ -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_DCKCFGR_PLLDIVR) -/** @defgroup RCC_LL_EC_PLLDIVR PLLDIVR division factor (PLLDIVR) - * @{ - */ -#define LL_RCC_PLLDIVR_DIV_1 (RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 1 */ -#define LL_RCC_PLLDIVR_DIV_2 (RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 2 */ -#define LL_RCC_PLLDIVR_DIV_3 (RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 3 */ -#define LL_RCC_PLLDIVR_DIV_4 (RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 4 */ -#define LL_RCC_PLLDIVR_DIV_5 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 5 */ -#define LL_RCC_PLLDIVR_DIV_6 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 6 */ -#define LL_RCC_PLLDIVR_DIV_7 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 7 */ -#define LL_RCC_PLLDIVR_DIV_8 (RCC_DCKCFGR_PLLDIVR_3) /*!< PLL division factor for PLLDIVR output by 8 */ -#define LL_RCC_PLLDIVR_DIV_9 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 9 */ -#define LL_RCC_PLLDIVR_DIV_10 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 10 */ -#define LL_RCC_PLLDIVR_DIV_11 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 11 */ -#define LL_RCC_PLLDIVR_DIV_12 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 12 */ -#define LL_RCC_PLLDIVR_DIV_13 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 13 */ -#define LL_RCC_PLLDIVR_DIV_14 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 14 */ -#define LL_RCC_PLLDIVR_DIV_15 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 15 */ -#define LL_RCC_PLLDIVR_DIV_16 (RCC_DCKCFGR_PLLDIVR_4) /*!< PLL division factor for PLLDIVR output by 16 */ -#define LL_RCC_PLLDIVR_DIV_17 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 17 */ -#define LL_RCC_PLLDIVR_DIV_18 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 18 */ -#define LL_RCC_PLLDIVR_DIV_19 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 19 */ -#define LL_RCC_PLLDIVR_DIV_20 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 20 */ -#define LL_RCC_PLLDIVR_DIV_21 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 21 */ -#define LL_RCC_PLLDIVR_DIV_22 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 22 */ -#define LL_RCC_PLLDIVR_DIV_23 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 23 */ -#define LL_RCC_PLLDIVR_DIV_24 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3) /*!< PLL division factor for PLLDIVR output by 24 */ -#define LL_RCC_PLLDIVR_DIV_25 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 25 */ -#define LL_RCC_PLLDIVR_DIV_26 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 26 */ -#define LL_RCC_PLLDIVR_DIV_27 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 27 */ -#define LL_RCC_PLLDIVR_DIV_28 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 28 */ -#define LL_RCC_PLLDIVR_DIV_29 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 29 */ -#define LL_RCC_PLLDIVR_DIV_30 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 30 */ -#define LL_RCC_PLLDIVR_DIV_31 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 31 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLDIVR */ - -/** @defgroup RCC_LL_EC_PLLP_DIV PLL division factor (PLLP) - * @{ - */ -#define LL_RCC_PLLP_DIV_2 0x00000000U /*!< Main PLL division factor for PLLP output by 2 */ -#define LL_RCC_PLLP_DIV_4 RCC_PLLCFGR_PLLP_0 /*!< Main PLL division factor for PLLP output by 4 */ -#define LL_RCC_PLLP_DIV_6 RCC_PLLCFGR_PLLP_1 /*!< Main PLL division factor for PLLP output by 6 */ -#define LL_RCC_PLLP_DIV_8 (RCC_PLLCFGR_PLLP_1 | RCC_PLLCFGR_PLLP_0) /*!< Main PLL division factor for PLLP output by 8 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLQ_DIV PLL division factor (PLLQ) - * @{ - */ -#define LL_RCC_PLLQ_DIV_2 RCC_PLLCFGR_PLLQ_1 /*!< Main PLL division factor for PLLQ output by 2 */ -#define LL_RCC_PLLQ_DIV_3 (RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 3 */ -#define LL_RCC_PLLQ_DIV_4 RCC_PLLCFGR_PLLQ_2 /*!< Main PLL division factor for PLLQ output by 4 */ -#define LL_RCC_PLLQ_DIV_5 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 5 */ -#define LL_RCC_PLLQ_DIV_6 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 6 */ -#define LL_RCC_PLLQ_DIV_7 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 7 */ -#define LL_RCC_PLLQ_DIV_8 RCC_PLLCFGR_PLLQ_3 /*!< Main PLL division factor for PLLQ output by 8 */ -#define LL_RCC_PLLQ_DIV_9 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 9 */ -#define LL_RCC_PLLQ_DIV_10 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 10 */ -#define LL_RCC_PLLQ_DIV_11 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 11 */ -#define LL_RCC_PLLQ_DIV_12 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2) /*!< Main PLL division factor for PLLQ output by 12 */ -#define LL_RCC_PLLQ_DIV_13 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 13 */ -#define LL_RCC_PLLQ_DIV_14 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 14 */ -#define LL_RCC_PLLQ_DIV_15 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 15 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLL_SPRE_SEL PLL Spread Spectrum Selection - * @{ - */ -#define LL_RCC_SPREAD_SELECT_CENTER 0x00000000U /*!< PLL center spread spectrum selection */ -#define LL_RCC_SPREAD_SELECT_DOWN RCC_SSCGR_SPREADSEL /*!< PLL down spread spectrum selection */ -/** - * @} - */ - -#if defined(RCC_PLLI2S_SUPPORT) -/** @defgroup RCC_LL_EC_PLLI2SM PLLI2SM division factor (PLLI2SM) - * @{ - */ -#if defined(RCC_PLLI2SCFGR_PLLI2SM) -#define LL_RCC_PLLI2SM_DIV_2 (RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 2 */ -#define LL_RCC_PLLI2SM_DIV_3 (RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 3 */ -#define LL_RCC_PLLI2SM_DIV_4 (RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 4 */ -#define LL_RCC_PLLI2SM_DIV_5 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 5 */ -#define LL_RCC_PLLI2SM_DIV_6 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 6 */ -#define LL_RCC_PLLI2SM_DIV_7 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 7 */ -#define LL_RCC_PLLI2SM_DIV_8 (RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 8 */ -#define LL_RCC_PLLI2SM_DIV_9 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 9 */ -#define LL_RCC_PLLI2SM_DIV_10 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 10 */ -#define LL_RCC_PLLI2SM_DIV_11 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 11 */ -#define LL_RCC_PLLI2SM_DIV_12 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 12 */ -#define LL_RCC_PLLI2SM_DIV_13 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 13 */ -#define LL_RCC_PLLI2SM_DIV_14 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 14 */ -#define LL_RCC_PLLI2SM_DIV_15 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 15 */ -#define LL_RCC_PLLI2SM_DIV_16 (RCC_PLLI2SCFGR_PLLI2SM_4) /*!< PLLI2S division factor for PLLI2SM output by 16 */ -#define LL_RCC_PLLI2SM_DIV_17 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 17 */ -#define LL_RCC_PLLI2SM_DIV_18 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 18 */ -#define LL_RCC_PLLI2SM_DIV_19 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 19 */ -#define LL_RCC_PLLI2SM_DIV_20 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 20 */ -#define LL_RCC_PLLI2SM_DIV_21 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 21 */ -#define LL_RCC_PLLI2SM_DIV_22 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 22 */ -#define LL_RCC_PLLI2SM_DIV_23 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 23 */ -#define LL_RCC_PLLI2SM_DIV_24 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 24 */ -#define LL_RCC_PLLI2SM_DIV_25 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 25 */ -#define LL_RCC_PLLI2SM_DIV_26 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 26 */ -#define LL_RCC_PLLI2SM_DIV_27 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 27 */ -#define LL_RCC_PLLI2SM_DIV_28 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 28 */ -#define LL_RCC_PLLI2SM_DIV_29 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 29 */ -#define LL_RCC_PLLI2SM_DIV_30 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 30 */ -#define LL_RCC_PLLI2SM_DIV_31 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 31 */ -#define LL_RCC_PLLI2SM_DIV_32 (RCC_PLLI2SCFGR_PLLI2SM_5) /*!< PLLI2S division factor for PLLI2SM output by 32 */ -#define LL_RCC_PLLI2SM_DIV_33 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 33 */ -#define LL_RCC_PLLI2SM_DIV_34 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 34 */ -#define LL_RCC_PLLI2SM_DIV_35 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 35 */ -#define LL_RCC_PLLI2SM_DIV_36 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 36 */ -#define LL_RCC_PLLI2SM_DIV_37 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 37 */ -#define LL_RCC_PLLI2SM_DIV_38 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 38 */ -#define LL_RCC_PLLI2SM_DIV_39 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 39 */ -#define LL_RCC_PLLI2SM_DIV_40 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 40 */ -#define LL_RCC_PLLI2SM_DIV_41 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 41 */ -#define LL_RCC_PLLI2SM_DIV_42 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 42 */ -#define LL_RCC_PLLI2SM_DIV_43 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 43 */ -#define LL_RCC_PLLI2SM_DIV_44 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 44 */ -#define LL_RCC_PLLI2SM_DIV_45 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 45 */ -#define LL_RCC_PLLI2SM_DIV_46 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 46 */ -#define LL_RCC_PLLI2SM_DIV_47 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 47 */ -#define LL_RCC_PLLI2SM_DIV_48 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4) /*!< PLLI2S division factor for PLLI2SM output by 48 */ -#define LL_RCC_PLLI2SM_DIV_49 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 49 */ -#define LL_RCC_PLLI2SM_DIV_50 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 50 */ -#define LL_RCC_PLLI2SM_DIV_51 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 51 */ -#define LL_RCC_PLLI2SM_DIV_52 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 52 */ -#define LL_RCC_PLLI2SM_DIV_53 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 53 */ -#define LL_RCC_PLLI2SM_DIV_54 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 54 */ -#define LL_RCC_PLLI2SM_DIV_55 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 55 */ -#define LL_RCC_PLLI2SM_DIV_56 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 56 */ -#define LL_RCC_PLLI2SM_DIV_57 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 57 */ -#define LL_RCC_PLLI2SM_DIV_58 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 58 */ -#define LL_RCC_PLLI2SM_DIV_59 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 59 */ -#define LL_RCC_PLLI2SM_DIV_60 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 60 */ -#define LL_RCC_PLLI2SM_DIV_61 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 61 */ -#define LL_RCC_PLLI2SM_DIV_62 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 62 */ -#define LL_RCC_PLLI2SM_DIV_63 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 63 */ -#else -#define LL_RCC_PLLI2SM_DIV_2 LL_RCC_PLLM_DIV_2 /*!< PLLI2S division factor for PLLI2SM output by 2 */ -#define LL_RCC_PLLI2SM_DIV_3 LL_RCC_PLLM_DIV_3 /*!< PLLI2S division factor for PLLI2SM output by 3 */ -#define LL_RCC_PLLI2SM_DIV_4 LL_RCC_PLLM_DIV_4 /*!< PLLI2S division factor for PLLI2SM output by 4 */ -#define LL_RCC_PLLI2SM_DIV_5 LL_RCC_PLLM_DIV_5 /*!< PLLI2S division factor for PLLI2SM output by 5 */ -#define LL_RCC_PLLI2SM_DIV_6 LL_RCC_PLLM_DIV_6 /*!< PLLI2S division factor for PLLI2SM output by 6 */ -#define LL_RCC_PLLI2SM_DIV_7 LL_RCC_PLLM_DIV_7 /*!< PLLI2S division factor for PLLI2SM output by 7 */ -#define LL_RCC_PLLI2SM_DIV_8 LL_RCC_PLLM_DIV_8 /*!< PLLI2S division factor for PLLI2SM output by 8 */ -#define LL_RCC_PLLI2SM_DIV_9 LL_RCC_PLLM_DIV_9 /*!< PLLI2S division factor for PLLI2SM output by 9 */ -#define LL_RCC_PLLI2SM_DIV_10 LL_RCC_PLLM_DIV_10 /*!< PLLI2S division factor for PLLI2SM output by 10 */ -#define LL_RCC_PLLI2SM_DIV_11 LL_RCC_PLLM_DIV_11 /*!< PLLI2S division factor for PLLI2SM output by 11 */ -#define LL_RCC_PLLI2SM_DIV_12 LL_RCC_PLLM_DIV_12 /*!< PLLI2S division factor for PLLI2SM output by 12 */ -#define LL_RCC_PLLI2SM_DIV_13 LL_RCC_PLLM_DIV_13 /*!< PLLI2S division factor for PLLI2SM output by 13 */ -#define LL_RCC_PLLI2SM_DIV_14 LL_RCC_PLLM_DIV_14 /*!< PLLI2S division factor for PLLI2SM output by 14 */ -#define LL_RCC_PLLI2SM_DIV_15 LL_RCC_PLLM_DIV_15 /*!< PLLI2S division factor for PLLI2SM output by 15 */ -#define LL_RCC_PLLI2SM_DIV_16 LL_RCC_PLLM_DIV_16 /*!< PLLI2S division factor for PLLI2SM output by 16 */ -#define LL_RCC_PLLI2SM_DIV_17 LL_RCC_PLLM_DIV_17 /*!< PLLI2S division factor for PLLI2SM output by 17 */ -#define LL_RCC_PLLI2SM_DIV_18 LL_RCC_PLLM_DIV_18 /*!< PLLI2S division factor for PLLI2SM output by 18 */ -#define LL_RCC_PLLI2SM_DIV_19 LL_RCC_PLLM_DIV_19 /*!< PLLI2S division factor for PLLI2SM output by 19 */ -#define LL_RCC_PLLI2SM_DIV_20 LL_RCC_PLLM_DIV_20 /*!< PLLI2S division factor for PLLI2SM output by 20 */ -#define LL_RCC_PLLI2SM_DIV_21 LL_RCC_PLLM_DIV_21 /*!< PLLI2S division factor for PLLI2SM output by 21 */ -#define LL_RCC_PLLI2SM_DIV_22 LL_RCC_PLLM_DIV_22 /*!< PLLI2S division factor for PLLI2SM output by 22 */ -#define LL_RCC_PLLI2SM_DIV_23 LL_RCC_PLLM_DIV_23 /*!< PLLI2S division factor for PLLI2SM output by 23 */ -#define LL_RCC_PLLI2SM_DIV_24 LL_RCC_PLLM_DIV_24 /*!< PLLI2S division factor for PLLI2SM output by 24 */ -#define LL_RCC_PLLI2SM_DIV_25 LL_RCC_PLLM_DIV_25 /*!< PLLI2S division factor for PLLI2SM output by 25 */ -#define LL_RCC_PLLI2SM_DIV_26 LL_RCC_PLLM_DIV_26 /*!< PLLI2S division factor for PLLI2SM output by 26 */ -#define LL_RCC_PLLI2SM_DIV_27 LL_RCC_PLLM_DIV_27 /*!< PLLI2S division factor for PLLI2SM output by 27 */ -#define LL_RCC_PLLI2SM_DIV_28 LL_RCC_PLLM_DIV_28 /*!< PLLI2S division factor for PLLI2SM output by 28 */ -#define LL_RCC_PLLI2SM_DIV_29 LL_RCC_PLLM_DIV_29 /*!< PLLI2S division factor for PLLI2SM output by 29 */ -#define LL_RCC_PLLI2SM_DIV_30 LL_RCC_PLLM_DIV_30 /*!< PLLI2S division factor for PLLI2SM output by 30 */ -#define LL_RCC_PLLI2SM_DIV_31 LL_RCC_PLLM_DIV_31 /*!< PLLI2S division factor for PLLI2SM output by 31 */ -#define LL_RCC_PLLI2SM_DIV_32 LL_RCC_PLLM_DIV_32 /*!< PLLI2S division factor for PLLI2SM output by 32 */ -#define LL_RCC_PLLI2SM_DIV_33 LL_RCC_PLLM_DIV_33 /*!< PLLI2S division factor for PLLI2SM output by 33 */ -#define LL_RCC_PLLI2SM_DIV_34 LL_RCC_PLLM_DIV_34 /*!< PLLI2S division factor for PLLI2SM output by 34 */ -#define LL_RCC_PLLI2SM_DIV_35 LL_RCC_PLLM_DIV_35 /*!< PLLI2S division factor for PLLI2SM output by 35 */ -#define LL_RCC_PLLI2SM_DIV_36 LL_RCC_PLLM_DIV_36 /*!< PLLI2S division factor for PLLI2SM output by 36 */ -#define LL_RCC_PLLI2SM_DIV_37 LL_RCC_PLLM_DIV_37 /*!< PLLI2S division factor for PLLI2SM output by 37 */ -#define LL_RCC_PLLI2SM_DIV_38 LL_RCC_PLLM_DIV_38 /*!< PLLI2S division factor for PLLI2SM output by 38 */ -#define LL_RCC_PLLI2SM_DIV_39 LL_RCC_PLLM_DIV_39 /*!< PLLI2S division factor for PLLI2SM output by 39 */ -#define LL_RCC_PLLI2SM_DIV_40 LL_RCC_PLLM_DIV_40 /*!< PLLI2S division factor for PLLI2SM output by 40 */ -#define LL_RCC_PLLI2SM_DIV_41 LL_RCC_PLLM_DIV_41 /*!< PLLI2S division factor for PLLI2SM output by 41 */ -#define LL_RCC_PLLI2SM_DIV_42 LL_RCC_PLLM_DIV_42 /*!< PLLI2S division factor for PLLI2SM output by 42 */ -#define LL_RCC_PLLI2SM_DIV_43 LL_RCC_PLLM_DIV_43 /*!< PLLI2S division factor for PLLI2SM output by 43 */ -#define LL_RCC_PLLI2SM_DIV_44 LL_RCC_PLLM_DIV_44 /*!< PLLI2S division factor for PLLI2SM output by 44 */ -#define LL_RCC_PLLI2SM_DIV_45 LL_RCC_PLLM_DIV_45 /*!< PLLI2S division factor for PLLI2SM output by 45 */ -#define LL_RCC_PLLI2SM_DIV_46 LL_RCC_PLLM_DIV_46 /*!< PLLI2S division factor for PLLI2SM output by 46 */ -#define LL_RCC_PLLI2SM_DIV_47 LL_RCC_PLLM_DIV_47 /*!< PLLI2S division factor for PLLI2SM output by 47 */ -#define LL_RCC_PLLI2SM_DIV_48 LL_RCC_PLLM_DIV_48 /*!< PLLI2S division factor for PLLI2SM output by 48 */ -#define LL_RCC_PLLI2SM_DIV_49 LL_RCC_PLLM_DIV_49 /*!< PLLI2S division factor for PLLI2SM output by 49 */ -#define LL_RCC_PLLI2SM_DIV_50 LL_RCC_PLLM_DIV_50 /*!< PLLI2S division factor for PLLI2SM output by 50 */ -#define LL_RCC_PLLI2SM_DIV_51 LL_RCC_PLLM_DIV_51 /*!< PLLI2S division factor for PLLI2SM output by 51 */ -#define LL_RCC_PLLI2SM_DIV_52 LL_RCC_PLLM_DIV_52 /*!< PLLI2S division factor for PLLI2SM output by 52 */ -#define LL_RCC_PLLI2SM_DIV_53 LL_RCC_PLLM_DIV_53 /*!< PLLI2S division factor for PLLI2SM output by 53 */ -#define LL_RCC_PLLI2SM_DIV_54 LL_RCC_PLLM_DIV_54 /*!< PLLI2S division factor for PLLI2SM output by 54 */ -#define LL_RCC_PLLI2SM_DIV_55 LL_RCC_PLLM_DIV_55 /*!< PLLI2S division factor for PLLI2SM output by 55 */ -#define LL_RCC_PLLI2SM_DIV_56 LL_RCC_PLLM_DIV_56 /*!< PLLI2S division factor for PLLI2SM output by 56 */ -#define LL_RCC_PLLI2SM_DIV_57 LL_RCC_PLLM_DIV_57 /*!< PLLI2S division factor for PLLI2SM output by 57 */ -#define LL_RCC_PLLI2SM_DIV_58 LL_RCC_PLLM_DIV_58 /*!< PLLI2S division factor for PLLI2SM output by 58 */ -#define LL_RCC_PLLI2SM_DIV_59 LL_RCC_PLLM_DIV_59 /*!< PLLI2S division factor for PLLI2SM output by 59 */ -#define LL_RCC_PLLI2SM_DIV_60 LL_RCC_PLLM_DIV_60 /*!< PLLI2S division factor for PLLI2SM output by 60 */ -#define LL_RCC_PLLI2SM_DIV_61 LL_RCC_PLLM_DIV_61 /*!< PLLI2S division factor for PLLI2SM output by 61 */ -#define LL_RCC_PLLI2SM_DIV_62 LL_RCC_PLLM_DIV_62 /*!< PLLI2S division factor for PLLI2SM output by 62 */ -#define LL_RCC_PLLI2SM_DIV_63 LL_RCC_PLLM_DIV_63 /*!< PLLI2S division factor for PLLI2SM output by 63 */ -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ -/** - * @} - */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) -/** @defgroup RCC_LL_EC_PLLI2SQ PLLI2SQ division factor (PLLI2SQ) - * @{ - */ -#define LL_RCC_PLLI2SQ_DIV_2 RCC_PLLI2SCFGR_PLLI2SQ_1 /*!< PLLI2S division factor for PLLI2SQ output by 2 */ -#define LL_RCC_PLLI2SQ_DIV_3 (RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 3 */ -#define LL_RCC_PLLI2SQ_DIV_4 RCC_PLLI2SCFGR_PLLI2SQ_2 /*!< PLLI2S division factor for PLLI2SQ output by 4 */ -#define LL_RCC_PLLI2SQ_DIV_5 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 5 */ -#define LL_RCC_PLLI2SQ_DIV_6 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 6 */ -#define LL_RCC_PLLI2SQ_DIV_7 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 7 */ -#define LL_RCC_PLLI2SQ_DIV_8 RCC_PLLI2SCFGR_PLLI2SQ_3 /*!< PLLI2S division factor for PLLI2SQ output by 8 */ -#define LL_RCC_PLLI2SQ_DIV_9 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 9 */ -#define LL_RCC_PLLI2SQ_DIV_10 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 10 */ -#define LL_RCC_PLLI2SQ_DIV_11 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 11 */ -#define LL_RCC_PLLI2SQ_DIV_12 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2) /*!< PLLI2S division factor for PLLI2SQ output by 12 */ -#define LL_RCC_PLLI2SQ_DIV_13 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 13 */ -#define LL_RCC_PLLI2SQ_DIV_14 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 14 */ -#define LL_RCC_PLLI2SQ_DIV_15 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 15 */ -/** - * @} - */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** @defgroup RCC_LL_EC_PLLI2SDIVQ PLLI2SDIVQ division factor (PLLI2SDIVQ) - * @{ - */ -#define LL_RCC_PLLI2SDIVQ_DIV_1 0x00000000U /*!< PLLI2S division factor for PLLI2SDIVQ output by 1 */ -#define LL_RCC_PLLI2SDIVQ_DIV_2 RCC_DCKCFGR_PLLI2SDIVQ_0 /*!< PLLI2S division factor for PLLI2SDIVQ output by 2 */ -#define LL_RCC_PLLI2SDIVQ_DIV_3 RCC_DCKCFGR_PLLI2SDIVQ_1 /*!< PLLI2S division factor for PLLI2SDIVQ output by 3 */ -#define LL_RCC_PLLI2SDIVQ_DIV_4 (RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 4 */ -#define LL_RCC_PLLI2SDIVQ_DIV_5 RCC_DCKCFGR_PLLI2SDIVQ_2 /*!< PLLI2S division factor for PLLI2SDIVQ output by 5 */ -#define LL_RCC_PLLI2SDIVQ_DIV_6 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 6 */ -#define LL_RCC_PLLI2SDIVQ_DIV_7 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 7 */ -#define LL_RCC_PLLI2SDIVQ_DIV_8 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 8 */ -#define LL_RCC_PLLI2SDIVQ_DIV_9 RCC_DCKCFGR_PLLI2SDIVQ_3 /*!< PLLI2S division factor for PLLI2SDIVQ output by 9 */ -#define LL_RCC_PLLI2SDIVQ_DIV_10 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 10 */ -#define LL_RCC_PLLI2SDIVQ_DIV_11 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 11 */ -#define LL_RCC_PLLI2SDIVQ_DIV_12 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 12 */ -#define LL_RCC_PLLI2SDIVQ_DIV_13 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 13 */ -#define LL_RCC_PLLI2SDIVQ_DIV_14 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 14 */ -#define LL_RCC_PLLI2SDIVQ_DIV_15 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 15 */ -#define LL_RCC_PLLI2SDIVQ_DIV_16 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 16 */ -#define LL_RCC_PLLI2SDIVQ_DIV_17 RCC_DCKCFGR_PLLI2SDIVQ_4 /*!< PLLI2S division factor for PLLI2SDIVQ output by 17 */ -#define LL_RCC_PLLI2SDIVQ_DIV_18 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 18 */ -#define LL_RCC_PLLI2SDIVQ_DIV_19 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 19 */ -#define LL_RCC_PLLI2SDIVQ_DIV_20 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 20 */ -#define LL_RCC_PLLI2SDIVQ_DIV_21 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 21 */ -#define LL_RCC_PLLI2SDIVQ_DIV_22 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 22 */ -#define LL_RCC_PLLI2SDIVQ_DIV_23 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 23 */ -#define LL_RCC_PLLI2SDIVQ_DIV_24 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 24 */ -#define LL_RCC_PLLI2SDIVQ_DIV_25 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3) /*!< PLLI2S division factor for PLLI2SDIVQ output by 25 */ -#define LL_RCC_PLLI2SDIVQ_DIV_26 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 26 */ -#define LL_RCC_PLLI2SDIVQ_DIV_27 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 27 */ -#define LL_RCC_PLLI2SDIVQ_DIV_28 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 28 */ -#define LL_RCC_PLLI2SDIVQ_DIV_29 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 29 */ -#define LL_RCC_PLLI2SDIVQ_DIV_30 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 30 */ -#define LL_RCC_PLLI2SDIVQ_DIV_31 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 31 */ -#define LL_RCC_PLLI2SDIVQ_DIV_32 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 32 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVR) -/** @defgroup RCC_LL_EC_PLLI2SDIVR PLLI2SDIVR division factor (PLLI2SDIVR) - * @{ - */ -#define LL_RCC_PLLI2SDIVR_DIV_1 (RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 1 */ -#define LL_RCC_PLLI2SDIVR_DIV_2 (RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 2 */ -#define LL_RCC_PLLI2SDIVR_DIV_3 (RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 3 */ -#define LL_RCC_PLLI2SDIVR_DIV_4 (RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 4 */ -#define LL_RCC_PLLI2SDIVR_DIV_5 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 5 */ -#define LL_RCC_PLLI2SDIVR_DIV_6 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 6 */ -#define LL_RCC_PLLI2SDIVR_DIV_7 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 7 */ -#define LL_RCC_PLLI2SDIVR_DIV_8 (RCC_DCKCFGR_PLLI2SDIVR_3) /*!< PLLI2S division factor for PLLI2SDIVR output by 8 */ -#define LL_RCC_PLLI2SDIVR_DIV_9 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 9 */ -#define LL_RCC_PLLI2SDIVR_DIV_10 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 10 */ -#define LL_RCC_PLLI2SDIVR_DIV_11 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 11 */ -#define LL_RCC_PLLI2SDIVR_DIV_12 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 12 */ -#define LL_RCC_PLLI2SDIVR_DIV_13 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 13 */ -#define LL_RCC_PLLI2SDIVR_DIV_14 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 14 */ -#define LL_RCC_PLLI2SDIVR_DIV_15 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 15 */ -#define LL_RCC_PLLI2SDIVR_DIV_16 (RCC_DCKCFGR_PLLI2SDIVR_4) /*!< PLLI2S division factor for PLLI2SDIVR output by 16 */ -#define LL_RCC_PLLI2SDIVR_DIV_17 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 17 */ -#define LL_RCC_PLLI2SDIVR_DIV_18 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 18 */ -#define LL_RCC_PLLI2SDIVR_DIV_19 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 19 */ -#define LL_RCC_PLLI2SDIVR_DIV_20 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 20 */ -#define LL_RCC_PLLI2SDIVR_DIV_21 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 21 */ -#define LL_RCC_PLLI2SDIVR_DIV_22 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 22 */ -#define LL_RCC_PLLI2SDIVR_DIV_23 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 23 */ -#define LL_RCC_PLLI2SDIVR_DIV_24 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3) /*!< PLLI2S division factor for PLLI2SDIVR output by 24 */ -#define LL_RCC_PLLI2SDIVR_DIV_25 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 25 */ -#define LL_RCC_PLLI2SDIVR_DIV_26 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 26 */ -#define LL_RCC_PLLI2SDIVR_DIV_27 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 27 */ -#define LL_RCC_PLLI2SDIVR_DIV_28 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 28 */ -#define LL_RCC_PLLI2SDIVR_DIV_29 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 29 */ -#define LL_RCC_PLLI2SDIVR_DIV_30 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 30 */ -#define LL_RCC_PLLI2SDIVR_DIV_31 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 31 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLI2SDIVR */ - -/** @defgroup RCC_LL_EC_PLLI2SR PLLI2SR division factor (PLLI2SR) - * @{ - */ -#define LL_RCC_PLLI2SR_DIV_2 RCC_PLLI2SCFGR_PLLI2SR_1 /*!< PLLI2S division factor for PLLI2SR output by 2 */ -#define LL_RCC_PLLI2SR_DIV_3 (RCC_PLLI2SCFGR_PLLI2SR_1 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 3 */ -#define LL_RCC_PLLI2SR_DIV_4 RCC_PLLI2SCFGR_PLLI2SR_2 /*!< PLLI2S division factor for PLLI2SR output by 4 */ -#define LL_RCC_PLLI2SR_DIV_5 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 5 */ -#define LL_RCC_PLLI2SR_DIV_6 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_1) /*!< PLLI2S division factor for PLLI2SR output by 6 */ -#define LL_RCC_PLLI2SR_DIV_7 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_1 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 7 */ -/** - * @} - */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SP) -/** @defgroup RCC_LL_EC_PLLI2SP PLLI2SP division factor (PLLI2SP) - * @{ - */ -#define LL_RCC_PLLI2SP_DIV_2 0x00000000U /*!< PLLI2S division factor for PLLI2SP output by 2 */ -#define LL_RCC_PLLI2SP_DIV_4 RCC_PLLI2SCFGR_PLLI2SP_0 /*!< PLLI2S division factor for PLLI2SP output by 4 */ -#define LL_RCC_PLLI2SP_DIV_6 RCC_PLLI2SCFGR_PLLI2SP_1 /*!< PLLI2S division factor for PLLI2SP output by 6 */ -#define LL_RCC_PLLI2SP_DIV_8 (RCC_PLLI2SCFGR_PLLI2SP_1 | RCC_PLLI2SCFGR_PLLI2SP_0) /*!< PLLI2S division factor for PLLI2SP output by 8 */ -/** - * @} - */ -#endif /* RCC_PLLI2SCFGR_PLLI2SP */ -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** @defgroup RCC_LL_EC_PLLSAIM PLLSAIM division factor (PLLSAIM or PLLM) - * @{ - */ -#if defined(RCC_PLLSAICFGR_PLLSAIM) -#define LL_RCC_PLLSAIM_DIV_2 (RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 2 */ -#define LL_RCC_PLLSAIM_DIV_3 (RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 3 */ -#define LL_RCC_PLLSAIM_DIV_4 (RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 4 */ -#define LL_RCC_PLLSAIM_DIV_5 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 5 */ -#define LL_RCC_PLLSAIM_DIV_6 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 6 */ -#define LL_RCC_PLLSAIM_DIV_7 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 7 */ -#define LL_RCC_PLLSAIM_DIV_8 (RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 8 */ -#define LL_RCC_PLLSAIM_DIV_9 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 9 */ -#define LL_RCC_PLLSAIM_DIV_10 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 10 */ -#define LL_RCC_PLLSAIM_DIV_11 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 11 */ -#define LL_RCC_PLLSAIM_DIV_12 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 12 */ -#define LL_RCC_PLLSAIM_DIV_13 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 13 */ -#define LL_RCC_PLLSAIM_DIV_14 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 14 */ -#define LL_RCC_PLLSAIM_DIV_15 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 15 */ -#define LL_RCC_PLLSAIM_DIV_16 (RCC_PLLSAICFGR_PLLSAIM_4) /*!< PLLSAI division factor for PLLSAIM output by 16 */ -#define LL_RCC_PLLSAIM_DIV_17 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 17 */ -#define LL_RCC_PLLSAIM_DIV_18 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 18 */ -#define LL_RCC_PLLSAIM_DIV_19 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 19 */ -#define LL_RCC_PLLSAIM_DIV_20 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 20 */ -#define LL_RCC_PLLSAIM_DIV_21 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 21 */ -#define LL_RCC_PLLSAIM_DIV_22 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 22 */ -#define LL_RCC_PLLSAIM_DIV_23 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 23 */ -#define LL_RCC_PLLSAIM_DIV_24 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 24 */ -#define LL_RCC_PLLSAIM_DIV_25 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 25 */ -#define LL_RCC_PLLSAIM_DIV_26 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 26 */ -#define LL_RCC_PLLSAIM_DIV_27 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 27 */ -#define LL_RCC_PLLSAIM_DIV_28 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 28 */ -#define LL_RCC_PLLSAIM_DIV_29 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 29 */ -#define LL_RCC_PLLSAIM_DIV_30 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 30 */ -#define LL_RCC_PLLSAIM_DIV_31 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 31 */ -#define LL_RCC_PLLSAIM_DIV_32 (RCC_PLLSAICFGR_PLLSAIM_5) /*!< PLLSAI division factor for PLLSAIM output by 32 */ -#define LL_RCC_PLLSAIM_DIV_33 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 33 */ -#define LL_RCC_PLLSAIM_DIV_34 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 34 */ -#define LL_RCC_PLLSAIM_DIV_35 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 35 */ -#define LL_RCC_PLLSAIM_DIV_36 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 36 */ -#define LL_RCC_PLLSAIM_DIV_37 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 37 */ -#define LL_RCC_PLLSAIM_DIV_38 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 38 */ -#define LL_RCC_PLLSAIM_DIV_39 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 39 */ -#define LL_RCC_PLLSAIM_DIV_40 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 40 */ -#define LL_RCC_PLLSAIM_DIV_41 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 41 */ -#define LL_RCC_PLLSAIM_DIV_42 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 42 */ -#define LL_RCC_PLLSAIM_DIV_43 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 43 */ -#define LL_RCC_PLLSAIM_DIV_44 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 44 */ -#define LL_RCC_PLLSAIM_DIV_45 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 45 */ -#define LL_RCC_PLLSAIM_DIV_46 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 46 */ -#define LL_RCC_PLLSAIM_DIV_47 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 47 */ -#define LL_RCC_PLLSAIM_DIV_48 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4) /*!< PLLSAI division factor for PLLSAIM output by 48 */ -#define LL_RCC_PLLSAIM_DIV_49 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 49 */ -#define LL_RCC_PLLSAIM_DIV_50 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 50 */ -#define LL_RCC_PLLSAIM_DIV_51 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 51 */ -#define LL_RCC_PLLSAIM_DIV_52 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 52 */ -#define LL_RCC_PLLSAIM_DIV_53 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 53 */ -#define LL_RCC_PLLSAIM_DIV_54 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 54 */ -#define LL_RCC_PLLSAIM_DIV_55 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 55 */ -#define LL_RCC_PLLSAIM_DIV_56 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 56 */ -#define LL_RCC_PLLSAIM_DIV_57 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 57 */ -#define LL_RCC_PLLSAIM_DIV_58 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 58 */ -#define LL_RCC_PLLSAIM_DIV_59 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 59 */ -#define LL_RCC_PLLSAIM_DIV_60 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 60 */ -#define LL_RCC_PLLSAIM_DIV_61 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 61 */ -#define LL_RCC_PLLSAIM_DIV_62 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 62 */ -#define LL_RCC_PLLSAIM_DIV_63 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 63 */ -#else -#define LL_RCC_PLLSAIM_DIV_2 LL_RCC_PLLM_DIV_2 /*!< PLLSAI division factor for PLLSAIM output by 2 */ -#define LL_RCC_PLLSAIM_DIV_3 LL_RCC_PLLM_DIV_3 /*!< PLLSAI division factor for PLLSAIM output by 3 */ -#define LL_RCC_PLLSAIM_DIV_4 LL_RCC_PLLM_DIV_4 /*!< PLLSAI division factor for PLLSAIM output by 4 */ -#define LL_RCC_PLLSAIM_DIV_5 LL_RCC_PLLM_DIV_5 /*!< PLLSAI division factor for PLLSAIM output by 5 */ -#define LL_RCC_PLLSAIM_DIV_6 LL_RCC_PLLM_DIV_6 /*!< PLLSAI division factor for PLLSAIM output by 6 */ -#define LL_RCC_PLLSAIM_DIV_7 LL_RCC_PLLM_DIV_7 /*!< PLLSAI division factor for PLLSAIM output by 7 */ -#define LL_RCC_PLLSAIM_DIV_8 LL_RCC_PLLM_DIV_8 /*!< PLLSAI division factor for PLLSAIM output by 8 */ -#define LL_RCC_PLLSAIM_DIV_9 LL_RCC_PLLM_DIV_9 /*!< PLLSAI division factor for PLLSAIM output by 9 */ -#define LL_RCC_PLLSAIM_DIV_10 LL_RCC_PLLM_DIV_10 /*!< PLLSAI division factor for PLLSAIM output by 10 */ -#define LL_RCC_PLLSAIM_DIV_11 LL_RCC_PLLM_DIV_11 /*!< PLLSAI division factor for PLLSAIM output by 11 */ -#define LL_RCC_PLLSAIM_DIV_12 LL_RCC_PLLM_DIV_12 /*!< PLLSAI division factor for PLLSAIM output by 12 */ -#define LL_RCC_PLLSAIM_DIV_13 LL_RCC_PLLM_DIV_13 /*!< PLLSAI division factor for PLLSAIM output by 13 */ -#define LL_RCC_PLLSAIM_DIV_14 LL_RCC_PLLM_DIV_14 /*!< PLLSAI division factor for PLLSAIM output by 14 */ -#define LL_RCC_PLLSAIM_DIV_15 LL_RCC_PLLM_DIV_15 /*!< PLLSAI division factor for PLLSAIM output by 15 */ -#define LL_RCC_PLLSAIM_DIV_16 LL_RCC_PLLM_DIV_16 /*!< PLLSAI division factor for PLLSAIM output by 16 */ -#define LL_RCC_PLLSAIM_DIV_17 LL_RCC_PLLM_DIV_17 /*!< PLLSAI division factor for PLLSAIM output by 17 */ -#define LL_RCC_PLLSAIM_DIV_18 LL_RCC_PLLM_DIV_18 /*!< PLLSAI division factor for PLLSAIM output by 18 */ -#define LL_RCC_PLLSAIM_DIV_19 LL_RCC_PLLM_DIV_19 /*!< PLLSAI division factor for PLLSAIM output by 19 */ -#define LL_RCC_PLLSAIM_DIV_20 LL_RCC_PLLM_DIV_20 /*!< PLLSAI division factor for PLLSAIM output by 20 */ -#define LL_RCC_PLLSAIM_DIV_21 LL_RCC_PLLM_DIV_21 /*!< PLLSAI division factor for PLLSAIM output by 21 */ -#define LL_RCC_PLLSAIM_DIV_22 LL_RCC_PLLM_DIV_22 /*!< PLLSAI division factor for PLLSAIM output by 22 */ -#define LL_RCC_PLLSAIM_DIV_23 LL_RCC_PLLM_DIV_23 /*!< PLLSAI division factor for PLLSAIM output by 23 */ -#define LL_RCC_PLLSAIM_DIV_24 LL_RCC_PLLM_DIV_24 /*!< PLLSAI division factor for PLLSAIM output by 24 */ -#define LL_RCC_PLLSAIM_DIV_25 LL_RCC_PLLM_DIV_25 /*!< PLLSAI division factor for PLLSAIM output by 25 */ -#define LL_RCC_PLLSAIM_DIV_26 LL_RCC_PLLM_DIV_26 /*!< PLLSAI division factor for PLLSAIM output by 26 */ -#define LL_RCC_PLLSAIM_DIV_27 LL_RCC_PLLM_DIV_27 /*!< PLLSAI division factor for PLLSAIM output by 27 */ -#define LL_RCC_PLLSAIM_DIV_28 LL_RCC_PLLM_DIV_28 /*!< PLLSAI division factor for PLLSAIM output by 28 */ -#define LL_RCC_PLLSAIM_DIV_29 LL_RCC_PLLM_DIV_29 /*!< PLLSAI division factor for PLLSAIM output by 29 */ -#define LL_RCC_PLLSAIM_DIV_30 LL_RCC_PLLM_DIV_30 /*!< PLLSAI division factor for PLLSAIM output by 30 */ -#define LL_RCC_PLLSAIM_DIV_31 LL_RCC_PLLM_DIV_31 /*!< PLLSAI division factor for PLLSAIM output by 31 */ -#define LL_RCC_PLLSAIM_DIV_32 LL_RCC_PLLM_DIV_32 /*!< PLLSAI division factor for PLLSAIM output by 32 */ -#define LL_RCC_PLLSAIM_DIV_33 LL_RCC_PLLM_DIV_33 /*!< PLLSAI division factor for PLLSAIM output by 33 */ -#define LL_RCC_PLLSAIM_DIV_34 LL_RCC_PLLM_DIV_34 /*!< PLLSAI division factor for PLLSAIM output by 34 */ -#define LL_RCC_PLLSAIM_DIV_35 LL_RCC_PLLM_DIV_35 /*!< PLLSAI division factor for PLLSAIM output by 35 */ -#define LL_RCC_PLLSAIM_DIV_36 LL_RCC_PLLM_DIV_36 /*!< PLLSAI division factor for PLLSAIM output by 36 */ -#define LL_RCC_PLLSAIM_DIV_37 LL_RCC_PLLM_DIV_37 /*!< PLLSAI division factor for PLLSAIM output by 37 */ -#define LL_RCC_PLLSAIM_DIV_38 LL_RCC_PLLM_DIV_38 /*!< PLLSAI division factor for PLLSAIM output by 38 */ -#define LL_RCC_PLLSAIM_DIV_39 LL_RCC_PLLM_DIV_39 /*!< PLLSAI division factor for PLLSAIM output by 39 */ -#define LL_RCC_PLLSAIM_DIV_40 LL_RCC_PLLM_DIV_40 /*!< PLLSAI division factor for PLLSAIM output by 40 */ -#define LL_RCC_PLLSAIM_DIV_41 LL_RCC_PLLM_DIV_41 /*!< PLLSAI division factor for PLLSAIM output by 41 */ -#define LL_RCC_PLLSAIM_DIV_42 LL_RCC_PLLM_DIV_42 /*!< PLLSAI division factor for PLLSAIM output by 42 */ -#define LL_RCC_PLLSAIM_DIV_43 LL_RCC_PLLM_DIV_43 /*!< PLLSAI division factor for PLLSAIM output by 43 */ -#define LL_RCC_PLLSAIM_DIV_44 LL_RCC_PLLM_DIV_44 /*!< PLLSAI division factor for PLLSAIM output by 44 */ -#define LL_RCC_PLLSAIM_DIV_45 LL_RCC_PLLM_DIV_45 /*!< PLLSAI division factor for PLLSAIM output by 45 */ -#define LL_RCC_PLLSAIM_DIV_46 LL_RCC_PLLM_DIV_46 /*!< PLLSAI division factor for PLLSAIM output by 46 */ -#define LL_RCC_PLLSAIM_DIV_47 LL_RCC_PLLM_DIV_47 /*!< PLLSAI division factor for PLLSAIM output by 47 */ -#define LL_RCC_PLLSAIM_DIV_48 LL_RCC_PLLM_DIV_48 /*!< PLLSAI division factor for PLLSAIM output by 48 */ -#define LL_RCC_PLLSAIM_DIV_49 LL_RCC_PLLM_DIV_49 /*!< PLLSAI division factor for PLLSAIM output by 49 */ -#define LL_RCC_PLLSAIM_DIV_50 LL_RCC_PLLM_DIV_50 /*!< PLLSAI division factor for PLLSAIM output by 50 */ -#define LL_RCC_PLLSAIM_DIV_51 LL_RCC_PLLM_DIV_51 /*!< PLLSAI division factor for PLLSAIM output by 51 */ -#define LL_RCC_PLLSAIM_DIV_52 LL_RCC_PLLM_DIV_52 /*!< PLLSAI division factor for PLLSAIM output by 52 */ -#define LL_RCC_PLLSAIM_DIV_53 LL_RCC_PLLM_DIV_53 /*!< PLLSAI division factor for PLLSAIM output by 53 */ -#define LL_RCC_PLLSAIM_DIV_54 LL_RCC_PLLM_DIV_54 /*!< PLLSAI division factor for PLLSAIM output by 54 */ -#define LL_RCC_PLLSAIM_DIV_55 LL_RCC_PLLM_DIV_55 /*!< PLLSAI division factor for PLLSAIM output by 55 */ -#define LL_RCC_PLLSAIM_DIV_56 LL_RCC_PLLM_DIV_56 /*!< PLLSAI division factor for PLLSAIM output by 56 */ -#define LL_RCC_PLLSAIM_DIV_57 LL_RCC_PLLM_DIV_57 /*!< PLLSAI division factor for PLLSAIM output by 57 */ -#define LL_RCC_PLLSAIM_DIV_58 LL_RCC_PLLM_DIV_58 /*!< PLLSAI division factor for PLLSAIM output by 58 */ -#define LL_RCC_PLLSAIM_DIV_59 LL_RCC_PLLM_DIV_59 /*!< PLLSAI division factor for PLLSAIM output by 59 */ -#define LL_RCC_PLLSAIM_DIV_60 LL_RCC_PLLM_DIV_60 /*!< PLLSAI division factor for PLLSAIM output by 60 */ -#define LL_RCC_PLLSAIM_DIV_61 LL_RCC_PLLM_DIV_61 /*!< PLLSAI division factor for PLLSAIM output by 61 */ -#define LL_RCC_PLLSAIM_DIV_62 LL_RCC_PLLM_DIV_62 /*!< PLLSAI division factor for PLLSAIM output by 62 */ -#define LL_RCC_PLLSAIM_DIV_63 LL_RCC_PLLM_DIV_63 /*!< PLLSAI division factor for PLLSAIM output by 63 */ -#endif /* RCC_PLLSAICFGR_PLLSAIM */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLSAIQ PLLSAIQ division factor (PLLSAIQ) - * @{ - */ -#define LL_RCC_PLLSAIQ_DIV_2 RCC_PLLSAICFGR_PLLSAIQ_1 /*!< PLLSAI division factor for PLLSAIQ output by 2 */ -#define LL_RCC_PLLSAIQ_DIV_3 (RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 3 */ -#define LL_RCC_PLLSAIQ_DIV_4 RCC_PLLSAICFGR_PLLSAIQ_2 /*!< PLLSAI division factor for PLLSAIQ output by 4 */ -#define LL_RCC_PLLSAIQ_DIV_5 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 5 */ -#define LL_RCC_PLLSAIQ_DIV_6 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 6 */ -#define LL_RCC_PLLSAIQ_DIV_7 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 7 */ -#define LL_RCC_PLLSAIQ_DIV_8 RCC_PLLSAICFGR_PLLSAIQ_3 /*!< PLLSAI division factor for PLLSAIQ output by 8 */ -#define LL_RCC_PLLSAIQ_DIV_9 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 9 */ -#define LL_RCC_PLLSAIQ_DIV_10 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 10 */ -#define LL_RCC_PLLSAIQ_DIV_11 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 11 */ -#define LL_RCC_PLLSAIQ_DIV_12 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2) /*!< PLLSAI division factor for PLLSAIQ output by 12 */ -#define LL_RCC_PLLSAIQ_DIV_13 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 13 */ -#define LL_RCC_PLLSAIQ_DIV_14 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 14 */ -#define LL_RCC_PLLSAIQ_DIV_15 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 15 */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVQ) -/** @defgroup RCC_LL_EC_PLLSAIDIVQ PLLSAIDIVQ division factor (PLLSAIDIVQ) - * @{ - */ -#define LL_RCC_PLLSAIDIVQ_DIV_1 0x00000000U /*!< PLLSAI division factor for PLLSAIDIVQ output by 1 */ -#define LL_RCC_PLLSAIDIVQ_DIV_2 RCC_DCKCFGR_PLLSAIDIVQ_0 /*!< PLLSAI division factor for PLLSAIDIVQ output by 2 */ -#define LL_RCC_PLLSAIDIVQ_DIV_3 RCC_DCKCFGR_PLLSAIDIVQ_1 /*!< PLLSAI division factor for PLLSAIDIVQ output by 3 */ -#define LL_RCC_PLLSAIDIVQ_DIV_4 (RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 4 */ -#define LL_RCC_PLLSAIDIVQ_DIV_5 RCC_DCKCFGR_PLLSAIDIVQ_2 /*!< PLLSAI division factor for PLLSAIDIVQ output by 5 */ -#define LL_RCC_PLLSAIDIVQ_DIV_6 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 6 */ -#define LL_RCC_PLLSAIDIVQ_DIV_7 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 7 */ -#define LL_RCC_PLLSAIDIVQ_DIV_8 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 8 */ -#define LL_RCC_PLLSAIDIVQ_DIV_9 RCC_DCKCFGR_PLLSAIDIVQ_3 /*!< PLLSAI division factor for PLLSAIDIVQ output by 9 */ -#define LL_RCC_PLLSAIDIVQ_DIV_10 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 10 */ -#define LL_RCC_PLLSAIDIVQ_DIV_11 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 11 */ -#define LL_RCC_PLLSAIDIVQ_DIV_12 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 12 */ -#define LL_RCC_PLLSAIDIVQ_DIV_13 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 13 */ -#define LL_RCC_PLLSAIDIVQ_DIV_14 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 14 */ -#define LL_RCC_PLLSAIDIVQ_DIV_15 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 15 */ -#define LL_RCC_PLLSAIDIVQ_DIV_16 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 16 */ -#define LL_RCC_PLLSAIDIVQ_DIV_17 RCC_DCKCFGR_PLLSAIDIVQ_4 /*!< PLLSAI division factor for PLLSAIDIVQ output by 17 */ -#define LL_RCC_PLLSAIDIVQ_DIV_18 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 18 */ -#define LL_RCC_PLLSAIDIVQ_DIV_19 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 19 */ -#define LL_RCC_PLLSAIDIVQ_DIV_20 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 20 */ -#define LL_RCC_PLLSAIDIVQ_DIV_21 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 21 */ -#define LL_RCC_PLLSAIDIVQ_DIV_22 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 22 */ -#define LL_RCC_PLLSAIDIVQ_DIV_23 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 23 */ -#define LL_RCC_PLLSAIDIVQ_DIV_24 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 24 */ -#define LL_RCC_PLLSAIDIVQ_DIV_25 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3) /*!< PLLSAI division factor for PLLSAIDIVQ output by 25 */ -#define LL_RCC_PLLSAIDIVQ_DIV_26 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 26 */ -#define LL_RCC_PLLSAIDIVQ_DIV_27 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 27 */ -#define LL_RCC_PLLSAIDIVQ_DIV_28 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 28 */ -#define LL_RCC_PLLSAIDIVQ_DIV_29 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 29 */ -#define LL_RCC_PLLSAIDIVQ_DIV_30 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 30 */ -#define LL_RCC_PLLSAIDIVQ_DIV_31 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 31 */ -#define LL_RCC_PLLSAIDIVQ_DIV_32 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 32 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLSAIDIVQ */ - -#if defined(RCC_PLLSAICFGR_PLLSAIR) -/** @defgroup RCC_LL_EC_PLLSAIR PLLSAIR division factor (PLLSAIR) - * @{ - */ -#define LL_RCC_PLLSAIR_DIV_2 RCC_PLLSAICFGR_PLLSAIR_1 /*!< PLLSAI division factor for PLLSAIR output by 2 */ -#define LL_RCC_PLLSAIR_DIV_3 (RCC_PLLSAICFGR_PLLSAIR_1 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 3 */ -#define LL_RCC_PLLSAIR_DIV_4 RCC_PLLSAICFGR_PLLSAIR_2 /*!< PLLSAI division factor for PLLSAIR output by 4 */ -#define LL_RCC_PLLSAIR_DIV_5 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 5 */ -#define LL_RCC_PLLSAIR_DIV_6 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_1) /*!< PLLSAI division factor for PLLSAIR output by 6 */ -#define LL_RCC_PLLSAIR_DIV_7 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_1 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 7 */ -/** - * @} - */ -#endif /* RCC_PLLSAICFGR_PLLSAIR */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -/** @defgroup RCC_LL_EC_PLLSAIDIVR PLLSAIDIVR division factor (PLLSAIDIVR) - * @{ - */ -#define LL_RCC_PLLSAIDIVR_DIV_2 0x00000000U /*!< PLLSAI division factor for PLLSAIDIVR output by 2 */ -#define LL_RCC_PLLSAIDIVR_DIV_4 RCC_DCKCFGR_PLLSAIDIVR_0 /*!< PLLSAI division factor for PLLSAIDIVR output by 4 */ -#define LL_RCC_PLLSAIDIVR_DIV_8 RCC_DCKCFGR_PLLSAIDIVR_1 /*!< PLLSAI division factor for PLLSAIDIVR output by 8 */ -#define LL_RCC_PLLSAIDIVR_DIV_16 (RCC_DCKCFGR_PLLSAIDIVR_1 | RCC_DCKCFGR_PLLSAIDIVR_0) /*!< PLLSAI division factor for PLLSAIDIVR output by 16 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** @defgroup RCC_LL_EC_PLLSAIP PLLSAIP division factor (PLLSAIP) - * @{ - */ -#define LL_RCC_PLLSAIP_DIV_2 0x00000000U /*!< PLLSAI division factor for PLLSAIP output by 2 */ -#define LL_RCC_PLLSAIP_DIV_4 RCC_PLLSAICFGR_PLLSAIP_0 /*!< PLLSAI division factor for PLLSAIP output by 4 */ -#define LL_RCC_PLLSAIP_DIV_6 RCC_PLLSAICFGR_PLLSAIP_1 /*!< PLLSAI division factor for PLLSAIP output by 6 */ -#define LL_RCC_PLLSAIP_DIV_8 (RCC_PLLSAICFGR_PLLSAIP_1 | RCC_PLLSAICFGR_PLLSAIP_0) /*!< PLLSAI division factor for PLLSAIP output by 8 */ -/** - * @} - */ -#endif /* RCC_PLLSAICFGR_PLLSAIP */ -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Macros RCC Exported Macros - * @{ - */ - -/** @defgroup RCC_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in RCC register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_RCC_WriteReg(__REG__, __VALUE__) WRITE_REG(RCC->__REG__, (__VALUE__)) - -/** - * @brief Read a value in RCC register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_RCC_ReadReg(__REG__) READ_REG(RCC->__REG__) -/** - * @} - */ - -/** @defgroup RCC_LL_EM_CALC_FREQ Calculate frequencies - * @{ - */ - -/** - * @brief Helper macro to calculate the PLLCLK frequency on system domain - * @note ex: @ref __LL_RCC_CALC_PLLCLK_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLP__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((((__PLLP__) >> RCC_PLLCFGR_PLLP_Pos ) + 1U) * 2U)) - -#if defined(RCC_PLLR_SYSCLK_SUPPORT) -/** - * @brief Helper macro to calculate the PLLRCLK frequency on system domain - * @note ex: @ref __LL_RCC_CALC_PLLRCLK_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLRCLK_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) - -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ - -/** - * @brief Helper macro to calculate the PLLCLK frequency used on 48M domain - * @note ex: @ref __LL_RCC_CALC_PLLCLK_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLQ__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLQ__) >> RCC_PLLCFGR_PLLQ_Pos )) - -#if defined(DSI) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on DSI - * @note ex: @ref __LL_RCC_CALC_PLLCLK_DSI_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_DSI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* DSI */ - -#if defined(RCC_PLLR_I2S_CLKSOURCE_SUPPORT) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on I2S - * @note ex: @ref __LL_RCC_CALC_PLLCLK_I2S_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_I2S_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* RCC_PLLR_I2S_CLKSOURCE_SUPPORT */ - -#if defined(SPDIFRX) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on SPDIFRX - * @note ex: @ref __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* SPDIFRX */ - -#if defined(RCC_PLLCFGR_PLLR) -#if defined(SAI1) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on SAI - * @note ex: @ref __LL_RCC_CALC_PLLCLK_SAI_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR (), @ref LL_RCC_PLL_GetDIVR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @param __PLLDIVR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval PLL clock frequency (in Hz) - */ -#if defined(RCC_DCKCFGR_PLLDIVR) -#define __LL_RCC_CALC_PLLCLK_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__, __PLLDIVR__) (((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) / ((__PLLDIVR__) >> RCC_DCKCFGR_PLLDIVR_Pos )) -#else -#define __LL_RCC_CALC_PLLCLK_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* RCC_DCKCFGR_PLLDIVR */ -#endif /* SAI1 */ -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Helper macro to calculate the PLLSAI frequency used for SAI domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_SAI_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetQ (), @ref LL_RCC_PLLSAI_GetDIVQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLSAIQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - * @param __PLLSAIDIVQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIQ__, __PLLSAIDIVQ__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - (((__PLLSAIQ__) >> RCC_PLLSAICFGR_PLLSAIQ_Pos) * (((__PLLSAIDIVQ__) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos) + 1U))) - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Helper macro to calculate the PLLSAI frequency used on 48Mhz domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 50 and 432 - * @param __PLLSAIP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIP__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - ((((__PLLSAIP__) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) * 2U)) -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -#if defined(LTDC) -/** - * @brief Helper macro to calculate the PLLSAI frequency used for LTDC domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_LTDC_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetR (), @ref LL_RCC_PLLSAI_GetDIVR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLSAIR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - * @param __PLLSAIDIVR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_LTDC_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIR__, __PLLSAIDIVR__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - (((__PLLSAIR__) >> RCC_PLLSAICFGR_PLLSAIR_Pos) * (aRCC_PLLSAIDIVRPrescTable[(__PLLSAIDIVR__) >> RCC_DCKCFGR_PLLSAIDIVR_Pos]))) -#endif /* LTDC */ -#endif /* RCC_PLLSAI_SUPPORT */ - -#if defined(RCC_PLLI2S_SUPPORT) -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) || defined(RCC_DCKCFGR_PLLI2SDIVR) -/** - * @brief Helper macro to calculate the PLLI2S frequency used for SAI domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_SAI_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetQ (), @ref LL_RCC_PLLI2S_GetDIVQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLI2SQ_R__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @param __PLLI2SDIVQ_R__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval PLLI2S clock frequency (in Hz) - */ -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define __LL_RCC_CALC_PLLI2S_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ_R__, __PLLI2SDIVQ_R__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - (((__PLLI2SQ_R__) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos) * (((__PLLI2SDIVQ_R__) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos) + 1U))) -#else -#define __LL_RCC_CALC_PLLI2S_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ_R__, __PLLI2SDIVQ_R__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - (((__PLLI2SQ_R__) >> RCC_PLLI2SCFGR_PLLI2SR_Pos) * ((__PLLI2SDIVQ_R__) >> RCC_DCKCFGR_PLLI2SDIVR_Pos))) - -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_DCKCFGR_PLLI2SDIVQ || RCC_DCKCFGR_PLLI2SDIVR */ - -#if defined(SPDIFRX) -/** - * @brief Helper macro to calculate the PLLI2S frequency used on SPDIFRX domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50 and 432 - * @param __PLLI2SP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SP__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((((__PLLI2SP__) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) * 2U)) - -#endif /* SPDIFRX */ - -/** - * @brief Helper macro to calculate the PLLI2S frequency used for I2S domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_I2S_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLI2SR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_I2S_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SR__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((__PLLI2SR__) >> RCC_PLLI2SCFGR_PLLI2SR_Pos)) - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Helper macro to calculate the PLLI2S frequency used for 48Mhz domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50 and 432 - * @param __PLLI2SQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((__PLLI2SQ__) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos)) - -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_PLLI2S_SUPPORT */ - -/** - * @brief Helper macro to calculate the HCLK frequency - * @param __SYSCLKFREQ__ SYSCLK frequency (based on HSE/HSI/PLLCLK) - * @param __AHBPRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - * @retval HCLK clock frequency (in Hz) - */ -#define __LL_RCC_CALC_HCLK_FREQ(__SYSCLKFREQ__, __AHBPRESCALER__) ((__SYSCLKFREQ__) >> AHBPrescTable[((__AHBPRESCALER__) & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos]) - -/** - * @brief Helper macro to calculate the PCLK1 frequency (ABP1) - * @param __HCLKFREQ__ HCLK frequency - * @param __APB1PRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - * @retval PCLK1 clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PCLK1_FREQ(__HCLKFREQ__, __APB1PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB1PRESCALER__) >> RCC_CFGR_PPRE1_Pos]) - -/** - * @brief Helper macro to calculate the PCLK2 frequency (ABP2) - * @param __HCLKFREQ__ HCLK frequency - * @param __APB2PRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - * @retval PCLK2 clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PCLK2_FREQ(__HCLKFREQ__, __APB2PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB2PRESCALER__) >> RCC_CFGR_PPRE2_Pos]) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Functions RCC Exported Functions - * @{ - */ - -/** @defgroup RCC_LL_EF_HSE HSE - * @{ - */ - -/** - * @brief Enable the Clock Security System. - * @rmtoll CR CSSON LL_RCC_HSE_EnableCSS - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_EnableCSS(void) -{ - SET_BIT(RCC->CR, RCC_CR_CSSON); -} - -/** - * @brief Enable HSE external oscillator (HSE Bypass) - * @rmtoll CR HSEBYP LL_RCC_HSE_EnableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_EnableBypass(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSEBYP); -} - -/** - * @brief Disable HSE external oscillator (HSE Bypass) - * @rmtoll CR HSEBYP LL_RCC_HSE_DisableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_DisableBypass(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); -} - -/** - * @brief Enable HSE crystal oscillator (HSE ON) - * @rmtoll CR HSEON LL_RCC_HSE_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSEON); -} - -/** - * @brief Disable HSE crystal oscillator (HSE ON) - * @rmtoll CR HSEON LL_RCC_HSE_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSEON); -} - -/** - * @brief Check if HSE oscillator Ready - * @rmtoll CR HSERDY LL_RCC_HSE_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_HSE_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_HSERDY) == (RCC_CR_HSERDY)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_HSI HSI - * @{ - */ - -/** - * @brief Enable HSI oscillator - * @rmtoll CR HSION LL_RCC_HSI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSION); -} - -/** - * @brief Disable HSI oscillator - * @rmtoll CR HSION LL_RCC_HSI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSION); -} - -/** - * @brief Check if HSI clock is ready - * @rmtoll CR HSIRDY LL_RCC_HSI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == (RCC_CR_HSIRDY)); -} - -/** - * @brief Get HSI Calibration value - * @note When HSITRIM is written, HSICAL is updated with the sum of - * HSITRIM and the factory trim value - * @rmtoll CR HSICAL LL_RCC_HSI_GetCalibration - * @retval Between Min_Data = 0x00 and Max_Data = 0xFF - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibration(void) -{ - return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSICAL) >> RCC_CR_HSICAL_Pos); -} - -/** - * @brief Set HSI Calibration trimming - * @note user-programmable trimming value that is added to the HSICAL - * @note Default value is 16, which, when added to the HSICAL value, - * should trim the HSI to 16 MHz +/- 1 % - * @rmtoll CR HSITRIM LL_RCC_HSI_SetCalibTrimming - * @param Value Between Min_Data = 0 and Max_Data = 31 - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_SetCalibTrimming(uint32_t Value) -{ - MODIFY_REG(RCC->CR, RCC_CR_HSITRIM, Value << RCC_CR_HSITRIM_Pos); -} - -/** - * @brief Get HSI Calibration trimming - * @rmtoll CR HSITRIM LL_RCC_HSI_GetCalibTrimming - * @retval Between Min_Data = 0 and Max_Data = 31 - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibTrimming(void) -{ - return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_LSE LSE - * @{ - */ - -/** - * @brief Enable Low Speed External (LSE) crystal. - * @rmtoll BDCR LSEON LL_RCC_LSE_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_Enable(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); -} - -/** - * @brief Disable Low Speed External (LSE) crystal. - * @rmtoll BDCR LSEON LL_RCC_LSE_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_Disable(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); -} - -/** - * @brief Enable external clock source (LSE bypass). - * @rmtoll BDCR LSEBYP LL_RCC_LSE_EnableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_EnableBypass(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); -} - -/** - * @brief Disable external clock source (LSE bypass). - * @rmtoll BDCR LSEBYP LL_RCC_LSE_DisableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_DisableBypass(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); -} - -/** - * @brief Check if LSE oscillator Ready - * @rmtoll BDCR LSERDY LL_RCC_LSE_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_LSE_IsReady(void) -{ - return (READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) == (RCC_BDCR_LSERDY)); -} - -#if defined(RCC_BDCR_LSEMOD) -/** - * @brief Enable LSE high drive mode. - * @note LSE high drive mode can be enabled only when the LSE clock is disabled - * @rmtoll BDCR LSEMOD LL_RCC_LSE_EnableHighDriveMode - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_EnableHighDriveMode(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); -} - -/** - * @brief Disable LSE high drive mode. - * @note LSE high drive mode can be disabled only when the LSE clock is disabled - * @rmtoll BDCR LSEMOD LL_RCC_LSE_DisableHighDriveMode - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_DisableHighDriveMode(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); -} -#endif /* RCC_BDCR_LSEMOD */ - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_LSI LSI - * @{ - */ - -/** - * @brief Enable LSI Oscillator - * @rmtoll CSR LSION LL_RCC_LSI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSI_Enable(void) -{ - SET_BIT(RCC->CSR, RCC_CSR_LSION); -} - -/** - * @brief Disable LSI Oscillator - * @rmtoll CSR LSION LL_RCC_LSI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSI_Disable(void) -{ - CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); -} - -/** - * @brief Check if LSI is Ready - * @rmtoll CSR LSIRDY LL_RCC_LSI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_LSI_IsReady(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) == (RCC_CSR_LSIRDY)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_System System - * @{ - */ - -/** - * @brief Configure the system clock source - * @rmtoll CFGR SW LL_RCC_SetSysClkSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_SYS_CLKSOURCE_HSI - * @arg @ref LL_RCC_SYS_CLKSOURCE_HSE - * @arg @ref LL_RCC_SYS_CLKSOURCE_PLL - * @arg @ref LL_RCC_SYS_CLKSOURCE_PLLR (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSysClkSource(uint32_t Source) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, Source); -} - -/** - * @brief Get the system clock source - * @rmtoll CFGR SWS LL_RCC_GetSysClkSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSI - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSE - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLL - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLLR (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSysClkSource(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_SWS)); -} - -/** - * @brief Set AHB prescaler - * @rmtoll CFGR HPRE LL_RCC_SetAHBPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAHBPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, Prescaler); -} - -/** - * @brief Set APB1 prescaler - * @rmtoll CFGR PPRE1 LL_RCC_SetAPB1Prescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAPB1Prescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, Prescaler); -} - -/** - * @brief Set APB2 prescaler - * @rmtoll CFGR PPRE2 LL_RCC_SetAPB2Prescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAPB2Prescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, Prescaler); -} - -/** - * @brief Get AHB prescaler - * @rmtoll CFGR HPRE LL_RCC_GetAHBPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAHBPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_HPRE)); -} - -/** - * @brief Get APB1 prescaler - * @rmtoll CFGR PPRE1 LL_RCC_GetAPB1Prescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAPB1Prescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE1)); -} - -/** - * @brief Get APB2 prescaler - * @rmtoll CFGR PPRE2 LL_RCC_GetAPB2Prescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAPB2Prescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE2)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_MCO MCO - * @{ - */ - -#if defined(RCC_CFGR_MCO1EN) -/** - * @brief Enable MCO1 output - * @rmtoll CFGR RCC_CFGR_MCO1EN LL_RCC_MCO1_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO1_Enable(void) -{ - SET_BIT(RCC->CFGR, RCC_CFGR_MCO1EN); -} - -/** - * @brief Disable MCO1 output - * @rmtoll CFGR RCC_CFGR_MCO1EN LL_RCC_MCO1_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO1_Disable(void) -{ - CLEAR_BIT(RCC->CFGR, RCC_CFGR_MCO1EN); -} -#endif /* RCC_CFGR_MCO1EN */ - -#if defined(RCC_CFGR_MCO2EN) -/** - * @brief Enable MCO2 output - * @rmtoll CFGR RCC_CFGR_MCO2EN LL_RCC_MCO2_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO2_Enable(void) -{ - SET_BIT(RCC->CFGR, RCC_CFGR_MCO2EN); -} - -/** - * @brief Disable MCO2 output - * @rmtoll CFGR RCC_CFGR_MCO2EN LL_RCC_MCO2_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO2_Disable(void) -{ - CLEAR_BIT(RCC->CFGR, RCC_CFGR_MCO2EN); -} -#endif /* RCC_CFGR_MCO2EN */ - -/** - * @brief Configure MCOx - * @rmtoll CFGR MCO1 LL_RCC_ConfigMCO\n - * CFGR MCO1PRE LL_RCC_ConfigMCO\n - * CFGR MCO2 LL_RCC_ConfigMCO\n - * CFGR MCO2PRE LL_RCC_ConfigMCO - * @param MCOxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_MCO1SOURCE_HSI - * @arg @ref LL_RCC_MCO1SOURCE_LSE - * @arg @ref LL_RCC_MCO1SOURCE_HSE - * @arg @ref LL_RCC_MCO1SOURCE_PLLCLK - * @arg @ref LL_RCC_MCO2SOURCE_SYSCLK - * @arg @ref LL_RCC_MCO2SOURCE_PLLI2S - * @arg @ref LL_RCC_MCO2SOURCE_HSE - * @arg @ref LL_RCC_MCO2SOURCE_PLLCLK - * @param MCOxPrescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_MCO1_DIV_1 - * @arg @ref LL_RCC_MCO1_DIV_2 - * @arg @ref LL_RCC_MCO1_DIV_3 - * @arg @ref LL_RCC_MCO1_DIV_4 - * @arg @ref LL_RCC_MCO1_DIV_5 - * @arg @ref LL_RCC_MCO2_DIV_1 - * @arg @ref LL_RCC_MCO2_DIV_2 - * @arg @ref LL_RCC_MCO2_DIV_3 - * @arg @ref LL_RCC_MCO2_DIV_4 - * @arg @ref LL_RCC_MCO2_DIV_5 - * @retval None - */ -__STATIC_INLINE void LL_RCC_ConfigMCO(uint32_t MCOxSource, uint32_t MCOxPrescaler) -{ - MODIFY_REG(RCC->CFGR, (MCOxSource & 0xFFFF0000U) | (MCOxPrescaler & 0xFFFF0000U), (MCOxSource << 16U) | (MCOxPrescaler << 16U)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_Peripheral_Clock_Source Peripheral Clock Source - * @{ - */ -#if defined(FMPI2C1) -/** - * @brief Configure FMPI2C clock source - * @rmtoll DCKCFGR2 FMPI2C1SEL LL_RCC_SetFMPI2CClockSource - * @param FMPI2CxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_HSI - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetFMPI2CClockSource(uint32_t FMPI2CxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, FMPI2CxSource); -} -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** - * @brief Configure LPTIMx clock source - * @rmtoll DCKCFGR2 LPTIM1SEL LL_RCC_SetLPTIMClockSource - * @param LPTIMxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_HSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetLPTIMClockSource(uint32_t LPTIMxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, LPTIMxSource); -} -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** - * @brief Configure SAIx clock source - * @rmtoll DCKCFGR SAI1SRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI2SRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI1ASRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI1BSRC LL_RCC_SetSAIClockSource - * @param SAIxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSAIClockSource(uint32_t SAIxSource) -{ - MODIFY_REG(RCC->DCKCFGR, (SAIxSource & 0xFFFF0000U), (SAIxSource << 16U)); -} -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** - * @brief Configure SDIO clock source - * @rmtoll DCKCFGR SDIOSEL LL_RCC_SetSDIOClockSource\n - * DCKCFGR2 SDIOSEL LL_RCC_SetSDIOClockSource - * @param SDIOxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE_PLL48CLK - * @arg @ref LL_RCC_SDIO_CLKSOURCE_SYSCLK - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSDIOClockSource(uint32_t SDIOxSource) -{ -#if defined(RCC_DCKCFGR_SDIOSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL, SDIOxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, SDIOxSource); -#endif /* RCC_DCKCFGR_SDIOSEL */ -} -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** - * @brief Configure 48Mhz domain clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetCK48MClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetCK48MClockSource - * @param CK48MxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLL - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetCK48MClockSource(uint32_t CK48MxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, CK48MxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, CK48MxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} - -#if defined(RNG) -/** - * @brief Configure RNG clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetRNGClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetRNGClockSource - * @param RNGxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLL - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRNGClockSource(uint32_t RNGxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, RNGxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, RNGxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** - * @brief Configure USB clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetUSBClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetUSBClockSource - * @param USBxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE_PLL - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetUSBClockSource(uint32_t USBxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, USBxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, USBxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* USB_OTG_FS || USB_OTG_HS */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(CEC) -/** - * @brief Configure CEC clock source - * @rmtoll DCKCFGR2 CECSEL LL_RCC_SetCECClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV488 - * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetCECClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL, Source); -} -#endif /* CEC */ - -/** - * @brief Configure I2S clock source - * @rmtoll CFGR I2SSRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2SSRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2S1SRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2S2SRC LL_RCC_SetI2SClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PIN - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetI2SClockSource(uint32_t Source) -{ -#if defined(RCC_CFGR_I2SSRC) - MODIFY_REG(RCC->CFGR, RCC_CFGR_I2SSRC, Source); -#else - MODIFY_REG(RCC->DCKCFGR, (Source & 0xFFFF0000U), (Source << 16U)); -#endif /* RCC_CFGR_I2SSRC */ -} - -#if defined(DSI) -/** - * @brief Configure DSI clock source - * @rmtoll DCKCFGR DSISEL LL_RCC_SetDSIClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE_PHY - * @arg @ref LL_RCC_DSI_CLKSOURCE_PLL - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDSIClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL, Source); -} -#endif /* DSI */ - -#if defined(DFSDM1_Channel0) -/** - * @brief Configure DFSDM Audio clock source - * @rmtoll DCKCFGR CKDFSDM1ASEL LL_RCC_SetDFSDMAudioClockSource\n - * DCKCFGR CKDFSDM2ASEL LL_RCC_SetDFSDMAudioClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (*) - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDFSDMAudioClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, (Source & 0x0000FFFFU), (Source >> 16U)); -} - -/** - * @brief Configure DFSDM Kernel clock source - * @rmtoll DCKCFGR CKDFSDM1SEL LL_RCC_SetDFSDMClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_PCLK2 - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_PCLK2 (*) - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_SYSCLK (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDFSDMClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, Source); -} -#endif /* DFSDM1_Channel0 */ - -#if defined(SPDIFRX) -/** - * @brief Configure SPDIFRX clock source - * @rmtoll DCKCFGR2 SPDIFRXSEL LL_RCC_SetSPDIFRXClockSource - * @param SPDIFRXxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLL - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSPDIFRXClockSource(uint32_t SPDIFRXxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL, SPDIFRXxSource); -} -#endif /* SPDIFRX */ - -#if defined(FMPI2C1) -/** - * @brief Get FMPI2C clock source - * @rmtoll DCKCFGR2 FMPI2C1SEL LL_RCC_GetFMPI2CClockSource - * @param FMPI2Cx This parameter can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_HSI - */ -__STATIC_INLINE uint32_t LL_RCC_GetFMPI2CClockSource(uint32_t FMPI2Cx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, FMPI2Cx)); -} -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** - * @brief Get LPTIMx clock source - * @rmtoll DCKCFGR2 LPTIM1SEL LL_RCC_GetLPTIMClockSource - * @param LPTIMx This parameter can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_HSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetLPTIMClockSource(uint32_t LPTIMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)); -} -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** - * @brief Get SAIx clock source - * @rmtoll DCKCFGR SAI1SEL LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI2SEL LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI1ASRC LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI1BSRC LL_RCC_GetSAIClockSource - * @param SAIx This parameter can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE (*) - * - * (*) value not defined in all devices. - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSAIClockSource(uint32_t SAIx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, SAIx) >> 16U | SAIx); -} -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** - * @brief Get SDIOx clock source - * @rmtoll DCKCFGR SDIOSEL LL_RCC_GetSDIOClockSource\n - * DCKCFGR2 SDIOSEL LL_RCC_GetSDIOClockSource - * @param SDIOx This parameter can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE_PLL48CLK - * @arg @ref LL_RCC_SDIO_CLKSOURCE_SYSCLK - */ -__STATIC_INLINE uint32_t LL_RCC_GetSDIOClockSource(uint32_t SDIOx) -{ -#if defined(RCC_DCKCFGR_SDIOSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, SDIOx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, SDIOx)); -#endif /* RCC_DCKCFGR_SDIOSEL */ -} -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** - * @brief Get 48Mhz domain clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetCK48MClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetCK48MClockSource - * @param CK48Mx This parameter can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLL - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetCK48MClockSource(uint32_t CK48Mx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, CK48Mx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, CK48Mx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} - -#if defined(RNG) -/** - * @brief Get RNGx clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetRNGClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetRNGClockSource - * @param RNGx This parameter can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLL - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetRNGClockSource(uint32_t RNGx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RNGx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RNGx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** - * @brief Get USBx clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetUSBClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetUSBClockSource - * @param USBx This parameter can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE_PLL - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetUSBClockSource(uint32_t USBx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, USBx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, USBx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* USB_OTG_FS || USB_OTG_HS */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(CEC) -/** - * @brief Get CEC Clock Source - * @rmtoll DCKCFGR2 CECSEL LL_RCC_GetCECClockSource - * @param CECx This parameter can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV488 - * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetCECClockSource(uint32_t CECx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, CECx)); -} -#endif /* CEC */ - -/** - * @brief Get I2S Clock Source - * @rmtoll CFGR I2SSRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2SSRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2S1SRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2S2SRC LL_RCC_GetI2SClockSource - * @param I2Sx This parameter can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE - * @arg @ref LL_RCC_I2S2_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PIN - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetI2SClockSource(uint32_t I2Sx) -{ -#if defined(RCC_CFGR_I2SSRC) - return (uint32_t)(READ_BIT(RCC->CFGR, I2Sx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR, I2Sx) >> 16U | I2Sx); -#endif /* RCC_CFGR_I2SSRC */ -} - -#if defined(DFSDM1_Channel0) -/** - * @brief Get DFSDM Audio Clock Source - * @rmtoll DCKCFGR CKDFSDM1ASEL LL_RCC_GetDFSDMAudioClockSource\n - * DCKCFGR CKDFSDM2ASEL LL_RCC_GetDFSDMAudioClockSource - * @param DFSDMx This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (*) - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetDFSDMAudioClockSource(uint32_t DFSDMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DFSDMx) << 16U | DFSDMx); -} - -/** - * @brief Get DFSDM Audio Clock Source - * @rmtoll DCKCFGR CKDFSDM1SEL LL_RCC_GetDFSDMClockSource - * @param DFSDMx This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_PCLK2 - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_PCLK2 (*) - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_SYSCLK (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetDFSDMClockSource(uint32_t DFSDMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DFSDMx)); -} -#endif /* DFSDM1_Channel0 */ - -#if defined(SPDIFRX) -/** - * @brief Get SPDIFRX clock source - * @rmtoll DCKCFGR2 SPDIFRXSEL LL_RCC_GetSPDIFRXClockSource - * @param SPDIFRXx This parameter can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLL - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSPDIFRXClockSource(uint32_t SPDIFRXx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, SPDIFRXx)); -} -#endif /* SPDIFRX */ - -#if defined(DSI) -/** - * @brief Get DSI Clock Source - * @rmtoll DCKCFGR DSISEL LL_RCC_GetDSIClockSource - * @param DSIx This parameter can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE_PHY - * @arg @ref LL_RCC_DSI_CLKSOURCE_PLL - */ -__STATIC_INLINE uint32_t LL_RCC_GetDSIClockSource(uint32_t DSIx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DSIx)); -} -#endif /* DSI */ - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_RTC RTC - * @{ - */ - -/** - * @brief Set RTC Clock Source - * @note Once the RTC clock source has been selected, it cannot be changed anymore unless - * the Backup domain is reset, or unless a failure is detected on LSE (LSECSSD is - * set). The BDRST bit can be used to reset them. - * @rmtoll BDCR RTCSEL LL_RCC_SetRTCClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI - * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRTCClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->BDCR, RCC_BDCR_RTCSEL, Source); -} - -/** - * @brief Get RTC Clock Source - * @rmtoll BDCR RTCSEL LL_RCC_GetRTCClockSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI - * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetRTCClockSource(void) -{ - return (uint32_t)(READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL)); -} - -/** - * @brief Enable RTC - * @rmtoll BDCR RTCEN LL_RCC_EnableRTC - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableRTC(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_RTCEN); -} - -/** - * @brief Disable RTC - * @rmtoll BDCR RTCEN LL_RCC_DisableRTC - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableRTC(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_RTCEN); -} - -/** - * @brief Check if RTC has been enabled or not - * @rmtoll BDCR RTCEN LL_RCC_IsEnabledRTC - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledRTC(void) -{ - return (READ_BIT(RCC->BDCR, RCC_BDCR_RTCEN) == (RCC_BDCR_RTCEN)); -} - -/** - * @brief Force the Backup domain reset - * @rmtoll BDCR BDRST LL_RCC_ForceBackupDomainReset - * @retval None - */ -__STATIC_INLINE void LL_RCC_ForceBackupDomainReset(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_BDRST); -} - -/** - * @brief Release the Backup domain reset - * @rmtoll BDCR BDRST LL_RCC_ReleaseBackupDomainReset - * @retval None - */ -__STATIC_INLINE void LL_RCC_ReleaseBackupDomainReset(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_BDRST); -} - -/** - * @brief Set HSE Prescalers for RTC Clock - * @rmtoll CFGR RTCPRE LL_RCC_SetRTC_HSEPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_RTC_NOCLOCK - * @arg @ref LL_RCC_RTC_HSE_DIV_2 - * @arg @ref LL_RCC_RTC_HSE_DIV_3 - * @arg @ref LL_RCC_RTC_HSE_DIV_4 - * @arg @ref LL_RCC_RTC_HSE_DIV_5 - * @arg @ref LL_RCC_RTC_HSE_DIV_6 - * @arg @ref LL_RCC_RTC_HSE_DIV_7 - * @arg @ref LL_RCC_RTC_HSE_DIV_8 - * @arg @ref LL_RCC_RTC_HSE_DIV_9 - * @arg @ref LL_RCC_RTC_HSE_DIV_10 - * @arg @ref LL_RCC_RTC_HSE_DIV_11 - * @arg @ref LL_RCC_RTC_HSE_DIV_12 - * @arg @ref LL_RCC_RTC_HSE_DIV_13 - * @arg @ref LL_RCC_RTC_HSE_DIV_14 - * @arg @ref LL_RCC_RTC_HSE_DIV_15 - * @arg @ref LL_RCC_RTC_HSE_DIV_16 - * @arg @ref LL_RCC_RTC_HSE_DIV_17 - * @arg @ref LL_RCC_RTC_HSE_DIV_18 - * @arg @ref LL_RCC_RTC_HSE_DIV_19 - * @arg @ref LL_RCC_RTC_HSE_DIV_20 - * @arg @ref LL_RCC_RTC_HSE_DIV_21 - * @arg @ref LL_RCC_RTC_HSE_DIV_22 - * @arg @ref LL_RCC_RTC_HSE_DIV_23 - * @arg @ref LL_RCC_RTC_HSE_DIV_24 - * @arg @ref LL_RCC_RTC_HSE_DIV_25 - * @arg @ref LL_RCC_RTC_HSE_DIV_26 - * @arg @ref LL_RCC_RTC_HSE_DIV_27 - * @arg @ref LL_RCC_RTC_HSE_DIV_28 - * @arg @ref LL_RCC_RTC_HSE_DIV_29 - * @arg @ref LL_RCC_RTC_HSE_DIV_30 - * @arg @ref LL_RCC_RTC_HSE_DIV_31 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRTC_HSEPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_RTCPRE, Prescaler); -} - -/** - * @brief Get HSE Prescalers for RTC Clock - * @rmtoll CFGR RTCPRE LL_RCC_GetRTC_HSEPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RTC_NOCLOCK - * @arg @ref LL_RCC_RTC_HSE_DIV_2 - * @arg @ref LL_RCC_RTC_HSE_DIV_3 - * @arg @ref LL_RCC_RTC_HSE_DIV_4 - * @arg @ref LL_RCC_RTC_HSE_DIV_5 - * @arg @ref LL_RCC_RTC_HSE_DIV_6 - * @arg @ref LL_RCC_RTC_HSE_DIV_7 - * @arg @ref LL_RCC_RTC_HSE_DIV_8 - * @arg @ref LL_RCC_RTC_HSE_DIV_9 - * @arg @ref LL_RCC_RTC_HSE_DIV_10 - * @arg @ref LL_RCC_RTC_HSE_DIV_11 - * @arg @ref LL_RCC_RTC_HSE_DIV_12 - * @arg @ref LL_RCC_RTC_HSE_DIV_13 - * @arg @ref LL_RCC_RTC_HSE_DIV_14 - * @arg @ref LL_RCC_RTC_HSE_DIV_15 - * @arg @ref LL_RCC_RTC_HSE_DIV_16 - * @arg @ref LL_RCC_RTC_HSE_DIV_17 - * @arg @ref LL_RCC_RTC_HSE_DIV_18 - * @arg @ref LL_RCC_RTC_HSE_DIV_19 - * @arg @ref LL_RCC_RTC_HSE_DIV_20 - * @arg @ref LL_RCC_RTC_HSE_DIV_21 - * @arg @ref LL_RCC_RTC_HSE_DIV_22 - * @arg @ref LL_RCC_RTC_HSE_DIV_23 - * @arg @ref LL_RCC_RTC_HSE_DIV_24 - * @arg @ref LL_RCC_RTC_HSE_DIV_25 - * @arg @ref LL_RCC_RTC_HSE_DIV_26 - * @arg @ref LL_RCC_RTC_HSE_DIV_27 - * @arg @ref LL_RCC_RTC_HSE_DIV_28 - * @arg @ref LL_RCC_RTC_HSE_DIV_29 - * @arg @ref LL_RCC_RTC_HSE_DIV_30 - * @arg @ref LL_RCC_RTC_HSE_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_GetRTC_HSEPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_RTCPRE)); -} - -/** - * @} - */ - -#if defined(RCC_DCKCFGR_TIMPRE) -/** @defgroup RCC_LL_EF_TIM_CLOCK_PRESCALER TIM - * @{ - */ - -/** - * @brief Set Timers Clock Prescalers - * @rmtoll DCKCFGR TIMPRE LL_RCC_SetTIMPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_TIM_PRESCALER_TWICE - * @arg @ref LL_RCC_TIM_PRESCALER_FOUR_TIMES - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetTIMPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_TIMPRE, Prescaler); -} - -/** - * @brief Get Timers Clock Prescalers - * @rmtoll DCKCFGR TIMPRE LL_RCC_GetTIMPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_TIM_PRESCALER_TWICE - * @arg @ref LL_RCC_TIM_PRESCALER_FOUR_TIMES - */ -__STATIC_INLINE uint32_t LL_RCC_GetTIMPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_TIMPRE)); -} - -/** - * @} - */ -#endif /* RCC_DCKCFGR_TIMPRE */ - -/** @defgroup RCC_LL_EF_PLL PLL - * @{ - */ - -/** - * @brief Enable PLL - * @rmtoll CR PLLON LL_RCC_PLL_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLON); -} - -/** - * @brief Disable PLL - * @note Cannot be disabled if the PLL clock is used as the system clock - * @rmtoll CR PLLON LL_RCC_PLL_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLON); -} - -/** - * @brief Check if PLL Ready - * @rmtoll CR PLLRDY LL_RCC_PLL_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLRDY) == (RCC_CR_PLLRDY)); -} - -/** - * @brief Configure PLL used for SYSCLK Domain - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLL is disabled - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLP LL_RCC_PLL_ConfigDomain_SYS - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLP_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - * @arg @ref LL_RCC_PLLR_DIV_2 (*) - * @arg @ref LL_RCC_PLLR_DIV_3 (*) - * @arg @ref LL_RCC_PLLR_DIV_4 (*) - * @arg @ref LL_RCC_PLLR_DIV_5 (*) - * @arg @ref LL_RCC_PLLR_DIV_6 (*) - * @arg @ref LL_RCC_PLLR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SYS(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP_R) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos); - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLP, PLLP_R); -#if defined(RCC_PLLR_SYSCLK_SUPPORT) - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLR, PLLP_R); -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ -} - -/** - * @brief Configure PLL used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLL is disabled - * @note This can be selected for USB, RNG, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLQ LL_RCC_PLL_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLQ, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLQ); -} - -#if defined(DSI) -/** - * @brief Configure PLL used for DSI clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for DSI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_DSI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_DSI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* DSI */ - -#if defined(RCC_PLLR_I2S_CLKSOURCE_SUPPORT) -/** - * @brief Configure PLL used for I2S clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for I2S - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_I2S - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_I2S(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* RCC_PLLR_I2S_CLKSOURCE_SUPPORT */ - -#if defined(SPDIFRX) -/** - * @brief Configure PLL used for SPDIFRX clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for SPDIFRX - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SPDIFRX - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SPDIFRX(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* SPDIFRX */ - -#if defined(RCC_PLLCFGR_PLLR) -#if defined(SAI1) -/** - * @brief Configure PLL used for SAI clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SAI\n - * DCKCFGR PLLDIVR LL_RCC_PLL_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @param PLLDIVR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -#if defined(RCC_DCKCFGR_PLLDIVR) -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR, uint32_t PLLDIVR) -#else -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -#endif /* RCC_DCKCFGR_PLLDIVR */ -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -#if defined(RCC_DCKCFGR_PLLDIVR) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR, PLLDIVR); -#endif /* RCC_DCKCFGR_PLLDIVR */ -} -#endif /* SAI1 */ -#endif /* RCC_PLLCFGR_PLLR */ - -/** - * @brief Configure PLL clock source - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_SetMainSource - * @param PLLSource This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SetMainSource(uint32_t PLLSource) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, PLLSource); -} - -/** - * @brief Get the oscillator used as PLL clock source. - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_GetMainSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetMainSource(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC)); -} - -/** - * @brief Get Main PLL multiplication factor for VCO - * @rmtoll PLLCFGR PLLN LL_RCC_PLL_GetN - * @retval Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); -} - -/** - * @brief Get Main PLL division factor for PLLP - * @rmtoll PLLCFGR PLLP LL_RCC_PLL_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLP)); -} - -/** - * @brief Get Main PLL division factor for PLLQ - * @note used for PLL48MCLK selected for USB, RNG, SDIO (48 MHz clock) - * @rmtoll PLLCFGR PLLQ LL_RCC_PLL_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLQ)); -} - -#if defined(RCC_PLLCFGR_PLLR) -/** - * @brief Get Main PLL division factor for PLLR - * @note used for PLLCLK (system clock) - * @rmtoll PLLCFGR PLLR LL_RCC_PLL_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR)); -} -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_DCKCFGR_PLLDIVR) -/** - * @brief Get Main PLL division factor for PLLDIVR - * @note used for PLLSAICLK (SAI1 and SAI2 clock) - * @rmtoll DCKCFGR PLLDIVR LL_RCC_PLL_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 - * @arg @ref LL_RCC_PLLDIVR_DIV_2 - * @arg @ref LL_RCC_PLLDIVR_DIV_3 - * @arg @ref LL_RCC_PLLDIVR_DIV_4 - * @arg @ref LL_RCC_PLLDIVR_DIV_5 - * @arg @ref LL_RCC_PLLDIVR_DIV_6 - * @arg @ref LL_RCC_PLLDIVR_DIV_7 - * @arg @ref LL_RCC_PLLDIVR_DIV_8 - * @arg @ref LL_RCC_PLLDIVR_DIV_9 - * @arg @ref LL_RCC_PLLDIVR_DIV_10 - * @arg @ref LL_RCC_PLLDIVR_DIV_11 - * @arg @ref LL_RCC_PLLDIVR_DIV_12 - * @arg @ref LL_RCC_PLLDIVR_DIV_13 - * @arg @ref LL_RCC_PLLDIVR_DIV_14 - * @arg @ref LL_RCC_PLLDIVR_DIV_15 - * @arg @ref LL_RCC_PLLDIVR_DIV_16 - * @arg @ref LL_RCC_PLLDIVR_DIV_17 - * @arg @ref LL_RCC_PLLDIVR_DIV_18 - * @arg @ref LL_RCC_PLLDIVR_DIV_19 - * @arg @ref LL_RCC_PLLDIVR_DIV_20 - * @arg @ref LL_RCC_PLLDIVR_DIV_21 - * @arg @ref LL_RCC_PLLDIVR_DIV_22 - * @arg @ref LL_RCC_PLLDIVR_DIV_23 - * @arg @ref LL_RCC_PLLDIVR_DIV_24 - * @arg @ref LL_RCC_PLLDIVR_DIV_25 - * @arg @ref LL_RCC_PLLDIVR_DIV_26 - * @arg @ref LL_RCC_PLLDIVR_DIV_27 - * @arg @ref LL_RCC_PLLDIVR_DIV_28 - * @arg @ref LL_RCC_PLLDIVR_DIV_29 - * @arg @ref LL_RCC_PLLDIVR_DIV_30 - * @arg @ref LL_RCC_PLLDIVR_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR)); -} -#endif /* RCC_DCKCFGR_PLLDIVR */ - -/** - * @brief Get Division factor for the main PLL and other PLL - * @rmtoll PLLCFGR PLLM LL_RCC_PLL_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetDivider(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -} - -/** - * @brief Configure Spread Spectrum used for PLL - * @note These bits must be written before enabling PLL - * @rmtoll SSCGR MODPER LL_RCC_PLL_ConfigSpreadSpectrum\n - * SSCGR INCSTEP LL_RCC_PLL_ConfigSpreadSpectrum\n - * SSCGR SPREADSEL LL_RCC_PLL_ConfigSpreadSpectrum - * @param Mod Between Min_Data=0 and Max_Data=8191 - * @param Inc Between Min_Data=0 and Max_Data=32767 - * @param Sel This parameter can be one of the following values: - * @arg @ref LL_RCC_SPREAD_SELECT_CENTER - * @arg @ref LL_RCC_SPREAD_SELECT_DOWN - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigSpreadSpectrum(uint32_t Mod, uint32_t Inc, uint32_t Sel) -{ - MODIFY_REG(RCC->SSCGR, RCC_SSCGR_MODPER | RCC_SSCGR_INCSTEP | RCC_SSCGR_SPREADSEL, Mod | (Inc << RCC_SSCGR_INCSTEP_Pos) | Sel); -} - -/** - * @brief Get Spread Spectrum Modulation Period for PLL - * @rmtoll SSCGR MODPER LL_RCC_PLL_GetPeriodModulation - * @retval Between Min_Data=0 and Max_Data=8191 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetPeriodModulation(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_MODPER)); -} - -/** - * @brief Get Spread Spectrum Incrementation Step for PLL - * @note Must be written before enabling PLL - * @rmtoll SSCGR INCSTEP LL_RCC_PLL_GetStepIncrementation - * @retval Between Min_Data=0 and Max_Data=32767 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetStepIncrementation(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_INCSTEP) >> RCC_SSCGR_INCSTEP_Pos); -} - -/** - * @brief Get Spread Spectrum Selection for PLL - * @note Must be written before enabling PLL - * @rmtoll SSCGR SPREADSEL LL_RCC_PLL_GetSpreadSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SPREAD_SELECT_CENTER - * @arg @ref LL_RCC_SPREAD_SELECT_DOWN - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetSpreadSelection(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_SPREADSEL)); -} - -/** - * @brief Enable Spread Spectrum for PLL. - * @rmtoll SSCGR SSCGEN LL_RCC_PLL_SpreadSpectrum_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SpreadSpectrum_Enable(void) -{ - SET_BIT(RCC->SSCGR, RCC_SSCGR_SSCGEN); -} - -/** - * @brief Disable Spread Spectrum for PLL. - * @rmtoll SSCGR SSCGEN LL_RCC_PLL_SpreadSpectrum_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SpreadSpectrum_Disable(void) -{ - CLEAR_BIT(RCC->SSCGR, RCC_SSCGR_SSCGEN); -} - -/** - * @} - */ - -#if defined(RCC_PLLI2S_SUPPORT) -/** @defgroup RCC_LL_EF_PLLI2S PLLI2S - * @{ - */ - -/** - * @brief Enable PLLI2S - * @rmtoll CR PLLI2SON LL_RCC_PLLI2S_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLI2SON); -} - -/** - * @brief Disable PLLI2S - * @rmtoll CR PLLI2SON LL_RCC_PLLI2S_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLI2SON); -} - -/** - * @brief Check if PLLI2S Ready - * @rmtoll CR PLLI2SRDY LL_RCC_PLLI2S_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) == (RCC_CR_PLLI2SRDY)); -} - -#if (defined(RCC_DCKCFGR_PLLI2SDIVQ) || defined(RCC_DCKCFGR_PLLI2SDIVR)) -/** - * @brief Configure PLLI2S used for SAI domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ/PLLR can be written only when PLLI2S is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_ConfigDomain_SAI\n - * DCKCFGR PLLI2SDIVQ LL_RCC_PLLI2S_ConfigDomain_SAI\n - * DCKCFGR PLLI2SDIVR LL_RCC_PLLI2S_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @param PLLDIVQ_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ_R, uint32_t PLLDIVQ_R) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos); -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SQ, PLLQ_R); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ, PLLDIVQ_R); -#else - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SR, PLLQ_R); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR, PLLDIVQ_R); -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ -} -#endif /* RCC_DCKCFGR_PLLI2SDIVQ && RCC_DCKCFGR_PLLI2SDIVR */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Configure PLLI2S used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLLI2S is disabled - * @note This can be selected for RNG, USB, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SQ, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLQ); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(SPDIFRX) -/** - * @brief Configure PLLI2S used for SPDIFRX domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLLI2S is disabled - * @note This can be selected for SPDIFRX - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SP LL_RCC_PLLI2S_ConfigDomain_SPDIFRX - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLP This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_SPDIFRX(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SP, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLP); -} -#endif /* SPDIFRX */ - -/** - * @brief Configure PLLI2S used for I2S1 domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLR can be written only when PLLI2S is disabled - * @note This can be selected for I2S - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_ConfigDomain_I2S - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_I2S(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SR, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLR); -} - -/** - * @brief Get I2SPLL multiplication factor for VCO - * @rmtoll PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_GetN - * @retval Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); -} - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) -/** - * @brief Get I2SPLL division factor for PLLI2SQ - * @rmtoll PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SQ)); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ - -/** - * @brief Get I2SPLL division factor for PLLI2SR - * @note used for PLLI2SCLK (I2S clock) - * @rmtoll PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SR)); -} - -#if defined(RCC_PLLI2SCFGR_PLLI2SP) -/** - * @brief Get I2SPLL division factor for PLLI2SP - * @note used for PLLSPDIFRXCLK (SPDIFRX clock) - * @rmtoll PLLI2SCFGR PLLI2SP LL_RCC_PLLI2S_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SP)); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SP */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Get I2SPLL division factor for PLLI2SDIVQ - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLI2SDIVQ LL_RCC_PLLI2S_GetDIVQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDIVQ(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ)); -} -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVR) -/** - * @brief Get I2SPLL division factor for PLLI2SDIVR - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLI2SDIVR LL_RCC_PLLI2S_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR)); -} -#endif /* RCC_DCKCFGR_PLLI2SDIVR */ - -/** - * @brief Get division factor for PLLI2S input clock - * @rmtoll PLLCFGR PLLM LL_RCC_PLLI2S_GetDivider\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDivider(void) -{ -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM)); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ -} - -/** - * @brief Get the oscillator used as PLL clock source. - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_GetMainSource\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_GetMainSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetMainSource(void) -{ -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) - uint32_t pllsrc = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC); - uint32_t plli2sssrc0 = READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SSRC); - uint32_t plli2sssrc1 = READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SSRC) >> 15U; - return (uint32_t)(pllsrc | plli2sssrc0 | plli2sssrc1); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC)); -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ -} - -/** - * @} - */ -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** @defgroup RCC_LL_EF_PLLSAI PLLSAI - * @{ - */ - -/** - * @brief Enable PLLSAI - * @rmtoll CR PLLSAION LL_RCC_PLLSAI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLSAION); -} - -/** - * @brief Disable PLLSAI - * @rmtoll CR PLLSAION LL_RCC_PLLSAI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLSAION); -} - -/** - * @brief Check if PLLSAI Ready - * @rmtoll CR PLLSAIRDY LL_RCC_PLLSAI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLSAIRDY) == (RCC_CR_PLLSAIRDY)); -} - -/** - * @brief Configure PLLSAI used for SAI domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLLSAI is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIQ LL_RCC_PLLSAI_ConfigDomain_SAI\n - * DCKCFGR PLLSAIDIVQ LL_RCC_PLLSAI_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - * @param PLLDIVQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ, uint32_t PLLDIVQ) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLSAICFGR_PLLSAIM) - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIQ, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLQ); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ, PLLDIVQ); -} - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Configure PLLSAI used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLLSAI is disabled - * @note This can be selected for USB, RNG, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIP LL_RCC_PLLSAI_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLP This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLSAICFGR_PLLSAIM) - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIP, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLP); -} -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -#if defined(LTDC) -/** - * @brief Configure PLLSAI used for LTDC domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLR can be written only when PLLSAI is disabled - * @note This can be selected for LTDC - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLSAICFGR PLLSAIR LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * DCKCFGR PLLSAIDIVR LL_RCC_PLLSAI_ConfigDomain_LTDC - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - * @param PLLDIVR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_LTDC(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR, uint32_t PLLDIVR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM, Source | PLLM); - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIR, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLR); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR, PLLDIVR); -} -#endif /* LTDC */ - -/** - * @brief Get division factor for PLLSAI input clock - * @rmtoll PLLCFGR PLLM LL_RCC_PLLSAI_GetDivider\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDivider(void) -{ -#if defined(RCC_PLLSAICFGR_PLLSAIM) - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM)); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ -} - -/** - * @brief Get SAIPLL multiplication factor for VCO - * @rmtoll PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_GetN - * @retval Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); -} - -/** - * @brief Get SAIPLL division factor for PLLSAIQ - * @rmtoll PLLSAICFGR PLLSAIQ LL_RCC_PLLSAI_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIQ)); -} - -#if defined(RCC_PLLSAICFGR_PLLSAIR) -/** - * @brief Get SAIPLL division factor for PLLSAIR - * @note used for PLLSAICLK (SAI clock) - * @rmtoll PLLSAICFGR PLLSAIR LL_RCC_PLLSAI_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIR)); -} -#endif /* RCC_PLLSAICFGR_PLLSAIR */ - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Get SAIPLL division factor for PLLSAIP - * @note used for PLL48MCLK (48M domain clock) - * @rmtoll PLLSAICFGR PLLSAIP LL_RCC_PLLSAI_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIP)); -} -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -/** - * @brief Get SAIPLL division factor for PLLSAIDIVQ - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLSAIDIVQ LL_RCC_PLLSAI_GetDIVQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDIVQ(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ)); -} - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -/** - * @brief Get SAIPLL division factor for PLLSAIDIVR - * @note used for LTDC domain clock - * @rmtoll DCKCFGR PLLSAIDIVR LL_RCC_PLLSAI_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR)); -} -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -/** - * @} - */ -#endif /* RCC_PLLSAI_SUPPORT */ - -/** @defgroup RCC_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Clear LSI ready interrupt flag - * @rmtoll CIR LSIRDYC LL_RCC_ClearFlag_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_LSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC); -} - -/** - * @brief Clear LSE ready interrupt flag - * @rmtoll CIR LSERDYC LL_RCC_ClearFlag_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_LSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSERDYC); -} - -/** - * @brief Clear HSI ready interrupt flag - * @rmtoll CIR HSIRDYC LL_RCC_ClearFlag_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSIRDYC); -} - -/** - * @brief Clear HSE ready interrupt flag - * @rmtoll CIR HSERDYC LL_RCC_ClearFlag_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSERDYC); -} - -/** - * @brief Clear PLL ready interrupt flag - * @rmtoll CIR PLLRDYC LL_RCC_ClearFlag_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLRDYC); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Clear PLLI2S ready interrupt flag - * @rmtoll CIR PLLI2SRDYC LL_RCC_ClearFlag_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLI2SRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Clear PLLSAI ready interrupt flag - * @rmtoll CIR PLLSAIRDYC LL_RCC_ClearFlag_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLSAIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); -} - -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Clear Clock security system interrupt flag - * @rmtoll CIR CSSC LL_RCC_ClearFlag_HSECSS - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSECSS(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_CSSC); -} - -/** - * @brief Check if LSI ready interrupt occurred or not - * @rmtoll CIR LSIRDYF LL_RCC_IsActiveFlag_LSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYF) == (RCC_CIR_LSIRDYF)); -} - -/** - * @brief Check if LSE ready interrupt occurred or not - * @rmtoll CIR LSERDYF LL_RCC_IsActiveFlag_LSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYF) == (RCC_CIR_LSERDYF)); -} - -/** - * @brief Check if HSI ready interrupt occurred or not - * @rmtoll CIR HSIRDYF LL_RCC_IsActiveFlag_HSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYF) == (RCC_CIR_HSIRDYF)); -} - -/** - * @brief Check if HSE ready interrupt occurred or not - * @rmtoll CIR HSERDYF LL_RCC_IsActiveFlag_HSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYF) == (RCC_CIR_HSERDYF)); -} - -/** - * @brief Check if PLL ready interrupt occurred or not - * @rmtoll CIR PLLRDYF LL_RCC_IsActiveFlag_PLLRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYF) == (RCC_CIR_PLLRDYF)); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Check if PLLI2S ready interrupt occurred or not - * @rmtoll CIR PLLI2SRDYF LL_RCC_IsActiveFlag_PLLI2SRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLI2SRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYF) == (RCC_CIR_PLLI2SRDYF)); -} -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Check if PLLSAI ready interrupt occurred or not - * @rmtoll CIR PLLSAIRDYF LL_RCC_IsActiveFlag_PLLSAIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLSAIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYF) == (RCC_CIR_PLLSAIRDYF)); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Check if Clock security system interrupt occurred or not - * @rmtoll CIR CSSF LL_RCC_IsActiveFlag_HSECSS - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSECSS(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_CSSF) == (RCC_CIR_CSSF)); -} - -/** - * @brief Check if RCC flag Independent Watchdog reset is set or not. - * @rmtoll CSR IWDGRSTF LL_RCC_IsActiveFlag_IWDGRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_IWDGRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_IWDGRSTF) == (RCC_CSR_IWDGRSTF)); -} - -/** - * @brief Check if RCC flag Low Power reset is set or not. - * @rmtoll CSR LPWRRSTF LL_RCC_IsActiveFlag_LPWRRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LPWRRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_LPWRRSTF) == (RCC_CSR_LPWRRSTF)); -} - -/** - * @brief Check if RCC flag Pin reset is set or not. - * @rmtoll CSR PINRSTF LL_RCC_IsActiveFlag_PINRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PINRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_PINRSTF) == (RCC_CSR_PINRSTF)); -} - -/** - * @brief Check if RCC flag POR/PDR reset is set or not. - * @rmtoll CSR PORRSTF LL_RCC_IsActiveFlag_PORRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PORRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_PORRSTF) == (RCC_CSR_PORRSTF)); -} - -/** - * @brief Check if RCC flag Software reset is set or not. - * @rmtoll CSR SFTRSTF LL_RCC_IsActiveFlag_SFTRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_SFTRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_SFTRSTF) == (RCC_CSR_SFTRSTF)); -} - -/** - * @brief Check if RCC flag Window Watchdog reset is set or not. - * @rmtoll CSR WWDGRSTF LL_RCC_IsActiveFlag_WWDGRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_WWDGRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_WWDGRSTF) == (RCC_CSR_WWDGRSTF)); -} - -#if defined(RCC_CSR_BORRSTF) -/** - * @brief Check if RCC flag BOR reset is set or not. - * @rmtoll CSR BORRSTF LL_RCC_IsActiveFlag_BORRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_BORRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_BORRSTF) == (RCC_CSR_BORRSTF)); -} -#endif /* RCC_CSR_BORRSTF */ - -/** - * @brief Set RMVF bit to clear the reset flags. - * @rmtoll CSR RMVF LL_RCC_ClearResetFlags - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearResetFlags(void) -{ - SET_BIT(RCC->CSR, RCC_CSR_RMVF); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_IT_Management IT Management - * @{ - */ - -/** - * @brief Enable LSI ready interrupt - * @rmtoll CIR LSIRDYIE LL_RCC_EnableIT_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_LSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYIE); -} - -/** - * @brief Enable LSE ready interrupt - * @rmtoll CIR LSERDYIE LL_RCC_EnableIT_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_LSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSERDYIE); -} - -/** - * @brief Enable HSI ready interrupt - * @rmtoll CIR HSIRDYIE LL_RCC_EnableIT_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_HSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSIRDYIE); -} - -/** - * @brief Enable HSE ready interrupt - * @rmtoll CIR HSERDYIE LL_RCC_EnableIT_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_HSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSERDYIE); -} - -/** - * @brief Enable PLL ready interrupt - * @rmtoll CIR PLLRDYIE LL_RCC_EnableIT_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLRDYIE); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Enable PLLI2S ready interrupt - * @rmtoll CIR PLLI2SRDYIE LL_RCC_EnableIT_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLI2SRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -} -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Enable PLLSAI ready interrupt - * @rmtoll CIR PLLSAIRDYIE LL_RCC_EnableIT_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLSAIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Disable LSI ready interrupt - * @rmtoll CIR LSIRDYIE LL_RCC_DisableIT_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_LSIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE); -} - -/** - * @brief Disable LSE ready interrupt - * @rmtoll CIR LSERDYIE LL_RCC_DisableIT_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_LSERDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSERDYIE); -} - -/** - * @brief Disable HSI ready interrupt - * @rmtoll CIR HSIRDYIE LL_RCC_DisableIT_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_HSIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_HSIRDYIE); -} - -/** - * @brief Disable HSE ready interrupt - * @rmtoll CIR HSERDYIE LL_RCC_DisableIT_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_HSERDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_HSERDYIE); -} - -/** - * @brief Disable PLL ready interrupt - * @rmtoll CIR PLLRDYIE LL_RCC_DisableIT_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLRDYIE); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Disable PLLI2S ready interrupt - * @rmtoll CIR PLLI2SRDYIE LL_RCC_DisableIT_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLI2SRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Disable PLLSAI ready interrupt - * @rmtoll CIR PLLSAIRDYIE LL_RCC_DisableIT_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLSAIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Checks if LSI ready interrupt source is enabled or disabled. - * @rmtoll CIR LSIRDYIE LL_RCC_IsEnabledIT_LSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYIE) == (RCC_CIR_LSIRDYIE)); -} - -/** - * @brief Checks if LSE ready interrupt source is enabled or disabled. - * @rmtoll CIR LSERDYIE LL_RCC_IsEnabledIT_LSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYIE) == (RCC_CIR_LSERDYIE)); -} - -/** - * @brief Checks if HSI ready interrupt source is enabled or disabled. - * @rmtoll CIR HSIRDYIE LL_RCC_IsEnabledIT_HSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYIE) == (RCC_CIR_HSIRDYIE)); -} - -/** - * @brief Checks if HSE ready interrupt source is enabled or disabled. - * @rmtoll CIR HSERDYIE LL_RCC_IsEnabledIT_HSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYIE) == (RCC_CIR_HSERDYIE)); -} - -/** - * @brief Checks if PLL ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLRDYIE LL_RCC_IsEnabledIT_PLLRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYIE) == (RCC_CIR_PLLRDYIE)); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Checks if PLLI2S ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLI2SRDYIE LL_RCC_IsEnabledIT_PLLI2SRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLI2SRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE) == (RCC_CIR_PLLI2SRDYIE)); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Checks if PLLSAI ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLSAIRDYIE LL_RCC_IsEnabledIT_PLLSAIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLSAIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE) == (RCC_CIR_PLLSAIRDYIE)); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_EF_Init De-initialization function - * @{ - */ -ErrorStatus LL_RCC_DeInit(void); -/** - * @} - */ - -/** @defgroup RCC_LL_EF_Get_Freq Get system and peripherals clocks frequency functions - * @{ - */ -void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks); -#if defined(FMPI2C1) -uint32_t LL_RCC_GetFMPI2CClockFreq(uint32_t FMPI2CxSource); -#endif /* FMPI2C1 */ -#if defined(LPTIM1) -uint32_t LL_RCC_GetLPTIMClockFreq(uint32_t LPTIMxSource); -#endif /* LPTIM1 */ -#if defined(SAI1) -uint32_t LL_RCC_GetSAIClockFreq(uint32_t SAIxSource); -#endif /* SAI1 */ -#if defined(SDIO) -uint32_t LL_RCC_GetSDIOClockFreq(uint32_t SDIOxSource); -#endif /* SDIO */ -#if defined(RNG) -uint32_t LL_RCC_GetRNGClockFreq(uint32_t RNGxSource); -#endif /* RNG */ -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource); -#endif /* USB_OTG_FS || USB_OTG_HS */ -#if defined(DFSDM1_Channel0) -uint32_t LL_RCC_GetDFSDMClockFreq(uint32_t DFSDMxSource); -uint32_t LL_RCC_GetDFSDMAudioClockFreq(uint32_t DFSDMxSource); -#endif /* DFSDM1_Channel0 */ -uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource); -#if defined(CEC) -uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource); -#endif /* CEC */ -#if defined(LTDC) -uint32_t LL_RCC_GetLTDCClockFreq(uint32_t LTDCxSource); -#endif /* LTDC */ -#if defined(SPDIFRX) -uint32_t LL_RCC_GetSPDIFRXClockFreq(uint32_t SPDIFRXxSource); -#endif /* SPDIFRX */ -#if defined(DSI) -uint32_t LL_RCC_GetDSIClockFreq(uint32_t DSIxSource); -#endif /* DSI */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RCC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_RCC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rng.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rng.h deleted file mode 100644 index c142717b0cfb921..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rng.h +++ /dev/null @@ -1,337 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rng.h - * @author MCD Application Team - * @brief Header file of RNG LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_RNG_H -#define STM32F4xx_LL_RNG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (RNG) - -/** @defgroup RNG_LL RNG - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RNG_LL_Exported_Constants RNG Exported Constants - * @{ - */ - - -/** @defgroup RNG_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_RNG_ReadReg function - * @{ - */ -#define LL_RNG_SR_DRDY RNG_SR_DRDY /*!< Register contains valid random data */ -#define LL_RNG_SR_CECS RNG_SR_CECS /*!< Clock error current status */ -#define LL_RNG_SR_SECS RNG_SR_SECS /*!< Seed error current status */ -#define LL_RNG_SR_CEIS RNG_SR_CEIS /*!< Clock error interrupt status */ -#define LL_RNG_SR_SEIS RNG_SR_SEIS /*!< Seed error interrupt status */ -/** - * @} - */ - -/** @defgroup RNG_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_RNG_ReadReg and LL_RNG_WriteReg macros - * @{ - */ -#define LL_RNG_CR_IE RNG_CR_IE /*!< RNG Interrupt enable */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RNG_LL_Exported_Macros RNG Exported Macros - * @{ - */ - -/** @defgroup RNG_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in RNG register - * @param __INSTANCE__ RNG Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_RNG_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in RNG register - * @param __INSTANCE__ RNG Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_RNG_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RNG_LL_Exported_Functions RNG Exported Functions - * @{ - */ -/** @defgroup RNG_LL_EF_Configuration RNG Configuration functions - * @{ - */ - -/** - * @brief Enable Random Number Generation - * @rmtoll CR RNGEN LL_RNG_Enable - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_Enable(RNG_TypeDef *RNGx) -{ - SET_BIT(RNGx->CR, RNG_CR_RNGEN); -} - -/** - * @brief Disable Random Number Generation - * @rmtoll CR RNGEN LL_RNG_Disable - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_Disable(RNG_TypeDef *RNGx) -{ - CLEAR_BIT(RNGx->CR, RNG_CR_RNGEN); -} - -/** - * @brief Check if Random Number Generator is enabled - * @rmtoll CR RNGEN LL_RNG_IsEnabled - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsEnabled(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->CR, RNG_CR_RNGEN) == (RNG_CR_RNGEN)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup RNG_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Indicate if the RNG Data ready Flag is set or not - * @rmtoll SR DRDY LL_RNG_IsActiveFlag_DRDY - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_DRDY(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_DRDY) == (RNG_SR_DRDY)) ? 1UL : 0UL); -} - -/** - * @brief Indicate if the Clock Error Current Status Flag is set or not - * @rmtoll SR CECS LL_RNG_IsActiveFlag_CECS - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_CECS(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_CECS) == (RNG_SR_CECS)) ? 1UL : 0UL); -} - -/** - * @brief Indicate if the Seed Error Current Status Flag is set or not - * @rmtoll SR SECS LL_RNG_IsActiveFlag_SECS - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_SECS(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_SECS) == (RNG_SR_SECS)) ? 1UL : 0UL); -} - -/** - * @brief Indicate if the Clock Error Interrupt Status Flag is set or not - * @rmtoll SR CEIS LL_RNG_IsActiveFlag_CEIS - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_CEIS(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_CEIS) == (RNG_SR_CEIS)) ? 1UL : 0UL); -} - -/** - * @brief Indicate if the Seed Error Interrupt Status Flag is set or not - * @rmtoll SR SEIS LL_RNG_IsActiveFlag_SEIS - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_SEIS(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_SEIS) == (RNG_SR_SEIS)) ? 1UL : 0UL); -} - -/** - * @brief Clear Clock Error interrupt Status (CEIS) Flag - * @rmtoll SR CEIS LL_RNG_ClearFlag_CEIS - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_ClearFlag_CEIS(RNG_TypeDef *RNGx) -{ - WRITE_REG(RNGx->SR, ~RNG_SR_CEIS); -} - -/** - * @brief Clear Seed Error interrupt Status (SEIS) Flag - * @rmtoll SR SEIS LL_RNG_ClearFlag_SEIS - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_ClearFlag_SEIS(RNG_TypeDef *RNGx) -{ - WRITE_REG(RNGx->SR, ~RNG_SR_SEIS); -} - -/** - * @} - */ - -/** @defgroup RNG_LL_EF_IT_Management IT Management - * @{ - */ - -/** - * @brief Enable Random Number Generator Interrupt - * (applies for either Seed error, Clock Error or Data ready interrupts) - * @rmtoll CR IE LL_RNG_EnableIT - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_EnableIT(RNG_TypeDef *RNGx) -{ - SET_BIT(RNGx->CR, RNG_CR_IE); -} - -/** - * @brief Disable Random Number Generator Interrupt - * (applies for either Seed error, Clock Error or Data ready interrupts) - * @rmtoll CR IE LL_RNG_DisableIT - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_DisableIT(RNG_TypeDef *RNGx) -{ - CLEAR_BIT(RNGx->CR, RNG_CR_IE); -} - -/** - * @brief Check if Random Number Generator Interrupt is enabled - * (applies for either Seed error, Clock Error or Data ready interrupts) - * @rmtoll CR IE LL_RNG_IsEnabledIT - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsEnabledIT(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->CR, RNG_CR_IE) == (RNG_CR_IE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup RNG_LL_EF_Data_Management Data Management - * @{ - */ - -/** - * @brief Return32-bit Random Number value - * @rmtoll DR RNDATA LL_RNG_ReadRandData32 - * @param RNGx RNG Instance - * @retval Generated 32-bit random value - */ -__STATIC_INLINE uint32_t LL_RNG_ReadRandData32(RNG_TypeDef *RNGx) -{ - return (uint32_t)(READ_REG(RNGx->DR)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RNG_LL_EF_Init Initialization and de-initialization functions - * @{ - */ -ErrorStatus LL_RNG_DeInit(RNG_TypeDef *RNGx); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* RNG */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_RNG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rtc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rtc.h deleted file mode 100644 index 1f57ce444543ec3..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rtc.h +++ /dev/null @@ -1,3793 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rtc.h - * @author MCD Application Team - * @brief Header file of RTC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_RTC_H -#define __STM32F4xx_LL_RTC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RTC) - -/** @defgroup RTC_LL RTC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RTC_LL_Private_Constants RTC Private Constants - * @{ - */ -/* Masks Definition */ -#define RTC_INIT_MASK 0xFFFFFFFFU -#define RTC_RSF_MASK 0xFFFFFF5FU - -/* Write protection defines */ -#define RTC_WRITE_PROTECTION_DISABLE ((uint8_t)0xFFU) -#define RTC_WRITE_PROTECTION_ENABLE_1 ((uint8_t)0xCAU) -#define RTC_WRITE_PROTECTION_ENABLE_2 ((uint8_t)0x53U) - -/* Defines used to combine date & time */ -#define RTC_OFFSET_WEEKDAY 24U -#define RTC_OFFSET_DAY 16U -#define RTC_OFFSET_MONTH 8U -#define RTC_OFFSET_HOUR 16U -#define RTC_OFFSET_MINUTE 8U - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RTC_LL_Private_Macros RTC Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RTC_LL_ES_INIT RTC Exported Init structure - * @{ - */ - -/** - * @brief RTC Init structures definition - */ -typedef struct -{ - uint32_t HourFormat; /*!< Specifies the RTC Hours Format. - This parameter can be a value of @ref RTC_LL_EC_HOURFORMAT - - This feature can be modified afterwards using unitary function - @ref LL_RTC_SetHourFormat(). */ - - uint32_t AsynchPrescaler; /*!< Specifies the RTC Asynchronous Predivider value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7F - - This feature can be modified afterwards using unitary function - @ref LL_RTC_SetAsynchPrescaler(). */ - - uint32_t SynchPrescaler; /*!< Specifies the RTC Synchronous Predivider value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7FFF - - This feature can be modified afterwards using unitary function - @ref LL_RTC_SetSynchPrescaler(). */ -} LL_RTC_InitTypeDef; - -/** - * @brief RTC Time structure definition - */ -typedef struct -{ - uint32_t TimeFormat; /*!< Specifies the RTC AM/PM Time. - This parameter can be a value of @ref RTC_LL_EC_TIME_FORMAT - - This feature can be modified afterwards using unitary function @ref LL_RTC_TIME_SetFormat(). */ - - uint8_t Hours; /*!< Specifies the RTC Time Hours. - This parameter must be a number between Min_Data = 0 and Max_Data = 12 if the @ref LL_RTC_TIME_FORMAT_PM is selected. - This parameter must be a number between Min_Data = 0 and Max_Data = 23 if the @ref LL_RTC_TIME_FORMAT_AM_OR_24 is selected. - - This feature can be modified afterwards using unitary function @ref LL_RTC_TIME_SetHour(). */ - - uint8_t Minutes; /*!< Specifies the RTC Time Minutes. - This parameter must be a number between Min_Data = 0 and Max_Data = 59 - - This feature can be modified afterwards using unitary function @ref LL_RTC_TIME_SetMinute(). */ - - uint8_t Seconds; /*!< Specifies the RTC Time Seconds. - This parameter must be a number between Min_Data = 0 and Max_Data = 59 - - This feature can be modified afterwards using unitary function @ref LL_RTC_TIME_SetSecond(). */ -} LL_RTC_TimeTypeDef; - -/** - * @brief RTC Date structure definition - */ -typedef struct -{ - uint8_t WeekDay; /*!< Specifies the RTC Date WeekDay. - This parameter can be a value of @ref RTC_LL_EC_WEEKDAY - - This feature can be modified afterwards using unitary function @ref LL_RTC_DATE_SetWeekDay(). */ - - uint8_t Month; /*!< Specifies the RTC Date Month. - This parameter can be a value of @ref RTC_LL_EC_MONTH - - This feature can be modified afterwards using unitary function @ref LL_RTC_DATE_SetMonth(). */ - - uint8_t Day; /*!< Specifies the RTC Date Day. - This parameter must be a number between Min_Data = 1 and Max_Data = 31 - - This feature can be modified afterwards using unitary function @ref LL_RTC_DATE_SetDay(). */ - - uint8_t Year; /*!< Specifies the RTC Date Year. - This parameter must be a number between Min_Data = 0 and Max_Data = 99 - - This feature can be modified afterwards using unitary function @ref LL_RTC_DATE_SetYear(). */ -} LL_RTC_DateTypeDef; - -/** - * @brief RTC Alarm structure definition - */ -typedef struct -{ - LL_RTC_TimeTypeDef AlarmTime; /*!< Specifies the RTC Alarm Time members. */ - - uint32_t AlarmMask; /*!< Specifies the RTC Alarm Masks. - This parameter can be a value of @ref RTC_LL_EC_ALMA_MASK for ALARM A or @ref RTC_LL_EC_ALMB_MASK for ALARM B. - - This feature can be modified afterwards using unitary function @ref LL_RTC_ALMA_SetMask() for ALARM A - or @ref LL_RTC_ALMB_SetMask() for ALARM B - */ - - uint32_t AlarmDateWeekDaySel; /*!< Specifies the RTC Alarm is on day or WeekDay. - This parameter can be a value of @ref RTC_LL_EC_ALMA_WEEKDAY_SELECTION for ALARM A or @ref RTC_LL_EC_ALMB_WEEKDAY_SELECTION for ALARM B - - This feature can be modified afterwards using unitary function @ref LL_RTC_ALMA_EnableWeekday() or @ref LL_RTC_ALMA_DisableWeekday() - for ALARM A or @ref LL_RTC_ALMB_EnableWeekday() or @ref LL_RTC_ALMB_DisableWeekday() for ALARM B - */ - - uint8_t AlarmDateWeekDay; /*!< Specifies the RTC Alarm Day/WeekDay. - If AlarmDateWeekDaySel set to day, this parameter must be a number between Min_Data = 1 and Max_Data = 31. - - This feature can be modified afterwards using unitary function @ref LL_RTC_ALMA_SetDay() - for ALARM A or @ref LL_RTC_ALMB_SetDay() for ALARM B. - - If AlarmDateWeekDaySel set to Weekday, this parameter can be a value of @ref RTC_LL_EC_WEEKDAY. - - This feature can be modified afterwards using unitary function @ref LL_RTC_ALMA_SetWeekDay() - for ALARM A or @ref LL_RTC_ALMB_SetWeekDay() for ALARM B. - */ -} LL_RTC_AlarmTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RTC_LL_Exported_Constants RTC Exported Constants - * @{ - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RTC_LL_EC_FORMAT FORMAT - * @{ - */ -#define LL_RTC_FORMAT_BIN 0x000000000U /*!< Binary data format */ -#define LL_RTC_FORMAT_BCD 0x000000001U /*!< BCD data format */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMA_WEEKDAY_SELECTION RTC Alarm A Date WeekDay - * @{ - */ -#define LL_RTC_ALMA_DATEWEEKDAYSEL_DATE 0x00000000U /*!< Alarm A Date is selected */ -#define LL_RTC_ALMA_DATEWEEKDAYSEL_WEEKDAY RTC_ALRMAR_WDSEL /*!< Alarm A WeekDay is selected */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMB_WEEKDAY_SELECTION RTC Alarm B Date WeekDay - * @{ - */ -#define LL_RTC_ALMB_DATEWEEKDAYSEL_DATE 0x00000000U /*!< Alarm B Date is selected */ -#define LL_RTC_ALMB_DATEWEEKDAYSEL_WEEKDAY RTC_ALRMBR_WDSEL /*!< Alarm B WeekDay is selected */ -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/** @defgroup RTC_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_RTC_ReadReg function - * @{ - */ -#define LL_RTC_ISR_RECALPF RTC_ISR_RECALPF -#define LL_RTC_ISR_TAMP3F RTC_ISR_TAMP3F -#define LL_RTC_ISR_TAMP2F RTC_ISR_TAMP2F -#define LL_RTC_ISR_TAMP1F RTC_ISR_TAMP1F -#define LL_RTC_ISR_TSOVF RTC_ISR_TSOVF -#define LL_RTC_ISR_TSF RTC_ISR_TSF -#define LL_RTC_ISR_WUTF RTC_ISR_WUTF -#define LL_RTC_ISR_ALRBF RTC_ISR_ALRBF -#define LL_RTC_ISR_ALRAF RTC_ISR_ALRAF -#define LL_RTC_ISR_INITF RTC_ISR_INITF -#define LL_RTC_ISR_RSF RTC_ISR_RSF -#define LL_RTC_ISR_INITS RTC_ISR_INITS -#define LL_RTC_ISR_SHPF RTC_ISR_SHPF -#define LL_RTC_ISR_WUTWF RTC_ISR_WUTWF -#define LL_RTC_ISR_ALRBWF RTC_ISR_ALRBWF -#define LL_RTC_ISR_ALRAWF RTC_ISR_ALRAWF -/** - * @} - */ - -/** @defgroup RTC_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_RTC_ReadReg and LL_RTC_WriteReg functions - * @{ - */ -#define LL_RTC_CR_TSIE RTC_CR_TSIE -#define LL_RTC_CR_WUTIE RTC_CR_WUTIE -#define LL_RTC_CR_ALRBIE RTC_CR_ALRBIE -#define LL_RTC_CR_ALRAIE RTC_CR_ALRAIE -#define LL_RTC_TAFCR_TAMPIE RTC_TAFCR_TAMPIE -/** - * @} - */ - -/** @defgroup RTC_LL_EC_WEEKDAY WEEK DAY - * @{ - */ -#define LL_RTC_WEEKDAY_MONDAY ((uint8_t)0x01U) /*!< Monday */ -#define LL_RTC_WEEKDAY_TUESDAY ((uint8_t)0x02U) /*!< Tuesday */ -#define LL_RTC_WEEKDAY_WEDNESDAY ((uint8_t)0x03U) /*!< Wednesday */ -#define LL_RTC_WEEKDAY_THURSDAY ((uint8_t)0x04U) /*!< Thrusday */ -#define LL_RTC_WEEKDAY_FRIDAY ((uint8_t)0x05U) /*!< Friday */ -#define LL_RTC_WEEKDAY_SATURDAY ((uint8_t)0x06U) /*!< Saturday */ -#define LL_RTC_WEEKDAY_SUNDAY ((uint8_t)0x07U) /*!< Sunday */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_MONTH MONTH - * @{ - */ -#define LL_RTC_MONTH_JANUARY ((uint8_t)0x01U) /*!< January */ -#define LL_RTC_MONTH_FEBRUARY ((uint8_t)0x02U) /*!< February */ -#define LL_RTC_MONTH_MARCH ((uint8_t)0x03U) /*!< March */ -#define LL_RTC_MONTH_APRIL ((uint8_t)0x04U) /*!< April */ -#define LL_RTC_MONTH_MAY ((uint8_t)0x05U) /*!< May */ -#define LL_RTC_MONTH_JUNE ((uint8_t)0x06U) /*!< June */ -#define LL_RTC_MONTH_JULY ((uint8_t)0x07U) /*!< July */ -#define LL_RTC_MONTH_AUGUST ((uint8_t)0x08U) /*!< August */ -#define LL_RTC_MONTH_SEPTEMBER ((uint8_t)0x09U) /*!< September */ -#define LL_RTC_MONTH_OCTOBER ((uint8_t)0x10U) /*!< October */ -#define LL_RTC_MONTH_NOVEMBER ((uint8_t)0x11U) /*!< November */ -#define LL_RTC_MONTH_DECEMBER ((uint8_t)0x12U) /*!< December */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_HOURFORMAT HOUR FORMAT - * @{ - */ -#define LL_RTC_HOURFORMAT_24HOUR 0x00000000U /*!< 24 hour/day format */ -#define LL_RTC_HOURFORMAT_AMPM RTC_CR_FMT /*!< AM/PM hour format */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALARMOUT ALARM OUTPUT - * @{ - */ -#define LL_RTC_ALARMOUT_DISABLE 0x00000000U /*!< Output disabled */ -#define LL_RTC_ALARMOUT_ALMA RTC_CR_OSEL_0 /*!< Alarm A output enabled */ -#define LL_RTC_ALARMOUT_ALMB RTC_CR_OSEL_1 /*!< Alarm B output enabled */ -#define LL_RTC_ALARMOUT_WAKEUP RTC_CR_OSEL /*!< Wakeup output enabled */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALARM_OUTPUTTYPE ALARM OUTPUT TYPE - * @{ - */ -#define LL_RTC_ALARM_OUTPUTTYPE_OPENDRAIN 0x00000000U /*!< RTC_ALARM, when mapped on PC13, is open-drain output */ -#define LL_RTC_ALARM_OUTPUTTYPE_PUSHPULL RTC_TAFCR_ALARMOUTTYPE /*!< RTC_ALARM, when mapped on PC13, is push-pull output */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_PIN PIN - * @{ - */ -#define LL_RTC_PIN_PC13 RTC_TAFCR_PC13MODE /*!< PC13 is forced to push-pull output if all RTC alternate functions are disabled */ -#define LL_RTC_PIN_PC14 RTC_TAFCR_PC14MODE /*!< PC14 is forced to push-pull output if LSE is disabled */ -#define LL_RTC_PIN_PC15 RTC_TAFCR_PC15MODE /*!< PC15 is forced to push-pull output if LSE is disabled */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_OUTPUTPOLARITY_PIN OUTPUT POLARITY PIN - * @{ - */ -#define LL_RTC_OUTPUTPOLARITY_PIN_HIGH 0x00000000U /*!< Pin is high when ALRAF/ALRBF/WUTF is asserted (depending on OSEL)*/ -#define LL_RTC_OUTPUTPOLARITY_PIN_LOW RTC_CR_POL /*!< Pin is low when ALRAF/ALRBF/WUTF is asserted (depending on OSEL) */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TIME_FORMAT TIME FORMAT - * @{ - */ -#define LL_RTC_TIME_FORMAT_AM_OR_24 0x00000000U /*!< AM or 24-hour format */ -#define LL_RTC_TIME_FORMAT_PM RTC_TR_PM /*!< PM */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_SHIFT_SECOND SHIFT SECOND - * @{ - */ -#define LL_RTC_SHIFT_SECOND_DELAY 0x00000000U /* Delay (seconds) = SUBFS / (PREDIV_S + 1) */ -#define LL_RTC_SHIFT_SECOND_ADVANCE RTC_SHIFTR_ADD1S /* Advance (seconds) = (1 - (SUBFS / (PREDIV_S + 1))) */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMA_MASK ALARMA MASK - * @{ - */ -#define LL_RTC_ALMA_MASK_NONE 0x00000000U /*!< No masks applied on Alarm A*/ -#define LL_RTC_ALMA_MASK_DATEWEEKDAY RTC_ALRMAR_MSK4 /*!< Date/day do not care in Alarm A comparison */ -#define LL_RTC_ALMA_MASK_HOURS RTC_ALRMAR_MSK3 /*!< Hours do not care in Alarm A comparison */ -#define LL_RTC_ALMA_MASK_MINUTES RTC_ALRMAR_MSK2 /*!< Minutes do not care in Alarm A comparison */ -#define LL_RTC_ALMA_MASK_SECONDS RTC_ALRMAR_MSK1 /*!< Seconds do not care in Alarm A comparison */ -#define LL_RTC_ALMA_MASK_ALL (RTC_ALRMAR_MSK4 | RTC_ALRMAR_MSK3 | RTC_ALRMAR_MSK2 | RTC_ALRMAR_MSK1) /*!< Masks all */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMA_TIME_FORMAT ALARMA TIME FORMAT - * @{ - */ -#define LL_RTC_ALMA_TIME_FORMAT_AM 0x00000000U /*!< AM or 24-hour format */ -#define LL_RTC_ALMA_TIME_FORMAT_PM RTC_ALRMAR_PM /*!< PM */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMB_MASK ALARMB MASK - * @{ - */ -#define LL_RTC_ALMB_MASK_NONE 0x00000000U /*!< No masks applied on Alarm B*/ -#define LL_RTC_ALMB_MASK_DATEWEEKDAY RTC_ALRMBR_MSK4 /*!< Date/day do not care in Alarm B comparison */ -#define LL_RTC_ALMB_MASK_HOURS RTC_ALRMBR_MSK3 /*!< Hours do not care in Alarm B comparison */ -#define LL_RTC_ALMB_MASK_MINUTES RTC_ALRMBR_MSK2 /*!< Minutes do not care in Alarm B comparison */ -#define LL_RTC_ALMB_MASK_SECONDS RTC_ALRMBR_MSK1 /*!< Seconds do not care in Alarm B comparison */ -#define LL_RTC_ALMB_MASK_ALL (RTC_ALRMBR_MSK4 | RTC_ALRMBR_MSK3 | RTC_ALRMBR_MSK2 | RTC_ALRMBR_MSK1) /*!< Masks all */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMB_TIME_FORMAT ALARMB TIME FORMAT - * @{ - */ -#define LL_RTC_ALMB_TIME_FORMAT_AM 0x00000000U /*!< AM or 24-hour format */ -#define LL_RTC_ALMB_TIME_FORMAT_PM RTC_ALRMBR_PM /*!< PM */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TIMESTAMP_EDGE TIMESTAMP EDGE - * @{ - */ -#define LL_RTC_TIMESTAMP_EDGE_RISING 0x00000000U /*!< RTC_TS input rising edge generates a time-stamp event */ -#define LL_RTC_TIMESTAMP_EDGE_FALLING RTC_CR_TSEDGE /*!< RTC_TS input falling edge generates a time-stamp even */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TS_TIME_FORMAT TIMESTAMP TIME FORMAT - * @{ - */ -#define LL_RTC_TS_TIME_FORMAT_AM 0x00000000U /*!< AM or 24-hour format */ -#define LL_RTC_TS_TIME_FORMAT_PM RTC_TSTR_PM /*!< PM */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TAMPER TAMPER - * @{ - */ -#define LL_RTC_TAMPER_1 RTC_TAFCR_TAMP1E /*!< RTC_TAMP1 input detection */ -#if defined(RTC_TAMPER2_SUPPORT) -#define LL_RTC_TAMPER_2 RTC_TAFCR_TAMP2E /*!< RTC_TAMP2 input detection */ -#endif /* RTC_TAMPER2_SUPPORT */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TAMPER_MASK TAMPER MASK - * @{ - */ -#define LL_RTC_TAMPER_MASK_TAMPER1 RTC_TAFCR_TAMP1MF /*!< Tamper 1 event generates a trigger event. TAMP1F is masked and internally cleared by hardware.The backup registers are not erased */ -#if defined(RTC_TAMPER2_SUPPORT) -#define LL_RTC_TAMPER_MASK_TAMPER2 RTC_TAFCR_TAMP2MF /*!< Tamper 2 event generates a trigger event. TAMP2F is masked and internally cleared by hardware. The backup registers are not erased. */ -#endif /* RTC_TAMPER2_SUPPORT */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TAMPER_NOERASE TAMPER NO ERASE - * @{ - */ -#define LL_RTC_TAMPER_NOERASE_TAMPER1 RTC_TAFCR_TAMP1NOERASE /*!< Tamper 1 event does not erase the backup registers. */ -#if defined(RTC_TAMPER2_SUPPORT) -#define LL_RTC_TAMPER_NOERASE_TAMPER2 RTC_TAFCR_TAMP2NOERASE /*!< Tamper 2 event does not erase the backup registers. */ -#endif /* RTC_TAMPER2_SUPPORT */ -/** - * @} - */ - -#if defined(RTC_TAFCR_TAMPPRCH) -/** @defgroup RTC_LL_EC_TAMPER_DURATION TAMPER DURATION - * @{ - */ -#define LL_RTC_TAMPER_DURATION_1RTCCLK 0x00000000U /*!< Tamper pins are pre-charged before sampling during 1 RTCCLK cycle */ -#define LL_RTC_TAMPER_DURATION_2RTCCLK RTC_TAFCR_TAMPPRCH_0 /*!< Tamper pins are pre-charged before sampling during 2 RTCCLK cycles */ -#define LL_RTC_TAMPER_DURATION_4RTCCLK RTC_TAFCR_TAMPPRCH_1 /*!< Tamper pins are pre-charged before sampling during 4 RTCCLK cycles */ -#define LL_RTC_TAMPER_DURATION_8RTCCLK RTC_TAFCR_TAMPPRCH /*!< Tamper pins are pre-charged before sampling during 8 RTCCLK cycles */ -/** - * @} - */ -#endif /* RTC_TAFCR_TAMPPRCH */ - -#if defined(RTC_TAFCR_TAMPFLT) -/** @defgroup RTC_LL_EC_TAMPER_FILTER TAMPER FILTER - * @{ - */ -#define LL_RTC_TAMPER_FILTER_DISABLE 0x00000000U /*!< Tamper filter is disabled */ -#define LL_RTC_TAMPER_FILTER_2SAMPLE RTC_TAFCR_TAMPFLT_0 /*!< Tamper is activated after 2 consecutive samples at the active level */ -#define LL_RTC_TAMPER_FILTER_4SAMPLE RTC_TAFCR_TAMPFLT_1 /*!< Tamper is activated after 4 consecutive samples at the active level */ -#define LL_RTC_TAMPER_FILTER_8SAMPLE RTC_TAFCR_TAMPFLT /*!< Tamper is activated after 8 consecutive samples at the active level. */ -/** - * @} - */ -#endif /* RTC_TAFCR_TAMPFLT */ - -#if defined(RTC_TAFCR_TAMPFREQ) -/** @defgroup RTC_LL_EC_TAMPER_SAMPLFREQDIV TAMPER SAMPLING FREQUENCY DIVIDER - * @{ - */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_32768 0x00000000U /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 32768 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_16384 RTC_TAFCR_TAMPFREQ_0 /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 16384 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_8192 RTC_TAFCR_TAMPFREQ_1 /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 8192 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_4096 (RTC_TAFCR_TAMPFREQ_1 | RTC_TAFCR_TAMPFREQ_0) /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 4096 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_2048 RTC_TAFCR_TAMPFREQ_2 /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 2048 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_1024 (RTC_TAFCR_TAMPFREQ_2 | RTC_TAFCR_TAMPFREQ_0) /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 1024 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_512 (RTC_TAFCR_TAMPFREQ_2 | RTC_TAFCR_TAMPFREQ_1) /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 512 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_256 RTC_TAFCR_TAMPFREQ /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 256 */ -/** - * @} - */ -#endif /* RTC_TAFCR_TAMPFREQ */ - -/** @defgroup RTC_LL_EC_TAMPER_ACTIVELEVEL TAMPER ACTIVE LEVEL - * @{ - */ -#define LL_RTC_TAMPER_ACTIVELEVEL_TAMP1 RTC_TAFCR_TAMP1TRG /*!< RTC_TAMP1 input falling edge (if TAMPFLT = 00) or staying high (if TAMPFLT != 00) triggers a tamper detection event*/ -#if defined(RTC_TAMPER2_SUPPORT) -#define LL_RTC_TAMPER_ACTIVELEVEL_TAMP2 RTC_TAFCR_TAMP2TRG /*!< RTC_TAMP2 input falling edge (if TAMPFLT = 00) or staying high (if TAMPFLT != 00) triggers a tamper detection event*/ -#endif /* RTC_TAMPER2_SUPPORT */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_WAKEUPCLOCK_DIV WAKEUP CLOCK DIV - * @{ - */ -#define LL_RTC_WAKEUPCLOCK_DIV_16 0x00000000U /*!< RTC/16 clock is selected */ -#define LL_RTC_WAKEUPCLOCK_DIV_8 (RTC_CR_WUCKSEL_0) /*!< RTC/8 clock is selected */ -#define LL_RTC_WAKEUPCLOCK_DIV_4 (RTC_CR_WUCKSEL_1) /*!< RTC/4 clock is selected */ -#define LL_RTC_WAKEUPCLOCK_DIV_2 (RTC_CR_WUCKSEL_1 | RTC_CR_WUCKSEL_0) /*!< RTC/2 clock is selected */ -#define LL_RTC_WAKEUPCLOCK_CKSPRE (RTC_CR_WUCKSEL_2) /*!< ck_spre (usually 1 Hz) clock is selected */ -#define LL_RTC_WAKEUPCLOCK_CKSPRE_WUT (RTC_CR_WUCKSEL_2 | RTC_CR_WUCKSEL_1) /*!< ck_spre (usually 1 Hz) clock is selected and 2exp16 is added to the WUT counter value*/ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_BKP BACKUP - * @{ - */ -#define LL_RTC_BKP_DR0 0x00000000U -#define LL_RTC_BKP_DR1 0x00000001U -#define LL_RTC_BKP_DR2 0x00000002U -#define LL_RTC_BKP_DR3 0x00000003U -#define LL_RTC_BKP_DR4 0x00000004U -#if RTC_BKP_NUMBER > 5 -#define LL_RTC_BKP_DR5 0x00000005U -#define LL_RTC_BKP_DR6 0x00000006U -#define LL_RTC_BKP_DR7 0x00000007U -#define LL_RTC_BKP_DR8 0x00000008U -#define LL_RTC_BKP_DR9 0x00000009U -#define LL_RTC_BKP_DR10 0x0000000AU -#define LL_RTC_BKP_DR11 0x0000000BU -#define LL_RTC_BKP_DR12 0x0000000CU -#define LL_RTC_BKP_DR13 0x0000000DU -#define LL_RTC_BKP_DR14 0x0000000EU -#define LL_RTC_BKP_DR15 0x0000000FU -#endif /* RTC_BKP_NUMBER > 5 */ - -#if RTC_BKP_NUMBER > 16 -#define LL_RTC_BKP_DR16 0x00000010U -#define LL_RTC_BKP_DR17 0x00000011U -#define LL_RTC_BKP_DR18 0x00000012U -#define LL_RTC_BKP_DR19 0x00000013U -#endif /* RTC_BKP_NUMBER > 16 */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_CALIB_OUTPUT Calibration output - * @{ - */ -#define LL_RTC_CALIB_OUTPUT_NONE 0x00000000U /*!< Calibration output disabled */ -#define LL_RTC_CALIB_OUTPUT_1HZ (RTC_CR_COE | RTC_CR_COSEL) /*!< Calibration output is 1 Hz */ -#define LL_RTC_CALIB_OUTPUT_512HZ (RTC_CR_COE) /*!< Calibration output is 512 Hz */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_CALIB_SIGN Coarse digital calibration sign - * @{ - */ -#define LL_RTC_CALIB_SIGN_POSITIVE 0x00000000U /*!< Positive calibration: calendar update frequency is increased */ -#define LL_RTC_CALIB_SIGN_NEGATIVE RTC_CALIBR_DCS /*!< Negative calibration: calendar update frequency is decreased */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_CALIB_INSERTPULSE Calibration pulse insertion - * @{ - */ -#define LL_RTC_CALIB_INSERTPULSE_NONE 0x00000000U /*!< No RTCCLK pulses are added */ -#define LL_RTC_CALIB_INSERTPULSE_SET RTC_CALR_CALP /*!< One RTCCLK pulse is effectively inserted every 2exp11 pulses (frequency increased by 488.5 ppm) */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_CALIB_PERIOD Calibration period - * @{ - */ -#define LL_RTC_CALIB_PERIOD_32SEC 0x00000000U /*!< Use a 32-second calibration cycle period */ -#define LL_RTC_CALIB_PERIOD_16SEC RTC_CALR_CALW16 /*!< Use a 16-second calibration cycle period */ -#define LL_RTC_CALIB_PERIOD_8SEC RTC_CALR_CALW8 /*!< Use a 8-second calibration cycle period */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TSINSEL TIMESTAMP mapping - * @{ - */ -#define LL_RTC_TimeStampPin_Default 0x00000000U /*!< Use RTC_AF1 as TIMESTAMP */ -#if defined(RTC_AF2_SUPPORT) -#define LL_RTC_TimeStampPin_Pos1 RTC_TAFCR_TSINSEL /*!< Use RTC_AF2 as TIMESTAMP */ -#endif -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TAMP1INSEL TAMPER1 mapping - * @{ - */ -#define LL_RTC_TamperPin_Default 0x00000000U /*!< Use RTC_AF1 as TAMPER1 */ -#if defined(RTC_AF2_SUPPORT) -#define LL_RTC_TamperPin_Pos1 RTC_TAFCR_TAMP1INSEL /*!< Use RTC_AF2 as TAMPER1 */ -#endif -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RTC_LL_Exported_Macros RTC Exported Macros - * @{ - */ - -/** @defgroup RTC_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in RTC register - * @param __INSTANCE__ RTC Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_RTC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in RTC register - * @param __INSTANCE__ RTC Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_RTC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup RTC_LL_EM_Convert Convert helper Macros - * @{ - */ - -/** - * @brief Helper macro to convert a value from 2 digit decimal format to BCD format - * @param __VALUE__ Byte to be converted - * @retval Converted byte - */ -#define __LL_RTC_CONVERT_BIN2BCD(__VALUE__) (uint8_t)((((__VALUE__) / 10U) << 4U) | ((__VALUE__) % 10U)) - -/** - * @brief Helper macro to convert a value from BCD format to 2 digit decimal format - * @param __VALUE__ BCD value to be converted - * @retval Converted byte - */ -#define __LL_RTC_CONVERT_BCD2BIN(__VALUE__) (uint8_t)(((uint8_t)((__VALUE__) & (uint8_t)0xF0U) >> (uint8_t)0x4U) * 10U + ((__VALUE__) & (uint8_t)0x0FU)) - -/** - * @} - */ - -/** @defgroup RTC_LL_EM_Date Date helper Macros - * @{ - */ - -/** - * @brief Helper macro to retrieve weekday. - * @param __RTC_DATE__ Date returned by @ref LL_RTC_DATE_Get function. - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -#define __LL_RTC_GET_WEEKDAY(__RTC_DATE__) (((__RTC_DATE__) >> RTC_OFFSET_WEEKDAY) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve Year in BCD format - * @param __RTC_DATE__ Value returned by @ref LL_RTC_DATE_Get - * @retval Year in BCD format (0x00 . . . 0x99) - */ -#define __LL_RTC_GET_YEAR(__RTC_DATE__) ((__RTC_DATE__) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve Month in BCD format - * @param __RTC_DATE__ Value returned by @ref LL_RTC_DATE_Get - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - */ -#define __LL_RTC_GET_MONTH(__RTC_DATE__) (((__RTC_DATE__) >>RTC_OFFSET_MONTH) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve Day in BCD format - * @param __RTC_DATE__ Value returned by @ref LL_RTC_DATE_Get - * @retval Day in BCD format (0x01 . . . 0x31) - */ -#define __LL_RTC_GET_DAY(__RTC_DATE__) (((__RTC_DATE__) >>RTC_OFFSET_DAY) & 0x000000FFU) - -/** - * @} - */ - -/** @defgroup RTC_LL_EM_Time Time helper Macros - * @{ - */ - -/** - * @brief Helper macro to retrieve hour in BCD format - * @param __RTC_TIME__ RTC time returned by @ref LL_RTC_TIME_Get function - * @retval Hours in BCD format (0x01. . .0x12 or between Min_Data=0x00 and Max_Data=0x23) - */ -#define __LL_RTC_GET_HOUR(__RTC_TIME__) (((__RTC_TIME__) >> RTC_OFFSET_HOUR) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve minute in BCD format - * @param __RTC_TIME__ RTC time returned by @ref LL_RTC_TIME_Get function - * @retval Minutes in BCD format (0x00. . .0x59) - */ -#define __LL_RTC_GET_MINUTE(__RTC_TIME__) (((__RTC_TIME__) >> RTC_OFFSET_MINUTE) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve second in BCD format - * @param __RTC_TIME__ RTC time returned by @ref LL_RTC_TIME_Get function - * @retval Seconds in format (0x00. . .0x59) - */ -#define __LL_RTC_GET_SECOND(__RTC_TIME__) ((__RTC_TIME__) & 0x000000FFU) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RTC_LL_Exported_Functions RTC Exported Functions - * @{ - */ - -/** @defgroup RTC_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Set Hours format (24 hour/day or AM/PM hour format) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR FMT LL_RTC_SetHourFormat - * @param RTCx RTC Instance - * @param HourFormat This parameter can be one of the following values: - * @arg @ref LL_RTC_HOURFORMAT_24HOUR - * @arg @ref LL_RTC_HOURFORMAT_AMPM - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetHourFormat(RTC_TypeDef *RTCx, uint32_t HourFormat) -{ - MODIFY_REG(RTCx->CR, RTC_CR_FMT, HourFormat); -} - -/** - * @brief Get Hours format (24 hour/day or AM/PM hour format) - * @rmtoll CR FMT LL_RTC_GetHourFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_HOURFORMAT_24HOUR - * @arg @ref LL_RTC_HOURFORMAT_AMPM - */ -__STATIC_INLINE uint32_t LL_RTC_GetHourFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_FMT)); -} - -/** - * @brief Select the flag to be routed to RTC_ALARM output - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR OSEL LL_RTC_SetAlarmOutEvent - * @param RTCx RTC Instance - * @param AlarmOutput This parameter can be one of the following values: - * @arg @ref LL_RTC_ALARMOUT_DISABLE - * @arg @ref LL_RTC_ALARMOUT_ALMA - * @arg @ref LL_RTC_ALARMOUT_ALMB - * @arg @ref LL_RTC_ALARMOUT_WAKEUP - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetAlarmOutEvent(RTC_TypeDef *RTCx, uint32_t AlarmOutput) -{ - MODIFY_REG(RTCx->CR, RTC_CR_OSEL, AlarmOutput); -} - -/** - * @brief Get the flag to be routed to RTC_ALARM output - * @rmtoll CR OSEL LL_RTC_GetAlarmOutEvent - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_ALARMOUT_DISABLE - * @arg @ref LL_RTC_ALARMOUT_ALMA - * @arg @ref LL_RTC_ALARMOUT_ALMB - * @arg @ref LL_RTC_ALARMOUT_WAKEUP - */ -__STATIC_INLINE uint32_t LL_RTC_GetAlarmOutEvent(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_OSEL)); -} - -/** - * @brief Set RTC_ALARM output type (ALARM in push-pull or open-drain output) - * @note Used only when RTC_ALARM is mapped on PC13 - * @note If all RTC alternate functions are disabled and PC13MODE = 1, PC13VALUE configures the - * PC13 output data - * @rmtoll TAFCR ALARMOUTTYPE LL_RTC_SetAlarmOutputType - * @param RTCx RTC Instance - * @param Output This parameter can be one of the following values: - * @arg @ref LL_RTC_ALARM_OUTPUTTYPE_OPENDRAIN - * @arg @ref LL_RTC_ALARM_OUTPUTTYPE_PUSHPULL - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetAlarmOutputType(RTC_TypeDef *RTCx, uint32_t Output) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_ALARMOUTTYPE, Output); -} - -/** - * @brief Get RTC_ALARM output type (ALARM in push-pull or open-drain output) - * @note used only when RTC_ALARM is mapped on PC13 - * @note If all RTC alternate functions are disabled and PC13MODE = 1, PC13VALUE configures the - * PC13 output data - * @rmtoll TAFCR ALARMOUTTYPE LL_RTC_GetAlarmOutputType - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_ALARM_OUTPUTTYPE_OPENDRAIN - * @arg @ref LL_RTC_ALARM_OUTPUTTYPE_PUSHPULL - */ -__STATIC_INLINE uint32_t LL_RTC_GetAlarmOutputType(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_ALARMOUTTYPE)); -} - -/** - * @brief Enable push-pull output on PC13, PC14 and/or PC15 - * @note PC13 forced to push-pull output if all RTC alternate functions are disabled - * @note PC14 and PC15 forced to push-pull output if LSE is disabled - * @rmtoll TAFCR PC13MODE LL_RTC_EnablePushPullMode\n - * @rmtoll TAFCR PC14MODE LL_RTC_EnablePushPullMode\n - * @rmtoll TAFCR PC15MODE LL_RTC_EnablePushPullMode - * @param RTCx RTC Instance - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_PIN_PC13 - * @arg @ref LL_RTC_PIN_PC14 - * @arg @ref LL_RTC_PIN_PC15 - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnablePushPullMode(RTC_TypeDef *RTCx, uint32_t PinMask) -{ - SET_BIT(RTCx->TAFCR, PinMask); -} - -/** - * @brief Disable push-pull output on PC13, PC14 and/or PC15 - * @note PC13, PC14 and/or PC15 are controlled by the GPIO configuration registers. - * Consequently PC13, PC14 and/or PC15 are floating in Standby mode. - * @rmtoll TAFCR PC13MODE LL_RTC_DisablePushPullMode\n - * TAFCR PC14MODE LL_RTC_DisablePushPullMode\n - * TAFCR PC15MODE LL_RTC_DisablePushPullMode - * @param RTCx RTC Instance - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_PIN_PC13 - * @arg @ref LL_RTC_PIN_PC14 - * @arg @ref LL_RTC_PIN_PC15 - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisablePushPullMode(RTC_TypeDef* RTCx, uint32_t PinMask) -{ - CLEAR_BIT(RTCx->TAFCR, PinMask); -} - -/** - * @brief Set PC14 and/or PC15 to high level. - * @note Output data configuration is possible if the LSE is disabled and PushPull output is enabled (through @ref LL_RTC_EnablePushPullMode) - * @rmtoll TAFCR PC14VALUE LL_RTC_SetOutputPin\n - * TAFCR PC15VALUE LL_RTC_SetOutputPin - * @param RTCx RTC Instance - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_PIN_PC14 - * @arg @ref LL_RTC_PIN_PC15 - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetOutputPin(RTC_TypeDef* RTCx, uint32_t PinMask) -{ - SET_BIT(RTCx->TAFCR, (PinMask >> 1)); -} - -/** - * @brief Set PC14 and/or PC15 to low level. - * @note Output data configuration is possible if the LSE is disabled and PushPull output is enabled (through @ref LL_RTC_EnablePushPullMode) - * @rmtoll TAFCR PC14VALUE LL_RTC_ResetOutputPin\n - * TAFCR PC15VALUE LL_RTC_ResetOutputPin - * @param RTCx RTC Instance - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_PIN_PC14 - * @arg @ref LL_RTC_PIN_PC15 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ResetOutputPin(RTC_TypeDef* RTCx, uint32_t PinMask) -{ - CLEAR_BIT(RTCx->TAFCR, (PinMask >> 1)); -} - -/** - * @brief Enable initialization mode - * @note Initialization mode is used to program time and date register (RTC_TR and RTC_DR) - * and prescaler register (RTC_PRER). - * Counters are stopped and start counting from the new value when INIT is reset. - * @rmtoll ISR INIT LL_RTC_EnableInitMode - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableInitMode(RTC_TypeDef *RTCx) -{ - /* Set the Initialization mode */ - WRITE_REG(RTCx->ISR, RTC_INIT_MASK); -} - -/** - * @brief Disable initialization mode (Free running mode) - * @rmtoll ISR INIT LL_RTC_DisableInitMode - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableInitMode(RTC_TypeDef *RTCx) -{ - /* Exit Initialization mode */ - WRITE_REG(RTCx->ISR, (uint32_t)~RTC_ISR_INIT); -} - -/** - * @brief Set Output polarity (pin is low when ALRAF/ALRBF/WUTF is asserted) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR POL LL_RTC_SetOutputPolarity - * @param RTCx RTC Instance - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_RTC_OUTPUTPOLARITY_PIN_HIGH - * @arg @ref LL_RTC_OUTPUTPOLARITY_PIN_LOW - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetOutputPolarity(RTC_TypeDef *RTCx, uint32_t Polarity) -{ - MODIFY_REG(RTCx->CR, RTC_CR_POL, Polarity); -} - -/** - * @brief Get Output polarity - * @rmtoll CR POL LL_RTC_GetOutputPolarity - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_OUTPUTPOLARITY_PIN_HIGH - * @arg @ref LL_RTC_OUTPUTPOLARITY_PIN_LOW - */ -__STATIC_INLINE uint32_t LL_RTC_GetOutputPolarity(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_POL)); -} - -/** - * @brief Enable Bypass the shadow registers - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR BYPSHAD LL_RTC_EnableShadowRegBypass - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableShadowRegBypass(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_BYPSHAD); -} - -/** - * @brief Disable Bypass the shadow registers - * @rmtoll CR BYPSHAD LL_RTC_DisableShadowRegBypass - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableShadowRegBypass(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_BYPSHAD); -} - -/** - * @brief Check if Shadow registers bypass is enabled or not. - * @rmtoll CR BYPSHAD LL_RTC_IsShadowRegBypassEnabled - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsShadowRegBypassEnabled(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_BYPSHAD) == (RTC_CR_BYPSHAD)); -} - -/** - * @brief Enable RTC_REFIN reference clock detection (50 or 60 Hz) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR REFCKON LL_RTC_EnableRefClock - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableRefClock(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_REFCKON); -} - -/** - * @brief Disable RTC_REFIN reference clock detection (50 or 60 Hz) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR REFCKON LL_RTC_DisableRefClock - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableRefClock(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_REFCKON); -} - -/** - * @brief Set Asynchronous prescaler factor - * @rmtoll PRER PREDIV_A LL_RTC_SetAsynchPrescaler - * @param RTCx RTC Instance - * @param AsynchPrescaler Value between Min_Data = 0 and Max_Data = 0x7F - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetAsynchPrescaler(RTC_TypeDef *RTCx, uint32_t AsynchPrescaler) -{ - MODIFY_REG(RTCx->PRER, RTC_PRER_PREDIV_A, AsynchPrescaler << RTC_PRER_PREDIV_A_Pos); -} - -/** - * @brief Set Synchronous prescaler factor - * @rmtoll PRER PREDIV_S LL_RTC_SetSynchPrescaler - * @param RTCx RTC Instance - * @param SynchPrescaler Value between Min_Data = 0 and Max_Data = 0x7FFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetSynchPrescaler(RTC_TypeDef *RTCx, uint32_t SynchPrescaler) -{ - MODIFY_REG(RTCx->PRER, RTC_PRER_PREDIV_S, SynchPrescaler); -} - -/** - * @brief Get Asynchronous prescaler factor - * @rmtoll PRER PREDIV_A LL_RTC_GetAsynchPrescaler - * @param RTCx RTC Instance - * @retval Value between Min_Data = 0 and Max_Data = 0x7F - */ -__STATIC_INLINE uint32_t LL_RTC_GetAsynchPrescaler(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->PRER, RTC_PRER_PREDIV_A) >> RTC_PRER_PREDIV_A_Pos); -} - -/** - * @brief Get Synchronous prescaler factor - * @rmtoll PRER PREDIV_S LL_RTC_GetSynchPrescaler - * @param RTCx RTC Instance - * @retval Value between Min_Data = 0 and Max_Data = 0x7FFF - */ -__STATIC_INLINE uint32_t LL_RTC_GetSynchPrescaler(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->PRER, RTC_PRER_PREDIV_S)); -} - -/** - * @brief Enable the write protection for RTC registers. - * @rmtoll WPR KEY LL_RTC_EnableWriteProtection - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableWriteProtection(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->WPR, RTC_WRITE_PROTECTION_DISABLE); -} - -/** - * @brief Disable the write protection for RTC registers. - * @rmtoll WPR KEY LL_RTC_DisableWriteProtection - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableWriteProtection(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->WPR, RTC_WRITE_PROTECTION_ENABLE_1); - WRITE_REG(RTCx->WPR, RTC_WRITE_PROTECTION_ENABLE_2); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Time Time - * @{ - */ - -/** - * @brief Set time format (AM/24-hour or PM notation) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll TR PM LL_RTC_TIME_SetFormat - * @param RTCx RTC Instance - * @param TimeFormat This parameter can be one of the following values: - * @arg @ref LL_RTC_TIME_FORMAT_AM_OR_24 - * @arg @ref LL_RTC_TIME_FORMAT_PM - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_SetFormat(RTC_TypeDef *RTCx, uint32_t TimeFormat) -{ - MODIFY_REG(RTCx->TR, RTC_TR_PM, TimeFormat); -} - -/** - * @brief Get time format (AM or PM notation) - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @rmtoll TR PM LL_RTC_TIME_GetFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TIME_FORMAT_AM_OR_24 - * @arg @ref LL_RTC_TIME_FORMAT_PM - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TR, RTC_TR_PM)); -} - -/** - * @brief Set Hours in BCD format - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert hour from binary to BCD format - * @rmtoll TR HT LL_RTC_TIME_SetHour\n - * TR HU LL_RTC_TIME_SetHour - * @param RTCx RTC Instance - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_SetHour(RTC_TypeDef *RTCx, uint32_t Hours) -{ - MODIFY_REG(RTCx->TR, (RTC_TR_HT | RTC_TR_HU), - (((Hours & 0xF0U) << (RTC_TR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_TR_HU_Pos))); -} - -/** - * @brief Get Hours in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert hour from BCD to - * Binary format - * @rmtoll TR HT LL_RTC_TIME_GetHour\n - * TR HU LL_RTC_TIME_GetHour - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetHour(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->TR, (RTC_TR_HT | RTC_TR_HU))) >> RTC_TR_HU_Pos); -} - -/** - * @brief Set Minutes in BCD format - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Minutes from binary to BCD format - * @rmtoll TR MNT LL_RTC_TIME_SetMinute\n - * TR MNU LL_RTC_TIME_SetMinute - * @param RTCx RTC Instance - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_SetMinute(RTC_TypeDef *RTCx, uint32_t Minutes) -{ - MODIFY_REG(RTCx->TR, (RTC_TR_MNT | RTC_TR_MNU), - (((Minutes & 0xF0U) << (RTC_TR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_TR_MNU_Pos))); -} - -/** - * @brief Get Minutes in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert minute from BCD - * to Binary format - * @rmtoll TR MNT LL_RTC_TIME_GetMinute\n - * TR MNU LL_RTC_TIME_GetMinute - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetMinute(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TR, (RTC_TR_MNT | RTC_TR_MNU))>> RTC_TR_MNU_Pos); -} - -/** - * @brief Set Seconds in BCD format - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Seconds from binary to BCD format - * @rmtoll TR ST LL_RTC_TIME_SetSecond\n - * TR SU LL_RTC_TIME_SetSecond - * @param RTCx RTC Instance - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_SetSecond(RTC_TypeDef *RTCx, uint32_t Seconds) -{ - MODIFY_REG(RTCx->TR, (RTC_TR_ST | RTC_TR_SU), - (((Seconds & 0xF0U) << (RTC_TR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_TR_SU_Pos))); -} - -/** - * @brief Get Seconds in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Seconds from BCD - * to Binary format - * @rmtoll TR ST LL_RTC_TIME_GetSecond\n - * TR SU LL_RTC_TIME_GetSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TR, (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); -} - -/** - * @brief Set time (hour, minute and second) in BCD format - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @note TimeFormat and Hours should follow the same format - * @rmtoll TR PM LL_RTC_TIME_Config\n - * TR HT LL_RTC_TIME_Config\n - * TR HU LL_RTC_TIME_Config\n - * TR MNT LL_RTC_TIME_Config\n - * TR MNU LL_RTC_TIME_Config\n - * TR ST LL_RTC_TIME_Config\n - * TR SU LL_RTC_TIME_Config - * @param RTCx RTC Instance - * @param Format12_24 This parameter can be one of the following values: - * @arg @ref LL_RTC_TIME_FORMAT_AM_OR_24 - * @arg @ref LL_RTC_TIME_FORMAT_PM - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_Config(RTC_TypeDef *RTCx, uint32_t Format12_24, uint32_t Hours, uint32_t Minutes, uint32_t Seconds) -{ - register uint32_t temp = 0U; - - temp = Format12_24 | \ - (((Hours & 0xF0U) << (RTC_TR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_TR_HU_Pos)) | \ - (((Minutes & 0xF0U) << (RTC_TR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_TR_MNU_Pos)) | \ - (((Seconds & 0xF0U) << (RTC_TR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_TR_SU_Pos)); - MODIFY_REG(RTCx->TR, (RTC_TR_PM | RTC_TR_HT | RTC_TR_HU | RTC_TR_MNT | RTC_TR_MNU | RTC_TR_ST | RTC_TR_SU), temp); -} - -/** - * @brief Get time (hour, minute and second) in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @note helper macros __LL_RTC_GET_HOUR, __LL_RTC_GET_MINUTE and __LL_RTC_GET_SECOND - * are available to get independently each parameter. - * @rmtoll TR HT LL_RTC_TIME_Get\n - * TR HU LL_RTC_TIME_Get\n - * TR MNT LL_RTC_TIME_Get\n - * TR MNU LL_RTC_TIME_Get\n - * TR ST LL_RTC_TIME_Get\n - * TR SU LL_RTC_TIME_Get - * @param RTCx RTC Instance - * @retval Combination of hours, minutes and seconds (Format: 0x00HHMMSS). - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_Get(RTC_TypeDef *RTCx) -{ - register uint32_t temp = 0U; - - temp = READ_BIT(RTCx->TR, (RTC_TR_HT | RTC_TR_HU | RTC_TR_MNT | RTC_TR_MNU | RTC_TR_ST | RTC_TR_SU)); - return (uint32_t)((((((temp & RTC_TR_HT) >> RTC_TR_HT_Pos) << 4U) | ((temp & RTC_TR_HU) >> RTC_TR_HU_Pos)) << RTC_OFFSET_HOUR) | \ - (((((temp & RTC_TR_MNT) >> RTC_TR_MNT_Pos) << 4U) | ((temp & RTC_TR_MNU) >> RTC_TR_MNU_Pos)) << RTC_OFFSET_MINUTE) | \ - ((((temp & RTC_TR_ST) >> RTC_TR_ST_Pos) << 4U) | ((temp & RTC_TR_SU) >> RTC_TR_SU_Pos))); -} - -/** - * @brief Memorize whether the daylight saving time change has been performed - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR BKP LL_RTC_TIME_EnableDayLightStore - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_EnableDayLightStore(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_BKP); -} - -/** - * @brief Disable memorization whether the daylight saving time change has been performed. - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR BKP LL_RTC_TIME_DisableDayLightStore - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_DisableDayLightStore(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_BKP); -} - -/** - * @brief Check if RTC Day Light Saving stored operation has been enabled or not - * @rmtoll CR BKP LL_RTC_TIME_IsDayLightStoreEnabled - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_IsDayLightStoreEnabled(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_BKP) == (RTC_CR_BKP)); -} - -/** - * @brief Subtract 1 hour (winter time change) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR SUB1H LL_RTC_TIME_DecHour - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_DecHour(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_SUB1H); -} - -/** - * @brief Add 1 hour (summer time change) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ADD1H LL_RTC_TIME_IncHour - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_IncHour(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ADD1H); -} - -/** - * @brief Get Sub second value in the synchronous prescaler counter. - * @note You can use both SubSeconds value and SecondFraction (PREDIV_S through - * LL_RTC_GetSynchPrescaler function) terms returned to convert Calendar - * SubSeconds value in second fraction ratio with time unit following - * generic formula: - * ==> Seconds fraction ratio * time_unit= [(SecondFraction-SubSeconds)/(SecondFraction+1)] * time_unit - * This conversion can be performed only if no shift operation is pending - * (ie. SHFP=0) when PREDIV_S >= SS. - * @rmtoll SSR SS LL_RTC_TIME_GetSubSecond - * @param RTCx RTC Instance - * @retval Sub second value (number between 0 and 65535) - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetSubSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->SSR, RTC_SSR_SS)); -} - -/** - * @brief Synchronize to a remote clock with a high degree of precision. - * @note This operation effectively subtracts from (delays) or advance the clock of a fraction of a second. - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note When REFCKON is set, firmware must not write to Shift control register. - * @rmtoll SHIFTR ADD1S LL_RTC_TIME_Synchronize\n - * SHIFTR SUBFS LL_RTC_TIME_Synchronize - * @param RTCx RTC Instance - * @param ShiftSecond This parameter can be one of the following values: - * @arg @ref LL_RTC_SHIFT_SECOND_DELAY - * @arg @ref LL_RTC_SHIFT_SECOND_ADVANCE - * @param Fraction Number of Seconds Fractions (any value from 0 to 0x7FFF) - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_Synchronize(RTC_TypeDef *RTCx, uint32_t ShiftSecond, uint32_t Fraction) -{ - WRITE_REG(RTCx->SHIFTR, ShiftSecond | Fraction); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Date Date - * @{ - */ - -/** - * @brief Set Year in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Year from binary to BCD format - * @rmtoll DR YT LL_RTC_DATE_SetYear\n - * DR YU LL_RTC_DATE_SetYear - * @param RTCx RTC Instance - * @param Year Value between Min_Data=0x00 and Max_Data=0x99 - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_SetYear(RTC_TypeDef *RTCx, uint32_t Year) -{ - MODIFY_REG(RTCx->DR, (RTC_DR_YT | RTC_DR_YU), - (((Year & 0xF0U) << (RTC_DR_YT_Pos - 4U)) | ((Year & 0x0FU) << RTC_DR_YU_Pos))); -} - -/** - * @brief Get Year in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Year from BCD to Binary format - * @rmtoll DR YT LL_RTC_DATE_GetYear\n - * DR YU LL_RTC_DATE_GetYear - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x99 - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_GetYear(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->DR, (RTC_DR_YT | RTC_DR_YU))) >> RTC_DR_YU_Pos); -} - -/** - * @brief Set Week day - * @rmtoll DR WDU LL_RTC_DATE_SetWeekDay - * @param RTCx RTC Instance - * @param WeekDay This parameter can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_SetWeekDay(RTC_TypeDef *RTCx, uint32_t WeekDay) -{ - MODIFY_REG(RTCx->DR, RTC_DR_WDU, WeekDay << RTC_DR_WDU_Pos); -} - -/** - * @brief Get Week day - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @rmtoll DR WDU LL_RTC_DATE_GetWeekDay - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_GetWeekDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->DR, RTC_DR_WDU) >> RTC_DR_WDU_Pos); -} - -/** - * @brief Set Month in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Month from binary to BCD format - * @rmtoll DR MT LL_RTC_DATE_SetMonth\n - * DR MU LL_RTC_DATE_SetMonth - * @param RTCx RTC Instance - * @param Month This parameter can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_SetMonth(RTC_TypeDef *RTCx, uint32_t Month) -{ - MODIFY_REG(RTCx->DR, (RTC_DR_MT | RTC_DR_MU), - (((Month & 0xF0U) << (RTC_DR_MT_Pos - 4U)) | ((Month & 0x0FU) << RTC_DR_MU_Pos))); -} - -/** - * @brief Get Month in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Month from BCD to Binary format - * @rmtoll DR MT LL_RTC_DATE_GetMonth\n - * DR MU LL_RTC_DATE_GetMonth - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_GetMonth(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->DR, (RTC_DR_MT | RTC_DR_MU)))>> RTC_DR_MU_Pos); -} - -/** - * @brief Set Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Day from binary to BCD format - * @rmtoll DR DT LL_RTC_DATE_SetDay\n - * DR DU LL_RTC_DATE_SetDay - * @param RTCx RTC Instance - * @param Day Value between Min_Data=0x01 and Max_Data=0x31 - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_SetDay(RTC_TypeDef *RTCx, uint32_t Day) -{ - MODIFY_REG(RTCx->DR, (RTC_DR_DT | RTC_DR_DU), - (((Day & 0xF0U) << (RTC_DR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_DR_DU_Pos))); -} - -/** - * @brief Get Day in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Day from BCD to Binary format - * @rmtoll DR DT LL_RTC_DATE_GetDay\n - * DR DU LL_RTC_DATE_GetDay - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x31 - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_GetDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->DR, (RTC_DR_DT | RTC_DR_DU))) >> RTC_DR_DU_Pos); -} - -/** - * @brief Set date (WeekDay, Day, Month and Year) in BCD format - * @rmtoll DR WDU LL_RTC_DATE_Config\n - * DR MT LL_RTC_DATE_Config\n - * DR MU LL_RTC_DATE_Config\n - * DR DT LL_RTC_DATE_Config\n - * DR DU LL_RTC_DATE_Config\n - * DR YT LL_RTC_DATE_Config\n - * DR YU LL_RTC_DATE_Config - * @param RTCx RTC Instance - * @param WeekDay This parameter can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - * @param Day Value between Min_Data=0x01 and Max_Data=0x31 - * @param Month This parameter can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - * @param Year Value between Min_Data=0x00 and Max_Data=0x99 - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_Config(RTC_TypeDef *RTCx, uint32_t WeekDay, uint32_t Day, uint32_t Month, uint32_t Year) -{ - register uint32_t temp = 0U; - - temp = (WeekDay << RTC_DR_WDU_Pos) | \ - (((Year & 0xF0U) << (RTC_DR_YT_Pos - 4U)) | ((Year & 0x0FU) << RTC_DR_YU_Pos)) | \ - (((Month & 0xF0U) << (RTC_DR_MT_Pos - 4U)) | ((Month & 0x0FU) << RTC_DR_MU_Pos)) | \ - (((Day & 0xF0U) << (RTC_DR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_DR_DU_Pos)); - - MODIFY_REG(RTCx->DR, (RTC_DR_WDU | RTC_DR_MT | RTC_DR_MU | RTC_DR_DT | RTC_DR_DU | RTC_DR_YT | RTC_DR_YU), temp); -} - -/** - * @brief Get date (WeekDay, Day, Month and Year) in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note helper macros __LL_RTC_GET_WEEKDAY, __LL_RTC_GET_YEAR, __LL_RTC_GET_MONTH, - * and __LL_RTC_GET_DAY are available to get independently each parameter. - * @rmtoll DR WDU LL_RTC_DATE_Get\n - * DR MT LL_RTC_DATE_Get\n - * DR MU LL_RTC_DATE_Get\n - * DR DT LL_RTC_DATE_Get\n - * DR DU LL_RTC_DATE_Get\n - * DR YT LL_RTC_DATE_Get\n - * DR YU LL_RTC_DATE_Get - * @param RTCx RTC Instance - * @retval Combination of WeekDay, Day, Month and Year (Format: 0xWWDDMMYY). - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_Get(RTC_TypeDef *RTCx) -{ - register uint32_t temp = 0U; - - temp = READ_BIT(RTCx->DR, (RTC_DR_WDU | RTC_DR_MT | RTC_DR_MU | RTC_DR_DT | RTC_DR_DU | RTC_DR_YT | RTC_DR_YU)); - return (uint32_t)((((temp & RTC_DR_WDU) >> RTC_DR_WDU_Pos) << RTC_OFFSET_WEEKDAY) | \ - (((((temp & RTC_DR_DT) >> RTC_DR_DT_Pos) << 4U) | ((temp & RTC_DR_DU) >> RTC_DR_DU_Pos)) << RTC_OFFSET_DAY) | \ - (((((temp & RTC_DR_MT) >> RTC_DR_MT_Pos) << 4U) | ((temp & RTC_DR_MU) >> RTC_DR_MU_Pos)) << RTC_OFFSET_MONTH) | \ - ((((temp & RTC_DR_YT) >> RTC_DR_YT_Pos) << 4U) | ((temp & RTC_DR_YU) >> RTC_DR_YU_Pos))); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_ALARMA ALARMA - * @{ - */ - -/** - * @brief Enable Alarm A - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRAE LL_RTC_ALMA_Enable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_Enable(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ALRAE); -} - -/** - * @brief Disable Alarm A - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRAE LL_RTC_ALMA_Disable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_Disable(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_ALRAE); -} - -/** - * @brief Specify the Alarm A masks. - * @rmtoll ALRMAR MSK4 LL_RTC_ALMA_SetMask\n - * ALRMAR MSK3 LL_RTC_ALMA_SetMask\n - * ALRMAR MSK2 LL_RTC_ALMA_SetMask\n - * ALRMAR MSK1 LL_RTC_ALMA_SetMask - * @param RTCx RTC Instance - * @param Mask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_ALMA_MASK_NONE - * @arg @ref LL_RTC_ALMA_MASK_DATEWEEKDAY - * @arg @ref LL_RTC_ALMA_MASK_HOURS - * @arg @ref LL_RTC_ALMA_MASK_MINUTES - * @arg @ref LL_RTC_ALMA_MASK_SECONDS - * @arg @ref LL_RTC_ALMA_MASK_ALL - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetMask(RTC_TypeDef *RTCx, uint32_t Mask) -{ - MODIFY_REG(RTCx->ALRMAR, RTC_ALRMAR_MSK4 | RTC_ALRMAR_MSK3 | RTC_ALRMAR_MSK2 | RTC_ALRMAR_MSK1, Mask); -} - -/** - * @brief Get the Alarm A masks. - * @rmtoll ALRMAR MSK4 LL_RTC_ALMA_GetMask\n - * ALRMAR MSK3 LL_RTC_ALMA_GetMask\n - * ALRMAR MSK2 LL_RTC_ALMA_GetMask\n - * ALRMAR MSK1 LL_RTC_ALMA_GetMask - * @param RTCx RTC Instance - * @retval Returned value can be can be a combination of the following values: - * @arg @ref LL_RTC_ALMA_MASK_NONE - * @arg @ref LL_RTC_ALMA_MASK_DATEWEEKDAY - * @arg @ref LL_RTC_ALMA_MASK_HOURS - * @arg @ref LL_RTC_ALMA_MASK_MINUTES - * @arg @ref LL_RTC_ALMA_MASK_SECONDS - * @arg @ref LL_RTC_ALMA_MASK_ALL - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetMask(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMAR, RTC_ALRMAR_MSK4 | RTC_ALRMAR_MSK3 | RTC_ALRMAR_MSK2 | RTC_ALRMAR_MSK1)); -} - -/** - * @brief Enable AlarmA Week day selection (DU[3:0] represents the week day. DT[1:0] is do not care) - * @rmtoll ALRMAR WDSEL LL_RTC_ALMA_EnableWeekday - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_EnableWeekday(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->ALRMAR, RTC_ALRMAR_WDSEL); -} - -/** - * @brief Disable AlarmA Week day selection (DU[3:0] represents the date ) - * @rmtoll ALRMAR WDSEL LL_RTC_ALMA_DisableWeekday - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_DisableWeekday(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->ALRMAR, RTC_ALRMAR_WDSEL); -} - -/** - * @brief Set ALARM A Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Day from binary to BCD format - * @rmtoll ALRMAR DT LL_RTC_ALMA_SetDay\n - * ALRMAR DU LL_RTC_ALMA_SetDay - * @param RTCx RTC Instance - * @param Day Value between Min_Data=0x01 and Max_Data=0x31 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetDay(RTC_TypeDef *RTCx, uint32_t Day) -{ - MODIFY_REG(RTCx->ALRMAR, (RTC_ALRMAR_DT | RTC_ALRMAR_DU), - (((Day & 0xF0U) << (RTC_ALRMAR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_ALRMAR_DU_Pos))); -} - -/** - * @brief Get ALARM A Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Day from BCD to Binary format - * @rmtoll ALRMAR DT LL_RTC_ALMA_GetDay\n - * ALRMAR DU LL_RTC_ALMA_GetDay - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x31 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMAR, (RTC_ALRMAR_DT | RTC_ALRMAR_DU))) >> RTC_ALRMAR_DU_Pos); -} - -/** - * @brief Set ALARM A Weekday - * @rmtoll ALRMAR DU LL_RTC_ALMA_SetWeekDay - * @param RTCx RTC Instance - * @param WeekDay This parameter can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetWeekDay(RTC_TypeDef *RTCx, uint32_t WeekDay) -{ - MODIFY_REG(RTCx->ALRMAR, RTC_ALRMAR_DU, WeekDay << RTC_ALRMAR_DU_Pos); -} - -/** - * @brief Get ALARM A Weekday - * @rmtoll ALRMAR DU LL_RTC_ALMA_GetWeekDay - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetWeekDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMAR, RTC_ALRMAR_DU) >> RTC_ALRMAR_DU_Pos); -} - -/** - * @brief Set Alarm A time format (AM/24-hour or PM notation) - * @rmtoll ALRMAR PM LL_RTC_ALMA_SetTimeFormat - * @param RTCx RTC Instance - * @param TimeFormat This parameter can be one of the following values: - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_PM - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetTimeFormat(RTC_TypeDef *RTCx, uint32_t TimeFormat) -{ - MODIFY_REG(RTCx->ALRMAR, RTC_ALRMAR_PM, TimeFormat); -} - -/** - * @brief Get Alarm A time format (AM or PM notation) - * @rmtoll ALRMAR PM LL_RTC_ALMA_GetTimeFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_PM - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetTimeFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMAR, RTC_ALRMAR_PM)); -} - -/** - * @brief Set ALARM A Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Hours from binary to BCD format - * @rmtoll ALRMAR HT LL_RTC_ALMA_SetHour\n - * ALRMAR HU LL_RTC_ALMA_SetHour - * @param RTCx RTC Instance - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetHour(RTC_TypeDef *RTCx, uint32_t Hours) -{ - MODIFY_REG(RTCx->ALRMAR, (RTC_ALRMAR_HT | RTC_ALRMAR_HU), - (((Hours & 0xF0U) << (RTC_ALRMAR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_ALRMAR_HU_Pos))); -} - -/** - * @brief Get ALARM A Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Hours from BCD to Binary format - * @rmtoll ALRMAR HT LL_RTC_ALMA_GetHour\n - * ALRMAR HU LL_RTC_ALMA_GetHour - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetHour(RTC_TypeDef *RTCx) -{ - return (uint32_t)(( READ_BIT(RTCx->ALRMAR, (RTC_ALRMAR_HT | RTC_ALRMAR_HU))) >> RTC_ALRMAR_HU_Pos); -} - -/** - * @brief Set ALARM A Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Minutes from binary to BCD format - * @rmtoll ALRMAR MNT LL_RTC_ALMA_SetMinute\n - * ALRMAR MNU LL_RTC_ALMA_SetMinute - * @param RTCx RTC Instance - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetMinute(RTC_TypeDef *RTCx, uint32_t Minutes) -{ - MODIFY_REG(RTCx->ALRMAR, (RTC_ALRMAR_MNT | RTC_ALRMAR_MNU), - (((Minutes & 0xF0U) << (RTC_ALRMAR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_ALRMAR_MNU_Pos))); -} - -/** - * @brief Get ALARM A Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Minutes from BCD to Binary format - * @rmtoll ALRMAR MNT LL_RTC_ALMA_GetMinute\n - * ALRMAR MNU LL_RTC_ALMA_GetMinute - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetMinute(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMAR, (RTC_ALRMAR_MNT | RTC_ALRMAR_MNU))) >> RTC_ALRMAR_MNU_Pos); -} - -/** - * @brief Set ALARM A Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Seconds from binary to BCD format - * @rmtoll ALRMAR ST LL_RTC_ALMA_SetSecond\n - * ALRMAR SU LL_RTC_ALMA_SetSecond - * @param RTCx RTC Instance - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetSecond(RTC_TypeDef *RTCx, uint32_t Seconds) -{ - MODIFY_REG(RTCx->ALRMAR, (RTC_ALRMAR_ST | RTC_ALRMAR_SU), - (((Seconds & 0xF0U) << (RTC_ALRMAR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_ALRMAR_SU_Pos))); -} - -/** - * @brief Get ALARM A Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Seconds from BCD to Binary format - * @rmtoll ALRMAR ST LL_RTC_ALMA_GetSecond\n - * ALRMAR SU LL_RTC_ALMA_GetSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMAR, (RTC_ALRMAR_ST | RTC_ALRMAR_SU))) >> RTC_ALRMAR_SU_Pos); -} - -/** - * @brief Set Alarm A Time (hour, minute and second) in BCD format - * @rmtoll ALRMAR PM LL_RTC_ALMA_ConfigTime\n - * ALRMAR HT LL_RTC_ALMA_ConfigTime\n - * ALRMAR HU LL_RTC_ALMA_ConfigTime\n - * ALRMAR MNT LL_RTC_ALMA_ConfigTime\n - * ALRMAR MNU LL_RTC_ALMA_ConfigTime\n - * ALRMAR ST LL_RTC_ALMA_ConfigTime\n - * ALRMAR SU LL_RTC_ALMA_ConfigTime - * @param RTCx RTC Instance - * @param Format12_24 This parameter can be one of the following values: - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_PM - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_ConfigTime(RTC_TypeDef *RTCx, uint32_t Format12_24, uint32_t Hours, uint32_t Minutes, uint32_t Seconds) -{ - register uint32_t temp = 0U; - - temp = Format12_24 | (((Hours & 0xF0U) << (RTC_ALRMAR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_ALRMAR_HU_Pos)) | \ - (((Minutes & 0xF0U) << (RTC_ALRMAR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_ALRMAR_MNU_Pos)) | \ - (((Seconds & 0xF0U) << (RTC_ALRMAR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_ALRMAR_SU_Pos)); - - MODIFY_REG(RTCx->ALRMAR, RTC_ALRMAR_PM | RTC_ALRMAR_HT | RTC_ALRMAR_HU | RTC_ALRMAR_MNT | RTC_ALRMAR_MNU | RTC_ALRMAR_ST | RTC_ALRMAR_SU, temp); -} - -/** - * @brief Get Alarm B Time (hour, minute and second) in BCD format - * @note helper macros __LL_RTC_GET_HOUR, __LL_RTC_GET_MINUTE and __LL_RTC_GET_SECOND - * are available to get independently each parameter. - * @rmtoll ALRMAR HT LL_RTC_ALMA_GetTime\n - * ALRMAR HU LL_RTC_ALMA_GetTime\n - * ALRMAR MNT LL_RTC_ALMA_GetTime\n - * ALRMAR MNU LL_RTC_ALMA_GetTime\n - * ALRMAR ST LL_RTC_ALMA_GetTime\n - * ALRMAR SU LL_RTC_ALMA_GetTime - * @param RTCx RTC Instance - * @retval Combination of hours, minutes and seconds. - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetTime(RTC_TypeDef *RTCx) -{ - return (uint32_t)((LL_RTC_ALMA_GetHour(RTCx) << RTC_OFFSET_HOUR) | (LL_RTC_ALMA_GetMinute(RTCx) << RTC_OFFSET_MINUTE) | LL_RTC_ALMA_GetSecond(RTCx)); -} - -/** - * @brief Set Alarm A Mask the most-significant bits starting at this bit - * @note This register can be written only when ALRAE is reset in RTC_CR register, - * or in initialization mode. - * @rmtoll ALRMASSR MASKSS LL_RTC_ALMA_SetSubSecondMask - * @param RTCx RTC Instance - * @param Mask Value between Min_Data=0x00 and Max_Data=0xF - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetSubSecondMask(RTC_TypeDef *RTCx, uint32_t Mask) -{ - MODIFY_REG(RTCx->ALRMASSR, RTC_ALRMASSR_MASKSS, Mask << RTC_ALRMASSR_MASKSS_Pos); -} - -/** - * @brief Get Alarm A Mask the most-significant bits starting at this bit - * @rmtoll ALRMASSR MASKSS LL_RTC_ALMA_GetSubSecondMask - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetSubSecondMask(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMASSR, RTC_ALRMASSR_MASKSS) >> RTC_ALRMASSR_MASKSS_Pos); -} - -/** - * @brief Set Alarm A Sub seconds value - * @rmtoll ALRMASSR SS LL_RTC_ALMA_SetSubSecond - * @param RTCx RTC Instance - * @param Subsecond Value between Min_Data=0x00 and Max_Data=0x7FFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetSubSecond(RTC_TypeDef *RTCx, uint32_t Subsecond) -{ - MODIFY_REG(RTCx->ALRMASSR, RTC_ALRMASSR_SS, Subsecond); -} - -/** - * @brief Get Alarm A Sub seconds value - * @rmtoll ALRMASSR SS LL_RTC_ALMA_GetSubSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x7FFF - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetSubSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMASSR, RTC_ALRMASSR_SS)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_ALARMB ALARMB - * @{ - */ - -/** - * @brief Enable Alarm B - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRBE LL_RTC_ALMB_Enable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_Enable(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ALRBE); -} - -/** - * @brief Disable Alarm B - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRBE LL_RTC_ALMB_Disable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_Disable(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_ALRBE); -} - -/** - * @brief Specify the Alarm B masks. - * @rmtoll ALRMBR MSK4 LL_RTC_ALMB_SetMask\n - * ALRMBR MSK3 LL_RTC_ALMB_SetMask\n - * ALRMBR MSK2 LL_RTC_ALMB_SetMask\n - * ALRMBR MSK1 LL_RTC_ALMB_SetMask - * @param RTCx RTC Instance - * @param Mask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_ALMB_MASK_NONE - * @arg @ref LL_RTC_ALMB_MASK_DATEWEEKDAY - * @arg @ref LL_RTC_ALMB_MASK_HOURS - * @arg @ref LL_RTC_ALMB_MASK_MINUTES - * @arg @ref LL_RTC_ALMB_MASK_SECONDS - * @arg @ref LL_RTC_ALMB_MASK_ALL - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetMask(RTC_TypeDef *RTCx, uint32_t Mask) -{ - MODIFY_REG(RTCx->ALRMBR, RTC_ALRMBR_MSK4 | RTC_ALRMBR_MSK3 | RTC_ALRMBR_MSK2 | RTC_ALRMBR_MSK1, Mask); -} - -/** - * @brief Get the Alarm B masks. - * @rmtoll ALRMBR MSK4 LL_RTC_ALMB_GetMask\n - * ALRMBR MSK3 LL_RTC_ALMB_GetMask\n - * ALRMBR MSK2 LL_RTC_ALMB_GetMask\n - * ALRMBR MSK1 LL_RTC_ALMB_GetMask - * @param RTCx RTC Instance - * @retval Returned value can be can be a combination of the following values: - * @arg @ref LL_RTC_ALMB_MASK_NONE - * @arg @ref LL_RTC_ALMB_MASK_DATEWEEKDAY - * @arg @ref LL_RTC_ALMB_MASK_HOURS - * @arg @ref LL_RTC_ALMB_MASK_MINUTES - * @arg @ref LL_RTC_ALMB_MASK_SECONDS - * @arg @ref LL_RTC_ALMB_MASK_ALL - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetMask(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBR, RTC_ALRMBR_MSK4 | RTC_ALRMBR_MSK3 | RTC_ALRMBR_MSK2 | RTC_ALRMBR_MSK1)); -} - -/** - * @brief Enable AlarmB Week day selection (DU[3:0] represents the week day. DT[1:0] is do not care) - * @rmtoll ALRMBR WDSEL LL_RTC_ALMB_EnableWeekday - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_EnableWeekday(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->ALRMBR, RTC_ALRMBR_WDSEL); -} - -/** - * @brief Disable AlarmB Week day selection (DU[3:0] represents the date ) - * @rmtoll ALRMBR WDSEL LL_RTC_ALMB_DisableWeekday - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_DisableWeekday(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->ALRMBR, RTC_ALRMBR_WDSEL); -} - -/** - * @brief Set ALARM B Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Day from binary to BCD format - * @rmtoll ALRMBR DT LL_RTC_ALMB_SetDay\n - * ALRMBR DU LL_RTC_ALMB_SetDay - * @param RTCx RTC Instance - * @param Day Value between Min_Data=0x01 and Max_Data=0x31 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetDay(RTC_TypeDef *RTCx, uint32_t Day) -{ - MODIFY_REG(RTC->ALRMBR, (RTC_ALRMBR_DT | RTC_ALRMBR_DU), - (((Day & 0xF0U) << (RTC_ALRMBR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_ALRMBR_DU_Pos))); -} - -/** - * @brief Get ALARM B Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Day from BCD to Binary format - * @rmtoll ALRMBR DT LL_RTC_ALMB_GetDay\n - * ALRMBR DU LL_RTC_ALMB_GetDay - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x31 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(( READ_BIT(RTCx->ALRMBR, (RTC_ALRMBR_DT | RTC_ALRMBR_DU))) >> RTC_ALRMBR_DU_Pos); -} - -/** - * @brief Set ALARM B Weekday - * @rmtoll ALRMBR DU LL_RTC_ALMB_SetWeekDay - * @param RTCx RTC Instance - * @param WeekDay This parameter can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetWeekDay(RTC_TypeDef *RTCx, uint32_t WeekDay) -{ - MODIFY_REG(RTCx->ALRMBR, RTC_ALRMBR_DU, WeekDay << RTC_ALRMBR_DU_Pos); -} - -/** - * @brief Get ALARM B Weekday - * @rmtoll ALRMBR DU LL_RTC_ALMB_GetWeekDay - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetWeekDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBR, RTC_ALRMBR_DU) >> RTC_ALRMBR_DU_Pos); -} - -/** - * @brief Set ALARM B time format (AM/24-hour or PM notation) - * @rmtoll ALRMBR PM LL_RTC_ALMB_SetTimeFormat - * @param RTCx RTC Instance - * @param TimeFormat This parameter can be one of the following values: - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_PM - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetTimeFormat(RTC_TypeDef *RTCx, uint32_t TimeFormat) -{ - MODIFY_REG(RTCx->ALRMBR, RTC_ALRMBR_PM, TimeFormat); -} - -/** - * @brief Get ALARM B time format (AM or PM notation) - * @rmtoll ALRMBR PM LL_RTC_ALMB_GetTimeFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_PM - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetTimeFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBR, RTC_ALRMBR_PM)); -} - -/** - * @brief Set ALARM B Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Hours from binary to BCD format - * @rmtoll ALRMBR HT LL_RTC_ALMB_SetHour\n - * ALRMBR HU LL_RTC_ALMB_SetHour - * @param RTCx RTC Instance - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetHour(RTC_TypeDef *RTCx, uint32_t Hours) -{ - MODIFY_REG(RTCx->ALRMBR, (RTC_ALRMBR_HT | RTC_ALRMBR_HU), - (((Hours & 0xF0U) << (RTC_ALRMBR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_ALRMBR_HU_Pos))); -} - -/** - * @brief Get ALARM B Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Hours from BCD to Binary format - * @rmtoll ALRMBR HT LL_RTC_ALMB_GetHour\n - * ALRMBR HU LL_RTC_ALMB_GetHour - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetHour(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMBR, (RTC_ALRMBR_HT | RTC_ALRMBR_HU))) >> RTC_ALRMBR_HU_Pos); -} - -/** - * @brief Set ALARM B Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Minutes from binary to BCD format - * @rmtoll ALRMBR MNT LL_RTC_ALMB_SetMinute\n - * ALRMBR MNU LL_RTC_ALMB_SetMinute - * @param RTCx RTC Instance - * @param Minutes between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetMinute(RTC_TypeDef *RTCx, uint32_t Minutes) -{ - MODIFY_REG(RTCx->ALRMBR, (RTC_ALRMBR_MNT | RTC_ALRMBR_MNU), - (((Minutes & 0xF0U) << (RTC_ALRMBR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_ALRMBR_MNU_Pos))); -} - -/** - * @brief Get ALARM B Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Minutes from BCD to Binary format - * @rmtoll ALRMBR MNT LL_RTC_ALMB_GetMinute\n - * ALRMBR MNU LL_RTC_ALMB_GetMinute - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetMinute(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMBR, (RTC_ALRMBR_MNT | RTC_ALRMBR_MNU))) >> RTC_ALRMBR_MNU_Pos); -} - -/** - * @brief Set ALARM B Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Seconds from binary to BCD format - * @rmtoll ALRMBR ST LL_RTC_ALMB_SetSecond\n - * ALRMBR SU LL_RTC_ALMB_SetSecond - * @param RTCx RTC Instance - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetSecond(RTC_TypeDef *RTCx, uint32_t Seconds) -{ - MODIFY_REG(RTCx->ALRMBR, (RTC_ALRMBR_ST | RTC_ALRMBR_SU), - (((Seconds & 0xF0U) << (RTC_ALRMBR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_ALRMBR_SU_Pos))); -} - -/** - * @brief Get ALARM B Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Seconds from BCD to Binary format - * @rmtoll ALRMBR ST LL_RTC_ALMB_GetSecond\n - * ALRMBR SU LL_RTC_ALMB_GetSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetSecond(RTC_TypeDef *RTCx) -{ - register uint32_t temp = 0U; - - temp = READ_BIT(RTCx->ALRMBR, (RTC_ALRMBR_ST | RTC_ALRMBR_SU)); - return (uint32_t)((((temp & RTC_ALRMBR_ST) >> RTC_ALRMBR_ST_Pos) << 4U) | ((temp & RTC_ALRMBR_SU) >> RTC_ALRMBR_SU_Pos)); -} - -/** - * @brief Set Alarm B Time (hour, minute and second) in BCD format - * @rmtoll ALRMBR PM LL_RTC_ALMB_ConfigTime\n - * ALRMBR HT LL_RTC_ALMB_ConfigTime\n - * ALRMBR HU LL_RTC_ALMB_ConfigTime\n - * ALRMBR MNT LL_RTC_ALMB_ConfigTime\n - * ALRMBR MNU LL_RTC_ALMB_ConfigTime\n - * ALRMBR ST LL_RTC_ALMB_ConfigTime\n - * ALRMBR SU LL_RTC_ALMB_ConfigTime - * @param RTCx RTC Instance - * @param Format12_24 This parameter can be one of the following values: - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_PM - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_ConfigTime(RTC_TypeDef *RTCx, uint32_t Format12_24, uint32_t Hours, uint32_t Minutes, uint32_t Seconds) -{ - register uint32_t temp = 0U; - - temp = Format12_24 | (((Hours & 0xF0U) << (RTC_ALRMBR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_ALRMBR_HU_Pos)) | \ - (((Minutes & 0xF0U) << (RTC_ALRMBR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_ALRMBR_MNU_Pos)) | \ - (((Seconds & 0xF0U) << (RTC_ALRMBR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_ALRMBR_SU_Pos)); - - MODIFY_REG(RTCx->ALRMBR, RTC_ALRMBR_PM| RTC_ALRMBR_HT | RTC_ALRMBR_HU | RTC_ALRMBR_MNT | RTC_ALRMBR_MNU | RTC_ALRMBR_ST | RTC_ALRMBR_SU, temp); -} - -/** - * @brief Get Alarm B Time (hour, minute and second) in BCD format - * @note helper macros __LL_RTC_GET_HOUR, __LL_RTC_GET_MINUTE and __LL_RTC_GET_SECOND - * are available to get independently each parameter. - * @rmtoll ALRMBR HT LL_RTC_ALMB_GetTime\n - * ALRMBR HU LL_RTC_ALMB_GetTime\n - * ALRMBR MNT LL_RTC_ALMB_GetTime\n - * ALRMBR MNU LL_RTC_ALMB_GetTime\n - * ALRMBR ST LL_RTC_ALMB_GetTime\n - * ALRMBR SU LL_RTC_ALMB_GetTime - * @param RTCx RTC Instance - * @retval Combination of hours, minutes and seconds. - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetTime(RTC_TypeDef *RTCx) -{ - return (uint32_t)((LL_RTC_ALMB_GetHour(RTCx) << RTC_OFFSET_HOUR) | (LL_RTC_ALMB_GetMinute(RTCx) << RTC_OFFSET_MINUTE) | LL_RTC_ALMB_GetSecond(RTCx)); -} - -/** - * @brief Set Alarm B Mask the most-significant bits starting at this bit - * @note This register can be written only when ALRBE is reset in RTC_CR register, - * or in initialization mode. - * @rmtoll ALRMBSSR MASKSS LL_RTC_ALMB_SetSubSecondMask - * @param RTCx RTC Instance - * @param Mask Value between Min_Data=0x00 and Max_Data=0xF - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetSubSecondMask(RTC_TypeDef *RTCx, uint32_t Mask) -{ - MODIFY_REG(RTCx->ALRMBSSR, RTC_ALRMBSSR_MASKSS, Mask << RTC_ALRMBSSR_MASKSS_Pos); -} - -/** - * @brief Get Alarm B Mask the most-significant bits starting at this bit - * @rmtoll ALRMBSSR MASKSS LL_RTC_ALMB_GetSubSecondMask - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetSubSecondMask(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBSSR, RTC_ALRMBSSR_MASKSS) >> RTC_ALRMBSSR_MASKSS_Pos); -} - -/** - * @brief Set Alarm B Sub seconds value - * @rmtoll ALRMBSSR SS LL_RTC_ALMB_SetSubSecond - * @param RTCx RTC Instance - * @param Subsecond Value between Min_Data=0x00 and Max_Data=0x7FFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetSubSecond(RTC_TypeDef *RTCx, uint32_t Subsecond) -{ - MODIFY_REG(RTCx->ALRMBSSR, RTC_ALRMBSSR_SS, Subsecond); -} - -/** - * @brief Get Alarm B Sub seconds value - * @rmtoll ALRMBSSR SS LL_RTC_ALMB_GetSubSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x7FFF - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetSubSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBSSR, RTC_ALRMBSSR_SS)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Timestamp Timestamp - * @{ - */ - -/** - * @brief Enable Timestamp - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSE LL_RTC_TS_Enable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_Enable(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_TSE); -} - -/** - * @brief Disable Timestamp - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSE LL_RTC_TS_Disable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_Disable(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_TSE); -} - -/** - * @brief Set Time-stamp event active edge - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note TSE must be reset when TSEDGE is changed to avoid unwanted TSF setting - * @rmtoll CR TSEDGE LL_RTC_TS_SetActiveEdge - * @param RTCx RTC Instance - * @param Edge This parameter can be one of the following values: - * @arg @ref LL_RTC_TIMESTAMP_EDGE_RISING - * @arg @ref LL_RTC_TIMESTAMP_EDGE_FALLING - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_SetActiveEdge(RTC_TypeDef *RTCx, uint32_t Edge) -{ - MODIFY_REG(RTCx->CR, RTC_CR_TSEDGE, Edge); -} - -/** - * @brief Get Time-stamp event active edge - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSEDGE LL_RTC_TS_GetActiveEdge - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TIMESTAMP_EDGE_RISING - * @arg @ref LL_RTC_TIMESTAMP_EDGE_FALLING - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetActiveEdge(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_TSEDGE)); -} - -/** - * @brief Get Timestamp AM/PM notation (AM or 24-hour format) - * @rmtoll TSTR PM LL_RTC_TS_GetTimeFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TS_TIME_FORMAT_AM - * @arg @ref LL_RTC_TS_TIME_FORMAT_PM - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetTimeFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, RTC_TSTR_PM)); -} - -/** - * @brief Get Timestamp Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Hours from BCD to Binary format - * @rmtoll TSTR HT LL_RTC_TS_GetHour\n - * TSTR HU LL_RTC_TS_GetHour - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetHour(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, RTC_TSTR_HT | RTC_TSTR_HU) >> RTC_TSTR_HU_Pos); -} - -/** - * @brief Get Timestamp Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Minutes from BCD to Binary format - * @rmtoll TSTR MNT LL_RTC_TS_GetMinute\n - * TSTR MNU LL_RTC_TS_GetMinute - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetMinute(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, RTC_TSTR_MNT | RTC_TSTR_MNU) >> RTC_TSTR_MNU_Pos); -} - -/** - * @brief Get Timestamp Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Seconds from BCD to Binary format - * @rmtoll TSTR ST LL_RTC_TS_GetSecond\n - * TSTR SU LL_RTC_TS_GetSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, RTC_TSTR_ST | RTC_TSTR_SU)); -} - -/** - * @brief Get Timestamp time (hour, minute and second) in BCD format - * @note helper macros __LL_RTC_GET_HOUR, __LL_RTC_GET_MINUTE and __LL_RTC_GET_SECOND - * are available to get independently each parameter. - * @rmtoll TSTR HT LL_RTC_TS_GetTime\n - * TSTR HU LL_RTC_TS_GetTime\n - * TSTR MNT LL_RTC_TS_GetTime\n - * TSTR MNU LL_RTC_TS_GetTime\n - * TSTR ST LL_RTC_TS_GetTime\n - * TSTR SU LL_RTC_TS_GetTime - * @param RTCx RTC Instance - * @retval Combination of hours, minutes and seconds. - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetTime(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, - RTC_TSTR_HT | RTC_TSTR_HU | RTC_TSTR_MNT | RTC_TSTR_MNU | RTC_TSTR_ST | RTC_TSTR_SU)); -} - -/** - * @brief Get Timestamp Week day - * @rmtoll TSDR WDU LL_RTC_TS_GetWeekDay - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetWeekDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSDR, RTC_TSDR_WDU) >> RTC_TSDR_WDU_Pos); -} - -/** - * @brief Get Timestamp Month in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Month from BCD to Binary format - * @rmtoll TSDR MT LL_RTC_TS_GetMonth\n - * TSDR MU LL_RTC_TS_GetMonth - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetMonth(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSDR, RTC_TSDR_MT | RTC_TSDR_MU) >> RTC_TSDR_MU_Pos); -} - -/** - * @brief Get Timestamp Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Day from BCD to Binary format - * @rmtoll TSDR DT LL_RTC_TS_GetDay\n - * TSDR DU LL_RTC_TS_GetDay - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x31 - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSDR, RTC_TSDR_DT | RTC_TSDR_DU)); -} - -/** - * @brief Get Timestamp date (WeekDay, Day and Month) in BCD format - * @note helper macros __LL_RTC_GET_WEEKDAY, __LL_RTC_GET_MONTH, - * and __LL_RTC_GET_DAY are available to get independently each parameter. - * @rmtoll TSDR WDU LL_RTC_TS_GetDate\n - * TSDR MT LL_RTC_TS_GetDate\n - * TSDR MU LL_RTC_TS_GetDate\n - * TSDR DT LL_RTC_TS_GetDate\n - * TSDR DU LL_RTC_TS_GetDate - * @param RTCx RTC Instance - * @retval Combination of Weekday, Day and Month - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetDate(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSDR, RTC_TSDR_WDU | RTC_TSDR_MT | RTC_TSDR_MU | RTC_TSDR_DT | RTC_TSDR_DU)); -} - -/** - * @brief Get time-stamp sub second value - * @rmtoll TSSSR SS LL_RTC_TS_GetSubSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetSubSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSSSR, RTC_TSSSR_SS)); -} - -#if defined(RTC_TAFCR_TAMPTS) -/** - * @brief Activate timestamp on tamper detection event - * @rmtoll TAFCR TAMPTS LL_RTC_TS_EnableOnTamper - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_EnableOnTamper(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPTS); -} - -/** - * @brief Disable timestamp on tamper detection event - * @rmtoll TAFCR TAMPTS LL_RTC_TS_DisableOnTamper - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_DisableOnTamper(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPTS); -} -#endif /* RTC_TAFCR_TAMPTS */ - -/** - * @brief Set timestamp Pin - * @rmtoll TAFCR TSINSEL LL_RTC_TS_SetPin - * @param RTCx RTC Instance - * @param TSPin specifies the RTC TimeStamp Pin. - * This parameter can be one of the following values: - * @arg LL_RTC_TimeStampPin_Default: RTC_AF1 is used as RTC TimeStamp. - * @arg LL_RTC_TimeStampPin_Pos1: RTC_AF2 is selected as RTC TimeStamp. (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_SetPin(RTC_TypeDef *RTCx, uint32_t TSPin) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TSINSEL , TSPin); -} - -/** - * @brief Get timestamp Pin - * @rmtoll TAFCR TSINSEL LL_RTC_TS_GetPin - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg LL_RTC_TimeStampPin_Default: RTC_AF1 is used as RTC TimeStamp Pin. - * @arg LL_RTC_TimeStampPin_Pos1: RTC_AF2 is selected as RTC TimeStamp Pin. (*) - * - * (*) value not defined in all devices. - * @retval None - */ - -__STATIC_INLINE uint32_t LL_RTC_TS_GetPin(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TSINSEL)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Tamper Tamper - * @{ - */ - -/** - * @brief Enable RTC_TAMPx input detection - * @rmtoll TAFCR TAMP1E LL_RTC_TAMPER_Enable\n - * TAFCR TAMP2E LL_RTC_TAMPER_Enable\n - * @param RTCx RTC Instance - * @param Tamper This parameter can be a combination of the following values: - * @arg @ref LL_RTC_TAMPER_1 - * @arg @ref LL_RTC_TAMPER_2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_Enable(RTC_TypeDef *RTCx, uint32_t Tamper) -{ - SET_BIT(RTCx->TAFCR, Tamper); -} - -/** - * @brief Clear RTC_TAMPx input detection - * @rmtoll TAFCR TAMP1E LL_RTC_TAMPER_Disable\n - * TAFCR TAMP2E LL_RTC_TAMPER_Disable\n - * @param RTCx RTC Instance - * @param Tamper This parameter can be a combination of the following values: - * @arg @ref LL_RTC_TAMPER_1 - * @arg @ref LL_RTC_TAMPER_2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_Disable(RTC_TypeDef *RTCx, uint32_t Tamper) -{ - CLEAR_BIT(RTCx->TAFCR, Tamper); -} - -#if defined(RTC_TAFCR_TAMPPUDIS) -/** - * @brief Disable RTC_TAMPx pull-up disable (Disable precharge of RTC_TAMPx pins) - * @rmtoll TAFCR TAMPPUDIS LL_RTC_TAMPER_DisablePullUp - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_DisablePullUp(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPPUDIS); -} - -/** - * @brief Enable RTC_TAMPx pull-up disable ( Precharge RTC_TAMPx pins before sampling) - * @rmtoll TAFCR TAMPPUDIS LL_RTC_TAMPER_EnablePullUp - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_EnablePullUp(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPPUDIS); -} -#endif /* RTC_TAFCR_TAMPPUDIS */ - -#if defined(RTC_TAFCR_TAMPPRCH) -/** - * @brief Set RTC_TAMPx precharge duration - * @rmtoll TAFCR TAMPPRCH LL_RTC_TAMPER_SetPrecharge - * @param RTCx RTC Instance - * @param Duration This parameter can be one of the following values: - * @arg @ref LL_RTC_TAMPER_DURATION_1RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_2RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_4RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_8RTCCLK - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_SetPrecharge(RTC_TypeDef *RTCx, uint32_t Duration) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TAMPPRCH, Duration); -} - -/** - * @brief Get RTC_TAMPx precharge duration - * @rmtoll TAFCR TAMPPRCH LL_RTC_TAMPER_GetPrecharge - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TAMPER_DURATION_1RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_2RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_4RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_8RTCCLK - */ -__STATIC_INLINE uint32_t LL_RTC_TAMPER_GetPrecharge(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPPRCH)); -} -#endif /* RTC_TAFCR_TAMPPRCH */ - -#if defined(RTC_TAFCR_TAMPFLT) -/** - * @brief Set RTC_TAMPx filter count - * @rmtoll TAFCR TAMPFLT LL_RTC_TAMPER_SetFilterCount - * @param RTCx RTC Instance - * @param FilterCount This parameter can be one of the following values: - * @arg @ref LL_RTC_TAMPER_FILTER_DISABLE - * @arg @ref LL_RTC_TAMPER_FILTER_2SAMPLE - * @arg @ref LL_RTC_TAMPER_FILTER_4SAMPLE - * @arg @ref LL_RTC_TAMPER_FILTER_8SAMPLE - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_SetFilterCount(RTC_TypeDef *RTCx, uint32_t FilterCount) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TAMPFLT, FilterCount); -} - -/** - * @brief Get RTC_TAMPx filter count - * @rmtoll TAFCR TAMPFLT LL_RTC_TAMPER_GetFilterCount - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TAMPER_FILTER_DISABLE - * @arg @ref LL_RTC_TAMPER_FILTER_2SAMPLE - * @arg @ref LL_RTC_TAMPER_FILTER_4SAMPLE - * @arg @ref LL_RTC_TAMPER_FILTER_8SAMPLE - */ -__STATIC_INLINE uint32_t LL_RTC_TAMPER_GetFilterCount(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPFLT)); -} -#endif /* RTC_TAFCR_TAMPFLT */ - -#if defined(RTC_TAFCR_TAMPFREQ) -/** - * @brief Set Tamper sampling frequency - * @rmtoll TAFCR TAMPFREQ LL_RTC_TAMPER_SetSamplingFreq - * @param RTCx RTC Instance - * @param SamplingFreq This parameter can be one of the following values: - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_32768 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_16384 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_8192 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_4096 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_2048 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_1024 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_512 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_256 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_SetSamplingFreq(RTC_TypeDef *RTCx, uint32_t SamplingFreq) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TAMPFREQ, SamplingFreq); -} - -/** - * @brief Get Tamper sampling frequency - * @rmtoll TAFCR TAMPFREQ LL_RTC_TAMPER_GetSamplingFreq - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_32768 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_16384 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_8192 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_4096 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_2048 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_1024 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_512 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_256 - */ -__STATIC_INLINE uint32_t LL_RTC_TAMPER_GetSamplingFreq(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPFREQ)); -} -#endif /* RTC_TAFCR_TAMPFREQ */ - -/** - * @brief Enable Active level for Tamper input - * @rmtoll TAFCR TAMP1TRG LL_RTC_TAMPER_EnableActiveLevel\n - * TAFCR TAMP2TRG LL_RTC_TAMPER_EnableActiveLevel\n - * @param RTCx RTC Instance - * @param Tamper This parameter can be a combination of the following values: - * @arg @ref LL_RTC_TAMPER_ACTIVELEVEL_TAMP1 - * @arg @ref LL_RTC_TAMPER_ACTIVELEVEL_TAMP2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_EnableActiveLevel(RTC_TypeDef *RTCx, uint32_t Tamper) -{ - SET_BIT(RTCx->TAFCR, Tamper); -} - -/** - * @brief Disable Active level for Tamper input - * @rmtoll TAFCR TAMP1TRG LL_RTC_TAMPER_DisableActiveLevel\n - * TAFCR TAMP2TRG LL_RTC_TAMPER_DisableActiveLevel\n - * @param RTCx RTC Instance - * @param Tamper This parameter can be a combination of the following values: - * @arg @ref LL_RTC_TAMPER_ACTIVELEVEL_TAMP1 - * @arg @ref LL_RTC_TAMPER_ACTIVELEVEL_TAMP2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_DisableActiveLevel(RTC_TypeDef *RTCx, uint32_t Tamper) -{ - CLEAR_BIT(RTCx->TAFCR, Tamper); -} - -/** - * @brief Set Tamper Pin - * @rmtoll TAFCR TAMP1INSEL LL_RTC_TAMPER_SetPin - * @param RTCx RTC Instance - * @param TamperPin specifies the RTC Tamper Pin. - * This parameter can be one of the following values: - * @arg LL_RTC_TamperPin_Default: RTC_AF1 is used as RTC Tamper. - * @arg LL_RTC_TamperPin_Pos1: RTC_AF2 is selected as RTC Tamper. (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_SetPin(RTC_TypeDef *RTCx, uint32_t TamperPin) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TAMP1INSEL , TamperPin); -} - -/** - * @brief Get Tamper Pin - * @rmtoll TAFCR TAMP1INSEL LL_RTC_TAMPER_GetPin - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg LL_RTC_TamperPin_Default: RTC_AF1 is used as RTC Tamper Pin. - * @arg LL_RTC_TamperPin_Pos1: RTC_AF2 is selected as RTC Tamper Pin. (*) - * - * (*) value not defined in all devices. - * @retval None - */ - -__STATIC_INLINE uint32_t LL_RTC_TAMPER_GetPin(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TAMP1INSEL)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Wakeup Wakeup - * @{ - */ - -/** - * @brief Enable Wakeup timer - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR WUTE LL_RTC_WAKEUP_Enable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_WAKEUP_Enable(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_WUTE); -} - -/** - * @brief Disable Wakeup timer - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR WUTE LL_RTC_WAKEUP_Disable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_WAKEUP_Disable(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_WUTE); -} - -/** - * @brief Check if Wakeup timer is enabled or not - * @rmtoll CR WUTE LL_RTC_WAKEUP_IsEnabled - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_WAKEUP_IsEnabled(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_WUTE) == (RTC_CR_WUTE)); -} - -/** - * @brief Select Wakeup clock - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note Bit can be written only when RTC_CR WUTE bit = 0 and RTC_ISR WUTWF bit = 1 - * @rmtoll CR WUCKSEL LL_RTC_WAKEUP_SetClock - * @param RTCx RTC Instance - * @param WakeupClock This parameter can be one of the following values: - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_16 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_8 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_4 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_2 - * @arg @ref LL_RTC_WAKEUPCLOCK_CKSPRE - * @arg @ref LL_RTC_WAKEUPCLOCK_CKSPRE_WUT - * @retval None - */ -__STATIC_INLINE void LL_RTC_WAKEUP_SetClock(RTC_TypeDef *RTCx, uint32_t WakeupClock) -{ - MODIFY_REG(RTCx->CR, RTC_CR_WUCKSEL, WakeupClock); -} - -/** - * @brief Get Wakeup clock - * @rmtoll CR WUCKSEL LL_RTC_WAKEUP_GetClock - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_16 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_8 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_4 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_2 - * @arg @ref LL_RTC_WAKEUPCLOCK_CKSPRE - * @arg @ref LL_RTC_WAKEUPCLOCK_CKSPRE_WUT - */ -__STATIC_INLINE uint32_t LL_RTC_WAKEUP_GetClock(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_WUCKSEL)); -} - -/** - * @brief Set Wakeup auto-reload value - * @note Bit can be written only when WUTWF is set to 1 in RTC_ISR - * @rmtoll WUTR WUT LL_RTC_WAKEUP_SetAutoReload - * @param RTCx RTC Instance - * @param Value Value between Min_Data=0x00 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_WAKEUP_SetAutoReload(RTC_TypeDef *RTCx, uint32_t Value) -{ - MODIFY_REG(RTCx->WUTR, RTC_WUTR_WUT, Value); -} - -/** - * @brief Get Wakeup auto-reload value - * @rmtoll WUTR WUT LL_RTC_WAKEUP_GetAutoReload - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_RTC_WAKEUP_GetAutoReload(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->WUTR, RTC_WUTR_WUT)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Backup_Registers Backup_Registers - * @{ - */ - -/** - * @brief Writes a data in a specified RTC Backup data register. - * @rmtoll BKPxR BKP LL_RTC_BAK_SetRegister - * @param RTCx RTC Instance - * @param BackupRegister This parameter can be one of the following values: - * @arg @ref LL_RTC_BKP_DR0 - * @arg @ref LL_RTC_BKP_DR1 - * @arg @ref LL_RTC_BKP_DR2 - * @arg @ref LL_RTC_BKP_DR3 - * @arg @ref LL_RTC_BKP_DR4 - * @arg @ref LL_RTC_BKP_DR5 - * @arg @ref LL_RTC_BKP_DR6 - * @arg @ref LL_RTC_BKP_DR7 - * @arg @ref LL_RTC_BKP_DR8 - * @arg @ref LL_RTC_BKP_DR9 - * @arg @ref LL_RTC_BKP_DR10 - * @arg @ref LL_RTC_BKP_DR11 - * @arg @ref LL_RTC_BKP_DR12 - * @arg @ref LL_RTC_BKP_DR13 - * @arg @ref LL_RTC_BKP_DR14 - * @arg @ref LL_RTC_BKP_DR15 - * @arg @ref LL_RTC_BKP_DR16 - * @arg @ref LL_RTC_BKP_DR17 - * @arg @ref LL_RTC_BKP_DR18 - * @arg @ref LL_RTC_BKP_DR19 - * @param Data Value between Min_Data=0x00 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_BAK_SetRegister(RTC_TypeDef *RTCx, uint32_t BackupRegister, uint32_t Data) -{ - register uint32_t tmp = 0U; - - tmp = (uint32_t)(&(RTCx->BKP0R)); - tmp += (BackupRegister * 4U); - - /* Write the specified register */ - *(__IO uint32_t *)tmp = (uint32_t)Data; -} - -/** - * @brief Reads data from the specified RTC Backup data Register. - * @rmtoll BKPxR BKP LL_RTC_BAK_GetRegister - * @param RTCx RTC Instance - * @param BackupRegister This parameter can be one of the following values: - * @arg @ref LL_RTC_BKP_DR0 - * @arg @ref LL_RTC_BKP_DR1 - * @arg @ref LL_RTC_BKP_DR2 - * @arg @ref LL_RTC_BKP_DR3 - * @arg @ref LL_RTC_BKP_DR4 - * @arg @ref LL_RTC_BKP_DR5 - * @arg @ref LL_RTC_BKP_DR6 - * @arg @ref LL_RTC_BKP_DR7 - * @arg @ref LL_RTC_BKP_DR8 - * @arg @ref LL_RTC_BKP_DR9 - * @arg @ref LL_RTC_BKP_DR10 - * @arg @ref LL_RTC_BKP_DR11 - * @arg @ref LL_RTC_BKP_DR12 - * @arg @ref LL_RTC_BKP_DR13 - * @arg @ref LL_RTC_BKP_DR14 - * @arg @ref LL_RTC_BKP_DR15 - * @arg @ref LL_RTC_BKP_DR16 - * @arg @ref LL_RTC_BKP_DR17 - * @arg @ref LL_RTC_BKP_DR18 - * @arg @ref LL_RTC_BKP_DR19 - * @retval Value between Min_Data=0x00 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_RTC_BAK_GetRegister(RTC_TypeDef *RTCx, uint32_t BackupRegister) -{ - register uint32_t tmp = 0U; - - tmp = (uint32_t)(&(RTCx->BKP0R)); - tmp += (BackupRegister * 4U); - - /* Read the specified register */ - return (*(__IO uint32_t *)tmp); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Calibration Calibration - * @{ - */ - -/** - * @brief Set Calibration output frequency (1 Hz or 512 Hz) - * @note Bits are write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR COE LL_RTC_CAL_SetOutputFreq\n - * CR COSEL LL_RTC_CAL_SetOutputFreq - * @param RTCx RTC Instance - * @param Frequency This parameter can be one of the following values: - * @arg @ref LL_RTC_CALIB_OUTPUT_NONE - * @arg @ref LL_RTC_CALIB_OUTPUT_1HZ - * @arg @ref LL_RTC_CALIB_OUTPUT_512HZ - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_SetOutputFreq(RTC_TypeDef *RTCx, uint32_t Frequency) -{ - MODIFY_REG(RTCx->CR, RTC_CR_COE | RTC_CR_COSEL, Frequency); -} - -/** - * @brief Get Calibration output frequency (1 Hz or 512 Hz) - * @rmtoll CR COE LL_RTC_CAL_GetOutputFreq\n - * CR COSEL LL_RTC_CAL_GetOutputFreq - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_CALIB_OUTPUT_NONE - * @arg @ref LL_RTC_CALIB_OUTPUT_1HZ - * @arg @ref LL_RTC_CALIB_OUTPUT_512HZ - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetOutputFreq(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_COE | RTC_CR_COSEL)); -} - -/** - * @brief Enable Coarse digital calibration - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR DCE LL_RTC_CAL_EnableCoarseDigital - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_EnableCoarseDigital(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_DCE); -} - -/** - * @brief Disable Coarse digital calibration - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR DCE LL_RTC_CAL_DisableCoarseDigital - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_DisableCoarseDigital(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_DCE); -} - -/** - * @brief Set the coarse digital calibration - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CALIBR DCS LL_RTC_CAL_ConfigCoarseDigital\n - * CALIBR DC LL_RTC_CAL_ConfigCoarseDigital - * @param RTCx RTC Instance - * @param Sign This parameter can be one of the following values: - * @arg @ref LL_RTC_CALIB_SIGN_POSITIVE - * @arg @ref LL_RTC_CALIB_SIGN_NEGATIVE - * @param Value value of coarse calibration expressed in ppm (coded on 5 bits) - * @note This Calibration value should be between 0 and 63 when using negative sign with a 2-ppm step. - * @note This Calibration value should be between 0 and 126 when using positive sign with a 4-ppm step. - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_ConfigCoarseDigital(RTC_TypeDef* RTCx, uint32_t Sign, uint32_t Value) -{ - MODIFY_REG(RTCx->CALIBR, RTC_CALIBR_DCS | RTC_CALIBR_DC, Sign | Value); -} - -/** - * @brief Get the coarse digital calibration value - * @rmtoll CALIBR DC LL_RTC_CAL_GetCoarseDigitalValue - * @param RTCx RTC Instance - * @retval value of coarse calibration expressed in ppm (coded on 5 bits) - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetCoarseDigitalValue(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CALIBR, RTC_CALIBR_DC)); -} - -/** - * @brief Get the coarse digital calibration sign - * @rmtoll CALIBR DCS LL_RTC_CAL_GetCoarseDigitalSign - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_CALIB_SIGN_POSITIVE - * @arg @ref LL_RTC_CALIB_SIGN_NEGATIVE - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetCoarseDigitalSign(RTC_TypeDef* RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CALIBR, RTC_CALIBR_DCS)); -} - -/** - * @brief Insert or not One RTCCLK pulse every 2exp11 pulses (frequency increased by 488.5 ppm) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note Bit can be written only when RECALPF is set to 0 in RTC_ISR - * @rmtoll CALR CALP LL_RTC_CAL_SetPulse - * @param RTCx RTC Instance - * @param Pulse This parameter can be one of the following values: - * @arg @ref LL_RTC_CALIB_INSERTPULSE_NONE - * @arg @ref LL_RTC_CALIB_INSERTPULSE_SET - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_SetPulse(RTC_TypeDef *RTCx, uint32_t Pulse) -{ - MODIFY_REG(RTCx->CALR, RTC_CALR_CALP, Pulse); -} - -/** - * @brief Check if one RTCCLK has been inserted or not every 2exp11 pulses (frequency increased by 488.5 ppm) - * @rmtoll CALR CALP LL_RTC_CAL_IsPulseInserted - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_IsPulseInserted(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CALR, RTC_CALR_CALP) == (RTC_CALR_CALP)); -} - -/** - * @brief Set the calibration cycle period - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note Bit can be written only when RECALPF is set to 0 in RTC_ISR - * @rmtoll CALR CALW8 LL_RTC_CAL_SetPeriod\n - * CALR CALW16 LL_RTC_CAL_SetPeriod - * @param RTCx RTC Instance - * @param Period This parameter can be one of the following values: - * @arg @ref LL_RTC_CALIB_PERIOD_32SEC - * @arg @ref LL_RTC_CALIB_PERIOD_16SEC - * @arg @ref LL_RTC_CALIB_PERIOD_8SEC - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_SetPeriod(RTC_TypeDef *RTCx, uint32_t Period) -{ - MODIFY_REG(RTCx->CALR, RTC_CALR_CALW8 | RTC_CALR_CALW16, Period); -} - -/** - * @brief Get the calibration cycle period - * @rmtoll CALR CALW8 LL_RTC_CAL_GetPeriod\n - * CALR CALW16 LL_RTC_CAL_GetPeriod - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_CALIB_PERIOD_32SEC - * @arg @ref LL_RTC_CALIB_PERIOD_16SEC - * @arg @ref LL_RTC_CALIB_PERIOD_8SEC - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetPeriod(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CALR, RTC_CALR_CALW8 | RTC_CALR_CALW16)); -} - -/** - * @brief Set Calibration minus - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note Bit can be written only when RECALPF is set to 0 in RTC_ISR - * @rmtoll CALR CALM LL_RTC_CAL_SetMinus - * @param RTCx RTC Instance - * @param CalibMinus Value between Min_Data=0x00 and Max_Data=0x1FF - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_SetMinus(RTC_TypeDef *RTCx, uint32_t CalibMinus) -{ - MODIFY_REG(RTCx->CALR, RTC_CALR_CALM, CalibMinus); -} - -/** - * @brief Get Calibration minus - * @rmtoll CALR CALM LL_RTC_CAL_GetMinus - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data= 0x1FF - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetMinus(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CALR, RTC_CALR_CALM)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Get Recalibration pending Flag - * @rmtoll ISR RECALPF LL_RTC_IsActiveFlag_RECALP - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_RECALP(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_RECALPF) == (RTC_ISR_RECALPF)); -} - - -#if defined(RTC_TAMPER2_SUPPORT) -/** - * @brief Get RTC_TAMP2 detection flag - * @rmtoll ISR TAMP2F LL_RTC_IsActiveFlag_TAMP2 - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_TAMP2(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_TAMP2F) == (RTC_ISR_TAMP2F)); -} -#endif /* RTC_TAMPER2_SUPPORT */ - -/** - * @brief Get RTC_TAMP1 detection flag - * @rmtoll ISR TAMP1F LL_RTC_IsActiveFlag_TAMP1 - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_TAMP1(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_TAMP1F) == (RTC_ISR_TAMP1F)); -} - -/** - * @brief Get Time-stamp overflow flag - * @rmtoll ISR TSOVF LL_RTC_IsActiveFlag_TSOV - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_TSOV(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_TSOVF) == (RTC_ISR_TSOVF)); -} - -/** - * @brief Get Time-stamp flag - * @rmtoll ISR TSF LL_RTC_IsActiveFlag_TS - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_TS(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_TSF) == (RTC_ISR_TSF)); -} - -/** - * @brief Get Wakeup timer flag - * @rmtoll ISR WUTF LL_RTC_IsActiveFlag_WUT - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_WUT(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_WUTF) == (RTC_ISR_WUTF)); -} - -/** - * @brief Get Alarm B flag - * @rmtoll ISR ALRBF LL_RTC_IsActiveFlag_ALRB - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_ALRB(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_ALRBF) == (RTC_ISR_ALRBF)); -} - -/** - * @brief Get Alarm A flag - * @rmtoll ISR ALRAF LL_RTC_IsActiveFlag_ALRA - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_ALRA(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_ALRAF) == (RTC_ISR_ALRAF)); -} - - -#if defined(RTC_TAMPER2_SUPPORT) -/** - * @brief Clear RTC_TAMP2 detection flag - * @rmtoll ISR TAMP2F LL_RTC_ClearFlag_TAMP2 - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_TAMP2(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_TAMP2F | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} -#endif /* RTC_TAMPER2_SUPPORT */ - -/** - * @brief Clear RTC_TAMP1 detection flag - * @rmtoll ISR TAMP1F LL_RTC_ClearFlag_TAMP1 - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_TAMP1(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_TAMP1F | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Time-stamp overflow flag - * @rmtoll ISR TSOVF LL_RTC_ClearFlag_TSOV - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_TSOV(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_TSOVF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Time-stamp flag - * @rmtoll ISR TSF LL_RTC_ClearFlag_TS - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_TS(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_TSF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Wakeup timer flag - * @rmtoll ISR WUTF LL_RTC_ClearFlag_WUT - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_WUT(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_WUTF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Alarm B flag - * @rmtoll ISR ALRBF LL_RTC_ClearFlag_ALRB - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_ALRB(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_ALRBF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Alarm A flag - * @rmtoll ISR ALRAF LL_RTC_ClearFlag_ALRA - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_ALRA(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_ALRAF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Get Initialization flag - * @rmtoll ISR INITF LL_RTC_IsActiveFlag_INIT - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_INIT(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_INITF) == (RTC_ISR_INITF)); -} - -/** - * @brief Get Registers synchronization flag - * @rmtoll ISR RSF LL_RTC_IsActiveFlag_RS - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_RS(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_RSF) == (RTC_ISR_RSF)); -} - -/** - * @brief Clear Registers synchronization flag - * @rmtoll ISR RSF LL_RTC_ClearFlag_RS - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_RS(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_RSF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Get Initialization status flag - * @rmtoll ISR INITS LL_RTC_IsActiveFlag_INITS - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_INITS(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_INITS) == (RTC_ISR_INITS)); -} - -/** - * @brief Get Shift operation pending flag - * @rmtoll ISR SHPF LL_RTC_IsActiveFlag_SHP - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_SHP(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_SHPF) == (RTC_ISR_SHPF)); -} - -/** - * @brief Get Wakeup timer write flag - * @rmtoll ISR WUTWF LL_RTC_IsActiveFlag_WUTW - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_WUTW(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_WUTWF) == (RTC_ISR_WUTWF)); -} - -/** - * @brief Get Alarm B write flag - * @rmtoll ISR ALRBWF LL_RTC_IsActiveFlag_ALRBW - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_ALRBW(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_ALRBWF) == (RTC_ISR_ALRBWF)); -} - -/** - * @brief Get Alarm A write flag - * @rmtoll ISR ALRAWF LL_RTC_IsActiveFlag_ALRAW - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_ALRAW(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_ALRAWF) == (RTC_ISR_ALRAWF)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable Time-stamp interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSIE LL_RTC_EnableIT_TS - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_TS(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_TSIE); -} - -/** - * @brief Disable Time-stamp interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSIE LL_RTC_DisableIT_TS - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_TS(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_TSIE); -} - -/** - * @brief Enable Wakeup timer interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR WUTIE LL_RTC_EnableIT_WUT - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_WUT(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_WUTIE); -} - -/** - * @brief Disable Wakeup timer interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR WUTIE LL_RTC_DisableIT_WUT - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_WUT(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_WUTIE); -} - -/** - * @brief Enable Alarm B interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRBIE LL_RTC_EnableIT_ALRB - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_ALRB(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ALRBIE); -} - -/** - * @brief Disable Alarm B interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRBIE LL_RTC_DisableIT_ALRB - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_ALRB(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_ALRBIE); -} - -/** - * @brief Enable Alarm A interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRAIE LL_RTC_EnableIT_ALRA - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_ALRA(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ALRAIE); -} - -/** - * @brief Disable Alarm A interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRAIE LL_RTC_DisableIT_ALRA - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_ALRA(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_ALRAIE); -} - -/** - * @brief Enable all Tamper Interrupt - * @rmtoll TAFCR TAMPIE LL_RTC_EnableIT_TAMP - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_TAMP(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPIE); -} - -/** - * @brief Disable all Tamper Interrupt - * @rmtoll TAFCR TAMPIE LL_RTC_DisableIT_TAMP - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_TAMP(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPIE); -} - -/** - * @brief Check if Time-stamp interrupt is enabled or not - * @rmtoll CR TSIE LL_RTC_IsEnabledIT_TS - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_TS(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_TSIE) == (RTC_CR_TSIE)); -} - -/** - * @brief Check if Wakeup timer interrupt is enabled or not - * @rmtoll CR WUTIE LL_RTC_IsEnabledIT_WUT - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_WUT(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_WUTIE) == (RTC_CR_WUTIE)); -} - -/** - * @brief Check if Alarm B interrupt is enabled or not - * @rmtoll CR ALRBIE LL_RTC_IsEnabledIT_ALRB - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_ALRB(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_ALRBIE) == (RTC_CR_ALRBIE)); -} - -/** - * @brief Check if Alarm A interrupt is enabled or not - * @rmtoll CR ALRAIE LL_RTC_IsEnabledIT_ALRA - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_ALRA(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_ALRAIE) == (RTC_CR_ALRAIE)); -} - -/** - * @brief Check if all the TAMPER interrupts are enabled or not - * @rmtoll TAFCR TAMPIE LL_RTC_IsEnabledIT_TAMP - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_TAMP(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->TAFCR, - RTC_TAFCR_TAMPIE) == (RTC_TAFCR_TAMPIE)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RTC_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_RTC_DeInit(RTC_TypeDef *RTCx); -ErrorStatus LL_RTC_Init(RTC_TypeDef *RTCx, LL_RTC_InitTypeDef *RTC_InitStruct); -void LL_RTC_StructInit(LL_RTC_InitTypeDef *RTC_InitStruct); -ErrorStatus LL_RTC_TIME_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_TimeTypeDef *RTC_TimeStruct); -void LL_RTC_TIME_StructInit(LL_RTC_TimeTypeDef *RTC_TimeStruct); -ErrorStatus LL_RTC_DATE_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_DateTypeDef *RTC_DateStruct); -void LL_RTC_DATE_StructInit(LL_RTC_DateTypeDef *RTC_DateStruct); -ErrorStatus LL_RTC_ALMA_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct); -ErrorStatus LL_RTC_ALMB_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct); -void LL_RTC_ALMA_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct); -void LL_RTC_ALMB_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct); -ErrorStatus LL_RTC_EnterInitMode(RTC_TypeDef *RTCx); -ErrorStatus LL_RTC_ExitInitMode(RTC_TypeDef *RTCx); -ErrorStatus LL_RTC_WaitForSynchro(RTC_TypeDef *RTCx); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RTC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_RTC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h deleted file mode 100644 index 540a0e180d2de6b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h +++ /dev/null @@ -1,1125 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_sdmmc.h - * @author MCD Application Team - * @brief Header file of SDMMC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_SDMMC_H -#define STM32F4xx_LL_SDMMC_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(SDIO) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_Driver - * @{ - */ - -/** @addtogroup SDMMC_LL - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SDMMC_LL_Exported_Types SDMMC_LL Exported Types - * @{ - */ - -/** - * @brief SDMMC Configuration Structure definition - */ -typedef struct -{ - uint32_t ClockEdge; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref SDMMC_LL_Clock_Edge */ - - uint32_t ClockBypass; /*!< Specifies whether the SDMMC Clock divider bypass is - enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_Clock_Bypass */ - - uint32_t ClockPowerSave; /*!< Specifies whether SDMMC Clock output is enabled or - disabled when the bus is idle. - This parameter can be a value of @ref SDMMC_LL_Clock_Power_Save */ - - uint32_t BusWide; /*!< Specifies the SDMMC bus width. - This parameter can be a value of @ref SDMMC_LL_Bus_Wide */ - - uint32_t HardwareFlowControl; /*!< Specifies whether the SDMMC hardware flow control is enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_Hardware_Flow_Control */ - - uint32_t ClockDiv; /*!< Specifies the clock frequency of the SDMMC controller. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - -}SDIO_InitTypeDef; - - -/** - * @brief SDMMC Command Control structure - */ -typedef struct -{ - uint32_t Argument; /*!< Specifies the SDMMC command argument which is sent - to a card as part of a command message. If a command - contains an argument, it must be loaded into this register - before writing the command to the command register. */ - - uint32_t CmdIndex; /*!< Specifies the SDMMC command index. It must be Min_Data = 0 and - Max_Data = 64 */ - - uint32_t Response; /*!< Specifies the SDMMC response type. - This parameter can be a value of @ref SDMMC_LL_Response_Type */ - - uint32_t WaitForInterrupt; /*!< Specifies whether SDMMC wait for interrupt request is - enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_Wait_Interrupt_State */ - - uint32_t CPSM; /*!< Specifies whether SDMMC Command path state machine (CPSM) - is enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_CPSM_State */ -}SDIO_CmdInitTypeDef; - - -/** - * @brief SDMMC Data Control structure - */ -typedef struct -{ - uint32_t DataTimeOut; /*!< Specifies the data timeout period in card bus clock periods. */ - - uint32_t DataLength; /*!< Specifies the number of data bytes to be transferred. */ - - uint32_t DataBlockSize; /*!< Specifies the data block size for block transfer. - This parameter can be a value of @ref SDMMC_LL_Data_Block_Size */ - - uint32_t TransferDir; /*!< Specifies the data transfer direction, whether the transfer - is a read or write. - This parameter can be a value of @ref SDMMC_LL_Transfer_Direction */ - - uint32_t TransferMode; /*!< Specifies whether data transfer is in stream or block mode. - This parameter can be a value of @ref SDMMC_LL_Transfer_Type */ - - uint32_t DPSM; /*!< Specifies whether SDMMC Data path state machine (DPSM) - is enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_DPSM_State */ -}SDIO_DataInitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SDMMC_LL_Exported_Constants SDMMC_LL Exported Constants - * @{ - */ -#define SDMMC_ERROR_NONE 0x00000000U /*!< No error */ -#define SDMMC_ERROR_CMD_CRC_FAIL 0x00000001U /*!< Command response received (but CRC check failed) */ -#define SDMMC_ERROR_DATA_CRC_FAIL 0x00000002U /*!< Data block sent/received (CRC check failed) */ -#define SDMMC_ERROR_CMD_RSP_TIMEOUT 0x00000004U /*!< Command response timeout */ -#define SDMMC_ERROR_DATA_TIMEOUT 0x00000008U /*!< Data timeout */ -#define SDMMC_ERROR_TX_UNDERRUN 0x00000010U /*!< Transmit FIFO underrun */ -#define SDMMC_ERROR_RX_OVERRUN 0x00000020U /*!< Receive FIFO overrun */ -#define SDMMC_ERROR_ADDR_MISALIGNED 0x00000040U /*!< Misaligned address */ -#define SDMMC_ERROR_BLOCK_LEN_ERR 0x00000080U /*!< Transferred block length is not allowed for the card or the - number of transferred bytes does not match the block length */ -#define SDMMC_ERROR_ERASE_SEQ_ERR 0x00000100U /*!< An error in the sequence of erase command occurs */ -#define SDMMC_ERROR_BAD_ERASE_PARAM 0x00000200U /*!< An invalid selection for erase groups */ -#define SDMMC_ERROR_WRITE_PROT_VIOLATION 0x00000400U /*!< Attempt to program a write protect block */ -#define SDMMC_ERROR_LOCK_UNLOCK_FAILED 0x00000800U /*!< Sequence or password error has been detected in unlock - command or if there was an attempt to access a locked card */ -#define SDMMC_ERROR_COM_CRC_FAILED 0x00001000U /*!< CRC check of the previous command failed */ -#define SDMMC_ERROR_ILLEGAL_CMD 0x00002000U /*!< Command is not legal for the card state */ -#define SDMMC_ERROR_CARD_ECC_FAILED 0x00004000U /*!< Card internal ECC was applied but failed to correct the data */ -#define SDMMC_ERROR_CC_ERR 0x00008000U /*!< Internal card controller error */ -#define SDMMC_ERROR_GENERAL_UNKNOWN_ERR 0x00010000U /*!< General or unknown error */ -#define SDMMC_ERROR_STREAM_READ_UNDERRUN 0x00020000U /*!< The card could not sustain data reading in stream rmode */ -#define SDMMC_ERROR_STREAM_WRITE_OVERRUN 0x00040000U /*!< The card could not sustain data programming in stream mode */ -#define SDMMC_ERROR_CID_CSD_OVERWRITE 0x00080000U /*!< CID/CSD overwrite error */ -#define SDMMC_ERROR_WP_ERASE_SKIP 0x00100000U /*!< Only partial address space was erased */ -#define SDMMC_ERROR_CARD_ECC_DISABLED 0x00200000U /*!< Command has been executed without using internal ECC */ -#define SDMMC_ERROR_ERASE_RESET 0x00400000U /*!< Erase sequence was cleared before executing because an out - of erase sequence command was received */ -#define SDMMC_ERROR_AKE_SEQ_ERR 0x00800000U /*!< Error in sequence of authentication */ -#define SDMMC_ERROR_INVALID_VOLTRANGE 0x01000000U /*!< Error in case of invalid voltage range */ -#define SDMMC_ERROR_ADDR_OUT_OF_RANGE 0x02000000U /*!< Error when addressed block is out of range */ -#define SDMMC_ERROR_REQUEST_NOT_APPLICABLE 0x04000000U /*!< Error when command request is not applicable */ -#define SDMMC_ERROR_INVALID_PARAMETER 0x08000000U /*!< the used parameter is not valid */ -#define SDMMC_ERROR_UNSUPPORTED_FEATURE 0x10000000U /*!< Error when feature is not insupported */ -#define SDMMC_ERROR_BUSY 0x20000000U /*!< Error when transfer process is busy */ -#define SDMMC_ERROR_DMA 0x40000000U /*!< Error while DMA transfer */ -#define SDMMC_ERROR_TIMEOUT 0x80000000U /*!< Timeout error */ - -/** - * @brief SDMMC Commands Index - */ -#define SDMMC_CMD_GO_IDLE_STATE 0U /*!< Resets the SD memory card. */ -#define SDMMC_CMD_SEND_OP_COND 1U /*!< Sends host capacity support information and activates the card's initialization process. */ -#define SDMMC_CMD_ALL_SEND_CID 2U /*!< Asks any card connected to the host to send the CID numbers on the CMD line. */ -#define SDMMC_CMD_SET_REL_ADDR 3U /*!< Asks the card to publish a new relative address (RCA). */ -#define SDMMC_CMD_SET_DSR 4U /*!< Programs the DSR of all cards. */ -#define SDMMC_CMD_SDMMC_SEN_OP_COND 5U /*!< Sends host capacity support information (HCS) and asks the accessed card to send its - operating condition register (OCR) content in the response on the CMD line. */ -#define SDMMC_CMD_HS_SWITCH 6U /*!< Checks switchable function (mode 0) and switch card function (mode 1). */ -#define SDMMC_CMD_SEL_DESEL_CARD 7U /*!< Selects the card by its own relative address and gets deselected by any other address */ -#define SDMMC_CMD_HS_SEND_EXT_CSD 8U /*!< Sends SD Memory Card interface condition, which includes host supply voltage information - and asks the card whether card supports voltage. */ -#define SDMMC_CMD_SEND_CSD 9U /*!< Addressed card sends its card specific data (CSD) on the CMD line. */ -#define SDMMC_CMD_SEND_CID 10U /*!< Addressed card sends its card identification (CID) on the CMD line. */ -#define SDMMC_CMD_READ_DAT_UNTIL_STOP 11U /*!< SD card doesn't support it. */ -#define SDMMC_CMD_STOP_TRANSMISSION 12U /*!< Forces the card to stop transmission. */ -#define SDMMC_CMD_SEND_STATUS 13U /*!< Addressed card sends its status register. */ -#define SDMMC_CMD_HS_BUSTEST_READ 14U /*!< Reserved */ -#define SDMMC_CMD_GO_INACTIVE_STATE 15U /*!< Sends an addressed card into the inactive state. */ -#define SDMMC_CMD_SET_BLOCKLEN 16U /*!< Sets the block length (in bytes for SDSC) for all following block commands - (read, write, lock). Default block length is fixed to 512 Bytes. Not effective - for SDHS and SDXC. */ -#define SDMMC_CMD_READ_SINGLE_BLOCK 17U /*!< Reads single block of size selected by SET_BLOCKLEN in case of SDSC, and a block of - fixed 512 bytes in case of SDHC and SDXC. */ -#define SDMMC_CMD_READ_MULT_BLOCK 18U /*!< Continuously transfers data blocks from card to host until interrupted by - STOP_TRANSMISSION command. */ -#define SDMMC_CMD_HS_BUSTEST_WRITE 19U /*!< 64 bytes tuning pattern is sent for SDR50 and SDR104. */ -#define SDMMC_CMD_WRITE_DAT_UNTIL_STOP 20U /*!< Speed class control command. */ -#define SDMMC_CMD_SET_BLOCK_COUNT 23U /*!< Specify block count for CMD18 and CMD25. */ -#define SDMMC_CMD_WRITE_SINGLE_BLOCK 24U /*!< Writes single block of size selected by SET_BLOCKLEN in case of SDSC, and a block of - fixed 512 bytes in case of SDHC and SDXC. */ -#define SDMMC_CMD_WRITE_MULT_BLOCK 25U /*!< Continuously writes blocks of data until a STOP_TRANSMISSION follows. */ -#define SDMMC_CMD_PROG_CID 26U /*!< Reserved for manufacturers. */ -#define SDMMC_CMD_PROG_CSD 27U /*!< Programming of the programmable bits of the CSD. */ -#define SDMMC_CMD_SET_WRITE_PROT 28U /*!< Sets the write protection bit of the addressed group. */ -#define SDMMC_CMD_CLR_WRITE_PROT 29U /*!< Clears the write protection bit of the addressed group. */ -#define SDMMC_CMD_SEND_WRITE_PROT 30U /*!< Asks the card to send the status of the write protection bits. */ -#define SDMMC_CMD_SD_ERASE_GRP_START 32U /*!< Sets the address of the first write block to be erased. (For SD card only). */ -#define SDMMC_CMD_SD_ERASE_GRP_END 33U /*!< Sets the address of the last write block of the continuous range to be erased. */ -#define SDMMC_CMD_ERASE_GRP_START 35U /*!< Sets the address of the first write block to be erased. Reserved for each command - system set by switch function command (CMD6). */ -#define SDMMC_CMD_ERASE_GRP_END 36U /*!< Sets the address of the last write block of the continuous range to be erased. - Reserved for each command system set by switch function command (CMD6). */ -#define SDMMC_CMD_ERASE 38U /*!< Reserved for SD security applications. */ -#define SDMMC_CMD_FAST_IO 39U /*!< SD card doesn't support it (Reserved). */ -#define SDMMC_CMD_GO_IRQ_STATE 40U /*!< SD card doesn't support it (Reserved). */ -#define SDMMC_CMD_LOCK_UNLOCK 42U /*!< Sets/resets the password or lock/unlock the card. The size of the data block is set by - the SET_BLOCK_LEN command. */ -#define SDMMC_CMD_APP_CMD 55U /*!< Indicates to the card that the next command is an application specific command rather - than a standard command. */ -#define SDMMC_CMD_GEN_CMD 56U /*!< Used either to transfer a data block to the card or to get a data block from the card - for general purpose/application specific commands. */ -#define SDMMC_CMD_NO_CMD 64U /*!< No command */ - -/** - * @brief Following commands are SD Card Specific commands. - * SDMMC_APP_CMD should be sent before sending these commands. - */ -#define SDMMC_CMD_APP_SD_SET_BUSWIDTH 6U /*!< (ACMD6) Defines the data bus width to be used for data transfer. The allowed data bus - widths are given in SCR register. */ -#define SDMMC_CMD_SD_APP_STATUS 13U /*!< (ACMD13) Sends the SD status. */ -#define SDMMC_CMD_SD_APP_SEND_NUM_WRITE_BLOCKS 22U /*!< (ACMD22) Sends the number of the written (without errors) write blocks. Responds with - 32bit+CRC data block. */ -#define SDMMC_CMD_SD_APP_OP_COND 41U /*!< (ACMD41) Sends host capacity support information (HCS) and asks the accessed card to - send its operating condition register (OCR) content in the response on the CMD line. */ -#define SDMMC_CMD_SD_APP_SET_CLR_CARD_DETECT 42U /*!< (ACMD42) Connect/Disconnect the 50 KOhm pull-up resistor on CD/DAT3 (pin 1) of the card */ -#define SDMMC_CMD_SD_APP_SEND_SCR 51U /*!< Reads the SD Configuration Register (SCR). */ -#define SDMMC_CMD_SDMMC_RW_DIRECT 52U /*!< For SD I/O card only, reserved for security specification. */ -#define SDMMC_CMD_SDMMC_RW_EXTENDED 53U /*!< For SD I/O card only, reserved for security specification. */ - -/** - * @brief Following commands are SD Card Specific security commands. - * SDMMC_CMD_APP_CMD should be sent before sending these commands. - */ -#define SDMMC_CMD_SD_APP_GET_MKB 43U -#define SDMMC_CMD_SD_APP_GET_MID 44U -#define SDMMC_CMD_SD_APP_SET_CER_RN1 45U -#define SDMMC_CMD_SD_APP_GET_CER_RN2 46U -#define SDMMC_CMD_SD_APP_SET_CER_RES2 47U -#define SDMMC_CMD_SD_APP_GET_CER_RES1 48U -#define SDMMC_CMD_SD_APP_SECURE_READ_MULTIPLE_BLOCK 18U -#define SDMMC_CMD_SD_APP_SECURE_WRITE_MULTIPLE_BLOCK 25U -#define SDMMC_CMD_SD_APP_SECURE_ERASE 38U -#define SDMMC_CMD_SD_APP_CHANGE_SECURE_AREA 49U -#define SDMMC_CMD_SD_APP_SECURE_WRITE_MKB 48U - -/** - * @brief Masks for errors Card Status R1 (OCR Register) - */ -#define SDMMC_OCR_ADDR_OUT_OF_RANGE 0x80000000U -#define SDMMC_OCR_ADDR_MISALIGNED 0x40000000U -#define SDMMC_OCR_BLOCK_LEN_ERR 0x20000000U -#define SDMMC_OCR_ERASE_SEQ_ERR 0x10000000U -#define SDMMC_OCR_BAD_ERASE_PARAM 0x08000000U -#define SDMMC_OCR_WRITE_PROT_VIOLATION 0x04000000U -#define SDMMC_OCR_LOCK_UNLOCK_FAILED 0x01000000U -#define SDMMC_OCR_COM_CRC_FAILED 0x00800000U -#define SDMMC_OCR_ILLEGAL_CMD 0x00400000U -#define SDMMC_OCR_CARD_ECC_FAILED 0x00200000U -#define SDMMC_OCR_CC_ERROR 0x00100000U -#define SDMMC_OCR_GENERAL_UNKNOWN_ERROR 0x00080000U -#define SDMMC_OCR_STREAM_READ_UNDERRUN 0x00040000U -#define SDMMC_OCR_STREAM_WRITE_OVERRUN 0x00020000U -#define SDMMC_OCR_CID_CSD_OVERWRITE 0x00010000U -#define SDMMC_OCR_WP_ERASE_SKIP 0x00008000U -#define SDMMC_OCR_CARD_ECC_DISABLED 0x00004000U -#define SDMMC_OCR_ERASE_RESET 0x00002000U -#define SDMMC_OCR_AKE_SEQ_ERROR 0x00000008U -#define SDMMC_OCR_ERRORBITS 0xFDFFE008U - -/** - * @brief Masks for R6 Response - */ -#define SDMMC_R6_GENERAL_UNKNOWN_ERROR 0x00002000U -#define SDMMC_R6_ILLEGAL_CMD 0x00004000U -#define SDMMC_R6_COM_CRC_FAILED 0x00008000U - -#define SDMMC_VOLTAGE_WINDOW_SD 0x80100000U -#define SDMMC_HIGH_CAPACITY 0x40000000U -#define SDMMC_STD_CAPACITY 0x00000000U -#define SDMMC_CHECK_PATTERN 0x000001AAU -#define SD_SWITCH_1_8V_CAPACITY 0x01000000U - -#define SDMMC_MAX_VOLT_TRIAL 0x0000FFFFU - -#define SDMMC_MAX_TRIAL 0x0000FFFFU - -#define SDMMC_ALLZERO 0x00000000U - -#define SDMMC_WIDE_BUS_SUPPORT 0x00040000U -#define SDMMC_SINGLE_BUS_SUPPORT 0x00010000U -#define SDMMC_CARD_LOCKED 0x02000000U - -#ifndef SDMMC_DATATIMEOUT -#define SDMMC_DATATIMEOUT 0xFFFFFFFFU -#endif /* SDMMC_DATATIMEOUT */ - -#define SDMMC_0TO7BITS 0x000000FFU -#define SDMMC_8TO15BITS 0x0000FF00U -#define SDMMC_16TO23BITS 0x00FF0000U -#define SDMMC_24TO31BITS 0xFF000000U -#define SDMMC_MAX_DATA_LENGTH 0x01FFFFFFU - -#define SDMMC_HALFFIFO 0x00000008U -#define SDMMC_HALFFIFOBYTES 0x00000020U - -/** - * @brief Command Class supported - */ -#define SDIO_CCCC_ERASE 0x00000020U - -#define SDIO_CMDTIMEOUT 5000U /* Command send and response timeout */ -#define SDIO_MAXERASETIMEOUT 63000U /* Max erase Timeout 63 s */ -#define SDIO_STOPTRANSFERTIMEOUT 100000000U /* Timeout for STOP TRANSMISSION command */ - -/** @defgroup SDIO_LL_Clock_Edge Clock Edge - * @{ - */ -#define SDIO_CLOCK_EDGE_RISING 0x00000000U -#define SDIO_CLOCK_EDGE_FALLING SDIO_CLKCR_NEGEDGE - -#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_CLOCK_EDGE_RISING) || \ - ((EDGE) == SDIO_CLOCK_EDGE_FALLING)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Clock_Bypass Clock Bypass - * @{ - */ -#define SDIO_CLOCK_BYPASS_DISABLE 0x00000000U -#define SDIO_CLOCK_BYPASS_ENABLE SDIO_CLKCR_BYPASS - -#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_CLOCK_BYPASS_DISABLE) || \ - ((BYPASS) == SDIO_CLOCK_BYPASS_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Clock_Power_Save Clock Power Saving - * @{ - */ -#define SDIO_CLOCK_POWER_SAVE_DISABLE 0x00000000U -#define SDIO_CLOCK_POWER_SAVE_ENABLE SDIO_CLKCR_PWRSAV - -#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_CLOCK_POWER_SAVE_DISABLE) || \ - ((SAVE) == SDIO_CLOCK_POWER_SAVE_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Bus_Wide Bus Width - * @{ - */ -#define SDIO_BUS_WIDE_1B 0x00000000U -#define SDIO_BUS_WIDE_4B SDIO_CLKCR_WIDBUS_0 -#define SDIO_BUS_WIDE_8B SDIO_CLKCR_WIDBUS_1 - -#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BUS_WIDE_1B) || \ - ((WIDE) == SDIO_BUS_WIDE_4B) || \ - ((WIDE) == SDIO_BUS_WIDE_8B)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Hardware_Flow_Control Hardware Flow Control - * @{ - */ -#define SDIO_HARDWARE_FLOW_CONTROL_DISABLE 0x00000000U -#define SDIO_HARDWARE_FLOW_CONTROL_ENABLE SDIO_CLKCR_HWFC_EN - -#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HARDWARE_FLOW_CONTROL_DISABLE) || \ - ((CONTROL) == SDIO_HARDWARE_FLOW_CONTROL_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Clock_Division Clock Division - * @{ - */ -#define IS_SDIO_CLKDIV(DIV) ((DIV) <= 0xFFU) -/** - * @} - */ - -/** @defgroup SDIO_LL_Command_Index Command Index - * @{ - */ -#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40U) -/** - * @} - */ - -/** @defgroup SDIO_LL_Response_Type Response Type - * @{ - */ -#define SDIO_RESPONSE_NO 0x00000000U -#define SDIO_RESPONSE_SHORT SDIO_CMD_WAITRESP_0 -#define SDIO_RESPONSE_LONG SDIO_CMD_WAITRESP - -#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_RESPONSE_NO) || \ - ((RESPONSE) == SDIO_RESPONSE_SHORT) || \ - ((RESPONSE) == SDIO_RESPONSE_LONG)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Wait_Interrupt_State Wait Interrupt - * @{ - */ -#define SDIO_WAIT_NO 0x00000000U -#define SDIO_WAIT_IT SDIO_CMD_WAITINT -#define SDIO_WAIT_PEND SDIO_CMD_WAITPEND - -#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_WAIT_NO) || \ - ((WAIT) == SDIO_WAIT_IT) || \ - ((WAIT) == SDIO_WAIT_PEND)) -/** - * @} - */ - -/** @defgroup SDIO_LL_CPSM_State CPSM State - * @{ - */ -#define SDIO_CPSM_DISABLE 0x00000000U -#define SDIO_CPSM_ENABLE SDIO_CMD_CPSMEN - -#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_DISABLE) || \ - ((CPSM) == SDIO_CPSM_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Response_Registers Response Register - * @{ - */ -#define SDIO_RESP1 0x00000000U -#define SDIO_RESP2 0x00000004U -#define SDIO_RESP3 0x00000008U -#define SDIO_RESP4 0x0000000CU - -#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || \ - ((RESP) == SDIO_RESP2) || \ - ((RESP) == SDIO_RESP3) || \ - ((RESP) == SDIO_RESP4)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Data_Length Data Length - * @{ - */ -#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFFU) -/** - * @} - */ - -/** @defgroup SDIO_LL_Data_Block_Size Data Block Size - * @{ - */ -#define SDIO_DATABLOCK_SIZE_1B 0x00000000U -#define SDIO_DATABLOCK_SIZE_2B SDIO_DCTRL_DBLOCKSIZE_0 -#define SDIO_DATABLOCK_SIZE_4B SDIO_DCTRL_DBLOCKSIZE_1 -#define SDIO_DATABLOCK_SIZE_8B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_1) -#define SDIO_DATABLOCK_SIZE_16B SDIO_DCTRL_DBLOCKSIZE_2 -#define SDIO_DATABLOCK_SIZE_32B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_2) -#define SDIO_DATABLOCK_SIZE_64B (SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_2) -#define SDIO_DATABLOCK_SIZE_128B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_2) -#define SDIO_DATABLOCK_SIZE_256B SDIO_DCTRL_DBLOCKSIZE_3 -#define SDIO_DATABLOCK_SIZE_512B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_1024B (SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_2048B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_4096B (SDIO_DCTRL_DBLOCKSIZE_2|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_8192B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_2|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_16384B (SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_2|SDIO_DCTRL_DBLOCKSIZE_3) - -#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DATABLOCK_SIZE_1B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_2B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_4B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_8B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_16B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_32B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_64B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_128B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_256B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_512B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_1024B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_2048B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_4096B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_8192B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_16384B)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Transfer_Direction Transfer Direction - * @{ - */ -#define SDIO_TRANSFER_DIR_TO_CARD 0x00000000U -#define SDIO_TRANSFER_DIR_TO_SDIO SDIO_DCTRL_DTDIR - -#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TRANSFER_DIR_TO_CARD) || \ - ((DIR) == SDIO_TRANSFER_DIR_TO_SDIO)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Transfer_Type Transfer Type - * @{ - */ -#define SDIO_TRANSFER_MODE_BLOCK 0x00000000U -#define SDIO_TRANSFER_MODE_STREAM SDIO_DCTRL_DTMODE - -#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TRANSFER_MODE_BLOCK) || \ - ((MODE) == SDIO_TRANSFER_MODE_STREAM)) -/** - * @} - */ - -/** @defgroup SDIO_LL_DPSM_State DPSM State - * @{ - */ -#define SDIO_DPSM_DISABLE 0x00000000U -#define SDIO_DPSM_ENABLE SDIO_DCTRL_DTEN - -#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_DISABLE) ||\ - ((DPSM) == SDIO_DPSM_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Read_Wait_Mode Read Wait Mode - * @{ - */ -#define SDIO_READ_WAIT_MODE_DATA2 0x00000000U -#define SDIO_READ_WAIT_MODE_CLK (SDIO_DCTRL_RWMOD) - -#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_READ_WAIT_MODE_CLK) || \ - ((MODE) == SDIO_READ_WAIT_MODE_DATA2)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Interrupt_sources Interrupt Sources - * @{ - */ -#define SDIO_IT_CCRCFAIL SDIO_MASK_CCRCFAILIE -#define SDIO_IT_DCRCFAIL SDIO_MASK_DCRCFAILIE -#define SDIO_IT_CTIMEOUT SDIO_MASK_CTIMEOUTIE -#define SDIO_IT_DTIMEOUT SDIO_MASK_DTIMEOUTIE -#define SDIO_IT_TXUNDERR SDIO_MASK_TXUNDERRIE -#define SDIO_IT_RXOVERR SDIO_MASK_RXOVERRIE -#define SDIO_IT_CMDREND SDIO_MASK_CMDRENDIE -#define SDIO_IT_CMDSENT SDIO_MASK_CMDSENTIE -#define SDIO_IT_DATAEND SDIO_MASK_DATAENDIE -#if defined(SDIO_STA_STBITERR) -#define SDIO_IT_STBITERR SDIO_MASK_STBITERRIE -#endif -#define SDIO_IT_DBCKEND SDIO_MASK_DBCKENDIE -#define SDIO_IT_CMDACT SDIO_MASK_CMDACTIE -#define SDIO_IT_TXACT SDIO_MASK_TXACTIE -#define SDIO_IT_RXACT SDIO_MASK_RXACTIE -#define SDIO_IT_TXFIFOHE SDIO_MASK_TXFIFOHEIE -#define SDIO_IT_RXFIFOHF SDIO_MASK_RXFIFOHFIE -#define SDIO_IT_TXFIFOF SDIO_MASK_TXFIFOFIE -#define SDIO_IT_RXFIFOF SDIO_MASK_RXFIFOFIE -#define SDIO_IT_TXFIFOE SDIO_MASK_TXFIFOEIE -#define SDIO_IT_RXFIFOE SDIO_MASK_RXFIFOEIE -#define SDIO_IT_TXDAVL SDIO_MASK_TXDAVLIE -#define SDIO_IT_RXDAVL SDIO_MASK_RXDAVLIE -#define SDIO_IT_SDIOIT SDIO_MASK_SDIOITIE -#if defined(SDIO_CMD_CEATACMD) -#define SDIO_IT_CEATAEND SDIO_MASK_CEATAENDIE -#endif -/** - * @} - */ - -/** @defgroup SDIO_LL_Flags Flags - * @{ - */ -#define SDIO_FLAG_CCRCFAIL SDIO_STA_CCRCFAIL -#define SDIO_FLAG_DCRCFAIL SDIO_STA_DCRCFAIL -#define SDIO_FLAG_CTIMEOUT SDIO_STA_CTIMEOUT -#define SDIO_FLAG_DTIMEOUT SDIO_STA_DTIMEOUT -#define SDIO_FLAG_TXUNDERR SDIO_STA_TXUNDERR -#define SDIO_FLAG_RXOVERR SDIO_STA_RXOVERR -#define SDIO_FLAG_CMDREND SDIO_STA_CMDREND -#define SDIO_FLAG_CMDSENT SDIO_STA_CMDSENT -#define SDIO_FLAG_DATAEND SDIO_STA_DATAEND -#if defined(SDIO_STA_STBITERR) -#define SDIO_FLAG_STBITERR SDIO_STA_STBITERR -#endif -#define SDIO_FLAG_DBCKEND SDIO_STA_DBCKEND -#define SDIO_FLAG_CMDACT SDIO_STA_CMDACT -#define SDIO_FLAG_TXACT SDIO_STA_TXACT -#define SDIO_FLAG_RXACT SDIO_STA_RXACT -#define SDIO_FLAG_TXFIFOHE SDIO_STA_TXFIFOHE -#define SDIO_FLAG_RXFIFOHF SDIO_STA_RXFIFOHF -#define SDIO_FLAG_TXFIFOF SDIO_STA_TXFIFOF -#define SDIO_FLAG_RXFIFOF SDIO_STA_RXFIFOF -#define SDIO_FLAG_TXFIFOE SDIO_STA_TXFIFOE -#define SDIO_FLAG_RXFIFOE SDIO_STA_RXFIFOE -#define SDIO_FLAG_TXDAVL SDIO_STA_TXDAVL -#define SDIO_FLAG_RXDAVL SDIO_STA_RXDAVL -#define SDIO_FLAG_SDIOIT SDIO_STA_SDIOIT -#if defined(SDIO_CMD_CEATACMD) -#define SDIO_FLAG_CEATAEND SDIO_STA_CEATAEND -#endif -#define SDIO_STATIC_FLAGS ((uint32_t)(SDIO_FLAG_CCRCFAIL | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_CTIMEOUT |\ - SDIO_FLAG_DTIMEOUT | SDIO_FLAG_TXUNDERR | SDIO_FLAG_RXOVERR |\ - SDIO_FLAG_CMDREND | SDIO_FLAG_CMDSENT | SDIO_FLAG_DATAEND |\ - SDIO_FLAG_DBCKEND | SDIO_FLAG_SDIOIT)) - -#define SDIO_STATIC_CMD_FLAGS ((uint32_t)(SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CTIMEOUT | SDIO_FLAG_CMDREND |\ - SDIO_FLAG_CMDSENT)) - -#define SDIO_STATIC_DATA_FLAGS ((uint32_t)(SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_TXUNDERR |\ - SDIO_FLAG_RXOVERR | SDIO_FLAG_DATAEND | SDIO_FLAG_DBCKEND)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SDIO_LL_Exported_macros SDIO_LL Exported Macros - * @{ - */ - -/** @defgroup SDMMC_LL_Alias_Region Bit Address in the alias region - * @{ - */ -/* ------------ SDIO registers bit address in the alias region -------------- */ -#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE) - -/* --- CLKCR Register ---*/ -/* Alias word address of CLKEN bit */ -#define CLKCR_OFFSET (SDIO_OFFSET + 0x04U) -#define CLKEN_BITNUMBER 0x08U -#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32U) + (CLKEN_BITNUMBER * 4U)) - -/* --- CMD Register ---*/ -/* Alias word address of SDIOSUSPEND bit */ -#define CMD_OFFSET (SDIO_OFFSET + 0x0CU) -#define SDIOSUSPEND_BITNUMBER 0x0BU -#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32U) + (SDIOSUSPEND_BITNUMBER * 4U)) - -/* Alias word address of ENCMDCOMPL bit */ -#define ENCMDCOMPL_BITNUMBER 0x0CU -#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32U) + (ENCMDCOMPL_BITNUMBER * 4U)) - -/* Alias word address of NIEN bit */ -#define NIEN_BITNUMBER 0x0DU -#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32U) + (NIEN_BITNUMBER * 4U)) - -/* Alias word address of ATACMD bit */ -#define ATACMD_BITNUMBER 0x0EU -#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32U) + (ATACMD_BITNUMBER * 4U)) - -/* --- DCTRL Register ---*/ -/* Alias word address of DMAEN bit */ -#define DCTRL_OFFSET (SDIO_OFFSET + 0x2CU) -#define DMAEN_BITNUMBER 0x03U -#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (DMAEN_BITNUMBER * 4U)) - -/* Alias word address of RWSTART bit */ -#define RWSTART_BITNUMBER 0x08U -#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (RWSTART_BITNUMBER * 4U)) - -/* Alias word address of RWSTOP bit */ -#define RWSTOP_BITNUMBER 0x09U -#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (RWSTOP_BITNUMBER * 4U)) - -/* Alias word address of RWMOD bit */ -#define RWMOD_BITNUMBER 0x0AU -#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (RWMOD_BITNUMBER * 4U)) - -/* Alias word address of SDIOEN bit */ -#define SDIOEN_BITNUMBER 0x0BU -#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (SDIOEN_BITNUMBER * 4U)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Register Bits And Addresses Definitions - * @brief SDIO_LL registers bit address in the alias region - * @{ - */ -/* ---------------------- SDIO registers bit mask --------------------------- */ -/* --- CLKCR Register ---*/ -/* CLKCR register clear mask */ -#define CLKCR_CLEAR_MASK ((uint32_t)(SDIO_CLKCR_CLKDIV | SDIO_CLKCR_PWRSAV |\ - SDIO_CLKCR_BYPASS | SDIO_CLKCR_WIDBUS |\ - SDIO_CLKCR_NEGEDGE | SDIO_CLKCR_HWFC_EN)) - -/* --- DCTRL Register ---*/ -/* SDIO DCTRL Clear Mask */ -#define DCTRL_CLEAR_MASK ((uint32_t)(SDIO_DCTRL_DTEN | SDIO_DCTRL_DTDIR |\ - SDIO_DCTRL_DTMODE | SDIO_DCTRL_DBLOCKSIZE)) - -/* --- CMD Register ---*/ -/* CMD Register clear mask */ -#define CMD_CLEAR_MASK ((uint32_t)(SDIO_CMD_CMDINDEX | SDIO_CMD_WAITRESP |\ - SDIO_CMD_WAITINT | SDIO_CMD_WAITPEND |\ - SDIO_CMD_CPSMEN | SDIO_CMD_SDIOSUSPEND)) - -/* SDIO Initialization Frequency (400KHz max) */ -#define SDIO_INIT_CLK_DIV ((uint8_t)0x76) /* 48MHz / (SDMMC_INIT_CLK_DIV + 2) < 400KHz */ - -/* SDIO Data Transfer Frequency (25MHz max) */ -#define SDIO_TRANSFER_CLK_DIV ((uint8_t)0x0) /* 48MHz / (SDMMC_TRANSFER_CLK_DIV + 2) < 25MHz */ -/** - * @} - */ - -/** @defgroup SDIO_LL_Interrupt_Clock Interrupt And Clock Configuration - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ - -/** - * @brief Enable the SDIO device. - * @param __INSTANCE__: SDIO Instance - * @retval None - */ -#define __SDIO_ENABLE(__INSTANCE__) (*(__IO uint32_t *)CLKCR_CLKEN_BB = ENABLE) - -/** - * @brief Disable the SDIO device. - * @param __INSTANCE__: SDIO Instance - * @retval None - */ -#define __SDIO_DISABLE(__INSTANCE__) (*(__IO uint32_t *)CLKCR_CLKEN_BB = DISABLE) - -/** - * @brief Enable the SDIO DMA transfer. - * @param __INSTANCE__: SDIO Instance - * @retval None - */ -#define __SDIO_DMA_ENABLE(__INSTANCE__) (*(__IO uint32_t *)DCTRL_DMAEN_BB = ENABLE) - -/** - * @brief Disable the SDIO DMA transfer. - * @param __INSTANCE__: SDIO Instance - * @retval None - */ -#define __SDIO_DMA_DISABLE(__INSTANCE__) (*(__IO uint32_t *)DCTRL_DMAEN_BB = DISABLE) - -/** - * @brief Enable the SDIO device interrupt. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __INTERRUPT__ : specifies the SDIO interrupt sources to be enabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __SDIO_ENABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->MASK |= (__INTERRUPT__)) - -/** - * @brief Disable the SDIO device interrupt. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __INTERRUPT__ : specifies the SDIO interrupt sources to be disabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __SDIO_DISABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->MASK &= ~(__INTERRUPT__)) - -/** - * @brief Checks whether the specified SDIO flag is set or not. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __FLAG__: specifies the flag to check. - * This parameter can be one of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_CMDACT: Command transfer in progress - * @arg SDIO_FLAG_TXACT: Data transmit in progress - * @arg SDIO_FLAG_RXACT: Data receive in progress - * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty - * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full - * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full - * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full - * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty - * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty - * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO - * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO - * @arg SDIO_FLAG_SDIOIT: SDIO interrupt received - * @retval The new state of SDIO_FLAG (SET or RESET). - */ -#define __SDIO_GET_FLAG(__INSTANCE__, __FLAG__) (((__INSTANCE__)->STA &(__FLAG__)) != 0U) - - -/** - * @brief Clears the SDIO pending flags. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __FLAG__: specifies the flag to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_SDIOIT: SDIO interrupt received - * @retval None - */ -#define __SDIO_CLEAR_FLAG(__INSTANCE__, __FLAG__) ((__INSTANCE__)->ICR = (__FLAG__)) - -/** - * @brief Checks whether the specified SDIO interrupt has occurred or not. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __INTERRUPT__: specifies the SDIO interrupt source to check. - * This parameter can be one of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval The new state of SDIO_IT (SET or RESET). - */ -#define __SDIO_GET_IT (__INSTANCE__, __INTERRUPT__) (((__INSTANCE__)->STA &(__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @brief Clears the SDIO's interrupt pending bits. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __INTERRUPT__: specifies the interrupt pending bit to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __SDIO_CLEAR_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->ICR = (__INTERRUPT__)) - -/** - * @brief Enable Start the SD I/O Read Wait operation. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_START_READWAIT_ENABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_RWSTART_BB = ENABLE) - -/** - * @brief Disable Start the SD I/O Read Wait operations. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_START_READWAIT_DISABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_RWSTART_BB = DISABLE) - -/** - * @brief Enable Start the SD I/O Read Wait operation. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_STOP_READWAIT_ENABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_RWSTOP_BB = ENABLE) - -/** - * @brief Disable Stop the SD I/O Read Wait operations. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_STOP_READWAIT_DISABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_RWSTOP_BB = DISABLE) - -/** - * @brief Enable the SD I/O Mode Operation. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_OPERATION_ENABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_SDIOEN_BB = ENABLE) - -/** - * @brief Disable the SD I/O Mode Operation. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_OPERATION_DISABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_SDIOEN_BB = DISABLE) - -/** - * @brief Enable the SD I/O Suspend command sending. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_SUSPEND_CMD_ENABLE(__INSTANCE__) (*(__IO uint32_t *) CMD_SDIOSUSPEND_BB = ENABLE) - -/** - * @brief Disable the SD I/O Suspend command sending. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_SUSPEND_CMD_DISABLE(__INSTANCE__) (*(__IO uint32_t *) CMD_SDIOSUSPEND_BB = DISABLE) - -#if defined(SDIO_CMD_CEATACMD) -/** - * @brief Enable the command completion signal. - * @retval None - */ -#define __SDIO_CEATA_CMD_COMPLETION_ENABLE() (*(__IO uint32_t *) CMD_ENCMDCOMPL_BB = ENABLE) - -/** - * @brief Disable the command completion signal. - * @retval None - */ -#define __SDIO_CEATA_CMD_COMPLETION_DISABLE() (*(__IO uint32_t *) CMD_ENCMDCOMPL_BB = DISABLE) - -/** - * @brief Enable the CE-ATA interrupt. - * @retval None - */ -#define __SDIO_CEATA_ENABLE_IT() (*(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)0U) - -/** - * @brief Disable the CE-ATA interrupt. - * @retval None - */ -#define __SDIO_CEATA_DISABLE_IT() (*(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)1U) - -/** - * @brief Enable send CE-ATA command (CMD61). - * @retval None - */ -#define __SDIO_CEATA_SENDCMD_ENABLE() (*(__IO uint32_t *) CMD_ATACMD_BB = ENABLE) - -/** - * @brief Disable send CE-ATA command (CMD61). - * @retval None - */ -#define __SDIO_CEATA_SENDCMD_DISABLE() (*(__IO uint32_t *) CMD_ATACMD_BB = DISABLE) - -#endif -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SDMMC_LL_Exported_Functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -/** @addtogroup HAL_SDMMC_LL_Group1 - * @{ - */ -HAL_StatusTypeDef SDIO_Init(SDIO_TypeDef *SDIOx, SDIO_InitTypeDef Init); -/** - * @} - */ - -/* I/O operation functions *****************************************************/ -/** @addtogroup HAL_SDMMC_LL_Group2 - * @{ - */ -uint32_t SDIO_ReadFIFO(SDIO_TypeDef *SDIOx); -HAL_StatusTypeDef SDIO_WriteFIFO(SDIO_TypeDef *SDIOx, uint32_t *pWriteData); -/** - * @} - */ - -/* Peripheral Control functions ************************************************/ -/** @addtogroup HAL_SDMMC_LL_Group3 - * @{ - */ -HAL_StatusTypeDef SDIO_PowerState_ON(SDIO_TypeDef *SDIOx); -HAL_StatusTypeDef SDIO_PowerState_OFF(SDIO_TypeDef *SDIOx); -uint32_t SDIO_GetPowerState(SDIO_TypeDef *SDIOx); - -/* Command path state machine (CPSM) management functions */ -HAL_StatusTypeDef SDIO_SendCommand(SDIO_TypeDef *SDIOx, SDIO_CmdInitTypeDef *Command); -uint8_t SDIO_GetCommandResponse(SDIO_TypeDef *SDIOx); -uint32_t SDIO_GetResponse(SDIO_TypeDef *SDIOx, uint32_t Response); - -/* Data path state machine (DPSM) management functions */ -HAL_StatusTypeDef SDIO_ConfigData(SDIO_TypeDef *SDIOx, SDIO_DataInitTypeDef* Data); -uint32_t SDIO_GetDataCounter(SDIO_TypeDef *SDIOx); -uint32_t SDIO_GetFIFOCount(SDIO_TypeDef *SDIOx); - -/* SDMMC Cards mode management functions */ -HAL_StatusTypeDef SDIO_SetSDMMCReadWaitMode(SDIO_TypeDef *SDIOx, uint32_t SDIO_ReadWaitMode); - -/* SDMMC Commands management functions */ -uint32_t SDMMC_CmdBlockLength(SDIO_TypeDef *SDIOx, uint32_t BlockSize); -uint32_t SDMMC_CmdReadSingleBlock(SDIO_TypeDef *SDIOx, uint32_t ReadAdd); -uint32_t SDMMC_CmdReadMultiBlock(SDIO_TypeDef *SDIOx, uint32_t ReadAdd); -uint32_t SDMMC_CmdWriteSingleBlock(SDIO_TypeDef *SDIOx, uint32_t WriteAdd); -uint32_t SDMMC_CmdWriteMultiBlock(SDIO_TypeDef *SDIOx, uint32_t WriteAdd); -uint32_t SDMMC_CmdEraseStartAdd(SDIO_TypeDef *SDIOx, uint32_t StartAdd); -uint32_t SDMMC_CmdSDEraseStartAdd(SDIO_TypeDef *SDIOx, uint32_t StartAdd); -uint32_t SDMMC_CmdEraseEndAdd(SDIO_TypeDef *SDIOx, uint32_t EndAdd); -uint32_t SDMMC_CmdSDEraseEndAdd(SDIO_TypeDef *SDIOx, uint32_t EndAdd); -uint32_t SDMMC_CmdErase(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdStopTransfer(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdSelDesel(SDIO_TypeDef *SDIOx, uint64_t Addr); -uint32_t SDMMC_CmdGoIdleState(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdOperCond(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdAppCommand(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdAppOperCommand(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdBusWidth(SDIO_TypeDef *SDIOx, uint32_t BusWidth); -uint32_t SDMMC_CmdSendSCR(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdSendCID(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdSendCSD(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdSendEXTCSD(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdSetRelAdd(SDIO_TypeDef *SDIOx, uint16_t *pRCA); -uint32_t SDMMC_CmdSendStatus(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdStatusRegister(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdOpCondition(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdSwitch(SDIO_TypeDef *SDIOx, uint32_t Argument); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* SDIO */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_SDMMC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h deleted file mode 100644 index d7ef2f6b1f9dd96..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h +++ /dev/null @@ -1,2029 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_spi.h - * @author MCD Application Team - * @brief Header file of SPI LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_SPI_H -#define STM32F4xx_LL_SPI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) - -/** @defgroup SPI_LL SPI - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup SPI_LL_ES_INIT SPI Exported Init structure - * @{ - */ - -/** - * @brief SPI Init structures definition - */ -typedef struct -{ - uint32_t TransferDirection; /*!< Specifies the SPI unidirectional or bidirectional data mode. - This parameter can be a value of @ref SPI_LL_EC_TRANSFER_MODE. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetTransferDirection().*/ - - uint32_t Mode; /*!< Specifies the SPI mode (Master/Slave). - This parameter can be a value of @ref SPI_LL_EC_MODE. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetMode().*/ - - uint32_t DataWidth; /*!< Specifies the SPI data width. - This parameter can be a value of @ref SPI_LL_EC_DATAWIDTH. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetDataWidth().*/ - - uint32_t ClockPolarity; /*!< Specifies the serial clock steady state. - This parameter can be a value of @ref SPI_LL_EC_POLARITY. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetClockPolarity().*/ - - uint32_t ClockPhase; /*!< Specifies the clock active edge for the bit capture. - This parameter can be a value of @ref SPI_LL_EC_PHASE. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetClockPhase().*/ - - uint32_t NSS; /*!< Specifies whether the NSS signal is managed by hardware (NSS pin) or by software using the SSI bit. - This parameter can be a value of @ref SPI_LL_EC_NSS_MODE. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetNSSMode().*/ - - uint32_t BaudRate; /*!< Specifies the BaudRate prescaler value which will be used to configure the transmit and receive SCK clock. - This parameter can be a value of @ref SPI_LL_EC_BAUDRATEPRESCALER. - @note The communication clock is derived from the master clock. The slave clock does not need to be set. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetBaudRatePrescaler().*/ - - uint32_t BitOrder; /*!< Specifies whether data transfers start from MSB or LSB bit. - This parameter can be a value of @ref SPI_LL_EC_BIT_ORDER. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetTransferBitOrder().*/ - - uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not. - This parameter can be a value of @ref SPI_LL_EC_CRC_CALCULATION. - - This feature can be modified afterwards using unitary functions @ref LL_SPI_EnableCRC() and @ref LL_SPI_DisableCRC().*/ - - uint32_t CRCPoly; /*!< Specifies the polynomial used for the CRC calculation. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFF. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetCRCPolynomial().*/ - -} LL_SPI_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SPI_LL_Exported_Constants SPI Exported Constants - * @{ - */ - -/** @defgroup SPI_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_SPI_ReadReg function - * @{ - */ -#define LL_SPI_SR_RXNE SPI_SR_RXNE /*!< Rx buffer not empty flag */ -#define LL_SPI_SR_TXE SPI_SR_TXE /*!< Tx buffer empty flag */ -#define LL_SPI_SR_BSY SPI_SR_BSY /*!< Busy flag */ -#define LL_SPI_SR_CRCERR SPI_SR_CRCERR /*!< CRC error flag */ -#define LL_SPI_SR_MODF SPI_SR_MODF /*!< Mode fault flag */ -#define LL_SPI_SR_OVR SPI_SR_OVR /*!< Overrun flag */ -#define LL_SPI_SR_FRE SPI_SR_FRE /*!< TI mode frame format error flag */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_SPI_ReadReg and LL_SPI_WriteReg functions - * @{ - */ -#define LL_SPI_CR2_RXNEIE SPI_CR2_RXNEIE /*!< Rx buffer not empty interrupt enable */ -#define LL_SPI_CR2_TXEIE SPI_CR2_TXEIE /*!< Tx buffer empty interrupt enable */ -#define LL_SPI_CR2_ERRIE SPI_CR2_ERRIE /*!< Error interrupt enable */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_MODE Operation Mode - * @{ - */ -#define LL_SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI) /*!< Master configuration */ -#define LL_SPI_MODE_SLAVE 0x00000000U /*!< Slave configuration */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_PROTOCOL Serial Protocol - * @{ - */ -#define LL_SPI_PROTOCOL_MOTOROLA 0x00000000U /*!< Motorola mode. Used as default value */ -#define LL_SPI_PROTOCOL_TI (SPI_CR2_FRF) /*!< TI mode */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_PHASE Clock Phase - * @{ - */ -#define LL_SPI_PHASE_1EDGE 0x00000000U /*!< First clock transition is the first data capture edge */ -#define LL_SPI_PHASE_2EDGE (SPI_CR1_CPHA) /*!< Second clock transition is the first data capture edge */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_POLARITY Clock Polarity - * @{ - */ -#define LL_SPI_POLARITY_LOW 0x00000000U /*!< Clock to 0 when idle */ -#define LL_SPI_POLARITY_HIGH (SPI_CR1_CPOL) /*!< Clock to 1 when idle */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_BAUDRATEPRESCALER Baud Rate Prescaler - * @{ - */ -#define LL_SPI_BAUDRATEPRESCALER_DIV2 0x00000000U /*!< BaudRate control equal to fPCLK/2 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV4 (SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/4 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV8 (SPI_CR1_BR_1) /*!< BaudRate control equal to fPCLK/8 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV16 (SPI_CR1_BR_1 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/16 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV32 (SPI_CR1_BR_2) /*!< BaudRate control equal to fPCLK/32 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV64 (SPI_CR1_BR_2 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/64 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV128 (SPI_CR1_BR_2 | SPI_CR1_BR_1) /*!< BaudRate control equal to fPCLK/128 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/256 */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_BIT_ORDER Transmission Bit Order - * @{ - */ -#define LL_SPI_LSB_FIRST (SPI_CR1_LSBFIRST) /*!< Data is transmitted/received with the LSB first */ -#define LL_SPI_MSB_FIRST 0x00000000U /*!< Data is transmitted/received with the MSB first */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_TRANSFER_MODE Transfer Mode - * @{ - */ -#define LL_SPI_FULL_DUPLEX 0x00000000U /*!< Full-Duplex mode. Rx and Tx transfer on 2 lines */ -#define LL_SPI_SIMPLEX_RX (SPI_CR1_RXONLY) /*!< Simplex Rx mode. Rx transfer only on 1 line */ -#define LL_SPI_HALF_DUPLEX_RX (SPI_CR1_BIDIMODE) /*!< Half-Duplex Rx mode. Rx transfer on 1 line */ -#define LL_SPI_HALF_DUPLEX_TX (SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE) /*!< Half-Duplex Tx mode. Tx transfer on 1 line */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_NSS_MODE Slave Select Pin Mode - * @{ - */ -#define LL_SPI_NSS_SOFT (SPI_CR1_SSM) /*!< NSS managed internally. NSS pin not used and free */ -#define LL_SPI_NSS_HARD_INPUT 0x00000000U /*!< NSS pin used in Input. Only used in Master mode */ -#define LL_SPI_NSS_HARD_OUTPUT (((uint32_t)SPI_CR2_SSOE << 16U)) /*!< NSS pin used in Output. Only used in Slave mode as chip select */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_DATAWIDTH Datawidth - * @{ - */ -#define LL_SPI_DATAWIDTH_8BIT 0x00000000U /*!< Data length for SPI transfer: 8 bits */ -#define LL_SPI_DATAWIDTH_16BIT (SPI_CR1_DFF) /*!< Data length for SPI transfer: 16 bits */ -/** - * @} - */ -#if defined(USE_FULL_LL_DRIVER) - -/** @defgroup SPI_LL_EC_CRC_CALCULATION CRC Calculation - * @{ - */ -#define LL_SPI_CRCCALCULATION_DISABLE 0x00000000U /*!< CRC calculation disabled */ -#define LL_SPI_CRCCALCULATION_ENABLE (SPI_CR1_CRCEN) /*!< CRC calculation enabled */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SPI_LL_Exported_Macros SPI Exported Macros - * @{ - */ - -/** @defgroup SPI_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in SPI register - * @param __INSTANCE__ SPI Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_SPI_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in SPI register - * @param __INSTANCE__ SPI Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_SPI_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SPI_LL_Exported_Functions SPI Exported Functions - * @{ - */ - -/** @defgroup SPI_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Enable SPI peripheral - * @rmtoll CR1 SPE LL_SPI_Enable - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_Enable(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR1, SPI_CR1_SPE); -} - -/** - * @brief Disable SPI peripheral - * @note When disabling the SPI, follow the procedure described in the Reference Manual. - * @rmtoll CR1 SPE LL_SPI_Disable - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_Disable(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR1, SPI_CR1_SPE); -} - -/** - * @brief Check if SPI peripheral is enabled - * @rmtoll CR1 SPE LL_SPI_IsEnabled - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabled(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR1, SPI_CR1_SPE) == (SPI_CR1_SPE)) ? 1UL : 0UL); -} - -/** - * @brief Set SPI operation mode to Master or Slave - * @note This bit should not be changed when communication is ongoing. - * @rmtoll CR1 MSTR LL_SPI_SetMode\n - * CR1 SSI LL_SPI_SetMode - * @param SPIx SPI Instance - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_SPI_MODE_MASTER - * @arg @ref LL_SPI_MODE_SLAVE - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetMode(SPI_TypeDef *SPIx, uint32_t Mode) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_MSTR | SPI_CR1_SSI, Mode); -} - -/** - * @brief Get SPI operation mode (Master or Slave) - * @rmtoll CR1 MSTR LL_SPI_GetMode\n - * CR1 SSI LL_SPI_GetMode - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_MODE_MASTER - * @arg @ref LL_SPI_MODE_SLAVE - */ -__STATIC_INLINE uint32_t LL_SPI_GetMode(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_MSTR | SPI_CR1_SSI)); -} - -/** - * @brief Set serial protocol used - * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. - * @rmtoll CR2 FRF LL_SPI_SetStandard - * @param SPIx SPI Instance - * @param Standard This parameter can be one of the following values: - * @arg @ref LL_SPI_PROTOCOL_MOTOROLA - * @arg @ref LL_SPI_PROTOCOL_TI - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetStandard(SPI_TypeDef *SPIx, uint32_t Standard) -{ - MODIFY_REG(SPIx->CR2, SPI_CR2_FRF, Standard); -} - -/** - * @brief Get serial protocol used - * @rmtoll CR2 FRF LL_SPI_GetStandard - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_PROTOCOL_MOTOROLA - * @arg @ref LL_SPI_PROTOCOL_TI - */ -__STATIC_INLINE uint32_t LL_SPI_GetStandard(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR2, SPI_CR2_FRF)); -} - -/** - * @brief Set clock phase - * @note This bit should not be changed when communication is ongoing. - * This bit is not used in SPI TI mode. - * @rmtoll CR1 CPHA LL_SPI_SetClockPhase - * @param SPIx SPI Instance - * @param ClockPhase This parameter can be one of the following values: - * @arg @ref LL_SPI_PHASE_1EDGE - * @arg @ref LL_SPI_PHASE_2EDGE - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetClockPhase(SPI_TypeDef *SPIx, uint32_t ClockPhase) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_CPHA, ClockPhase); -} - -/** - * @brief Get clock phase - * @rmtoll CR1 CPHA LL_SPI_GetClockPhase - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_PHASE_1EDGE - * @arg @ref LL_SPI_PHASE_2EDGE - */ -__STATIC_INLINE uint32_t LL_SPI_GetClockPhase(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CPHA)); -} - -/** - * @brief Set clock polarity - * @note This bit should not be changed when communication is ongoing. - * This bit is not used in SPI TI mode. - * @rmtoll CR1 CPOL LL_SPI_SetClockPolarity - * @param SPIx SPI Instance - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_SPI_POLARITY_LOW - * @arg @ref LL_SPI_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetClockPolarity(SPI_TypeDef *SPIx, uint32_t ClockPolarity) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_CPOL, ClockPolarity); -} - -/** - * @brief Get clock polarity - * @rmtoll CR1 CPOL LL_SPI_GetClockPolarity - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_POLARITY_LOW - * @arg @ref LL_SPI_POLARITY_HIGH - */ -__STATIC_INLINE uint32_t LL_SPI_GetClockPolarity(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CPOL)); -} - -/** - * @brief Set baud rate prescaler - * @note These bits should not be changed when communication is ongoing. SPI BaudRate = fPCLK/Prescaler. - * @rmtoll CR1 BR LL_SPI_SetBaudRatePrescaler - * @param SPIx SPI Instance - * @param BaudRate This parameter can be one of the following values: - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV2 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV4 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV8 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV16 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV32 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV64 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV128 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV256 - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetBaudRatePrescaler(SPI_TypeDef *SPIx, uint32_t BaudRate) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_BR, BaudRate); -} - -/** - * @brief Get baud rate prescaler - * @rmtoll CR1 BR LL_SPI_GetBaudRatePrescaler - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV2 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV4 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV8 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV16 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV32 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV64 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV128 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV256 - */ -__STATIC_INLINE uint32_t LL_SPI_GetBaudRatePrescaler(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_BR)); -} - -/** - * @brief Set transfer bit order - * @note This bit should not be changed when communication is ongoing. This bit is not used in SPI TI mode. - * @rmtoll CR1 LSBFIRST LL_SPI_SetTransferBitOrder - * @param SPIx SPI Instance - * @param BitOrder This parameter can be one of the following values: - * @arg @ref LL_SPI_LSB_FIRST - * @arg @ref LL_SPI_MSB_FIRST - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetTransferBitOrder(SPI_TypeDef *SPIx, uint32_t BitOrder) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_LSBFIRST, BitOrder); -} - -/** - * @brief Get transfer bit order - * @rmtoll CR1 LSBFIRST LL_SPI_GetTransferBitOrder - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_LSB_FIRST - * @arg @ref LL_SPI_MSB_FIRST - */ -__STATIC_INLINE uint32_t LL_SPI_GetTransferBitOrder(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_LSBFIRST)); -} - -/** - * @brief Set transfer direction mode - * @note For Half-Duplex mode, Rx Direction is set by default. - * In master mode, the MOSI pin is used and in slave mode, the MISO pin is used for Half-Duplex. - * @rmtoll CR1 RXONLY LL_SPI_SetTransferDirection\n - * CR1 BIDIMODE LL_SPI_SetTransferDirection\n - * CR1 BIDIOE LL_SPI_SetTransferDirection - * @param SPIx SPI Instance - * @param TransferDirection This parameter can be one of the following values: - * @arg @ref LL_SPI_FULL_DUPLEX - * @arg @ref LL_SPI_SIMPLEX_RX - * @arg @ref LL_SPI_HALF_DUPLEX_RX - * @arg @ref LL_SPI_HALF_DUPLEX_TX - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetTransferDirection(SPI_TypeDef *SPIx, uint32_t TransferDirection) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_RXONLY | SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE, TransferDirection); -} - -/** - * @brief Get transfer direction mode - * @rmtoll CR1 RXONLY LL_SPI_GetTransferDirection\n - * CR1 BIDIMODE LL_SPI_GetTransferDirection\n - * CR1 BIDIOE LL_SPI_GetTransferDirection - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_FULL_DUPLEX - * @arg @ref LL_SPI_SIMPLEX_RX - * @arg @ref LL_SPI_HALF_DUPLEX_RX - * @arg @ref LL_SPI_HALF_DUPLEX_TX - */ -__STATIC_INLINE uint32_t LL_SPI_GetTransferDirection(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_RXONLY | SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE)); -} - -/** - * @brief Set frame data width - * @rmtoll CR1 DFF LL_SPI_SetDataWidth - * @param SPIx SPI Instance - * @param DataWidth This parameter can be one of the following values: - * @arg @ref LL_SPI_DATAWIDTH_8BIT - * @arg @ref LL_SPI_DATAWIDTH_16BIT - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetDataWidth(SPI_TypeDef *SPIx, uint32_t DataWidth) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_DFF, DataWidth); -} - -/** - * @brief Get frame data width - * @rmtoll CR1 DFF LL_SPI_GetDataWidth - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_DATAWIDTH_8BIT - * @arg @ref LL_SPI_DATAWIDTH_16BIT - */ -__STATIC_INLINE uint32_t LL_SPI_GetDataWidth(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_DFF)); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_CRC_Management CRC Management - * @{ - */ - -/** - * @brief Enable CRC - * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. - * @rmtoll CR1 CRCEN LL_SPI_EnableCRC - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableCRC(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR1, SPI_CR1_CRCEN); -} - -/** - * @brief Disable CRC - * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. - * @rmtoll CR1 CRCEN LL_SPI_DisableCRC - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableCRC(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR1, SPI_CR1_CRCEN); -} - -/** - * @brief Check if CRC is enabled - * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. - * @rmtoll CR1 CRCEN LL_SPI_IsEnabledCRC - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledCRC(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR1, SPI_CR1_CRCEN) == (SPI_CR1_CRCEN)) ? 1UL : 0UL); -} - -/** - * @brief Set CRCNext to transfer CRC on the line - * @note This bit has to be written as soon as the last data is written in the SPIx_DR register. - * @rmtoll CR1 CRCNEXT LL_SPI_SetCRCNext - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetCRCNext(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR1, SPI_CR1_CRCNEXT); -} - -/** - * @brief Set polynomial for CRC calculation - * @rmtoll CRCPR CRCPOLY LL_SPI_SetCRCPolynomial - * @param SPIx SPI Instance - * @param CRCPoly This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetCRCPolynomial(SPI_TypeDef *SPIx, uint32_t CRCPoly) -{ - WRITE_REG(SPIx->CRCPR, (uint16_t)CRCPoly); -} - -/** - * @brief Get polynomial for CRC calculation - * @rmtoll CRCPR CRCPOLY LL_SPI_GetCRCPolynomial - * @param SPIx SPI Instance - * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF - */ -__STATIC_INLINE uint32_t LL_SPI_GetCRCPolynomial(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_REG(SPIx->CRCPR)); -} - -/** - * @brief Get Rx CRC - * @rmtoll RXCRCR RXCRC LL_SPI_GetRxCRC - * @param SPIx SPI Instance - * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF - */ -__STATIC_INLINE uint32_t LL_SPI_GetRxCRC(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_REG(SPIx->RXCRCR)); -} - -/** - * @brief Get Tx CRC - * @rmtoll TXCRCR TXCRC LL_SPI_GetTxCRC - * @param SPIx SPI Instance - * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF - */ -__STATIC_INLINE uint32_t LL_SPI_GetTxCRC(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_REG(SPIx->TXCRCR)); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_NSS_Management Slave Select Pin Management - * @{ - */ - -/** - * @brief Set NSS mode - * @note LL_SPI_NSS_SOFT Mode is not used in SPI TI mode. - * @rmtoll CR1 SSM LL_SPI_SetNSSMode\n - * @rmtoll CR2 SSOE LL_SPI_SetNSSMode - * @param SPIx SPI Instance - * @param NSS This parameter can be one of the following values: - * @arg @ref LL_SPI_NSS_SOFT - * @arg @ref LL_SPI_NSS_HARD_INPUT - * @arg @ref LL_SPI_NSS_HARD_OUTPUT - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetNSSMode(SPI_TypeDef *SPIx, uint32_t NSS) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_SSM, NSS); - MODIFY_REG(SPIx->CR2, SPI_CR2_SSOE, ((uint32_t)(NSS >> 16U))); -} - -/** - * @brief Get NSS mode - * @rmtoll CR1 SSM LL_SPI_GetNSSMode\n - * @rmtoll CR2 SSOE LL_SPI_GetNSSMode - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_NSS_SOFT - * @arg @ref LL_SPI_NSS_HARD_INPUT - * @arg @ref LL_SPI_NSS_HARD_OUTPUT - */ -__STATIC_INLINE uint32_t LL_SPI_GetNSSMode(SPI_TypeDef *SPIx) -{ - uint32_t Ssm = (READ_BIT(SPIx->CR1, SPI_CR1_SSM)); - uint32_t Ssoe = (READ_BIT(SPIx->CR2, SPI_CR2_SSOE) << 16U); - return (Ssm | Ssoe); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Check if Rx buffer is not empty - * @rmtoll SR RXNE LL_SPI_IsActiveFlag_RXNE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_RXNE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_RXNE) == (SPI_SR_RXNE)) ? 1UL : 0UL); -} - -/** - * @brief Check if Tx buffer is empty - * @rmtoll SR TXE LL_SPI_IsActiveFlag_TXE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_TXE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_TXE) == (SPI_SR_TXE)) ? 1UL : 0UL); -} - -/** - * @brief Get CRC error flag - * @rmtoll SR CRCERR LL_SPI_IsActiveFlag_CRCERR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_CRCERR(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_CRCERR) == (SPI_SR_CRCERR)) ? 1UL : 0UL); -} - -/** - * @brief Get mode fault error flag - * @rmtoll SR MODF LL_SPI_IsActiveFlag_MODF - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_MODF(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_MODF) == (SPI_SR_MODF)) ? 1UL : 0UL); -} - -/** - * @brief Get overrun error flag - * @rmtoll SR OVR LL_SPI_IsActiveFlag_OVR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_OVR(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_OVR) == (SPI_SR_OVR)) ? 1UL : 0UL); -} - -/** - * @brief Get busy flag - * @note The BSY flag is cleared under any one of the following conditions: - * -When the SPI is correctly disabled - * -When a fault is detected in Master mode (MODF bit set to 1) - * -In Master mode, when it finishes a data transmission and no new data is ready to be - * sent - * -In Slave mode, when the BSY flag is set to '0' for at least one SPI clock cycle between - * each data transfer. - * @rmtoll SR BSY LL_SPI_IsActiveFlag_BSY - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_BSY(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_BSY) == (SPI_SR_BSY)) ? 1UL : 0UL); -} - -/** - * @brief Get frame format error flag - * @rmtoll SR FRE LL_SPI_IsActiveFlag_FRE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_FRE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_FRE) == (SPI_SR_FRE)) ? 1UL : 0UL); -} - -/** - * @brief Clear CRC error flag - * @rmtoll SR CRCERR LL_SPI_ClearFlag_CRCERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_ClearFlag_CRCERR(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->SR, SPI_SR_CRCERR); -} - -/** - * @brief Clear mode fault error flag - * @note Clearing this flag is done by a read access to the SPIx_SR - * register followed by a write access to the SPIx_CR1 register - * @rmtoll SR MODF LL_SPI_ClearFlag_MODF - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_ClearFlag_MODF(SPI_TypeDef *SPIx) -{ - __IO uint32_t tmpreg_sr; - tmpreg_sr = SPIx->SR; - (void) tmpreg_sr; - CLEAR_BIT(SPIx->CR1, SPI_CR1_SPE); -} - -/** - * @brief Clear overrun error flag - * @note Clearing this flag is done by a read access to the SPIx_DR - * register followed by a read access to the SPIx_SR register - * @rmtoll SR OVR LL_SPI_ClearFlag_OVR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_ClearFlag_OVR(SPI_TypeDef *SPIx) -{ - __IO uint32_t tmpreg; - tmpreg = SPIx->DR; - (void) tmpreg; - tmpreg = SPIx->SR; - (void) tmpreg; -} - -/** - * @brief Clear frame format error flag - * @note Clearing this flag is done by reading SPIx_SR register - * @rmtoll SR FRE LL_SPI_ClearFlag_FRE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_ClearFlag_FRE(SPI_TypeDef *SPIx) -{ - __IO uint32_t tmpreg; - tmpreg = SPIx->SR; - (void) tmpreg; -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_IT_Management Interrupt Management - * @{ - */ - -/** - * @brief Enable error interrupt - * @note This bit controls the generation of an interrupt when an error condition occurs (CRCERR, OVR, MODF in SPI mode, FRE at TI mode). - * @rmtoll CR2 ERRIE LL_SPI_EnableIT_ERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableIT_ERR(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_ERRIE); -} - -/** - * @brief Enable Rx buffer not empty interrupt - * @rmtoll CR2 RXNEIE LL_SPI_EnableIT_RXNE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableIT_RXNE(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_RXNEIE); -} - -/** - * @brief Enable Tx buffer empty interrupt - * @rmtoll CR2 TXEIE LL_SPI_EnableIT_TXE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableIT_TXE(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_TXEIE); -} - -/** - * @brief Disable error interrupt - * @note This bit controls the generation of an interrupt when an error condition occurs (CRCERR, OVR, MODF in SPI mode, FRE at TI mode). - * @rmtoll CR2 ERRIE LL_SPI_DisableIT_ERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableIT_ERR(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_ERRIE); -} - -/** - * @brief Disable Rx buffer not empty interrupt - * @rmtoll CR2 RXNEIE LL_SPI_DisableIT_RXNE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableIT_RXNE(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_RXNEIE); -} - -/** - * @brief Disable Tx buffer empty interrupt - * @rmtoll CR2 TXEIE LL_SPI_DisableIT_TXE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableIT_TXE(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_TXEIE); -} - -/** - * @brief Check if error interrupt is enabled - * @rmtoll CR2 ERRIE LL_SPI_IsEnabledIT_ERR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_ERR(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_ERRIE) == (SPI_CR2_ERRIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if Rx buffer not empty interrupt is enabled - * @rmtoll CR2 RXNEIE LL_SPI_IsEnabledIT_RXNE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_RXNE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_RXNEIE) == (SPI_CR2_RXNEIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if Tx buffer empty interrupt - * @rmtoll CR2 TXEIE LL_SPI_IsEnabledIT_TXE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_TXE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_TXEIE) == (SPI_CR2_TXEIE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_DMA_Management DMA Management - * @{ - */ - -/** - * @brief Enable DMA Rx - * @rmtoll CR2 RXDMAEN LL_SPI_EnableDMAReq_RX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableDMAReq_RX(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_RXDMAEN); -} - -/** - * @brief Disable DMA Rx - * @rmtoll CR2 RXDMAEN LL_SPI_DisableDMAReq_RX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableDMAReq_RX(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_RXDMAEN); -} - -/** - * @brief Check if DMA Rx is enabled - * @rmtoll CR2 RXDMAEN LL_SPI_IsEnabledDMAReq_RX - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledDMAReq_RX(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_RXDMAEN) == (SPI_CR2_RXDMAEN)) ? 1UL : 0UL); -} - -/** - * @brief Enable DMA Tx - * @rmtoll CR2 TXDMAEN LL_SPI_EnableDMAReq_TX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableDMAReq_TX(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_TXDMAEN); -} - -/** - * @brief Disable DMA Tx - * @rmtoll CR2 TXDMAEN LL_SPI_DisableDMAReq_TX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableDMAReq_TX(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_TXDMAEN); -} - -/** - * @brief Check if DMA Tx is enabled - * @rmtoll CR2 TXDMAEN LL_SPI_IsEnabledDMAReq_TX - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledDMAReq_TX(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_TXDMAEN) == (SPI_CR2_TXDMAEN)) ? 1UL : 0UL); -} - -/** - * @brief Get the data register address used for DMA transfer - * @rmtoll DR DR LL_SPI_DMA_GetRegAddr - * @param SPIx SPI Instance - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_SPI_DMA_GetRegAddr(SPI_TypeDef *SPIx) -{ - return (uint32_t) &(SPIx->DR); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_DATA_Management DATA Management - * @{ - */ - -/** - * @brief Read 8-Bits in the data register - * @rmtoll DR DR LL_SPI_ReceiveData8 - * @param SPIx SPI Instance - * @retval RxData Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_SPI_ReceiveData8(SPI_TypeDef *SPIx) -{ - return (*((__IO uint8_t *)&SPIx->DR)); -} - -/** - * @brief Read 16-Bits in the data register - * @rmtoll DR DR LL_SPI_ReceiveData16 - * @param SPIx SPI Instance - * @retval RxData Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint16_t LL_SPI_ReceiveData16(SPI_TypeDef *SPIx) -{ - return (uint16_t)(READ_REG(SPIx->DR)); -} - -/** - * @brief Write 8-Bits in the data register - * @rmtoll DR DR LL_SPI_TransmitData8 - * @param SPIx SPI Instance - * @param TxData Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_SPI_TransmitData8(SPI_TypeDef *SPIx, uint8_t TxData) -{ -#if defined (__GNUC__) - __IO uint8_t *spidr = ((__IO uint8_t *)&SPIx->DR); - *spidr = TxData; -#else - *((__IO uint8_t *)&SPIx->DR) = TxData; -#endif /* __GNUC__ */ -} - -/** - * @brief Write 16-Bits in the data register - * @rmtoll DR DR LL_SPI_TransmitData16 - * @param SPIx SPI Instance - * @param TxData Value between Min_Data=0x00 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_SPI_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData) -{ -#if defined (__GNUC__) - __IO uint16_t *spidr = ((__IO uint16_t *)&SPIx->DR); - *spidr = TxData; -#else - SPIx->DR = TxData; -#endif /* __GNUC__ */ -} - -/** - * @} - */ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup SPI_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_SPI_DeInit(SPI_TypeDef *SPIx); -ErrorStatus LL_SPI_Init(SPI_TypeDef *SPIx, LL_SPI_InitTypeDef *SPI_InitStruct); -void LL_SPI_StructInit(LL_SPI_InitTypeDef *SPI_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup I2S_LL I2S - * @{ - */ - -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2S_LL_ES_INIT I2S Exported Init structure - * @{ - */ - -/** - * @brief I2S Init structure definition - */ - -typedef struct -{ - uint32_t Mode; /*!< Specifies the I2S operating mode. - This parameter can be a value of @ref I2S_LL_EC_MODE - - This feature can be modified afterwards using unitary function @ref LL_I2S_SetTransferMode().*/ - - uint32_t Standard; /*!< Specifies the standard used for the I2S communication. - This parameter can be a value of @ref I2S_LL_EC_STANDARD - - This feature can be modified afterwards using unitary function @ref LL_I2S_SetStandard().*/ - - - uint32_t DataFormat; /*!< Specifies the data format for the I2S communication. - This parameter can be a value of @ref I2S_LL_EC_DATA_FORMAT - - This feature can be modified afterwards using unitary function @ref LL_I2S_SetDataFormat().*/ - - - uint32_t MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. - This parameter can be a value of @ref I2S_LL_EC_MCLK_OUTPUT - - This feature can be modified afterwards using unitary functions @ref LL_I2S_EnableMasterClock() or @ref LL_I2S_DisableMasterClock.*/ - - - uint32_t AudioFreq; /*!< Specifies the frequency selected for the I2S communication. - This parameter can be a value of @ref I2S_LL_EC_AUDIO_FREQ - - Audio Frequency can be modified afterwards using Reference manual formulas to calculate Prescaler Linear, Parity - and unitary functions @ref LL_I2S_SetPrescalerLinear() and @ref LL_I2S_SetPrescalerParity() to set it.*/ - - - uint32_t ClockPolarity; /*!< Specifies the idle state of the I2S clock. - This parameter can be a value of @ref I2S_LL_EC_POLARITY - - This feature can be modified afterwards using unitary function @ref LL_I2S_SetClockPolarity().*/ - -} LL_I2S_InitTypeDef; - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2S_LL_Exported_Constants I2S Exported Constants - * @{ - */ - -/** @defgroup I2S_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_I2S_ReadReg function - * @{ - */ -#define LL_I2S_SR_RXNE LL_SPI_SR_RXNE /*!< Rx buffer not empty flag */ -#define LL_I2S_SR_TXE LL_SPI_SR_TXE /*!< Tx buffer empty flag */ -#define LL_I2S_SR_BSY LL_SPI_SR_BSY /*!< Busy flag */ -#define LL_I2S_SR_UDR SPI_SR_UDR /*!< Underrun flag */ -#define LL_I2S_SR_OVR LL_SPI_SR_OVR /*!< Overrun flag */ -#define LL_I2S_SR_FRE LL_SPI_SR_FRE /*!< TI mode frame format error flag */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_SPI_ReadReg and LL_SPI_WriteReg functions - * @{ - */ -#define LL_I2S_CR2_RXNEIE LL_SPI_CR2_RXNEIE /*!< Rx buffer not empty interrupt enable */ -#define LL_I2S_CR2_TXEIE LL_SPI_CR2_TXEIE /*!< Tx buffer empty interrupt enable */ -#define LL_I2S_CR2_ERRIE LL_SPI_CR2_ERRIE /*!< Error interrupt enable */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_DATA_FORMAT Data format - * @{ - */ -#define LL_I2S_DATAFORMAT_16B 0x00000000U /*!< Data length 16 bits, Channel length 16bit */ -#define LL_I2S_DATAFORMAT_16B_EXTENDED (SPI_I2SCFGR_CHLEN) /*!< Data length 16 bits, Channel length 32bit */ -#define LL_I2S_DATAFORMAT_24B (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_0) /*!< Data length 24 bits, Channel length 32bit */ -#define LL_I2S_DATAFORMAT_32B (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_1) /*!< Data length 16 bits, Channel length 32bit */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_POLARITY Clock Polarity - * @{ - */ -#define LL_I2S_POLARITY_LOW 0x00000000U /*!< Clock steady state is low level */ -#define LL_I2S_POLARITY_HIGH (SPI_I2SCFGR_CKPOL) /*!< Clock steady state is high level */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_STANDARD I2s Standard - * @{ - */ -#define LL_I2S_STANDARD_PHILIPS 0x00000000U /*!< I2S standard philips */ -#define LL_I2S_STANDARD_MSB (SPI_I2SCFGR_I2SSTD_0) /*!< MSB justified standard (left justified) */ -#define LL_I2S_STANDARD_LSB (SPI_I2SCFGR_I2SSTD_1) /*!< LSB justified standard (right justified) */ -#define LL_I2S_STANDARD_PCM_SHORT (SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1) /*!< PCM standard, short frame synchronization */ -#define LL_I2S_STANDARD_PCM_LONG (SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1 | SPI_I2SCFGR_PCMSYNC) /*!< PCM standard, long frame synchronization */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_MODE Operation Mode - * @{ - */ -#define LL_I2S_MODE_SLAVE_TX 0x00000000U /*!< Slave Tx configuration */ -#define LL_I2S_MODE_SLAVE_RX (SPI_I2SCFGR_I2SCFG_0) /*!< Slave Rx configuration */ -#define LL_I2S_MODE_MASTER_TX (SPI_I2SCFGR_I2SCFG_1) /*!< Master Tx configuration */ -#define LL_I2S_MODE_MASTER_RX (SPI_I2SCFGR_I2SCFG_0 | SPI_I2SCFGR_I2SCFG_1) /*!< Master Rx configuration */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_PRESCALER_FACTOR Prescaler Factor - * @{ - */ -#define LL_I2S_PRESCALER_PARITY_EVEN 0x00000000U /*!< Odd factor: Real divider value is = I2SDIV * 2 */ -#define LL_I2S_PRESCALER_PARITY_ODD (SPI_I2SPR_ODD >> 8U) /*!< Odd factor: Real divider value is = (I2SDIV * 2)+1 */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) - -/** @defgroup I2S_LL_EC_MCLK_OUTPUT MCLK Output - * @{ - */ -#define LL_I2S_MCLK_OUTPUT_DISABLE 0x00000000U /*!< Master clock output is disabled */ -#define LL_I2S_MCLK_OUTPUT_ENABLE (SPI_I2SPR_MCKOE) /*!< Master clock output is enabled */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_AUDIO_FREQ Audio Frequency - * @{ - */ - -#define LL_I2S_AUDIOFREQ_192K 192000U /*!< Audio Frequency configuration 192000 Hz */ -#define LL_I2S_AUDIOFREQ_96K 96000U /*!< Audio Frequency configuration 96000 Hz */ -#define LL_I2S_AUDIOFREQ_48K 48000U /*!< Audio Frequency configuration 48000 Hz */ -#define LL_I2S_AUDIOFREQ_44K 44100U /*!< Audio Frequency configuration 44100 Hz */ -#define LL_I2S_AUDIOFREQ_32K 32000U /*!< Audio Frequency configuration 32000 Hz */ -#define LL_I2S_AUDIOFREQ_22K 22050U /*!< Audio Frequency configuration 22050 Hz */ -#define LL_I2S_AUDIOFREQ_16K 16000U /*!< Audio Frequency configuration 16000 Hz */ -#define LL_I2S_AUDIOFREQ_11K 11025U /*!< Audio Frequency configuration 11025 Hz */ -#define LL_I2S_AUDIOFREQ_8K 8000U /*!< Audio Frequency configuration 8000 Hz */ -#define LL_I2S_AUDIOFREQ_DEFAULT 2U /*!< Audio Freq not specified. Register I2SDIV = 2 */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup I2S_LL_Exported_Macros I2S Exported Macros - * @{ - */ - -/** @defgroup I2S_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in I2S register - * @param __INSTANCE__ I2S Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_I2S_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in I2S register - * @param __INSTANCE__ I2S Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_I2S_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup I2S_LL_Exported_Functions I2S Exported Functions - * @{ - */ - -/** @defgroup I2S_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Select I2S mode and Enable I2S peripheral - * @rmtoll I2SCFGR I2SMOD LL_I2S_Enable\n - * I2SCFGR I2SE LL_I2S_Enable - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_Enable(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SE); -} - -/** - * @brief Disable I2S peripheral - * @rmtoll I2SCFGR I2SE LL_I2S_Disable - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_Disable(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SE); -} - -/** - * @brief Check if I2S peripheral is enabled - * @rmtoll I2SCFGR I2SE LL_I2S_IsEnabled - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabled(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SE) == (SPI_I2SCFGR_I2SE)) ? 1UL : 0UL); -} - -/** - * @brief Set I2S data frame length - * @rmtoll I2SCFGR DATLEN LL_I2S_SetDataFormat\n - * I2SCFGR CHLEN LL_I2S_SetDataFormat - * @param SPIx SPI Instance - * @param DataFormat This parameter can be one of the following values: - * @arg @ref LL_I2S_DATAFORMAT_16B - * @arg @ref LL_I2S_DATAFORMAT_16B_EXTENDED - * @arg @ref LL_I2S_DATAFORMAT_24B - * @arg @ref LL_I2S_DATAFORMAT_32B - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetDataFormat(SPI_TypeDef *SPIx, uint32_t DataFormat) -{ - MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN, DataFormat); -} - -/** - * @brief Get I2S data frame length - * @rmtoll I2SCFGR DATLEN LL_I2S_GetDataFormat\n - * I2SCFGR CHLEN LL_I2S_GetDataFormat - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_DATAFORMAT_16B - * @arg @ref LL_I2S_DATAFORMAT_16B_EXTENDED - * @arg @ref LL_I2S_DATAFORMAT_24B - * @arg @ref LL_I2S_DATAFORMAT_32B - */ -__STATIC_INLINE uint32_t LL_I2S_GetDataFormat(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)); -} - -/** - * @brief Set I2S clock polarity - * @rmtoll I2SCFGR CKPOL LL_I2S_SetClockPolarity - * @param SPIx SPI Instance - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_I2S_POLARITY_LOW - * @arg @ref LL_I2S_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetClockPolarity(SPI_TypeDef *SPIx, uint32_t ClockPolarity) -{ - SET_BIT(SPIx->I2SCFGR, ClockPolarity); -} - -/** - * @brief Get I2S clock polarity - * @rmtoll I2SCFGR CKPOL LL_I2S_GetClockPolarity - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_POLARITY_LOW - * @arg @ref LL_I2S_POLARITY_HIGH - */ -__STATIC_INLINE uint32_t LL_I2S_GetClockPolarity(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_CKPOL)); -} - -/** - * @brief Set I2S standard protocol - * @rmtoll I2SCFGR I2SSTD LL_I2S_SetStandard\n - * I2SCFGR PCMSYNC LL_I2S_SetStandard - * @param SPIx SPI Instance - * @param Standard This parameter can be one of the following values: - * @arg @ref LL_I2S_STANDARD_PHILIPS - * @arg @ref LL_I2S_STANDARD_MSB - * @arg @ref LL_I2S_STANDARD_LSB - * @arg @ref LL_I2S_STANDARD_PCM_SHORT - * @arg @ref LL_I2S_STANDARD_PCM_LONG - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetStandard(SPI_TypeDef *SPIx, uint32_t Standard) -{ - MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC, Standard); -} - -/** - * @brief Get I2S standard protocol - * @rmtoll I2SCFGR I2SSTD LL_I2S_GetStandard\n - * I2SCFGR PCMSYNC LL_I2S_GetStandard - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_STANDARD_PHILIPS - * @arg @ref LL_I2S_STANDARD_MSB - * @arg @ref LL_I2S_STANDARD_LSB - * @arg @ref LL_I2S_STANDARD_PCM_SHORT - * @arg @ref LL_I2S_STANDARD_PCM_LONG - */ -__STATIC_INLINE uint32_t LL_I2S_GetStandard(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC)); -} - -/** - * @brief Set I2S transfer mode - * @rmtoll I2SCFGR I2SCFG LL_I2S_SetTransferMode - * @param SPIx SPI Instance - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_I2S_MODE_SLAVE_TX - * @arg @ref LL_I2S_MODE_SLAVE_RX - * @arg @ref LL_I2S_MODE_MASTER_TX - * @arg @ref LL_I2S_MODE_MASTER_RX - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetTransferMode(SPI_TypeDef *SPIx, uint32_t Mode) -{ - MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_I2SCFG, Mode); -} - -/** - * @brief Get I2S transfer mode - * @rmtoll I2SCFGR I2SCFG LL_I2S_GetTransferMode - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_MODE_SLAVE_TX - * @arg @ref LL_I2S_MODE_SLAVE_RX - * @arg @ref LL_I2S_MODE_MASTER_TX - * @arg @ref LL_I2S_MODE_MASTER_RX - */ -__STATIC_INLINE uint32_t LL_I2S_GetTransferMode(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SCFG)); -} - -/** - * @brief Set I2S linear prescaler - * @rmtoll I2SPR I2SDIV LL_I2S_SetPrescalerLinear - * @param SPIx SPI Instance - * @param PrescalerLinear Value between Min_Data=0x02 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetPrescalerLinear(SPI_TypeDef *SPIx, uint8_t PrescalerLinear) -{ - MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_I2SDIV, PrescalerLinear); -} - -/** - * @brief Get I2S linear prescaler - * @rmtoll I2SPR I2SDIV LL_I2S_GetPrescalerLinear - * @param SPIx SPI Instance - * @retval PrescalerLinear Value between Min_Data=0x02 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_I2S_GetPrescalerLinear(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SPR, SPI_I2SPR_I2SDIV)); -} - -/** - * @brief Set I2S parity prescaler - * @rmtoll I2SPR ODD LL_I2S_SetPrescalerParity - * @param SPIx SPI Instance - * @param PrescalerParity This parameter can be one of the following values: - * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN - * @arg @ref LL_I2S_PRESCALER_PARITY_ODD - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetPrescalerParity(SPI_TypeDef *SPIx, uint32_t PrescalerParity) -{ - MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_ODD, PrescalerParity << 8U); -} - -/** - * @brief Get I2S parity prescaler - * @rmtoll I2SPR ODD LL_I2S_GetPrescalerParity - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN - * @arg @ref LL_I2S_PRESCALER_PARITY_ODD - */ -__STATIC_INLINE uint32_t LL_I2S_GetPrescalerParity(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SPR, SPI_I2SPR_ODD) >> 8U); -} - -/** - * @brief Enable the master clock output (Pin MCK) - * @rmtoll I2SPR MCKOE LL_I2S_EnableMasterClock - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableMasterClock(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE); -} - -/** - * @brief Disable the master clock output (Pin MCK) - * @rmtoll I2SPR MCKOE LL_I2S_DisableMasterClock - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableMasterClock(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE); -} - -/** - * @brief Check if the master clock output (Pin MCK) is enabled - * @rmtoll I2SPR MCKOE LL_I2S_IsEnabledMasterClock - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledMasterClock(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE) == (SPI_I2SPR_MCKOE)) ? 1UL : 0UL); -} - -#if defined(SPI_I2SCFGR_ASTRTEN) -/** - * @brief Enable asynchronous start - * @rmtoll I2SCFGR ASTRTEN LL_I2S_EnableAsyncStart - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableAsyncStart(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN); -} - -/** - * @brief Disable asynchronous start - * @rmtoll I2SCFGR ASTRTEN LL_I2S_DisableAsyncStart - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableAsyncStart(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN); -} - -/** - * @brief Check if asynchronous start is enabled - * @rmtoll I2SCFGR ASTRTEN LL_I2S_IsEnabledAsyncStart - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledAsyncStart(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN) == (SPI_I2SCFGR_ASTRTEN)) ? 1UL : 0UL); -} -#endif /* SPI_I2SCFGR_ASTRTEN */ - -/** - * @} - */ - -/** @defgroup I2S_LL_EF_FLAG FLAG Management - * @{ - */ - -/** - * @brief Check if Rx buffer is not empty - * @rmtoll SR RXNE LL_I2S_IsActiveFlag_RXNE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_RXNE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_RXNE(SPIx); -} - -/** - * @brief Check if Tx buffer is empty - * @rmtoll SR TXE LL_I2S_IsActiveFlag_TXE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_TXE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_TXE(SPIx); -} - -/** - * @brief Get busy flag - * @rmtoll SR BSY LL_I2S_IsActiveFlag_BSY - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_BSY(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_BSY(SPIx); -} - -/** - * @brief Get overrun error flag - * @rmtoll SR OVR LL_I2S_IsActiveFlag_OVR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_OVR(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_OVR(SPIx); -} - -/** - * @brief Get underrun error flag - * @rmtoll SR UDR LL_I2S_IsActiveFlag_UDR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_UDR(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_UDR) == (SPI_SR_UDR)) ? 1UL : 0UL); -} - -/** - * @brief Get frame format error flag - * @rmtoll SR FRE LL_I2S_IsActiveFlag_FRE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_FRE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_FRE(SPIx); -} - -/** - * @brief Get channel side flag. - * @note 0: Channel Left has to be transmitted or has been received\n - * 1: Channel Right has to be transmitted or has been received\n - * It has no significance in PCM mode. - * @rmtoll SR CHSIDE LL_I2S_IsActiveFlag_CHSIDE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_CHSIDE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_CHSIDE) == (SPI_SR_CHSIDE)) ? 1UL : 0UL); -} - -/** - * @brief Clear overrun error flag - * @rmtoll SR OVR LL_I2S_ClearFlag_OVR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_ClearFlag_OVR(SPI_TypeDef *SPIx) -{ - LL_SPI_ClearFlag_OVR(SPIx); -} - -/** - * @brief Clear underrun error flag - * @rmtoll SR UDR LL_I2S_ClearFlag_UDR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_ClearFlag_UDR(SPI_TypeDef *SPIx) -{ - __IO uint32_t tmpreg; - tmpreg = SPIx->SR; - (void)tmpreg; -} - -/** - * @brief Clear frame format error flag - * @rmtoll SR FRE LL_I2S_ClearFlag_FRE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_ClearFlag_FRE(SPI_TypeDef *SPIx) -{ - LL_SPI_ClearFlag_FRE(SPIx); -} - -/** - * @} - */ - -/** @defgroup I2S_LL_EF_IT Interrupt Management - * @{ - */ - -/** - * @brief Enable error IT - * @note This bit controls the generation of an interrupt when an error condition occurs (OVR, UDR and FRE in I2S mode). - * @rmtoll CR2 ERRIE LL_I2S_EnableIT_ERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableIT_ERR(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableIT_ERR(SPIx); -} - -/** - * @brief Enable Rx buffer not empty IT - * @rmtoll CR2 RXNEIE LL_I2S_EnableIT_RXNE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableIT_RXNE(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableIT_RXNE(SPIx); -} - -/** - * @brief Enable Tx buffer empty IT - * @rmtoll CR2 TXEIE LL_I2S_EnableIT_TXE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableIT_TXE(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableIT_TXE(SPIx); -} - -/** - * @brief Disable error IT - * @note This bit controls the generation of an interrupt when an error condition occurs (OVR, UDR and FRE in I2S mode). - * @rmtoll CR2 ERRIE LL_I2S_DisableIT_ERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableIT_ERR(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableIT_ERR(SPIx); -} - -/** - * @brief Disable Rx buffer not empty IT - * @rmtoll CR2 RXNEIE LL_I2S_DisableIT_RXNE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableIT_RXNE(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableIT_RXNE(SPIx); -} - -/** - * @brief Disable Tx buffer empty IT - * @rmtoll CR2 TXEIE LL_I2S_DisableIT_TXE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableIT_TXE(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableIT_TXE(SPIx); -} - -/** - * @brief Check if ERR IT is enabled - * @rmtoll CR2 ERRIE LL_I2S_IsEnabledIT_ERR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_ERR(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledIT_ERR(SPIx); -} - -/** - * @brief Check if RXNE IT is enabled - * @rmtoll CR2 RXNEIE LL_I2S_IsEnabledIT_RXNE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_RXNE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledIT_RXNE(SPIx); -} - -/** - * @brief Check if TXE IT is enabled - * @rmtoll CR2 TXEIE LL_I2S_IsEnabledIT_TXE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_TXE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledIT_TXE(SPIx); -} - -/** - * @} - */ - -/** @defgroup I2S_LL_EF_DMA DMA Management - * @{ - */ - -/** - * @brief Enable DMA Rx - * @rmtoll CR2 RXDMAEN LL_I2S_EnableDMAReq_RX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableDMAReq_RX(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableDMAReq_RX(SPIx); -} - -/** - * @brief Disable DMA Rx - * @rmtoll CR2 RXDMAEN LL_I2S_DisableDMAReq_RX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableDMAReq_RX(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableDMAReq_RX(SPIx); -} - -/** - * @brief Check if DMA Rx is enabled - * @rmtoll CR2 RXDMAEN LL_I2S_IsEnabledDMAReq_RX - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledDMAReq_RX(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledDMAReq_RX(SPIx); -} - -/** - * @brief Enable DMA Tx - * @rmtoll CR2 TXDMAEN LL_I2S_EnableDMAReq_TX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableDMAReq_TX(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableDMAReq_TX(SPIx); -} - -/** - * @brief Disable DMA Tx - * @rmtoll CR2 TXDMAEN LL_I2S_DisableDMAReq_TX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableDMAReq_TX(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableDMAReq_TX(SPIx); -} - -/** - * @brief Check if DMA Tx is enabled - * @rmtoll CR2 TXDMAEN LL_I2S_IsEnabledDMAReq_TX - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledDMAReq_TX(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledDMAReq_TX(SPIx); -} - -/** - * @} - */ - -/** @defgroup I2S_LL_EF_DATA DATA Management - * @{ - */ - -/** - * @brief Read 16-Bits in data register - * @rmtoll DR DR LL_I2S_ReceiveData16 - * @param SPIx SPI Instance - * @retval RxData Value between Min_Data=0x0000 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint16_t LL_I2S_ReceiveData16(SPI_TypeDef *SPIx) -{ - return LL_SPI_ReceiveData16(SPIx); -} - -/** - * @brief Write 16-Bits in data register - * @rmtoll DR DR LL_I2S_TransmitData16 - * @param SPIx SPI Instance - * @param TxData Value between Min_Data=0x0000 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_I2S_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData) -{ - LL_SPI_TransmitData16(SPIx, TxData); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2S_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_I2S_DeInit(SPI_TypeDef *SPIx); -ErrorStatus LL_I2S_Init(SPI_TypeDef *SPIx, LL_I2S_InitTypeDef *I2S_InitStruct); -void LL_I2S_StructInit(LL_I2S_InitTypeDef *I2S_InitStruct); -void LL_I2S_ConfigPrescaler(SPI_TypeDef *SPIx, uint32_t PrescalerLinear, uint32_t PrescalerParity); -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) -ErrorStatus LL_I2S_InitFullDuplex(SPI_TypeDef *I2Sxext, LL_I2S_InitTypeDef *I2S_InitStruct); -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_SPI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h deleted file mode 100644 index cc7635e9f88b455..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h +++ /dev/null @@ -1,1710 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_system.h - * @author MCD Application Team - * @brief Header file of SYSTEM LL module. - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL SYSTEM driver contains a set of generic APIs that can be - used by user: - (+) Some of the FLASH features need to be handled in the SYSTEM file. - (+) Access to DBGCMU registers - (+) Access to SYSCFG registers - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_SYSTEM_H -#define __STM32F4xx_LL_SYSTEM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) - -/** @defgroup SYSTEM_LL SYSTEM - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Private_Constants SYSTEM Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Exported_Constants SYSTEM Exported Constants - * @{ - */ - -/** @defgroup SYSTEM_LL_EC_REMAP SYSCFG REMAP -* @{ -*/ -#define LL_SYSCFG_REMAP_FLASH (uint32_t)0x00000000 /*!< Main Flash memory mapped at 0x00000000 */ -#define LL_SYSCFG_REMAP_SYSTEMFLASH SYSCFG_MEMRMP_MEM_MODE_0 /*!< System Flash memory mapped at 0x00000000 */ -#if defined(FSMC_Bank1) -#define LL_SYSCFG_REMAP_FSMC SYSCFG_MEMRMP_MEM_MODE_1 /*!< FSMC(NOR/PSRAM 1 and 2) mapped at 0x00000000 */ -#endif /* FSMC_Bank1 */ -#if defined(FMC_Bank1) -#define LL_SYSCFG_REMAP_FMC SYSCFG_MEMRMP_MEM_MODE_1 /*!< FMC(NOR/PSRAM 1 and 2) mapped at 0x00000000 */ -#define LL_SYSCFG_REMAP_SDRAM SYSCFG_MEMRMP_MEM_MODE_2 /*!< FMC/SDRAM mapped at 0x00000000 */ -#endif /* FMC_Bank1 */ -#define LL_SYSCFG_REMAP_SRAM (SYSCFG_MEMRMP_MEM_MODE_1 | SYSCFG_MEMRMP_MEM_MODE_0) /*!< SRAM1 mapped at 0x00000000 */ - -/** - * @} - */ - -#if defined(SYSCFG_PMC_MII_RMII_SEL) - /** @defgroup SYSTEM_LL_EC_PMC SYSCFG PMC -* @{ -*/ -#define LL_SYSCFG_PMC_ETHMII (uint32_t)0x00000000 /*!< ETH Media MII interface */ -#define LL_SYSCFG_PMC_ETHRMII (uint32_t)SYSCFG_PMC_MII_RMII_SEL /*!< ETH Media RMII interface */ - -/** - * @} - */ -#endif /* SYSCFG_PMC_MII_RMII_SEL */ - - - -#if defined(SYSCFG_MEMRMP_UFB_MODE) -/** @defgroup SYSTEM_LL_EC_BANKMODE SYSCFG BANK MODE - * @{ - */ -#define LL_SYSCFG_BANKMODE_BANK1 (uint32_t)0x00000000 /*!< Flash Bank 1 base address mapped at 0x0800 0000 (AXI) and 0x0020 0000 (TCM) - and Flash Bank 2 base address mapped at 0x0810 0000 (AXI) and 0x0030 0000 (TCM)*/ -#define LL_SYSCFG_BANKMODE_BANK2 SYSCFG_MEMRMP_UFB_MODE /*!< Flash Bank 2 base address mapped at 0x0800 0000 (AXI) and 0x0020 0000(TCM) - and Flash Bank 1 base address mapped at 0x0810 0000 (AXI) and 0x0030 0000(TCM) */ -/** - * @} - */ -#endif /* SYSCFG_MEMRMP_UFB_MODE */ -/** @defgroup SYSTEM_LL_EC_I2C_FASTMODEPLUS SYSCFG I2C FASTMODEPLUS - * @{ - */ -#if defined(SYSCFG_CFGR_FMPI2C1_SCL) -#define LL_SYSCFG_I2C_FASTMODEPLUS_SCL SYSCFG_CFGR_FMPI2C1_SCL /*!< Enable Fast Mode Plus on FMPI2C_SCL pin */ -#define LL_SYSCFG_I2C_FASTMODEPLUS_SDA SYSCFG_CFGR_FMPI2C1_SDA /*!< Enable Fast Mode Plus on FMPI2C_SDA pin*/ -#endif /* SYSCFG_CFGR_FMPI2C1_SCL */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_EXTI_PORT SYSCFG EXTI PORT - * @{ - */ -#define LL_SYSCFG_EXTI_PORTA (uint32_t)0 /*!< EXTI PORT A */ -#define LL_SYSCFG_EXTI_PORTB (uint32_t)1 /*!< EXTI PORT B */ -#define LL_SYSCFG_EXTI_PORTC (uint32_t)2 /*!< EXTI PORT C */ -#define LL_SYSCFG_EXTI_PORTD (uint32_t)3 /*!< EXTI PORT D */ -#define LL_SYSCFG_EXTI_PORTE (uint32_t)4 /*!< EXTI PORT E */ -#if defined(GPIOF) -#define LL_SYSCFG_EXTI_PORTF (uint32_t)5 /*!< EXTI PORT F */ -#endif /* GPIOF */ -#if defined(GPIOG) -#define LL_SYSCFG_EXTI_PORTG (uint32_t)6 /*!< EXTI PORT G */ -#endif /* GPIOG */ -#define LL_SYSCFG_EXTI_PORTH (uint32_t)7 /*!< EXTI PORT H */ -#if defined(GPIOI) -#define LL_SYSCFG_EXTI_PORTI (uint32_t)8 /*!< EXTI PORT I */ -#endif /* GPIOI */ -#if defined(GPIOJ) -#define LL_SYSCFG_EXTI_PORTJ (uint32_t)9 /*!< EXTI PORT J */ -#endif /* GPIOJ */ -#if defined(GPIOK) -#define LL_SYSCFG_EXTI_PORTK (uint32_t)10 /*!< EXTI PORT k */ -#endif /* GPIOK */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_EXTI_LINE SYSCFG EXTI LINE - * @{ - */ -#define LL_SYSCFG_EXTI_LINE0 (uint32_t)(0x000FU << 16 | 0) /*!< EXTI_POSITION_0 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE1 (uint32_t)(0x00F0U << 16 | 0) /*!< EXTI_POSITION_4 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE2 (uint32_t)(0x0F00U << 16 | 0) /*!< EXTI_POSITION_8 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE3 (uint32_t)(0xF000U << 16 | 0) /*!< EXTI_POSITION_12 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE4 (uint32_t)(0x000FU << 16 | 1) /*!< EXTI_POSITION_0 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE5 (uint32_t)(0x00F0U << 16 | 1) /*!< EXTI_POSITION_4 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE6 (uint32_t)(0x0F00U << 16 | 1) /*!< EXTI_POSITION_8 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE7 (uint32_t)(0xF000U << 16 | 1) /*!< EXTI_POSITION_12 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE8 (uint32_t)(0x000FU << 16 | 2) /*!< EXTI_POSITION_0 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE9 (uint32_t)(0x00F0U << 16 | 2) /*!< EXTI_POSITION_4 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE10 (uint32_t)(0x0F00U << 16 | 2) /*!< EXTI_POSITION_8 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE11 (uint32_t)(0xF000U << 16 | 2) /*!< EXTI_POSITION_12 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE12 (uint32_t)(0x000FU << 16 | 3) /*!< EXTI_POSITION_0 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE13 (uint32_t)(0x00F0U << 16 | 3) /*!< EXTI_POSITION_4 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE14 (uint32_t)(0x0F00U << 16 | 3) /*!< EXTI_POSITION_8 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE15 (uint32_t)(0xF000U << 16 | 3) /*!< EXTI_POSITION_12 | EXTICR[3] */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_TIMBREAK SYSCFG TIMER BREAK - * @{ - */ -#if defined(SYSCFG_CFGR2_LOCKUP_LOCK) -#define LL_SYSCFG_TIMBREAK_LOCKUP SYSCFG_CFGR2_LOCKUP_LOCK /*!< Enables and locks the LOCKUP output of CortexM4 - with Break Input of TIM1/8 */ -#define LL_SYSCFG_TIMBREAK_PVD SYSCFG_CFGR2_PVD_LOCK /*!< Enables and locks the PVD connection with TIM1/8 Break Input - and also the PVDE and PLS bits of the Power Control Interface */ -#endif /* SYSCFG_CFGR2_CLL */ -/** - * @} - */ - -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** @defgroup SYSTEM_LL_DFSDM_BitStream_ClockSource SYSCFG MCHDLY BCKKSEL - * @{ - */ -#define LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 (uint32_t)0x00000000 -#define LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 SYSCFG_MCHDLYCR_BSCKSEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_MCHDLYEN SYSCFG MCHDLY MCHDLYEN - * @{ - */ -#define LL_SYSCFG_DFSDM1_MCHDLYEN SYSCFG_MCHDLYCR_MCHDLY1EN -#define LL_SYSCFG_DFSDM2_MCHDLYEN SYSCFG_MCHDLYCR_MCHDLY2EN -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_DataIn0_Source SYSCFG MCHDLY DFSDMD0SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_DataIn0 SYSCFG_MCHDLYCR_DFSDM1D0SEL -#define LL_SYSCFG_DFSDM2_DataIn0 SYSCFG_MCHDLYCR_DFSDM2D0SEL - -#define LL_SYSCFG_DFSDM1_DataIn0_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D0SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM1_DataIn0_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D0SEL << 16) | SYSCFG_MCHDLYCR_DFSDM1D0SEL) -#define LL_SYSCFG_DFSDM2_DataIn0_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D0SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM2_DataIn0_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D0SEL << 16) | SYSCFG_MCHDLYCR_DFSDM2D0SEL) -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_DataIn2_Source SYSCFG MCHDLY DFSDMD2SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_DataIn2 SYSCFG_MCHDLYCR_DFSDM1D2SEL -#define LL_SYSCFG_DFSDM2_DataIn2 SYSCFG_MCHDLYCR_DFSDM2D2SEL - -#define LL_SYSCFG_DFSDM1_DataIn2_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D2SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM1_DataIn2_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D2SEL << 16) | SYSCFG_MCHDLYCR_DFSDM1D2SEL) -#define LL_SYSCFG_DFSDM2_DataIn2_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D2SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM2_DataIn2_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D2SEL << 16) | SYSCFG_MCHDLYCR_DFSDM2D2SEL) -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_TIM4OC2_BitstreamDistribution SYSCFG MCHDLY DFSDM1CK02SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_TIM4OC1_BitstreamDistribution SYSCFG MCHDLY DFSDM1CK13SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 SYSCFG_MCHDLYCR_DFSDM1CK13SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_CLKIN_SourceSelection SYSCFG MCHDLY DFSDMCFG - * @{ - */ -#define LL_SYSCFG_DFSDM1_CKIN_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_CKIN_DM SYSCFG_MCHDLYCR_DFSDM1CFG -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_CLKOUT_SourceSelection SYSCFG MCHDLY DFSDM1CKOSEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_CKOUT (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM1CKOSEL -/** - * @} - */ - -/** @defgroup SYSTEM_LL_DFSDM2_DataIn4_SourceSelection SYSCFG MCHDLY DFSDM2D4SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_DataIn4_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_DataIn4_DM SYSCFG_MCHDLYCR_DFSDM2D4SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_DataIn6_SourceSelection SYSCFG MCHDLY DFSDM2D6SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_DataIn6_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_DataIn6_DM SYSCFG_MCHDLYCR_DFSDM2D6SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC4_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK04SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC3_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK15SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 SYSCFG_MCHDLYCR_DFSDM2CK15SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC2_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK26SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 SYSCFG_MCHDLYCR_DFSDM2CK26SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC1_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK37SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 SYSCFG_MCHDLYCR_DFSDM2CK37SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_CLKIN_SourceSelection SYSCFG MCHDLY DFSDM2CFG - * @{ - */ -#define LL_SYSCFG_DFSDM2_CKIN_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_CKIN_DM SYSCFG_MCHDLYCR_DFSDM2CFG -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_CLKOUT_SourceSelection SYSCFG MCHDLY DFSDM2CKOSEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_CKOUT (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM2CKOSEL -/** - * @} - */ -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ - -/** @defgroup SYSTEM_LL_EC_TRACE DBGMCU TRACE Pin Assignment - * @{ - */ -#define LL_DBGMCU_TRACE_NONE 0x00000000U /*!< TRACE pins not assigned (default state) */ -#define LL_DBGMCU_TRACE_ASYNCH DBGMCU_CR_TRACE_IOEN /*!< TRACE pin assignment for Asynchronous Mode */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE1 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE_0) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 1 */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE2 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE_1) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 2 */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE4 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 4 */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_APB1_GRP1_STOP_IP DBGMCU APB1 GRP1 STOP IP - * @{ - */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM2_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM2_STOP DBGMCU_APB1_FZ_DBG_TIM2_STOP /*!< TIM2 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM2_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM3_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM3_STOP DBGMCU_APB1_FZ_DBG_TIM3_STOP /*!< TIM3 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM3_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM4_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM4_STOP DBGMCU_APB1_FZ_DBG_TIM4_STOP /*!< TIM4 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM4_STOP */ -#define LL_DBGMCU_APB1_GRP1_TIM5_STOP DBGMCU_APB1_FZ_DBG_TIM5_STOP /*!< TIM5 counter stopped when core is halted */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM6_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM6_STOP DBGMCU_APB1_FZ_DBG_TIM6_STOP /*!< TIM6 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM6_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM7_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM7_STOP DBGMCU_APB1_FZ_DBG_TIM7_STOP /*!< TIM7 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM7_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM12_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM12_STOP DBGMCU_APB1_FZ_DBG_TIM12_STOP /*!< TIM12 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM12_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM13_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM13_STOP DBGMCU_APB1_FZ_DBG_TIM13_STOP /*!< TIM13 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM13_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM14_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM14_STOP DBGMCU_APB1_FZ_DBG_TIM14_STOP /*!< TIM14 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM14_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_LPTIM_STOP) -#define LL_DBGMCU_APB1_GRP1_LPTIM_STOP DBGMCU_APB1_FZ_DBG_LPTIM_STOP /*!< LPTIM counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_LPTIM_STOP */ -#define LL_DBGMCU_APB1_GRP1_RTC_STOP DBGMCU_APB1_FZ_DBG_RTC_STOP /*!< RTC counter stopped when core is halted */ -#define LL_DBGMCU_APB1_GRP1_WWDG_STOP DBGMCU_APB1_FZ_DBG_WWDG_STOP /*!< Debug Window Watchdog stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_IWDG_STOP DBGMCU_APB1_FZ_DBG_IWDG_STOP /*!< Debug Independent Watchdog stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_I2C1_STOP DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT /*!< I2C1 SMBUS timeout mode stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_I2C2_STOP DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT /*!< I2C2 SMBUS timeout mode stopped when Core is halted */ -#if defined(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT) -#define LL_DBGMCU_APB1_GRP1_I2C3_STOP DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT /*!< I2C3 SMBUS timeout mode stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT */ -#if defined(DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT) -#define LL_DBGMCU_APB1_GRP1_I2C4_STOP DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT /*!< I2C4 SMBUS timeout mode stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN1_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN1_STOP DBGMCU_APB1_FZ_DBG_CAN1_STOP /*!< CAN1 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN1_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN2_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN2_STOP DBGMCU_APB1_FZ_DBG_CAN2_STOP /*!< CAN2 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN2_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN3_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN3_STOP DBGMCU_APB1_FZ_DBG_CAN3_STOP /*!< CAN3 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN3_STOP */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_APB2_GRP1_STOP_IP DBGMCU APB2 GRP1 STOP IP - * @{ - */ -#define LL_DBGMCU_APB2_GRP1_TIM1_STOP DBGMCU_APB2_FZ_DBG_TIM1_STOP /*!< TIM1 counter stopped when core is halted */ -#if defined(DBGMCU_APB2_FZ_DBG_TIM8_STOP) -#define LL_DBGMCU_APB2_GRP1_TIM8_STOP DBGMCU_APB2_FZ_DBG_TIM8_STOP /*!< TIM8 counter stopped when core is halted */ -#endif /* DBGMCU_APB2_FZ_DBG_TIM8_STOP */ -#define LL_DBGMCU_APB2_GRP1_TIM9_STOP DBGMCU_APB2_FZ_DBG_TIM9_STOP /*!< TIM9 counter stopped when core is halted */ -#if defined(DBGMCU_APB2_FZ_DBG_TIM10_STOP) -#define LL_DBGMCU_APB2_GRP1_TIM10_STOP DBGMCU_APB2_FZ_DBG_TIM10_STOP /*!< TIM10 counter stopped when core is halted */ -#endif /* DBGMCU_APB2_FZ_DBG_TIM10_STOP */ -#define LL_DBGMCU_APB2_GRP1_TIM11_STOP DBGMCU_APB2_FZ_DBG_TIM11_STOP /*!< TIM11 counter stopped when core is halted */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_LATENCY FLASH LATENCY - * @{ - */ -#define LL_FLASH_LATENCY_0 FLASH_ACR_LATENCY_0WS /*!< FLASH Zero wait state */ -#define LL_FLASH_LATENCY_1 FLASH_ACR_LATENCY_1WS /*!< FLASH One wait state */ -#define LL_FLASH_LATENCY_2 FLASH_ACR_LATENCY_2WS /*!< FLASH Two wait states */ -#define LL_FLASH_LATENCY_3 FLASH_ACR_LATENCY_3WS /*!< FLASH Three wait states */ -#define LL_FLASH_LATENCY_4 FLASH_ACR_LATENCY_4WS /*!< FLASH Four wait states */ -#define LL_FLASH_LATENCY_5 FLASH_ACR_LATENCY_5WS /*!< FLASH five wait state */ -#define LL_FLASH_LATENCY_6 FLASH_ACR_LATENCY_6WS /*!< FLASH six wait state */ -#define LL_FLASH_LATENCY_7 FLASH_ACR_LATENCY_7WS /*!< FLASH seven wait states */ -#define LL_FLASH_LATENCY_8 FLASH_ACR_LATENCY_8WS /*!< FLASH eight wait states */ -#define LL_FLASH_LATENCY_9 FLASH_ACR_LATENCY_9WS /*!< FLASH nine wait states */ -#define LL_FLASH_LATENCY_10 FLASH_ACR_LATENCY_10WS /*!< FLASH ten wait states */ -#define LL_FLASH_LATENCY_11 FLASH_ACR_LATENCY_11WS /*!< FLASH eleven wait states */ -#define LL_FLASH_LATENCY_12 FLASH_ACR_LATENCY_12WS /*!< FLASH twelve wait states */ -#define LL_FLASH_LATENCY_13 FLASH_ACR_LATENCY_13WS /*!< FLASH thirteen wait states */ -#define LL_FLASH_LATENCY_14 FLASH_ACR_LATENCY_14WS /*!< FLASH fourteen wait states */ -#define LL_FLASH_LATENCY_15 FLASH_ACR_LATENCY_15WS /*!< FLASH fifteen wait states */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Exported_Functions SYSTEM Exported Functions - * @{ - */ - -/** @defgroup SYSTEM_LL_EF_SYSCFG SYSCFG - * @{ - */ -/** - * @brief Set memory mapping at address 0x00000000 - * @rmtoll SYSCFG_MEMRMP MEM_MODE LL_SYSCFG_SetRemapMemory - * @param Memory This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_REMAP_FLASH - * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH - * @arg @ref LL_SYSCFG_REMAP_SRAM - * @arg @ref LL_SYSCFG_REMAP_FSMC (*) - * @arg @ref LL_SYSCFG_REMAP_FMC (*) - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetRemapMemory(uint32_t Memory) -{ - MODIFY_REG(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_MODE, Memory); -} - -/** - * @brief Get memory mapping at address 0x00000000 - * @rmtoll SYSCFG_MEMRMP MEM_MODE LL_SYSCFG_GetRemapMemory - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_REMAP_FLASH - * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH - * @arg @ref LL_SYSCFG_REMAP_SRAM - * @arg @ref LL_SYSCFG_REMAP_FSMC (*) - * @arg @ref LL_SYSCFG_REMAP_FMC (*) - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetRemapMemory(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_MODE)); -} - -#if defined(SYSCFG_MEMRMP_SWP_FMC) -/** - * @brief Enables the FMC Memory Mapping Swapping - * @rmtoll SYSCFG_MEMRMP SWP_FMC LL_SYSCFG_EnableFMCMemorySwapping - * @note SDRAM is accessible at 0x60000000 and NOR/RAM - * is accessible at 0xC0000000 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableFMCMemorySwapping(void) -{ - SET_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_SWP_FMC_0); -} - -/** - * @brief Disables the FMC Memory Mapping Swapping - * @rmtoll SYSCFG_MEMRMP SWP_FMC LL_SYSCFG_DisableFMCMemorySwapping - * @note SDRAM is accessible at 0xC0000000 (default mapping) - * and NOR/RAM is accessible at 0x60000000 (default mapping) - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableFMCMemorySwapping(void) -{ - CLEAR_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_SWP_FMC); -} - -#endif /* SYSCFG_MEMRMP_SWP_FMC */ -/** - * @brief Enables the Compensation cell Power Down - * @rmtoll SYSCFG_CMPCR CMP_PD LL_SYSCFG_EnableCompensationCell - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableCompensationCell(void) -{ - SET_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_CMP_PD); -} - -/** - * @brief Disables the Compensation cell Power Down - * @rmtoll SYSCFG_CMPCR CMP_PD LL_SYSCFG_DisableCompensationCell - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableCompensationCell(void) -{ - CLEAR_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_CMP_PD); -} - -/** - * @brief Get Compensation Cell ready Flag - * @rmtoll SYSCFG_CMPCR READY LL_SYSCFG_IsActiveFlag_CMPCR - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_CMPCR(void) -{ - return (READ_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_READY) == (SYSCFG_CMPCR_READY)); -} - -#if defined(SYSCFG_PMC_MII_RMII_SEL) -/** - * @brief Select Ethernet PHY interface - * @rmtoll SYSCFG_PMC MII_RMII_SEL LL_SYSCFG_SetPHYInterface - * @param Interface This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_PMC_ETHMII - * @arg @ref LL_SYSCFG_PMC_ETHRMII - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetPHYInterface(uint32_t Interface) -{ - MODIFY_REG(SYSCFG->PMC, SYSCFG_PMC_MII_RMII_SEL, Interface); -} - -/** - * @brief Get Ethernet PHY interface - * @rmtoll SYSCFG_PMC MII_RMII_SEL LL_SYSCFG_GetPHYInterface - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_PMC_ETHMII - * @arg @ref LL_SYSCFG_PMC_ETHRMII - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetPHYInterface(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->PMC, SYSCFG_PMC_MII_RMII_SEL)); -} -#endif /* SYSCFG_PMC_MII_RMII_SEL */ - - - -#if defined(SYSCFG_MEMRMP_UFB_MODE) -/** - * @brief Select Flash bank mode (Bank flashed at 0x08000000) - * @rmtoll SYSCFG_MEMRMP UFB_MODE LL_SYSCFG_SetFlashBankMode - * @param Bank This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_BANKMODE_BANK1 - * @arg @ref LL_SYSCFG_BANKMODE_BANK2 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetFlashBankMode(uint32_t Bank) -{ - MODIFY_REG(SYSCFG->MEMRMP, SYSCFG_MEMRMP_UFB_MODE, Bank); -} - -/** - * @brief Get Flash bank mode (Bank flashed at 0x08000000) - * @rmtoll SYSCFG_MEMRMP UFB_MODE LL_SYSCFG_GetFlashBankMode - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_BANKMODE_BANK1 - * @arg @ref LL_SYSCFG_BANKMODE_BANK2 - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetFlashBankMode(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_UFB_MODE)); -} -#endif /* SYSCFG_MEMRMP_UFB_MODE */ - -#if defined(SYSCFG_CFGR_FMPI2C1_SCL) -/** - * @brief Enable the I2C fast mode plus driving capability. - * @rmtoll SYSCFG_CFGR FMPI2C1_SCL LL_SYSCFG_EnableFastModePlus\n - * SYSCFG_CFGR FMPI2C1_SDA LL_SYSCFG_EnableFastModePlus - * @param ConfigFastModePlus This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SCL - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SDA - * (*) value not defined in all devices - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableFastModePlus(uint32_t ConfigFastModePlus) -{ - SET_BIT(SYSCFG->CFGR, ConfigFastModePlus); -} - -/** - * @brief Disable the I2C fast mode plus driving capability. - * @rmtoll SYSCFG_CFGR FMPI2C1_SCL LL_SYSCFG_DisableFastModePlus\n - * SYSCFG_CFGR FMPI2C1_SDA LL_SYSCFG_DisableFastModePlus\n - * @param ConfigFastModePlus This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SCL - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SDA - * (*) value not defined in all devices - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableFastModePlus(uint32_t ConfigFastModePlus) -{ - CLEAR_BIT(SYSCFG->CFGR, ConfigFastModePlus); -} -#endif /* SYSCFG_CFGR_FMPI2C1_SCL */ - -/** - * @brief Configure source input for the EXTI external interrupt. - * @rmtoll SYSCFG_EXTICR1 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR2 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR3 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR4 EXTIx LL_SYSCFG_SetEXTISource - * @param Port This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_PORTA - * @arg @ref LL_SYSCFG_EXTI_PORTB - * @arg @ref LL_SYSCFG_EXTI_PORTC - * @arg @ref LL_SYSCFG_EXTI_PORTD - * @arg @ref LL_SYSCFG_EXTI_PORTE - * @arg @ref LL_SYSCFG_EXTI_PORTF (*) - * @arg @ref LL_SYSCFG_EXTI_PORTG (*) - * @arg @ref LL_SYSCFG_EXTI_PORTH - * - * (*) value not defined in all devices - * @param Line This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_LINE0 - * @arg @ref LL_SYSCFG_EXTI_LINE1 - * @arg @ref LL_SYSCFG_EXTI_LINE2 - * @arg @ref LL_SYSCFG_EXTI_LINE3 - * @arg @ref LL_SYSCFG_EXTI_LINE4 - * @arg @ref LL_SYSCFG_EXTI_LINE5 - * @arg @ref LL_SYSCFG_EXTI_LINE6 - * @arg @ref LL_SYSCFG_EXTI_LINE7 - * @arg @ref LL_SYSCFG_EXTI_LINE8 - * @arg @ref LL_SYSCFG_EXTI_LINE9 - * @arg @ref LL_SYSCFG_EXTI_LINE10 - * @arg @ref LL_SYSCFG_EXTI_LINE11 - * @arg @ref LL_SYSCFG_EXTI_LINE12 - * @arg @ref LL_SYSCFG_EXTI_LINE13 - * @arg @ref LL_SYSCFG_EXTI_LINE14 - * @arg @ref LL_SYSCFG_EXTI_LINE15 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetEXTISource(uint32_t Port, uint32_t Line) -{ - MODIFY_REG(SYSCFG->EXTICR[Line & 0xFF], (Line >> 16), Port << POSITION_VAL((Line >> 16))); -} - -/** - * @brief Get the configured defined for specific EXTI Line - * @rmtoll SYSCFG_EXTICR1 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR2 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR3 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR4 EXTIx LL_SYSCFG_GetEXTISource - * @param Line This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_LINE0 - * @arg @ref LL_SYSCFG_EXTI_LINE1 - * @arg @ref LL_SYSCFG_EXTI_LINE2 - * @arg @ref LL_SYSCFG_EXTI_LINE3 - * @arg @ref LL_SYSCFG_EXTI_LINE4 - * @arg @ref LL_SYSCFG_EXTI_LINE5 - * @arg @ref LL_SYSCFG_EXTI_LINE6 - * @arg @ref LL_SYSCFG_EXTI_LINE7 - * @arg @ref LL_SYSCFG_EXTI_LINE8 - * @arg @ref LL_SYSCFG_EXTI_LINE9 - * @arg @ref LL_SYSCFG_EXTI_LINE10 - * @arg @ref LL_SYSCFG_EXTI_LINE11 - * @arg @ref LL_SYSCFG_EXTI_LINE12 - * @arg @ref LL_SYSCFG_EXTI_LINE13 - * @arg @ref LL_SYSCFG_EXTI_LINE14 - * @arg @ref LL_SYSCFG_EXTI_LINE15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_PORTA - * @arg @ref LL_SYSCFG_EXTI_PORTB - * @arg @ref LL_SYSCFG_EXTI_PORTC - * @arg @ref LL_SYSCFG_EXTI_PORTD - * @arg @ref LL_SYSCFG_EXTI_PORTE - * @arg @ref LL_SYSCFG_EXTI_PORTF (*) - * @arg @ref LL_SYSCFG_EXTI_PORTG (*) - * @arg @ref LL_SYSCFG_EXTI_PORTH - * (*) value not defined in all devices - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetEXTISource(uint32_t Line) -{ - return (uint32_t)(READ_BIT(SYSCFG->EXTICR[Line & 0xFF], (Line >> 16)) >> POSITION_VAL(Line >> 16)); -} - -#if defined(SYSCFG_CFGR2_LOCKUP_LOCK) -/** - * @brief Set connections to TIM1/8 break inputs - * @rmtoll SYSCFG_CFGR2 LockUp Lock LL_SYSCFG_SetTIMBreakInputs \n - * SYSCFG_CFGR2 PVD Lock LL_SYSCFG_SetTIMBreakInputs - * @param Break This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP - * @arg @ref LL_SYSCFG_TIMBREAK_PVD - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetTIMBreakInputs(uint32_t Break) -{ - MODIFY_REG(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_PVD_LOCK, Break); -} - -/** - * @brief Get connections to TIM1/8 Break inputs - * @rmtoll SYSCFG_CFGR2 LockUp Lock LL_SYSCFG_SetTIMBreakInputs \n - * SYSCFG_CFGR2 PVD Lock LL_SYSCFG_SetTIMBreakInputs - * @retval Returned value can be can be a combination of the following values: - * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP - * @arg @ref LL_SYSCFG_TIMBREAK_PVD - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetTIMBreakInputs(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_PVD_LOCK)); -} -#endif /* SYSCFG_CFGR2_LOCKUP_LOCK */ -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** - * @brief Select the DFSDM2 or TIM2_OC1 as clock source for the bitstream clock. - * @rmtoll SYSCFG_MCHDLYCR BSCKSEL LL_SYSCFG_DFSDM_SetBitstreamClockSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetBitstreamClockSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_BSCKSEL, ClockSource); -} -/** - * @brief Get the DFSDM2 or TIM2_OC1 as clock source for the bitstream clock. - * @rmtoll SYSCFG_MCHDLYCR BSCKSEL LL_SYSCFG_DFSDM_GetBitstreamClockSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetBitstreamClockSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_BSCKSEL)); -} -/** - * @brief Enables the DFSDM1 or DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLYEN LL_SYSCFG_DFSDM_EnableDelayClock - * @param MCHDLY This paramater can be one of the following values - * @arg @ref LL_SYSCFG_DFSDM1_MCHDLYEN - * @arg @ref LL_SYSCFG_DFSDM2_MCHDLYEN - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_EnableDelayClock(uint32_t MCHDLY) -{ - SET_BIT(SYSCFG->MCHDLYCR, MCHDLY); -} - -/** - * @brief Disables the DFSDM1 or the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY1EN LL_SYSCFG_DFSDM1_DisableDelayClock - * @param MCHDLY This paramater can be one of the following values - * @arg @ref LL_SYSCFG_DFSDM1_MCHDLYEN - * @arg @ref LL_SYSCFG_DFSDM2_MCHDLYEN - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_DisableDelayClock(uint32_t MCHDLY) -{ - CLEAR_BIT(SYSCFG->MCHDLYCR, MCHDLY); -} - -/** - * @brief Select the source for DFSDM1 or DFSDM2 DatIn0 - * @rmtoll SYSCFG_MCHDLYCR DFSDMD0SEL LL_SYSCFG_DFSDM_SetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetDataIn0Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, (Source >> 16), (Source & 0x0000FFFF)); -} -/** - * @brief Get the source for DFSDM1 or DFSDM2 DatIn0. - * @rmtoll SYSCFG_MCHDLYCR DFSDMD0SEL LL_SYSCFG_DFSDM_GetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0 - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetDataIn0Source(uint32_t Source) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, Source)); -} -/** - * @brief Select the source for DFSDM1 or DFSDM2 DatIn2 - * @rmtoll SYSCFG_MCHDLYCR DFSDMD2SEL LL_SYSCFG_DFSDM_SetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetDataIn2Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, (Source >> 16), (Source & 0x0000FFFF)); -} -/** - * @brief Get the source for DFSDM1 or DFSDM2 DatIn2. - * @rmtoll SYSCFG_MCHDLYCR DFSDMD2SEL LL_SYSCFG_DFSDM_GetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2 - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetDataIn2Source(uint32_t Source) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, Source)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM4 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CK02SEL LL_SYSCFG_DFSDM1_SetTIM4OC2BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetTIM4OC2BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK02SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM4 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1D2SEL LL_SYSCFG_DFSDM1_GetTIM4OC2BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetTIM4OC2BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK02SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM4 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CK13SEL LL_SYSCFG_DFSDM1_SetTIM4OC1BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetTIM4OC1BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK13SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM4 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1D2SEL LL_SYSCFG_DFSDM1_GetTIM4OC1BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetTIM4OC1BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK13SEL)); -} - -/** - * @brief Select the DFSDM1 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CFG LL_SYSCFG_DFSDM1_SetClockInSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetClockInSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CFG, ClockSource); -} -/** - * @brief GET the DFSDM1 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CFG LL_SYSCFG_DFSDM1_GetClockInSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetClockInSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CFG)); -} - -/** - * @brief Select the DFSDM1 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CKOSEL LL_SYSCFG_DFSDM1_SetClockOutSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetClockOutSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CKOSEL, ClockSource); -} -/** - * @brief GET the DFSDM1 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CKOSEL LL_SYSCFG_DFSDM1_GetClockOutSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetClockOutSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CKOSEL)); -} - -/** - * @brief Enables the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY2EN LL_SYSCFG_DFSDM2_EnableDelayClock - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_EnableDelayClock(void) -{ - SET_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_MCHDLY2EN); -} - -/** - * @brief Disables the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY2EN LL_SYSCFG_DFSDM2_DisableDelayClock - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_DisableDelayClock(void) -{ - CLEAR_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_MCHDLY2EN); -} -/** - * @brief Select the source for DFSDM2 DatIn0 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D0SEL LL_SYSCFG_DFSDM2_SetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn0Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D0SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn0. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D0SEL LL_SYSCFG_DFSDM2_GetDataIn0Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn0Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D0SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D2SEL LL_SYSCFG_DFSDM2_SetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn2Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D2SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn2. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D2SEL LL_SYSCFG_DFSDM2_GetDataIn2Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn2Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D2SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D4SEL LL_SYSCFG_DFSDM2_SetDataIn4Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn4Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D4SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn4. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D4SEL LL_SYSCFG_DFSDM2_GetDataIn4Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn4Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D4SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn6 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D6SEL LL_SYSCFG_DFSDM2_SetDataIn6Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn6Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D6SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn6. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D6SEL LL_SYSCFG_DFSDM2_GetDataIn6Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn6Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D6SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_SetTIM3OC4BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC4BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK04SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC4BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC4BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK04SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC3 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK15SEL LL_SYSCFG_DFSDM2_SetTIM3OC3BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC3BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK15SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC3BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC3BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK15SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK26SEL LL_SYSCFG_DFSDM2_SetTIM3OC2BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC2BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK26SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC2BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC2BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK26SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK37SEL LL_SYSCFG_DFSDM2_SetTIM3OC1BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC1BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK37SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK37SEL LL_SYSCFG_DFSDM2_GetTIM3OC1BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC1BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK37SEL)); -} - -/** - * @brief Select the DFSDM2 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CFG LL_SYSCFG_DFSDM2_SetClockInSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetClockInSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CFG, ClockSource); -} -/** - * @brief GET the DFSDM2 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CFG LL_SYSCFG_DFSDM2_GetClockInSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetClockInSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CFG)); -} - -/** - * @brief Select the DFSDM2 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CKOSEL LL_SYSCFG_DFSDM2_SetClockOutSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetClockOutSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CKOSEL, ClockSource); -} -/** - * @brief GET the DFSDM2 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CKOSEL LL_SYSCFG_DFSDM2_GetClockOutSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetClockOutSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CKOSEL)); -} - -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ -/** - * @} - */ - - -/** @defgroup SYSTEM_LL_EF_DBGMCU DBGMCU - * @{ - */ - -/** - * @brief Return the device identifier - * @note For STM32F405/407xx and STM32F415/417xx devices, the device ID is 0x413 - * @note For STM32F42xxx and STM32F43xxx devices, the device ID is 0x419 - * @note For STM32F401xx devices, the device ID is 0x423 - * @note For STM32F401xx devices, the device ID is 0x433 - * @note For STM32F411xx devices, the device ID is 0x431 - * @note For STM32F410xx devices, the device ID is 0x458 - * @note For STM32F412xx devices, the device ID is 0x441 - * @note For STM32F413xx and STM32423xx devices, the device ID is 0x463 - * @note For STM32F446xx devices, the device ID is 0x421 - * @note For STM32F469xx and STM32F479xx devices, the device ID is 0x434 - * @rmtoll DBGMCU_IDCODE DEV_ID LL_DBGMCU_GetDeviceID - * @retval Values between Min_Data=0x00 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetDeviceID(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_DEV_ID)); -} - -/** - * @brief Return the device revision identifier - * @note This field indicates the revision of the device. - For example, it is read as RevA -> 0x1000, Cat 2 revZ -> 0x1001, rev1 -> 0x1003, rev2 ->0x1007, revY -> 0x100F for STM32F405/407xx and STM32F415/417xx devices - For example, it is read as RevA -> 0x1000, Cat 2 revY -> 0x1003, rev1 -> 0x1007, rev3 ->0x2001 for STM32F42xxx and STM32F43xxx devices - For example, it is read as RevZ -> 0x1000, Cat 2 revA -> 0x1001 for STM32F401xB/C devices - For example, it is read as RevA -> 0x1000, Cat 2 revZ -> 0x1001 for STM32F401xD/E devices - For example, it is read as RevA -> 0x1000 for STM32F411xx,STM32F413/423xx,STM32F469/423xx, STM32F446xx and STM32F410xx devices - For example, it is read as RevZ -> 0x1001, Cat 2 revB -> 0x2000, revC -> 0x3000 for STM32F412xx devices - * @rmtoll DBGMCU_IDCODE REV_ID LL_DBGMCU_GetRevisionID - * @retval Values between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetRevisionID(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_REV_ID) >> DBGMCU_IDCODE_REV_ID_Pos); -} - -/** - * @brief Enable the Debug Module during SLEEP mode - * @rmtoll DBGMCU_CR DBG_SLEEP LL_DBGMCU_EnableDBGSleepMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGSleepMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Disable the Debug Module during SLEEP mode - * @rmtoll DBGMCU_CR DBG_SLEEP LL_DBGMCU_DisableDBGSleepMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGSleepMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Enable the Debug Module during STOP mode - * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_EnableDBGStopMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGStopMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Disable the Debug Module during STOP mode - * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_DisableDBGStopMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGStopMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Enable the Debug Module during STANDBY mode - * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_EnableDBGStandbyMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGStandbyMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Disable the Debug Module during STANDBY mode - * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_DisableDBGStandbyMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGStandbyMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Set Trace pin assignment control - * @rmtoll DBGMCU_CR TRACE_IOEN LL_DBGMCU_SetTracePinAssignment\n - * DBGMCU_CR TRACE_MODE LL_DBGMCU_SetTracePinAssignment - * @param PinAssignment This parameter can be one of the following values: - * @arg @ref LL_DBGMCU_TRACE_NONE - * @arg @ref LL_DBGMCU_TRACE_ASYNCH - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE1 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE2 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE4 - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_SetTracePinAssignment(uint32_t PinAssignment) -{ - MODIFY_REG(DBGMCU->CR, DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE, PinAssignment); -} - -/** - * @brief Get Trace pin assignment control - * @rmtoll DBGMCU_CR TRACE_IOEN LL_DBGMCU_GetTracePinAssignment\n - * DBGMCU_CR TRACE_MODE LL_DBGMCU_GetTracePinAssignment - * @retval Returned value can be one of the following values: - * @arg @ref LL_DBGMCU_TRACE_NONE - * @arg @ref LL_DBGMCU_TRACE_ASYNCH - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE1 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE2 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE4 - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetTracePinAssignment(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->CR, DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE)); -} - -/** - * @brief Freeze APB1 peripherals (group1 peripherals) - * @rmtoll DBGMCU_APB1_FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM4_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM5_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM12_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM13_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_LPTIM_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C2_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C3_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C4_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN1_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM5_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM12_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM13_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_LPTIM_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C2_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN1_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN3_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_FreezePeriph(uint32_t Periphs) -{ - SET_BIT(DBGMCU->APB1FZ, Periphs); -} - -/** - * @brief Unfreeze APB1 peripherals (group1 peripherals) - * @rmtoll DBGMCU_APB1_FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM4_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM5_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM12_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM13_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_LPTIM_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C2_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C3_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C4_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN1_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM5_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM12_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM13_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_LPTIM_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C2_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN1_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN3_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_UnFreezePeriph(uint32_t Periphs) -{ - CLEAR_BIT(DBGMCU->APB1FZ, Periphs); -} - -/** - * @brief Freeze APB2 peripherals - * @rmtoll DBGMCU_APB2_FZ DBG_TIM1_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM8_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM9_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM10_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM11_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM1_STOP - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM8_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM9_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM10_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM11_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB2_GRP1_FreezePeriph(uint32_t Periphs) -{ - SET_BIT(DBGMCU->APB2FZ, Periphs); -} - -/** - * @brief Unfreeze APB2 peripherals - * @rmtoll DBGMCU_APB2_FZ DBG_TIM1_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM8_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM9_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM10_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM11_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM1_STOP - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM8_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM9_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM10_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM11_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB2_GRP1_UnFreezePeriph(uint32_t Periphs) -{ - CLEAR_BIT(DBGMCU->APB2FZ, Periphs); -} -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EF_FLASH FLASH - * @{ - */ - -/** - * @brief Set FLASH Latency - * @rmtoll FLASH_ACR LATENCY LL_FLASH_SetLatency - * @param Latency This parameter can be one of the following values: - * @arg @ref LL_FLASH_LATENCY_0 - * @arg @ref LL_FLASH_LATENCY_1 - * @arg @ref LL_FLASH_LATENCY_2 - * @arg @ref LL_FLASH_LATENCY_3 - * @arg @ref LL_FLASH_LATENCY_4 - * @arg @ref LL_FLASH_LATENCY_5 - * @arg @ref LL_FLASH_LATENCY_6 - * @arg @ref LL_FLASH_LATENCY_7 - * @arg @ref LL_FLASH_LATENCY_8 - * @arg @ref LL_FLASH_LATENCY_9 - * @arg @ref LL_FLASH_LATENCY_10 - * @arg @ref LL_FLASH_LATENCY_11 - * @arg @ref LL_FLASH_LATENCY_12 - * @arg @ref LL_FLASH_LATENCY_13 - * @arg @ref LL_FLASH_LATENCY_14 - * @arg @ref LL_FLASH_LATENCY_15 - * @retval None - */ -__STATIC_INLINE void LL_FLASH_SetLatency(uint32_t Latency) -{ - MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, Latency); -} - -/** - * @brief Get FLASH Latency - * @rmtoll FLASH_ACR LATENCY LL_FLASH_GetLatency - * @retval Returned value can be one of the following values: - * @arg @ref LL_FLASH_LATENCY_0 - * @arg @ref LL_FLASH_LATENCY_1 - * @arg @ref LL_FLASH_LATENCY_2 - * @arg @ref LL_FLASH_LATENCY_3 - * @arg @ref LL_FLASH_LATENCY_4 - * @arg @ref LL_FLASH_LATENCY_5 - * @arg @ref LL_FLASH_LATENCY_6 - * @arg @ref LL_FLASH_LATENCY_7 - * @arg @ref LL_FLASH_LATENCY_8 - * @arg @ref LL_FLASH_LATENCY_9 - * @arg @ref LL_FLASH_LATENCY_10 - * @arg @ref LL_FLASH_LATENCY_11 - * @arg @ref LL_FLASH_LATENCY_12 - * @arg @ref LL_FLASH_LATENCY_13 - * @arg @ref LL_FLASH_LATENCY_14 - * @arg @ref LL_FLASH_LATENCY_15 - */ -__STATIC_INLINE uint32_t LL_FLASH_GetLatency(void) -{ - return (uint32_t)(READ_BIT(FLASH->ACR, FLASH_ACR_LATENCY)); -} - -/** - * @brief Enable Prefetch - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_EnablePrefetch - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnablePrefetch(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_PRFTEN); -} - -/** - * @brief Disable Prefetch - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_DisablePrefetch - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisablePrefetch(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_PRFTEN); -} - -/** - * @brief Check if Prefetch buffer is enabled - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_IsPrefetchEnabled - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FLASH_IsPrefetchEnabled(void) -{ - return (READ_BIT(FLASH->ACR, FLASH_ACR_PRFTEN) == (FLASH_ACR_PRFTEN)); -} - -/** - * @brief Enable Instruction cache - * @rmtoll FLASH_ACR ICEN LL_FLASH_EnableInstCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableInstCache(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_ICEN); -} - -/** - * @brief Disable Instruction cache - * @rmtoll FLASH_ACR ICEN LL_FLASH_DisableInstCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableInstCache(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_ICEN); -} - -/** - * @brief Enable Data cache - * @rmtoll FLASH_ACR DCEN LL_FLASH_EnableDataCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableDataCache(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_DCEN); -} - -/** - * @brief Disable Data cache - * @rmtoll FLASH_ACR DCEN LL_FLASH_DisableDataCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableDataCache(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_DCEN); -} - -/** - * @brief Enable Instruction cache reset - * @note bit can be written only when the instruction cache is disabled - * @rmtoll FLASH_ACR ICRST LL_FLASH_EnableInstCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableInstCacheReset(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_ICRST); -} - -/** - * @brief Disable Instruction cache reset - * @rmtoll FLASH_ACR ICRST LL_FLASH_DisableInstCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableInstCacheReset(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_ICRST); -} - -/** - * @brief Enable Data cache reset - * @note bit can be written only when the data cache is disabled - * @rmtoll FLASH_ACR DCRST LL_FLASH_EnableDataCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableDataCacheReset(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_DCRST); -} - -/** - * @brief Disable Data cache reset - * @rmtoll FLASH_ACR DCRST LL_FLASH_DisableDataCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableDataCacheReset(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_DCRST); -} - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_SYSTEM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h deleted file mode 100644 index 3f83c98dd9f9477..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h +++ /dev/null @@ -1,4095 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_tim.h - * @author MCD Application Team - * @brief Header file of TIM LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_TIM_H -#define __STM32F4xx_LL_TIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (TIM1) || defined (TIM2) || defined (TIM3) || defined (TIM4) || defined (TIM5) || defined (TIM6) || defined (TIM7) || defined (TIM8) || defined (TIM9) || defined (TIM10) || defined (TIM11) || defined (TIM12) || defined (TIM13) || defined (TIM14) - -/** @defgroup TIM_LL TIM - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup TIM_LL_Private_Variables TIM Private Variables - * @{ - */ -static const uint8_t OFFSET_TAB_CCMRx[] = -{ - 0x00U, /* 0: TIMx_CH1 */ - 0x00U, /* 1: TIMx_CH1N */ - 0x00U, /* 2: TIMx_CH2 */ - 0x00U, /* 3: TIMx_CH2N */ - 0x04U, /* 4: TIMx_CH3 */ - 0x04U, /* 5: TIMx_CH3N */ - 0x04U /* 6: TIMx_CH4 */ -}; - -static const uint8_t SHIFT_TAB_OCxx[] = -{ - 0U, /* 0: OC1M, OC1FE, OC1PE */ - 0U, /* 1: - NA */ - 8U, /* 2: OC2M, OC2FE, OC2PE */ - 0U, /* 3: - NA */ - 0U, /* 4: OC3M, OC3FE, OC3PE */ - 0U, /* 5: - NA */ - 8U /* 6: OC4M, OC4FE, OC4PE */ -}; - -static const uint8_t SHIFT_TAB_ICxx[] = -{ - 0U, /* 0: CC1S, IC1PSC, IC1F */ - 0U, /* 1: - NA */ - 8U, /* 2: CC2S, IC2PSC, IC2F */ - 0U, /* 3: - NA */ - 0U, /* 4: CC3S, IC3PSC, IC3F */ - 0U, /* 5: - NA */ - 8U /* 6: CC4S, IC4PSC, IC4F */ -}; - -static const uint8_t SHIFT_TAB_CCxP[] = -{ - 0U, /* 0: CC1P */ - 2U, /* 1: CC1NP */ - 4U, /* 2: CC2P */ - 6U, /* 3: CC2NP */ - 8U, /* 4: CC3P */ - 10U, /* 5: CC3NP */ - 12U /* 6: CC4P */ -}; - -static const uint8_t SHIFT_TAB_OISx[] = -{ - 0U, /* 0: OIS1 */ - 1U, /* 1: OIS1N */ - 2U, /* 2: OIS2 */ - 3U, /* 3: OIS2N */ - 4U, /* 4: OIS3 */ - 5U, /* 5: OIS3N */ - 6U /* 6: OIS4 */ -}; -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup TIM_LL_Private_Constants TIM Private Constants - * @{ - */ - - -/* Remap mask definitions */ -#define TIMx_OR_RMP_SHIFT 16U -#define TIMx_OR_RMP_MASK 0x0000FFFFU -#define TIM2_OR_RMP_MASK (TIM_OR_ITR1_RMP << TIMx_OR_RMP_SHIFT) -#define TIM5_OR_RMP_MASK (TIM_OR_TI4_RMP << TIMx_OR_RMP_SHIFT) -#define TIM11_OR_RMP_MASK (TIM_OR_TI1_RMP << TIMx_OR_RMP_SHIFT) - -/* Mask used to set the TDG[x:0] of the DTG bits of the TIMx_BDTR register */ -#define DT_DELAY_1 ((uint8_t)0x7F) -#define DT_DELAY_2 ((uint8_t)0x3F) -#define DT_DELAY_3 ((uint8_t)0x1F) -#define DT_DELAY_4 ((uint8_t)0x1F) - -/* Mask used to set the DTG[7:5] bits of the DTG bits of the TIMx_BDTR register */ -#define DT_RANGE_1 ((uint8_t)0x00) -#define DT_RANGE_2 ((uint8_t)0x80) -#define DT_RANGE_3 ((uint8_t)0xC0) -#define DT_RANGE_4 ((uint8_t)0xE0) - - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup TIM_LL_Private_Macros TIM Private Macros - * @{ - */ -/** @brief Convert channel id into channel index. - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval none - */ -#define TIM_GET_CHANNEL_INDEX( __CHANNEL__) \ - (((__CHANNEL__) == LL_TIM_CHANNEL_CH1) ? 0U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH1N) ? 1U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH2) ? 2U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH2N) ? 3U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH3) ? 4U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH3N) ? 5U : 6U) - -/** @brief Calculate the deadtime sampling period(in ps). - * @param __TIMCLK__ timer input clock frequency (in Hz). - * @param __CKD__ This parameter can be one of the following values: - * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 - * @retval none - */ -#define TIM_CALC_DTS(__TIMCLK__, __CKD__) \ - (((__CKD__) == LL_TIM_CLOCKDIVISION_DIV1) ? ((uint64_t)1000000000000U/(__TIMCLK__)) : \ - ((__CKD__) == LL_TIM_CLOCKDIVISION_DIV2) ? ((uint64_t)1000000000000U/((__TIMCLK__) >> 1U)) : \ - ((uint64_t)1000000000000U/((__TIMCLK__) >> 2U))) -/** - * @} - */ - - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup TIM_LL_ES_INIT TIM Exported Init structure - * @{ - */ - -/** - * @brief TIM Time Base configuration structure definition. - */ -typedef struct -{ - uint16_t Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. - This parameter can be a number between Min_Data=0x0000 and Max_Data=0xFFFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetPrescaler().*/ - - uint32_t CounterMode; /*!< Specifies the counter mode. - This parameter can be a value of @ref TIM_LL_EC_COUNTERMODE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetCounterMode().*/ - - uint32_t Autoreload; /*!< Specifies the auto reload value to be loaded into the active - Auto-Reload Register at the next update event. - This parameter must be a number between Min_Data=0x0000 and Max_Data=0xFFFF. - Some timer instances may support 32 bits counters. In that case this parameter must - be a number between 0x0000 and 0xFFFFFFFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetAutoReload().*/ - - uint32_t ClockDivision; /*!< Specifies the clock division. - This parameter can be a value of @ref TIM_LL_EC_CLOCKDIVISION. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetClockDivision().*/ - - uint32_t RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter - reaches zero, an update event is generated and counting restarts - from the RCR value (N). - This means in PWM mode that (N+1) corresponds to: - - the number of PWM periods in edge-aligned mode - - the number of half PWM period in center-aligned mode - GP timers: this parameter must be a number between Min_Data = 0x00 and - Max_Data = 0xFF. - Advanced timers: this parameter must be a number between Min_Data = 0x0000 and - Max_Data = 0xFFFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetRepetitionCounter().*/ -} LL_TIM_InitTypeDef; - -/** - * @brief TIM Output Compare configuration structure definition. - */ -typedef struct -{ - uint32_t OCMode; /*!< Specifies the output mode. - This parameter can be a value of @ref TIM_LL_EC_OCMODE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetMode().*/ - - uint32_t OCState; /*!< Specifies the TIM Output Compare state. - This parameter can be a value of @ref TIM_LL_EC_OCSTATE. - - This feature can be modified afterwards using unitary functions - @ref LL_TIM_CC_EnableChannel() or @ref LL_TIM_CC_DisableChannel().*/ - - uint32_t OCNState; /*!< Specifies the TIM complementary Output Compare state. - This parameter can be a value of @ref TIM_LL_EC_OCSTATE. - - This feature can be modified afterwards using unitary functions - @ref LL_TIM_CC_EnableChannel() or @ref LL_TIM_CC_DisableChannel().*/ - - uint32_t CompareValue; /*!< Specifies the Compare value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data=0x0000 and Max_Data=0xFFFF. - - This feature can be modified afterwards using unitary function - LL_TIM_OC_SetCompareCHx (x=1..6).*/ - - uint32_t OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_LL_EC_OCPOLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetPolarity().*/ - - uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_LL_EC_OCPOLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetPolarity().*/ - - - uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_LL_EC_OCIDLESTATE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetIdleState().*/ - - uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_LL_EC_OCIDLESTATE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetIdleState().*/ -} LL_TIM_OC_InitTypeDef; - -/** - * @brief TIM Input Capture configuration structure definition. - */ - -typedef struct -{ - - uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPolarity().*/ - - uint32_t ICActiveInput; /*!< Specifies the input. - This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetActiveInput().*/ - - uint32_t ICPrescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_LL_EC_ICPSC. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPrescaler().*/ - - uint32_t ICFilter; /*!< Specifies the input capture filter. - This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetFilter().*/ -} LL_TIM_IC_InitTypeDef; - - -/** - * @brief TIM Encoder interface configuration structure definition. - */ -typedef struct -{ - uint32_t EncoderMode; /*!< Specifies the encoder resolution (x2 or x4). - This parameter can be a value of @ref TIM_LL_EC_ENCODERMODE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetEncoderMode().*/ - - uint32_t IC1Polarity; /*!< Specifies the active edge of TI1 input. - This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPolarity().*/ - - uint32_t IC1ActiveInput; /*!< Specifies the TI1 input source - This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetActiveInput().*/ - - uint32_t IC1Prescaler; /*!< Specifies the TI1 input prescaler value. - This parameter can be a value of @ref TIM_LL_EC_ICPSC. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPrescaler().*/ - - uint32_t IC1Filter; /*!< Specifies the TI1 input filter. - This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetFilter().*/ - - uint32_t IC2Polarity; /*!< Specifies the active edge of TI2 input. - This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPolarity().*/ - - uint32_t IC2ActiveInput; /*!< Specifies the TI2 input source - This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetActiveInput().*/ - - uint32_t IC2Prescaler; /*!< Specifies the TI2 input prescaler value. - This parameter can be a value of @ref TIM_LL_EC_ICPSC. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPrescaler().*/ - - uint32_t IC2Filter; /*!< Specifies the TI2 input filter. - This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetFilter().*/ - -} LL_TIM_ENCODER_InitTypeDef; - -/** - * @brief TIM Hall sensor interface configuration structure definition. - */ -typedef struct -{ - - uint32_t IC1Polarity; /*!< Specifies the active edge of TI1 input. - This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPolarity().*/ - - uint32_t IC1Prescaler; /*!< Specifies the TI1 input prescaler value. - Prescaler must be set to get a maximum counter period longer than the - time interval between 2 consecutive changes on the Hall inputs. - This parameter can be a value of @ref TIM_LL_EC_ICPSC. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPrescaler().*/ - - uint32_t IC1Filter; /*!< Specifies the TI1 input filter. - This parameter can be a value of - @ref TIM_LL_EC_IC_FILTER. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetFilter().*/ - - uint32_t CommutationDelay; /*!< Specifies the compare value to be loaded into the Capture Compare Register. - A positive pulse (TRGO event) is generated with a programmable delay every time - a change occurs on the Hall inputs. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetCompareCH2().*/ -} LL_TIM_HALLSENSOR_InitTypeDef; - -/** - * @brief BDTR (Break and Dead Time) structure definition - */ -typedef struct -{ - uint32_t OSSRState; /*!< Specifies the Off-State selection used in Run mode. - This parameter can be a value of @ref TIM_LL_EC_OSSR - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetOffStates() - - @note This bit-field cannot be modified as long as LOCK level 2 has been - programmed. */ - - uint32_t OSSIState; /*!< Specifies the Off-State used in Idle state. - This parameter can be a value of @ref TIM_LL_EC_OSSI - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetOffStates() - - @note This bit-field cannot be modified as long as LOCK level 2 has been - programmed. */ - - uint32_t LockLevel; /*!< Specifies the LOCK level parameters. - This parameter can be a value of @ref TIM_LL_EC_LOCKLEVEL - - @note The LOCK bits can be written only once after the reset. Once the TIMx_BDTR - register has been written, their content is frozen until the next reset.*/ - - uint8_t DeadTime; /*!< Specifies the delay time between the switching-off and the - switching-on of the outputs. - This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetDeadTime() - - @note This bit-field can not be modified as long as LOCK level 1, 2 or 3 has been - programmed. */ - - uint16_t BreakState; /*!< Specifies whether the TIM Break input is enabled or not. - This parameter can be a value of @ref TIM_LL_EC_BREAK_ENABLE - - This feature can be modified afterwards using unitary functions - @ref LL_TIM_EnableBRK() or @ref LL_TIM_DisableBRK() - - @note This bit-field can not be modified as long as LOCK level 1 has been - programmed. */ - - uint32_t BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. - This parameter can be a value of @ref TIM_LL_EC_BREAK_POLARITY - - This feature can be modified afterwards using unitary function - @ref LL_TIM_ConfigBRK() - - @note This bit-field can not be modified as long as LOCK level 1 has been - programmed. */ - - uint32_t AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. - This parameter can be a value of @ref TIM_LL_EC_AUTOMATICOUTPUT_ENABLE - - This feature can be modified afterwards using unitary functions - @ref LL_TIM_EnableAutomaticOutput() or @ref LL_TIM_DisableAutomaticOutput() - - @note This bit-field can not be modified as long as LOCK level 1 has been - programmed. */ -} LL_TIM_BDTR_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup TIM_LL_Exported_Constants TIM Exported Constants - * @{ - */ - -/** @defgroup TIM_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_TIM_ReadReg function. - * @{ - */ -#define LL_TIM_SR_UIF TIM_SR_UIF /*!< Update interrupt flag */ -#define LL_TIM_SR_CC1IF TIM_SR_CC1IF /*!< Capture/compare 1 interrupt flag */ -#define LL_TIM_SR_CC2IF TIM_SR_CC2IF /*!< Capture/compare 2 interrupt flag */ -#define LL_TIM_SR_CC3IF TIM_SR_CC3IF /*!< Capture/compare 3 interrupt flag */ -#define LL_TIM_SR_CC4IF TIM_SR_CC4IF /*!< Capture/compare 4 interrupt flag */ -#define LL_TIM_SR_COMIF TIM_SR_COMIF /*!< COM interrupt flag */ -#define LL_TIM_SR_TIF TIM_SR_TIF /*!< Trigger interrupt flag */ -#define LL_TIM_SR_BIF TIM_SR_BIF /*!< Break interrupt flag */ -#define LL_TIM_SR_CC1OF TIM_SR_CC1OF /*!< Capture/Compare 1 overcapture flag */ -#define LL_TIM_SR_CC2OF TIM_SR_CC2OF /*!< Capture/Compare 2 overcapture flag */ -#define LL_TIM_SR_CC3OF TIM_SR_CC3OF /*!< Capture/Compare 3 overcapture flag */ -#define LL_TIM_SR_CC4OF TIM_SR_CC4OF /*!< Capture/Compare 4 overcapture flag */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup TIM_LL_EC_BREAK_ENABLE Break Enable - * @{ - */ -#define LL_TIM_BREAK_DISABLE 0x00000000U /*!< Break function disabled */ -#define LL_TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break function enabled */ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_AUTOMATICOUTPUT_ENABLE Automatic output enable - * @{ - */ -#define LL_TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */ -#define LL_TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** @defgroup TIM_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_TIM_ReadReg and LL_TIM_WriteReg functions. - * @{ - */ -#define LL_TIM_DIER_UIE TIM_DIER_UIE /*!< Update interrupt enable */ -#define LL_TIM_DIER_CC1IE TIM_DIER_CC1IE /*!< Capture/compare 1 interrupt enable */ -#define LL_TIM_DIER_CC2IE TIM_DIER_CC2IE /*!< Capture/compare 2 interrupt enable */ -#define LL_TIM_DIER_CC3IE TIM_DIER_CC3IE /*!< Capture/compare 3 interrupt enable */ -#define LL_TIM_DIER_CC4IE TIM_DIER_CC4IE /*!< Capture/compare 4 interrupt enable */ -#define LL_TIM_DIER_COMIE TIM_DIER_COMIE /*!< COM interrupt enable */ -#define LL_TIM_DIER_TIE TIM_DIER_TIE /*!< Trigger interrupt enable */ -#define LL_TIM_DIER_BIE TIM_DIER_BIE /*!< Break interrupt enable */ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_UPDATESOURCE Update Source - * @{ - */ -#define LL_TIM_UPDATESOURCE_REGULAR 0x00000000U /*!< Counter overflow/underflow, Setting the UG bit or Update generation through the slave mode controller generates an update request */ -#define LL_TIM_UPDATESOURCE_COUNTER TIM_CR1_URS /*!< Only counter overflow/underflow generates an update request */ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_ONEPULSEMODE One Pulse Mode - * @{ - */ -#define LL_TIM_ONEPULSEMODE_SINGLE TIM_CR1_OPM /*!< Counter stops counting at the next update event */ -#define LL_TIM_ONEPULSEMODE_REPETITIVE 0x00000000U /*!< Counter is not stopped at update event */ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_COUNTERMODE Counter Mode - * @{ - */ -#define LL_TIM_COUNTERMODE_UP 0x00000000U /*!TIMx_CCRy else active.*/ -#define LL_TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!TIMx_CCRy else inactive*/ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_OCPOLARITY Output Configuration Polarity - * @{ - */ -#define LL_TIM_OCPOLARITY_HIGH 0x00000000U /*!< OCxactive high*/ -#define LL_TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< OCxactive low*/ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_OCIDLESTATE Output Configuration Idle State - * @{ - */ -#define LL_TIM_OCIDLESTATE_LOW 0x00000000U /*!__REG__, (__VALUE__)) - -/** - * @brief Read a value in TIM register. - * @param __INSTANCE__ TIM Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_TIM_ReadReg(__INSTANCE__, __REG__) READ_REG((__INSTANCE__)->__REG__) -/** - * @} - */ - -/** @defgroup TIM_LL_EM_Exported_Macros Exported_Macros - * @{ - */ - -/** - * @brief HELPER macro calculating DTG[0:7] in the TIMx_BDTR register to achieve the requested dead time duration. - * @note ex: @ref __LL_TIM_CALC_DEADTIME (80000000, @ref LL_TIM_GetClockDivision (), 120); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __CKD__ This parameter can be one of the following values: - * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 - * @param __DT__ deadtime duration (in ns) - * @retval DTG[0:7] - */ -#define __LL_TIM_CALC_DEADTIME(__TIMCLK__, __CKD__, __DT__) \ - ( (((uint64_t)((__DT__)*1000U)) < ((DT_DELAY_1+1U) * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ - (uint8_t)(((uint64_t)((__DT__)*1000U) / TIM_CALC_DTS((__TIMCLK__), (__CKD__))) & DT_DELAY_1) : \ - (((uint64_t)((__DT__)*1000U)) < ((64U + (DT_DELAY_2+1U)) * 2U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ - (uint8_t)(DT_RANGE_2 | ((uint8_t)((uint8_t)((((uint64_t)((__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ - (__CKD__))) >> 1U) - (uint8_t) 64) & DT_DELAY_2)) :\ - (((uint64_t)((__DT__)*1000U)) < ((32U + (DT_DELAY_3+1U)) * 8U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ - (uint8_t)(DT_RANGE_3 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ - (__CKD__))) >> 3U) - (uint8_t) 32) & DT_DELAY_3)) :\ - (((uint64_t)((__DT__)*1000U)) < ((32U + (DT_DELAY_4+1U)) * 16U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ - (uint8_t)(DT_RANGE_4 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ - (__CKD__))) >> 4U) - (uint8_t) 32) & DT_DELAY_4)) :\ - 0U) - -/** - * @brief HELPER macro calculating the prescaler value to achieve the required counter clock frequency. - * @note ex: @ref __LL_TIM_CALC_PSC (80000000, 1000000); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __CNTCLK__ counter clock frequency (in Hz) - * @retval Prescaler value (between Min_Data=0 and Max_Data=65535) - */ -#define __LL_TIM_CALC_PSC(__TIMCLK__, __CNTCLK__) \ - (((__TIMCLK__) >= (__CNTCLK__)) ? (uint32_t)(((__TIMCLK__)/(__CNTCLK__)) - 1U) : 0U) - -/** - * @brief HELPER macro calculating the auto-reload value to achieve the required output signal frequency. - * @note ex: @ref __LL_TIM_CALC_ARR (1000000, @ref LL_TIM_GetPrescaler (), 10000); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __PSC__ prescaler - * @param __FREQ__ output signal frequency (in Hz) - * @retval Auto-reload value (between Min_Data=0 and Max_Data=65535) - */ -#define __LL_TIM_CALC_ARR(__TIMCLK__, __PSC__, __FREQ__) \ - ((((__TIMCLK__)/((__PSC__) + 1U)) >= (__FREQ__)) ? (((__TIMCLK__)/((__FREQ__) * ((__PSC__) + 1U))) - 1U) : 0U) - -/** - * @brief HELPER macro calculating the compare value required to achieve the required timer output compare - * active/inactive delay. - * @note ex: @ref __LL_TIM_CALC_DELAY (1000000, @ref LL_TIM_GetPrescaler (), 10); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __PSC__ prescaler - * @param __DELAY__ timer output compare active/inactive delay (in us) - * @retval Compare value (between Min_Data=0 and Max_Data=65535) - */ -#define __LL_TIM_CALC_DELAY(__TIMCLK__, __PSC__, __DELAY__) \ - ((uint32_t)(((uint64_t)(__TIMCLK__) * (uint64_t)(__DELAY__)) \ - / ((uint64_t)1000000U * (uint64_t)((__PSC__) + 1U)))) - -/** - * @brief HELPER macro calculating the auto-reload value to achieve the required pulse duration - * (when the timer operates in one pulse mode). - * @note ex: @ref __LL_TIM_CALC_PULSE (1000000, @ref LL_TIM_GetPrescaler (), 10, 20); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __PSC__ prescaler - * @param __DELAY__ timer output compare active/inactive delay (in us) - * @param __PULSE__ pulse duration (in us) - * @retval Auto-reload value (between Min_Data=0 and Max_Data=65535) - */ -#define __LL_TIM_CALC_PULSE(__TIMCLK__, __PSC__, __DELAY__, __PULSE__) \ - ((uint32_t)(__LL_TIM_CALC_DELAY((__TIMCLK__), (__PSC__), (__PULSE__)) \ - + __LL_TIM_CALC_DELAY((__TIMCLK__), (__PSC__), (__DELAY__)))) - -/** - * @brief HELPER macro retrieving the ratio of the input capture prescaler - * @note ex: @ref __LL_TIM_GET_ICPSC_RATIO (@ref LL_TIM_IC_GetPrescaler ()); - * @param __ICPSC__ This parameter can be one of the following values: - * @arg @ref LL_TIM_ICPSC_DIV1 - * @arg @ref LL_TIM_ICPSC_DIV2 - * @arg @ref LL_TIM_ICPSC_DIV4 - * @arg @ref LL_TIM_ICPSC_DIV8 - * @retval Input capture prescaler ratio (1, 2, 4 or 8) - */ -#define __LL_TIM_GET_ICPSC_RATIO(__ICPSC__) \ - ((uint32_t)(0x01U << (((__ICPSC__) >> 16U) >> TIM_CCMR1_IC1PSC_Pos))) - - -/** - * @} - */ - - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup TIM_LL_Exported_Functions TIM Exported Functions - * @{ - */ - -/** @defgroup TIM_LL_EF_Time_Base Time Base configuration - * @{ - */ -/** - * @brief Enable timer counter. - * @rmtoll CR1 CEN LL_TIM_EnableCounter - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableCounter(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR1, TIM_CR1_CEN); -} - -/** - * @brief Disable timer counter. - * @rmtoll CR1 CEN LL_TIM_DisableCounter - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableCounter(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR1, TIM_CR1_CEN); -} - -/** - * @brief Indicates whether the timer counter is enabled. - * @rmtoll CR1 CEN LL_TIM_IsEnabledCounter - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledCounter(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->CR1, TIM_CR1_CEN) == (TIM_CR1_CEN)) ? 1UL : 0UL); -} - -/** - * @brief Enable update event generation. - * @rmtoll CR1 UDIS LL_TIM_EnableUpdateEvent - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableUpdateEvent(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR1, TIM_CR1_UDIS); -} - -/** - * @brief Disable update event generation. - * @rmtoll CR1 UDIS LL_TIM_DisableUpdateEvent - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableUpdateEvent(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR1, TIM_CR1_UDIS); -} - -/** - * @brief Indicates whether update event generation is enabled. - * @rmtoll CR1 UDIS LL_TIM_IsEnabledUpdateEvent - * @param TIMx Timer instance - * @retval Inverted state of bit (0 or 1). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledUpdateEvent(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->CR1, TIM_CR1_UDIS) == (uint32_t)RESET) ? 1UL : 0UL); -} - -/** - * @brief Set update event source - * @note Update event source set to LL_TIM_UPDATESOURCE_REGULAR: any of the following events - * generate an update interrupt or DMA request if enabled: - * - Counter overflow/underflow - * - Setting the UG bit - * - Update generation through the slave mode controller - * @note Update event source set to LL_TIM_UPDATESOURCE_COUNTER: only counter - * overflow/underflow generates an update interrupt or DMA request if enabled. - * @rmtoll CR1 URS LL_TIM_SetUpdateSource - * @param TIMx Timer instance - * @param UpdateSource This parameter can be one of the following values: - * @arg @ref LL_TIM_UPDATESOURCE_REGULAR - * @arg @ref LL_TIM_UPDATESOURCE_COUNTER - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetUpdateSource(TIM_TypeDef *TIMx, uint32_t UpdateSource) -{ - MODIFY_REG(TIMx->CR1, TIM_CR1_URS, UpdateSource); -} - -/** - * @brief Get actual event update source - * @rmtoll CR1 URS LL_TIM_GetUpdateSource - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_UPDATESOURCE_REGULAR - * @arg @ref LL_TIM_UPDATESOURCE_COUNTER - */ -__STATIC_INLINE uint32_t LL_TIM_GetUpdateSource(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_URS)); -} - -/** - * @brief Set one pulse mode (one shot v.s. repetitive). - * @rmtoll CR1 OPM LL_TIM_SetOnePulseMode - * @param TIMx Timer instance - * @param OnePulseMode This parameter can be one of the following values: - * @arg @ref LL_TIM_ONEPULSEMODE_SINGLE - * @arg @ref LL_TIM_ONEPULSEMODE_REPETITIVE - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetOnePulseMode(TIM_TypeDef *TIMx, uint32_t OnePulseMode) -{ - MODIFY_REG(TIMx->CR1, TIM_CR1_OPM, OnePulseMode); -} - -/** - * @brief Get actual one pulse mode. - * @rmtoll CR1 OPM LL_TIM_GetOnePulseMode - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_ONEPULSEMODE_SINGLE - * @arg @ref LL_TIM_ONEPULSEMODE_REPETITIVE - */ -__STATIC_INLINE uint32_t LL_TIM_GetOnePulseMode(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_OPM)); -} - -/** - * @brief Set the timer counter counting mode. - * @note Macro IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx) can be used to - * check whether or not the counter mode selection feature is supported - * by a timer instance. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * @rmtoll CR1 DIR LL_TIM_SetCounterMode\n - * CR1 CMS LL_TIM_SetCounterMode - * @param TIMx Timer instance - * @param CounterMode This parameter can be one of the following values: - * @arg @ref LL_TIM_COUNTERMODE_UP - * @arg @ref LL_TIM_COUNTERMODE_DOWN - * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP - * @arg @ref LL_TIM_COUNTERMODE_CENTER_DOWN - * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP_DOWN - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetCounterMode(TIM_TypeDef *TIMx, uint32_t CounterMode) -{ - MODIFY_REG(TIMx->CR1, (TIM_CR1_DIR | TIM_CR1_CMS), CounterMode); -} - -/** - * @brief Get actual counter mode. - * @note Macro IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx) can be used to - * check whether or not the counter mode selection feature is supported - * by a timer instance. - * @rmtoll CR1 DIR LL_TIM_GetCounterMode\n - * CR1 CMS LL_TIM_GetCounterMode - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_COUNTERMODE_UP - * @arg @ref LL_TIM_COUNTERMODE_DOWN - * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP - * @arg @ref LL_TIM_COUNTERMODE_CENTER_DOWN - * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP_DOWN - */ -__STATIC_INLINE uint32_t LL_TIM_GetCounterMode(TIM_TypeDef *TIMx) -{ - uint32_t counter_mode; - - counter_mode = (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_CMS)); - - if (counter_mode == 0U) - { - counter_mode = (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_DIR)); - } - - return counter_mode; -} - -/** - * @brief Enable auto-reload (ARR) preload. - * @rmtoll CR1 ARPE LL_TIM_EnableARRPreload - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableARRPreload(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR1, TIM_CR1_ARPE); -} - -/** - * @brief Disable auto-reload (ARR) preload. - * @rmtoll CR1 ARPE LL_TIM_DisableARRPreload - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableARRPreload(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR1, TIM_CR1_ARPE); -} - -/** - * @brief Indicates whether auto-reload (ARR) preload is enabled. - * @rmtoll CR1 ARPE LL_TIM_IsEnabledARRPreload - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledARRPreload(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->CR1, TIM_CR1_ARPE) == (TIM_CR1_ARPE)) ? 1UL : 0UL); -} - -/** - * @brief Set the division ratio between the timer clock and the sampling clock used by the dead-time generators - * (when supported) and the digital filters. - * @note Macro IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx) can be used to check - * whether or not the clock division feature is supported by the timer - * instance. - * @rmtoll CR1 CKD LL_TIM_SetClockDivision - * @param TIMx Timer instance - * @param ClockDivision This parameter can be one of the following values: - * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetClockDivision(TIM_TypeDef *TIMx, uint32_t ClockDivision) -{ - MODIFY_REG(TIMx->CR1, TIM_CR1_CKD, ClockDivision); -} - -/** - * @brief Get the actual division ratio between the timer clock and the sampling clock used by the dead-time - * generators (when supported) and the digital filters. - * @note Macro IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx) can be used to check - * whether or not the clock division feature is supported by the timer - * instance. - * @rmtoll CR1 CKD LL_TIM_GetClockDivision - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 - */ -__STATIC_INLINE uint32_t LL_TIM_GetClockDivision(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_CKD)); -} - -/** - * @brief Set the counter value. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @rmtoll CNT CNT LL_TIM_SetCounter - * @param TIMx Timer instance - * @param Counter Counter value (between Min_Data=0 and Max_Data=0xFFFF or 0xFFFFFFFF) - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetCounter(TIM_TypeDef *TIMx, uint32_t Counter) -{ - WRITE_REG(TIMx->CNT, Counter); -} - -/** - * @brief Get the counter value. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @rmtoll CNT CNT LL_TIM_GetCounter - * @param TIMx Timer instance - * @retval Counter value (between Min_Data=0 and Max_Data=0xFFFF or 0xFFFFFFFF) - */ -__STATIC_INLINE uint32_t LL_TIM_GetCounter(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CNT)); -} - -/** - * @brief Get the current direction of the counter - * @rmtoll CR1 DIR LL_TIM_GetDirection - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_COUNTERDIRECTION_UP - * @arg @ref LL_TIM_COUNTERDIRECTION_DOWN - */ -__STATIC_INLINE uint32_t LL_TIM_GetDirection(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_DIR)); -} - -/** - * @brief Set the prescaler value. - * @note The counter clock frequency CK_CNT is equal to fCK_PSC / (PSC[15:0] + 1). - * @note The prescaler can be changed on the fly as this control register is buffered. The new - * prescaler ratio is taken into account at the next update event. - * @note Helper macro @ref __LL_TIM_CALC_PSC can be used to calculate the Prescaler parameter - * @rmtoll PSC PSC LL_TIM_SetPrescaler - * @param TIMx Timer instance - * @param Prescaler between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetPrescaler(TIM_TypeDef *TIMx, uint32_t Prescaler) -{ - WRITE_REG(TIMx->PSC, Prescaler); -} - -/** - * @brief Get the prescaler value. - * @rmtoll PSC PSC LL_TIM_GetPrescaler - * @param TIMx Timer instance - * @retval Prescaler value between Min_Data=0 and Max_Data=65535 - */ -__STATIC_INLINE uint32_t LL_TIM_GetPrescaler(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->PSC)); -} - -/** - * @brief Set the auto-reload value. - * @note The counter is blocked while the auto-reload value is null. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Helper macro @ref __LL_TIM_CALC_ARR can be used to calculate the AutoReload parameter - * @rmtoll ARR ARR LL_TIM_SetAutoReload - * @param TIMx Timer instance - * @param AutoReload between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetAutoReload(TIM_TypeDef *TIMx, uint32_t AutoReload) -{ - WRITE_REG(TIMx->ARR, AutoReload); -} - -/** - * @brief Get the auto-reload value. - * @rmtoll ARR ARR LL_TIM_GetAutoReload - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @param TIMx Timer instance - * @retval Auto-reload value - */ -__STATIC_INLINE uint32_t LL_TIM_GetAutoReload(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->ARR)); -} - -/** - * @brief Set the repetition counter value. - * @note Macro IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a repetition counter. - * @rmtoll RCR REP LL_TIM_SetRepetitionCounter - * @param TIMx Timer instance - * @param RepetitionCounter between Min_Data=0 and Max_Data=255 or 65535 for advanced timer. - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetRepetitionCounter(TIM_TypeDef *TIMx, uint32_t RepetitionCounter) -{ - WRITE_REG(TIMx->RCR, RepetitionCounter); -} - -/** - * @brief Get the repetition counter value. - * @note Macro IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a repetition counter. - * @rmtoll RCR REP LL_TIM_GetRepetitionCounter - * @param TIMx Timer instance - * @retval Repetition counter value - */ -__STATIC_INLINE uint32_t LL_TIM_GetRepetitionCounter(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->RCR)); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Capture_Compare Capture Compare configuration - * @{ - */ -/** - * @brief Enable the capture/compare control bits (CCxE, CCxNE and OCxM) preload. - * @note CCxE, CCxNE and OCxM bits are preloaded, after having been written, - * they are updated only when a commutation event (COM) occurs. - * @note Only on channels that have a complementary output. - * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check - * whether or not a timer instance is able to generate a commutation event. - * @rmtoll CR2 CCPC LL_TIM_CC_EnablePreload - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_EnablePreload(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR2, TIM_CR2_CCPC); -} - -/** - * @brief Disable the capture/compare control bits (CCxE, CCxNE and OCxM) preload. - * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check - * whether or not a timer instance is able to generate a commutation event. - * @rmtoll CR2 CCPC LL_TIM_CC_DisablePreload - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_DisablePreload(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR2, TIM_CR2_CCPC); -} - -/** - * @brief Set the updated source of the capture/compare control bits (CCxE, CCxNE and OCxM). - * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check - * whether or not a timer instance is able to generate a commutation event. - * @rmtoll CR2 CCUS LL_TIM_CC_SetUpdate - * @param TIMx Timer instance - * @param CCUpdateSource This parameter can be one of the following values: - * @arg @ref LL_TIM_CCUPDATESOURCE_COMG_ONLY - * @arg @ref LL_TIM_CCUPDATESOURCE_COMG_AND_TRGI - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_SetUpdate(TIM_TypeDef *TIMx, uint32_t CCUpdateSource) -{ - MODIFY_REG(TIMx->CR2, TIM_CR2_CCUS, CCUpdateSource); -} - -/** - * @brief Set the trigger of the capture/compare DMA request. - * @rmtoll CR2 CCDS LL_TIM_CC_SetDMAReqTrigger - * @param TIMx Timer instance - * @param DMAReqTrigger This parameter can be one of the following values: - * @arg @ref LL_TIM_CCDMAREQUEST_CC - * @arg @ref LL_TIM_CCDMAREQUEST_UPDATE - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_SetDMAReqTrigger(TIM_TypeDef *TIMx, uint32_t DMAReqTrigger) -{ - MODIFY_REG(TIMx->CR2, TIM_CR2_CCDS, DMAReqTrigger); -} - -/** - * @brief Get actual trigger of the capture/compare DMA request. - * @rmtoll CR2 CCDS LL_TIM_CC_GetDMAReqTrigger - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_CCDMAREQUEST_CC - * @arg @ref LL_TIM_CCDMAREQUEST_UPDATE - */ -__STATIC_INLINE uint32_t LL_TIM_CC_GetDMAReqTrigger(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR2, TIM_CR2_CCDS)); -} - -/** - * @brief Set the lock level to freeze the - * configuration of several capture/compare parameters. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * the lock mechanism is supported by a timer instance. - * @rmtoll BDTR LOCK LL_TIM_CC_SetLockLevel - * @param TIMx Timer instance - * @param LockLevel This parameter can be one of the following values: - * @arg @ref LL_TIM_LOCKLEVEL_OFF - * @arg @ref LL_TIM_LOCKLEVEL_1 - * @arg @ref LL_TIM_LOCKLEVEL_2 - * @arg @ref LL_TIM_LOCKLEVEL_3 - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_SetLockLevel(TIM_TypeDef *TIMx, uint32_t LockLevel) -{ - MODIFY_REG(TIMx->BDTR, TIM_BDTR_LOCK, LockLevel); -} - -/** - * @brief Enable capture/compare channels. - * @rmtoll CCER CC1E LL_TIM_CC_EnableChannel\n - * CCER CC1NE LL_TIM_CC_EnableChannel\n - * CCER CC2E LL_TIM_CC_EnableChannel\n - * CCER CC2NE LL_TIM_CC_EnableChannel\n - * CCER CC3E LL_TIM_CC_EnableChannel\n - * CCER CC3NE LL_TIM_CC_EnableChannel\n - * CCER CC4E LL_TIM_CC_EnableChannel - * @param TIMx Timer instance - * @param Channels This parameter can be a combination of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_EnableChannel(TIM_TypeDef *TIMx, uint32_t Channels) -{ - SET_BIT(TIMx->CCER, Channels); -} - -/** - * @brief Disable capture/compare channels. - * @rmtoll CCER CC1E LL_TIM_CC_DisableChannel\n - * CCER CC1NE LL_TIM_CC_DisableChannel\n - * CCER CC2E LL_TIM_CC_DisableChannel\n - * CCER CC2NE LL_TIM_CC_DisableChannel\n - * CCER CC3E LL_TIM_CC_DisableChannel\n - * CCER CC3NE LL_TIM_CC_DisableChannel\n - * CCER CC4E LL_TIM_CC_DisableChannel - * @param TIMx Timer instance - * @param Channels This parameter can be a combination of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_DisableChannel(TIM_TypeDef *TIMx, uint32_t Channels) -{ - CLEAR_BIT(TIMx->CCER, Channels); -} - -/** - * @brief Indicate whether channel(s) is(are) enabled. - * @rmtoll CCER CC1E LL_TIM_CC_IsEnabledChannel\n - * CCER CC1NE LL_TIM_CC_IsEnabledChannel\n - * CCER CC2E LL_TIM_CC_IsEnabledChannel\n - * CCER CC2NE LL_TIM_CC_IsEnabledChannel\n - * CCER CC3E LL_TIM_CC_IsEnabledChannel\n - * CCER CC3NE LL_TIM_CC_IsEnabledChannel\n - * CCER CC4E LL_TIM_CC_IsEnabledChannel - * @param TIMx Timer instance - * @param Channels This parameter can be a combination of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_CC_IsEnabledChannel(TIM_TypeDef *TIMx, uint32_t Channels) -{ - return ((READ_BIT(TIMx->CCER, Channels) == (Channels)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Output_Channel Output channel configuration - * @{ - */ -/** - * @brief Configure an output channel. - * @rmtoll CCMR1 CC1S LL_TIM_OC_ConfigOutput\n - * CCMR1 CC2S LL_TIM_OC_ConfigOutput\n - * CCMR2 CC3S LL_TIM_OC_ConfigOutput\n - * CCMR2 CC4S LL_TIM_OC_ConfigOutput\n - * CCER CC1P LL_TIM_OC_ConfigOutput\n - * CCER CC2P LL_TIM_OC_ConfigOutput\n - * CCER CC3P LL_TIM_OC_ConfigOutput\n - * CCER CC4P LL_TIM_OC_ConfigOutput\n - * CR2 OIS1 LL_TIM_OC_ConfigOutput\n - * CR2 OIS2 LL_TIM_OC_ConfigOutput\n - * CR2 OIS3 LL_TIM_OC_ConfigOutput\n - * CR2 OIS4 LL_TIM_OC_ConfigOutput - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param Configuration This parameter must be a combination of all the following values: - * @arg @ref LL_TIM_OCPOLARITY_HIGH or @ref LL_TIM_OCPOLARITY_LOW - * @arg @ref LL_TIM_OCIDLESTATE_LOW or @ref LL_TIM_OCIDLESTATE_HIGH - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_ConfigOutput(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Configuration) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - CLEAR_BIT(*pReg, (TIM_CCMR1_CC1S << SHIFT_TAB_OCxx[iChannel])); - MODIFY_REG(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel]), - (Configuration & TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]); - MODIFY_REG(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel]), - (Configuration & TIM_CR2_OIS1) << SHIFT_TAB_OISx[iChannel]); -} - -/** - * @brief Define the behavior of the output reference signal OCxREF from which - * OCx and OCxN (when relevant) are derived. - * @rmtoll CCMR1 OC1M LL_TIM_OC_SetMode\n - * CCMR1 OC2M LL_TIM_OC_SetMode\n - * CCMR2 OC3M LL_TIM_OC_SetMode\n - * CCMR2 OC4M LL_TIM_OC_SetMode - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_TIM_OCMODE_FROZEN - * @arg @ref LL_TIM_OCMODE_ACTIVE - * @arg @ref LL_TIM_OCMODE_INACTIVE - * @arg @ref LL_TIM_OCMODE_TOGGLE - * @arg @ref LL_TIM_OCMODE_FORCED_INACTIVE - * @arg @ref LL_TIM_OCMODE_FORCED_ACTIVE - * @arg @ref LL_TIM_OCMODE_PWM1 - * @arg @ref LL_TIM_OCMODE_PWM2 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetMode(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Mode) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_OC1M | TIM_CCMR1_CC1S) << SHIFT_TAB_OCxx[iChannel]), Mode << SHIFT_TAB_OCxx[iChannel]); -} - -/** - * @brief Get the output compare mode of an output channel. - * @rmtoll CCMR1 OC1M LL_TIM_OC_GetMode\n - * CCMR1 OC2M LL_TIM_OC_GetMode\n - * CCMR2 OC3M LL_TIM_OC_GetMode\n - * CCMR2 OC4M LL_TIM_OC_GetMode - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_OCMODE_FROZEN - * @arg @ref LL_TIM_OCMODE_ACTIVE - * @arg @ref LL_TIM_OCMODE_INACTIVE - * @arg @ref LL_TIM_OCMODE_TOGGLE - * @arg @ref LL_TIM_OCMODE_FORCED_INACTIVE - * @arg @ref LL_TIM_OCMODE_FORCED_ACTIVE - * @arg @ref LL_TIM_OCMODE_PWM1 - * @arg @ref LL_TIM_OCMODE_PWM2 - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetMode(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - return (READ_BIT(*pReg, ((TIM_CCMR1_OC1M | TIM_CCMR1_CC1S) << SHIFT_TAB_OCxx[iChannel])) >> SHIFT_TAB_OCxx[iChannel]); -} - -/** - * @brief Set the polarity of an output channel. - * @rmtoll CCER CC1P LL_TIM_OC_SetPolarity\n - * CCER CC1NP LL_TIM_OC_SetPolarity\n - * CCER CC2P LL_TIM_OC_SetPolarity\n - * CCER CC2NP LL_TIM_OC_SetPolarity\n - * CCER CC3P LL_TIM_OC_SetPolarity\n - * CCER CC3NP LL_TIM_OC_SetPolarity\n - * CCER CC4P LL_TIM_OC_SetPolarity - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_TIM_OCPOLARITY_HIGH - * @arg @ref LL_TIM_OCPOLARITY_LOW - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetPolarity(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Polarity) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - MODIFY_REG(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel]), Polarity << SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Get the polarity of an output channel. - * @rmtoll CCER CC1P LL_TIM_OC_GetPolarity\n - * CCER CC1NP LL_TIM_OC_GetPolarity\n - * CCER CC2P LL_TIM_OC_GetPolarity\n - * CCER CC2NP LL_TIM_OC_GetPolarity\n - * CCER CC3P LL_TIM_OC_GetPolarity\n - * CCER CC3NP LL_TIM_OC_GetPolarity\n - * CCER CC4P LL_TIM_OC_GetPolarity - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_OCPOLARITY_HIGH - * @arg @ref LL_TIM_OCPOLARITY_LOW - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetPolarity(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - return (READ_BIT(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel])) >> SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Set the IDLE state of an output channel - * @note This function is significant only for the timer instances - * supporting the break feature. Macro IS_TIM_BREAK_INSTANCE(TIMx) - * can be used to check whether or not a timer instance provides - * a break input. - * @rmtoll CR2 OIS1 LL_TIM_OC_SetIdleState\n - * CR2 OIS1N LL_TIM_OC_SetIdleState\n - * CR2 OIS2 LL_TIM_OC_SetIdleState\n - * CR2 OIS2N LL_TIM_OC_SetIdleState\n - * CR2 OIS3 LL_TIM_OC_SetIdleState\n - * CR2 OIS3N LL_TIM_OC_SetIdleState\n - * CR2 OIS4 LL_TIM_OC_SetIdleState - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param IdleState This parameter can be one of the following values: - * @arg @ref LL_TIM_OCIDLESTATE_LOW - * @arg @ref LL_TIM_OCIDLESTATE_HIGH - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetIdleState(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t IdleState) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - MODIFY_REG(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel]), IdleState << SHIFT_TAB_OISx[iChannel]); -} - -/** - * @brief Get the IDLE state of an output channel - * @rmtoll CR2 OIS1 LL_TIM_OC_GetIdleState\n - * CR2 OIS1N LL_TIM_OC_GetIdleState\n - * CR2 OIS2 LL_TIM_OC_GetIdleState\n - * CR2 OIS2N LL_TIM_OC_GetIdleState\n - * CR2 OIS3 LL_TIM_OC_GetIdleState\n - * CR2 OIS3N LL_TIM_OC_GetIdleState\n - * CR2 OIS4 LL_TIM_OC_GetIdleState - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_OCIDLESTATE_LOW - * @arg @ref LL_TIM_OCIDLESTATE_HIGH - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetIdleState(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - return (READ_BIT(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel])) >> SHIFT_TAB_OISx[iChannel]); -} - -/** - * @brief Enable fast mode for the output channel. - * @note Acts only if the channel is configured in PWM1 or PWM2 mode. - * @rmtoll CCMR1 OC1FE LL_TIM_OC_EnableFast\n - * CCMR1 OC2FE LL_TIM_OC_EnableFast\n - * CCMR2 OC3FE LL_TIM_OC_EnableFast\n - * CCMR2 OC4FE LL_TIM_OC_EnableFast - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_EnableFast(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - SET_BIT(*pReg, (TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel])); - -} - -/** - * @brief Disable fast mode for the output channel. - * @rmtoll CCMR1 OC1FE LL_TIM_OC_DisableFast\n - * CCMR1 OC2FE LL_TIM_OC_DisableFast\n - * CCMR2 OC3FE LL_TIM_OC_DisableFast\n - * CCMR2 OC4FE LL_TIM_OC_DisableFast - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_DisableFast(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - CLEAR_BIT(*pReg, (TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel])); - -} - -/** - * @brief Indicates whether fast mode is enabled for the output channel. - * @rmtoll CCMR1 OC1FE LL_TIM_OC_IsEnabledFast\n - * CCMR1 OC2FE LL_TIM_OC_IsEnabledFast\n - * CCMR2 OC3FE LL_TIM_OC_IsEnabledFast\n - * CCMR2 OC4FE LL_TIM_OC_IsEnabledFast\n - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledFast(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - uint32_t bitfield = TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel]; - return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); -} - -/** - * @brief Enable compare register (TIMx_CCRx) preload for the output channel. - * @rmtoll CCMR1 OC1PE LL_TIM_OC_EnablePreload\n - * CCMR1 OC2PE LL_TIM_OC_EnablePreload\n - * CCMR2 OC3PE LL_TIM_OC_EnablePreload\n - * CCMR2 OC4PE LL_TIM_OC_EnablePreload - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_EnablePreload(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - SET_BIT(*pReg, (TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel])); -} - -/** - * @brief Disable compare register (TIMx_CCRx) preload for the output channel. - * @rmtoll CCMR1 OC1PE LL_TIM_OC_DisablePreload\n - * CCMR1 OC2PE LL_TIM_OC_DisablePreload\n - * CCMR2 OC3PE LL_TIM_OC_DisablePreload\n - * CCMR2 OC4PE LL_TIM_OC_DisablePreload - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_DisablePreload(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - CLEAR_BIT(*pReg, (TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel])); -} - -/** - * @brief Indicates whether compare register (TIMx_CCRx) preload is enabled for the output channel. - * @rmtoll CCMR1 OC1PE LL_TIM_OC_IsEnabledPreload\n - * CCMR1 OC2PE LL_TIM_OC_IsEnabledPreload\n - * CCMR2 OC3PE LL_TIM_OC_IsEnabledPreload\n - * CCMR2 OC4PE LL_TIM_OC_IsEnabledPreload\n - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledPreload(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - uint32_t bitfield = TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel]; - return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); -} - -/** - * @brief Enable clearing the output channel on an external event. - * @note This function can only be used in Output compare and PWM modes. It does not work in Forced mode. - * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether - * or not a timer instance can clear the OCxREF signal on an external event. - * @rmtoll CCMR1 OC1CE LL_TIM_OC_EnableClear\n - * CCMR1 OC2CE LL_TIM_OC_EnableClear\n - * CCMR2 OC3CE LL_TIM_OC_EnableClear\n - * CCMR2 OC4CE LL_TIM_OC_EnableClear - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_EnableClear(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - SET_BIT(*pReg, (TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel])); -} - -/** - * @brief Disable clearing the output channel on an external event. - * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether - * or not a timer instance can clear the OCxREF signal on an external event. - * @rmtoll CCMR1 OC1CE LL_TIM_OC_DisableClear\n - * CCMR1 OC2CE LL_TIM_OC_DisableClear\n - * CCMR2 OC3CE LL_TIM_OC_DisableClear\n - * CCMR2 OC4CE LL_TIM_OC_DisableClear - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_DisableClear(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - CLEAR_BIT(*pReg, (TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel])); -} - -/** - * @brief Indicates clearing the output channel on an external event is enabled for the output channel. - * @note This function enables clearing the output channel on an external event. - * @note This function can only be used in Output compare and PWM modes. It does not work in Forced mode. - * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether - * or not a timer instance can clear the OCxREF signal on an external event. - * @rmtoll CCMR1 OC1CE LL_TIM_OC_IsEnabledClear\n - * CCMR1 OC2CE LL_TIM_OC_IsEnabledClear\n - * CCMR2 OC3CE LL_TIM_OC_IsEnabledClear\n - * CCMR2 OC4CE LL_TIM_OC_IsEnabledClear\n - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledClear(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - uint32_t bitfield = TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel]; - return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); -} - -/** - * @brief Set the dead-time delay (delay inserted between the rising edge of the OCxREF signal and the rising edge of - * the Ocx and OCxN signals). - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * dead-time insertion feature is supported by a timer instance. - * @note Helper macro @ref __LL_TIM_CALC_DEADTIME can be used to calculate the DeadTime parameter - * @rmtoll BDTR DTG LL_TIM_OC_SetDeadTime - * @param TIMx Timer instance - * @param DeadTime between Min_Data=0 and Max_Data=255 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetDeadTime(TIM_TypeDef *TIMx, uint32_t DeadTime) -{ - MODIFY_REG(TIMx->BDTR, TIM_BDTR_DTG, DeadTime); -} - -/** - * @brief Set compare value for output channel 1 (TIMx_CCR1). - * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not - * output channel 1 is supported by a timer instance. - * @rmtoll CCR1 CCR1 LL_TIM_OC_SetCompareCH1 - * @param TIMx Timer instance - * @param CompareValue between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetCompareCH1(TIM_TypeDef *TIMx, uint32_t CompareValue) -{ - WRITE_REG(TIMx->CCR1, CompareValue); -} - -/** - * @brief Set compare value for output channel 2 (TIMx_CCR2). - * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not - * output channel 2 is supported by a timer instance. - * @rmtoll CCR2 CCR2 LL_TIM_OC_SetCompareCH2 - * @param TIMx Timer instance - * @param CompareValue between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetCompareCH2(TIM_TypeDef *TIMx, uint32_t CompareValue) -{ - WRITE_REG(TIMx->CCR2, CompareValue); -} - -/** - * @brief Set compare value for output channel 3 (TIMx_CCR3). - * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not - * output channel is supported by a timer instance. - * @rmtoll CCR3 CCR3 LL_TIM_OC_SetCompareCH3 - * @param TIMx Timer instance - * @param CompareValue between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetCompareCH3(TIM_TypeDef *TIMx, uint32_t CompareValue) -{ - WRITE_REG(TIMx->CCR3, CompareValue); -} - -/** - * @brief Set compare value for output channel 4 (TIMx_CCR4). - * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not - * output channel 4 is supported by a timer instance. - * @rmtoll CCR4 CCR4 LL_TIM_OC_SetCompareCH4 - * @param TIMx Timer instance - * @param CompareValue between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetCompareCH4(TIM_TypeDef *TIMx, uint32_t CompareValue) -{ - WRITE_REG(TIMx->CCR4, CompareValue); -} - -/** - * @brief Get compare value (TIMx_CCR1) set for output channel 1. - * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not - * output channel 1 is supported by a timer instance. - * @rmtoll CCR1 CCR1 LL_TIM_OC_GetCompareCH1 - * @param TIMx Timer instance - * @retval CompareValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH1(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR1)); -} - -/** - * @brief Get compare value (TIMx_CCR2) set for output channel 2. - * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not - * output channel 2 is supported by a timer instance. - * @rmtoll CCR2 CCR2 LL_TIM_OC_GetCompareCH2 - * @param TIMx Timer instance - * @retval CompareValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH2(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR2)); -} - -/** - * @brief Get compare value (TIMx_CCR3) set for output channel 3. - * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not - * output channel 3 is supported by a timer instance. - * @rmtoll CCR3 CCR3 LL_TIM_OC_GetCompareCH3 - * @param TIMx Timer instance - * @retval CompareValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH3(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR3)); -} - -/** - * @brief Get compare value (TIMx_CCR4) set for output channel 4. - * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not - * output channel 4 is supported by a timer instance. - * @rmtoll CCR4 CCR4 LL_TIM_OC_GetCompareCH4 - * @param TIMx Timer instance - * @retval CompareValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH4(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR4)); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Input_Channel Input channel configuration - * @{ - */ -/** - * @brief Configure input channel. - * @rmtoll CCMR1 CC1S LL_TIM_IC_Config\n - * CCMR1 IC1PSC LL_TIM_IC_Config\n - * CCMR1 IC1F LL_TIM_IC_Config\n - * CCMR1 CC2S LL_TIM_IC_Config\n - * CCMR1 IC2PSC LL_TIM_IC_Config\n - * CCMR1 IC2F LL_TIM_IC_Config\n - * CCMR2 CC3S LL_TIM_IC_Config\n - * CCMR2 IC3PSC LL_TIM_IC_Config\n - * CCMR2 IC3F LL_TIM_IC_Config\n - * CCMR2 CC4S LL_TIM_IC_Config\n - * CCMR2 IC4PSC LL_TIM_IC_Config\n - * CCMR2 IC4F LL_TIM_IC_Config\n - * CCER CC1P LL_TIM_IC_Config\n - * CCER CC1NP LL_TIM_IC_Config\n - * CCER CC2P LL_TIM_IC_Config\n - * CCER CC2NP LL_TIM_IC_Config\n - * CCER CC3P LL_TIM_IC_Config\n - * CCER CC3NP LL_TIM_IC_Config\n - * CCER CC4P LL_TIM_IC_Config\n - * CCER CC4NP LL_TIM_IC_Config - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param Configuration This parameter must be a combination of all the following values: - * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI or @ref LL_TIM_ACTIVEINPUT_INDIRECTTI or @ref LL_TIM_ACTIVEINPUT_TRC - * @arg @ref LL_TIM_ICPSC_DIV1 or ... or @ref LL_TIM_ICPSC_DIV8 - * @arg @ref LL_TIM_IC_FILTER_FDIV1 or ... or @ref LL_TIM_IC_FILTER_FDIV32_N8 - * @arg @ref LL_TIM_IC_POLARITY_RISING or @ref LL_TIM_IC_POLARITY_FALLING or @ref LL_TIM_IC_POLARITY_BOTHEDGE - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_Config(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Configuration) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC | TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel]), - ((Configuration >> 16U) & (TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC | TIM_CCMR1_CC1S)) \ - << SHIFT_TAB_ICxx[iChannel]); - MODIFY_REG(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]), - (Configuration & (TIM_CCER_CC1NP | TIM_CCER_CC1P)) << SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Set the active input. - * @rmtoll CCMR1 CC1S LL_TIM_IC_SetActiveInput\n - * CCMR1 CC2S LL_TIM_IC_SetActiveInput\n - * CCMR2 CC3S LL_TIM_IC_SetActiveInput\n - * CCMR2 CC4S LL_TIM_IC_SetActiveInput - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param ICActiveInput This parameter can be one of the following values: - * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI - * @arg @ref LL_TIM_ACTIVEINPUT_INDIRECTTI - * @arg @ref LL_TIM_ACTIVEINPUT_TRC - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_SetActiveInput(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICActiveInput) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel]), (ICActiveInput >> 16U) << SHIFT_TAB_ICxx[iChannel]); -} - -/** - * @brief Get the current active input. - * @rmtoll CCMR1 CC1S LL_TIM_IC_GetActiveInput\n - * CCMR1 CC2S LL_TIM_IC_GetActiveInput\n - * CCMR2 CC3S LL_TIM_IC_GetActiveInput\n - * CCMR2 CC4S LL_TIM_IC_GetActiveInput - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI - * @arg @ref LL_TIM_ACTIVEINPUT_INDIRECTTI - * @arg @ref LL_TIM_ACTIVEINPUT_TRC - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetActiveInput(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - return ((READ_BIT(*pReg, ((TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); -} - -/** - * @brief Set the prescaler of input channel. - * @rmtoll CCMR1 IC1PSC LL_TIM_IC_SetPrescaler\n - * CCMR1 IC2PSC LL_TIM_IC_SetPrescaler\n - * CCMR2 IC3PSC LL_TIM_IC_SetPrescaler\n - * CCMR2 IC4PSC LL_TIM_IC_SetPrescaler - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param ICPrescaler This parameter can be one of the following values: - * @arg @ref LL_TIM_ICPSC_DIV1 - * @arg @ref LL_TIM_ICPSC_DIV2 - * @arg @ref LL_TIM_ICPSC_DIV4 - * @arg @ref LL_TIM_ICPSC_DIV8 - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_SetPrescaler(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICPrescaler) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_IC1PSC) << SHIFT_TAB_ICxx[iChannel]), (ICPrescaler >> 16U) << SHIFT_TAB_ICxx[iChannel]); -} - -/** - * @brief Get the current prescaler value acting on an input channel. - * @rmtoll CCMR1 IC1PSC LL_TIM_IC_GetPrescaler\n - * CCMR1 IC2PSC LL_TIM_IC_GetPrescaler\n - * CCMR2 IC3PSC LL_TIM_IC_GetPrescaler\n - * CCMR2 IC4PSC LL_TIM_IC_GetPrescaler - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_ICPSC_DIV1 - * @arg @ref LL_TIM_ICPSC_DIV2 - * @arg @ref LL_TIM_ICPSC_DIV4 - * @arg @ref LL_TIM_ICPSC_DIV8 - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetPrescaler(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - return ((READ_BIT(*pReg, ((TIM_CCMR1_IC1PSC) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); -} - -/** - * @brief Set the input filter duration. - * @rmtoll CCMR1 IC1F LL_TIM_IC_SetFilter\n - * CCMR1 IC2F LL_TIM_IC_SetFilter\n - * CCMR2 IC3F LL_TIM_IC_SetFilter\n - * CCMR2 IC4F LL_TIM_IC_SetFilter - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param ICFilter This parameter can be one of the following values: - * @arg @ref LL_TIM_IC_FILTER_FDIV1 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N2 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N4 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV2_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV2_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV4_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV4_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV8_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV8_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N5 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N5 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N8 - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_SetFilter(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICFilter) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_IC1F) << SHIFT_TAB_ICxx[iChannel]), (ICFilter >> 16U) << SHIFT_TAB_ICxx[iChannel]); -} - -/** - * @brief Get the input filter duration. - * @rmtoll CCMR1 IC1F LL_TIM_IC_GetFilter\n - * CCMR1 IC2F LL_TIM_IC_GetFilter\n - * CCMR2 IC3F LL_TIM_IC_GetFilter\n - * CCMR2 IC4F LL_TIM_IC_GetFilter - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_IC_FILTER_FDIV1 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N2 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N4 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV2_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV2_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV4_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV4_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV8_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV8_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N5 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N5 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N8 - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetFilter(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - return ((READ_BIT(*pReg, ((TIM_CCMR1_IC1F) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); -} - -/** - * @brief Set the input channel polarity. - * @rmtoll CCER CC1P LL_TIM_IC_SetPolarity\n - * CCER CC1NP LL_TIM_IC_SetPolarity\n - * CCER CC2P LL_TIM_IC_SetPolarity\n - * CCER CC2NP LL_TIM_IC_SetPolarity\n - * CCER CC3P LL_TIM_IC_SetPolarity\n - * CCER CC3NP LL_TIM_IC_SetPolarity\n - * CCER CC4P LL_TIM_IC_SetPolarity\n - * CCER CC4NP LL_TIM_IC_SetPolarity - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param ICPolarity This parameter can be one of the following values: - * @arg @ref LL_TIM_IC_POLARITY_RISING - * @arg @ref LL_TIM_IC_POLARITY_FALLING - * @arg @ref LL_TIM_IC_POLARITY_BOTHEDGE - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_SetPolarity(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICPolarity) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - MODIFY_REG(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]), - ICPolarity << SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Get the current input channel polarity. - * @rmtoll CCER CC1P LL_TIM_IC_GetPolarity\n - * CCER CC1NP LL_TIM_IC_GetPolarity\n - * CCER CC2P LL_TIM_IC_GetPolarity\n - * CCER CC2NP LL_TIM_IC_GetPolarity\n - * CCER CC3P LL_TIM_IC_GetPolarity\n - * CCER CC3NP LL_TIM_IC_GetPolarity\n - * CCER CC4P LL_TIM_IC_GetPolarity\n - * CCER CC4NP LL_TIM_IC_GetPolarity - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_IC_POLARITY_RISING - * @arg @ref LL_TIM_IC_POLARITY_FALLING - * @arg @ref LL_TIM_IC_POLARITY_BOTHEDGE - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetPolarity(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - return (READ_BIT(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel])) >> - SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Connect the TIMx_CH1, CH2 and CH3 pins to the TI1 input (XOR combination). - * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides an XOR input. - * @rmtoll CR2 TI1S LL_TIM_IC_EnableXORCombination - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_EnableXORCombination(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR2, TIM_CR2_TI1S); -} - -/** - * @brief Disconnect the TIMx_CH1, CH2 and CH3 pins from the TI1 input. - * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides an XOR input. - * @rmtoll CR2 TI1S LL_TIM_IC_DisableXORCombination - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_DisableXORCombination(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR2, TIM_CR2_TI1S); -} - -/** - * @brief Indicates whether the TIMx_CH1, CH2 and CH3 pins are connectected to the TI1 input. - * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides an XOR input. - * @rmtoll CR2 TI1S LL_TIM_IC_IsEnabledXORCombination - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IC_IsEnabledXORCombination(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->CR2, TIM_CR2_TI1S) == (TIM_CR2_TI1S)) ? 1UL : 0UL); -} - -/** - * @brief Get captured value for input channel 1. - * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not - * input channel 1 is supported by a timer instance. - * @rmtoll CCR1 CCR1 LL_TIM_IC_GetCaptureCH1 - * @param TIMx Timer instance - * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH1(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR1)); -} - -/** - * @brief Get captured value for input channel 2. - * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not - * input channel 2 is supported by a timer instance. - * @rmtoll CCR2 CCR2 LL_TIM_IC_GetCaptureCH2 - * @param TIMx Timer instance - * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH2(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR2)); -} - -/** - * @brief Get captured value for input channel 3. - * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not - * input channel 3 is supported by a timer instance. - * @rmtoll CCR3 CCR3 LL_TIM_IC_GetCaptureCH3 - * @param TIMx Timer instance - * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH3(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR3)); -} - -/** - * @brief Get captured value for input channel 4. - * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not - * input channel 4 is supported by a timer instance. - * @rmtoll CCR4 CCR4 LL_TIM_IC_GetCaptureCH4 - * @param TIMx Timer instance - * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH4(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR4)); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Clock_Selection Counter clock selection - * @{ - */ -/** - * @brief Enable external clock mode 2. - * @note When external clock mode 2 is enabled the counter is clocked by any active edge on the ETRF signal. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode2. - * @rmtoll SMCR ECE LL_TIM_EnableExternalClock - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableExternalClock(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->SMCR, TIM_SMCR_ECE); -} - -/** - * @brief Disable external clock mode 2. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode2. - * @rmtoll SMCR ECE LL_TIM_DisableExternalClock - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableExternalClock(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->SMCR, TIM_SMCR_ECE); -} - -/** - * @brief Indicate whether external clock mode 2 is enabled. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode2. - * @rmtoll SMCR ECE LL_TIM_IsEnabledExternalClock - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledExternalClock(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SMCR, TIM_SMCR_ECE) == (TIM_SMCR_ECE)) ? 1UL : 0UL); -} - -/** - * @brief Set the clock source of the counter clock. - * @note when selected clock source is external clock mode 1, the timer input - * the external clock is applied is selected by calling the @ref LL_TIM_SetTriggerInput() - * function. This timer input must be configured by calling - * the @ref LL_TIM_IC_Config() function. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode1. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode2. - * @rmtoll SMCR SMS LL_TIM_SetClockSource\n - * SMCR ECE LL_TIM_SetClockSource - * @param TIMx Timer instance - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_TIM_CLOCKSOURCE_INTERNAL - * @arg @ref LL_TIM_CLOCKSOURCE_EXT_MODE1 - * @arg @ref LL_TIM_CLOCKSOURCE_EXT_MODE2 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetClockSource(TIM_TypeDef *TIMx, uint32_t ClockSource) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS | TIM_SMCR_ECE, ClockSource); -} - -/** - * @brief Set the encoder interface mode. - * @note Macro IS_TIM_ENCODER_INTERFACE_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports the encoder mode. - * @rmtoll SMCR SMS LL_TIM_SetEncoderMode - * @param TIMx Timer instance - * @param EncoderMode This parameter can be one of the following values: - * @arg @ref LL_TIM_ENCODERMODE_X2_TI1 - * @arg @ref LL_TIM_ENCODERMODE_X2_TI2 - * @arg @ref LL_TIM_ENCODERMODE_X4_TI12 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetEncoderMode(TIM_TypeDef *TIMx, uint32_t EncoderMode) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS, EncoderMode); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Timer_Synchronization Timer synchronisation configuration - * @{ - */ -/** - * @brief Set the trigger output (TRGO) used for timer synchronization . - * @note Macro IS_TIM_MASTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance can operate as a master timer. - * @rmtoll CR2 MMS LL_TIM_SetTriggerOutput - * @param TIMx Timer instance - * @param TimerSynchronization This parameter can be one of the following values: - * @arg @ref LL_TIM_TRGO_RESET - * @arg @ref LL_TIM_TRGO_ENABLE - * @arg @ref LL_TIM_TRGO_UPDATE - * @arg @ref LL_TIM_TRGO_CC1IF - * @arg @ref LL_TIM_TRGO_OC1REF - * @arg @ref LL_TIM_TRGO_OC2REF - * @arg @ref LL_TIM_TRGO_OC3REF - * @arg @ref LL_TIM_TRGO_OC4REF - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetTriggerOutput(TIM_TypeDef *TIMx, uint32_t TimerSynchronization) -{ - MODIFY_REG(TIMx->CR2, TIM_CR2_MMS, TimerSynchronization); -} - -/** - * @brief Set the synchronization mode of a slave timer. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR SMS LL_TIM_SetSlaveMode - * @param TIMx Timer instance - * @param SlaveMode This parameter can be one of the following values: - * @arg @ref LL_TIM_SLAVEMODE_DISABLED - * @arg @ref LL_TIM_SLAVEMODE_RESET - * @arg @ref LL_TIM_SLAVEMODE_GATED - * @arg @ref LL_TIM_SLAVEMODE_TRIGGER - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetSlaveMode(TIM_TypeDef *TIMx, uint32_t SlaveMode) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS, SlaveMode); -} - -/** - * @brief Set the selects the trigger input to be used to synchronize the counter. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR TS LL_TIM_SetTriggerInput - * @param TIMx Timer instance - * @param TriggerInput This parameter can be one of the following values: - * @arg @ref LL_TIM_TS_ITR0 - * @arg @ref LL_TIM_TS_ITR1 - * @arg @ref LL_TIM_TS_ITR2 - * @arg @ref LL_TIM_TS_ITR3 - * @arg @ref LL_TIM_TS_TI1F_ED - * @arg @ref LL_TIM_TS_TI1FP1 - * @arg @ref LL_TIM_TS_TI2FP2 - * @arg @ref LL_TIM_TS_ETRF - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetTriggerInput(TIM_TypeDef *TIMx, uint32_t TriggerInput) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_TS, TriggerInput); -} - -/** - * @brief Enable the Master/Slave mode. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR MSM LL_TIM_EnableMasterSlaveMode - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableMasterSlaveMode(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->SMCR, TIM_SMCR_MSM); -} - -/** - * @brief Disable the Master/Slave mode. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR MSM LL_TIM_DisableMasterSlaveMode - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableMasterSlaveMode(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->SMCR, TIM_SMCR_MSM); -} - -/** - * @brief Indicates whether the Master/Slave mode is enabled. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR MSM LL_TIM_IsEnabledMasterSlaveMode - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledMasterSlaveMode(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SMCR, TIM_SMCR_MSM) == (TIM_SMCR_MSM)) ? 1UL : 0UL); -} - -/** - * @brief Configure the external trigger (ETR) input. - * @note Macro IS_TIM_ETR_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides an external trigger input. - * @rmtoll SMCR ETP LL_TIM_ConfigETR\n - * SMCR ETPS LL_TIM_ConfigETR\n - * SMCR ETF LL_TIM_ConfigETR - * @param TIMx Timer instance - * @param ETRPolarity This parameter can be one of the following values: - * @arg @ref LL_TIM_ETR_POLARITY_NONINVERTED - * @arg @ref LL_TIM_ETR_POLARITY_INVERTED - * @param ETRPrescaler This parameter can be one of the following values: - * @arg @ref LL_TIM_ETR_PRESCALER_DIV1 - * @arg @ref LL_TIM_ETR_PRESCALER_DIV2 - * @arg @ref LL_TIM_ETR_PRESCALER_DIV4 - * @arg @ref LL_TIM_ETR_PRESCALER_DIV8 - * @param ETRFilter This parameter can be one of the following values: - * @arg @ref LL_TIM_ETR_FILTER_FDIV1 - * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N2 - * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N4 - * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV2_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV2_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV4_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV4_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV8_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV8_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N5 - * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N5 - * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N8 - * @retval None - */ -__STATIC_INLINE void LL_TIM_ConfigETR(TIM_TypeDef *TIMx, uint32_t ETRPolarity, uint32_t ETRPrescaler, - uint32_t ETRFilter) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_ETP | TIM_SMCR_ETPS | TIM_SMCR_ETF, ETRPolarity | ETRPrescaler | ETRFilter); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Break_Function Break function configuration - * @{ - */ -/** - * @brief Enable the break function. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR BKE LL_TIM_EnableBRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableBRK(TIM_TypeDef *TIMx) -{ - __IO uint32_t tmpreg; - SET_BIT(TIMx->BDTR, TIM_BDTR_BKE); - /* Note: Any write operation to this bit takes a delay of 1 APB clock cycle to become effective. */ - tmpreg = READ_REG(TIMx->BDTR); - (void)(tmpreg); -} - -/** - * @brief Disable the break function. - * @rmtoll BDTR BKE LL_TIM_DisableBRK - * @param TIMx Timer instance - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableBRK(TIM_TypeDef *TIMx) -{ - __IO uint32_t tmpreg; - CLEAR_BIT(TIMx->BDTR, TIM_BDTR_BKE); - /* Note: Any write operation to this bit takes a delay of 1 APB clock cycle to become effective. */ - tmpreg = READ_REG(TIMx->BDTR); - (void)(tmpreg); -} - -/** - * @brief Configure the break input. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR BKP LL_TIM_ConfigBRK - * @param TIMx Timer instance - * @param BreakPolarity This parameter can be one of the following values: - * @arg @ref LL_TIM_BREAK_POLARITY_LOW - * @arg @ref LL_TIM_BREAK_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_TIM_ConfigBRK(TIM_TypeDef *TIMx, uint32_t BreakPolarity) -{ - __IO uint32_t tmpreg; - MODIFY_REG(TIMx->BDTR, TIM_BDTR_BKP, BreakPolarity); - /* Note: Any write operation to BKP bit takes a delay of 1 APB clock cycle to become effective. */ - tmpreg = READ_REG(TIMx->BDTR); - (void)(tmpreg); -} - -/** - * @brief Select the outputs off state (enabled v.s. disabled) in Idle and Run modes. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR OSSI LL_TIM_SetOffStates\n - * BDTR OSSR LL_TIM_SetOffStates - * @param TIMx Timer instance - * @param OffStateIdle This parameter can be one of the following values: - * @arg @ref LL_TIM_OSSI_DISABLE - * @arg @ref LL_TIM_OSSI_ENABLE - * @param OffStateRun This parameter can be one of the following values: - * @arg @ref LL_TIM_OSSR_DISABLE - * @arg @ref LL_TIM_OSSR_ENABLE - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetOffStates(TIM_TypeDef *TIMx, uint32_t OffStateIdle, uint32_t OffStateRun) -{ - MODIFY_REG(TIMx->BDTR, TIM_BDTR_OSSI | TIM_BDTR_OSSR, OffStateIdle | OffStateRun); -} - -/** - * @brief Enable automatic output (MOE can be set by software or automatically when a break input is active). - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR AOE LL_TIM_EnableAutomaticOutput - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableAutomaticOutput(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->BDTR, TIM_BDTR_AOE); -} - -/** - * @brief Disable automatic output (MOE can be set only by software). - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR AOE LL_TIM_DisableAutomaticOutput - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableAutomaticOutput(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->BDTR, TIM_BDTR_AOE); -} - -/** - * @brief Indicate whether automatic output is enabled. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR AOE LL_TIM_IsEnabledAutomaticOutput - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledAutomaticOutput(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->BDTR, TIM_BDTR_AOE) == (TIM_BDTR_AOE)) ? 1UL : 0UL); -} - -/** - * @brief Enable the outputs (set the MOE bit in TIMx_BDTR register). - * @note The MOE bit in TIMx_BDTR register allows to enable /disable the outputs by - * software and is reset in case of break or break2 event - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR MOE LL_TIM_EnableAllOutputs - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableAllOutputs(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->BDTR, TIM_BDTR_MOE); -} - -/** - * @brief Disable the outputs (reset the MOE bit in TIMx_BDTR register). - * @note The MOE bit in TIMx_BDTR register allows to enable /disable the outputs by - * software and is reset in case of break or break2 event. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR MOE LL_TIM_DisableAllOutputs - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableAllOutputs(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->BDTR, TIM_BDTR_MOE); -} - -/** - * @brief Indicates whether outputs are enabled. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR MOE LL_TIM_IsEnabledAllOutputs - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledAllOutputs(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->BDTR, TIM_BDTR_MOE) == (TIM_BDTR_MOE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_DMA_Burst_Mode DMA burst mode configuration - * @{ - */ -/** - * @brief Configures the timer DMA burst feature. - * @note Macro IS_TIM_DMABURST_INSTANCE(TIMx) can be used to check whether or - * not a timer instance supports the DMA burst mode. - * @rmtoll DCR DBL LL_TIM_ConfigDMABurst\n - * DCR DBA LL_TIM_ConfigDMABurst - * @param TIMx Timer instance - * @param DMABurstBaseAddress This parameter can be one of the following values: - * @arg @ref LL_TIM_DMABURST_BASEADDR_CR1 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CR2 - * @arg @ref LL_TIM_DMABURST_BASEADDR_SMCR - * @arg @ref LL_TIM_DMABURST_BASEADDR_DIER - * @arg @ref LL_TIM_DMABURST_BASEADDR_SR - * @arg @ref LL_TIM_DMABURST_BASEADDR_EGR - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCMR1 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCMR2 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCER - * @arg @ref LL_TIM_DMABURST_BASEADDR_CNT - * @arg @ref LL_TIM_DMABURST_BASEADDR_PSC - * @arg @ref LL_TIM_DMABURST_BASEADDR_ARR - * @arg @ref LL_TIM_DMABURST_BASEADDR_RCR - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR1 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR2 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR3 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR4 - * @arg @ref LL_TIM_DMABURST_BASEADDR_BDTR - * @param DMABurstLength This parameter can be one of the following values: - * @arg @ref LL_TIM_DMABURST_LENGTH_1TRANSFER - * @arg @ref LL_TIM_DMABURST_LENGTH_2TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_3TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_4TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_5TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_6TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_7TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_8TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_9TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_10TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_11TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_12TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_13TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_14TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_15TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_16TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_17TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_18TRANSFERS - * @retval None - */ -__STATIC_INLINE void LL_TIM_ConfigDMABurst(TIM_TypeDef *TIMx, uint32_t DMABurstBaseAddress, uint32_t DMABurstLength) -{ - MODIFY_REG(TIMx->DCR, (TIM_DCR_DBL | TIM_DCR_DBA), (DMABurstBaseAddress | DMABurstLength)); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Timer_Inputs_Remapping Timer input remapping - * @{ - */ -/** - * @brief Remap TIM inputs (input channel, internal/external triggers). - * @note Macro IS_TIM_REMAP_INSTANCE(TIMx) can be used to check whether or not - * a some timer inputs can be remapped. - * @rmtoll TIM1_OR ITR2_RMP LL_TIM_SetRemap\n - * TIM2_OR ITR1_RMP LL_TIM_SetRemap\n - * TIM5_OR ITR1_RMP LL_TIM_SetRemap\n - * TIM5_OR TI4_RMP LL_TIM_SetRemap\n - * TIM9_OR ITR1_RMP LL_TIM_SetRemap\n - * TIM11_OR TI1_RMP LL_TIM_SetRemap\n - * LPTIM1_OR OR LL_TIM_SetRemap - * @param TIMx Timer instance - * @param Remap Remap param depends on the TIMx. Description available only - * in CHM version of the User Manual (not in .pdf). - * Otherwise see Reference Manual description of OR registers. - * - * Below description summarizes "Timer Instance" and "Remap" param combinations: - * - * TIM1: one of the following values - * - * ITR2_RMP can be one of the following values - * @arg @ref LL_TIM_TIM1_ITR2_RMP_TIM3_TRGO (*) - * @arg @ref LL_TIM_TIM1_ITR2_RMP_LPTIM (*) - * - * TIM2: one of the following values - * - * ITR1_RMP can be one of the following values - * @arg @ref LL_TIM_TIM2_ITR1_RMP_TIM8_TRGO - * @arg @ref LL_TIM_TIM2_ITR1_RMP_OTG_FS_SOF - * @arg @ref LL_TIM_TIM2_ITR1_RMP_OTG_HS_SOF - * - * TIM5: one of the following values - * - * @arg @ref LL_TIM_TIM5_TI4_RMP_GPIO - * @arg @ref LL_TIM_TIM5_TI4_RMP_LSI - * @arg @ref LL_TIM_TIM5_TI4_RMP_LSE - * @arg @ref LL_TIM_TIM5_TI4_RMP_RTC - * @arg @ref LL_TIM_TIM5_ITR1_RMP_TIM3_TRGO (*) - * @arg @ref LL_TIM_TIM5_ITR1_RMP_LPTIM (*) - * - * TIM9: one of the following values - * - * ITR1_RMP can be one of the following values - * @arg @ref LL_TIM_TIM9_ITR1_RMP_TIM3_TRGO (*) - * @arg @ref LL_TIM_TIM9_ITR1_RMP_LPTIM (*) - * - * TIM11: one of the following values - * - * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO - * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO1 (*) - * @arg @ref LL_TIM_TIM11_TI1_RMP_HSE_RTC - * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO2 - * @arg @ref LL_TIM_TIM11_TI1_RMP_SPDIFRX (*) - * - * (*) Value not defined in all devices. \n - * - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetRemap(TIM_TypeDef *TIMx, uint32_t Remap) -{ -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM9_ITR1_RMP) - if ((Remap & LL_TIM_LPTIM_REMAP_MASK) == LL_TIM_LPTIM_REMAP_MASK) - { - /* Connect TIMx internal trigger to LPTIM1 output */ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN); - MODIFY_REG(LPTIM1->OR, - (LPTIM_OR_TIM1_ITR2_RMP | LPTIM_OR_TIM5_ITR1_RMP | LPTIM_OR_TIM9_ITR1_RMP), - Remap & ~(LL_TIM_LPTIM_REMAP_MASK)); - } - else - { - MODIFY_REG(TIMx->OR, (Remap >> TIMx_OR_RMP_SHIFT), (Remap & TIMx_OR_RMP_MASK)); - } -#else - MODIFY_REG(TIMx->OR, (Remap >> TIMx_OR_RMP_SHIFT), (Remap & TIMx_OR_RMP_MASK)); -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM9_ITR1_RMP */ -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_FLAG_Management FLAG-Management - * @{ - */ -/** - * @brief Clear the update interrupt flag (UIF). - * @rmtoll SR UIF LL_TIM_ClearFlag_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_UPDATE(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_UIF)); -} - -/** - * @brief Indicate whether update interrupt flag (UIF) is set (update interrupt is pending). - * @rmtoll SR UIF LL_TIM_IsActiveFlag_UPDATE - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_UPDATE(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_UIF) == (TIM_SR_UIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 1 interrupt flag (CC1F). - * @rmtoll SR CC1IF LL_TIM_ClearFlag_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC1(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC1IF)); -} - -/** - * @brief Indicate whether Capture/Compare 1 interrupt flag (CC1F) is set (Capture/Compare 1 interrupt is pending). - * @rmtoll SR CC1IF LL_TIM_IsActiveFlag_CC1 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC1(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC1IF) == (TIM_SR_CC1IF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 2 interrupt flag (CC2F). - * @rmtoll SR CC2IF LL_TIM_ClearFlag_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC2(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC2IF)); -} - -/** - * @brief Indicate whether Capture/Compare 2 interrupt flag (CC2F) is set (Capture/Compare 2 interrupt is pending). - * @rmtoll SR CC2IF LL_TIM_IsActiveFlag_CC2 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC2(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC2IF) == (TIM_SR_CC2IF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 3 interrupt flag (CC3F). - * @rmtoll SR CC3IF LL_TIM_ClearFlag_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC3(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC3IF)); -} - -/** - * @brief Indicate whether Capture/Compare 3 interrupt flag (CC3F) is set (Capture/Compare 3 interrupt is pending). - * @rmtoll SR CC3IF LL_TIM_IsActiveFlag_CC3 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC3(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC3IF) == (TIM_SR_CC3IF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 4 interrupt flag (CC4F). - * @rmtoll SR CC4IF LL_TIM_ClearFlag_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC4(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC4IF)); -} - -/** - * @brief Indicate whether Capture/Compare 4 interrupt flag (CC4F) is set (Capture/Compare 4 interrupt is pending). - * @rmtoll SR CC4IF LL_TIM_IsActiveFlag_CC4 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC4(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC4IF) == (TIM_SR_CC4IF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the commutation interrupt flag (COMIF). - * @rmtoll SR COMIF LL_TIM_ClearFlag_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_COM(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_COMIF)); -} - -/** - * @brief Indicate whether commutation interrupt flag (COMIF) is set (commutation interrupt is pending). - * @rmtoll SR COMIF LL_TIM_IsActiveFlag_COM - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_COM(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_COMIF) == (TIM_SR_COMIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the trigger interrupt flag (TIF). - * @rmtoll SR TIF LL_TIM_ClearFlag_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_TRIG(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_TIF)); -} - -/** - * @brief Indicate whether trigger interrupt flag (TIF) is set (trigger interrupt is pending). - * @rmtoll SR TIF LL_TIM_IsActiveFlag_TRIG - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_TRIG(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_TIF) == (TIM_SR_TIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the break interrupt flag (BIF). - * @rmtoll SR BIF LL_TIM_ClearFlag_BRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_BRK(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_BIF)); -} - -/** - * @brief Indicate whether break interrupt flag (BIF) is set (break interrupt is pending). - * @rmtoll SR BIF LL_TIM_IsActiveFlag_BRK - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_BRK(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_BIF) == (TIM_SR_BIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 1 over-capture interrupt flag (CC1OF). - * @rmtoll SR CC1OF LL_TIM_ClearFlag_CC1OVR - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC1OVR(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC1OF)); -} - -/** - * @brief Indicate whether Capture/Compare 1 over-capture interrupt flag (CC1OF) is set - * (Capture/Compare 1 interrupt is pending). - * @rmtoll SR CC1OF LL_TIM_IsActiveFlag_CC1OVR - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC1OVR(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC1OF) == (TIM_SR_CC1OF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 2 over-capture interrupt flag (CC2OF). - * @rmtoll SR CC2OF LL_TIM_ClearFlag_CC2OVR - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC2OVR(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC2OF)); -} - -/** - * @brief Indicate whether Capture/Compare 2 over-capture interrupt flag (CC2OF) is set - * (Capture/Compare 2 over-capture interrupt is pending). - * @rmtoll SR CC2OF LL_TIM_IsActiveFlag_CC2OVR - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC2OVR(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC2OF) == (TIM_SR_CC2OF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 3 over-capture interrupt flag (CC3OF). - * @rmtoll SR CC3OF LL_TIM_ClearFlag_CC3OVR - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC3OVR(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC3OF)); -} - -/** - * @brief Indicate whether Capture/Compare 3 over-capture interrupt flag (CC3OF) is set - * (Capture/Compare 3 over-capture interrupt is pending). - * @rmtoll SR CC3OF LL_TIM_IsActiveFlag_CC3OVR - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC3OVR(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC3OF) == (TIM_SR_CC3OF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 4 over-capture interrupt flag (CC4OF). - * @rmtoll SR CC4OF LL_TIM_ClearFlag_CC4OVR - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC4OVR(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC4OF)); -} - -/** - * @brief Indicate whether Capture/Compare 4 over-capture interrupt flag (CC4OF) is set - * (Capture/Compare 4 over-capture interrupt is pending). - * @rmtoll SR CC4OF LL_TIM_IsActiveFlag_CC4OVR - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC4OVR(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC4OF) == (TIM_SR_CC4OF)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_IT_Management IT-Management - * @{ - */ -/** - * @brief Enable update interrupt (UIE). - * @rmtoll DIER UIE LL_TIM_EnableIT_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_UPDATE(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_UIE); -} - -/** - * @brief Disable update interrupt (UIE). - * @rmtoll DIER UIE LL_TIM_DisableIT_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_UPDATE(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_UIE); -} - -/** - * @brief Indicates whether the update interrupt (UIE) is enabled. - * @rmtoll DIER UIE LL_TIM_IsEnabledIT_UPDATE - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_UPDATE(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_UIE) == (TIM_DIER_UIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 1 interrupt (CC1IE). - * @rmtoll DIER CC1IE LL_TIM_EnableIT_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_CC1(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC1IE); -} - -/** - * @brief Disable capture/compare 1 interrupt (CC1IE). - * @rmtoll DIER CC1IE LL_TIM_DisableIT_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_CC1(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC1IE); -} - -/** - * @brief Indicates whether the capture/compare 1 interrupt (CC1IE) is enabled. - * @rmtoll DIER CC1IE LL_TIM_IsEnabledIT_CC1 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC1(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC1IE) == (TIM_DIER_CC1IE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 2 interrupt (CC2IE). - * @rmtoll DIER CC2IE LL_TIM_EnableIT_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_CC2(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC2IE); -} - -/** - * @brief Disable capture/compare 2 interrupt (CC2IE). - * @rmtoll DIER CC2IE LL_TIM_DisableIT_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_CC2(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC2IE); -} - -/** - * @brief Indicates whether the capture/compare 2 interrupt (CC2IE) is enabled. - * @rmtoll DIER CC2IE LL_TIM_IsEnabledIT_CC2 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC2(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC2IE) == (TIM_DIER_CC2IE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 3 interrupt (CC3IE). - * @rmtoll DIER CC3IE LL_TIM_EnableIT_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_CC3(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC3IE); -} - -/** - * @brief Disable capture/compare 3 interrupt (CC3IE). - * @rmtoll DIER CC3IE LL_TIM_DisableIT_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_CC3(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC3IE); -} - -/** - * @brief Indicates whether the capture/compare 3 interrupt (CC3IE) is enabled. - * @rmtoll DIER CC3IE LL_TIM_IsEnabledIT_CC3 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC3(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC3IE) == (TIM_DIER_CC3IE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 4 interrupt (CC4IE). - * @rmtoll DIER CC4IE LL_TIM_EnableIT_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_CC4(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC4IE); -} - -/** - * @brief Disable capture/compare 4 interrupt (CC4IE). - * @rmtoll DIER CC4IE LL_TIM_DisableIT_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_CC4(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC4IE); -} - -/** - * @brief Indicates whether the capture/compare 4 interrupt (CC4IE) is enabled. - * @rmtoll DIER CC4IE LL_TIM_IsEnabledIT_CC4 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC4(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC4IE) == (TIM_DIER_CC4IE)) ? 1UL : 0UL); -} - -/** - * @brief Enable commutation interrupt (COMIE). - * @rmtoll DIER COMIE LL_TIM_EnableIT_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_COM(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_COMIE); -} - -/** - * @brief Disable commutation interrupt (COMIE). - * @rmtoll DIER COMIE LL_TIM_DisableIT_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_COM(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_COMIE); -} - -/** - * @brief Indicates whether the commutation interrupt (COMIE) is enabled. - * @rmtoll DIER COMIE LL_TIM_IsEnabledIT_COM - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_COM(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_COMIE) == (TIM_DIER_COMIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable trigger interrupt (TIE). - * @rmtoll DIER TIE LL_TIM_EnableIT_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_TRIG(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_TIE); -} - -/** - * @brief Disable trigger interrupt (TIE). - * @rmtoll DIER TIE LL_TIM_DisableIT_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_TRIG(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_TIE); -} - -/** - * @brief Indicates whether the trigger interrupt (TIE) is enabled. - * @rmtoll DIER TIE LL_TIM_IsEnabledIT_TRIG - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_TRIG(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_TIE) == (TIM_DIER_TIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable break interrupt (BIE). - * @rmtoll DIER BIE LL_TIM_EnableIT_BRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_BRK(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_BIE); -} - -/** - * @brief Disable break interrupt (BIE). - * @rmtoll DIER BIE LL_TIM_DisableIT_BRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_BRK(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_BIE); -} - -/** - * @brief Indicates whether the break interrupt (BIE) is enabled. - * @rmtoll DIER BIE LL_TIM_IsEnabledIT_BRK - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_BRK(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_BIE) == (TIM_DIER_BIE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_DMA_Management DMA Management - * @{ - */ -/** - * @brief Enable update DMA request (UDE). - * @rmtoll DIER UDE LL_TIM_EnableDMAReq_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_UPDATE(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_UDE); -} - -/** - * @brief Disable update DMA request (UDE). - * @rmtoll DIER UDE LL_TIM_DisableDMAReq_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_UPDATE(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_UDE); -} - -/** - * @brief Indicates whether the update DMA request (UDE) is enabled. - * @rmtoll DIER UDE LL_TIM_IsEnabledDMAReq_UPDATE - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_UPDATE(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_UDE) == (TIM_DIER_UDE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 1 DMA request (CC1DE). - * @rmtoll DIER CC1DE LL_TIM_EnableDMAReq_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_CC1(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC1DE); -} - -/** - * @brief Disable capture/compare 1 DMA request (CC1DE). - * @rmtoll DIER CC1DE LL_TIM_DisableDMAReq_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_CC1(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC1DE); -} - -/** - * @brief Indicates whether the capture/compare 1 DMA request (CC1DE) is enabled. - * @rmtoll DIER CC1DE LL_TIM_IsEnabledDMAReq_CC1 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC1(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC1DE) == (TIM_DIER_CC1DE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 2 DMA request (CC2DE). - * @rmtoll DIER CC2DE LL_TIM_EnableDMAReq_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_CC2(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC2DE); -} - -/** - * @brief Disable capture/compare 2 DMA request (CC2DE). - * @rmtoll DIER CC2DE LL_TIM_DisableDMAReq_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_CC2(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC2DE); -} - -/** - * @brief Indicates whether the capture/compare 2 DMA request (CC2DE) is enabled. - * @rmtoll DIER CC2DE LL_TIM_IsEnabledDMAReq_CC2 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC2(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC2DE) == (TIM_DIER_CC2DE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 3 DMA request (CC3DE). - * @rmtoll DIER CC3DE LL_TIM_EnableDMAReq_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_CC3(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC3DE); -} - -/** - * @brief Disable capture/compare 3 DMA request (CC3DE). - * @rmtoll DIER CC3DE LL_TIM_DisableDMAReq_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_CC3(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC3DE); -} - -/** - * @brief Indicates whether the capture/compare 3 DMA request (CC3DE) is enabled. - * @rmtoll DIER CC3DE LL_TIM_IsEnabledDMAReq_CC3 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC3(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC3DE) == (TIM_DIER_CC3DE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 4 DMA request (CC4DE). - * @rmtoll DIER CC4DE LL_TIM_EnableDMAReq_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_CC4(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC4DE); -} - -/** - * @brief Disable capture/compare 4 DMA request (CC4DE). - * @rmtoll DIER CC4DE LL_TIM_DisableDMAReq_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_CC4(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC4DE); -} - -/** - * @brief Indicates whether the capture/compare 4 DMA request (CC4DE) is enabled. - * @rmtoll DIER CC4DE LL_TIM_IsEnabledDMAReq_CC4 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC4(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC4DE) == (TIM_DIER_CC4DE)) ? 1UL : 0UL); -} - -/** - * @brief Enable commutation DMA request (COMDE). - * @rmtoll DIER COMDE LL_TIM_EnableDMAReq_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_COM(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_COMDE); -} - -/** - * @brief Disable commutation DMA request (COMDE). - * @rmtoll DIER COMDE LL_TIM_DisableDMAReq_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_COM(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_COMDE); -} - -/** - * @brief Indicates whether the commutation DMA request (COMDE) is enabled. - * @rmtoll DIER COMDE LL_TIM_IsEnabledDMAReq_COM - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_COM(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_COMDE) == (TIM_DIER_COMDE)) ? 1UL : 0UL); -} - -/** - * @brief Enable trigger interrupt (TDE). - * @rmtoll DIER TDE LL_TIM_EnableDMAReq_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_TRIG(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_TDE); -} - -/** - * @brief Disable trigger interrupt (TDE). - * @rmtoll DIER TDE LL_TIM_DisableDMAReq_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_TRIG(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_TDE); -} - -/** - * @brief Indicates whether the trigger interrupt (TDE) is enabled. - * @rmtoll DIER TDE LL_TIM_IsEnabledDMAReq_TRIG - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_TRIG(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_TDE) == (TIM_DIER_TDE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_EVENT_Management EVENT-Management - * @{ - */ -/** - * @brief Generate an update event. - * @rmtoll EGR UG LL_TIM_GenerateEvent_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_UPDATE(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_UG); -} - -/** - * @brief Generate Capture/Compare 1 event. - * @rmtoll EGR CC1G LL_TIM_GenerateEvent_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_CC1(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_CC1G); -} - -/** - * @brief Generate Capture/Compare 2 event. - * @rmtoll EGR CC2G LL_TIM_GenerateEvent_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_CC2(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_CC2G); -} - -/** - * @brief Generate Capture/Compare 3 event. - * @rmtoll EGR CC3G LL_TIM_GenerateEvent_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_CC3(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_CC3G); -} - -/** - * @brief Generate Capture/Compare 4 event. - * @rmtoll EGR CC4G LL_TIM_GenerateEvent_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_CC4(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_CC4G); -} - -/** - * @brief Generate commutation event. - * @rmtoll EGR COMG LL_TIM_GenerateEvent_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_COM(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_COMG); -} - -/** - * @brief Generate trigger event. - * @rmtoll EGR TG LL_TIM_GenerateEvent_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_TRIG(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_TG); -} - -/** - * @brief Generate break event. - * @rmtoll EGR BG LL_TIM_GenerateEvent_BRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_BRK(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_BG); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup TIM_LL_EF_Init Initialisation and deinitialisation functions - * @{ - */ - -ErrorStatus LL_TIM_DeInit(TIM_TypeDef *TIMx); -void LL_TIM_StructInit(LL_TIM_InitTypeDef *TIM_InitStruct); -ErrorStatus LL_TIM_Init(TIM_TypeDef *TIMx, LL_TIM_InitTypeDef *TIM_InitStruct); -void LL_TIM_OC_StructInit(LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct); -ErrorStatus LL_TIM_OC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct); -void LL_TIM_IC_StructInit(LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); -ErrorStatus LL_TIM_IC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_IC_InitTypeDef *TIM_IC_InitStruct); -void LL_TIM_ENCODER_StructInit(LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct); -ErrorStatus LL_TIM_ENCODER_Init(TIM_TypeDef *TIMx, LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct); -void LL_TIM_HALLSENSOR_StructInit(LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct); -ErrorStatus LL_TIM_HALLSENSOR_Init(TIM_TypeDef *TIMx, LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct); -void LL_TIM_BDTR_StructInit(LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct); -ErrorStatus LL_TIM_BDTR_Init(TIM_TypeDef *TIMx, LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* TIM1 || TIM2 || TIM3 || TIM4 || TIM5 || TIM6 || TIM7 || TIM8 || TIM9 || TIM10 || TIM11 || TIM12 || TIM13 || TIM14 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_TIM_H */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h deleted file mode 100644 index 86ee731cb3c920d..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h +++ /dev/null @@ -1,2523 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usart.h - * @author MCD Application Team - * @brief Header file of USART LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_USART_H -#define __STM32F4xx_LL_USART_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8) || defined (UART9) || defined (UART10) - -/** @defgroup USART_LL USART - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup USART_LL_Private_Constants USART Private Constants - * @{ - */ - -/* Defines used for the bit position in the register and perform offsets*/ -#define USART_POSITION_GTPR_GT USART_GTPR_GT_Pos -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_Private_Macros USART Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_ES_INIT USART Exported Init structures - * @{ - */ - -/** - * @brief LL USART Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This field defines expected Usart communication baud rate. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/ - - uint32_t DataWidth; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref USART_LL_EC_DATAWIDTH. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref USART_LL_EC_STOPBITS. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref USART_LL_EC_PARITY. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/ - - uint32_t TransferDirection; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_DIRECTION. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/ - - uint32_t HardwareFlowControl; /*!< Specifies whether the hardware flow control mode is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_HWCONTROL. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/ - - uint32_t OverSampling; /*!< Specifies whether USART oversampling mode is 16 or 8. - This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/ - -} LL_USART_InitTypeDef; - -/** - * @brief LL USART Clock Init Structure definition - */ -typedef struct -{ - uint32_t ClockOutput; /*!< Specifies whether the USART clock is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_CLOCK. - - USART HW configuration can be modified afterwards using unitary functions - @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput(). - For more details, refer to description of this function. */ - - uint32_t ClockPolarity; /*!< Specifies the steady state of the serial clock. - This parameter can be a value of @ref USART_LL_EC_POLARITY. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity(). - For more details, refer to description of this function. */ - - uint32_t ClockPhase; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref USART_LL_EC_PHASE. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase(). - For more details, refer to description of this function. */ - - uint32_t LastBitClockPulse; /*!< Specifies whether the clock pulse corresponding to the last transmitted - data bit (MSB) has to be output on the SCLK pin in synchronous mode. - This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput(). - For more details, refer to description of this function. */ - -} LL_USART_ClockInitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup USART_LL_Exported_Constants USART Exported Constants - * @{ - */ - -/** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_USART_ReadReg function - * @{ - */ -#define LL_USART_SR_PE USART_SR_PE /*!< Parity error flag */ -#define LL_USART_SR_FE USART_SR_FE /*!< Framing error flag */ -#define LL_USART_SR_NE USART_SR_NE /*!< Noise detected flag */ -#define LL_USART_SR_ORE USART_SR_ORE /*!< Overrun error flag */ -#define LL_USART_SR_IDLE USART_SR_IDLE /*!< Idle line detected flag */ -#define LL_USART_SR_RXNE USART_SR_RXNE /*!< Read data register not empty flag */ -#define LL_USART_SR_TC USART_SR_TC /*!< Transmission complete flag */ -#define LL_USART_SR_TXE USART_SR_TXE /*!< Transmit data register empty flag */ -#define LL_USART_SR_LBD USART_SR_LBD /*!< LIN break detection flag */ -#define LL_USART_SR_CTS USART_SR_CTS /*!< CTS flag */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions - * @{ - */ -#define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */ -#define LL_USART_CR1_RXNEIE USART_CR1_RXNEIE /*!< Read data register not empty interrupt enable */ -#define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */ -#define LL_USART_CR1_TXEIE USART_CR1_TXEIE /*!< Transmit data register empty interrupt enable */ -#define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */ -#define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */ -#define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */ -#define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_DIRECTION Communication Direction - * @{ - */ -#define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */ -#define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */ -#define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */ -#define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_PARITY Parity Control - * @{ - */ -#define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */ -#define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */ -#define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_WAKEUP Wakeup - * @{ - */ -#define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */ -#define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_DATAWIDTH Datawidth - * @{ - */ -#define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */ -#define LL_USART_DATAWIDTH_9B USART_CR1_M /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_OVERSAMPLING Oversampling - * @{ - */ -#define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */ -#define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_EC_CLOCK Clock Signal - * @{ - */ - -#define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */ -#define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse - * @{ - */ -#define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */ -#define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_PHASE Clock Phase - * @{ - */ -#define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */ -#define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_POLARITY Clock Polarity - * @{ - */ -#define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/ -#define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_STOPBITS Stop Bits - * @{ - */ -#define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */ -#define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */ -#define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */ -#define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_HWCONTROL Hardware Control - * @{ - */ -#define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */ -#define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */ -#define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */ -#define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_IRDA_POWER IrDA Power - * @{ - */ -#define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */ -#define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length - * @{ - */ -#define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */ -#define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup USART_LL_Exported_Macros USART Exported Macros - * @{ - */ - -/** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in USART register - * @param __INSTANCE__ USART Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in USART register - * @param __INSTANCE__ USART Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper - * @{ - */ - -/** - * @brief Compute USARTDIV value according to Peripheral Clock and - * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned) - * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance - * @param __BAUDRATE__ Baud rate value to achieve - * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case - */ -#define __LL_USART_DIV_SAMPLING8_100(__PERIPHCLK__, __BAUDRATE__) ((uint32_t)((((uint64_t)(__PERIPHCLK__))*25)/(2*((uint64_t)(__BAUDRATE__))))) -#define __LL_USART_DIVMANT_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__))/100) -#define __LL_USART_DIVFRAQ_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) ((((__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 8)\ - + 50) / 100) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07) */ -#define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \ - ((__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0xF8) << 1)) + \ - (__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0x07)) - -/** - * @brief Compute USARTDIV value according to Peripheral Clock and - * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned) - * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance - * @param __BAUDRATE__ Baud rate value to achieve - * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case - */ -#define __LL_USART_DIV_SAMPLING16_100(__PERIPHCLK__, __BAUDRATE__) ((uint32_t)((((uint64_t)(__PERIPHCLK__))*25)/(4*((uint64_t)(__BAUDRATE__))))) -#define __LL_USART_DIVMANT_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__))/100) -#define __LL_USART_DIVFRAQ_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) ((((__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 16)\ - + 50) / 100) -/* USART BRR = mantissa + overflow + fraction - = (USART DIVMANT << 4) + (USART DIVFRAQ & 0xF0) + (USART DIVFRAQ & 0x0F) */ -#define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \ - (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0xF0)) + \ - (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0x0F)) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup USART_LL_Exported_Functions USART Exported Functions - * @{ - */ - -/** @defgroup USART_LL_EF_Configuration Configuration functions - * @{ - */ - -/** - * @brief USART Enable - * @rmtoll CR1 UE LL_USART_Enable - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_Enable(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_UE); -} - -/** - * @brief USART Disable (all USART prescalers and outputs are disabled) - * @note When USART is disabled, USART prescalers and outputs are stopped immediately, - * and current operations are discarded. The configuration of the USART is kept, but all the status - * flags, in the USARTx_SR are set to their default values. - * @rmtoll CR1 UE LL_USART_Disable - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_Disable(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR1, USART_CR1_UE); -} - -/** - * @brief Indicate if USART is enabled - * @rmtoll CR1 UE LL_USART_IsEnabled - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabled(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_UE) == (USART_CR1_UE)); -} - -/** - * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit) - * @rmtoll CR1 RE LL_USART_EnableDirectionRx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDirectionRx(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_RE); -} - -/** - * @brief Receiver Disable - * @rmtoll CR1 RE LL_USART_DisableDirectionRx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDirectionRx(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_RE); -} - -/** - * @brief Transmitter Enable - * @rmtoll CR1 TE LL_USART_EnableDirectionTx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDirectionTx(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TE); -} - -/** - * @brief Transmitter Disable - * @rmtoll CR1 TE LL_USART_DisableDirectionTx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDirectionTx(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TE); -} - -/** - * @brief Configure simultaneously enabled/disabled states - * of Transmitter and Receiver - * @rmtoll CR1 RE LL_USART_SetTransferDirection\n - * CR1 TE LL_USART_SetTransferDirection - * @param USARTx USART Instance - * @param TransferDirection This parameter can be one of the following values: - * @arg @ref LL_USART_DIRECTION_NONE - * @arg @ref LL_USART_DIRECTION_RX - * @arg @ref LL_USART_DIRECTION_TX - * @arg @ref LL_USART_DIRECTION_TX_RX - * @retval None - */ -__STATIC_INLINE void LL_USART_SetTransferDirection(USART_TypeDef *USARTx, uint32_t TransferDirection) -{ - ATOMIC_MODIFY_REG(USARTx->CR1, USART_CR1_RE | USART_CR1_TE, TransferDirection); -} - -/** - * @brief Return enabled/disabled states of Transmitter and Receiver - * @rmtoll CR1 RE LL_USART_GetTransferDirection\n - * CR1 TE LL_USART_GetTransferDirection - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_DIRECTION_NONE - * @arg @ref LL_USART_DIRECTION_RX - * @arg @ref LL_USART_DIRECTION_TX - * @arg @ref LL_USART_DIRECTION_TX_RX - */ -__STATIC_INLINE uint32_t LL_USART_GetTransferDirection(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_RE | USART_CR1_TE)); -} - -/** - * @brief Configure Parity (enabled/disabled and parity mode if enabled). - * @note This function selects if hardware parity control (generation and detection) is enabled or disabled. - * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position - * (9th or 8th bit depending on data width) and parity is checked on the received data. - * @rmtoll CR1 PS LL_USART_SetParity\n - * CR1 PCE LL_USART_SetParity - * @param USARTx USART Instance - * @param Parity This parameter can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - * @retval None - */ -__STATIC_INLINE void LL_USART_SetParity(USART_TypeDef *USARTx, uint32_t Parity) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE, Parity); -} - -/** - * @brief Return Parity configuration (enabled/disabled and parity mode if enabled) - * @rmtoll CR1 PS LL_USART_GetParity\n - * CR1 PCE LL_USART_GetParity - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - */ -__STATIC_INLINE uint32_t LL_USART_GetParity(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE)); -} - -/** - * @brief Set Receiver Wake Up method from Mute mode. - * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod - * @param USARTx USART Instance - * @param Method This parameter can be one of the following values: - * @arg @ref LL_USART_WAKEUP_IDLELINE - * @arg @ref LL_USART_WAKEUP_ADDRESSMARK - * @retval None - */ -__STATIC_INLINE void LL_USART_SetWakeUpMethod(USART_TypeDef *USARTx, uint32_t Method) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_WAKE, Method); -} - -/** - * @brief Return Receiver Wake Up method from Mute mode - * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_WAKEUP_IDLELINE - * @arg @ref LL_USART_WAKEUP_ADDRESSMARK - */ -__STATIC_INLINE uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_WAKE)); -} - -/** - * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits) - * @rmtoll CR1 M LL_USART_SetDataWidth - * @param USARTx USART Instance - * @param DataWidth This parameter can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - * @retval None - */ -__STATIC_INLINE void LL_USART_SetDataWidth(USART_TypeDef *USARTx, uint32_t DataWidth) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_M, DataWidth); -} - -/** - * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits) - * @rmtoll CR1 M LL_USART_GetDataWidth - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - */ -__STATIC_INLINE uint32_t LL_USART_GetDataWidth(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_M)); -} - -/** - * @brief Set Oversampling to 8-bit or 16-bit mode - * @rmtoll CR1 OVER8 LL_USART_SetOverSampling - * @param USARTx USART Instance - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetOverSampling(USART_TypeDef *USARTx, uint32_t OverSampling) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_OVER8, OverSampling); -} - -/** - * @brief Return Oversampling mode - * @rmtoll CR1 OVER8 LL_USART_GetOverSampling - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - */ -__STATIC_INLINE uint32_t LL_USART_GetOverSampling(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_OVER8)); -} - -/** - * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput - * @param USARTx USART Instance - * @param LastBitClockPulse This parameter can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - * @retval None - */ -__STATIC_INLINE void LL_USART_SetLastClkPulseOutput(USART_TypeDef *USARTx, uint32_t LastBitClockPulse) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_LBCL, LastBitClockPulse); -} - -/** - * @brief Retrieve Clock pulse of the last data bit output configuration - * (Last bit Clock pulse output to the SCLK pin or not) - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - */ -__STATIC_INLINE uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBCL)); -} - -/** - * @brief Select the phase of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPHA LL_USART_SetClockPhase - * @param USARTx USART Instance - * @param ClockPhase This parameter can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - * @retval None - */ -__STATIC_INLINE void LL_USART_SetClockPhase(USART_TypeDef *USARTx, uint32_t ClockPhase) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPHA, ClockPhase); -} - -/** - * @brief Return phase of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPHA LL_USART_GetClockPhase - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - */ -__STATIC_INLINE uint32_t LL_USART_GetClockPhase(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPHA)); -} - -/** - * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPOL LL_USART_SetClockPolarity - * @param USARTx USART Instance - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_USART_SetClockPolarity(USART_TypeDef *USARTx, uint32_t ClockPolarity) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPOL, ClockPolarity); -} - -/** - * @brief Return polarity of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPOL LL_USART_GetClockPolarity - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - */ -__STATIC_INLINE uint32_t LL_USART_GetClockPolarity(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPOL)); -} - -/** - * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse) - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function - * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function - * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function - * @rmtoll CR2 CPHA LL_USART_ConfigClock\n - * CR2 CPOL LL_USART_ConfigClock\n - * CR2 LBCL LL_USART_ConfigClock - * @param USARTx USART Instance - * @param Phase This parameter can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - * @param LBCPOutput This parameter can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigClock(USART_TypeDef *USARTx, uint32_t Phase, uint32_t Polarity, uint32_t LBCPOutput) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_LBCL, Phase | Polarity | LBCPOutput); -} - -/** - * @brief Enable Clock output on SCLK pin - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSCLKOutput(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Disable Clock output on SCLK pin - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSCLKOutput(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Indicate if Clock output on SCLK pin is enabled - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_CLKEN) == (USART_CR2_CLKEN)); -} - -/** - * @brief Set the length of the stop bits - * @rmtoll CR2 STOP LL_USART_SetStopBitsLength - * @param USARTx USART Instance - * @param StopBits This parameter can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetStopBitsLength(USART_TypeDef *USARTx, uint32_t StopBits) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits); -} - -/** - * @brief Retrieve the length of the stop bits - * @rmtoll CR2 STOP LL_USART_GetStopBitsLength - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - */ -__STATIC_INLINE uint32_t LL_USART_GetStopBitsLength(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_STOP)); -} - -/** - * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits) - * @note Call of this function is equivalent to following function call sequence : - * - Data Width configuration using @ref LL_USART_SetDataWidth() function - * - Parity Control and mode configuration using @ref LL_USART_SetParity() function - * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function - * @rmtoll CR1 PS LL_USART_ConfigCharacter\n - * CR1 PCE LL_USART_ConfigCharacter\n - * CR1 M LL_USART_ConfigCharacter\n - * CR2 STOP LL_USART_ConfigCharacter - * @param USARTx USART Instance - * @param DataWidth This parameter can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - * @param Parity This parameter can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - * @param StopBits This parameter can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigCharacter(USART_TypeDef *USARTx, uint32_t DataWidth, uint32_t Parity, - uint32_t StopBits) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE | USART_CR1_M, Parity | DataWidth); - MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits); -} - -/** - * @brief Set Address of the USART node. - * @note This is used in multiprocessor communication during Mute mode or Stop mode, - * for wake up with address mark detection. - * @rmtoll CR2 ADD LL_USART_SetNodeAddress - * @param USARTx USART Instance - * @param NodeAddress 4 bit Address of the USART node. - * @retval None - */ -__STATIC_INLINE void LL_USART_SetNodeAddress(USART_TypeDef *USARTx, uint32_t NodeAddress) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_ADD, (NodeAddress & USART_CR2_ADD)); -} - -/** - * @brief Return 4 bit Address of the USART node as set in ADD field of CR2. - * @note only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant) - * @rmtoll CR2 ADD LL_USART_GetNodeAddress - * @param USARTx USART Instance - * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255) - */ -__STATIC_INLINE uint32_t LL_USART_GetNodeAddress(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ADD)); -} - -/** - * @brief Enable RTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_RTSE); -} - -/** - * @brief Disable RTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_RTSE); -} - -/** - * @brief Enable CTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_CTSE); -} - -/** - * @brief Disable CTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_CTSE); -} - -/** - * @brief Configure HW Flow Control mode (both CTS and RTS) - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n - * CR3 CTSE LL_USART_SetHWFlowCtrl - * @param USARTx USART Instance - * @param HardwareFlowControl This parameter can be one of the following values: - * @arg @ref LL_USART_HWCONTROL_NONE - * @arg @ref LL_USART_HWCONTROL_RTS - * @arg @ref LL_USART_HWCONTROL_CTS - * @arg @ref LL_USART_HWCONTROL_RTS_CTS - * @retval None - */ -__STATIC_INLINE void LL_USART_SetHWFlowCtrl(USART_TypeDef *USARTx, uint32_t HardwareFlowControl) -{ - MODIFY_REG(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE, HardwareFlowControl); -} - -/** - * @brief Return HW Flow Control configuration (both CTS and RTS) - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n - * CR3 CTSE LL_USART_GetHWFlowCtrl - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_HWCONTROL_NONE - * @arg @ref LL_USART_HWCONTROL_RTS - * @arg @ref LL_USART_HWCONTROL_CTS - * @arg @ref LL_USART_HWCONTROL_RTS_CTS - */ -__STATIC_INLINE uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE)); -} - -/** - * @brief Enable One bit sampling method - * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableOneBitSamp(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_ONEBIT); -} - -/** - * @brief Disable One bit sampling method - * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableOneBitSamp(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_ONEBIT); -} - -/** - * @brief Indicate if One bit sampling method is enabled - * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_ONEBIT) == (USART_CR3_ONEBIT)); -} - -/** - * @brief Configure USART BRR register for achieving expected Baud Rate value. - * @note Compute and set USARTDIV value in BRR Register (full BRR content) - * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values - * @note Peripheral clock and Baud rate values provided as function parameters should be valid - * (Baud rate value != 0) - * @rmtoll BRR BRR LL_USART_SetBaudRate - * @param USARTx USART Instance - * @param PeriphClk Peripheral Clock - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @param BaudRate Baud Rate - * @retval None - */ -__STATIC_INLINE void LL_USART_SetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling, - uint32_t BaudRate) -{ - if (OverSampling == LL_USART_OVERSAMPLING_8) - { - USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk, BaudRate)); - } - else - { - USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk, BaudRate)); - } -} - -/** - * @brief Return current Baud Rate value, according to USARTDIV present in BRR register - * (full BRR content), and to used Peripheral Clock and Oversampling mode values - * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned. - * @rmtoll BRR BRR LL_USART_GetBaudRate - * @param USARTx USART Instance - * @param PeriphClk Peripheral Clock - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @retval Baud Rate - */ -__STATIC_INLINE uint32_t LL_USART_GetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling) -{ - uint32_t usartdiv = 0x0U; - uint32_t brrresult = 0x0U; - - usartdiv = USARTx->BRR; - - if (OverSampling == LL_USART_OVERSAMPLING_8) - { - if ((usartdiv & 0xFFF7U) != 0U) - { - usartdiv = (uint16_t)((usartdiv & 0xFFF0U) | ((usartdiv & 0x0007U) << 1U)) ; - brrresult = (PeriphClk * 2U) / usartdiv; - } - } - else - { - if ((usartdiv & 0xFFFFU) != 0U) - { - brrresult = PeriphClk / usartdiv; - } - } - return (brrresult); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature - * @{ - */ - -/** - * @brief Enable IrDA mode - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_EnableIrda - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIrda(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Disable IrDA mode - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_DisableIrda - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIrda(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Indicate if IrDA mode is enabled - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_IsEnabledIrda - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIrda(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_IREN) == (USART_CR3_IREN)); -} - -/** - * @brief Configure IrDA Power Mode (Normal or Low Power) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode - * @param USARTx USART Instance - * @param PowerMode This parameter can be one of the following values: - * @arg @ref LL_USART_IRDA_POWER_NORMAL - * @arg @ref LL_USART_IRDA_POWER_LOW - * @retval None - */ -__STATIC_INLINE void LL_USART_SetIrdaPowerMode(USART_TypeDef *USARTx, uint32_t PowerMode) -{ - MODIFY_REG(USARTx->CR3, USART_CR3_IRLP, PowerMode); -} - -/** - * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_IRDA_POWER_NORMAL - * @arg @ref LL_USART_PHASE_2EDGE - */ -__STATIC_INLINE uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_IRLP)); -} - -/** - * @brief Set Irda prescaler value, used for dividing the USART clock source - * to achieve the Irda Low Power frequency (8 bits value) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler - * @param USARTx USART Instance - * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_SetIrdaPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue); -} - -/** - * @brief Return Irda prescaler value, used for dividing the USART clock source - * to achieve the Irda Low Power frequency (8 bits value) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_GetIrdaPrescaler - * @param USARTx USART Instance - * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF) - */ -__STATIC_INLINE uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature - * @{ - */ - -/** - * @brief Enable Smartcard NACK transmission - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSmartcardNACK(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_NACK); -} - -/** - * @brief Disable Smartcard NACK transmission - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSmartcardNACK(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_NACK); -} - -/** - * @brief Indicate if Smartcard NACK transmission is enabled - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_NACK) == (USART_CR3_NACK)); -} - -/** - * @brief Enable Smartcard mode - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_EnableSmartcard - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSmartcard(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Disable Smartcard mode - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_DisableSmartcard - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSmartcard(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Indicate if Smartcard mode is enabled - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_SCEN) == (USART_CR3_SCEN)); -} - -/** - * @brief Set Smartcard prescaler value, used for dividing the USART clock - * source to provide the SMARTCARD Clock (5 bits value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler - * @param USARTx USART Instance - * @param PrescalerValue Value between Min_Data=0 and Max_Data=31 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetSmartcardPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue); -} - -/** - * @brief Return Smartcard prescaler value, used for dividing the USART clock - * source to provide the SMARTCARD Clock (5 bits value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler - * @param USARTx USART Instance - * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31) - */ -__STATIC_INLINE uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC)); -} - -/** - * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods - * (GT[7:0] bits : Guard time value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime - * @param USARTx USART Instance - * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_SetSmartcardGuardTime(USART_TypeDef *USARTx, uint32_t GuardTime) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_GT, GuardTime << USART_POSITION_GTPR_GT); -} - -/** - * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods - * (GT[7:0] bits : Guard time value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime - * @param USARTx USART Instance - * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF) - */ -__STATIC_INLINE uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_GT) >> USART_POSITION_GTPR_GT); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature - * @{ - */ - -/** - * @brief Enable Single Wire Half-Duplex mode - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableHalfDuplex(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Disable Single Wire Half-Duplex mode - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableHalfDuplex(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Indicate if Single Wire Half-Duplex mode is enabled - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_HDSEL) == (USART_CR3_HDSEL)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature - * @{ - */ - -/** - * @brief Set LIN Break Detection Length - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen - * @param USARTx USART Instance - * @param LINBDLength This parameter can be one of the following values: - * @arg @ref LL_USART_LINBREAK_DETECT_10B - * @arg @ref LL_USART_LINBREAK_DETECT_11B - * @retval None - */ -__STATIC_INLINE void LL_USART_SetLINBrkDetectionLen(USART_TypeDef *USARTx, uint32_t LINBDLength) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_LBDL, LINBDLength); -} - -/** - * @brief Return LIN Break Detection Length - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_LINBREAK_DETECT_10B - * @arg @ref LL_USART_LINBREAK_DETECT_11B - */ -__STATIC_INLINE uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBDL)); -} - -/** - * @brief Enable LIN mode - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_EnableLIN - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableLIN(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Disable LIN mode - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_DisableLIN - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableLIN(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Indicate if LIN mode is enabled - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledLIN(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_LINEN) == (USART_CR2_LINEN)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services - * @{ - */ - -/** - * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART) - * @note In UART mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * @note Other remaining configurations items related to Asynchronous Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n - * CR2 CLKEN LL_USART_ConfigAsyncMode\n - * CR3 SCEN LL_USART_ConfigAsyncMode\n - * CR3 IREN LL_USART_ConfigAsyncMode\n - * CR3 HDSEL LL_USART_ConfigAsyncMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigAsyncMode(USART_TypeDef *USARTx) -{ - /* In Asynchronous mode, the following bits must be kept cleared: - - LINEN, CLKEN bits in the USART_CR2 register, - - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL)); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Synchronous Mode - * @note In Synchronous mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also sets the USART in Synchronous mode. - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function - * @note Other remaining configurations items related to Synchronous Mode - * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n - * CR2 CLKEN LL_USART_ConfigSyncMode\n - * CR3 SCEN LL_USART_ConfigSyncMode\n - * CR3 IREN LL_USART_ConfigSyncMode\n - * CR3 HDSEL LL_USART_ConfigSyncMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigSyncMode(USART_TypeDef *USARTx) -{ - /* In Synchronous mode, the following bits must be kept cleared: - - LINEN bit in the USART_CR2 register, - - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL)); - /* set the UART/USART in Synchronous mode */ - SET_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in LIN Mode - * @note In LIN mode, the following bits must be kept cleared: - * - STOP and CLKEN bits in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also set the UART/USART in LIN mode. - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function - * @note Other remaining configurations items related to LIN Mode - * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using - * dedicated functions - * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n - * CR2 STOP LL_USART_ConfigLINMode\n - * CR2 LINEN LL_USART_ConfigLINMode\n - * CR3 IREN LL_USART_ConfigLINMode\n - * CR3 SCEN LL_USART_ConfigLINMode\n - * CR3 HDSEL LL_USART_ConfigLINMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigLINMode(USART_TypeDef *USARTx) -{ - /* In LIN mode, the following bits must be kept cleared: - - STOP and CLKEN bits in the USART_CR2 register, - - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_CLKEN | USART_CR2_STOP)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_SCEN | USART_CR3_HDSEL)); - /* Set the UART/USART in LIN mode */ - SET_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode - * @note In Half Duplex mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * This function also sets the UART/USART in Half Duplex mode. - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function - * @note Other remaining configurations items related to Half Duplex Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n - * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n - * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n - * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n - * CR3 IREN LL_USART_ConfigHalfDuplexMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigHalfDuplexMode(USART_TypeDef *USARTx) -{ - /* In Half Duplex mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN)); - /* set the UART/USART in Half Duplex mode */ - SET_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Smartcard Mode - * @note In Smartcard mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also configures Stop bits to 1.5 bits and - * sets the USART in Smartcard mode (SCEN bit). - * Clock Output is also enabled (CLKEN). - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function - * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function - * @note Other remaining configurations items related to Smartcard Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n - * CR2 STOP LL_USART_ConfigSmartcardMode\n - * CR2 CLKEN LL_USART_ConfigSmartcardMode\n - * CR3 HDSEL LL_USART_ConfigSmartcardMode\n - * CR3 SCEN LL_USART_ConfigSmartcardMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigSmartcardMode(USART_TypeDef *USARTx) -{ - /* In Smartcard mode, the following bits must be kept cleared: - - LINEN bit in the USART_CR2 register, - - IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_HDSEL)); - /* Configure Stop bits to 1.5 bits */ - /* Synchronous mode is activated by default */ - SET_BIT(USARTx->CR2, (USART_CR2_STOP_0 | USART_CR2_STOP_1 | USART_CR2_CLKEN)); - /* set the UART/USART in Smartcard mode */ - SET_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Irda Mode - * @note In IRDA mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - STOP and CLKEN bits in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also sets the UART/USART in IRDA mode (IREN bit). - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function - * @note Other remaining configurations items related to Irda Mode - * (as Baud Rate, Word length, Power mode, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n - * CR2 CLKEN LL_USART_ConfigIrdaMode\n - * CR2 STOP LL_USART_ConfigIrdaMode\n - * CR3 SCEN LL_USART_ConfigIrdaMode\n - * CR3 HDSEL LL_USART_ConfigIrdaMode\n - * CR3 IREN LL_USART_ConfigIrdaMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigIrdaMode(USART_TypeDef *USARTx) -{ - /* In IRDA mode, the following bits must be kept cleared: - - LINEN, STOP and CLKEN bits in the USART_CR2 register, - - SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN | USART_CR2_STOP)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL)); - /* set the UART/USART in IRDA mode */ - SET_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Multi processor Mode - * (several USARTs connected in a network, one of the USARTs can be the master, - * its TX output connected to the RX inputs of the other slaves USARTs). - * @note In MultiProcessor mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * @note Other remaining configurations items related to Multi processor Mode - * (as Baud Rate, Wake Up Method, Node address, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n - * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n - * CR3 SCEN LL_USART_ConfigMultiProcessMode\n - * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n - * CR3 IREN LL_USART_ConfigMultiProcessMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigMultiProcessMode(USART_TypeDef *USARTx) -{ - /* In Multi Processor mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Check if the USART Parity Error Flag is set or not - * @rmtoll SR PE LL_USART_IsActiveFlag_PE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_PE) == (USART_SR_PE)); -} - -/** - * @brief Check if the USART Framing Error Flag is set or not - * @rmtoll SR FE LL_USART_IsActiveFlag_FE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_FE) == (USART_SR_FE)); -} - -/** - * @brief Check if the USART Noise error detected Flag is set or not - * @rmtoll SR NF LL_USART_IsActiveFlag_NE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_NE) == (USART_SR_NE)); -} - -/** - * @brief Check if the USART OverRun Error Flag is set or not - * @rmtoll SR ORE LL_USART_IsActiveFlag_ORE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_ORE) == (USART_SR_ORE)); -} - -/** - * @brief Check if the USART IDLE line detected Flag is set or not - * @rmtoll SR IDLE LL_USART_IsActiveFlag_IDLE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_IDLE) == (USART_SR_IDLE)); -} - -/** - * @brief Check if the USART Read Data Register Not Empty Flag is set or not - * @rmtoll SR RXNE LL_USART_IsActiveFlag_RXNE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RXNE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_RXNE) == (USART_SR_RXNE)); -} - -/** - * @brief Check if the USART Transmission Complete Flag is set or not - * @rmtoll SR TC LL_USART_IsActiveFlag_TC - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_TC) == (USART_SR_TC)); -} - -/** - * @brief Check if the USART Transmit Data Register Empty Flag is set or not - * @rmtoll SR TXE LL_USART_IsActiveFlag_TXE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TXE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_TXE) == (USART_SR_TXE)); -} - -/** - * @brief Check if the USART LIN Break Detection Flag is set or not - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll SR LBD LL_USART_IsActiveFlag_LBD - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_LBD) == (USART_SR_LBD)); -} - -/** - * @brief Check if the USART CTS Flag is set or not - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll SR CTS LL_USART_IsActiveFlag_nCTS - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_CTS) == (USART_SR_CTS)); -} - -/** - * @brief Check if the USART Send Break Flag is set or not - * @rmtoll CR1 SBK LL_USART_IsActiveFlag_SBK - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_SBK) == (USART_CR1_SBK)); -} - -/** - * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not - * @rmtoll CR1 RWU LL_USART_IsActiveFlag_RWU - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_RWU) == (USART_CR1_RWU)); -} - -/** - * @brief Clear Parity Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * NE, FE, ORE, IDLE would also be cleared. - * @rmtoll SR PE LL_USART_ClearFlag_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_PE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Framing Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, ORE, IDLE would also be cleared. - * @rmtoll SR FE LL_USART_ClearFlag_FE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_FE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Noise detected Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, FE, ORE, IDLE would also be cleared. - * @rmtoll SR NF LL_USART_ClearFlag_NE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_NE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear OverRun Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, FE, IDLE would also be cleared. - * @rmtoll SR ORE LL_USART_ClearFlag_ORE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_ORE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear IDLE line detected Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, FE, ORE would also be cleared. - * @rmtoll SR IDLE LL_USART_ClearFlag_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_IDLE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Transmission Complete Flag - * @rmtoll SR TC LL_USART_ClearFlag_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_TC(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_TC)); -} - -/** - * @brief Clear RX Not Empty Flag - * @rmtoll SR RXNE LL_USART_ClearFlag_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_RXNE(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_RXNE)); -} - -/** - * @brief Clear LIN Break Detection Flag - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll SR LBD LL_USART_ClearFlag_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_LBD(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_LBD)); -} - -/** - * @brief Clear CTS Interrupt Flag - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll SR CTS LL_USART_ClearFlag_nCTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_nCTS(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_CTS)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable IDLE Interrupt - * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_IDLE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_IDLEIE); -} - -/** - * @brief Enable RX Not Empty Interrupt - * @rmtoll CR1 RXNEIE LL_USART_EnableIT_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_RXNE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_RXNEIE); -} - -/** - * @brief Enable Transmission Complete Interrupt - * @rmtoll CR1 TCIE LL_USART_EnableIT_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_TC(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TCIE); -} - -/** - * @brief Enable TX Empty Interrupt - * @rmtoll CR1 TXEIE LL_USART_EnableIT_TXE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_TXE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TXEIE); -} - -/** - * @brief Enable Parity Error Interrupt - * @rmtoll CR1 PEIE LL_USART_EnableIT_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_PE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_PEIE); -} - -/** - * @brief Enable LIN Break Detection Interrupt - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_LBD(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_LBDIE); -} - -/** - * @brief Enable Error Interrupt - * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing - * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register). - * 0: Interrupt is inhibited - * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register. - * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_ERROR(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_EIE); -} - -/** - * @brief Enable CTS Interrupt - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_CTS(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_CTSIE); -} - -/** - * @brief Disable IDLE Interrupt - * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_IDLE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_IDLEIE); -} - -/** - * @brief Disable RX Not Empty Interrupt - * @rmtoll CR1 RXNEIE LL_USART_DisableIT_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_RXNE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_RXNEIE); -} - -/** - * @brief Disable Transmission Complete Interrupt - * @rmtoll CR1 TCIE LL_USART_DisableIT_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_TC(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TCIE); -} - -/** - * @brief Disable TX Empty Interrupt - * @rmtoll CR1 TXEIE LL_USART_DisableIT_TXE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_TXE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TXEIE); -} - -/** - * @brief Disable Parity Error Interrupt - * @rmtoll CR1 PEIE LL_USART_DisableIT_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_PE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_PEIE); -} - -/** - * @brief Disable LIN Break Detection Interrupt - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_LBD(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_LBDIE); -} - -/** - * @brief Disable Error Interrupt - * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing - * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register). - * 0: Interrupt is inhibited - * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register. - * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_ERROR(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_EIE); -} - -/** - * @brief Disable CTS Interrupt - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_CTS(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_CTSIE); -} - -/** - * @brief Check if the USART IDLE Interrupt source is enabled or disabled. - * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_IDLEIE) == (USART_CR1_IDLEIE)); -} - -/** - * @brief Check if the USART RX Not Empty Interrupt is enabled or disabled. - * @rmtoll CR1 RXNEIE LL_USART_IsEnabledIT_RXNE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_RXNE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_RXNEIE) == (USART_CR1_RXNEIE)); -} - -/** - * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled. - * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_TCIE) == (USART_CR1_TCIE)); -} - -/** - * @brief Check if the USART TX Empty Interrupt is enabled or disabled. - * @rmtoll CR1 TXEIE LL_USART_IsEnabledIT_TXE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TXE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_TXEIE) == (USART_CR1_TXEIE)); -} - -/** - * @brief Check if the USART Parity Error Interrupt is enabled or disabled. - * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_PEIE) == (USART_CR1_PEIE)); -} - -/** - * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled. - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_LBDIE) == (USART_CR2_LBDIE)); -} - -/** - * @brief Check if the USART Error Interrupt is enabled or disabled. - * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_EIE) == (USART_CR3_EIE)); -} - -/** - * @brief Check if the USART CTS Interrupt is enabled or disabled. - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_CTSIE) == (USART_CR3_CTSIE)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_DMA_Management DMA_Management - * @{ - */ - -/** - * @brief Enable DMA Mode for reception - * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDMAReq_RX(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_DMAR); -} - -/** - * @brief Disable DMA Mode for reception - * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDMAReq_RX(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_DMAR); -} - -/** - * @brief Check if DMA Mode is enabled for reception - * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_DMAR) == (USART_CR3_DMAR)); -} - -/** - * @brief Enable DMA Mode for transmission - * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDMAReq_TX(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_DMAT); -} - -/** - * @brief Disable DMA Mode for transmission - * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDMAReq_TX(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_DMAT); -} - -/** - * @brief Check if DMA Mode is enabled for transmission - * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_DMAT) == (USART_CR3_DMAT)); -} - -/** - * @brief Get the data register address used for DMA transfer - * @rmtoll DR DR LL_USART_DMA_GetRegAddr - * @note Address of Data Register is valid for both Transmit and Receive transfers. - * @param USARTx USART Instance - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef *USARTx) -{ - /* return address of DR register */ - return ((uint32_t) &(USARTx->DR)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Read Receiver Data register (Receive Data value, 8 bits) - * @rmtoll DR DR LL_USART_ReceiveData8 - * @param USARTx USART Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_USART_ReceiveData8(USART_TypeDef *USARTx) -{ - return (uint8_t)(READ_BIT(USARTx->DR, USART_DR_DR)); -} - -/** - * @brief Read Receiver Data register (Receive Data value, 9 bits) - * @rmtoll DR DR LL_USART_ReceiveData9 - * @param USARTx USART Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x1FF - */ -__STATIC_INLINE uint16_t LL_USART_ReceiveData9(USART_TypeDef *USARTx) -{ - return (uint16_t)(READ_BIT(USARTx->DR, USART_DR_DR)); -} - -/** - * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits) - * @rmtoll DR DR LL_USART_TransmitData8 - * @param USARTx USART Instance - * @param Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_TransmitData8(USART_TypeDef *USARTx, uint8_t Value) -{ - USARTx->DR = Value; -} - -/** - * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits) - * @rmtoll DR DR LL_USART_TransmitData9 - * @param USARTx USART Instance - * @param Value between Min_Data=0x00 and Max_Data=0x1FF - * @retval None - */ -__STATIC_INLINE void LL_USART_TransmitData9(USART_TypeDef *USARTx, uint16_t Value) -{ - USARTx->DR = Value & 0x1FFU; -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Execution Execution - * @{ - */ - -/** - * @brief Request Break sending - * @rmtoll CR1 SBK LL_USART_RequestBreakSending - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestBreakSending(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_SBK); -} - -/** - * @brief Put USART in Mute mode - * @rmtoll CR1 RWU LL_USART_RequestEnterMuteMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestEnterMuteMode(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_RWU); -} - -/** - * @brief Put USART in Active mode - * @rmtoll CR1 RWU LL_USART_RequestExitMuteMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestExitMuteMode(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR1, USART_CR1_RWU); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_EF_Init Initialization and de-initialization functions - * @{ - */ -ErrorStatus LL_USART_DeInit(USART_TypeDef *USARTx); -ErrorStatus LL_USART_Init(USART_TypeDef *USARTx, LL_USART_InitTypeDef *USART_InitStruct); -void LL_USART_StructInit(LL_USART_InitTypeDef *USART_InitStruct); -ErrorStatus LL_USART_ClockInit(USART_TypeDef *USARTx, LL_USART_ClockInitTypeDef *USART_ClockInitStruct); -void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef *USART_ClockInitStruct); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 || UART9 || UART10 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_USART_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h deleted file mode 100644 index ca78e2a350af879..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h +++ /dev/null @@ -1,522 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usb.h - * @author MCD Application Team - * @brief Header file of USB Low Layer HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_USB_H -#define STM32F4xx_LL_USB_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup USB_LL - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief USB Mode definition - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -typedef enum -{ - USB_DEVICE_MODE = 0, - USB_HOST_MODE = 1, - USB_DRD_MODE = 2 -} USB_OTG_ModeTypeDef; - -/** - * @brief URB States definition - */ -typedef enum -{ - URB_IDLE = 0, - URB_DONE, - URB_NOTREADY, - URB_NYET, - URB_ERROR, - URB_STALL -} USB_OTG_URBStateTypeDef; - -/** - * @brief Host channel States definition - */ -typedef enum -{ - HC_IDLE = 0, - HC_XFRC, - HC_HALTED, - HC_NAK, - HC_NYET, - HC_STALL, - HC_XACTERR, - HC_BBLERR, - HC_DATATGLERR -} USB_OTG_HCStateTypeDef; - -/** - * @brief USB Instance Initialization Structure definition - */ -typedef struct -{ - uint32_t dev_endpoints; /*!< Device Endpoints number. - This parameter depends on the used USB core. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t Host_channels; /*!< Host Channels number. - This parameter Depends on the used USB core. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t speed; /*!< USB Core speed. - This parameter can be any value of @ref PCD_Speed/HCD_Speed - (HCD_SPEED_xxx, HCD_SPEED_xxx) */ - - uint32_t dma_enable; /*!< Enable or disable of the USB embedded DMA used only for OTG HS. */ - - uint32_t ep0_mps; /*!< Set the Endpoint 0 Max Packet size. */ - - uint32_t phy_itface; /*!< Select the used PHY interface. - This parameter can be any value of @ref PCD_PHY_Module/HCD_PHY_Module */ - - uint32_t Sof_enable; /*!< Enable or disable the output of the SOF signal. */ - - uint32_t low_power_enable; /*!< Enable or disable the low power mode. */ - - uint32_t lpm_enable; /*!< Enable or disable Link Power Management. */ - - uint32_t battery_charging_enable; /*!< Enable or disable Battery charging. */ - - uint32_t vbus_sensing_enable; /*!< Enable or disable the VBUS Sensing feature. */ - - uint32_t use_dedicated_ep1; /*!< Enable or disable the use of the dedicated EP1 interrupt. */ - - uint32_t use_external_vbus; /*!< Enable or disable the use of the external VBUS. */ - -} USB_OTG_CfgTypeDef; - -typedef struct -{ - uint8_t num; /*!< Endpoint number - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t is_in; /*!< Endpoint direction - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t is_stall; /*!< Endpoint stall condition - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t type; /*!< Endpoint type - This parameter can be any value of @ref USB_LL_EP_Type */ - - uint8_t data_pid_start; /*!< Initial data PID - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t even_odd_frame; /*!< IFrame parity - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint16_t tx_fifo_num; /*!< Transmission FIFO number - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t maxpacket; /*!< Endpoint Max packet size - This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */ - - uint8_t *xfer_buff; /*!< Pointer to transfer buffer */ - - uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address */ - - uint32_t xfer_len; /*!< Current transfer length */ - - uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer */ -} USB_OTG_EPTypeDef; - -typedef struct -{ - uint8_t dev_addr; /*!< USB device address. - This parameter must be a number between Min_Data = 1 and Max_Data = 255 */ - - uint8_t ch_num; /*!< Host channel number. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t ep_num; /*!< Endpoint number. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t ep_is_in; /*!< Endpoint direction - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t speed; /*!< USB Host Channel speed. - This parameter can be any value of @ref HCD_Device_Speed: - (HCD_DEVICE_SPEED_xxx) */ - - uint8_t do_ping; /*!< Enable or disable the use of the PING protocol for HS mode. */ - - uint8_t process_ping; /*!< Execute the PING protocol for HS mode. */ - - uint8_t ep_type; /*!< Endpoint Type. - This parameter can be any value of @ref USB_LL_EP_Type */ - - uint16_t max_packet; /*!< Endpoint Max packet size. - This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */ - - uint8_t data_pid; /*!< Initial data PID. - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t *xfer_buff; /*!< Pointer to transfer buffer. */ - - uint32_t XferSize; /*!< OTG Channel transfer size. */ - - uint32_t xfer_len; /*!< Current transfer length. */ - - uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer. */ - - uint8_t toggle_in; /*!< IN transfer current toggle flag. - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t toggle_out; /*!< OUT transfer current toggle flag - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address. */ - - uint32_t ErrCnt; /*!< Host channel error count. */ - - USB_OTG_URBStateTypeDef urb_state; /*!< URB state. - This parameter can be any value of @ref USB_OTG_URBStateTypeDef */ - - USB_OTG_HCStateTypeDef state; /*!< Host Channel state. - This parameter can be any value of @ref USB_OTG_HCStateTypeDef */ -} USB_OTG_HCTypeDef; -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup PCD_Exported_Constants PCD Exported Constants - * @{ - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @defgroup USB_OTG_CORE VERSION ID - * @{ - */ -#define USB_OTG_CORE_ID_300A 0x4F54300AU -#define USB_OTG_CORE_ID_310A 0x4F54310AU -/** - * @} - */ - -/** @defgroup USB_Core_Mode_ USB Core Mode - * @{ - */ -#define USB_OTG_MODE_DEVICE 0U -#define USB_OTG_MODE_HOST 1U -#define USB_OTG_MODE_DRD 2U -/** - * @} - */ - -/** @defgroup USB_LL Device Speed - * @{ - */ -#define USBD_HS_SPEED 0U -#define USBD_HSINFS_SPEED 1U -#define USBH_HS_SPEED 0U -#define USBD_FS_SPEED 2U -#define USBH_FSLS_SPEED 1U -/** - * @} - */ - -/** @defgroup USB_LL_Core_Speed USB Low Layer Core Speed - * @{ - */ -#define USB_OTG_SPEED_HIGH 0U -#define USB_OTG_SPEED_HIGH_IN_FULL 1U -#define USB_OTG_SPEED_FULL 3U -/** - * @} - */ - -/** @defgroup USB_LL_Core_PHY USB Low Layer Core PHY - * @{ - */ -#define USB_OTG_ULPI_PHY 1U -#define USB_OTG_EMBEDDED_PHY 2U -/** - * @} - */ - -/** @defgroup USB_LL_Turnaround_Timeout Turnaround Timeout Value - * @{ - */ -#ifndef USBD_HS_TRDT_VALUE -#define USBD_HS_TRDT_VALUE 9U -#endif /* USBD_HS_TRDT_VALUE */ -#ifndef USBD_FS_TRDT_VALUE -#define USBD_FS_TRDT_VALUE 5U -#define USBD_DEFAULT_TRDT_VALUE 9U -#endif /* USBD_HS_TRDT_VALUE */ -/** - * @} - */ - -/** @defgroup USB_LL_Core_MPS USB Low Layer Core MPS - * @{ - */ -#define USB_OTG_HS_MAX_PACKET_SIZE 512U -#define USB_OTG_FS_MAX_PACKET_SIZE 64U -#define USB_OTG_MAX_EP0_SIZE 64U -/** - * @} - */ - -/** @defgroup USB_LL_Core_PHY_Frequency USB Low Layer Core PHY Frequency - * @{ - */ -#define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ (0U << 1) -#define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ (1U << 1) -#define DSTS_ENUMSPD_FS_PHY_48MHZ (3U << 1) -/** - * @} - */ - -/** @defgroup USB_LL_CORE_Frame_Interval USB Low Layer Core Frame Interval - * @{ - */ -#define DCFG_FRAME_INTERVAL_80 0U -#define DCFG_FRAME_INTERVAL_85 1U -#define DCFG_FRAME_INTERVAL_90 2U -#define DCFG_FRAME_INTERVAL_95 3U -/** - * @} - */ - -/** @defgroup USB_LL_EP0_MPS USB Low Layer EP0 MPS - * @{ - */ -#define EP_MPS_64 0U -#define EP_MPS_32 1U -#define EP_MPS_16 2U -#define EP_MPS_8 3U -/** - * @} - */ - -/** @defgroup USB_LL_EP_Speed USB Low Layer EP Speed - * @{ - */ -#define EP_SPEED_LOW 0U -#define EP_SPEED_FULL 1U -#define EP_SPEED_HIGH 2U -/** - * @} - */ - -/** @defgroup USB_LL_EP_Type USB Low Layer EP Type - * @{ - */ -#define EP_TYPE_CTRL 0U -#define EP_TYPE_ISOC 1U -#define EP_TYPE_BULK 2U -#define EP_TYPE_INTR 3U -#define EP_TYPE_MSK 3U -/** - * @} - */ - -/** @defgroup USB_LL_STS_Defines USB Low Layer STS Defines - * @{ - */ -#define STS_GOUT_NAK 1U -#define STS_DATA_UPDT 2U -#define STS_XFER_COMP 3U -#define STS_SETUP_COMP 4U -#define STS_SETUP_UPDT 6U -/** - * @} - */ - -/** @defgroup USB_LL_HCFG_SPEED_Defines USB Low Layer HCFG Speed Defines - * @{ - */ -#define HCFG_30_60_MHZ 0U -#define HCFG_48_MHZ 1U -#define HCFG_6_MHZ 2U -/** - * @} - */ - -/** @defgroup USB_LL_HPRT0_PRTSPD_SPEED_Defines USB Low Layer HPRT0 PRTSPD Speed Defines - * @{ - */ -#define HPRT0_PRTSPD_HIGH_SPEED 0U -#define HPRT0_PRTSPD_FULL_SPEED 1U -#define HPRT0_PRTSPD_LOW_SPEED 2U -/** - * @} - */ - -#define HCCHAR_CTRL 0U -#define HCCHAR_ISOC 1U -#define HCCHAR_BULK 2U -#define HCCHAR_INTR 3U - -#define HC_PID_DATA0 0U -#define HC_PID_DATA2 1U -#define HC_PID_DATA1 2U -#define HC_PID_SETUP 3U - -#define GRXSTS_PKTSTS_IN 2U -#define GRXSTS_PKTSTS_IN_XFER_COMP 3U -#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5U -#define GRXSTS_PKTSTS_CH_HALTED 7U - -#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_PCGCCTL_BASE) -#define USBx_HPRT0 *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_HOST_PORT_BASE) - -#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)(USBx_BASE + USB_OTG_DEVICE_BASE)) -#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)(USBx_BASE\ - + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) - -#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)(USBx_BASE\ - + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) - -#define USBx_DFIFO(i) *(__IO uint32_t *)(USBx_BASE + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) - -#define USBx_HOST ((USB_OTG_HostTypeDef *)(USBx_BASE + USB_OTG_HOST_BASE)) -#define USBx_HC(i) ((USB_OTG_HostChannelTypeDef *)(USBx_BASE\ - + USB_OTG_HOST_CHANNEL_BASE\ - + ((i) * USB_OTG_HOST_CHANNEL_SIZE))) - -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#define EP_ADDR_MSK 0xFU -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup USB_LL_Exported_Macros USB Low Layer Exported Macros - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define USB_MASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK &= ~(__INTERRUPT__)) -#define USB_UNMASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK |= (__INTERRUPT__)) - -#define CLEAR_IN_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_INEP(__EPNUM__)->DIEPINT = (__INTERRUPT__)) -#define CLEAR_OUT_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_OUTEP(__EPNUM__)->DOEPINT = (__INTERRUPT__)) -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup USB_LL_Exported_Functions USB Low Layer Exported Functions - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, uint32_t hclk, uint8_t speed); -HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode); -HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed); -HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num); -HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma); -HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma); -HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, - uint8_t ch_ep_num, uint16_t len, uint8_t dma); - -void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len); -HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address); -HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup); -uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum); -uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum); -void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt); - -HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq); -HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state); -uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num, - uint8_t epnum, uint8_t dev_address, uint8_t speed, - uint8_t ep_type, uint16_t mps); -HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, - USB_OTG_HCTypeDef *hc, uint8_t dma); - -uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num); -HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num); -HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx); -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_LL_USB_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h deleted file mode 100644 index 3bac30cf08d1d9c..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h +++ /dev/null @@ -1,310 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_utils.h - * @author MCD Application Team - * @brief Header file of UTILS LL module. - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL UTILS driver contains a set of generic APIs that can be - used by user: - (+) Device electronic signature - (+) Timing functions - (+) PLL configuration functions - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_UTILS_H -#define __STM32F4xx_LL_UTILS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -/** @defgroup UTILS_LL UTILS - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup UTILS_LL_Private_Constants UTILS Private Constants - * @{ - */ - -/* Max delay can be used in LL_mDelay */ -#define LL_MAX_DELAY 0xFFFFFFFFU - -/** - * @brief Unique device ID register base address - */ -#define UID_BASE_ADDRESS UID_BASE - -/** - * @brief Flash size data register base address - */ -#define FLASHSIZE_BASE_ADDRESS FLASHSIZE_BASE - -/** - * @brief Package data register base address - */ -#define PACKAGE_BASE_ADDRESS PACKAGE_BASE - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup UTILS_LL_Private_Macros UTILS Private Macros - * @{ - */ -/** - * @} - */ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup UTILS_LL_ES_INIT UTILS Exported structures - * @{ - */ -/** - * @brief UTILS PLL structure definition - */ -typedef struct -{ - uint32_t PLLM; /*!< Division factor for PLL VCO input clock. - This parameter can be a value of @ref RCC_LL_EC_PLLM_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ - - uint32_t PLLN; /*!< Multiplication factor for PLL VCO output clock. - This parameter must be a number between Min_Data = @ref RCC_PLLN_MIN_VALUE - and Max_Data = @ref RCC_PLLN_MIN_VALUE - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ - - uint32_t PLLP; /*!< Division for the main system clock. - This parameter can be a value of @ref RCC_LL_EC_PLLP_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ -} LL_UTILS_PLLInitTypeDef; - -/** - * @brief UTILS System, AHB and APB buses clock configuration structure definition - */ -typedef struct -{ - uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK). - This parameter can be a value of @ref RCC_LL_EC_SYSCLK_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAHBPrescaler(). */ - - uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_LL_EC_APB1_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAPB1Prescaler(). */ - - uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_LL_EC_APB2_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAPB2Prescaler(). */ - -} LL_UTILS_ClkInitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup UTILS_LL_Exported_Constants UTILS Exported Constants - * @{ - */ - -/** @defgroup UTILS_EC_HSE_BYPASS HSE Bypass activation - * @{ - */ -#define LL_UTILS_HSEBYPASS_OFF 0x00000000U /*!< HSE Bypass is not enabled */ -#define LL_UTILS_HSEBYPASS_ON 0x00000001U /*!< HSE Bypass is enabled */ -/** - * @} - */ - -/** @defgroup UTILS_EC_PACKAGETYPE PACKAGE TYPE - * @{ - */ -#define LL_UTILS_PACKAGETYPE_WLCSP36_UFQFPN48_LQFP64 0x00000000U /*!< WLCSP36 or UFQFPN48 or LQFP64 package type */ -#define LL_UTILS_PACKAGETYPE_WLCSP168_FBGA169_LQFP100_LQFP64_UFQFPN48 0x00000100U /*!< WLCSP168 or FBGA169 or LQFP100 or LQFP64 or UFQFPN48 package type */ -#define LL_UTILS_PACKAGETYPE_WLCSP64_WLCSP81_LQFP176_UFBGA176 0x00000200U /*!< WLCSP64 or WLCSP81 or LQFP176 or UFBGA176 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP144_UFBGA144_UFBGA144_UFBGA100 0x00000300U /*!< LQFP144 or UFBGA144 or UFBGA144 or UFBGA100 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP100_LQFP208_TFBGA216 0x00000400U /*!< LQFP100 or LQFP208 or TFBGA216 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP208_TFBGA216 0x00000500U /*!< LQFP208 or TFBGA216 package type */ -#define LL_UTILS_PACKAGETYPE_TQFP64_UFBGA144_LQFP144 0x00000700U /*!< TQFP64 or UFBGA144 or LQFP144 package type */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup UTILS_LL_Exported_Functions UTILS Exported Functions - * @{ - */ - -/** @defgroup UTILS_EF_DEVICE_ELECTRONIC_SIGNATURE DEVICE ELECTRONIC SIGNATURE - * @{ - */ - -/** - * @brief Get Word0 of the unique device identifier (UID based on 96 bits) - * @retval UID[31:0] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word0(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)UID_BASE_ADDRESS))); -} - -/** - * @brief Get Word1 of the unique device identifier (UID based on 96 bits) - * @retval UID[63:32] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word1(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 4U)))); -} - -/** - * @brief Get Word2 of the unique device identifier (UID based on 96 bits) - * @retval UID[95:64] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word2(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 8U)))); -} - -/** - * @brief Get Flash memory size - * @note This bitfield indicates the size of the device Flash memory expressed in - * Kbytes. As an example, 0x040 corresponds to 64 Kbytes. - * @retval FLASH_SIZE[15:0]: Flash memory size - */ -__STATIC_INLINE uint32_t LL_GetFlashSize(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)FLASHSIZE_BASE_ADDRESS)) & 0xFFFF); -} - -/** - * @brief Get Package type - * @retval Returned value can be one of the following values: - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP36_UFQFPN48_LQFP64 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP168_FBGA169_LQFP100_LQFP64_UFQFPN48 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP64_WLCSP81_LQFP176_UFBGA176 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP144_UFBGA144_UFBGA144_UFBGA100 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP100_LQFP208_TFBGA216 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP208_TFBGA216 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_TQFP64_UFBGA144_LQFP144 (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_GetPackageType(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)PACKAGE_BASE_ADDRESS)) & 0x0700U); -} - -/** - * @} - */ - -/** @defgroup UTILS_LL_EF_DELAY DELAY - * @{ - */ - -/** - * @brief This function configures the Cortex-M SysTick source of the time base. - * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro) - * @note When a RTOS is used, it is recommended to avoid changing the SysTick - * configuration by calling this function, for a delay use rather osDelay RTOS service. - * @param Ticks Number of ticks - * @retval None - */ -__STATIC_INLINE void LL_InitTick(uint32_t HCLKFrequency, uint32_t Ticks) -{ - /* Configure the SysTick to have interrupt in 1ms time base */ - SysTick->LOAD = (uint32_t)((HCLKFrequency / Ticks) - 1UL); /* set reload register */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable the Systick Timer */ -} - -void LL_Init1msTick(uint32_t HCLKFrequency); -void LL_mDelay(uint32_t Delay); - -/** - * @} - */ - -/** @defgroup UTILS_EF_SYSTEM SYSTEM - * @{ - */ - -void LL_SetSystemCoreClock(uint32_t HCLKFrequency); -ErrorStatus LL_SetFlashLatency(uint32_t HCLK_Frequency); -ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, - LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); -ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass, - LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_UTILS_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_wwdg.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_wwdg.h deleted file mode 100644 index f20b82dd80522c8..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_wwdg.h +++ /dev/null @@ -1,319 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_wwdg.h - * @author MCD Application Team - * @brief Header file of WWDG LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_WWDG_H -#define STM32F4xx_LL_WWDG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (WWDG) - -/** @defgroup WWDG_LL WWDG - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup WWDG_LL_Exported_Constants WWDG Exported Constants - * @{ - */ - -/** @defgroup WWDG_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_WWDG_ReadReg and LL_WWDG_WriteReg functions - * @{ - */ -#define LL_WWDG_CFR_EWI WWDG_CFR_EWI -/** - * @} - */ - -/** @defgroup WWDG_LL_EC_PRESCALER PRESCALER - * @{ - */ -#define LL_WWDG_PRESCALER_1 0x00000000u /*!< WWDG counter clock = (PCLK1/4096)/1 */ -#define LL_WWDG_PRESCALER_2 WWDG_CFR_WDGTB_0 /*!< WWDG counter clock = (PCLK1/4096)/2 */ -#define LL_WWDG_PRESCALER_4 WWDG_CFR_WDGTB_1 /*!< WWDG counter clock = (PCLK1/4096)/4 */ -#define LL_WWDG_PRESCALER_8 (WWDG_CFR_WDGTB_0 | WWDG_CFR_WDGTB_1) /*!< WWDG counter clock = (PCLK1/4096)/8 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup WWDG_LL_Exported_Macros WWDG Exported Macros - * @{ - */ -/** @defgroup WWDG_LL_EM_WRITE_READ Common Write and read registers macros - * @{ - */ -/** - * @brief Write a value in WWDG register - * @param __INSTANCE__ WWDG Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_WWDG_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in WWDG register - * @param __INSTANCE__ WWDG Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_WWDG_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup WWDG_LL_Exported_Functions WWDG Exported Functions - * @{ - */ - -/** @defgroup WWDG_LL_EF_Configuration Configuration - * @{ - */ -/** - * @brief Enable Window Watchdog. The watchdog is always disabled after a reset. - * @note It is enabled by setting the WDGA bit in the WWDG_CR register, - * then it cannot be disabled again except by a reset. - * This bit is set by software and only cleared by hardware after a reset. - * When WDGA = 1, the watchdog can generate a reset. - * @rmtoll CR WDGA LL_WWDG_Enable - * @param WWDGx WWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_WWDG_Enable(WWDG_TypeDef *WWDGx) -{ - SET_BIT(WWDGx->CR, WWDG_CR_WDGA); -} - -/** - * @brief Checks if Window Watchdog is enabled - * @rmtoll CR WDGA LL_WWDG_IsEnabled - * @param WWDGx WWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_WWDG_IsEnabled(WWDG_TypeDef *WWDGx) -{ - return ((READ_BIT(WWDGx->CR, WWDG_CR_WDGA) == (WWDG_CR_WDGA)) ? 1UL : 0UL); -} - -/** - * @brief Set the Watchdog counter value to provided value (7-bits T[6:0]) - * @note When writing to the WWDG_CR register, always write 1 in the MSB b6 to avoid generating an immediate reset - * This counter is decremented every (4096 x 2expWDGTB) PCLK cycles - * A reset is produced when it rolls over from 0x40 to 0x3F (bit T6 becomes cleared) - * Setting the counter lower then 0x40 causes an immediate reset (if WWDG enabled) - * @rmtoll CR T LL_WWDG_SetCounter - * @param WWDGx WWDG Instance - * @param Counter 0..0x7F (7 bit counter value) - * @retval None - */ -__STATIC_INLINE void LL_WWDG_SetCounter(WWDG_TypeDef *WWDGx, uint32_t Counter) -{ - MODIFY_REG(WWDGx->CR, WWDG_CR_T, Counter); -} - -/** - * @brief Return current Watchdog Counter Value (7 bits counter value) - * @rmtoll CR T LL_WWDG_GetCounter - * @param WWDGx WWDG Instance - * @retval 7 bit Watchdog Counter value - */ -__STATIC_INLINE uint32_t LL_WWDG_GetCounter(WWDG_TypeDef *WWDGx) -{ - return (READ_BIT(WWDGx->CR, WWDG_CR_T)); -} - -/** - * @brief Set the time base of the prescaler (WDGTB). - * @note Prescaler is used to apply ratio on PCLK clock, so that Watchdog counter - * is decremented every (4096 x 2expWDGTB) PCLK cycles - * @rmtoll CFR WDGTB LL_WWDG_SetPrescaler - * @param WWDGx WWDG Instance - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_WWDG_PRESCALER_1 - * @arg @ref LL_WWDG_PRESCALER_2 - * @arg @ref LL_WWDG_PRESCALER_4 - * @arg @ref LL_WWDG_PRESCALER_8 - * @retval None - */ -__STATIC_INLINE void LL_WWDG_SetPrescaler(WWDG_TypeDef *WWDGx, uint32_t Prescaler) -{ - MODIFY_REG(WWDGx->CFR, WWDG_CFR_WDGTB, Prescaler); -} - -/** - * @brief Return current Watchdog Prescaler Value - * @rmtoll CFR WDGTB LL_WWDG_GetPrescaler - * @param WWDGx WWDG Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_WWDG_PRESCALER_1 - * @arg @ref LL_WWDG_PRESCALER_2 - * @arg @ref LL_WWDG_PRESCALER_4 - * @arg @ref LL_WWDG_PRESCALER_8 - */ -__STATIC_INLINE uint32_t LL_WWDG_GetPrescaler(WWDG_TypeDef *WWDGx) -{ - return (READ_BIT(WWDGx->CFR, WWDG_CFR_WDGTB)); -} - -/** - * @brief Set the Watchdog Window value to be compared to the downcounter (7-bits W[6:0]). - * @note This window value defines when write in the WWDG_CR register - * to program Watchdog counter is allowed. - * Watchdog counter value update must occur only when the counter value - * is lower than the Watchdog window register value. - * Otherwise, a MCU reset is generated if the 7-bit Watchdog counter value - * (in the control register) is refreshed before the downcounter has reached - * the watchdog window register value. - * Physically is possible to set the Window lower then 0x40 but it is not recommended. - * To generate an immediate reset, it is possible to set the Counter lower than 0x40. - * @rmtoll CFR W LL_WWDG_SetWindow - * @param WWDGx WWDG Instance - * @param Window 0x00..0x7F (7 bit Window value) - * @retval None - */ -__STATIC_INLINE void LL_WWDG_SetWindow(WWDG_TypeDef *WWDGx, uint32_t Window) -{ - MODIFY_REG(WWDGx->CFR, WWDG_CFR_W, Window); -} - -/** - * @brief Return current Watchdog Window Value (7 bits value) - * @rmtoll CFR W LL_WWDG_GetWindow - * @param WWDGx WWDG Instance - * @retval 7 bit Watchdog Window value - */ -__STATIC_INLINE uint32_t LL_WWDG_GetWindow(WWDG_TypeDef *WWDGx) -{ - return (READ_BIT(WWDGx->CFR, WWDG_CFR_W)); -} - -/** - * @} - */ - -/** @defgroup WWDG_LL_EF_FLAG_Management FLAG_Management - * @{ - */ -/** - * @brief Indicates if the WWDG Early Wakeup Interrupt Flag is set or not. - * @note This bit is set by hardware when the counter has reached the value 0x40. - * It must be cleared by software by writing 0. - * A write of 1 has no effect. This bit is also set if the interrupt is not enabled. - * @rmtoll SR EWIF LL_WWDG_IsActiveFlag_EWKUP - * @param WWDGx WWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_WWDG_IsActiveFlag_EWKUP(WWDG_TypeDef *WWDGx) -{ - return ((READ_BIT(WWDGx->SR, WWDG_SR_EWIF) == (WWDG_SR_EWIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear WWDG Early Wakeup Interrupt Flag (EWIF) - * @rmtoll SR EWIF LL_WWDG_ClearFlag_EWKUP - * @param WWDGx WWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_WWDG_ClearFlag_EWKUP(WWDG_TypeDef *WWDGx) -{ - WRITE_REG(WWDGx->SR, ~WWDG_SR_EWIF); -} - -/** - * @} - */ - -/** @defgroup WWDG_LL_EF_IT_Management IT_Management - * @{ - */ -/** - * @brief Enable the Early Wakeup Interrupt. - * @note When set, an interrupt occurs whenever the counter reaches value 0x40. - * This interrupt is only cleared by hardware after a reset - * @rmtoll CFR EWI LL_WWDG_EnableIT_EWKUP - * @param WWDGx WWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_WWDG_EnableIT_EWKUP(WWDG_TypeDef *WWDGx) -{ - SET_BIT(WWDGx->CFR, WWDG_CFR_EWI); -} - -/** - * @brief Check if Early Wakeup Interrupt is enabled - * @rmtoll CFR EWI LL_WWDG_IsEnabledIT_EWKUP - * @param WWDGx WWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_WWDG_IsEnabledIT_EWKUP(WWDG_TypeDef *WWDGx) -{ - return ((READ_BIT(WWDGx->CFR, WWDG_CFR_EWI) == (WWDG_CFR_EWI)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* WWDG */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_WWDG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/Legacy/stm32f4xx_hal_can.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/Legacy/stm32f4xx_hal_can.c deleted file mode 100644 index 7a4cf5378eb7421..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/Legacy/stm32f4xx_hal_can.c +++ /dev/null @@ -1,1697 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_can.c - * @author MCD Application Team - * @brief This file provides firmware functions to manage the following - * functionalities of the Controller Area Network (CAN) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Error functions - * - @verbatim - ============================================================================== - ##### User NOTE ##### - ============================================================================== - [..] - (#) This HAL CAN driver is deprecated, it contains some CAN Tx/Rx FIFO management limitations. - Another HAL CAN driver version has been designed with new API's, to fix these limitations. - - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Enable the CAN controller interface clock using - __HAL_RCC_CAN1_CLK_ENABLE() for CAN1, __HAL_RCC_CAN2_CLK_ENABLE() for CAN2 - and __HAL_RCC_CAN3_CLK_ENABLE() for CAN3 - -@- In case you are using CAN2 only, you have to enable the CAN1 clock. - - (#) CAN pins configuration - (++) Enable the clock for the CAN GPIOs using the following function: - __GPIOx_CLK_ENABLE() - (++) Connect and configure the involved CAN pins to AF9 using the - following function HAL_GPIO_Init() - - (#) Initialize and configure the CAN using CAN_Init() function. - - (#) Transmit the desired CAN frame using HAL_CAN_Transmit() function. - - (#) Or transmit the desired CAN frame using HAL_CAN_Transmit_IT() function. - - (#) Receive a CAN frame using HAL_CAN_Receive() function. - - (#) Or receive a CAN frame using HAL_CAN_Receive_IT() function. - - *** Polling mode IO operation *** - ================================= - [..] - (+) Start the CAN peripheral transmission and wait the end of this operation - using HAL_CAN_Transmit(), at this stage user can specify the value of timeout - according to his end application - (+) Start the CAN peripheral reception and wait the end of this operation - using HAL_CAN_Receive(), at this stage user can specify the value of timeout - according to his end application - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Start the CAN peripheral transmission using HAL_CAN_Transmit_IT() - (+) Start the CAN peripheral reception using HAL_CAN_Receive_IT() - (+) Use HAL_CAN_IRQHandler() called under the used CAN Interrupt subroutine - (+) At CAN end of transmission HAL_CAN_TxCpltCallback() function is executed and user can - add his own code by customization of function pointer HAL_CAN_TxCpltCallback - (+) In case of CAN Error, HAL_CAN_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_CAN_ErrorCallback - - *** CAN HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in CAN HAL driver. - - (+) __HAL_CAN_ENABLE_IT: Enable the specified CAN interrupts - (+) __HAL_CAN_DISABLE_IT: Disable the specified CAN interrupts - (+) __HAL_CAN_GET_IT_SOURCE: Check if the specified CAN interrupt source is enabled or disabled - (+) __HAL_CAN_CLEAR_FLAG: Clear the CAN's pending flags - (+) __HAL_CAN_GET_FLAG: Get the selected CAN's flag status - - [..] - (@) You can refer to the CAN Legacy HAL driver header file for more useful macros - - @endverbatim - - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2017 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. - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup CAN CAN - * @brief CAN driver modules - * @{ - */ - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) - -#ifdef HAL_CAN_MODULE_ENABLED -/* Select HAL CAN module in stm32f4xx_hal_conf.h file: - (#) HAL_CAN_MODULE_ENABLED for new HAL CAN driver fixing FIFO limitations - (#) HAL_CAN_LEGACY_MODULE_ENABLED for legacy HAL CAN driver */ -#error 'The HAL CAN driver cannot be used with its legacy, Please ensure to enable only one HAL CAN module at once in stm32f4xx_hal_conf.h file' -#endif /* HAL_CAN_MODULE_ENABLED */ - -#warning 'Legacy HAL CAN driver is enabled! It can be used with known limitations, refer to the release notes. However it is recommended to use rather the new HAL CAN driver' - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup CAN_Private_Constants - * @{ - */ -#define CAN_TIMEOUT_VALUE 10U -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup CAN_Private_Functions - * @{ - */ -static HAL_StatusTypeDef CAN_Receive_IT(CAN_HandleTypeDef* hcan, uint8_t FIFONumber); -static HAL_StatusTypeDef CAN_Transmit_IT(CAN_HandleTypeDef* hcan); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CAN_Exported_Functions CAN Exported Functions - * @{ - */ - -/** @defgroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the CAN. - (+) De-initialize the CAN. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the CAN peripheral according to the specified - * parameters in the CAN_InitStruct. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef* hcan) -{ - uint32_t InitStatus = CAN_INITSTATUS_FAILED; - uint32_t tickstart = 0U; - - /* Check CAN handle */ - if(hcan == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TTCM)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.ABOM)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AWUM)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.NART)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.RFLM)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TXFP)); - assert_param(IS_CAN_MODE(hcan->Init.Mode)); - assert_param(IS_CAN_SJW(hcan->Init.SJW)); - assert_param(IS_CAN_BS1(hcan->Init.BS1)); - assert_param(IS_CAN_BS2(hcan->Init.BS2)); - assert_param(IS_CAN_PRESCALER(hcan->Init.Prescaler)); - - - if(hcan->State == HAL_CAN_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hcan->Lock = HAL_UNLOCKED; - /* Init the low level hardware */ - HAL_CAN_MspInit(hcan); - } - - /* Initialize the CAN state*/ - hcan->State = HAL_CAN_STATE_BUSY; - - /* Exit from sleep mode */ - hcan->Instance->MCR &= (~(uint32_t)CAN_MCR_SLEEP); - - /* Request initialisation */ - hcan->Instance->MCR |= CAN_MCR_INRQ ; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait the acknowledge */ - while((hcan->Instance->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) - { - if((HAL_GetTick() - tickstart ) > CAN_TIMEOUT_VALUE) - { - hcan->State= HAL_CAN_STATE_TIMEOUT; - /* Process unlocked */ - __HAL_UNLOCK(hcan); - return HAL_TIMEOUT; - } - } - - /* Check acknowledge */ - if ((hcan->Instance->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) - { - /* Set the time triggered communication mode */ - if (hcan->Init.TTCM == ENABLE) - { - hcan->Instance->MCR |= CAN_MCR_TTCM; - } - else - { - hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_TTCM; - } - - /* Set the automatic bus-off management */ - if (hcan->Init.ABOM == ENABLE) - { - hcan->Instance->MCR |= CAN_MCR_ABOM; - } - else - { - hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_ABOM; - } - - /* Set the automatic wake-up mode */ - if (hcan->Init.AWUM == ENABLE) - { - hcan->Instance->MCR |= CAN_MCR_AWUM; - } - else - { - hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_AWUM; - } - - /* Set the no automatic retransmission */ - if (hcan->Init.NART == ENABLE) - { - hcan->Instance->MCR |= CAN_MCR_NART; - } - else - { - hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_NART; - } - - /* Set the receive FIFO locked mode */ - if (hcan->Init.RFLM == ENABLE) - { - hcan->Instance->MCR |= CAN_MCR_RFLM; - } - else - { - hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_RFLM; - } - - /* Set the transmit FIFO priority */ - if (hcan->Init.TXFP == ENABLE) - { - hcan->Instance->MCR |= CAN_MCR_TXFP; - } - else - { - hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_TXFP; - } - - /* Set the bit timing register */ - hcan->Instance->BTR = (uint32_t)((uint32_t)hcan->Init.Mode) | \ - ((uint32_t)hcan->Init.SJW) | \ - ((uint32_t)hcan->Init.BS1) | \ - ((uint32_t)hcan->Init.BS2) | \ - ((uint32_t)hcan->Init.Prescaler - 1U); - - /* Request leave initialisation */ - hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_INRQ; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait the acknowledge */ - while((hcan->Instance->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) - { - if((HAL_GetTick() - tickstart ) > CAN_TIMEOUT_VALUE) - { - hcan->State= HAL_CAN_STATE_TIMEOUT; - /* Process unlocked */ - __HAL_UNLOCK(hcan); - return HAL_TIMEOUT; - } - } - - /* Check acknowledged */ - if ((hcan->Instance->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) - { - InitStatus = CAN_INITSTATUS_SUCCESS; - } - } - - if(InitStatus == CAN_INITSTATUS_SUCCESS) - { - /* Set CAN error code to none */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Initialize the CAN state */ - hcan->State = HAL_CAN_STATE_READY; - - /* Return function status */ - return HAL_OK; - } - else - { - /* Initialize the CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - /* Return function status */ - return HAL_ERROR; - } -} - -/** - * @brief Configures the CAN reception filter according to the specified - * parameters in the CAN_FilterInitStruct. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param sFilterConfig pointer to a CAN_FilterConfTypeDef structure that - * contains the filter configuration information. - * @retval None - */ -HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef* hcan, CAN_FilterConfTypeDef* sFilterConfig) -{ - uint32_t filternbrbitpos = 0U; - CAN_TypeDef *can_ip; - - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_NUMBER(sFilterConfig->FilterNumber)); - assert_param(IS_CAN_FILTER_MODE(sFilterConfig->FilterMode)); - assert_param(IS_CAN_FILTER_SCALE(sFilterConfig->FilterScale)); - assert_param(IS_CAN_FILTER_FIFO(sFilterConfig->FilterFIFOAssignment)); - assert_param(IS_FUNCTIONAL_STATE(sFilterConfig->FilterActivation)); - assert_param(IS_CAN_BANKNUMBER(sFilterConfig->BankNumber)); - - filternbrbitpos = 1U << sFilterConfig->FilterNumber; -#if defined (CAN3) - /* Check the CAN instance */ - if(hcan->Instance == CAN3) - { - can_ip = CAN3; - } - else - { - can_ip = CAN1; - } -#else - can_ip = CAN1; -#endif - - /* Initialisation mode for the filter */ - can_ip->FMR |= (uint32_t)CAN_FMR_FINIT; - -#if defined (CAN2) - /* Select the start slave bank */ - can_ip->FMR &= ~((uint32_t)CAN_FMR_CAN2SB); - can_ip->FMR |= (uint32_t)(sFilterConfig->BankNumber << 8U); -#endif - - /* Filter Deactivation */ - can_ip->FA1R &= ~(uint32_t)filternbrbitpos; - - /* Filter Scale */ - if (sFilterConfig->FilterScale == CAN_FILTERSCALE_16BIT) - { - /* 16-bit scale for the filter */ - can_ip->FS1R &= ~(uint32_t)filternbrbitpos; - - /* First 16-bit identifier and First 16-bit mask */ - /* Or First 16-bit identifier and Second 16-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterNumber].FR1 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); - - /* Second 16-bit identifier and Second 16-bit mask */ - /* Or Third 16-bit identifier and Fourth 16-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterNumber].FR2 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh); - } - - if (sFilterConfig->FilterScale == CAN_FILTERSCALE_32BIT) - { - /* 32-bit scale for the filter */ - can_ip->FS1R |= filternbrbitpos; - - /* 32-bit identifier or First 32-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterNumber].FR1 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); - /* 32-bit mask or Second 32-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterNumber].FR2 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow); - } - - /* Filter Mode */ - if (sFilterConfig->FilterMode == CAN_FILTERMODE_IDMASK) - { - /*Id/Mask mode for the filter*/ - can_ip->FM1R &= ~(uint32_t)filternbrbitpos; - } - else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ - { - /*Identifier list mode for the filter*/ - can_ip->FM1R |= (uint32_t)filternbrbitpos; - } - - /* Filter FIFO assignment */ - if (sFilterConfig->FilterFIFOAssignment == CAN_FILTER_FIFO0) - { - /* FIFO 0 assignation for the filter */ - can_ip->FFA1R &= ~(uint32_t)filternbrbitpos; - } - - if (sFilterConfig->FilterFIFOAssignment == CAN_FILTER_FIFO1) - { - /* FIFO 1 assignation for the filter */ - can_ip->FFA1R |= (uint32_t)filternbrbitpos; - } - - /* Filter activation */ - if (sFilterConfig->FilterActivation == ENABLE) - { - can_ip->FA1R |= filternbrbitpos; - } - - /* Leave the initialisation mode for the filter */ - can_ip->FMR &= ~((uint32_t)CAN_FMR_FINIT); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Deinitializes the CANx peripheral registers to their default reset values. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef* hcan) -{ - /* Check CAN handle */ - if(hcan == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_BUSY; - - /* DeInit the low level hardware */ - HAL_CAN_MspDeInit(hcan); - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hcan); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initializes the CAN MSP. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes the CAN MSP. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Transmit a CAN frame message. - (+) Receive a CAN frame message. - (+) Enter CAN peripheral in sleep mode. - (+) Wake up the CAN peripheral from sleep mode. - -@endverbatim - * @{ - */ - -/** - * @brief Initiates and transmits a CAN frame message. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param Timeout Specify Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Transmit(CAN_HandleTypeDef* hcan, uint32_t Timeout) -{ - uint32_t transmitmailbox = CAN_TXSTATUS_NOMAILBOX; - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_CAN_IDTYPE(hcan->pTxMsg->IDE)); - assert_param(IS_CAN_RTR(hcan->pTxMsg->RTR)); - assert_param(IS_CAN_DLC(hcan->pTxMsg->DLC)); - - if(((hcan->Instance->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) || \ - ((hcan->Instance->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) || \ - ((hcan->Instance->TSR&CAN_TSR_TME2) == CAN_TSR_TME2)) - { - /* Process locked */ - __HAL_LOCK(hcan); - - /* Change CAN state */ - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_RX0): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; - break; - case(HAL_CAN_STATE_BUSY_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; - break; - case(HAL_CAN_STATE_BUSY_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; - break; - default: /* HAL_CAN_STATE_READY */ - hcan->State = HAL_CAN_STATE_BUSY_TX; - break; - } - - /* Select one empty transmit mailbox */ - if ((hcan->Instance->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) - { - transmitmailbox = CAN_TXMAILBOX_0; - } - else if ((hcan->Instance->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) - { - transmitmailbox = CAN_TXMAILBOX_1; - } - else - { - transmitmailbox = CAN_TXMAILBOX_2; - } - - /* Set up the Id */ - hcan->Instance->sTxMailBox[transmitmailbox].TIR &= CAN_TI0R_TXRQ; - if (hcan->pTxMsg->IDE == CAN_ID_STD) - { - assert_param(IS_CAN_STDID(hcan->pTxMsg->StdId)); - hcan->Instance->sTxMailBox[transmitmailbox].TIR |= ((hcan->pTxMsg->StdId << 21U) | \ - hcan->pTxMsg->RTR); - } - else - { - assert_param(IS_CAN_EXTID(hcan->pTxMsg->ExtId)); - hcan->Instance->sTxMailBox[transmitmailbox].TIR |= ((hcan->pTxMsg->ExtId << 3U) | \ - hcan->pTxMsg->IDE | \ - hcan->pTxMsg->RTR); - } - - /* Set up the DLC */ - hcan->pTxMsg->DLC &= (uint8_t)0x0000000F; - hcan->Instance->sTxMailBox[transmitmailbox].TDTR &= (uint32_t)0xFFFFFFF0U; - hcan->Instance->sTxMailBox[transmitmailbox].TDTR |= hcan->pTxMsg->DLC; - - /* Set up the data field */ - hcan->Instance->sTxMailBox[transmitmailbox].TDLR = (((uint32_t)hcan->pTxMsg->Data[3U] << 24U) | - ((uint32_t)hcan->pTxMsg->Data[2U] << 16U) | - ((uint32_t)hcan->pTxMsg->Data[1U] << 8U) | - ((uint32_t)hcan->pTxMsg->Data[0U])); - hcan->Instance->sTxMailBox[transmitmailbox].TDHR = (((uint32_t)hcan->pTxMsg->Data[7U] << 24U) | - ((uint32_t)hcan->pTxMsg->Data[6U] << 16U) | - ((uint32_t)hcan->pTxMsg->Data[5U] << 8U) | - ((uint32_t)hcan->pTxMsg->Data[4U])); - /* Request transmission */ - hcan->Instance->sTxMailBox[transmitmailbox].TIR |= CAN_TI0R_TXRQ; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check End of transmission flag */ - while(!(__HAL_CAN_TRANSMIT_STATUS(hcan, transmitmailbox))) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - hcan->State = HAL_CAN_STATE_TIMEOUT; - - __HAL_CAN_CANCEL_TRANSMIT(hcan, transmitmailbox); - - /* Process unlocked */ - __HAL_UNLOCK(hcan); - return HAL_TIMEOUT; - } - } - } - - /* Change CAN state */ - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX_RX0): - hcan->State = HAL_CAN_STATE_BUSY_RX0; - break; - case(HAL_CAN_STATE_BUSY_TX_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX1; - break; - case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; - break; - default: /* HAL_CAN_STATE_BUSY_TX */ - hcan->State = HAL_CAN_STATE_READY; - break; - } - - /* Process unlocked */ - __HAL_UNLOCK(hcan); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - /* Return function status */ - return HAL_ERROR; - } -} - -/** - * @brief Initiates and transmits a CAN frame message. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Transmit_IT(CAN_HandleTypeDef* hcan) -{ - uint32_t transmitmailbox = CAN_TXSTATUS_NOMAILBOX; - - /* Check the parameters */ - assert_param(IS_CAN_IDTYPE(hcan->pTxMsg->IDE)); - assert_param(IS_CAN_RTR(hcan->pTxMsg->RTR)); - assert_param(IS_CAN_DLC(hcan->pTxMsg->DLC)); - - if(((hcan->Instance->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) || \ - ((hcan->Instance->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) || \ - ((hcan->Instance->TSR&CAN_TSR_TME2) == CAN_TSR_TME2)) - { - /* Process Locked */ - __HAL_LOCK(hcan); - - /* Select one empty transmit mailbox */ - if((hcan->Instance->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) - { - transmitmailbox = CAN_TXMAILBOX_0; - } - else if((hcan->Instance->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) - { - transmitmailbox = CAN_TXMAILBOX_1; - } - else - { - transmitmailbox = CAN_TXMAILBOX_2; - } - - /* Set up the Id */ - hcan->Instance->sTxMailBox[transmitmailbox].TIR &= CAN_TI0R_TXRQ; - if(hcan->pTxMsg->IDE == CAN_ID_STD) - { - assert_param(IS_CAN_STDID(hcan->pTxMsg->StdId)); - hcan->Instance->sTxMailBox[transmitmailbox].TIR |= ((hcan->pTxMsg->StdId << 21U) | \ - hcan->pTxMsg->RTR); - } - else - { - assert_param(IS_CAN_EXTID(hcan->pTxMsg->ExtId)); - hcan->Instance->sTxMailBox[transmitmailbox].TIR |= ((hcan->pTxMsg->ExtId << 3U) | \ - hcan->pTxMsg->IDE | \ - hcan->pTxMsg->RTR); - } - - /* Set up the DLC */ - hcan->pTxMsg->DLC &= (uint8_t)0x0000000F; - hcan->Instance->sTxMailBox[transmitmailbox].TDTR &= (uint32_t)0xFFFFFFF0U; - hcan->Instance->sTxMailBox[transmitmailbox].TDTR |= hcan->pTxMsg->DLC; - - /* Set up the data field */ - hcan->Instance->sTxMailBox[transmitmailbox].TDLR = (((uint32_t)hcan->pTxMsg->Data[3U] << 24U) | - ((uint32_t)hcan->pTxMsg->Data[2U] << 16U) | - ((uint32_t)hcan->pTxMsg->Data[1U] << 8U) | - ((uint32_t)hcan->pTxMsg->Data[0U])); - hcan->Instance->sTxMailBox[transmitmailbox].TDHR = (((uint32_t)hcan->pTxMsg->Data[7U] << 24U) | - ((uint32_t)hcan->pTxMsg->Data[6U] << 16U) | - ((uint32_t)hcan->pTxMsg->Data[5U] << 8U) | - ((uint32_t)hcan->pTxMsg->Data[4U])); - - /* Change CAN state */ - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_RX0): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; - break; - case(HAL_CAN_STATE_BUSY_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; - break; - case(HAL_CAN_STATE_BUSY_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; - break; - default: /* HAL_CAN_STATE_READY */ - hcan->State = HAL_CAN_STATE_BUSY_TX; - break; - } - - /* Set CAN error code to none */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hcan); - - /* Request transmission */ - hcan->Instance->sTxMailBox[transmitmailbox].TIR |= CAN_TI0R_TXRQ; - - /* Enable Error warning, Error passive, Bus-off, - Last error and Error Interrupts */ - __HAL_CAN_ENABLE_IT(hcan, CAN_IT_EWG | - CAN_IT_EPV | - CAN_IT_BOF | - CAN_IT_LEC | - CAN_IT_ERR | - CAN_IT_TME); - } - else - { - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - /* Return function status */ - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Receives a correct CAN frame. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param FIFONumber FIFO Number value - * @param Timeout Specify Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Receive(CAN_HandleTypeDef* hcan, uint8_t FIFONumber, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - CanRxMsgTypeDef* pRxMsg = NULL; - - /* Check the parameters */ - assert_param(IS_CAN_FIFO(FIFONumber)); - - /* Check if CAN state is not busy for RX FIFO0 */ - if ((FIFONumber == CAN_FIFO0) && ((hcan->State == HAL_CAN_STATE_BUSY_RX0) || \ - (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0) || \ - (hcan->State == HAL_CAN_STATE_BUSY_RX0_RX1) || \ - (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0_RX1))) - { - return HAL_BUSY; - } - - /* Check if CAN state is not busy for RX FIFO1 */ - if ((FIFONumber == CAN_FIFO1) && ((hcan->State == HAL_CAN_STATE_BUSY_RX1) || \ - (hcan->State == HAL_CAN_STATE_BUSY_TX_RX1) || \ - (hcan->State == HAL_CAN_STATE_BUSY_RX0_RX1) || \ - (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0_RX1))) - { - return HAL_BUSY; - } - - /* Process locked */ - __HAL_LOCK(hcan); - - /* Change CAN state */ - if (FIFONumber == CAN_FIFO0) - { - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; - break; - case(HAL_CAN_STATE_BUSY_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; - break; - case(HAL_CAN_STATE_BUSY_TX_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; - break; - default: /* HAL_CAN_STATE_READY */ - hcan->State = HAL_CAN_STATE_BUSY_RX0; - break; - } - } - else /* FIFONumber == CAN_FIFO1 */ - { - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; - break; - case(HAL_CAN_STATE_BUSY_RX0): - hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; - break; - case(HAL_CAN_STATE_BUSY_TX_RX0): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; - break; - default: /* HAL_CAN_STATE_READY */ - hcan->State = HAL_CAN_STATE_BUSY_RX1; - break; - } - } - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check pending message */ - while(__HAL_CAN_MSG_PENDING(hcan, FIFONumber) == 0U) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - hcan->State = HAL_CAN_STATE_TIMEOUT; - /* Process unlocked */ - __HAL_UNLOCK(hcan); - return HAL_TIMEOUT; - } - } - } - - /* Set RxMsg pointer */ - if(FIFONumber == CAN_FIFO0) - { - pRxMsg = hcan->pRxMsg; - } - else /* FIFONumber == CAN_FIFO1 */ - { - pRxMsg = hcan->pRx1Msg; - } - - /* Get the Id */ - pRxMsg->IDE = (uint8_t)0x04 & hcan->Instance->sFIFOMailBox[FIFONumber].RIR; - if (pRxMsg->IDE == CAN_ID_STD) - { - pRxMsg->StdId = 0x000007FFU & (hcan->Instance->sFIFOMailBox[FIFONumber].RIR >> 21U); - } - else - { - pRxMsg->ExtId = 0x1FFFFFFFU & (hcan->Instance->sFIFOMailBox[FIFONumber].RIR >> 3U); - } - - pRxMsg->RTR = (uint8_t)0x02 & hcan->Instance->sFIFOMailBox[FIFONumber].RIR; - /* Get the DLC */ - pRxMsg->DLC = (uint8_t)0x0F & hcan->Instance->sFIFOMailBox[FIFONumber].RDTR; - /* Get the FMI */ - pRxMsg->FMI = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDTR >> 8U); - /* Get the FIFONumber */ - pRxMsg->FIFONumber = FIFONumber; - /* Get the data field */ - pRxMsg->Data[0] = (uint8_t)0xFF & hcan->Instance->sFIFOMailBox[FIFONumber].RDLR; - pRxMsg->Data[1] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 8U); - pRxMsg->Data[2] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 16U); - pRxMsg->Data[3] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 24U); - pRxMsg->Data[4] = (uint8_t)0xFF & hcan->Instance->sFIFOMailBox[FIFONumber].RDHR; - pRxMsg->Data[5] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 8U); - pRxMsg->Data[6] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 16U); - pRxMsg->Data[7] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 24U); - - /* Release the FIFO */ - if(FIFONumber == CAN_FIFO0) - { - /* Release FIFO0 */ - __HAL_CAN_FIFO_RELEASE(hcan, CAN_FIFO0); - } - else /* FIFONumber == CAN_FIFO1 */ - { - /* Release FIFO1 */ - __HAL_CAN_FIFO_RELEASE(hcan, CAN_FIFO1); - } - - /* Change CAN state */ - if (FIFONumber == CAN_FIFO0) - { - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX_RX0): - hcan->State = HAL_CAN_STATE_BUSY_TX; - break; - case(HAL_CAN_STATE_BUSY_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX1; - break; - case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; - break; - default: /* HAL_CAN_STATE_BUSY_RX0 */ - hcan->State = HAL_CAN_STATE_READY; - break; - } - } - else /* FIFONumber == CAN_FIFO1 */ - { - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX; - break; - case(HAL_CAN_STATE_BUSY_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX0; - break; - case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; - break; - default: /* HAL_CAN_STATE_BUSY_RX1 */ - hcan->State = HAL_CAN_STATE_READY; - break; - } - } - - /* Process unlocked */ - __HAL_UNLOCK(hcan); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Receives a correct CAN frame. - * @param hcan Pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param FIFONumber Specify the FIFO number - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Receive_IT(CAN_HandleTypeDef* hcan, uint8_t FIFONumber) -{ - /* Check the parameters */ - assert_param(IS_CAN_FIFO(FIFONumber)); - - /* Check if CAN state is not busy for RX FIFO0 */ - if((FIFONumber == CAN_FIFO0) && ((hcan->State == HAL_CAN_STATE_BUSY_RX0) || \ - (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0) || \ - (hcan->State == HAL_CAN_STATE_BUSY_RX0_RX1) || \ - (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0_RX1))) - { - return HAL_BUSY; - } - - /* Check if CAN state is not busy for RX FIFO1 */ - if((FIFONumber == CAN_FIFO1) && ((hcan->State == HAL_CAN_STATE_BUSY_RX1) || \ - (hcan->State == HAL_CAN_STATE_BUSY_TX_RX1) || \ - (hcan->State == HAL_CAN_STATE_BUSY_RX0_RX1) || \ - (hcan->State == HAL_CAN_STATE_BUSY_TX_RX0_RX1))) - { - return HAL_BUSY; - } - - /* Process locked */ - __HAL_LOCK(hcan); - - /* Change CAN state */ - if(FIFONumber == CAN_FIFO0) - { - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; - break; - case(HAL_CAN_STATE_BUSY_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; - break; - case(HAL_CAN_STATE_BUSY_TX_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; - break; - default: /* HAL_CAN_STATE_READY */ - hcan->State = HAL_CAN_STATE_BUSY_RX0; - break; - } - } - else /* FIFONumber == CAN_FIFO1 */ - { - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; - break; - case(HAL_CAN_STATE_BUSY_RX0): - hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; - break; - case(HAL_CAN_STATE_BUSY_TX_RX0): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0_RX1; - break; - default: /* HAL_CAN_STATE_READY */ - hcan->State = HAL_CAN_STATE_BUSY_RX1; - break; - } - } - /* Set CAN error code to none */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Enable interrupts: */ - /* - Enable Error warning Interrupt */ - /* - Enable Error passive Interrupt */ - /* - Enable Bus-off Interrupt */ - /* - Enable Last error code Interrupt */ - /* - Enable Error Interrupt */ - /* - Enable Transmit mailbox empty Interrupt */ - __HAL_CAN_ENABLE_IT(hcan, CAN_IT_EWG | - CAN_IT_EPV | - CAN_IT_BOF | - CAN_IT_LEC | - CAN_IT_ERR | - CAN_IT_TME); - - /* Process unlocked */ - __HAL_UNLOCK(hcan); - - if(FIFONumber == CAN_FIFO0) - { - /* Enable FIFO 0 overrun and message pending Interrupt */ - __HAL_CAN_ENABLE_IT(hcan, CAN_IT_FOV0 | CAN_IT_FMP0); - } - else - { - /* Enable FIFO 1 overrun and message pending Interrupt */ - __HAL_CAN_ENABLE_IT(hcan, CAN_IT_FOV1 | CAN_IT_FMP1); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Enters the Sleep (low power) mode. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_CAN_Sleep(CAN_HandleTypeDef* hcan) -{ - uint32_t tickstart = 0U; - - /* Process locked */ - __HAL_LOCK(hcan); - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_BUSY; - - /* Request Sleep mode */ - hcan->Instance->MCR = (((hcan->Instance->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); - - /* Sleep mode status */ - if ((hcan->Instance->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) != CAN_MSR_SLAK) - { - /* Process unlocked */ - __HAL_UNLOCK(hcan); - - /* Return function status */ - return HAL_ERROR; - } - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait the acknowledge */ - while((hcan->Instance->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) != CAN_MSR_SLAK) - { - if((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - hcan->State = HAL_CAN_STATE_TIMEOUT; - /* Process unlocked */ - __HAL_UNLOCK(hcan); - return HAL_TIMEOUT; - } - } - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcan); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Wakes up the CAN peripheral from sleep mode, after that the CAN peripheral - * is in the normal mode. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef* hcan) -{ - uint32_t tickstart = 0U; - - /* Process locked */ - __HAL_LOCK(hcan); - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_BUSY; - - /* Wake up request */ - hcan->Instance->MCR &= ~(uint32_t)CAN_MCR_SLEEP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Sleep mode status */ - while((hcan->Instance->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK) - { - if((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - hcan->State= HAL_CAN_STATE_TIMEOUT; - /* Process unlocked */ - __HAL_UNLOCK(hcan); - return HAL_TIMEOUT; - } - } - if((hcan->Instance->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK) - { - /* Process unlocked */ - __HAL_UNLOCK(hcan); - - /* Return function status */ - return HAL_ERROR; - } - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcan); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Handles CAN interrupt request - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -void HAL_CAN_IRQHandler(CAN_HandleTypeDef* hcan) -{ - uint32_t tmp1 = 0U, tmp2 = 0U, tmp3 = 0U; - uint32_t errorcode = HAL_CAN_ERROR_NONE; - - /* Check Overrun flag for FIFO0 */ - tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_FOV0); - tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_FOV0); - if(tmp1 && tmp2) - { - /* Set CAN error code to FOV0 error */ - errorcode |= HAL_CAN_ERROR_FOV0; - - /* Clear FIFO0 Overrun Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV0); - } - /* Check Overrun flag for FIFO1 */ - tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_FOV1); - tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_FOV1); - - if(tmp1 && tmp2) - { - /* Set CAN error code to FOV1 error */ - errorcode |= HAL_CAN_ERROR_FOV1; - - /* Clear FIFO1 Overrun Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV1); - } - - /* Check End of transmission flag */ - if(__HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_TME)) - { - tmp1 = __HAL_CAN_TRANSMIT_STATUS(hcan, CAN_TXMAILBOX_0); - tmp2 = __HAL_CAN_TRANSMIT_STATUS(hcan, CAN_TXMAILBOX_1); - tmp3 = __HAL_CAN_TRANSMIT_STATUS(hcan, CAN_TXMAILBOX_2); - if(tmp1 || tmp2 || tmp3) - { - tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_TXOK0); - tmp2 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_TXOK1); - tmp3 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_TXOK2); - /* Check Transmit success */ - if(tmp1 || tmp2 || tmp3) - { - /* Call transmit function */ - CAN_Transmit_IT(hcan); - } - else /* Transmit failure */ - { - /* Set CAN error code to TXFAIL error */ - errorcode |= HAL_CAN_ERROR_TXFAIL; - } - - /* Clear transmission status flags (RQCPx and TXOKx) */ - SET_BIT(hcan->Instance->TSR, CAN_TSR_RQCP0 | CAN_TSR_RQCP1 | CAN_TSR_RQCP2 | \ - CAN_FLAG_TXOK0 | CAN_FLAG_TXOK1 | CAN_FLAG_TXOK2); - } - } - - tmp1 = __HAL_CAN_MSG_PENDING(hcan, CAN_FIFO0); - tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_FMP0); - /* Check End of reception flag for FIFO0 */ - if((tmp1 != 0U) && tmp2) - { - /* Call receive function */ - CAN_Receive_IT(hcan, CAN_FIFO0); - } - - tmp1 = __HAL_CAN_MSG_PENDING(hcan, CAN_FIFO1); - tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_FMP1); - /* Check End of reception flag for FIFO1 */ - if((tmp1 != 0U) && tmp2) - { - /* Call receive function */ - CAN_Receive_IT(hcan, CAN_FIFO1); - } - - /* Set error code in handle */ - hcan->ErrorCode |= errorcode; - - tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_EWG); - tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_EWG); - tmp3 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_ERR); - /* Check Error Warning Flag */ - if(tmp1 && tmp2 && tmp3) - { - /* Set CAN error code to EWG error */ - hcan->ErrorCode |= HAL_CAN_ERROR_EWG; - } - - tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_EPV); - tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_EPV); - tmp3 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_ERR); - /* Check Error Passive Flag */ - if(tmp1 && tmp2 && tmp3) - { - /* Set CAN error code to EPV error */ - hcan->ErrorCode |= HAL_CAN_ERROR_EPV; - } - - tmp1 = __HAL_CAN_GET_FLAG(hcan, CAN_FLAG_BOF); - tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_BOF); - tmp3 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_ERR); - /* Check Bus-Off Flag */ - if(tmp1 && tmp2 && tmp3) - { - /* Set CAN error code to BOF error */ - hcan->ErrorCode |= HAL_CAN_ERROR_BOF; - } - - tmp1 = HAL_IS_BIT_CLR(hcan->Instance->ESR, CAN_ESR_LEC); - tmp2 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_LEC); - tmp3 = __HAL_CAN_GET_IT_SOURCE(hcan, CAN_IT_ERR); - /* Check Last error code Flag */ - if((!tmp1) && tmp2 && tmp3) - { - tmp1 = (hcan->Instance->ESR) & CAN_ESR_LEC; - switch(tmp1) - { - case(CAN_ESR_LEC_0): - /* Set CAN error code to STF error */ - hcan->ErrorCode |= HAL_CAN_ERROR_STF; - break; - case(CAN_ESR_LEC_1): - /* Set CAN error code to FOR error */ - hcan->ErrorCode |= HAL_CAN_ERROR_FOR; - break; - case(CAN_ESR_LEC_1 | CAN_ESR_LEC_0): - /* Set CAN error code to ACK error */ - hcan->ErrorCode |= HAL_CAN_ERROR_ACK; - break; - case(CAN_ESR_LEC_2): - /* Set CAN error code to BR error */ - hcan->ErrorCode |= HAL_CAN_ERROR_BR; - break; - case(CAN_ESR_LEC_2 | CAN_ESR_LEC_0): - /* Set CAN error code to BD error */ - hcan->ErrorCode |= HAL_CAN_ERROR_BD; - break; - case(CAN_ESR_LEC_2 | CAN_ESR_LEC_1): - /* Set CAN error code to CRC error */ - hcan->ErrorCode |= HAL_CAN_ERROR_CRC; - break; - default: - break; - } - - /* Clear Last error code Flag */ - hcan->Instance->ESR &= ~(CAN_ESR_LEC); - } - - /* Call the Error call Back in case of Errors */ - if(hcan->ErrorCode != HAL_CAN_ERROR_NONE) - { - /* Clear ERRI Flag */ - hcan->Instance->MSR = CAN_MSR_ERRI; - /* Set the CAN state ready to be able to start again the process */ - hcan->State = HAL_CAN_STATE_READY; - - /* Disable interrupts: */ - /* - Disable Error warning Interrupt */ - /* - Disable Error passive Interrupt */ - /* - Disable Bus-off Interrupt */ - /* - Disable Last error code Interrupt */ - /* - Disable Error Interrupt */ - /* - Disable FIFO 0 message pending Interrupt */ - /* - Disable FIFO 0 Overrun Interrupt */ - /* - Disable FIFO 1 message pending Interrupt */ - /* - Disable FIFO 1 Overrun Interrupt */ - /* - Disable Transmit mailbox empty Interrupt */ - __HAL_CAN_DISABLE_IT(hcan, CAN_IT_EWG | - CAN_IT_EPV | - CAN_IT_BOF | - CAN_IT_LEC | - CAN_IT_ERR | - CAN_IT_FMP0| - CAN_IT_FOV0| - CAN_IT_FMP1| - CAN_IT_FOV1| - CAN_IT_TME); - - /* Call Error callback function */ - HAL_CAN_ErrorCallback(hcan); - } -} - -/** - * @brief Transmission complete callback in non blocking mode - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxCpltCallback(CAN_HandleTypeDef* hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Transmission complete callback in non blocking mode - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxCpltCallback(CAN_HandleTypeDef* hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Error CAN callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_ErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group3 Peripheral State and Error functions - * @brief CAN Peripheral State functions - * -@verbatim - ============================================================================== - ##### Peripheral State and Error functions ##### - ============================================================================== - [..] - This subsection provides functions allowing to : - (+) Check the CAN state. - (+) Check CAN Errors detected during interrupt process - -@endverbatim - * @{ - */ - -/** - * @brief return the CAN state - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL state - */ -HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef* hcan) -{ - /* Return CAN state */ - return hcan->State; -} - -/** - * @brief Return the CAN error code - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval CAN Error Code - */ -uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan) -{ - return hcan->ErrorCode; -} - -/** - * @} - */ -/** - * @brief Initiates and transmits a CAN frame message. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -static HAL_StatusTypeDef CAN_Transmit_IT(CAN_HandleTypeDef* hcan) -{ - /* Disable Transmit mailbox empty Interrupt */ - __HAL_CAN_DISABLE_IT(hcan, CAN_IT_TME); - - if(hcan->State == HAL_CAN_STATE_BUSY_TX) - { - /* Disable Error warning, Error passive, Bus-off, Last error code - and Error Interrupts */ - __HAL_CAN_DISABLE_IT(hcan, CAN_IT_EWG | - CAN_IT_EPV | - CAN_IT_BOF | - CAN_IT_LEC | - CAN_IT_ERR ); - } - - /* Change CAN state */ - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX_RX0): - hcan->State = HAL_CAN_STATE_BUSY_RX0; - break; - case(HAL_CAN_STATE_BUSY_TX_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX1; - break; - case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX0_RX1; - break; - default: /* HAL_CAN_STATE_BUSY_TX */ - hcan->State = HAL_CAN_STATE_READY; - break; - } - - /* Transmission complete callback */ - HAL_CAN_TxCpltCallback(hcan); - - return HAL_OK; -} - -/** - * @brief Receives a correct CAN frame. - * @param hcan Pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param FIFONumber Specify the FIFO number - * @retval HAL status - * @retval None - */ -static HAL_StatusTypeDef CAN_Receive_IT(CAN_HandleTypeDef* hcan, uint8_t FIFONumber) -{ - uint32_t tmp1 = 0U; - CanRxMsgTypeDef* pRxMsg = NULL; - - /* Set RxMsg pointer */ - if(FIFONumber == CAN_FIFO0) - { - pRxMsg = hcan->pRxMsg; - } - else /* FIFONumber == CAN_FIFO1 */ - { - pRxMsg = hcan->pRx1Msg; - } - - /* Get the Id */ - pRxMsg->IDE = (uint8_t)0x04 & hcan->Instance->sFIFOMailBox[FIFONumber].RIR; - if (pRxMsg->IDE == CAN_ID_STD) - { - pRxMsg->StdId = 0x000007FFU & (hcan->Instance->sFIFOMailBox[FIFONumber].RIR >> 21U); - } - else - { - pRxMsg->ExtId = 0x1FFFFFFFU & (hcan->Instance->sFIFOMailBox[FIFONumber].RIR >> 3U); - } - - pRxMsg->RTR = (uint8_t)0x02 & hcan->Instance->sFIFOMailBox[FIFONumber].RIR; - /* Get the DLC */ - pRxMsg->DLC = (uint8_t)0x0F & hcan->Instance->sFIFOMailBox[FIFONumber].RDTR; - /* Get the FIFONumber */ - pRxMsg->FIFONumber = FIFONumber; - /* Get the FMI */ - pRxMsg->FMI = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDTR >> 8U); - /* Get the data field */ - pRxMsg->Data[0] = (uint8_t)0xFF & hcan->Instance->sFIFOMailBox[FIFONumber].RDLR; - pRxMsg->Data[1] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 8U); - pRxMsg->Data[2] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 16U); - pRxMsg->Data[3] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDLR >> 24U); - pRxMsg->Data[4] = (uint8_t)0xFF & hcan->Instance->sFIFOMailBox[FIFONumber].RDHR; - pRxMsg->Data[5] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 8U); - pRxMsg->Data[6] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 16U); - pRxMsg->Data[7] = (uint8_t)0xFF & (hcan->Instance->sFIFOMailBox[FIFONumber].RDHR >> 24U); - /* Release the FIFO */ - /* Release FIFO0 */ - if (FIFONumber == CAN_FIFO0) - { - __HAL_CAN_FIFO_RELEASE(hcan, CAN_FIFO0); - - /* Disable FIFO 0 overrun and message pending Interrupt */ - __HAL_CAN_DISABLE_IT(hcan, CAN_IT_FOV0 | CAN_IT_FMP0); - } - /* Release FIFO1 */ - else /* FIFONumber == CAN_FIFO1 */ - { - __HAL_CAN_FIFO_RELEASE(hcan, CAN_FIFO1); - - /* Disable FIFO 1 overrun and message pending Interrupt */ - __HAL_CAN_DISABLE_IT(hcan, CAN_IT_FOV1 | CAN_IT_FMP1); - } - - tmp1 = hcan->State; - if((tmp1 == HAL_CAN_STATE_BUSY_RX0) || (tmp1 == HAL_CAN_STATE_BUSY_RX1)) - { - /* Disable Error warning, Error passive, Bus-off, Last error code - and Error Interrupts */ - __HAL_CAN_DISABLE_IT(hcan, CAN_IT_EWG | - CAN_IT_EPV | - CAN_IT_BOF | - CAN_IT_LEC | - CAN_IT_ERR); - } - - /* Change CAN state */ - if (FIFONumber == CAN_FIFO0) - { - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX_RX0): - hcan->State = HAL_CAN_STATE_BUSY_TX; - break; - case(HAL_CAN_STATE_BUSY_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX1; - break; - case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX1; - break; - default: /* HAL_CAN_STATE_BUSY_RX0 */ - hcan->State = HAL_CAN_STATE_READY; - break; - } - } - else /* FIFONumber == CAN_FIFO1 */ - { - switch(hcan->State) - { - case(HAL_CAN_STATE_BUSY_TX_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX; - break; - case(HAL_CAN_STATE_BUSY_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_RX0; - break; - case(HAL_CAN_STATE_BUSY_TX_RX0_RX1): - hcan->State = HAL_CAN_STATE_BUSY_TX_RX0; - break; - default: /* HAL_CAN_STATE_BUSY_RX1 */ - hcan->State = HAL_CAN_STATE_READY; - break; - } - } - - /* Receive complete callback */ - HAL_CAN_RxCpltCallback(hcan); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c deleted file mode 100644 index d0afdd373bf3460..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c +++ /dev/null @@ -1,615 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal.c - * @author MCD Application Team - * @brief HAL module driver. - * This is the common part of the HAL initialization - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The common HAL driver contains a set of generic and common APIs that can be - used by the PPP peripheral drivers and the user to start using the HAL. - [..] - The HAL contains two APIs' categories: - (+) Common HAL APIs - (+) Services HAL APIs - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup HAL HAL - * @brief HAL module driver. - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup HAL_Private_Constants - * @{ - */ -/** - * @brief STM32F4xx HAL Driver version number V1.7.13 - */ -#define __STM32F4xx_HAL_VERSION_MAIN (0x01U) /*!< [31:24] main version */ -#define __STM32F4xx_HAL_VERSION_SUB1 (0x07U) /*!< [23:16] sub1 version */ -#define __STM32F4xx_HAL_VERSION_SUB2 (0x0DU) /*!< [15:8] sub2 version */ -#define __STM32F4xx_HAL_VERSION_RC (0x00U) /*!< [7:0] release candidate */ -#define __STM32F4xx_HAL_VERSION ((__STM32F4xx_HAL_VERSION_MAIN << 24U)\ - |(__STM32F4xx_HAL_VERSION_SUB1 << 16U)\ - |(__STM32F4xx_HAL_VERSION_SUB2 << 8U )\ - |(__STM32F4xx_HAL_VERSION_RC)) - -#define IDCODE_DEVID_MASK 0x00000FFFU - -/* ------------ RCC registers bit address in the alias region ----------- */ -#define SYSCFG_OFFSET (SYSCFG_BASE - PERIPH_BASE) -/* --- MEMRMP Register ---*/ -/* Alias word address of UFB_MODE bit */ -#define MEMRMP_OFFSET SYSCFG_OFFSET -#define UFB_MODE_BIT_NUMBER SYSCFG_MEMRMP_UFB_MODE_Pos -#define UFB_MODE_BB (uint32_t)(PERIPH_BB_BASE + (MEMRMP_OFFSET * 32U) + (UFB_MODE_BIT_NUMBER * 4U)) - -/* --- CMPCR Register ---*/ -/* Alias word address of CMP_PD bit */ -#define CMPCR_OFFSET (SYSCFG_OFFSET + 0x20U) -#define CMP_PD_BIT_NUMBER SYSCFG_CMPCR_CMP_PD_Pos -#define CMPCR_CMP_PD_BB (uint32_t)(PERIPH_BB_BASE + (CMPCR_OFFSET * 32U) + (CMP_PD_BIT_NUMBER * 4U)) - -/* --- MCHDLYCR Register ---*/ -/* Alias word address of BSCKSEL bit */ -#define MCHDLYCR_OFFSET (SYSCFG_OFFSET + 0x30U) -#define BSCKSEL_BIT_NUMBER SYSCFG_MCHDLYCR_BSCKSEL_Pos -#define MCHDLYCR_BSCKSEL_BB (uint32_t)(PERIPH_BB_BASE + (MCHDLYCR_OFFSET * 32U) + (BSCKSEL_BIT_NUMBER * 4U)) -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @addtogroup HAL_Private_Variables - * @{ - */ -__IO uint32_t uwTick; -uint32_t uwTickPrio = (1UL << __NVIC_PRIO_BITS); /* Invalid PRIO */ -HAL_TickFreqTypeDef uwTickFreq = HAL_TICK_FREQ_DEFAULT; /* 1KHz */ -/** - * @} - */ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup HAL_Exported_Functions HAL Exported Functions - * @{ - */ - -/** @defgroup HAL_Exported_Functions_Group1 Initialization and de-initialization Functions - * @brief Initialization and de-initialization functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initializes the Flash interface the NVIC allocation and initial clock - configuration. It initializes the systick also when timeout is needed - and the backup domain when enabled. - (+) De-Initializes common part of the HAL. - (+) Configure the time base source to have 1ms time base with a dedicated - Tick interrupt priority. - (++) SysTick timer is used by default as source of time base, but user - can eventually implement his proper time base source (a general purpose - timer for example or other time source), keeping in mind that Time base - duration should be kept 1ms since PPP_TIMEOUT_VALUEs are defined and - handled in milliseconds basis. - (++) Time base configuration function (HAL_InitTick ()) is called automatically - at the beginning of the program after reset by HAL_Init() or at any time - when clock is configured, by HAL_RCC_ClockConfig(). - (++) Source of time base is configured to generate interrupts at regular - time intervals. Care must be taken if HAL_Delay() is called from a - peripheral ISR process, the Tick interrupt line must have higher priority - (numerically lower) than the peripheral interrupt. Otherwise the caller - ISR process will be blocked. - (++) functions affecting time base configurations are declared as __weak - to make override possible in case of other implementations in user file. -@endverbatim - * @{ - */ - -/** - * @brief This function is used to initialize the HAL Library; it must be the first - * instruction to be executed in the main program (before to call any other - * HAL function), it performs the following: - * Configure the Flash prefetch, instruction and Data caches. - * Configures the SysTick to generate an interrupt each 1 millisecond, - * which is clocked by the HSI (at this stage, the clock is not yet - * configured and thus the system is running from the internal HSI at 16 MHz). - * Set NVIC Group Priority to 4. - * Calls the HAL_MspInit() callback function defined in user file - * "stm32f4xx_hal_msp.c" to do the global low level hardware initialization - * - * @note SysTick is used as time base for the HAL_Delay() function, the application - * need to ensure that the SysTick time base is always set to 1 millisecond - * to have correct HAL operation. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_Init(void) -{ - /* Configure Flash prefetch, Instruction cache, Data cache */ -#if (INSTRUCTION_CACHE_ENABLE != 0U) - __HAL_FLASH_INSTRUCTION_CACHE_ENABLE(); -#endif /* INSTRUCTION_CACHE_ENABLE */ - -#if (DATA_CACHE_ENABLE != 0U) - __HAL_FLASH_DATA_CACHE_ENABLE(); -#endif /* DATA_CACHE_ENABLE */ - -#if (PREFETCH_ENABLE != 0U) - __HAL_FLASH_PREFETCH_BUFFER_ENABLE(); -#endif /* PREFETCH_ENABLE */ - - /* Set Interrupt Group Priority */ - HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); - - /* Use systick as time base source and configure 1ms tick (default clock after Reset is HSI) */ - HAL_InitTick(TICK_INT_PRIORITY); - - /* Init the low level hardware */ - HAL_MspInit(); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief This function de-Initializes common part of the HAL and stops the systick. - * This function is optional. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DeInit(void) -{ - /* Reset of all peripherals */ - __HAL_RCC_APB1_FORCE_RESET(); - __HAL_RCC_APB1_RELEASE_RESET(); - - __HAL_RCC_APB2_FORCE_RESET(); - __HAL_RCC_APB2_RELEASE_RESET(); - - __HAL_RCC_AHB1_FORCE_RESET(); - __HAL_RCC_AHB1_RELEASE_RESET(); - - __HAL_RCC_AHB2_FORCE_RESET(); - __HAL_RCC_AHB2_RELEASE_RESET(); - - __HAL_RCC_AHB3_FORCE_RESET(); - __HAL_RCC_AHB3_RELEASE_RESET(); - - /* De-Init the low level hardware */ - HAL_MspDeInit(); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initialize the MSP. - * @retval None - */ -__weak void HAL_MspInit(void) -{ - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes the MSP. - * @retval None - */ -__weak void HAL_MspDeInit(void) -{ - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief This function configures the source of the time base. - * The time source is configured to have 1ms time base with a dedicated - * Tick interrupt priority. - * @note This function is called automatically at the beginning of program after - * reset by HAL_Init() or at any time when clock is reconfigured by HAL_RCC_ClockConfig(). - * @note In the default implementation, SysTick timer is the source of time base. - * It is used to generate interrupts at regular time intervals. - * Care must be taken if HAL_Delay() is called from a peripheral ISR process, - * The SysTick interrupt must have higher priority (numerically lower) - * than the peripheral interrupt. Otherwise the caller ISR process will be blocked. - * The function is declared as __weak to be overwritten in case of other - * implementation in user file. - * @param TickPriority Tick interrupt priority. - * @retval HAL status - */ -__weak HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) -{ - /* Configure the SysTick to have interrupt in 1ms time basis*/ - if (HAL_SYSTICK_Config(SystemCoreClock / (1000U / uwTickFreq)) > 0U) - { - return HAL_ERROR; - } - - /* Configure the SysTick IRQ priority */ - if (TickPriority < (1UL << __NVIC_PRIO_BITS)) - { - HAL_NVIC_SetPriority(SysTick_IRQn, TickPriority, 0U); - uwTickPrio = TickPriority; - } - else - { - return HAL_ERROR; - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup HAL_Exported_Functions_Group2 HAL Control functions - * @brief HAL Control functions - * -@verbatim - =============================================================================== - ##### HAL Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Provide a tick value in millisecond - (+) Provide a blocking delay in millisecond - (+) Suspend the time base source interrupt - (+) Resume the time base source interrupt - (+) Get the HAL API driver version - (+) Get the device identifier - (+) Get the device revision identifier - (+) Enable/Disable Debug module during SLEEP mode - (+) Enable/Disable Debug module during STOP mode - (+) Enable/Disable Debug module during STANDBY mode - -@endverbatim - * @{ - */ - -/** - * @brief This function is called to increment a global variable "uwTick" - * used as application time base. - * @note In the default implementation, this variable is incremented each 1ms - * in SysTick ISR. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @retval None - */ -__weak void HAL_IncTick(void) -{ - uwTick += uwTickFreq; -} - -/** - * @brief Provides a tick value in millisecond. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @retval tick value - */ -__weak uint32_t HAL_GetTick(void) -{ - return uwTick; -} - -/** - * @brief This function returns a tick priority. - * @retval tick priority - */ -uint32_t HAL_GetTickPrio(void) -{ - return uwTickPrio; -} - -/** - * @brief Set new tick Freq. - * @retval Status - */ -HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_TickFreqTypeDef prevTickFreq; - - assert_param(IS_TICKFREQ(Freq)); - - if (uwTickFreq != Freq) - { - /* Back up uwTickFreq frequency */ - prevTickFreq = uwTickFreq; - - /* Update uwTickFreq global variable used by HAL_InitTick() */ - uwTickFreq = Freq; - - /* Apply the new tick Freq */ - status = HAL_InitTick(uwTickPrio); - - if (status != HAL_OK) - { - /* Restore previous tick frequency */ - uwTickFreq = prevTickFreq; - } - } - - return status; -} - -/** - * @brief Return tick frequency. - * @retval tick period in Hz - */ -HAL_TickFreqTypeDef HAL_GetTickFreq(void) -{ - return uwTickFreq; -} - -/** - * @brief This function provides minimum delay (in milliseconds) based - * on variable incremented. - * @note In the default implementation , SysTick timer is the source of time base. - * It is used to generate interrupts at regular time intervals where uwTick - * is incremented. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @param Delay specifies the delay time length, in milliseconds. - * @retval None - */ -__weak void HAL_Delay(uint32_t Delay) -{ - uint32_t tickstart = HAL_GetTick(); - uint32_t wait = Delay; - - /* Add a freq to guarantee minimum wait */ - if (wait < HAL_MAX_DELAY) - { - wait += (uint32_t)(uwTickFreq); - } - - while((HAL_GetTick() - tickstart) < wait) - { - } -} - -/** - * @brief Suspend Tick increment. - * @note In the default implementation , SysTick timer is the source of time base. It is - * used to generate interrupts at regular time intervals. Once HAL_SuspendTick() - * is called, the SysTick interrupt will be disabled and so Tick increment - * is suspended. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @retval None - */ -__weak void HAL_SuspendTick(void) -{ - /* Disable SysTick Interrupt */ - SysTick->CTRL &= ~SysTick_CTRL_TICKINT_Msk; -} - -/** - * @brief Resume Tick increment. - * @note In the default implementation , SysTick timer is the source of time base. It is - * used to generate interrupts at regular time intervals. Once HAL_ResumeTick() - * is called, the SysTick interrupt will be enabled and so Tick increment - * is resumed. - * @note This function is declared as __weak to be overwritten in case of other - * implementations in user file. - * @retval None - */ -__weak void HAL_ResumeTick(void) -{ - /* Enable SysTick Interrupt */ - SysTick->CTRL |= SysTick_CTRL_TICKINT_Msk; -} - -/** - * @brief Returns the HAL revision - * @retval version : 0xXYZR (8bits for each decimal, R for RC) - */ -uint32_t HAL_GetHalVersion(void) -{ - return __STM32F4xx_HAL_VERSION; -} - -/** - * @brief Returns the device revision identifier. - * @retval Device revision identifier - */ -uint32_t HAL_GetREVID(void) -{ - return((DBGMCU->IDCODE) >> 16U); -} - -/** - * @brief Returns the device identifier. - * @retval Device identifier - */ -uint32_t HAL_GetDEVID(void) -{ - return((DBGMCU->IDCODE) & IDCODE_DEVID_MASK); -} - -/** - * @brief Enable the Debug Module during SLEEP mode - * @retval None - */ -void HAL_DBGMCU_EnableDBGSleepMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Disable the Debug Module during SLEEP mode - * @retval None - */ -void HAL_DBGMCU_DisableDBGSleepMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Enable the Debug Module during STOP mode - * @retval None - */ -void HAL_DBGMCU_EnableDBGStopMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Disable the Debug Module during STOP mode - * @retval None - */ -void HAL_DBGMCU_DisableDBGStopMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Enable the Debug Module during STANDBY mode - * @retval None - */ -void HAL_DBGMCU_EnableDBGStandbyMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Disable the Debug Module during STANDBY mode - * @retval None - */ -void HAL_DBGMCU_DisableDBGStandbyMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Enables the I/O Compensation Cell. - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V. - * @retval None - */ -void HAL_EnableCompensationCell(void) -{ - *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)ENABLE; -} - -/** - * @brief Power-down the I/O Compensation Cell. - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V. - * @retval None - */ -void HAL_DisableCompensationCell(void) -{ - *(__IO uint32_t *)CMPCR_CMP_PD_BB = (uint32_t)DISABLE; -} - -/** - * @brief Returns first word of the unique device identifier (UID based on 96 bits) - * @retval Device identifier - */ -uint32_t HAL_GetUIDw0(void) -{ - return (READ_REG(*((uint32_t *)UID_BASE))); -} - -/** - * @brief Returns second word of the unique device identifier (UID based on 96 bits) - * @retval Device identifier - */ -uint32_t HAL_GetUIDw1(void) -{ - return (READ_REG(*((uint32_t *)(UID_BASE + 4U)))); -} - -/** - * @brief Returns third word of the unique device identifier (UID based on 96 bits) - * @retval Device identifier - */ -uint32_t HAL_GetUIDw2(void) -{ - return (READ_REG(*((uint32_t *)(UID_BASE + 8U)))); -} - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Enables the Internal FLASH Bank Swapping. - * - * @note This function can be used only for STM32F42xxx/43xxx/469xx/479xx devices. - * - * @note Flash Bank2 mapped at 0x08000000 (and aliased @0x00000000) - * and Flash Bank1 mapped at 0x08100000 (and aliased at 0x00100000) - * - * @retval None - */ -void HAL_EnableMemorySwappingBank(void) -{ - *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables the Internal FLASH Bank Swapping. - * - * @note This function can be used only for STM32F42xxx/43xxx/469xx/479xx devices. - * - * @note The default state : Flash Bank1 mapped at 0x08000000 (and aliased @0x00000000) - * and Flash Bank2 mapped at 0x08100000 (and aliased at 0x00100000) - * - * @retval None - */ -void HAL_DisableMemorySwappingBank(void) -{ - *(__IO uint32_t *)UFB_MODE_BB = (uint32_t)DISABLE; -} -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c deleted file mode 100644 index cf3df802b48fd4d..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c +++ /dev/null @@ -1,2109 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_adc.c - * @author MCD Application Team - * @brief This file provides firmware functions to manage the following - * functionalities of the Analog to Digital Converter (ADC) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + State and errors functions - * - @verbatim - ============================================================================== - ##### ADC Peripheral features ##### - ============================================================================== - [..] - (#) 12-bit, 10-bit, 8-bit or 6-bit configurable resolution. - (#) Interrupt generation at the end of conversion, end of injected conversion, - and in case of analog watchdog or overrun events - (#) Single and continuous conversion modes. - (#) Scan mode for automatic conversion of channel 0 to channel x. - (#) Data alignment with in-built data coherency. - (#) Channel-wise programmable sampling time. - (#) External trigger option with configurable polarity for both regular and - injected conversion. - (#) Dual/Triple mode (on devices with 2 ADCs or more). - (#) Configurable DMA data storage in Dual/Triple ADC mode. - (#) Configurable delay between conversions in Dual/Triple interleaved mode. - (#) ADC conversion type (refer to the datasheets). - (#) ADC supply requirements: 2.4 V to 3.6 V at full speed and down to 1.8 V at - slower speed. - (#) ADC input range: VREF(minus) = VIN = VREF(plus). - (#) DMA request generation during regular channel conversion. - - - ##### How to use this driver ##### - ============================================================================== - [..] - (#)Initialize the ADC low level resources by implementing the HAL_ADC_MspInit(): - (##) Enable the ADC interface clock using __HAL_RCC_ADC_CLK_ENABLE() - (##) ADC pins configuration - (+++) Enable the clock for the ADC GPIOs using the following function: - __HAL_RCC_GPIOx_CLK_ENABLE() - (+++) Configure these ADC pins in analog mode using HAL_GPIO_Init() - (##) In case of using interrupts (e.g. HAL_ADC_Start_IT()) - (+++) Configure the ADC interrupt priority using HAL_NVIC_SetPriority() - (+++) Enable the ADC IRQ handler using HAL_NVIC_EnableIRQ() - (+++) In ADC IRQ handler, call HAL_ADC_IRQHandler() - (##) In case of using DMA to control data transfer (e.g. HAL_ADC_Start_DMA()) - (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE() - (+++) Configure and enable two DMA streams stream for managing data - transfer from peripheral to memory (output stream) - (+++) Associate the initialized DMA handle to the CRYP DMA handle - using __HAL_LINKDMA() - (+++) Configure the priority and enable the NVIC for the transfer complete - interrupt on the two DMA Streams. The output stream should have higher - priority than the input stream. - - *** Configuration of ADC, groups regular/injected, channels parameters *** - ============================================================================== - [..] - (#) Configure the ADC parameters (resolution, data alignment, ...) - and regular group parameters (conversion trigger, sequencer, ...) - using function HAL_ADC_Init(). - - (#) Configure the channels for regular group parameters (channel number, - channel rank into sequencer, ..., into regular group) - using function HAL_ADC_ConfigChannel(). - - (#) Optionally, configure the injected group parameters (conversion trigger, - sequencer, ..., of injected group) - and the channels for injected group parameters (channel number, - channel rank into sequencer, ..., into injected group) - using function HAL_ADCEx_InjectedConfigChannel(). - - (#) Optionally, configure the analog watchdog parameters (channels - monitored, thresholds, ...) using function HAL_ADC_AnalogWDGConfig(). - - (#) Optionally, for devices with several ADC instances: configure the - multimode parameters using function HAL_ADCEx_MultiModeConfigChannel(). - - *** Execution of ADC conversions *** - ============================================================================== - [..] - (#) ADC driver can be used among three modes: polling, interruption, - transfer by DMA. - - *** Polling mode IO operation *** - ================================= - [..] - (+) Start the ADC peripheral using HAL_ADC_Start() - (+) Wait for end of conversion using HAL_ADC_PollForConversion(), at this stage - user can specify the value of timeout according to his end application - (+) To read the ADC converted values, use the HAL_ADC_GetValue() function. - (+) Stop the ADC peripheral using HAL_ADC_Stop() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Start the ADC peripheral using HAL_ADC_Start_IT() - (+) Use HAL_ADC_IRQHandler() called under ADC_IRQHandler() Interrupt subroutine - (+) At ADC end of conversion HAL_ADC_ConvCpltCallback() function is executed and user can - add his own code by customization of function pointer HAL_ADC_ConvCpltCallback - (+) In case of ADC Error, HAL_ADC_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_ADC_ErrorCallback - (+) Stop the ADC peripheral using HAL_ADC_Stop_IT() - - *** DMA mode IO operation *** - ============================== - [..] - (+) Start the ADC peripheral using HAL_ADC_Start_DMA(), at this stage the user specify the length - of data to be transferred at each end of conversion - (+) At The end of data transfer by HAL_ADC_ConvCpltCallback() function is executed and user can - add his own code by customization of function pointer HAL_ADC_ConvCpltCallback - (+) In case of transfer Error, HAL_ADC_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_ADC_ErrorCallback - (+) Stop the ADC peripheral using HAL_ADC_Stop_DMA() - - *** ADC HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in ADC HAL driver. - - (+) __HAL_ADC_ENABLE : Enable the ADC peripheral - (+) __HAL_ADC_DISABLE : Disable the ADC peripheral - (+) __HAL_ADC_ENABLE_IT: Enable the ADC end of conversion interrupt - (+) __HAL_ADC_DISABLE_IT: Disable the ADC end of conversion interrupt - (+) __HAL_ADC_GET_IT_SOURCE: Check if the specified ADC interrupt source is enabled or disabled - (+) __HAL_ADC_CLEAR_FLAG: Clear the ADC's pending flags - (+) __HAL_ADC_GET_FLAG: Get the selected ADC's flag status - (+) ADC_GET_RESOLUTION: Return resolution bits in CR1 register - - [..] - (@) You can refer to the ADC HAL driver header file for more useful macros - - *** Deinitialization of ADC *** - ============================================================================== - [..] - (#) Disable the ADC interface - (++) ADC clock can be hard reset and disabled at RCC top level. - (++) Hard reset of ADC peripherals - using macro __HAL_RCC_ADC_FORCE_RESET(), __HAL_RCC_ADC_RELEASE_RESET(). - (++) ADC clock disable using the equivalent macro/functions as configuration step. - (+++) Example: - Into HAL_ADC_MspDeInit() (recommended code location) or with - other device clock parameters configuration: - (+++) HAL_RCC_GetOscConfig(&RCC_OscInitStructure); - (+++) RCC_OscInitStructure.OscillatorType = RCC_OSCILLATORTYPE_HSI; - (+++) RCC_OscInitStructure.HSIState = RCC_HSI_OFF; (if not used for system clock) - (+++) HAL_RCC_OscConfig(&RCC_OscInitStructure); - - (#) ADC pins configuration - (++) Disable the clock for the ADC GPIOs using macro __HAL_RCC_GPIOx_CLK_DISABLE() - - (#) Optionally, in case of usage of ADC with interruptions: - (++) Disable the NVIC for ADC using function HAL_NVIC_DisableIRQ(ADCx_IRQn) - - (#) Optionally, in case of usage of DMA: - (++) Deinitialize the DMA using function HAL_DMA_DeInit(). - (++) Disable the NVIC for DMA using function HAL_NVIC_DisableIRQ(DMAx_Channelx_IRQn) - *** Callback registration *** - ============================================================================== - [..] - - The compilation flag USE_HAL_ADC_REGISTER_CALLBACKS, when set to 1, - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_ADC_RegisterCallback() - to register an interrupt callback. - [..] - - Function HAL_ADC_RegisterCallback() allows to register following callbacks: - (+) ConvCpltCallback : ADC conversion complete callback - (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback - (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback - (+) ErrorCallback : ADC error callback - (+) InjectedConvCpltCallback : ADC group injected conversion complete callback - (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback - (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback - (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback - (+) EndOfSamplingCallback : ADC end of sampling callback - (+) MspInitCallback : ADC Msp Init callback - (+) MspDeInitCallback : ADC Msp DeInit callback - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - [..] - - Use function HAL_ADC_UnRegisterCallback to reset a callback to the default - weak function. - [..] - - HAL_ADC_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) ConvCpltCallback : ADC conversion complete callback - (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback - (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback - (+) ErrorCallback : ADC error callback - (+) InjectedConvCpltCallback : ADC group injected conversion complete callback - (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback - (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback - (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback - (+) EndOfSamplingCallback : ADC end of sampling callback - (+) MspInitCallback : ADC Msp Init callback - (+) MspDeInitCallback : ADC Msp DeInit callback - [..] - - By default, after the HAL_ADC_Init() and when the state is HAL_ADC_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_ADC_ConvCpltCallback(), HAL_ADC_ErrorCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_ADC_Init()/ HAL_ADC_DeInit() only when - these callbacks are null (not registered beforehand). - [..] - - If MspInit or MspDeInit are not null, the HAL_ADC_Init()/ HAL_ADC_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - [..] - - Callbacks can be registered/unregistered in HAL_ADC_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_ADC_STATE_READY or HAL_ADC_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - [..] - - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_ADC_RegisterCallback() before calling HAL_ADC_DeInit() - or HAL_ADC_Init() function. - [..] - - When the compilation flag USE_HAL_ADC_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup ADC ADC - * @brief ADC driver modules - * @{ - */ - -#ifdef HAL_ADC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @addtogroup ADC_Private_Functions - * @{ - */ -/* Private function prototypes -----------------------------------------------*/ -static void ADC_Init(ADC_HandleTypeDef* hadc); -static void ADC_DMAConvCplt(DMA_HandleTypeDef *hdma); -static void ADC_DMAError(DMA_HandleTypeDef *hdma); -static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef *hdma); -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup ADC_Exported_Functions ADC Exported Functions - * @{ - */ - -/** @defgroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the ADC. - (+) De-initialize the ADC. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the ADCx peripheral according to the specified parameters - * in the ADC_InitStruct and initializes the ADC MSP. - * - * @note This function is used to configure the global features of the ADC ( - * ClockPrescaler, Resolution, Data Alignment and number of conversion), however, - * the rest of the configuration parameters are specific to the regular - * channels group (scan mode activation, continuous mode activation, - * External trigger source and edge, DMA continuous request after the - * last transfer and End of conversion selection). - * - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef* hadc) -{ - HAL_StatusTypeDef tmp_hal_status = HAL_OK; - - /* Check ADC handle */ - if(hadc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - assert_param(IS_ADC_CLOCKPRESCALER(hadc->Init.ClockPrescaler)); - assert_param(IS_ADC_RESOLUTION(hadc->Init.Resolution)); - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ScanConvMode)); - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); - assert_param(IS_ADC_EXT_TRIG(hadc->Init.ExternalTrigConv)); - assert_param(IS_ADC_DATA_ALIGN(hadc->Init.DataAlign)); - assert_param(IS_ADC_REGULAR_LENGTH(hadc->Init.NbrOfConversion)); - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DMAContinuousRequests)); - assert_param(IS_ADC_EOCSelection(hadc->Init.EOCSelection)); - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DiscontinuousConvMode)); - - if(hadc->Init.ExternalTrigConv != ADC_SOFTWARE_START) - { - assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); - } - - if(hadc->State == HAL_ADC_STATE_RESET) - { -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - /* Init the ADC Callback settings */ - hadc->ConvCpltCallback = HAL_ADC_ConvCpltCallback; /* Legacy weak callback */ - hadc->ConvHalfCpltCallback = HAL_ADC_ConvHalfCpltCallback; /* Legacy weak callback */ - hadc->LevelOutOfWindowCallback = HAL_ADC_LevelOutOfWindowCallback; /* Legacy weak callback */ - hadc->ErrorCallback = HAL_ADC_ErrorCallback; /* Legacy weak callback */ - hadc->InjectedConvCpltCallback = HAL_ADCEx_InjectedConvCpltCallback; /* Legacy weak callback */ - if (hadc->MspInitCallback == NULL) - { - hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware */ - hadc->MspInitCallback(hadc); -#else - /* Init the low level hardware */ - HAL_ADC_MspInit(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - - /* Initialize ADC error code */ - ADC_CLEAR_ERRORCODE(hadc); - - /* Allocate lock resource and initialize it */ - hadc->Lock = HAL_UNLOCKED; - } - - /* Configuration of ADC parameters if previous preliminary actions are */ - /* correctly completed. */ - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) - { - /* Set ADC state */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, - HAL_ADC_STATE_BUSY_INTERNAL); - - /* Set ADC parameters */ - ADC_Init(hadc); - - /* Set ADC error code to none */ - ADC_CLEAR_ERRORCODE(hadc); - - /* Set the ADC state */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_BUSY_INTERNAL, - HAL_ADC_STATE_READY); - } - else - { - tmp_hal_status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return tmp_hal_status; -} - -/** - * @brief Deinitializes the ADCx peripheral registers to their default reset values. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef* hadc) -{ - HAL_StatusTypeDef tmp_hal_status = HAL_OK; - - /* Check ADC handle */ - if(hadc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - - /* Set ADC state */ - SET_BIT(hadc->State, HAL_ADC_STATE_BUSY_INTERNAL); - - /* Stop potential conversion on going, on regular and injected groups */ - /* Disable ADC peripheral */ - __HAL_ADC_DISABLE(hadc); - - /* Configuration of ADC parameters if previous preliminary actions are */ - /* correctly completed. */ - if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) - { -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - if (hadc->MspDeInitCallback == NULL) - { - hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: RCC clock, NVIC */ - hadc->MspDeInitCallback(hadc); -#else - /* DeInit the low level hardware: RCC clock, NVIC */ - HAL_ADC_MspDeInit(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - - /* Set ADC error code to none */ - ADC_CLEAR_ERRORCODE(hadc); - - /* Set ADC state */ - hadc->State = HAL_ADC_STATE_RESET; - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return tmp_hal_status; -} - -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User ADC Callback - * To be used instead of the weak predefined callback - * @param hadc Pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID - * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID - * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID - * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID - * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID - * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID - * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_RegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID, pADC_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - if ((hadc->State & HAL_ADC_STATE_READY) != 0UL) - { - switch (CallbackID) - { - case HAL_ADC_CONVERSION_COMPLETE_CB_ID : - hadc->ConvCpltCallback = pCallback; - break; - - case HAL_ADC_CONVERSION_HALF_CB_ID : - hadc->ConvHalfCpltCallback = pCallback; - break; - - case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID : - hadc->LevelOutOfWindowCallback = pCallback; - break; - - case HAL_ADC_ERROR_CB_ID : - hadc->ErrorCallback = pCallback; - break; - - case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID : - hadc->InjectedConvCpltCallback = pCallback; - break; - - case HAL_ADC_MSPINIT_CB_ID : - hadc->MspInitCallback = pCallback; - break; - - case HAL_ADC_MSPDEINIT_CB_ID : - hadc->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_ADC_STATE_RESET == hadc->State) - { - switch (CallbackID) - { - case HAL_ADC_MSPINIT_CB_ID : - hadc->MspInitCallback = pCallback; - break; - - case HAL_ADC_MSPDEINIT_CB_ID : - hadc->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - return status; -} - -/** - * @brief Unregister a ADC Callback - * ADC callback is redirected to the weak predefined callback - * @param hadc Pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID - * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID - * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID - * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID - * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID - * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID - * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - if ((hadc->State & HAL_ADC_STATE_READY) != 0UL) - { - switch (CallbackID) - { - case HAL_ADC_CONVERSION_COMPLETE_CB_ID : - hadc->ConvCpltCallback = HAL_ADC_ConvCpltCallback; - break; - - case HAL_ADC_CONVERSION_HALF_CB_ID : - hadc->ConvHalfCpltCallback = HAL_ADC_ConvHalfCpltCallback; - break; - - case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID : - hadc->LevelOutOfWindowCallback = HAL_ADC_LevelOutOfWindowCallback; - break; - - case HAL_ADC_ERROR_CB_ID : - hadc->ErrorCallback = HAL_ADC_ErrorCallback; - break; - - case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID : - hadc->InjectedConvCpltCallback = HAL_ADCEx_InjectedConvCpltCallback; - break; - - case HAL_ADC_MSPINIT_CB_ID : - hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_ADC_MSPDEINIT_CB_ID : - hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_ADC_STATE_RESET == hadc->State) - { - switch (CallbackID) - { - case HAL_ADC_MSPINIT_CB_ID : - hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_ADC_MSPDEINIT_CB_ID : - hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - return status; -} - -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - -/** - * @brief Initializes the ADC MSP. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -__weak void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hadc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ADC_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes the ADC MSP. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -__weak void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hadc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ADC_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup ADC_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Start conversion of regular channel. - (+) Stop conversion of regular channel. - (+) Start conversion of regular channel and enable interrupt. - (+) Stop conversion of regular channel and disable interrupt. - (+) Start conversion of regular channel and enable DMA transfer. - (+) Stop conversion of regular channel and disable DMA transfer. - (+) Handle ADC interrupt request. - -@endverbatim - * @{ - */ - -/** - * @brief Enables ADC and starts conversion of the regular channels. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef* hadc) -{ - __IO uint32_t counter = 0U; - ADC_Common_TypeDef *tmpADC_Common; - - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); - assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Enable the ADC peripheral */ - /* Check if ADC peripheral is disabled in order to enable it and wait during - Tstab time the ADC's stabilization */ - if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) - { - /* Enable the Peripheral */ - __HAL_ADC_ENABLE(hadc); - - /* Delay for ADC stabilization time */ - /* Compute number of CPU cycles to wait for */ - counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); - while(counter != 0U) - { - counter--; - } - } - - /* Start conversion if ADC is effectively enabled */ - if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Set ADC state */ - /* - Clear state bitfield related to regular group conversion results */ - /* - Set state bitfield related to regular group operation */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, - HAL_ADC_STATE_REG_BUSY); - - /* If conversions on group regular are also triggering group injected, */ - /* update ADC state. */ - if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) - { - ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); - } - - /* State machine update: Check if an injected conversion is ongoing */ - if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) - { - /* Reset ADC error code fields related to conversions on group regular */ - CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); - } - else - { - /* Reset ADC all error code fields */ - ADC_CLEAR_ERRORCODE(hadc); - } - - /* Process unlocked */ - /* Unlock before starting ADC conversions: in case of potential */ - /* interruption, to let the process to ADC IRQ Handler. */ - __HAL_UNLOCK(hadc); - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Clear regular group conversion flag and overrun flag */ - /* (To ensure of no unknown state from potential previous ADC operations) */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); - - /* Check if Multimode enabled */ - if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) - { -#if defined(ADC2) && defined(ADC3) - if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ - || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) - { -#endif /* ADC2 || ADC3 */ - /* if no external trigger present enable software conversion of regular channels */ - if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) - { - /* Enable the selected ADC software conversion for regular group */ - hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; - } -#if defined(ADC2) && defined(ADC3) - } -#endif /* ADC2 || ADC3 */ - } - else - { - /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ - if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) - { - /* Enable the selected ADC software conversion for regular group */ - hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; - } - } - } - else - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); - - /* Set ADC error code to ADC IP internal error */ - SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Disables ADC and stop conversion of regular channels. - * - * @note Caution: This function will stop also injected channels. - * - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef* hadc) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Stop potential conversion on going, on regular and injected groups */ - /* Disable ADC peripheral */ - __HAL_ADC_DISABLE(hadc); - - /* Check if ADC is effectively disabled */ - if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Set ADC state */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, - HAL_ADC_STATE_READY); - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Poll for regular conversion complete - * @note ADC conversion flags EOS (end of sequence) and EOC (end of - * conversion) are cleared by this function. - * @note This function cannot be used in a particular setup: ADC configured - * in DMA mode and polling for end of each conversion (ADC init - * parameter "EOCSelection" set to ADC_EOC_SINGLE_CONV). - * In this case, DMA resets the flag EOC and polling cannot be - * performed on each conversion. Nevertheless, polling can still - * be performed on the complete sequence. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param Timeout Timeout value in millisecond. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Verification that ADC configuration is compliant with polling for */ - /* each conversion: */ - /* Particular case is ADC configured in DMA mode and ADC sequencer with */ - /* several ranks and polling for end of each conversion. */ - /* For code simplicity sake, this particular case is generalized to */ - /* ADC configured in DMA mode and polling for end of each conversion. */ - if (HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_EOCS) && - HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_DMA) ) - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - return HAL_ERROR; - } - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check End of conversion flag */ - while(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOC))) - { - /* Check if timeout is disabled (set to infinite wait) */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U) || ((HAL_GetTick() - tickstart ) > Timeout)) - { - /* New check to avoid false timeout detection in case of preemption */ - if(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOC))) - { - /* Update ADC state machine to timeout */ - SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT); - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - return HAL_TIMEOUT; - } - } - } - } - - /* Clear regular group conversion flag */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_STRT | ADC_FLAG_EOC); - - /* Update ADC state machine */ - SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); - - /* Determine whether any further conversion upcoming on group regular */ - /* by external trigger, continuous mode or scan sequence on going. */ - /* Note: On STM32F4, there is no independent flag of end of sequence. */ - /* The test of scan sequence on going is done either with scan */ - /* sequence disabled or with end of conversion flag set to */ - /* of end of sequence. */ - if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && - (hadc->Init.ContinuousConvMode == DISABLE) && - (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || - HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) - { - /* Set ADC state */ - CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); - - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) - { - SET_BIT(hadc->State, HAL_ADC_STATE_READY); - } - } - - /* Return ADC state */ - return HAL_OK; -} - -/** - * @brief Poll for conversion event - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param EventType the ADC event type. - * This parameter can be one of the following values: - * @arg ADC_AWD_EVENT: ADC Analog watch Dog event. - * @arg ADC_OVR_EVENT: ADC Overrun event. - * @param Timeout Timeout value in millisecond. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef* hadc, uint32_t EventType, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - assert_param(IS_ADC_EVENT_TYPE(EventType)); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check selected event flag */ - while(!(__HAL_ADC_GET_FLAG(hadc,EventType))) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U) || ((HAL_GetTick() - tickstart ) > Timeout)) - { - /* New check to avoid false timeout detection in case of preemption */ - if(!(__HAL_ADC_GET_FLAG(hadc,EventType))) - { - /* Update ADC state machine to timeout */ - SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT); - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - return HAL_TIMEOUT; - } - } - } - } - - /* Analog watchdog (level out of window) event */ - if(EventType == ADC_AWD_EVENT) - { - /* Set ADC state */ - SET_BIT(hadc->State, HAL_ADC_STATE_AWD1); - - /* Clear ADC analog watchdog flag */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD); - } - /* Overrun event */ - else - { - /* Set ADC state */ - SET_BIT(hadc->State, HAL_ADC_STATE_REG_OVR); - /* Set ADC error code to overrun */ - SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_OVR); - - /* Clear ADC overrun flag */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); - } - - /* Return ADC state */ - return HAL_OK; -} - - -/** - * @brief Enables the interrupt and starts ADC conversion of regular channels. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef* hadc) -{ - __IO uint32_t counter = 0U; - ADC_Common_TypeDef *tmpADC_Common; - - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); - assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Enable the ADC peripheral */ - /* Check if ADC peripheral is disabled in order to enable it and wait during - Tstab time the ADC's stabilization */ - if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) - { - /* Enable the Peripheral */ - __HAL_ADC_ENABLE(hadc); - - /* Delay for ADC stabilization time */ - /* Compute number of CPU cycles to wait for */ - counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); - while(counter != 0U) - { - counter--; - } - } - - /* Start conversion if ADC is effectively enabled */ - if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Set ADC state */ - /* - Clear state bitfield related to regular group conversion results */ - /* - Set state bitfield related to regular group operation */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, - HAL_ADC_STATE_REG_BUSY); - - /* If conversions on group regular are also triggering group injected, */ - /* update ADC state. */ - if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) - { - ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); - } - - /* State machine update: Check if an injected conversion is ongoing */ - if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) - { - /* Reset ADC error code fields related to conversions on group regular */ - CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); - } - else - { - /* Reset ADC all error code fields */ - ADC_CLEAR_ERRORCODE(hadc); - } - - /* Process unlocked */ - /* Unlock before starting ADC conversions: in case of potential */ - /* interruption, to let the process to ADC IRQ Handler. */ - __HAL_UNLOCK(hadc); - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Clear regular group conversion flag and overrun flag */ - /* (To ensure of no unknown state from potential previous ADC operations) */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); - - /* Enable end of conversion interrupt for regular group */ - __HAL_ADC_ENABLE_IT(hadc, (ADC_IT_EOC | ADC_IT_OVR)); - - /* Check if Multimode enabled */ - if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) - { -#if defined(ADC2) && defined(ADC3) - if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ - || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) - { -#endif /* ADC2 || ADC3 */ - /* if no external trigger present enable software conversion of regular channels */ - if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) - { - /* Enable the selected ADC software conversion for regular group */ - hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; - } -#if defined(ADC2) && defined(ADC3) - } -#endif /* ADC2 || ADC3 */ - } - else - { - /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ - if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) - { - /* Enable the selected ADC software conversion for regular group */ - hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; - } - } - } - else - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); - - /* Set ADC error code to ADC IP internal error */ - SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Disables the interrupt and stop ADC conversion of regular channels. - * - * @note Caution: This function will stop also injected channels. - * - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef* hadc) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Stop potential conversion on going, on regular and injected groups */ - /* Disable ADC peripheral */ - __HAL_ADC_DISABLE(hadc); - - /* Check if ADC is effectively disabled */ - if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Disable ADC end of conversion interrupt for regular group */ - __HAL_ADC_DISABLE_IT(hadc, (ADC_IT_EOC | ADC_IT_OVR)); - - /* Set ADC state */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, - HAL_ADC_STATE_READY); - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Handles ADC interrupt request - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -void HAL_ADC_IRQHandler(ADC_HandleTypeDef* hadc) -{ - uint32_t tmp1 = 0U, tmp2 = 0U; - - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); - assert_param(IS_ADC_REGULAR_LENGTH(hadc->Init.NbrOfConversion)); - assert_param(IS_ADC_EOCSelection(hadc->Init.EOCSelection)); - - tmp1 = __HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOC); - tmp2 = __HAL_ADC_GET_IT_SOURCE(hadc, ADC_IT_EOC); - /* Check End of conversion flag for regular channels */ - if(tmp1 && tmp2) - { - /* Update state machine on conversion status if not in error state */ - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) - { - /* Set ADC state */ - SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); - } - - /* Determine whether any further conversion upcoming on group regular */ - /* by external trigger, continuous mode or scan sequence on going. */ - /* Note: On STM32F4, there is no independent flag of end of sequence. */ - /* The test of scan sequence on going is done either with scan */ - /* sequence disabled or with end of conversion flag set to */ - /* of end of sequence. */ - if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && - (hadc->Init.ContinuousConvMode == DISABLE) && - (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || - HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) - { - /* Disable ADC end of single conversion interrupt on group regular */ - /* Note: Overrun interrupt was enabled with EOC interrupt in */ - /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ - /* by overrun IRQ process below. */ - __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); - - /* Set ADC state */ - CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); - - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) - { - SET_BIT(hadc->State, HAL_ADC_STATE_READY); - } - } - - /* Conversion complete callback */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - hadc->ConvCpltCallback(hadc); -#else - HAL_ADC_ConvCpltCallback(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - - /* Clear regular group conversion flag */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_STRT | ADC_FLAG_EOC); - } - - tmp1 = __HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOC); - tmp2 = __HAL_ADC_GET_IT_SOURCE(hadc, ADC_IT_JEOC); - /* Check End of conversion flag for injected channels */ - if(tmp1 && tmp2) - { - /* Update state machine on conversion status if not in error state */ - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL)) - { - /* Set ADC state */ - SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC); - } - - /* Determine whether any further conversion upcoming on group injected */ - /* by external trigger, scan sequence on going or by automatic injected */ - /* conversion from group regular (same conditions as group regular */ - /* interruption disabling above). */ - if(ADC_IS_SOFTWARE_START_INJECTED(hadc) && - (HAL_IS_BIT_CLR(hadc->Instance->JSQR, ADC_JSQR_JL) || - HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) && - (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) && - (ADC_IS_SOFTWARE_START_REGULAR(hadc) && - (hadc->Init.ContinuousConvMode == DISABLE) ) ) ) - { - /* Disable ADC end of single conversion interrupt on group injected */ - __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC); - - /* Set ADC state */ - CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY); - - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) - { - SET_BIT(hadc->State, HAL_ADC_STATE_READY); - } - } - - /* Conversion complete callback */ - /* Conversion complete callback */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - hadc->InjectedConvCpltCallback(hadc); -#else - HAL_ADCEx_InjectedConvCpltCallback(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - - /* Clear injected group conversion flag */ - __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_JSTRT | ADC_FLAG_JEOC)); - } - - tmp1 = __HAL_ADC_GET_FLAG(hadc, ADC_FLAG_AWD); - tmp2 = __HAL_ADC_GET_IT_SOURCE(hadc, ADC_IT_AWD); - /* Check Analog watchdog flag */ - if(tmp1 && tmp2) - { - if(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_AWD)) - { - /* Set ADC state */ - SET_BIT(hadc->State, HAL_ADC_STATE_AWD1); - - /* Level out of window callback */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - hadc->LevelOutOfWindowCallback(hadc); -#else - HAL_ADC_LevelOutOfWindowCallback(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - - /* Clear the ADC analog watchdog flag */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD); - } - } - - tmp1 = __HAL_ADC_GET_FLAG(hadc, ADC_FLAG_OVR); - tmp2 = __HAL_ADC_GET_IT_SOURCE(hadc, ADC_IT_OVR); - /* Check Overrun flag */ - if(tmp1 && tmp2) - { - /* Note: On STM32F4, ADC overrun can be set through other parameters */ - /* refer to description of parameter "EOCSelection" for more */ - /* details. */ - - /* Set ADC error code to overrun */ - SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_OVR); - - /* Clear ADC overrun flag */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); - - /* Error callback */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - hadc->ErrorCallback(hadc); -#else - HAL_ADC_ErrorCallback(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - - /* Clear the Overrun flag */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR); - } -} - -/** - * @brief Enables ADC DMA request after last transfer (Single-ADC mode) and enables ADC peripheral - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param pData The destination Buffer address. - * @param Length The length of data to be transferred from ADC peripheral to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length) -{ - __IO uint32_t counter = 0U; - ADC_Common_TypeDef *tmpADC_Common; - - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); - assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Enable the ADC peripheral */ - /* Check if ADC peripheral is disabled in order to enable it and wait during - Tstab time the ADC's stabilization */ - if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) - { - /* Enable the Peripheral */ - __HAL_ADC_ENABLE(hadc); - - /* Delay for ADC stabilization time */ - /* Compute number of CPU cycles to wait for */ - counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); - while(counter != 0U) - { - counter--; - } - } - - /* Check ADC DMA Mode */ - /* - disable the DMA Mode if it is already enabled */ - if((hadc->Instance->CR2 & ADC_CR2_DMA) == ADC_CR2_DMA) - { - CLEAR_BIT(hadc->Instance->CR2, ADC_CR2_DMA); - } - - /* Start conversion if ADC is effectively enabled */ - if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Set ADC state */ - /* - Clear state bitfield related to regular group conversion results */ - /* - Set state bitfield related to regular group operation */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, - HAL_ADC_STATE_REG_BUSY); - - /* If conversions on group regular are also triggering group injected, */ - /* update ADC state. */ - if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) - { - ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); - } - - /* State machine update: Check if an injected conversion is ongoing */ - if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) - { - /* Reset ADC error code fields related to conversions on group regular */ - CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); - } - else - { - /* Reset ADC all error code fields */ - ADC_CLEAR_ERRORCODE(hadc); - } - - /* Process unlocked */ - /* Unlock before starting ADC conversions: in case of potential */ - /* interruption, to let the process to ADC IRQ Handler. */ - __HAL_UNLOCK(hadc); - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Set the DMA transfer complete callback */ - hadc->DMA_Handle->XferCpltCallback = ADC_DMAConvCplt; - - /* Set the DMA half transfer complete callback */ - hadc->DMA_Handle->XferHalfCpltCallback = ADC_DMAHalfConvCplt; - - /* Set the DMA error callback */ - hadc->DMA_Handle->XferErrorCallback = ADC_DMAError; - - - /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */ - /* start (in case of SW start): */ - - /* Clear regular group conversion flag and overrun flag */ - /* (To ensure of no unknown state from potential previous ADC operations) */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC | ADC_FLAG_OVR); - - /* Enable ADC overrun interrupt */ - __HAL_ADC_ENABLE_IT(hadc, ADC_IT_OVR); - - /* Enable ADC DMA mode */ - hadc->Instance->CR2 |= ADC_CR2_DMA; - - /* Start the DMA channel */ - HAL_DMA_Start_IT(hadc->DMA_Handle, (uint32_t)&hadc->Instance->DR, (uint32_t)pData, Length); - - /* Check if Multimode enabled */ - if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) - { -#if defined(ADC2) && defined(ADC3) - if((hadc->Instance == ADC1) || ((hadc->Instance == ADC2) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_0)) \ - || ((hadc->Instance == ADC3) && ((ADC->CCR & ADC_CCR_MULTI_Msk) < ADC_CCR_MULTI_4))) - { -#endif /* ADC2 || ADC3 */ - /* if no external trigger present enable software conversion of regular channels */ - if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) - { - /* Enable the selected ADC software conversion for regular group */ - hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; - } -#if defined(ADC2) && defined(ADC3) - } -#endif /* ADC2 || ADC3 */ - } - else - { - /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */ - if((hadc->Instance == ADC1) && ((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET)) - { - /* Enable the selected ADC software conversion for regular group */ - hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; - } - } - } - else - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); - - /* Set ADC error code to ADC IP internal error */ - SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Disables ADC DMA (Single-ADC mode) and disables ADC peripheral - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef* hadc) -{ - HAL_StatusTypeDef tmp_hal_status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Stop potential conversion on going, on regular and injected groups */ - /* Disable ADC peripheral */ - __HAL_ADC_DISABLE(hadc); - - /* Check if ADC is effectively disabled */ - if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Disable the selected ADC DMA mode */ - hadc->Instance->CR2 &= ~ADC_CR2_DMA; - - /* Disable the DMA channel (in case of DMA in circular mode or stop while */ - /* DMA transfer is on going) */ - if (hadc->DMA_Handle->State == HAL_DMA_STATE_BUSY) - { - tmp_hal_status = HAL_DMA_Abort(hadc->DMA_Handle); - - /* Check if DMA channel effectively disabled */ - if (tmp_hal_status != HAL_OK) - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_DMA); - } - } - - /* Disable ADC overrun interrupt */ - __HAL_ADC_DISABLE_IT(hadc, ADC_IT_OVR); - - /* Set ADC state */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, - HAL_ADC_STATE_READY); - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return tmp_hal_status; -} - -/** - * @brief Gets the converted value from data register of regular channel. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval Converted value - */ -uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef* hadc) -{ - /* Return the selected ADC converted value */ - return hadc->Instance->DR; -} - -/** - * @brief Regular conversion complete callback in non blocking mode - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -__weak void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hadc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ADC_ConvCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Regular conversion half DMA transfer callback in non blocking mode - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -__weak void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hadc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ADC_ConvHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Analog watchdog callback in non blocking mode - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -__weak void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef* hadc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hadc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ADC_LevelOoutOfWindowCallback could be implemented in the user file - */ -} - -/** - * @brief Error ADC callback. - * @note In case of error due to overrun when using ADC with DMA transfer - * (HAL ADC handle paramater "ErrorCode" to state "HAL_ADC_ERROR_OVR"): - * - Reinitialize the DMA using function "HAL_ADC_Stop_DMA()". - * - If needed, restart a new ADC conversion using function - * "HAL_ADC_Start_DMA()" - * (this function is also clearing overrun flag) - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -__weak void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hadc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ADC_ErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure regular channels. - (+) Configure injected channels. - (+) Configure multimode. - (+) Configure the analog watch dog. - -@endverbatim - * @{ - */ - - /** - * @brief Configures for the selected ADC regular channel its corresponding - * rank in the sequencer and its sample time. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param sConfig ADC configuration structure. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef* hadc, ADC_ChannelConfTypeDef* sConfig) -{ - __IO uint32_t counter = 0U; - ADC_Common_TypeDef *tmpADC_Common; - - /* Check the parameters */ - assert_param(IS_ADC_CHANNEL(sConfig->Channel)); - assert_param(IS_ADC_REGULAR_RANK(sConfig->Rank)); - assert_param(IS_ADC_SAMPLE_TIME(sConfig->SamplingTime)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ - if (sConfig->Channel > ADC_CHANNEL_9) - { - /* Clear the old sample time */ - hadc->Instance->SMPR1 &= ~ADC_SMPR1(ADC_SMPR1_SMP10, sConfig->Channel); - - /* Set the new sample time */ - hadc->Instance->SMPR1 |= ADC_SMPR1(sConfig->SamplingTime, sConfig->Channel); - } - else /* ADC_Channel include in ADC_Channel_[0..9] */ - { - /* Clear the old sample time */ - hadc->Instance->SMPR2 &= ~ADC_SMPR2(ADC_SMPR2_SMP0, sConfig->Channel); - - /* Set the new sample time */ - hadc->Instance->SMPR2 |= ADC_SMPR2(sConfig->SamplingTime, sConfig->Channel); - } - - /* For Rank 1 to 6 */ - if (sConfig->Rank < 7U) - { - /* Clear the old SQx bits for the selected rank */ - hadc->Instance->SQR3 &= ~ADC_SQR3_RK(ADC_SQR3_SQ1, sConfig->Rank); - - /* Set the SQx bits for the selected rank */ - hadc->Instance->SQR3 |= ADC_SQR3_RK(sConfig->Channel, sConfig->Rank); - } - /* For Rank 7 to 12 */ - else if (sConfig->Rank < 13U) - { - /* Clear the old SQx bits for the selected rank */ - hadc->Instance->SQR2 &= ~ADC_SQR2_RK(ADC_SQR2_SQ7, sConfig->Rank); - - /* Set the SQx bits for the selected rank */ - hadc->Instance->SQR2 |= ADC_SQR2_RK(sConfig->Channel, sConfig->Rank); - } - /* For Rank 13 to 16 */ - else - { - /* Clear the old SQx bits for the selected rank */ - hadc->Instance->SQR1 &= ~ADC_SQR1_RK(ADC_SQR1_SQ13, sConfig->Rank); - - /* Set the SQx bits for the selected rank */ - hadc->Instance->SQR1 |= ADC_SQR1_RK(sConfig->Channel, sConfig->Rank); - } - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* if ADC1 Channel_18 is selected for VBAT Channel ennable VBATE */ - if ((hadc->Instance == ADC1) && (sConfig->Channel == ADC_CHANNEL_VBAT)) - { - /* Disable the TEMPSENSOR channel in case of using board with multiplixed ADC_CHANNEL_VBAT & ADC_CHANNEL_TEMPSENSOR*/ - if ((uint16_t)ADC_CHANNEL_TEMPSENSOR == (uint16_t)ADC_CHANNEL_VBAT) - { - tmpADC_Common->CCR &= ~ADC_CCR_TSVREFE; - } - /* Enable the VBAT channel*/ - tmpADC_Common->CCR |= ADC_CCR_VBATE; - } - - /* if ADC1 Channel_16 or Channel_18 is selected for Temperature sensor or - Channel_17 is selected for VREFINT enable TSVREFE */ - if ((hadc->Instance == ADC1) && ((sConfig->Channel == ADC_CHANNEL_TEMPSENSOR) || (sConfig->Channel == ADC_CHANNEL_VREFINT))) - { - /* Disable the VBAT channel in case of using board with multiplixed ADC_CHANNEL_VBAT & ADC_CHANNEL_TEMPSENSOR*/ - if ((uint16_t)ADC_CHANNEL_TEMPSENSOR == (uint16_t)ADC_CHANNEL_VBAT) - { - tmpADC_Common->CCR &= ~ADC_CCR_VBATE; - } - /* Enable the Temperature sensor and VREFINT channel*/ - tmpADC_Common->CCR |= ADC_CCR_TSVREFE; - - if(sConfig->Channel == ADC_CHANNEL_TEMPSENSOR) - { - /* Delay for temperature sensor stabilization time */ - /* Compute number of CPU cycles to wait for */ - counter = (ADC_TEMPSENSOR_DELAY_US * (SystemCoreClock / 1000000U)); - while(counter != 0U) - { - counter--; - } - } - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Configures the analog watchdog. - * @note Analog watchdog thresholds can be modified while ADC conversion - * is on going. - * In this case, some constraints must be taken into account: - * The programmed threshold values are effective from the next - * ADC EOC (end of unitary conversion). - * Considering that registers write delay may happen due to - * bus activity, this might cause an uncertainty on the - * effective timing of the new programmed threshold values. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param AnalogWDGConfig pointer to an ADC_AnalogWDGConfTypeDef structure - * that contains the configuration information of ADC analog watchdog. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef* hadc, ADC_AnalogWDGConfTypeDef* AnalogWDGConfig) -{ -#ifdef USE_FULL_ASSERT - uint32_t tmp = 0U; -#endif /* USE_FULL_ASSERT */ - - /* Check the parameters */ - assert_param(IS_ADC_ANALOG_WATCHDOG(AnalogWDGConfig->WatchdogMode)); - assert_param(IS_ADC_CHANNEL(AnalogWDGConfig->Channel)); - assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig->ITMode)); - -#ifdef USE_FULL_ASSERT - tmp = ADC_GET_RESOLUTION(hadc); - assert_param(IS_ADC_RANGE(tmp, AnalogWDGConfig->HighThreshold)); - assert_param(IS_ADC_RANGE(tmp, AnalogWDGConfig->LowThreshold)); -#endif /* USE_FULL_ASSERT */ - - /* Process locked */ - __HAL_LOCK(hadc); - - if(AnalogWDGConfig->ITMode == ENABLE) - { - /* Enable the ADC Analog watchdog interrupt */ - __HAL_ADC_ENABLE_IT(hadc, ADC_IT_AWD); - } - else - { - /* Disable the ADC Analog watchdog interrupt */ - __HAL_ADC_DISABLE_IT(hadc, ADC_IT_AWD); - } - - /* Clear AWDEN, JAWDEN and AWDSGL bits */ - hadc->Instance->CR1 &= ~(ADC_CR1_AWDSGL | ADC_CR1_JAWDEN | ADC_CR1_AWDEN); - - /* Set the analog watchdog enable mode */ - hadc->Instance->CR1 |= AnalogWDGConfig->WatchdogMode; - - /* Set the high threshold */ - hadc->Instance->HTR = AnalogWDGConfig->HighThreshold; - - /* Set the low threshold */ - hadc->Instance->LTR = AnalogWDGConfig->LowThreshold; - - /* Clear the Analog watchdog channel select bits */ - hadc->Instance->CR1 &= ~ADC_CR1_AWDCH; - - /* Set the Analog watchdog channel */ - hadc->Instance->CR1 |= (uint32_t)((uint16_t)(AnalogWDGConfig->Channel)); - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup ADC_Exported_Functions_Group4 ADC Peripheral State functions - * @brief ADC Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State and errors functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Check the ADC state - (+) Check the ADC Error - -@endverbatim - * @{ - */ - -/** - * @brief return the ADC state - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL state - */ -uint32_t HAL_ADC_GetState(ADC_HandleTypeDef* hadc) -{ - /* Return ADC state */ - return hadc->State; -} - -/** - * @brief Return the ADC error code - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval ADC Error Code - */ -uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc) -{ - return hadc->ErrorCode; -} - -/** - * @} - */ - -/** @addtogroup ADC_Private_Functions - * @{ - */ - -/** - * @brief Initializes the ADCx peripheral according to the specified parameters - * in the ADC_InitStruct without initializing the ADC MSP. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -static void ADC_Init(ADC_HandleTypeDef* hadc) -{ - ADC_Common_TypeDef *tmpADC_Common; - - /* Set ADC parameters */ - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Set the ADC clock prescaler */ - tmpADC_Common->CCR &= ~(ADC_CCR_ADCPRE); - tmpADC_Common->CCR |= hadc->Init.ClockPrescaler; - - /* Set ADC scan mode */ - hadc->Instance->CR1 &= ~(ADC_CR1_SCAN); - hadc->Instance->CR1 |= ADC_CR1_SCANCONV(hadc->Init.ScanConvMode); - - /* Set ADC resolution */ - hadc->Instance->CR1 &= ~(ADC_CR1_RES); - hadc->Instance->CR1 |= hadc->Init.Resolution; - - /* Set ADC data alignment */ - hadc->Instance->CR2 &= ~(ADC_CR2_ALIGN); - hadc->Instance->CR2 |= hadc->Init.DataAlign; - - /* Enable external trigger if trigger selection is different of software */ - /* start. */ - /* Note: This configuration keeps the hardware feature of parameter */ - /* ExternalTrigConvEdge "trigger edge none" equivalent to */ - /* software start. */ - if(hadc->Init.ExternalTrigConv != ADC_SOFTWARE_START) - { - /* Select external trigger to start conversion */ - hadc->Instance->CR2 &= ~(ADC_CR2_EXTSEL); - hadc->Instance->CR2 |= hadc->Init.ExternalTrigConv; - - /* Select external trigger polarity */ - hadc->Instance->CR2 &= ~(ADC_CR2_EXTEN); - hadc->Instance->CR2 |= hadc->Init.ExternalTrigConvEdge; - } - else - { - /* Reset the external trigger */ - hadc->Instance->CR2 &= ~(ADC_CR2_EXTSEL); - hadc->Instance->CR2 &= ~(ADC_CR2_EXTEN); - } - - /* Enable or disable ADC continuous conversion mode */ - hadc->Instance->CR2 &= ~(ADC_CR2_CONT); - hadc->Instance->CR2 |= ADC_CR2_CONTINUOUS((uint32_t)hadc->Init.ContinuousConvMode); - - if(hadc->Init.DiscontinuousConvMode != DISABLE) - { - assert_param(IS_ADC_REGULAR_DISC_NUMBER(hadc->Init.NbrOfDiscConversion)); - - /* Enable the selected ADC regular discontinuous mode */ - hadc->Instance->CR1 |= (uint32_t)ADC_CR1_DISCEN; - - /* Set the number of channels to be converted in discontinuous mode */ - hadc->Instance->CR1 &= ~(ADC_CR1_DISCNUM); - hadc->Instance->CR1 |= ADC_CR1_DISCONTINUOUS(hadc->Init.NbrOfDiscConversion); - } - else - { - /* Disable the selected ADC regular discontinuous mode */ - hadc->Instance->CR1 &= ~(ADC_CR1_DISCEN); - } - - /* Set ADC number of conversion */ - hadc->Instance->SQR1 &= ~(ADC_SQR1_L); - hadc->Instance->SQR1 |= ADC_SQR1(hadc->Init.NbrOfConversion); - - /* Enable or disable ADC DMA continuous request */ - hadc->Instance->CR2 &= ~(ADC_CR2_DDS); - hadc->Instance->CR2 |= ADC_CR2_DMAContReq((uint32_t)hadc->Init.DMAContinuousRequests); - - /* Enable or disable ADC end of conversion selection */ - hadc->Instance->CR2 &= ~(ADC_CR2_EOCS); - hadc->Instance->CR2 |= ADC_CR2_EOCSelection(hadc->Init.EOCSelection); -} - -/** - * @brief DMA transfer complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void ADC_DMAConvCplt(DMA_HandleTypeDef *hdma) -{ - /* Retrieve ADC handle corresponding to current DMA handle */ - ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - /* Update state machine on conversion status if not in error state */ - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL | HAL_ADC_STATE_ERROR_DMA)) - { - /* Update ADC state machine */ - SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); - - /* Determine whether any further conversion upcoming on group regular */ - /* by external trigger, continuous mode or scan sequence on going. */ - /* Note: On STM32F4, there is no independent flag of end of sequence. */ - /* The test of scan sequence on going is done either with scan */ - /* sequence disabled or with end of conversion flag set to */ - /* of end of sequence. */ - if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && - (hadc->Init.ContinuousConvMode == DISABLE) && - (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || - HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) - { - /* Disable ADC end of single conversion interrupt on group regular */ - /* Note: Overrun interrupt was enabled with EOC interrupt in */ - /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ - /* by overrun IRQ process below. */ - __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); - - /* Set ADC state */ - CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); - - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) - { - SET_BIT(hadc->State, HAL_ADC_STATE_READY); - } - } - - /* Conversion complete callback */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - hadc->ConvCpltCallback(hadc); -#else - HAL_ADC_ConvCpltCallback(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - } - else /* DMA and-or internal error occurred */ - { - if ((hadc->State & HAL_ADC_STATE_ERROR_INTERNAL) != 0UL) - { - /* Call HAL ADC Error Callback function */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - hadc->ErrorCallback(hadc); -#else - HAL_ADC_ErrorCallback(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - } - else - { - /* Call DMA error callback */ - hadc->DMA_Handle->XferErrorCallback(hdma); - } - } -} - -/** - * @brief DMA half transfer complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef *hdma) -{ - ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - /* Half conversion callback */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - hadc->ConvHalfCpltCallback(hadc); -#else - HAL_ADC_ConvHalfCpltCallback(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA error callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void ADC_DMAError(DMA_HandleTypeDef *hdma) -{ - ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - hadc->State= HAL_ADC_STATE_ERROR_DMA; - /* Set ADC error code to DMA error */ - hadc->ErrorCode |= HAL_ADC_ERROR_DMA; - /* Error callback */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - hadc->ErrorCallback(hadc); -#else - HAL_ADC_ErrorCallback(hadc); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_ADC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c deleted file mode 100644 index 1b6ee8551b91cbc..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c +++ /dev/null @@ -1,1115 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_adc_ex.c - * @author MCD Application Team - * @brief This file provides firmware functions to manage the following - * functionalities of the ADC extension peripheral: - * + Extended features functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#)Initialize the ADC low level resources by implementing the HAL_ADC_MspInit(): - (##) Enable the ADC interface clock using __HAL_RCC_ADC_CLK_ENABLE() - (##) ADC pins configuration - (+++) Enable the clock for the ADC GPIOs using the following function: - __HAL_RCC_GPIOx_CLK_ENABLE() - (+++) Configure these ADC pins in analog mode using HAL_GPIO_Init() - (##) In case of using interrupts (e.g. HAL_ADC_Start_IT()) - (+++) Configure the ADC interrupt priority using HAL_NVIC_SetPriority() - (+++) Enable the ADC IRQ handler using HAL_NVIC_EnableIRQ() - (+++) In ADC IRQ handler, call HAL_ADC_IRQHandler() - (##) In case of using DMA to control data transfer (e.g. HAL_ADC_Start_DMA()) - (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE() - (+++) Configure and enable two DMA streams stream for managing data - transfer from peripheral to memory (output stream) - (+++) Associate the initialized DMA handle to the ADC DMA handle - using __HAL_LINKDMA() - (+++) Configure the priority and enable the NVIC for the transfer complete - interrupt on the two DMA Streams. The output stream should have higher - priority than the input stream. - (#) Configure the ADC Prescaler, conversion resolution and data alignment - using the HAL_ADC_Init() function. - - (#) Configure the ADC Injected channels group features, use HAL_ADC_Init() - and HAL_ADC_ConfigChannel() functions. - - (#) Three operation modes are available within this driver: - - *** Polling mode IO operation *** - ================================= - [..] - (+) Start the ADC peripheral using HAL_ADCEx_InjectedStart() - (+) Wait for end of conversion using HAL_ADC_PollForConversion(), at this stage - user can specify the value of timeout according to his end application - (+) To read the ADC converted values, use the HAL_ADCEx_InjectedGetValue() function. - (+) Stop the ADC peripheral using HAL_ADCEx_InjectedStop() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Start the ADC peripheral using HAL_ADCEx_InjectedStart_IT() - (+) Use HAL_ADC_IRQHandler() called under ADC_IRQHandler() Interrupt subroutine - (+) At ADC end of conversion HAL_ADCEx_InjectedConvCpltCallback() function is executed and user can - add his own code by customization of function pointer HAL_ADCEx_InjectedConvCpltCallback - (+) In case of ADC Error, HAL_ADCEx_InjectedErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_ADCEx_InjectedErrorCallback - (+) Stop the ADC peripheral using HAL_ADCEx_InjectedStop_IT() - - *** Multi mode ADCs Regular channels configuration *** - ====================================================== - [..] - (+) Select the Multi mode ADC regular channels features (dual or triple mode) - and configure the DMA mode using HAL_ADCEx_MultiModeConfigChannel() functions. - (+) Start the ADC peripheral using HAL_ADCEx_MultiModeStart_DMA(), at this stage the user specify the length - of data to be transferred at each end of conversion - (+) Read the ADCs converted values using the HAL_ADCEx_MultiModeGetValue() function. - - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup ADCEx ADCEx - * @brief ADC Extended driver modules - * @{ - */ - -#ifdef HAL_ADC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @addtogroup ADCEx_Private_Functions - * @{ - */ -/* Private function prototypes -----------------------------------------------*/ -static void ADC_MultiModeDMAConvCplt(DMA_HandleTypeDef *hdma); -static void ADC_MultiModeDMAError(DMA_HandleTypeDef *hdma); -static void ADC_MultiModeDMAHalfConvCplt(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup ADCEx_Exported_Functions ADC Exported Functions - * @{ - */ - -/** @defgroup ADCEx_Exported_Functions_Group1 Extended features functions - * @brief Extended features functions - * -@verbatim - =============================================================================== - ##### Extended features functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Start conversion of injected channel. - (+) Stop conversion of injected channel. - (+) Start multimode and enable DMA transfer. - (+) Stop multimode and disable DMA transfer. - (+) Get result of injected channel conversion. - (+) Get result of multimode conversion. - (+) Configure injected channels. - (+) Configure multimode. - -@endverbatim - * @{ - */ - -/** - * @brief Enables the selected ADC software start conversion of the injected channels. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc) -{ - __IO uint32_t counter = 0U; - uint32_t tmp1 = 0U, tmp2 = 0U; - ADC_Common_TypeDef *tmpADC_Common; - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Enable the ADC peripheral */ - - /* Check if ADC peripheral is disabled in order to enable it and wait during - Tstab time the ADC's stabilization */ - if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) - { - /* Enable the Peripheral */ - __HAL_ADC_ENABLE(hadc); - - /* Delay for ADC stabilization time */ - /* Compute number of CPU cycles to wait for */ - counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); - while(counter != 0U) - { - counter--; - } - } - - /* Start conversion if ADC is effectively enabled */ - if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Set ADC state */ - /* - Clear state bitfield related to injected group conversion results */ - /* - Set state bitfield related to injected operation */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC, - HAL_ADC_STATE_INJ_BUSY); - - /* Check if a regular conversion is ongoing */ - /* Note: On this device, there is no ADC error code fields related to */ - /* conversions on group injected only. In case of conversion on */ - /* going on group regular, no error code is reset. */ - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) - { - /* Reset ADC all error code fields */ - ADC_CLEAR_ERRORCODE(hadc); - } - - /* Process unlocked */ - /* Unlock before starting ADC conversions: in case of potential */ - /* interruption, to let the process to ADC IRQ Handler. */ - __HAL_UNLOCK(hadc); - - /* Clear injected group conversion flag */ - /* (To ensure of no unknown state from potential previous ADC operations) */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Check if Multimode enabled */ - if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) - { - tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); - tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); - if(tmp1 && tmp2) - { - /* Enable the selected ADC software conversion for injected group */ - hadc->Instance->CR2 |= ADC_CR2_JSWSTART; - } - } - else - { - tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); - tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); - if((hadc->Instance == ADC1) && tmp1 && tmp2) - { - /* Enable the selected ADC software conversion for injected group */ - hadc->Instance->CR2 |= ADC_CR2_JSWSTART; - } - } - } - else - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); - - /* Set ADC error code to ADC IP internal error */ - SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Enables the interrupt and starts ADC conversion of injected channels. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc) -{ - __IO uint32_t counter = 0U; - uint32_t tmp1 = 0U, tmp2 = 0U; - ADC_Common_TypeDef *tmpADC_Common; - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Enable the ADC peripheral */ - - /* Check if ADC peripheral is disabled in order to enable it and wait during - Tstab time the ADC's stabilization */ - if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) - { - /* Enable the Peripheral */ - __HAL_ADC_ENABLE(hadc); - - /* Delay for ADC stabilization time */ - /* Compute number of CPU cycles to wait for */ - counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); - while(counter != 0U) - { - counter--; - } - } - - /* Start conversion if ADC is effectively enabled */ - if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Set ADC state */ - /* - Clear state bitfield related to injected group conversion results */ - /* - Set state bitfield related to injected operation */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC, - HAL_ADC_STATE_INJ_BUSY); - - /* Check if a regular conversion is ongoing */ - /* Note: On this device, there is no ADC error code fields related to */ - /* conversions on group injected only. In case of conversion on */ - /* going on group regular, no error code is reset. */ - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) - { - /* Reset ADC all error code fields */ - ADC_CLEAR_ERRORCODE(hadc); - } - - /* Process unlocked */ - /* Unlock before starting ADC conversions: in case of potential */ - /* interruption, to let the process to ADC IRQ Handler. */ - __HAL_UNLOCK(hadc); - - /* Clear injected group conversion flag */ - /* (To ensure of no unknown state from potential previous ADC operations) */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); - - /* Enable end of conversion interrupt for injected channels */ - __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOC); - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Check if Multimode enabled */ - if(HAL_IS_BIT_CLR(tmpADC_Common->CCR, ADC_CCR_MULTI)) - { - tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); - tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); - if(tmp1 && tmp2) - { - /* Enable the selected ADC software conversion for injected group */ - hadc->Instance->CR2 |= ADC_CR2_JSWSTART; - } - } - else - { - tmp1 = HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_JEXTEN); - tmp2 = HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO); - if((hadc->Instance == ADC1) && tmp1 && tmp2) - { - /* Enable the selected ADC software conversion for injected group */ - hadc->Instance->CR2 |= ADC_CR2_JSWSTART; - } - } - } - else - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); - - /* Set ADC error code to ADC IP internal error */ - SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop conversion of injected channels. Disable ADC peripheral if - * no regular conversion is on going. - * @note If ADC must be disabled and if conversion is on going on - * regular group, function HAL_ADC_Stop must be used to stop both - * injected and regular groups, and disable the ADC. - * @note If injected group mode auto-injection is enabled, - * function HAL_ADC_Stop must be used. - * @note In case of auto-injection mode, HAL_ADC_Stop must be used. - * @param hadc ADC handle - * @retval None - */ -HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc) -{ - HAL_StatusTypeDef tmp_hal_status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Stop potential conversion and disable ADC peripheral */ - /* Conditioned to: */ - /* - No conversion on the other group (regular group) is intended to */ - /* continue (injected and regular groups stop conversion and ADC disable */ - /* are common) */ - /* - In case of auto-injection mode, HAL_ADC_Stop must be used. */ - if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) && - HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) - { - /* Stop potential conversion on going, on regular and injected groups */ - /* Disable ADC peripheral */ - __HAL_ADC_DISABLE(hadc); - - /* Check if ADC is effectively disabled */ - if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Set ADC state */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, - HAL_ADC_STATE_READY); - } - } - else - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); - - tmp_hal_status = HAL_ERROR; - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return tmp_hal_status; -} - -/** - * @brief Poll for injected conversion complete - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param Timeout Timeout value in millisecond. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check End of conversion flag */ - while(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOC))) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - /* New check to avoid false timeout detection in case of preemption */ - if(!(__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOC))) - { - hadc->State= HAL_ADC_STATE_TIMEOUT; - /* Process unlocked */ - __HAL_UNLOCK(hadc); - return HAL_TIMEOUT; - } - } - } - } - - /* Clear injected group conversion flag */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JSTRT | ADC_FLAG_JEOC); - - /* Update ADC state machine */ - SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC); - - /* Determine whether any further conversion upcoming on group injected */ - /* by external trigger, continuous mode or scan sequence on going. */ - /* Note: On STM32F4, there is no independent flag of end of sequence. */ - /* The test of scan sequence on going is done either with scan */ - /* sequence disabled or with end of conversion flag set to */ - /* of end of sequence. */ - if(ADC_IS_SOFTWARE_START_INJECTED(hadc) && - (HAL_IS_BIT_CLR(hadc->Instance->JSQR, ADC_JSQR_JL) || - HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) && - (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) && - (ADC_IS_SOFTWARE_START_REGULAR(hadc) && - (hadc->Init.ContinuousConvMode == DISABLE) ) ) ) - { - /* Set ADC state */ - CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY); - - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY)) - { - SET_BIT(hadc->State, HAL_ADC_STATE_READY); - } - } - - /* Return ADC state */ - return HAL_OK; -} - -/** - * @brief Stop conversion of injected channels, disable interruption of - * end-of-conversion. Disable ADC peripheral if no regular conversion - * is on going. - * @note If ADC must be disabled and if conversion is on going on - * regular group, function HAL_ADC_Stop must be used to stop both - * injected and regular groups, and disable the ADC. - * @note If injected group mode auto-injection is enabled, - * function HAL_ADC_Stop must be used. - * @param hadc ADC handle - * @retval None - */ -HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc) -{ - HAL_StatusTypeDef tmp_hal_status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Stop potential conversion and disable ADC peripheral */ - /* Conditioned to: */ - /* - No conversion on the other group (regular group) is intended to */ - /* continue (injected and regular groups stop conversion and ADC disable */ - /* are common) */ - /* - In case of auto-injection mode, HAL_ADC_Stop must be used. */ - if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) && - HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) ) - { - /* Stop potential conversion on going, on regular and injected groups */ - /* Disable ADC peripheral */ - __HAL_ADC_DISABLE(hadc); - - /* Check if ADC is effectively disabled */ - if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Disable ADC end of conversion interrupt for injected channels */ - __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC); - - /* Set ADC state */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, - HAL_ADC_STATE_READY); - } - } - else - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG); - - tmp_hal_status = HAL_ERROR; - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return tmp_hal_status; -} - -/** - * @brief Gets the converted value from data register of injected channel. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param InjectedRank the ADC injected rank. - * This parameter can be one of the following values: - * @arg ADC_INJECTED_RANK_1: Injected Channel1 selected - * @arg ADC_INJECTED_RANK_2: Injected Channel2 selected - * @arg ADC_INJECTED_RANK_3: Injected Channel3 selected - * @arg ADC_INJECTED_RANK_4: Injected Channel4 selected - * @retval None - */ -uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank) -{ - __IO uint32_t tmp = 0U; - - /* Check the parameters */ - assert_param(IS_ADC_INJECTED_RANK(InjectedRank)); - - /* Clear injected group conversion flag to have similar behaviour as */ - /* regular group: reading data register also clears end of conversion flag. */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC); - - /* Return the selected ADC converted value */ - switch(InjectedRank) - { - case ADC_INJECTED_RANK_4: - { - tmp = hadc->Instance->JDR4; - } - break; - case ADC_INJECTED_RANK_3: - { - tmp = hadc->Instance->JDR3; - } - break; - case ADC_INJECTED_RANK_2: - { - tmp = hadc->Instance->JDR2; - } - break; - case ADC_INJECTED_RANK_1: - { - tmp = hadc->Instance->JDR1; - } - break; - default: - break; - } - return tmp; -} - -/** - * @brief Enables ADC DMA request after last transfer (Multi-ADC mode) and enables ADC peripheral - * - * @note Caution: This function must be used only with the ADC master. - * - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param pData Pointer to buffer in which transferred from ADC peripheral to memory will be stored. - * @param Length The length of data to be transferred from ADC peripheral to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADCEx_MultiModeStart_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length) -{ - __IO uint32_t counter = 0U; - ADC_Common_TypeDef *tmpADC_Common; - - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode)); - assert_param(IS_ADC_EXT_TRIG_EDGE(hadc->Init.ExternalTrigConvEdge)); - assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DMAContinuousRequests)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Check if ADC peripheral is disabled in order to enable it and wait during - Tstab time the ADC's stabilization */ - if((hadc->Instance->CR2 & ADC_CR2_ADON) != ADC_CR2_ADON) - { - /* Enable the Peripheral */ - __HAL_ADC_ENABLE(hadc); - - /* Delay for temperature sensor stabilization time */ - /* Compute number of CPU cycles to wait for */ - counter = (ADC_STAB_DELAY_US * (SystemCoreClock / 1000000U)); - while(counter != 0U) - { - counter--; - } - } - - /* Start conversion if ADC is effectively enabled */ - if(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Set ADC state */ - /* - Clear state bitfield related to regular group conversion results */ - /* - Set state bitfield related to regular group operation */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR, - HAL_ADC_STATE_REG_BUSY); - - /* If conversions on group regular are also triggering group injected, */ - /* update ADC state. */ - if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET) - { - ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY); - } - - /* State machine update: Check if an injected conversion is ongoing */ - if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY)) - { - /* Reset ADC error code fields related to conversions on group regular */ - CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA)); - } - else - { - /* Reset ADC all error code fields */ - ADC_CLEAR_ERRORCODE(hadc); - } - - /* Process unlocked */ - /* Unlock before starting ADC conversions: in case of potential */ - /* interruption, to let the process to ADC IRQ Handler. */ - __HAL_UNLOCK(hadc); - - /* Set the DMA transfer complete callback */ - hadc->DMA_Handle->XferCpltCallback = ADC_MultiModeDMAConvCplt; - - /* Set the DMA half transfer complete callback */ - hadc->DMA_Handle->XferHalfCpltCallback = ADC_MultiModeDMAHalfConvCplt; - - /* Set the DMA error callback */ - hadc->DMA_Handle->XferErrorCallback = ADC_MultiModeDMAError ; - - /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */ - /* start (in case of SW start): */ - - /* Clear regular group conversion flag and overrun flag */ - /* (To ensure of no unknown state from potential previous ADC operations) */ - __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC); - - /* Enable ADC overrun interrupt */ - __HAL_ADC_ENABLE_IT(hadc, ADC_IT_OVR); - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - if (hadc->Init.DMAContinuousRequests != DISABLE) - { - /* Enable the selected ADC DMA request after last transfer */ - tmpADC_Common->CCR |= ADC_CCR_DDS; - } - else - { - /* Disable the selected ADC EOC rising on each regular channel conversion */ - tmpADC_Common->CCR &= ~ADC_CCR_DDS; - } - - /* Enable the DMA Stream */ - HAL_DMA_Start_IT(hadc->DMA_Handle, (uint32_t)&tmpADC_Common->CDR, (uint32_t)pData, Length); - - /* if no external trigger present enable software conversion of regular channels */ - if((hadc->Instance->CR2 & ADC_CR2_EXTEN) == RESET) - { - /* Enable the selected ADC software conversion for regular group */ - hadc->Instance->CR2 |= (uint32_t)ADC_CR2_SWSTART; - } - } - else - { - /* Update ADC state machine to error */ - SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL); - - /* Set ADC error code to ADC IP internal error */ - SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Disables ADC DMA (multi-ADC mode) and disables ADC peripheral - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc) -{ - HAL_StatusTypeDef tmp_hal_status = HAL_OK; - ADC_Common_TypeDef *tmpADC_Common; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Stop potential conversion on going, on regular and injected groups */ - /* Disable ADC peripheral */ - __HAL_ADC_DISABLE(hadc); - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Check if ADC is effectively disabled */ - if(HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_ADON)) - { - /* Disable the selected ADC DMA mode for multimode */ - tmpADC_Common->CCR &= ~ADC_CCR_DDS; - - /* Disable the DMA channel (in case of DMA in circular mode or stop while */ - /* DMA transfer is on going) */ - tmp_hal_status = HAL_DMA_Abort(hadc->DMA_Handle); - - /* Disable ADC overrun interrupt */ - __HAL_ADC_DISABLE_IT(hadc, ADC_IT_OVR); - - /* Set ADC state */ - ADC_STATE_CLR_SET(hadc->State, - HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY, - HAL_ADC_STATE_READY); - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return tmp_hal_status; -} - -/** - * @brief Returns the last ADC1, ADC2 and ADC3 regular conversions results - * data in the selected multi mode. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval The converted data value. - */ -uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc) -{ - ADC_Common_TypeDef *tmpADC_Common; - UNUSED(hadc); // TODO: check if not breaks something! - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Return the multi mode conversion value */ - return tmpADC_Common->CDR; -} - -/** - * @brief Injected conversion complete callback in non blocking mode - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @retval None - */ -__weak void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hadc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ADC_InjectedConvCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Configures for the selected ADC injected channel its corresponding - * rank in the sequencer and its sample time. - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param sConfigInjected ADC configuration structure for injected channel. - * @retval None - */ -HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc, ADC_InjectionConfTypeDef* sConfigInjected) -{ - -#ifdef USE_FULL_ASSERT - uint32_t tmp = 0U; - -#endif /* USE_FULL_ASSERT */ - - ADC_Common_TypeDef *tmpADC_Common; - - /* Check the parameters */ - assert_param(IS_ADC_CHANNEL(sConfigInjected->InjectedChannel)); - assert_param(IS_ADC_INJECTED_RANK(sConfigInjected->InjectedRank)); - assert_param(IS_ADC_SAMPLE_TIME(sConfigInjected->InjectedSamplingTime)); - assert_param(IS_ADC_EXT_INJEC_TRIG(sConfigInjected->ExternalTrigInjecConv)); - assert_param(IS_ADC_INJECTED_LENGTH(sConfigInjected->InjectedNbrOfConversion)); - assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->AutoInjectedConv)); - assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->InjectedDiscontinuousConvMode)); - -#ifdef USE_FULL_ASSERT - tmp = ADC_GET_RESOLUTION(hadc); - assert_param(IS_ADC_RANGE(tmp, sConfigInjected->InjectedOffset)); -#endif /* USE_FULL_ASSERT */ - - if(sConfigInjected->ExternalTrigInjecConv != ADC_INJECTED_SOFTWARE_START) - { - assert_param(IS_ADC_EXT_INJEC_TRIG_EDGE(sConfigInjected->ExternalTrigInjecConvEdge)); - } - - /* Process locked */ - __HAL_LOCK(hadc); - - /* if ADC_Channel_10 ... ADC_Channel_18 is selected */ - if (sConfigInjected->InjectedChannel > ADC_CHANNEL_9) - { - /* Clear the old sample time */ - hadc->Instance->SMPR1 &= ~ADC_SMPR1(ADC_SMPR1_SMP10, sConfigInjected->InjectedChannel); - - /* Set the new sample time */ - hadc->Instance->SMPR1 |= ADC_SMPR1(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel); - } - else /* ADC_Channel include in ADC_Channel_[0..9] */ - { - /* Clear the old sample time */ - hadc->Instance->SMPR2 &= ~ADC_SMPR2(ADC_SMPR2_SMP0, sConfigInjected->InjectedChannel); - - /* Set the new sample time */ - hadc->Instance->SMPR2 |= ADC_SMPR2(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel); - } - - /*---------------------------- ADCx JSQR Configuration -----------------*/ - hadc->Instance->JSQR &= ~(ADC_JSQR_JL); - hadc->Instance->JSQR |= ADC_SQR1(sConfigInjected->InjectedNbrOfConversion); - - /* Rank configuration */ - - /* Clear the old SQx bits for the selected rank */ - hadc->Instance->JSQR &= ~ADC_JSQR(ADC_JSQR_JSQ1, sConfigInjected->InjectedRank,sConfigInjected->InjectedNbrOfConversion); - - /* Set the SQx bits for the selected rank */ - hadc->Instance->JSQR |= ADC_JSQR(sConfigInjected->InjectedChannel, sConfigInjected->InjectedRank,sConfigInjected->InjectedNbrOfConversion); - - /* Enable external trigger if trigger selection is different of software */ - /* start. */ - /* Note: This configuration keeps the hardware feature of parameter */ - /* ExternalTrigConvEdge "trigger edge none" equivalent to */ - /* software start. */ - if(sConfigInjected->ExternalTrigInjecConv != ADC_INJECTED_SOFTWARE_START) - { - /* Select external trigger to start conversion */ - hadc->Instance->CR2 &= ~(ADC_CR2_JEXTSEL); - hadc->Instance->CR2 |= sConfigInjected->ExternalTrigInjecConv; - - /* Select external trigger polarity */ - hadc->Instance->CR2 &= ~(ADC_CR2_JEXTEN); - hadc->Instance->CR2 |= sConfigInjected->ExternalTrigInjecConvEdge; - } - else - { - /* Reset the external trigger */ - hadc->Instance->CR2 &= ~(ADC_CR2_JEXTSEL); - hadc->Instance->CR2 &= ~(ADC_CR2_JEXTEN); - } - - if (sConfigInjected->AutoInjectedConv != DISABLE) - { - /* Enable the selected ADC automatic injected group conversion */ - hadc->Instance->CR1 |= ADC_CR1_JAUTO; - } - else - { - /* Disable the selected ADC automatic injected group conversion */ - hadc->Instance->CR1 &= ~(ADC_CR1_JAUTO); - } - - if (sConfigInjected->InjectedDiscontinuousConvMode != DISABLE) - { - /* Enable the selected ADC injected discontinuous mode */ - hadc->Instance->CR1 |= ADC_CR1_JDISCEN; - } - else - { - /* Disable the selected ADC injected discontinuous mode */ - hadc->Instance->CR1 &= ~(ADC_CR1_JDISCEN); - } - - switch(sConfigInjected->InjectedRank) - { - case 1U: - /* Set injected channel 1 offset */ - hadc->Instance->JOFR1 &= ~(ADC_JOFR1_JOFFSET1); - hadc->Instance->JOFR1 |= sConfigInjected->InjectedOffset; - break; - case 2U: - /* Set injected channel 2 offset */ - hadc->Instance->JOFR2 &= ~(ADC_JOFR2_JOFFSET2); - hadc->Instance->JOFR2 |= sConfigInjected->InjectedOffset; - break; - case 3U: - /* Set injected channel 3 offset */ - hadc->Instance->JOFR3 &= ~(ADC_JOFR3_JOFFSET3); - hadc->Instance->JOFR3 |= sConfigInjected->InjectedOffset; - break; - default: - /* Set injected channel 4 offset */ - hadc->Instance->JOFR4 &= ~(ADC_JOFR4_JOFFSET4); - hadc->Instance->JOFR4 |= sConfigInjected->InjectedOffset; - break; - } - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* if ADC1 Channel_18 is selected enable VBAT Channel */ - if ((hadc->Instance == ADC1) && (sConfigInjected->InjectedChannel == ADC_CHANNEL_VBAT)) - { - /* Enable the VBAT channel*/ - tmpADC_Common->CCR |= ADC_CCR_VBATE; - } - - /* if ADC1 Channel_16 or Channel_17 is selected enable TSVREFE Channel(Temperature sensor and VREFINT) */ - if ((hadc->Instance == ADC1) && ((sConfigInjected->InjectedChannel == ADC_CHANNEL_TEMPSENSOR) || (sConfigInjected->InjectedChannel == ADC_CHANNEL_VREFINT))) - { - /* Enable the TSVREFE channel*/ - tmpADC_Common->CCR |= ADC_CCR_TSVREFE; - } - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Configures the ADC multi-mode - * @param hadc pointer to a ADC_HandleTypeDef structure that contains - * the configuration information for the specified ADC. - * @param multimode pointer to an ADC_MultiModeTypeDef structure that contains - * the configuration information for multimode. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ADCEx_MultiModeConfigChannel(ADC_HandleTypeDef* hadc, ADC_MultiModeTypeDef* multimode) -{ - - ADC_Common_TypeDef *tmpADC_Common; - - /* Check the parameters */ - assert_param(IS_ADC_MODE(multimode->Mode)); - assert_param(IS_ADC_DMA_ACCESS_MODE(multimode->DMAAccessMode)); - assert_param(IS_ADC_SAMPLING_DELAY(multimode->TwoSamplingDelay)); - - /* Process locked */ - __HAL_LOCK(hadc); - - /* Pointer to the common control register to which is belonging hadc */ - /* (Depending on STM32F4 product, there may be up to 3 ADC and 1 common */ - /* control register) */ - tmpADC_Common = ADC_COMMON_REGISTER(hadc); - - /* Set ADC mode */ - tmpADC_Common->CCR &= ~(ADC_CCR_MULTI); - tmpADC_Common->CCR |= multimode->Mode; - - /* Set the ADC DMA access mode */ - tmpADC_Common->CCR &= ~(ADC_CCR_DMA); - tmpADC_Common->CCR |= multimode->DMAAccessMode; - - /* Set delay between two sampling phases */ - tmpADC_Common->CCR &= ~(ADC_CCR_DELAY); - tmpADC_Common->CCR |= multimode->TwoSamplingDelay; - - /* Process unlocked */ - __HAL_UNLOCK(hadc); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** - * @brief DMA transfer complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void ADC_MultiModeDMAConvCplt(DMA_HandleTypeDef *hdma) -{ - /* Retrieve ADC handle corresponding to current DMA handle */ - ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - /* Update state machine on conversion status if not in error state */ - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL | HAL_ADC_STATE_ERROR_DMA)) - { - /* Update ADC state machine */ - SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC); - - /* Determine whether any further conversion upcoming on group regular */ - /* by external trigger, continuous mode or scan sequence on going. */ - /* Note: On STM32F4, there is no independent flag of end of sequence. */ - /* The test of scan sequence on going is done either with scan */ - /* sequence disabled or with end of conversion flag set to */ - /* of end of sequence. */ - if(ADC_IS_SOFTWARE_START_REGULAR(hadc) && - (hadc->Init.ContinuousConvMode == DISABLE) && - (HAL_IS_BIT_CLR(hadc->Instance->SQR1, ADC_SQR1_L) || - HAL_IS_BIT_CLR(hadc->Instance->CR2, ADC_CR2_EOCS) ) ) - { - /* Disable ADC end of single conversion interrupt on group regular */ - /* Note: Overrun interrupt was enabled with EOC interrupt in */ - /* HAL_ADC_Start_IT(), but is not disabled here because can be used */ - /* by overrun IRQ process below. */ - __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC); - - /* Set ADC state */ - CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY); - - if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_INJ_BUSY)) - { - SET_BIT(hadc->State, HAL_ADC_STATE_READY); - } - } - - /* Conversion complete callback */ - HAL_ADC_ConvCpltCallback(hadc); - } - else - { - /* Call DMA error callback */ - hadc->DMA_Handle->XferErrorCallback(hdma); - } -} - -/** - * @brief DMA half transfer complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void ADC_MultiModeDMAHalfConvCplt(DMA_HandleTypeDef *hdma) -{ - ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - /* Conversion complete callback */ - HAL_ADC_ConvHalfCpltCallback(hadc); -} - -/** - * @brief DMA error callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void ADC_MultiModeDMAError(DMA_HandleTypeDef *hdma) -{ - ADC_HandleTypeDef* hadc = ( ADC_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - hadc->State= HAL_ADC_STATE_ERROR_DMA; - /* Set ADC error code to DMA error */ - hadc->ErrorCode |= HAL_ADC_ERROR_DMA; - HAL_ADC_ErrorCallback(hadc); -} - -/** - * @} - */ - -#endif /* HAL_ADC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c deleted file mode 100644 index 3e03475802ed7a1..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c +++ /dev/null @@ -1,2464 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_can.c - * @author MCD Application Team - * @brief CAN HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Controller Area Network (CAN) peripheral: - * + Initialization and de-initialization functions - * + Configuration functions - * + Control functions - * + Interrupts management - * + Callbacks functions - * + Peripheral State and Error functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Initialize the CAN low level resources by implementing the - HAL_CAN_MspInit(): - (++) Enable the CAN interface clock using __HAL_RCC_CANx_CLK_ENABLE() - (++) Configure CAN pins - (+++) Enable the clock for the CAN GPIOs - (+++) Configure CAN pins as alternate function open-drain - (++) In case of using interrupts (e.g. HAL_CAN_ActivateNotification()) - (+++) Configure the CAN interrupt priority using - HAL_NVIC_SetPriority() - (+++) Enable the CAN IRQ handler using HAL_NVIC_EnableIRQ() - (+++) In CAN IRQ handler, call HAL_CAN_IRQHandler() - - (#) Initialize the CAN peripheral using HAL_CAN_Init() function. This - function resorts to HAL_CAN_MspInit() for low-level initialization. - - (#) Configure the reception filters using the following configuration - functions: - (++) HAL_CAN_ConfigFilter() - - (#) Start the CAN module using HAL_CAN_Start() function. At this level - the node is active on the bus: it receive messages, and can send - messages. - - (#) To manage messages transmission, the following Tx control functions - can be used: - (++) HAL_CAN_AddTxMessage() to request transmission of a new - message. - (++) HAL_CAN_AbortTxRequest() to abort transmission of a pending - message. - (++) HAL_CAN_GetTxMailboxesFreeLevel() to get the number of free Tx - mailboxes. - (++) HAL_CAN_IsTxMessagePending() to check if a message is pending - in a Tx mailbox. - (++) HAL_CAN_GetTxTimestamp() to get the timestamp of Tx message - sent, if time triggered communication mode is enabled. - - (#) When a message is received into the CAN Rx FIFOs, it can be retrieved - using the HAL_CAN_GetRxMessage() function. The function - HAL_CAN_GetRxFifoFillLevel() allows to know how many Rx message are - stored in the Rx Fifo. - - (#) Calling the HAL_CAN_Stop() function stops the CAN module. - - (#) The deinitialization is achieved with HAL_CAN_DeInit() function. - - - *** Polling mode operation *** - ============================== - [..] - (#) Reception: - (++) Monitor reception of message using HAL_CAN_GetRxFifoFillLevel() - until at least one message is received. - (++) Then get the message using HAL_CAN_GetRxMessage(). - - (#) Transmission: - (++) Monitor the Tx mailboxes availability until at least one Tx - mailbox is free, using HAL_CAN_GetTxMailboxesFreeLevel(). - (++) Then request transmission of a message using - HAL_CAN_AddTxMessage(). - - - *** Interrupt mode operation *** - ================================ - [..] - (#) Notifications are activated using HAL_CAN_ActivateNotification() - function. Then, the process can be controlled through the - available user callbacks: HAL_CAN_xxxCallback(), using same APIs - HAL_CAN_GetRxMessage() and HAL_CAN_AddTxMessage(). - - (#) Notifications can be deactivated using - HAL_CAN_DeactivateNotification() function. - - (#) Special care should be taken for CAN_IT_RX_FIFO0_MSG_PENDING and - CAN_IT_RX_FIFO1_MSG_PENDING notifications. These notifications trig - the callbacks HAL_CAN_RxFIFO0MsgPendingCallback() and - HAL_CAN_RxFIFO1MsgPendingCallback(). User has two possible options - here. - (++) Directly get the Rx message in the callback, using - HAL_CAN_GetRxMessage(). - (++) Or deactivate the notification in the callback without - getting the Rx message. The Rx message can then be got later - using HAL_CAN_GetRxMessage(). Once the Rx message have been - read, the notification can be activated again. - - - *** Sleep mode *** - ================== - [..] - (#) The CAN peripheral can be put in sleep mode (low power), using - HAL_CAN_RequestSleep(). The sleep mode will be entered as soon as the - current CAN activity (transmission or reception of a CAN frame) will - be completed. - - (#) A notification can be activated to be informed when the sleep mode - will be entered. - - (#) It can be checked if the sleep mode is entered using - HAL_CAN_IsSleepActive(). - Note that the CAN state (accessible from the API HAL_CAN_GetState()) - is HAL_CAN_STATE_SLEEP_PENDING as soon as the sleep mode request is - submitted (the sleep mode is not yet entered), and become - HAL_CAN_STATE_SLEEP_ACTIVE when the sleep mode is effective. - - (#) The wake-up from sleep mode can be triggered by two ways: - (++) Using HAL_CAN_WakeUp(). When returning from this function, - the sleep mode is exited (if return status is HAL_OK). - (++) When a start of Rx CAN frame is detected by the CAN peripheral, - if automatic wake up mode is enabled. - - *** Callback registration *** - ============================================= - - The compilation define USE_HAL_CAN_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Function HAL_CAN_RegisterCallback() to register an interrupt callback. - - Function HAL_CAN_RegisterCallback() allows to register following callbacks: - (+) TxMailbox0CompleteCallback : Tx Mailbox 0 Complete Callback. - (+) TxMailbox1CompleteCallback : Tx Mailbox 1 Complete Callback. - (+) TxMailbox2CompleteCallback : Tx Mailbox 2 Complete Callback. - (+) TxMailbox0AbortCallback : Tx Mailbox 0 Abort Callback. - (+) TxMailbox1AbortCallback : Tx Mailbox 1 Abort Callback. - (+) TxMailbox2AbortCallback : Tx Mailbox 2 Abort Callback. - (+) RxFifo0MsgPendingCallback : Rx Fifo 0 Message Pending Callback. - (+) RxFifo0FullCallback : Rx Fifo 0 Full Callback. - (+) RxFifo1MsgPendingCallback : Rx Fifo 1 Message Pending Callback. - (+) RxFifo1FullCallback : Rx Fifo 1 Full Callback. - (+) SleepCallback : Sleep Callback. - (+) WakeUpFromRxMsgCallback : Wake Up From Rx Message Callback. - (+) ErrorCallback : Error Callback. - (+) MspInitCallback : CAN MspInit. - (+) MspDeInitCallback : CAN MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function HAL_CAN_UnRegisterCallback() to reset a callback to the default - weak function. - HAL_CAN_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxMailbox0CompleteCallback : Tx Mailbox 0 Complete Callback. - (+) TxMailbox1CompleteCallback : Tx Mailbox 1 Complete Callback. - (+) TxMailbox2CompleteCallback : Tx Mailbox 2 Complete Callback. - (+) TxMailbox0AbortCallback : Tx Mailbox 0 Abort Callback. - (+) TxMailbox1AbortCallback : Tx Mailbox 1 Abort Callback. - (+) TxMailbox2AbortCallback : Tx Mailbox 2 Abort Callback. - (+) RxFifo0MsgPendingCallback : Rx Fifo 0 Message Pending Callback. - (+) RxFifo0FullCallback : Rx Fifo 0 Full Callback. - (+) RxFifo1MsgPendingCallback : Rx Fifo 1 Message Pending Callback. - (+) RxFifo1FullCallback : Rx Fifo 1 Full Callback. - (+) SleepCallback : Sleep Callback. - (+) WakeUpFromRxMsgCallback : Wake Up From Rx Message Callback. - (+) ErrorCallback : Error Callback. - (+) MspInitCallback : CAN MspInit. - (+) MspDeInitCallback : CAN MspDeInit. - - By default, after the HAL_CAN_Init() and when the state is HAL_CAN_STATE_RESET, - all callbacks are set to the corresponding weak functions: - example HAL_CAN_ErrorCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak function in the HAL_CAN_Init()/ HAL_CAN_DeInit() only when - these callbacks are null (not registered beforehand). - if not, MspInit or MspDeInit are not null, the HAL_CAN_Init()/ HAL_CAN_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in HAL_CAN_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_CAN_STATE_READY or HAL_CAN_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_CAN_RegisterCallback() before calling HAL_CAN_DeInit() - or HAL_CAN_Init() function. - - When The compilation define USE_HAL_CAN_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined(CAN1) - -/** @defgroup CAN CAN - * @brief CAN driver modules - * @{ - */ - -#ifdef HAL_CAN_MODULE_ENABLED - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - #error "The CAN driver cannot be used with its legacy, Please enable only one CAN module at once" -#endif - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup CAN_Private_Constants CAN Private Constants - * @{ - */ -#define CAN_TIMEOUT_VALUE 10U -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup CAN_Exported_Functions CAN Exported Functions - * @{ - */ - -/** @defgroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) HAL_CAN_Init : Initialize and configure the CAN. - (+) HAL_CAN_DeInit : De-initialize the CAN. - (+) HAL_CAN_MspInit : Initialize the CAN MSP. - (+) HAL_CAN_MspDeInit : DeInitialize the CAN MSP. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the CAN peripheral according to the specified - * parameters in the CAN_InitStruct. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *hcan) -{ - uint32_t tickstart; - - /* Check CAN handle */ - if (hcan == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TimeTriggeredMode)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoBusOff)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoWakeUp)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.AutoRetransmission)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.ReceiveFifoLocked)); - assert_param(IS_FUNCTIONAL_STATE(hcan->Init.TransmitFifoPriority)); - assert_param(IS_CAN_MODE(hcan->Init.Mode)); - assert_param(IS_CAN_SJW(hcan->Init.SyncJumpWidth)); - assert_param(IS_CAN_BS1(hcan->Init.TimeSeg1)); - assert_param(IS_CAN_BS2(hcan->Init.TimeSeg2)); - assert_param(IS_CAN_PRESCALER(hcan->Init.Prescaler)); - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - if (hcan->State == HAL_CAN_STATE_RESET) - { - /* Reset callbacks to legacy functions */ - hcan->RxFifo0MsgPendingCallback = HAL_CAN_RxFifo0MsgPendingCallback; /* Legacy weak RxFifo0MsgPendingCallback */ - hcan->RxFifo0FullCallback = HAL_CAN_RxFifo0FullCallback; /* Legacy weak RxFifo0FullCallback */ - hcan->RxFifo1MsgPendingCallback = HAL_CAN_RxFifo1MsgPendingCallback; /* Legacy weak RxFifo1MsgPendingCallback */ - hcan->RxFifo1FullCallback = HAL_CAN_RxFifo1FullCallback; /* Legacy weak RxFifo1FullCallback */ - hcan->TxMailbox0CompleteCallback = HAL_CAN_TxMailbox0CompleteCallback; /* Legacy weak TxMailbox0CompleteCallback */ - hcan->TxMailbox1CompleteCallback = HAL_CAN_TxMailbox1CompleteCallback; /* Legacy weak TxMailbox1CompleteCallback */ - hcan->TxMailbox2CompleteCallback = HAL_CAN_TxMailbox2CompleteCallback; /* Legacy weak TxMailbox2CompleteCallback */ - hcan->TxMailbox0AbortCallback = HAL_CAN_TxMailbox0AbortCallback; /* Legacy weak TxMailbox0AbortCallback */ - hcan->TxMailbox1AbortCallback = HAL_CAN_TxMailbox1AbortCallback; /* Legacy weak TxMailbox1AbortCallback */ - hcan->TxMailbox2AbortCallback = HAL_CAN_TxMailbox2AbortCallback; /* Legacy weak TxMailbox2AbortCallback */ - hcan->SleepCallback = HAL_CAN_SleepCallback; /* Legacy weak SleepCallback */ - hcan->WakeUpFromRxMsgCallback = HAL_CAN_WakeUpFromRxMsgCallback; /* Legacy weak WakeUpFromRxMsgCallback */ - hcan->ErrorCallback = HAL_CAN_ErrorCallback; /* Legacy weak ErrorCallback */ - - if (hcan->MspInitCallback == NULL) - { - hcan->MspInitCallback = HAL_CAN_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware: CLOCK, NVIC */ - hcan->MspInitCallback(hcan); - } - -#else - if (hcan->State == HAL_CAN_STATE_RESET) - { - /* Init the low level hardware: CLOCK, NVIC */ - HAL_CAN_MspInit(hcan); - } -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ - - /* Request initialisation */ - SET_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait initialisation acknowledge */ - while ((hcan->Instance->MSR & CAN_MSR_INAK) == 0U) - { - if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - return HAL_ERROR; - } - } - - /* Exit from sleep mode */ - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check Sleep mode leave acknowledge */ - while ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) - { - if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - return HAL_ERROR; - } - } - - /* Set the time triggered communication mode */ - if (hcan->Init.TimeTriggeredMode == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_TTCM); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_TTCM); - } - - /* Set the automatic bus-off management */ - if (hcan->Init.AutoBusOff == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_ABOM); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_ABOM); - } - - /* Set the automatic wake-up mode */ - if (hcan->Init.AutoWakeUp == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_AWUM); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_AWUM); - } - - /* Set the automatic retransmission */ - if (hcan->Init.AutoRetransmission == ENABLE) - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_NART); - } - else - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_NART); - } - - /* Set the receive FIFO locked mode */ - if (hcan->Init.ReceiveFifoLocked == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_RFLM); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_RFLM); - } - - /* Set the transmit FIFO priority */ - if (hcan->Init.TransmitFifoPriority == ENABLE) - { - SET_BIT(hcan->Instance->MCR, CAN_MCR_TXFP); - } - else - { - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_TXFP); - } - - /* Set the bit timing register */ - WRITE_REG(hcan->Instance->BTR, (uint32_t)(hcan->Init.Mode | - hcan->Init.SyncJumpWidth | - hcan->Init.TimeSeg1 | - hcan->Init.TimeSeg2 | - (hcan->Init.Prescaler - 1U))); - - /* Initialize the error code */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Initialize the CAN state */ - hcan->State = HAL_CAN_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Deinitializes the CAN peripheral registers to their default - * reset values. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef *hcan) -{ - /* Check CAN handle */ - if (hcan == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CAN_ALL_INSTANCE(hcan->Instance)); - - /* Stop the CAN module */ - (void)HAL_CAN_Stop(hcan); - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - if (hcan->MspDeInitCallback == NULL) - { - hcan->MspDeInitCallback = HAL_CAN_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: CLOCK, NVIC */ - hcan->MspDeInitCallback(hcan); - -#else - /* DeInit the low level hardware: CLOCK, NVIC */ - HAL_CAN_MspDeInit(hcan); -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ - - /* Reset the CAN peripheral */ - SET_BIT(hcan->Instance->MCR, CAN_MCR_RESET); - - /* Reset the CAN ErrorCode */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_RESET; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initializes the CAN MSP. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes the CAN MSP. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_MspDeInit could be implemented in the user file - */ -} - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -/** - * @brief Register a CAN CallBack. - * To be used instead of the weak predefined callback - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for CAN module - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID Tx Mailbox 0 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID Tx Mailbox 1 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID Tx Mailbox 2 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX0_ABORT_CB_ID Tx Mailbox 0 Abort callback ID - * @arg @ref HAL_CAN_TX_MAILBOX1_ABORT_CB_ID Tx Mailbox 1 Abort callback ID - * @arg @ref HAL_CAN_TX_MAILBOX2_ABORT_CB_ID Tx Mailbox 2 Abort callback ID - * @arg @ref HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID Rx Fifo 0 message pending callback ID - * @arg @ref HAL_CAN_RX_FIFO0_FULL_CB_ID Rx Fifo 0 full callback ID - * @arg @ref HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID Rx Fifo 1 message pending callback ID - * @arg @ref HAL_CAN_RX_FIFO1_FULL_CB_ID Rx Fifo 1 full callback ID - * @arg @ref HAL_CAN_SLEEP_CB_ID Sleep callback ID - * @arg @ref HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID Wake Up from Rx message callback ID - * @arg @ref HAL_CAN_ERROR_CB_ID Error callback ID - * @arg @ref HAL_CAN_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_CAN_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_RegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID, void (* pCallback)(CAN_HandleTypeDef *_hcan)) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - if (hcan->State == HAL_CAN_STATE_READY) - { - switch (CallbackID) - { - case HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID : - hcan->TxMailbox0CompleteCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID : - hcan->TxMailbox1CompleteCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID : - hcan->TxMailbox2CompleteCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX0_ABORT_CB_ID : - hcan->TxMailbox0AbortCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX1_ABORT_CB_ID : - hcan->TxMailbox1AbortCallback = pCallback; - break; - - case HAL_CAN_TX_MAILBOX2_ABORT_CB_ID : - hcan->TxMailbox2AbortCallback = pCallback; - break; - - case HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID : - hcan->RxFifo0MsgPendingCallback = pCallback; - break; - - case HAL_CAN_RX_FIFO0_FULL_CB_ID : - hcan->RxFifo0FullCallback = pCallback; - break; - - case HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID : - hcan->RxFifo1MsgPendingCallback = pCallback; - break; - - case HAL_CAN_RX_FIFO1_FULL_CB_ID : - hcan->RxFifo1FullCallback = pCallback; - break; - - case HAL_CAN_SLEEP_CB_ID : - hcan->SleepCallback = pCallback; - break; - - case HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID : - hcan->WakeUpFromRxMsgCallback = pCallback; - break; - - case HAL_CAN_ERROR_CB_ID : - hcan->ErrorCallback = pCallback; - break; - - case HAL_CAN_MSPINIT_CB_ID : - hcan->MspInitCallback = pCallback; - break; - - case HAL_CAN_MSPDEINIT_CB_ID : - hcan->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hcan->State == HAL_CAN_STATE_RESET) - { - switch (CallbackID) - { - case HAL_CAN_MSPINIT_CB_ID : - hcan->MspInitCallback = pCallback; - break; - - case HAL_CAN_MSPDEINIT_CB_ID : - hcan->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - return status; -} - -/** - * @brief Unregister a CAN CallBack. - * CAN callabck is redirected to the weak predefined callback - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for CAN module - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID Tx Mailbox 0 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID Tx Mailbox 1 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID Tx Mailbox 2 Complete callback ID - * @arg @ref HAL_CAN_TX_MAILBOX0_ABORT_CB_ID Tx Mailbox 0 Abort callback ID - * @arg @ref HAL_CAN_TX_MAILBOX1_ABORT_CB_ID Tx Mailbox 1 Abort callback ID - * @arg @ref HAL_CAN_TX_MAILBOX2_ABORT_CB_ID Tx Mailbox 2 Abort callback ID - * @arg @ref HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID Rx Fifo 0 message pending callback ID - * @arg @ref HAL_CAN_RX_FIFO0_FULL_CB_ID Rx Fifo 0 full callback ID - * @arg @ref HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID Rx Fifo 1 message pending callback ID - * @arg @ref HAL_CAN_RX_FIFO1_FULL_CB_ID Rx Fifo 1 full callback ID - * @arg @ref HAL_CAN_SLEEP_CB_ID Sleep callback ID - * @arg @ref HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID Wake Up from Rx message callback ID - * @arg @ref HAL_CAN_ERROR_CB_ID Error callback ID - * @arg @ref HAL_CAN_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_CAN_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_UnRegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (hcan->State == HAL_CAN_STATE_READY) - { - switch (CallbackID) - { - case HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID : - hcan->TxMailbox0CompleteCallback = HAL_CAN_TxMailbox0CompleteCallback; - break; - - case HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID : - hcan->TxMailbox1CompleteCallback = HAL_CAN_TxMailbox1CompleteCallback; - break; - - case HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID : - hcan->TxMailbox2CompleteCallback = HAL_CAN_TxMailbox2CompleteCallback; - break; - - case HAL_CAN_TX_MAILBOX0_ABORT_CB_ID : - hcan->TxMailbox0AbortCallback = HAL_CAN_TxMailbox0AbortCallback; - break; - - case HAL_CAN_TX_MAILBOX1_ABORT_CB_ID : - hcan->TxMailbox1AbortCallback = HAL_CAN_TxMailbox1AbortCallback; - break; - - case HAL_CAN_TX_MAILBOX2_ABORT_CB_ID : - hcan->TxMailbox2AbortCallback = HAL_CAN_TxMailbox2AbortCallback; - break; - - case HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID : - hcan->RxFifo0MsgPendingCallback = HAL_CAN_RxFifo0MsgPendingCallback; - break; - - case HAL_CAN_RX_FIFO0_FULL_CB_ID : - hcan->RxFifo0FullCallback = HAL_CAN_RxFifo0FullCallback; - break; - - case HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID : - hcan->RxFifo1MsgPendingCallback = HAL_CAN_RxFifo1MsgPendingCallback; - break; - - case HAL_CAN_RX_FIFO1_FULL_CB_ID : - hcan->RxFifo1FullCallback = HAL_CAN_RxFifo1FullCallback; - break; - - case HAL_CAN_SLEEP_CB_ID : - hcan->SleepCallback = HAL_CAN_SleepCallback; - break; - - case HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID : - hcan->WakeUpFromRxMsgCallback = HAL_CAN_WakeUpFromRxMsgCallback; - break; - - case HAL_CAN_ERROR_CB_ID : - hcan->ErrorCallback = HAL_CAN_ErrorCallback; - break; - - case HAL_CAN_MSPINIT_CB_ID : - hcan->MspInitCallback = HAL_CAN_MspInit; - break; - - case HAL_CAN_MSPDEINIT_CB_ID : - hcan->MspDeInitCallback = HAL_CAN_MspDeInit; - break; - - default : - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hcan->State == HAL_CAN_STATE_RESET) - { - switch (CallbackID) - { - case HAL_CAN_MSPINIT_CB_ID : - hcan->MspInitCallback = HAL_CAN_MspInit; - break; - - case HAL_CAN_MSPDEINIT_CB_ID : - hcan->MspDeInitCallback = HAL_CAN_MspDeInit; - break; - - default : - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - return status; -} -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group2 Configuration functions - * @brief Configuration functions. - * -@verbatim - ============================================================================== - ##### Configuration functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) HAL_CAN_ConfigFilter : Configure the CAN reception filters - -@endverbatim - * @{ - */ - -/** - * @brief Configures the CAN reception filter according to the specified - * parameters in the CAN_FilterInitStruct. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param sFilterConfig pointer to a CAN_FilterTypeDef structure that - * contains the filter configuration information. - * @retval None - */ -HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef *hcan, CAN_FilterTypeDef *sFilterConfig) -{ - uint32_t filternbrbitpos; - CAN_TypeDef *can_ip = hcan->Instance; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check the parameters */ - assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterIdHigh)); - assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterIdLow)); - assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterMaskIdHigh)); - assert_param(IS_CAN_FILTER_ID_HALFWORD(sFilterConfig->FilterMaskIdLow)); - assert_param(IS_CAN_FILTER_MODE(sFilterConfig->FilterMode)); - assert_param(IS_CAN_FILTER_SCALE(sFilterConfig->FilterScale)); - assert_param(IS_CAN_FILTER_FIFO(sFilterConfig->FilterFIFOAssignment)); - assert_param(IS_CAN_FILTER_ACTIVATION(sFilterConfig->FilterActivation)); - -#if defined(CAN3) - /* Check the CAN instance */ - if (hcan->Instance == CAN3) - { - /* CAN3 is single instance with 14 dedicated filters banks */ - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_BANK_SINGLE(sFilterConfig->FilterBank)); - } - else - { - /* CAN1 and CAN2 are dual instances with 28 common filters banks */ - /* Select master instance to access the filter banks */ - can_ip = CAN1; - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->FilterBank)); - assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->SlaveStartFilterBank)); - } -#elif defined(CAN2) - /* CAN1 and CAN2 are dual instances with 28 common filters banks */ - /* Select master instance to access the filter banks */ - can_ip = CAN1; - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->FilterBank)); - assert_param(IS_CAN_FILTER_BANK_DUAL(sFilterConfig->SlaveStartFilterBank)); -#else - /* CAN1 is single instance with 14 dedicated filters banks */ - - /* Check the parameters */ - assert_param(IS_CAN_FILTER_BANK_SINGLE(sFilterConfig->FilterBank)); -#endif - - /* Initialisation mode for the filter */ - SET_BIT(can_ip->FMR, CAN_FMR_FINIT); - -#if defined(CAN3) - /* Check the CAN instance */ - if (can_ip == CAN1) - { - /* Select the start filter number of CAN2 slave instance */ - CLEAR_BIT(can_ip->FMR, CAN_FMR_CAN2SB); - SET_BIT(can_ip->FMR, sFilterConfig->SlaveStartFilterBank << CAN_FMR_CAN2SB_Pos); - } - -#elif defined(CAN2) - /* Select the start filter number of CAN2 slave instance */ - CLEAR_BIT(can_ip->FMR, CAN_FMR_CAN2SB); - SET_BIT(can_ip->FMR, sFilterConfig->SlaveStartFilterBank << CAN_FMR_CAN2SB_Pos); - -#endif - /* Convert filter number into bit position */ - filternbrbitpos = (uint32_t)1 << (sFilterConfig->FilterBank & 0x1FU); - - /* Filter Deactivation */ - CLEAR_BIT(can_ip->FA1R, filternbrbitpos); - - /* Filter Scale */ - if (sFilterConfig->FilterScale == CAN_FILTERSCALE_16BIT) - { - /* 16-bit scale for the filter */ - CLEAR_BIT(can_ip->FS1R, filternbrbitpos); - - /* First 16-bit identifier and First 16-bit mask */ - /* Or First 16-bit identifier and Second 16-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterBank].FR1 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); - - /* Second 16-bit identifier and Second 16-bit mask */ - /* Or Third 16-bit identifier and Fourth 16-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterBank].FR2 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh); - } - - if (sFilterConfig->FilterScale == CAN_FILTERSCALE_32BIT) - { - /* 32-bit scale for the filter */ - SET_BIT(can_ip->FS1R, filternbrbitpos); - - /* 32-bit identifier or First 32-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterBank].FR1 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterIdLow); - - /* 32-bit mask or Second 32-bit identifier */ - can_ip->sFilterRegister[sFilterConfig->FilterBank].FR2 = - ((0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdHigh) << 16U) | - (0x0000FFFFU & (uint32_t)sFilterConfig->FilterMaskIdLow); - } - - /* Filter Mode */ - if (sFilterConfig->FilterMode == CAN_FILTERMODE_IDMASK) - { - /* Id/Mask mode for the filter*/ - CLEAR_BIT(can_ip->FM1R, filternbrbitpos); - } - else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ - { - /* Identifier list mode for the filter*/ - SET_BIT(can_ip->FM1R, filternbrbitpos); - } - - /* Filter FIFO assignment */ - if (sFilterConfig->FilterFIFOAssignment == CAN_FILTER_FIFO0) - { - /* FIFO 0 assignation for the filter */ - CLEAR_BIT(can_ip->FFA1R, filternbrbitpos); - } - else - { - /* FIFO 1 assignation for the filter */ - SET_BIT(can_ip->FFA1R, filternbrbitpos); - } - - /* Filter activation */ - if (sFilterConfig->FilterActivation == CAN_FILTER_ENABLE) - { - SET_BIT(can_ip->FA1R, filternbrbitpos); - } - - /* Leave the initialisation mode for the filter */ - CLEAR_BIT(can_ip->FMR, CAN_FMR_FINIT); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group3 Control functions - * @brief Control functions - * -@verbatim - ============================================================================== - ##### Control functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) HAL_CAN_Start : Start the CAN module - (+) HAL_CAN_Stop : Stop the CAN module - (+) HAL_CAN_RequestSleep : Request sleep mode entry. - (+) HAL_CAN_WakeUp : Wake up from sleep mode. - (+) HAL_CAN_IsSleepActive : Check is sleep mode is active. - (+) HAL_CAN_AddTxMessage : Add a message to the Tx mailboxes - and activate the corresponding - transmission request - (+) HAL_CAN_AbortTxRequest : Abort transmission request - (+) HAL_CAN_GetTxMailboxesFreeLevel : Return Tx mailboxes free level - (+) HAL_CAN_IsTxMessagePending : Check if a transmission request is - pending on the selected Tx mailbox - (+) HAL_CAN_GetRxMessage : Get a CAN frame from the Rx FIFO - (+) HAL_CAN_GetRxFifoFillLevel : Return Rx FIFO fill level - -@endverbatim - * @{ - */ - -/** - * @brief Start the CAN module. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *hcan) -{ - uint32_t tickstart; - - if (hcan->State == HAL_CAN_STATE_READY) - { - /* Change CAN peripheral state */ - hcan->State = HAL_CAN_STATE_LISTENING; - - /* Request leave initialisation */ - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait the acknowledge */ - while ((hcan->Instance->MSR & CAN_MSR_INAK) != 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - return HAL_ERROR; - } - } - - /* Reset the CAN ErrorCode */ - hcan->ErrorCode = HAL_CAN_ERROR_NONE; - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_READY; - - return HAL_ERROR; - } -} - -/** - * @brief Stop the CAN module and enable access to configuration registers. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_Stop(CAN_HandleTypeDef *hcan) -{ - uint32_t tickstart; - - if (hcan->State == HAL_CAN_STATE_LISTENING) - { - /* Request initialisation */ - SET_BIT(hcan->Instance->MCR, CAN_MCR_INRQ); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait the acknowledge */ - while ((hcan->Instance->MSR & CAN_MSR_INAK) == 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > CAN_TIMEOUT_VALUE) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - /* Change CAN state */ - hcan->State = HAL_CAN_STATE_ERROR; - - return HAL_ERROR; - } - } - - /* Exit from sleep mode */ - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); - - /* Change CAN peripheral state */ - hcan->State = HAL_CAN_STATE_READY; - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_STARTED; - - return HAL_ERROR; - } -} - -/** - * @brief Request the sleep mode (low power) entry. - * When returning from this function, Sleep mode will be entered - * as soon as the current CAN activity (transmission or reception - * of a CAN frame) has been completed. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_CAN_RequestSleep(CAN_HandleTypeDef *hcan) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Request Sleep mode */ - SET_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - /* Return function status */ - return HAL_ERROR; - } -} - -/** - * @brief Wake up from sleep mode. - * When returning with HAL_OK status from this function, Sleep mode - * is exited. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan) -{ - __IO uint32_t count = 0; - uint32_t timeout = 1000000U; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Wake up request */ - CLEAR_BIT(hcan->Instance->MCR, CAN_MCR_SLEEP); - - /* Wait sleep mode is exited */ - do - { - /* Increment counter */ - count++; - - /* Check if timeout is reached */ - if (count > timeout) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_TIMEOUT; - - return HAL_ERROR; - } - } - while ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Check is sleep mode is active. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval Status - * - 0 : Sleep mode is not active. - * - 1 : Sleep mode is active. - */ -uint32_t HAL_CAN_IsSleepActive(CAN_HandleTypeDef *hcan) -{ - uint32_t status = 0U; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check Sleep mode */ - if ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) - { - status = 1U; - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Add a message to the first free Tx mailbox and activate the - * corresponding transmission request. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param pHeader pointer to a CAN_TxHeaderTypeDef structure. - * @param aData array containing the payload of the Tx frame. - * @param pTxMailbox pointer to a variable where the function will return - * the TxMailbox used to store the Tx message. - * This parameter can be a value of @arg CAN_Tx_Mailboxes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_AddTxMessage(CAN_HandleTypeDef *hcan, CAN_TxHeaderTypeDef *pHeader, uint8_t aData[], uint32_t *pTxMailbox) -{ - uint32_t transmitmailbox; - HAL_CAN_StateTypeDef state = hcan->State; - uint32_t tsr = READ_REG(hcan->Instance->TSR); - - /* Check the parameters */ - assert_param(IS_CAN_IDTYPE(pHeader->IDE)); - assert_param(IS_CAN_RTR(pHeader->RTR)); - assert_param(IS_CAN_DLC(pHeader->DLC)); - if (pHeader->IDE == CAN_ID_STD) - { - assert_param(IS_CAN_STDID(pHeader->StdId)); - } - else - { - assert_param(IS_CAN_EXTID(pHeader->ExtId)); - } - assert_param(IS_FUNCTIONAL_STATE(pHeader->TransmitGlobalTime)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check that all the Tx mailboxes are not full */ - if (((tsr & CAN_TSR_TME0) != 0U) || - ((tsr & CAN_TSR_TME1) != 0U) || - ((tsr & CAN_TSR_TME2) != 0U)) - { - /* Select an empty transmit mailbox */ - transmitmailbox = (tsr & CAN_TSR_CODE) >> CAN_TSR_CODE_Pos; - - /* Check transmit mailbox value */ - if (transmitmailbox > 2U) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_INTERNAL; - - return HAL_ERROR; - } - - /* Store the Tx mailbox */ - *pTxMailbox = (uint32_t)1 << transmitmailbox; - - /* Set up the Id */ - if (pHeader->IDE == CAN_ID_STD) - { - hcan->Instance->sTxMailBox[transmitmailbox].TIR = ((pHeader->StdId << CAN_TI0R_STID_Pos) | - pHeader->RTR); - } - else - { - hcan->Instance->sTxMailBox[transmitmailbox].TIR = ((pHeader->ExtId << CAN_TI0R_EXID_Pos) | - pHeader->IDE | - pHeader->RTR); - } - - /* Set up the DLC */ - hcan->Instance->sTxMailBox[transmitmailbox].TDTR = (pHeader->DLC); - - /* Set up the Transmit Global Time mode */ - if (pHeader->TransmitGlobalTime == ENABLE) - { - SET_BIT(hcan->Instance->sTxMailBox[transmitmailbox].TDTR, CAN_TDT0R_TGT); - } - - /* Set up the data field */ - WRITE_REG(hcan->Instance->sTxMailBox[transmitmailbox].TDHR, - ((uint32_t)aData[7] << CAN_TDH0R_DATA7_Pos) | - ((uint32_t)aData[6] << CAN_TDH0R_DATA6_Pos) | - ((uint32_t)aData[5] << CAN_TDH0R_DATA5_Pos) | - ((uint32_t)aData[4] << CAN_TDH0R_DATA4_Pos)); - WRITE_REG(hcan->Instance->sTxMailBox[transmitmailbox].TDLR, - ((uint32_t)aData[3] << CAN_TDL0R_DATA3_Pos) | - ((uint32_t)aData[2] << CAN_TDL0R_DATA2_Pos) | - ((uint32_t)aData[1] << CAN_TDL0R_DATA1_Pos) | - ((uint32_t)aData[0] << CAN_TDL0R_DATA0_Pos)); - - /* Request transmission */ - SET_BIT(hcan->Instance->sTxMailBox[transmitmailbox].TIR, CAN_TI0R_TXRQ); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; - - return HAL_ERROR; - } - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Abort transmission requests - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param TxMailboxes List of the Tx Mailboxes to abort. - * This parameter can be any combination of @arg CAN_Tx_Mailboxes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_AbortTxRequest(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_TX_MAILBOX_LIST(TxMailboxes)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check Tx Mailbox 0 */ - if ((TxMailboxes & CAN_TX_MAILBOX0) != 0U) - { - /* Add cancellation request for Tx Mailbox 0 */ - SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ0); - } - - /* Check Tx Mailbox 1 */ - if ((TxMailboxes & CAN_TX_MAILBOX1) != 0U) - { - /* Add cancellation request for Tx Mailbox 1 */ - SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ1); - } - - /* Check Tx Mailbox 2 */ - if ((TxMailboxes & CAN_TX_MAILBOX2) != 0U) - { - /* Add cancellation request for Tx Mailbox 2 */ - SET_BIT(hcan->Instance->TSR, CAN_TSR_ABRQ2); - } - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Return Tx Mailboxes free level: number of free Tx Mailboxes. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval Number of free Tx Mailboxes. - */ -uint32_t HAL_CAN_GetTxMailboxesFreeLevel(CAN_HandleTypeDef *hcan) -{ - uint32_t freelevel = 0U; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check Tx Mailbox 0 status */ - if ((hcan->Instance->TSR & CAN_TSR_TME0) != 0U) - { - freelevel++; - } - - /* Check Tx Mailbox 1 status */ - if ((hcan->Instance->TSR & CAN_TSR_TME1) != 0U) - { - freelevel++; - } - - /* Check Tx Mailbox 2 status */ - if ((hcan->Instance->TSR & CAN_TSR_TME2) != 0U) - { - freelevel++; - } - } - - /* Return Tx Mailboxes free level */ - return freelevel; -} - -/** - * @brief Check if a transmission request is pending on the selected Tx - * Mailboxes. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param TxMailboxes List of Tx Mailboxes to check. - * This parameter can be any combination of @arg CAN_Tx_Mailboxes. - * @retval Status - * - 0 : No pending transmission request on any selected Tx Mailboxes. - * - 1 : Pending transmission request on at least one of the selected - * Tx Mailbox. - */ -uint32_t HAL_CAN_IsTxMessagePending(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes) -{ - uint32_t status = 0U; - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_TX_MAILBOX_LIST(TxMailboxes)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check pending transmission request on the selected Tx Mailboxes */ - if ((hcan->Instance->TSR & (TxMailboxes << CAN_TSR_TME0_Pos)) != (TxMailboxes << CAN_TSR_TME0_Pos)) - { - status = 1U; - } - } - - /* Return status */ - return status; -} - -/** - * @brief Return timestamp of Tx message sent, if time triggered communication - mode is enabled. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param TxMailbox Tx Mailbox where the timestamp of message sent will be - * read. - * This parameter can be one value of @arg CAN_Tx_Mailboxes. - * @retval Timestamp of message sent from Tx Mailbox. - */ -uint32_t HAL_CAN_GetTxTimestamp(CAN_HandleTypeDef *hcan, uint32_t TxMailbox) -{ - uint32_t timestamp = 0U; - uint32_t transmitmailbox; - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_TX_MAILBOX(TxMailbox)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Select the Tx mailbox */ - transmitmailbox = POSITION_VAL(TxMailbox); - - /* Get timestamp */ - timestamp = (hcan->Instance->sTxMailBox[transmitmailbox].TDTR & CAN_TDT0R_TIME) >> CAN_TDT0R_TIME_Pos; - } - - /* Return the timestamp */ - return timestamp; -} - -/** - * @brief Get an CAN frame from the Rx FIFO zone into the message RAM. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param RxFifo Fifo number of the received message to be read. - * This parameter can be a value of @arg CAN_receive_FIFO_number. - * @param pHeader pointer to a CAN_RxHeaderTypeDef structure where the header - * of the Rx frame will be stored. - * @param aData array where the payload of the Rx frame will be stored. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_GetRxMessage(CAN_HandleTypeDef *hcan, uint32_t RxFifo, CAN_RxHeaderTypeDef *pHeader, uint8_t aData[]) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - assert_param(IS_CAN_RX_FIFO(RxFifo)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check the Rx FIFO */ - if (RxFifo == CAN_RX_FIFO0) /* Rx element is assigned to Rx FIFO 0 */ - { - /* Check that the Rx FIFO 0 is not empty */ - if ((hcan->Instance->RF0R & CAN_RF0R_FMP0) == 0U) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; - - return HAL_ERROR; - } - } - else /* Rx element is assigned to Rx FIFO 1 */ - { - /* Check that the Rx FIFO 1 is not empty */ - if ((hcan->Instance->RF1R & CAN_RF1R_FMP1) == 0U) - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_PARAM; - - return HAL_ERROR; - } - } - - /* Get the header */ - pHeader->IDE = CAN_RI0R_IDE & hcan->Instance->sFIFOMailBox[RxFifo].RIR; - if (pHeader->IDE == CAN_ID_STD) - { - pHeader->StdId = (CAN_RI0R_STID & hcan->Instance->sFIFOMailBox[RxFifo].RIR) >> CAN_TI0R_STID_Pos; - } - else - { - pHeader->ExtId = ((CAN_RI0R_EXID | CAN_RI0R_STID) & hcan->Instance->sFIFOMailBox[RxFifo].RIR) >> CAN_RI0R_EXID_Pos; - } - pHeader->RTR = (CAN_RI0R_RTR & hcan->Instance->sFIFOMailBox[RxFifo].RIR); - pHeader->DLC = (CAN_RDT0R_DLC & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_DLC_Pos; - pHeader->FilterMatchIndex = (CAN_RDT0R_FMI & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_FMI_Pos; - pHeader->Timestamp = (CAN_RDT0R_TIME & hcan->Instance->sFIFOMailBox[RxFifo].RDTR) >> CAN_RDT0R_TIME_Pos; - - /* Get the data */ - aData[0] = (uint8_t)((CAN_RDL0R_DATA0 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA0_Pos); - aData[1] = (uint8_t)((CAN_RDL0R_DATA1 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA1_Pos); - aData[2] = (uint8_t)((CAN_RDL0R_DATA2 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA2_Pos); - aData[3] = (uint8_t)((CAN_RDL0R_DATA3 & hcan->Instance->sFIFOMailBox[RxFifo].RDLR) >> CAN_RDL0R_DATA3_Pos); - aData[4] = (uint8_t)((CAN_RDH0R_DATA4 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA4_Pos); - aData[5] = (uint8_t)((CAN_RDH0R_DATA5 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA5_Pos); - aData[6] = (uint8_t)((CAN_RDH0R_DATA6 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA6_Pos); - aData[7] = (uint8_t)((CAN_RDH0R_DATA7 & hcan->Instance->sFIFOMailBox[RxFifo].RDHR) >> CAN_RDH0R_DATA7_Pos); - - /* Release the FIFO */ - if (RxFifo == CAN_RX_FIFO0) /* Rx element is assigned to Rx FIFO 0 */ - { - /* Release RX FIFO 0 */ - SET_BIT(hcan->Instance->RF0R, CAN_RF0R_RFOM0); - } - else /* Rx element is assigned to Rx FIFO 1 */ - { - /* Release RX FIFO 1 */ - SET_BIT(hcan->Instance->RF1R, CAN_RF1R_RFOM1); - } - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Return Rx FIFO fill level. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param RxFifo Rx FIFO. - * This parameter can be a value of @arg CAN_receive_FIFO_number. - * @retval Number of messages available in Rx FIFO. - */ -uint32_t HAL_CAN_GetRxFifoFillLevel(CAN_HandleTypeDef *hcan, uint32_t RxFifo) -{ - uint32_t filllevel = 0U; - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_RX_FIFO(RxFifo)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - if (RxFifo == CAN_RX_FIFO0) - { - filllevel = hcan->Instance->RF0R & CAN_RF0R_FMP0; - } - else /* RxFifo == CAN_RX_FIFO1 */ - { - filllevel = hcan->Instance->RF1R & CAN_RF1R_FMP1; - } - } - - /* Return Rx FIFO fill level */ - return filllevel; -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group4 Interrupts management - * @brief Interrupts management - * -@verbatim - ============================================================================== - ##### Interrupts management ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) HAL_CAN_ActivateNotification : Enable interrupts - (+) HAL_CAN_DeactivateNotification : Disable interrupts - (+) HAL_CAN_IRQHandler : Handles CAN interrupt request - -@endverbatim - * @{ - */ - -/** - * @brief Enable interrupts. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param ActiveITs indicates which interrupts will be enabled. - * This parameter can be any combination of @arg CAN_Interrupts. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *hcan, uint32_t ActiveITs) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_IT(ActiveITs)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Enable the selected interrupts */ - __HAL_CAN_ENABLE_IT(hcan, ActiveITs); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Disable interrupts. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @param InactiveITs indicates which interrupts will be disabled. - * This parameter can be any combination of @arg CAN_Interrupts. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_DeactivateNotification(CAN_HandleTypeDef *hcan, uint32_t InactiveITs) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - /* Check function parameters */ - assert_param(IS_CAN_IT(InactiveITs)); - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Disable the selected interrupts */ - __HAL_CAN_DISABLE_IT(hcan, InactiveITs); - - /* Return function status */ - return HAL_OK; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - return HAL_ERROR; - } -} - -/** - * @brief Handles CAN interrupt request - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -void HAL_CAN_IRQHandler(CAN_HandleTypeDef *hcan) -{ - uint32_t errorcode = HAL_CAN_ERROR_NONE; - uint32_t interrupts = READ_REG(hcan->Instance->IER); - uint32_t msrflags = READ_REG(hcan->Instance->MSR); - uint32_t tsrflags = READ_REG(hcan->Instance->TSR); - uint32_t rf0rflags = READ_REG(hcan->Instance->RF0R); - uint32_t rf1rflags = READ_REG(hcan->Instance->RF1R); - uint32_t esrflags = READ_REG(hcan->Instance->ESR); - - /* Transmit Mailbox empty interrupt management *****************************/ - if ((interrupts & CAN_IT_TX_MAILBOX_EMPTY) != 0U) - { - /* Transmit Mailbox 0 management *****************************************/ - if ((tsrflags & CAN_TSR_RQCP0) != 0U) - { - /* Clear the Transmission Complete flag (and TXOK0,ALST0,TERR0 bits) */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP0); - - if ((tsrflags & CAN_TSR_TXOK0) != 0U) - { - /* Transmission Mailbox 0 complete callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox0CompleteCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox0CompleteCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - else - { - if ((tsrflags & CAN_TSR_ALST0) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_ALST0; - } - else if ((tsrflags & CAN_TSR_TERR0) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_TERR0; - } - else - { - /* Transmission Mailbox 0 abort callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox0AbortCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox0AbortCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - } - - /* Transmit Mailbox 1 management *****************************************/ - if ((tsrflags & CAN_TSR_RQCP1) != 0U) - { - /* Clear the Transmission Complete flag (and TXOK1,ALST1,TERR1 bits) */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP1); - - if ((tsrflags & CAN_TSR_TXOK1) != 0U) - { - /* Transmission Mailbox 1 complete callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox1CompleteCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox1CompleteCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - else - { - if ((tsrflags & CAN_TSR_ALST1) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_ALST1; - } - else if ((tsrflags & CAN_TSR_TERR1) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_TERR1; - } - else - { - /* Transmission Mailbox 1 abort callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox1AbortCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox1AbortCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - } - - /* Transmit Mailbox 2 management *****************************************/ - if ((tsrflags & CAN_TSR_RQCP2) != 0U) - { - /* Clear the Transmission Complete flag (and TXOK2,ALST2,TERR2 bits) */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_RQCP2); - - if ((tsrflags & CAN_TSR_TXOK2) != 0U) - { - /* Transmission Mailbox 2 complete callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox2CompleteCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox2CompleteCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - else - { - if ((tsrflags & CAN_TSR_ALST2) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_ALST2; - } - else if ((tsrflags & CAN_TSR_TERR2) != 0U) - { - /* Update error code */ - errorcode |= HAL_CAN_ERROR_TX_TERR2; - } - else - { - /* Transmission Mailbox 2 abort callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->TxMailbox2AbortCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_TxMailbox2AbortCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - } - } - - /* Receive FIFO 0 overrun interrupt management *****************************/ - if ((interrupts & CAN_IT_RX_FIFO0_OVERRUN) != 0U) - { - if ((rf0rflags & CAN_RF0R_FOVR0) != 0U) - { - /* Set CAN error code to Rx Fifo 0 overrun error */ - errorcode |= HAL_CAN_ERROR_RX_FOV0; - - /* Clear FIFO0 Overrun Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV0); - } - } - - /* Receive FIFO 0 full interrupt management ********************************/ - if ((interrupts & CAN_IT_RX_FIFO0_FULL) != 0U) - { - if ((rf0rflags & CAN_RF0R_FULL0) != 0U) - { - /* Clear FIFO 0 full Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FF0); - - /* Receive FIFO 0 full Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->RxFifo0FullCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_RxFifo0FullCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Receive FIFO 0 message pending interrupt management *********************/ - if ((interrupts & CAN_IT_RX_FIFO0_MSG_PENDING) != 0U) - { - /* Check if message is still pending */ - if ((hcan->Instance->RF0R & CAN_RF0R_FMP0) != 0U) - { - /* Receive FIFO 0 message pending Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->RxFifo0MsgPendingCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_RxFifo0MsgPendingCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Receive FIFO 1 overrun interrupt management *****************************/ - if ((interrupts & CAN_IT_RX_FIFO1_OVERRUN) != 0U) - { - if ((rf1rflags & CAN_RF1R_FOVR1) != 0U) - { - /* Set CAN error code to Rx Fifo 1 overrun error */ - errorcode |= HAL_CAN_ERROR_RX_FOV1; - - /* Clear FIFO1 Overrun Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FOV1); - } - } - - /* Receive FIFO 1 full interrupt management ********************************/ - if ((interrupts & CAN_IT_RX_FIFO1_FULL) != 0U) - { - if ((rf1rflags & CAN_RF1R_FULL1) != 0U) - { - /* Clear FIFO 1 full Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_FF1); - - /* Receive FIFO 1 full Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->RxFifo1FullCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_RxFifo1FullCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Receive FIFO 1 message pending interrupt management *********************/ - if ((interrupts & CAN_IT_RX_FIFO1_MSG_PENDING) != 0U) - { - /* Check if message is still pending */ - if ((hcan->Instance->RF1R & CAN_RF1R_FMP1) != 0U) - { - /* Receive FIFO 1 message pending Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->RxFifo1MsgPendingCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_RxFifo1MsgPendingCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Sleep interrupt management *********************************************/ - if ((interrupts & CAN_IT_SLEEP_ACK) != 0U) - { - if ((msrflags & CAN_MSR_SLAKI) != 0U) - { - /* Clear Sleep interrupt Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_SLAKI); - - /* Sleep Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->SleepCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_SleepCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* WakeUp interrupt management *********************************************/ - if ((interrupts & CAN_IT_WAKEUP) != 0U) - { - if ((msrflags & CAN_MSR_WKUI) != 0U) - { - /* Clear WakeUp Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_WKU); - - /* WakeUp Callback */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->WakeUpFromRxMsgCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_WakeUpFromRxMsgCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } - } - - /* Error interrupts management *********************************************/ - if ((interrupts & CAN_IT_ERROR) != 0U) - { - if ((msrflags & CAN_MSR_ERRI) != 0U) - { - /* Check Error Warning Flag */ - if (((interrupts & CAN_IT_ERROR_WARNING) != 0U) && - ((esrflags & CAN_ESR_EWGF) != 0U)) - { - /* Set CAN error code to Error Warning */ - errorcode |= HAL_CAN_ERROR_EWG; - - /* No need for clear of Error Warning Flag as read-only */ - } - - /* Check Error Passive Flag */ - if (((interrupts & CAN_IT_ERROR_PASSIVE) != 0U) && - ((esrflags & CAN_ESR_EPVF) != 0U)) - { - /* Set CAN error code to Error Passive */ - errorcode |= HAL_CAN_ERROR_EPV; - - /* No need for clear of Error Passive Flag as read-only */ - } - - /* Check Bus-off Flag */ - if (((interrupts & CAN_IT_BUSOFF) != 0U) && - ((esrflags & CAN_ESR_BOFF) != 0U)) - { - /* Set CAN error code to Bus-Off */ - errorcode |= HAL_CAN_ERROR_BOF; - - /* No need for clear of Error Bus-Off as read-only */ - } - - /* Check Last Error Code Flag */ - if (((interrupts & CAN_IT_LAST_ERROR_CODE) != 0U) && - ((esrflags & CAN_ESR_LEC) != 0U)) - { - switch (esrflags & CAN_ESR_LEC) - { - case (CAN_ESR_LEC_0): - /* Set CAN error code to Stuff error */ - errorcode |= HAL_CAN_ERROR_STF; - break; - case (CAN_ESR_LEC_1): - /* Set CAN error code to Form error */ - errorcode |= HAL_CAN_ERROR_FOR; - break; - case (CAN_ESR_LEC_1 | CAN_ESR_LEC_0): - /* Set CAN error code to Acknowledgement error */ - errorcode |= HAL_CAN_ERROR_ACK; - break; - case (CAN_ESR_LEC_2): - /* Set CAN error code to Bit recessive error */ - errorcode |= HAL_CAN_ERROR_BR; - break; - case (CAN_ESR_LEC_2 | CAN_ESR_LEC_0): - /* Set CAN error code to Bit Dominant error */ - errorcode |= HAL_CAN_ERROR_BD; - break; - case (CAN_ESR_LEC_2 | CAN_ESR_LEC_1): - /* Set CAN error code to CRC error */ - errorcode |= HAL_CAN_ERROR_CRC; - break; - default: - break; - } - - /* Clear Last error code Flag */ - CLEAR_BIT(hcan->Instance->ESR, CAN_ESR_LEC); - } - } - - /* Clear ERRI Flag */ - __HAL_CAN_CLEAR_FLAG(hcan, CAN_FLAG_ERRI); - } - - /* Call the Error call Back in case of Errors */ - if (errorcode != HAL_CAN_ERROR_NONE) - { - /* Update error code in handle */ - hcan->ErrorCode |= errorcode; - - /* Call Error callback function */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - /* Call registered callback*/ - hcan->ErrorCallback(hcan); -#else - /* Call weak (surcharged) callback */ - HAL_CAN_ErrorCallback(hcan); -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ - } -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group5 Callback functions - * @brief CAN Callback functions - * -@verbatim - ============================================================================== - ##### Callback functions ##### - ============================================================================== - [..] - This subsection provides the following callback functions: - (+) HAL_CAN_TxMailbox0CompleteCallback - (+) HAL_CAN_TxMailbox1CompleteCallback - (+) HAL_CAN_TxMailbox2CompleteCallback - (+) HAL_CAN_TxMailbox0AbortCallback - (+) HAL_CAN_TxMailbox1AbortCallback - (+) HAL_CAN_TxMailbox2AbortCallback - (+) HAL_CAN_RxFifo0MsgPendingCallback - (+) HAL_CAN_RxFifo0FullCallback - (+) HAL_CAN_RxFifo1MsgPendingCallback - (+) HAL_CAN_RxFifo1FullCallback - (+) HAL_CAN_SleepCallback - (+) HAL_CAN_WakeUpFromRxMsgCallback - (+) HAL_CAN_ErrorCallback - -@endverbatim - * @{ - */ - -/** - * @brief Transmission Mailbox 0 complete callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox0CompleteCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 1 complete callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox1CompleteCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 2 complete callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox2CompleteCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 0 Cancellation callback. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox0AbortCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 1 Cancellation callback. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox1AbortCallback could be implemented in the - user file - */ -} - -/** - * @brief Transmission Mailbox 2 Cancellation callback. - * @param hcan pointer to an CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_TxMailbox2AbortCallback could be implemented in the - user file - */ -} - -/** - * @brief Rx FIFO 0 message pending callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxFifo0MsgPendingCallback could be implemented in the - user file - */ -} - -/** - * @brief Rx FIFO 0 full callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxFifo0FullCallback could be implemented in the user - file - */ -} - -/** - * @brief Rx FIFO 1 message pending callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxFifo1MsgPendingCallback could be implemented in the - user file - */ -} - -/** - * @brief Rx FIFO 1 full callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_RxFifo1FullCallback could be implemented in the user - file - */ -} - -/** - * @brief Sleep callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_SleepCallback could be implemented in the user file - */ -} - -/** - * @brief WakeUp from Rx message callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_WakeUpFromRxMsgCallback could be implemented in the - user file - */ -} - -/** - * @brief Error CAN callback. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval None - */ -__weak void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcan); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CAN_ErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions_Group6 Peripheral State and Error functions - * @brief CAN Peripheral State functions - * -@verbatim - ============================================================================== - ##### Peripheral State and Error functions ##### - ============================================================================== - [..] - This subsection provides functions allowing to : - (+) HAL_CAN_GetState() : Return the CAN state. - (+) HAL_CAN_GetError() : Return the CAN error codes if any. - (+) HAL_CAN_ResetError(): Reset the CAN error codes if any. - -@endverbatim - * @{ - */ - -/** - * @brief Return the CAN state. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL state - */ -HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef *hcan) -{ - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Check sleep mode acknowledge flag */ - if ((hcan->Instance->MSR & CAN_MSR_SLAK) != 0U) - { - /* Sleep mode is active */ - state = HAL_CAN_STATE_SLEEP_ACTIVE; - } - /* Check sleep mode request flag */ - else if ((hcan->Instance->MCR & CAN_MCR_SLEEP) != 0U) - { - /* Sleep mode request is pending */ - state = HAL_CAN_STATE_SLEEP_PENDING; - } - else - { - /* Neither sleep mode request nor sleep mode acknowledge */ - } - } - - /* Return CAN state */ - return state; -} - -/** - * @brief Return the CAN error code. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval CAN Error Code - */ -uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan) -{ - /* Return CAN error code */ - return hcan->ErrorCode; -} - -/** - * @brief Reset the CAN error code. - * @param hcan pointer to a CAN_HandleTypeDef structure that contains - * the configuration information for the specified CAN. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CAN_ResetError(CAN_HandleTypeDef *hcan) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_CAN_StateTypeDef state = hcan->State; - - if ((state == HAL_CAN_STATE_READY) || - (state == HAL_CAN_STATE_LISTENING)) - { - /* Reset CAN error code */ - hcan->ErrorCode = 0U; - } - else - { - /* Update error code */ - hcan->ErrorCode |= HAL_CAN_ERROR_NOT_INITIALIZED; - - status = HAL_ERROR; - } - - /* Return the status */ - return status; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_CAN_MODULE_ENABLED */ - -/** - * @} - */ - -#endif /* CAN1 */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cec.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cec.c deleted file mode 100644 index c599bcfc4a3ec1a..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cec.c +++ /dev/null @@ -1,997 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cec.c - * @author MCD Application Team - * @brief CEC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the High Definition Multimedia Interface - * Consumer Electronics Control Peripheral (CEC). - * + Initialization and de-initialization function - * + IO operation function - * + Peripheral Control function - * - * - @verbatim - =============================================================================== - ##### How to use this driver ##### - =============================================================================== - [..] - The CEC HAL driver can be used as follow: - - (#) Declare a CEC_HandleTypeDef handle structure. - (#) Initialize the CEC low level resources by implementing the HAL_CEC_MspInit ()API: - (##) Enable the CEC interface clock. - (##) CEC pins configuration: - (+++) Enable the clock for the CEC GPIOs. - (+++) Configure these CEC pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_CEC_Transmit_IT() - and HAL_CEC_Receive_IT() APIs): - (+++) Configure the CEC interrupt priority. - (+++) Enable the NVIC CEC IRQ handle. - (+++) The specific CEC interrupts (Transmission complete interrupt, - RXNE interrupt and Error Interrupts) will be managed using the macros - __HAL_CEC_ENABLE_IT() and __HAL_CEC_DISABLE_IT() inside the transmit - and receive process. - - (#) Program the Signal Free Time (SFT) and SFT option, Tolerance, reception stop in - in case of Bit Rising Error, Error-Bit generation conditions, device logical - address and Listen mode in the hcec Init structure. - - (#) Initialize the CEC registers by calling the HAL_CEC_Init() API. - - [..] - (@) This API (HAL_CEC_Init()) configures also the low level Hardware (GPIO, CLOCK, CORTEX...etc) - by calling the customed HAL_CEC_MspInit() API. - *** Callback registration *** - ============================================= - - The compilation define USE_HAL_CEC_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_CEC_RegisterCallback() or HAL_CEC_RegisterXXXCallback() - to register an interrupt callback. - - Function HAL_CEC_RegisterCallback() allows to register following callbacks: - (+) TxCpltCallback : Tx Transfer completed callback. - (+) ErrorCallback : callback for error detection. - (+) MspInitCallback : CEC MspInit. - (+) MspDeInitCallback : CEC MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - For specific callback HAL_CEC_RxCpltCallback use dedicated register callbacks - HAL_CEC_RegisterRxCpltCallback(). - - Use function HAL_CEC_UnRegisterCallback() to reset a callback to the default - weak function. - HAL_CEC_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxCpltCallback : Tx Transfer completed callback. - (+) ErrorCallback : callback for error detection. - (+) MspInitCallback : CEC MspInit. - (+) MspDeInitCallback : CEC MspDeInit. - - For callback HAL_CEC_RxCpltCallback use dedicated unregister callback : - HAL_CEC_UnRegisterRxCpltCallback(). - - By default, after the HAL_CEC_Init() and when the state is HAL_CEC_STATE_RESET - all callbacks are set to the corresponding weak functions : - examples HAL_CEC_TxCpltCallback() , HAL_CEC_RxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak function in the HAL_CEC_Init()/ HAL_CEC_DeInit() only when - these callbacks are null (not registered beforehand). - if not, MspInit or MspDeInit are not null, the HAL_CEC_Init() / HAL_CEC_DeInit() - keep and use the user MspInit/MspDeInit functions (registered beforehand) - - Callbacks can be registered/unregistered in HAL_CEC_STATE_READY state only. - Exception done MspInit/MspDeInit callbacks that can be registered/unregistered - in HAL_CEC_STATE_READY or HAL_CEC_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_CEC_RegisterCallback() before calling HAL_CEC_DeInit() - or HAL_CEC_Init() function. - - When the compilation define USE_HAL_CEC_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup CEC CEC - * @brief HAL CEC module driver - * @{ - */ -#ifdef HAL_CEC_MODULE_ENABLED -#if defined (CEC) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup CEC_Private_Constants CEC Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup CEC_Private_Functions CEC Private Functions - * @{ - */ -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ - -/** @defgroup CEC_Exported_Functions CEC Exported Functions - * @{ - */ - -/** @defgroup CEC_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim -=============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to initialize the CEC - (+) The following parameters need to be configured: - (++) SignalFreeTime - (++) Tolerance - (++) BRERxStop (RX stopped or not upon Bit Rising Error) - (++) BREErrorBitGen (Error-Bit generation in case of Bit Rising Error) - (++) LBPEErrorBitGen (Error-Bit generation in case of Long Bit Period Error) - (++) BroadcastMsgNoErrorBitGen (Error-bit generation in case of broadcast message error) - (++) SignalFreeTimeOption (SFT Timer start definition) - (++) OwnAddress (CEC device address) - (++) ListenMode - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the CEC mode according to the specified - * parameters in the CEC_InitTypeDef and creates the associated handle . - * @param hcec CEC handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CEC_Init(CEC_HandleTypeDef *hcec) -{ - /* Check the CEC handle allocation */ - if ((hcec == NULL) || (hcec->Init.RxBuffer == NULL)) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CEC_ALL_INSTANCE(hcec->Instance)); - assert_param(IS_CEC_SIGNALFREETIME(hcec->Init.SignalFreeTime)); - assert_param(IS_CEC_TOLERANCE(hcec->Init.Tolerance)); - assert_param(IS_CEC_BRERXSTOP(hcec->Init.BRERxStop)); - assert_param(IS_CEC_BREERRORBITGEN(hcec->Init.BREErrorBitGen)); - assert_param(IS_CEC_LBPEERRORBITGEN(hcec->Init.LBPEErrorBitGen)); - assert_param(IS_CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION(hcec->Init.BroadcastMsgNoErrorBitGen)); - assert_param(IS_CEC_SFTOP(hcec->Init.SignalFreeTimeOption)); - assert_param(IS_CEC_LISTENING_MODE(hcec->Init.ListenMode)); - assert_param(IS_CEC_OWN_ADDRESS(hcec->Init.OwnAddress)); - -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) - if (hcec->gState == HAL_CEC_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hcec->Lock = HAL_UNLOCKED; - - hcec->TxCpltCallback = HAL_CEC_TxCpltCallback; /* Legacy weak TxCpltCallback */ - hcec->RxCpltCallback = HAL_CEC_RxCpltCallback; /* Legacy weak RxCpltCallback */ - hcec->ErrorCallback = HAL_CEC_ErrorCallback; /* Legacy weak ErrorCallback */ - - if (hcec->MspInitCallback == NULL) - { - hcec->MspInitCallback = HAL_CEC_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware */ - hcec->MspInitCallback(hcec); - } -#else - if (hcec->gState == HAL_CEC_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hcec->Lock = HAL_UNLOCKED; - /* Init the low level hardware : GPIO, CLOCK */ - HAL_CEC_MspInit(hcec); - } -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ - - hcec->gState = HAL_CEC_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_CEC_DISABLE(hcec); - - /* Write to CEC Control Register */ - hcec->Instance->CFGR = hcec->Init.SignalFreeTime | hcec->Init.Tolerance | hcec->Init.BRERxStop | \ - hcec->Init.BREErrorBitGen | hcec->Init.LBPEErrorBitGen | hcec->Init.BroadcastMsgNoErrorBitGen | \ - hcec->Init.SignalFreeTimeOption | ((uint32_t)(hcec->Init.OwnAddress) << 16U) | \ - hcec->Init.ListenMode; - - /* Enable the following CEC Transmission/Reception interrupts as - * well as the following CEC Transmission/Reception Errors interrupts - * Rx Byte Received IT - * End of Reception IT - * Rx overrun - * Rx bit rising error - * Rx short bit period error - * Rx long bit period error - * Rx missing acknowledge - * Tx Byte Request IT - * End of Transmission IT - * Tx Missing Acknowledge IT - * Tx-Error IT - * Tx-Buffer Underrun IT - * Tx arbitration lost */ - __HAL_CEC_ENABLE_IT(hcec, CEC_IT_RXBR | CEC_IT_RXEND | CEC_IER_RX_ALL_ERR | CEC_IT_TXBR | CEC_IT_TXEND | - CEC_IER_TX_ALL_ERR); - - /* Enable the CEC Peripheral */ - __HAL_CEC_ENABLE(hcec); - - hcec->ErrorCode = HAL_CEC_ERROR_NONE; - hcec->gState = HAL_CEC_STATE_READY; - hcec->RxState = HAL_CEC_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the CEC peripheral - * @param hcec CEC handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CEC_DeInit(CEC_HandleTypeDef *hcec) -{ - /* Check the CEC handle allocation */ - if (hcec == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CEC_ALL_INSTANCE(hcec->Instance)); - - hcec->gState = HAL_CEC_STATE_BUSY; - -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) - if (hcec->MspDeInitCallback == NULL) - { - hcec->MspDeInitCallback = HAL_CEC_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware */ - hcec->MspDeInitCallback(hcec); - -#else - /* DeInit the low level hardware */ - HAL_CEC_MspDeInit(hcec); -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ - - /* Disable the Peripheral */ - __HAL_CEC_DISABLE(hcec); - - /* Clear Flags */ - __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_TXEND | CEC_FLAG_TXBR | CEC_FLAG_RXBR | CEC_FLAG_RXEND | CEC_ISR_ALL_ERROR); - - /* Disable the following CEC Transmission/Reception interrupts as - * well as the following CEC Transmission/Reception Errors interrupts - * Rx Byte Received IT - * End of Reception IT - * Rx overrun - * Rx bit rising error - * Rx short bit period error - * Rx long bit period error - * Rx missing acknowledge - * Tx Byte Request IT - * End of Transmission IT - * Tx Missing Acknowledge IT - * Tx-Error IT - * Tx-Buffer Underrun IT - * Tx arbitration lost */ - __HAL_CEC_DISABLE_IT(hcec, CEC_IT_RXBR | CEC_IT_RXEND | CEC_IER_RX_ALL_ERR | CEC_IT_TXBR | CEC_IT_TXEND | - CEC_IER_TX_ALL_ERR); - - hcec->ErrorCode = HAL_CEC_ERROR_NONE; - hcec->gState = HAL_CEC_STATE_RESET; - hcec->RxState = HAL_CEC_STATE_RESET; - - /* Process Unlock */ - __HAL_UNLOCK(hcec); - - return HAL_OK; -} - -/** - * @brief Initializes the Own Address of the CEC device - * @param hcec CEC handle - * @param CEC_OwnAddress The CEC own address. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CEC_SetDeviceAddress(CEC_HandleTypeDef *hcec, uint16_t CEC_OwnAddress) -{ - /* Check the parameters */ - assert_param(IS_CEC_OWN_ADDRESS(CEC_OwnAddress)); - - if ((hcec->gState == HAL_CEC_STATE_READY) && (hcec->RxState == HAL_CEC_STATE_READY)) - { - /* Process Locked */ - __HAL_LOCK(hcec); - - hcec->gState = HAL_CEC_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_CEC_DISABLE(hcec); - - if (CEC_OwnAddress != CEC_OWN_ADDRESS_NONE) - { - hcec->Instance->CFGR |= ((uint32_t)CEC_OwnAddress << 16); - } - else - { - hcec->Instance->CFGR &= ~(CEC_CFGR_OAR); - } - - hcec->gState = HAL_CEC_STATE_READY; - hcec->ErrorCode = HAL_CEC_ERROR_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hcec); - - /* Enable the Peripheral */ - __HAL_CEC_ENABLE(hcec); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief CEC MSP Init - * @param hcec CEC handle - * @retval None - */ -__weak void HAL_CEC_MspInit(CEC_HandleTypeDef *hcec) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcec); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CEC_MspInit can be implemented in the user file - */ -} - -/** - * @brief CEC MSP DeInit - * @param hcec CEC handle - * @retval None - */ -__weak void HAL_CEC_MspDeInit(CEC_HandleTypeDef *hcec) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcec); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CEC_MspDeInit can be implemented in the user file - */ -} -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User CEC Callback - * To be used instead of the weak predefined callback - * @param hcec CEC handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_CEC_TX_CPLT_CB_ID Tx Complete callback ID - * @arg @ref HAL_CEC_ERROR_CB_ID Error callback ID - * @arg @ref HAL_CEC_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_CEC_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CEC_RegisterCallback(CEC_HandleTypeDef *hcec, HAL_CEC_CallbackIDTypeDef CallbackID, - pCEC_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hcec); - - if (hcec->gState == HAL_CEC_STATE_READY) - { - switch (CallbackID) - { - case HAL_CEC_TX_CPLT_CB_ID : - hcec->TxCpltCallback = pCallback; - break; - - case HAL_CEC_ERROR_CB_ID : - hcec->ErrorCallback = pCallback; - break; - - case HAL_CEC_MSPINIT_CB_ID : - hcec->MspInitCallback = pCallback; - break; - - case HAL_CEC_MSPDEINIT_CB_ID : - hcec->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hcec->gState == HAL_CEC_STATE_RESET) - { - switch (CallbackID) - { - case HAL_CEC_MSPINIT_CB_ID : - hcec->MspInitCallback = pCallback; - break; - - case HAL_CEC_MSPDEINIT_CB_ID : - hcec->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hcec); - - return status; -} - -/** - * @brief Unregister an CEC Callback - * CEC callabck is redirected to the weak predefined callback - * @param hcec uart handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_CEC_TX_CPLT_CB_ID Tx Complete callback ID - * @arg @ref HAL_CEC_ERROR_CB_ID Error callback ID - * @arg @ref HAL_CEC_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_CEC_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_CEC_UnRegisterCallback(CEC_HandleTypeDef *hcec, HAL_CEC_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hcec); - - if (hcec->gState == HAL_CEC_STATE_READY) - { - switch (CallbackID) - { - case HAL_CEC_TX_CPLT_CB_ID : - hcec->TxCpltCallback = HAL_CEC_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_CEC_ERROR_CB_ID : - hcec->ErrorCallback = HAL_CEC_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_CEC_MSPINIT_CB_ID : - hcec->MspInitCallback = HAL_CEC_MspInit; - break; - - case HAL_CEC_MSPDEINIT_CB_ID : - hcec->MspDeInitCallback = HAL_CEC_MspDeInit; - break; - - default : - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hcec->gState == HAL_CEC_STATE_RESET) - { - switch (CallbackID) - { - case HAL_CEC_MSPINIT_CB_ID : - hcec->MspInitCallback = HAL_CEC_MspInit; - break; - - case HAL_CEC_MSPDEINIT_CB_ID : - hcec->MspDeInitCallback = HAL_CEC_MspDeInit; - break; - - default : - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hcec); - - return status; -} - -/** - * @brief Register CEC RX complete Callback - * To be used instead of the weak HAL_CEC_RxCpltCallback() predefined callback - * @param hcec CEC handle - * @param pCallback pointer to the Rx transfer compelete Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CEC_RegisterRxCpltCallback(CEC_HandleTypeDef *hcec, pCEC_RxCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hcec); - - if (HAL_CEC_STATE_READY == hcec->RxState) - { - hcec->RxCpltCallback = pCallback; - } - else - { - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hcec); - return status; -} - -/** - * @brief UnRegister CEC RX complete Callback - * CEC RX complete Callback is redirected to the weak HAL_CEC_RxCpltCallback() predefined callback - * @param hcec CEC handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CEC_UnRegisterRxCpltCallback(CEC_HandleTypeDef *hcec) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hcec); - - if (HAL_CEC_STATE_READY == hcec->RxState) - { - hcec->RxCpltCallback = HAL_CEC_RxCpltCallback; /* Legacy weak CEC RxCpltCallback */ - } - else - { - /* Update the error code */ - hcec->ErrorCode |= HAL_CEC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hcec); - return status; -} -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup CEC_Exported_Functions_Group2 Input and Output operation functions - * @brief CEC Transmit/Receive functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - This subsection provides a set of functions allowing to manage the CEC data transfers. - - (#) The CEC handle must contain the initiator (TX side) and the destination (RX side) - logical addresses (4-bit long addresses, 0xF for broadcast messages destination) - - (#) The communication is performed using Interrupts. - These API's return the HAL status. - The end of the data processing will be indicated through the - dedicated CEC IRQ when using Interrupt mode. - The HAL_CEC_TxCpltCallback(), HAL_CEC_RxCpltCallback() user callbacks - will be executed respectively at the end of the transmit or Receive process - The HAL_CEC_ErrorCallback() user callback will be executed when a communication - error is detected - - (#) API's with Interrupt are : - (+) HAL_CEC_Transmit_IT() - (+) HAL_CEC_IRQHandler() - - (#) A set of User Callbacks are provided: - (+) HAL_CEC_TxCpltCallback() - (+) HAL_CEC_RxCpltCallback() - (+) HAL_CEC_ErrorCallback() - -@endverbatim - * @{ - */ - -/** - * @brief Send data in interrupt mode - * @param hcec CEC handle - * @param InitiatorAddress Initiator address - * @param DestinationAddress destination logical address - * @param pData pointer to input byte data buffer - * @param Size amount of data to be sent in bytes (without counting the header). - * 0 means only the header is sent (ping operation). - * Maximum TX size is 15 bytes (1 opcode and up to 14 operands). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CEC_Transmit_IT(CEC_HandleTypeDef *hcec, uint8_t InitiatorAddress, uint8_t DestinationAddress, - uint8_t *pData, uint32_t Size) -{ - /* if the peripheral isn't already busy and if there is no previous transmission - already pending due to arbitration lost */ - if (hcec->gState == HAL_CEC_STATE_READY) - { - if ((pData == NULL) && (Size > 0U)) - { - return HAL_ERROR; - } - - assert_param(IS_CEC_ADDRESS(DestinationAddress)); - assert_param(IS_CEC_ADDRESS(InitiatorAddress)); - assert_param(IS_CEC_MSGSIZE(Size)); - - /* Process Locked */ - __HAL_LOCK(hcec); - hcec->pTxBuffPtr = pData; - hcec->gState = HAL_CEC_STATE_BUSY_TX; - hcec->ErrorCode = HAL_CEC_ERROR_NONE; - - /* initialize the number of bytes to send, - * 0 means only one header is sent (ping operation) */ - hcec->TxXferCount = (uint16_t)Size; - - /* in case of no payload (Size = 0), sender is only pinging the system; - Set TX End of Message (TXEOM) bit, must be set before writing data to TXDR */ - if (Size == 0U) - { - __HAL_CEC_LAST_BYTE_TX_SET(hcec); - } - - /* send header block */ - hcec->Instance->TXDR = (uint32_t)(((uint32_t)InitiatorAddress << CEC_INITIATOR_LSB_POS) | DestinationAddress); - - /* Set TX Start of Message (TXSOM) bit */ - __HAL_CEC_FIRST_BYTE_TX_SET(hcec); - - /* Process Unlocked */ - __HAL_UNLOCK(hcec); - - return HAL_OK; - - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Get size of the received frame. - * @param hcec CEC handle - * @retval Frame size - */ -uint32_t HAL_CEC_GetLastReceivedFrameSize(CEC_HandleTypeDef *hcec) -{ - return hcec->RxXferSize; -} - -/** - * @brief Change Rx Buffer. - * @param hcec CEC handle - * @param Rxbuffer Rx Buffer - * @note This function can be called only inside the HAL_CEC_RxCpltCallback() - * @retval Frame size - */ -void HAL_CEC_ChangeRxBuffer(CEC_HandleTypeDef *hcec, uint8_t *Rxbuffer) -{ - hcec->Init.RxBuffer = Rxbuffer; -} - -/** - * @brief This function handles CEC interrupt requests. - * @param hcec CEC handle - * @retval None - */ -void HAL_CEC_IRQHandler(CEC_HandleTypeDef *hcec) -{ - - /* save interrupts register for further error or interrupts handling purposes */ - uint32_t reg; - reg = hcec->Instance->ISR; - - - /* ----------------------------Arbitration Lost Management----------------------------------*/ - /* CEC TX arbitration error interrupt occurred --------------------------------------*/ - if ((reg & CEC_FLAG_ARBLST) != 0U) - { - hcec->ErrorCode = HAL_CEC_ERROR_ARBLST; - __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_ARBLST); - } - - /* ----------------------------Rx Management----------------------------------*/ - /* CEC RX byte received interrupt ---------------------------------------------------*/ - if ((reg & CEC_FLAG_RXBR) != 0U) - { - /* reception is starting */ - hcec->RxState = HAL_CEC_STATE_BUSY_RX; - hcec->RxXferSize++; - /* read received byte */ - *hcec->Init.RxBuffer = (uint8_t) hcec->Instance->RXDR; - hcec->Init.RxBuffer++; - __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_RXBR); - } - - /* CEC RX end received interrupt ---------------------------------------------------*/ - if ((reg & CEC_FLAG_RXEND) != 0U) - { - /* clear IT */ - __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_RXEND); - - /* Rx process is completed, restore hcec->RxState to Ready */ - hcec->RxState = HAL_CEC_STATE_READY; - hcec->ErrorCode = HAL_CEC_ERROR_NONE; - hcec->Init.RxBuffer -= hcec->RxXferSize; -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1U) - hcec->RxCpltCallback(hcec, hcec->RxXferSize); -#else - HAL_CEC_RxCpltCallback(hcec, hcec->RxXferSize); -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ - hcec->RxXferSize = 0U; - } - - /* ----------------------------Tx Management----------------------------------*/ - /* CEC TX byte request interrupt ------------------------------------------------*/ - if ((reg & CEC_FLAG_TXBR) != 0U) - { - --hcec->TxXferCount; - if (hcec->TxXferCount == 0U) - { - /* if this is the last byte transmission, set TX End of Message (TXEOM) bit */ - __HAL_CEC_LAST_BYTE_TX_SET(hcec); - } - /* In all cases transmit the byte */ - hcec->Instance->TXDR = *hcec->pTxBuffPtr; - hcec->pTxBuffPtr++; - /* clear Tx-Byte request flag */ - __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_TXBR); - } - - /* CEC TX end interrupt ------------------------------------------------*/ - if ((reg & CEC_FLAG_TXEND) != 0U) - { - __HAL_CEC_CLEAR_FLAG(hcec, CEC_FLAG_TXEND); - - /* Tx process is ended, restore hcec->gState to Ready */ - hcec->gState = HAL_CEC_STATE_READY; - /* Call the Process Unlocked before calling the Tx call back API to give the possibility to - start again the Transmission under the Tx call back API */ - __HAL_UNLOCK(hcec); - hcec->ErrorCode = HAL_CEC_ERROR_NONE; -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1U) - hcec->TxCpltCallback(hcec); -#else - HAL_CEC_TxCpltCallback(hcec); -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ - } - - /* ----------------------------Rx/Tx Error Management----------------------------------*/ - if ((reg & (CEC_ISR_RXOVR | CEC_ISR_BRE | CEC_ISR_SBPE | CEC_ISR_LBPE | CEC_ISR_RXACKE | CEC_ISR_TXUDR | CEC_ISR_TXERR | - CEC_ISR_TXACKE)) != 0U) - { - hcec->ErrorCode = reg; - __HAL_CEC_CLEAR_FLAG(hcec, HAL_CEC_ERROR_RXOVR | HAL_CEC_ERROR_BRE | CEC_FLAG_LBPE | CEC_FLAG_SBPE | - HAL_CEC_ERROR_RXACKE | HAL_CEC_ERROR_TXUDR | HAL_CEC_ERROR_TXERR | HAL_CEC_ERROR_TXACKE); - - - if ((reg & (CEC_ISR_RXOVR | CEC_ISR_BRE | CEC_ISR_SBPE | CEC_ISR_LBPE | CEC_ISR_RXACKE)) != 0U) - { - hcec->Init.RxBuffer -= hcec->RxXferSize; - hcec->RxXferSize = 0U; - hcec->RxState = HAL_CEC_STATE_READY; - } - else if (((reg & CEC_ISR_ARBLST) == 0U) && ((reg & (CEC_ISR_TXUDR | CEC_ISR_TXERR | CEC_ISR_TXACKE)) != 0U)) - { - /* Set the CEC state ready to be able to start again the process */ - hcec->gState = HAL_CEC_STATE_READY; - } - else - { - /* Nothing todo*/ - } -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1U) - hcec->ErrorCallback(hcec); -#else - /* Error Call Back */ - HAL_CEC_ErrorCallback(hcec); -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ - } - else - { - /* Nothing todo*/ - } -} - -/** - * @brief Tx Transfer completed callback - * @param hcec CEC handle - * @retval None - */ -__weak void HAL_CEC_TxCpltCallback(CEC_HandleTypeDef *hcec) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcec); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CEC_TxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callback - * @param hcec CEC handle - * @param RxFrameSize Size of frame - * @retval None - */ -__weak void HAL_CEC_RxCpltCallback(CEC_HandleTypeDef *hcec, uint32_t RxFrameSize) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcec); - UNUSED(RxFrameSize); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CEC_RxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief CEC error callbacks - * @param hcec CEC handle - * @retval None - */ -__weak void HAL_CEC_ErrorCallback(CEC_HandleTypeDef *hcec) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcec); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CEC_ErrorCallback can be implemented in the user file - */ -} -/** - * @} - */ - -/** @defgroup CEC_Exported_Functions_Group3 Peripheral Control function - * @brief CEC control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control function ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the CEC. - (+) HAL_CEC_GetState() API can be helpful to check in run-time the state of the CEC peripheral. - (+) HAL_CEC_GetError() API can be helpful to check in run-time the error of the CEC peripheral. -@endverbatim - * @{ - */ -/** - * @brief return the CEC state - * @param hcec pointer to a CEC_HandleTypeDef structure that contains - * the configuration information for the specified CEC module. - * @retval HAL state - */ -HAL_CEC_StateTypeDef HAL_CEC_GetState(CEC_HandleTypeDef *hcec) -{ - uint32_t temp1, temp2; - temp1 = hcec->gState; - temp2 = hcec->RxState; - - return (HAL_CEC_StateTypeDef)(temp1 | temp2); -} - -/** - * @brief Return the CEC error code - * @param hcec pointer to a CEC_HandleTypeDef structure that contains - * the configuration information for the specified CEC. - * @retval CEC Error Code - */ -uint32_t HAL_CEC_GetError(CEC_HandleTypeDef *hcec) -{ - return hcec->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ -#endif /* CEC */ -#endif /* HAL_CEC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c deleted file mode 100644 index 2efb98640c4ab1e..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c +++ /dev/null @@ -1,505 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cortex.c - * @author MCD Application Team - * @brief CORTEX HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the CORTEX: - * + Initialization and de-initialization functions - * + Peripheral Control functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - - [..] - *** How to configure Interrupts using CORTEX HAL driver *** - =========================================================== - [..] - This section provides functions allowing to configure the NVIC interrupts (IRQ). - The Cortex-M4 exceptions are managed by CMSIS functions. - - (#) Configure the NVIC Priority Grouping using HAL_NVIC_SetPriorityGrouping() - function according to the following table. - (#) Configure the priority of the selected IRQ Channels using HAL_NVIC_SetPriority(). - (#) Enable the selected IRQ Channels using HAL_NVIC_EnableIRQ(). - (#) please refer to programming manual for details in how to configure priority. - - -@- When the NVIC_PRIORITYGROUP_0 is selected, IRQ preemption is no more possible. - The pending IRQ priority will be managed only by the sub priority. - - -@- IRQ priority order (sorted by highest to lowest priority): - (+@) Lowest preemption priority - (+@) Lowest sub priority - (+@) Lowest hardware priority (IRQ number) - - [..] - *** How to configure Systick using CORTEX HAL driver *** - ======================================================== - [..] - Setup SysTick Timer for time base. - - (+) The HAL_SYSTICK_Config() function calls the SysTick_Config() function which - is a CMSIS function that: - (++) Configures the SysTick Reload register with value passed as function parameter. - (++) Configures the SysTick IRQ priority to the lowest value 0x0F. - (++) Resets the SysTick Counter register. - (++) Configures the SysTick Counter clock source to be Core Clock Source (HCLK). - (++) Enables the SysTick Interrupt. - (++) Starts the SysTick Counter. - - (+) You can change the SysTick Clock source to be HCLK_Div8 by calling the macro - __HAL_CORTEX_SYSTICKCLK_CONFIG(SYSTICK_CLKSOURCE_HCLK_DIV8) just after the - HAL_SYSTICK_Config() function call. The __HAL_CORTEX_SYSTICKCLK_CONFIG() macro is defined - inside the stm32f4xx_hal_cortex.h file. - - (+) You can change the SysTick IRQ priority by calling the - HAL_NVIC_SetPriority(SysTick_IRQn,...) function just after the HAL_SYSTICK_Config() function - call. The HAL_NVIC_SetPriority() call the NVIC_SetPriority() function which is a CMSIS function. - - (+) To adjust the SysTick time base, use the following formula: - - Reload Value = SysTick Counter Clock (Hz) x Desired Time base (s) - (++) Reload Value is the parameter to be passed for HAL_SYSTICK_Config() function - (++) Reload Value should not exceed 0xFFFFFF - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup CORTEX CORTEX - * @brief CORTEX HAL module driver - * @{ - */ - -#ifdef HAL_CORTEX_MODULE_ENABLED - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup CORTEX_Exported_Functions CORTEX Exported Functions - * @{ - */ - - -/** @defgroup CORTEX_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] - This section provides the CORTEX HAL driver functions allowing to configure Interrupts - Systick functionalities - -@endverbatim - * @{ - */ - - -/** - * @brief Sets the priority grouping field (preemption priority and subpriority) - * using the required unlock sequence. - * @param PriorityGroup The priority grouping bits length. - * This parameter can be one of the following values: - * @arg NVIC_PRIORITYGROUP_0: 0 bits for preemption priority - * 4 bits for subpriority - * @arg NVIC_PRIORITYGROUP_1: 1 bits for preemption priority - * 3 bits for subpriority - * @arg NVIC_PRIORITYGROUP_2: 2 bits for preemption priority - * 2 bits for subpriority - * @arg NVIC_PRIORITYGROUP_3: 3 bits for preemption priority - * 1 bits for subpriority - * @arg NVIC_PRIORITYGROUP_4: 4 bits for preemption priority - * 0 bits for subpriority - * @note When the NVIC_PriorityGroup_0 is selected, IRQ preemption is no more possible. - * The pending IRQ priority will be managed only by the subpriority. - * @retval None - */ -void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - /* Check the parameters */ - assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); - - /* Set the PRIGROUP[10:8] bits according to the PriorityGroup parameter value */ - NVIC_SetPriorityGrouping(PriorityGroup); -} - -/** - * @brief Sets the priority of an interrupt. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @param PreemptPriority The preemption priority for the IRQn channel. - * This parameter can be a value between 0 and 15 - * A lower priority value indicates a higher priority - * @param SubPriority the subpriority level for the IRQ channel. - * This parameter can be a value between 0 and 15 - * A lower priority value indicates a higher priority. - * @retval None - */ -void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t prioritygroup = 0x00U; - - /* Check the parameters */ - assert_param(IS_NVIC_SUB_PRIORITY(SubPriority)); - assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority)); - - prioritygroup = NVIC_GetPriorityGrouping(); - - NVIC_SetPriority(IRQn, NVIC_EncodePriority(prioritygroup, PreemptPriority, SubPriority)); -} - -/** - * @brief Enables a device specific interrupt in the NVIC interrupt controller. - * @note To configure interrupts priority correctly, the NVIC_PriorityGroupConfig() - * function should be called before. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval None - */ -void HAL_NVIC_EnableIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Enable interrupt */ - NVIC_EnableIRQ(IRQn); -} - -/** - * @brief Disables a device specific interrupt in the NVIC interrupt controller. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval None - */ -void HAL_NVIC_DisableIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Disable interrupt */ - NVIC_DisableIRQ(IRQn); -} - -/** - * @brief Initiates a system reset request to reset the MCU. - * @retval None - */ -void HAL_NVIC_SystemReset(void) -{ - /* System Reset */ - NVIC_SystemReset(); -} - -/** - * @brief Initializes the System Timer and its interrupt, and starts the System Tick Timer. - * Counter is in free running mode to generate periodic interrupts. - * @param TicksNumb Specifies the ticks Number of ticks between two interrupts. - * @retval status: - 0 Function succeeded. - * - 1 Function failed. - */ -uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb) -{ - return SysTick_Config(TicksNumb); -} -/** - * @} - */ - -/** @defgroup CORTEX_Exported_Functions_Group2 Peripheral Control functions - * @brief Cortex control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control the CORTEX - (NVIC, SYSTICK, MPU) functionalities. - - -@endverbatim - * @{ - */ - -#if (__MPU_PRESENT == 1U) -/** - * @brief Disables the MPU - * @retval None - */ -void HAL_MPU_Disable(void) -{ - /* Make sure outstanding transfers are done */ - __DMB(); - - /* Disable fault exceptions */ - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; - - /* Disable the MPU and clear the control register*/ - MPU->CTRL = 0U; -} - -/** - * @brief Enable the MPU. - * @param MPU_Control Specifies the control mode of the MPU during hard fault, - * NMI, FAULTMASK and privileged access to the default memory - * This parameter can be one of the following values: - * @arg MPU_HFNMI_PRIVDEF_NONE - * @arg MPU_HARDFAULT_NMI - * @arg MPU_PRIVILEGED_DEFAULT - * @arg MPU_HFNMI_PRIVDEF - * @retval None - */ -void HAL_MPU_Enable(uint32_t MPU_Control) -{ - /* Enable the MPU */ - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; - - /* Enable fault exceptions */ - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; - - /* Ensure MPU setting take effects */ - __DSB(); - __ISB(); -} - -/** - * @brief Initializes and configures the Region and the memory to be protected. - * @param MPU_Init Pointer to a MPU_Region_InitTypeDef structure that contains - * the initialization and configuration information. - * @retval None - */ -void HAL_MPU_ConfigRegion(MPU_Region_InitTypeDef *MPU_Init) -{ - /* Check the parameters */ - assert_param(IS_MPU_REGION_NUMBER(MPU_Init->Number)); - assert_param(IS_MPU_REGION_ENABLE(MPU_Init->Enable)); - - /* Set the Region number */ - MPU->RNR = MPU_Init->Number; - - if ((MPU_Init->Enable) != RESET) - { - /* Check the parameters */ - assert_param(IS_MPU_INSTRUCTION_ACCESS(MPU_Init->DisableExec)); - assert_param(IS_MPU_REGION_PERMISSION_ATTRIBUTE(MPU_Init->AccessPermission)); - assert_param(IS_MPU_TEX_LEVEL(MPU_Init->TypeExtField)); - assert_param(IS_MPU_ACCESS_SHAREABLE(MPU_Init->IsShareable)); - assert_param(IS_MPU_ACCESS_CACHEABLE(MPU_Init->IsCacheable)); - assert_param(IS_MPU_ACCESS_BUFFERABLE(MPU_Init->IsBufferable)); - assert_param(IS_MPU_SUB_REGION_DISABLE(MPU_Init->SubRegionDisable)); - assert_param(IS_MPU_REGION_SIZE(MPU_Init->Size)); - - MPU->RBAR = MPU_Init->BaseAddress; - MPU->RASR = ((uint32_t)MPU_Init->DisableExec << MPU_RASR_XN_Pos) | - ((uint32_t)MPU_Init->AccessPermission << MPU_RASR_AP_Pos) | - ((uint32_t)MPU_Init->TypeExtField << MPU_RASR_TEX_Pos) | - ((uint32_t)MPU_Init->IsShareable << MPU_RASR_S_Pos) | - ((uint32_t)MPU_Init->IsCacheable << MPU_RASR_C_Pos) | - ((uint32_t)MPU_Init->IsBufferable << MPU_RASR_B_Pos) | - ((uint32_t)MPU_Init->SubRegionDisable << MPU_RASR_SRD_Pos) | - ((uint32_t)MPU_Init->Size << MPU_RASR_SIZE_Pos) | - ((uint32_t)MPU_Init->Enable << MPU_RASR_ENABLE_Pos); - } - else - { - MPU->RBAR = 0x00U; - MPU->RASR = 0x00U; - } -} -#endif /* __MPU_PRESENT */ - -/** - * @brief Gets the priority grouping field from the NVIC Interrupt Controller. - * @retval Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field) - */ -uint32_t HAL_NVIC_GetPriorityGrouping(void) -{ - /* Get the PRIGROUP[10:8] field value */ - return NVIC_GetPriorityGrouping(); -} - -/** - * @brief Gets the priority of an interrupt. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @param PriorityGroup the priority grouping bits length. - * This parameter can be one of the following values: - * @arg NVIC_PRIORITYGROUP_0: 0 bits for preemption priority - * 4 bits for subpriority - * @arg NVIC_PRIORITYGROUP_1: 1 bits for preemption priority - * 3 bits for subpriority - * @arg NVIC_PRIORITYGROUP_2: 2 bits for preemption priority - * 2 bits for subpriority - * @arg NVIC_PRIORITYGROUP_3: 3 bits for preemption priority - * 1 bits for subpriority - * @arg NVIC_PRIORITYGROUP_4: 4 bits for preemption priority - * 0 bits for subpriority - * @param pPreemptPriority Pointer on the Preemptive priority value (starting from 0). - * @param pSubPriority Pointer on the Subpriority value (starting from 0). - * @retval None - */ -void HAL_NVIC_GetPriority(IRQn_Type IRQn, uint32_t PriorityGroup, uint32_t *pPreemptPriority, uint32_t *pSubPriority) -{ - /* Check the parameters */ - assert_param(IS_NVIC_PRIORITY_GROUP(PriorityGroup)); - /* Get priority for Cortex-M system or device specific interrupts */ - NVIC_DecodePriority(NVIC_GetPriority(IRQn), PriorityGroup, pPreemptPriority, pSubPriority); -} - -/** - * @brief Sets Pending bit of an external interrupt. - * @param IRQn External interrupt number - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval None - */ -void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Set interrupt pending */ - NVIC_SetPendingIRQ(IRQn); -} - -/** - * @brief Gets Pending Interrupt (reads the pending register in the NVIC - * and returns the pending bit for the specified interrupt). - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval status: - 0 Interrupt status is not pending. - * - 1 Interrupt status is pending. - */ -uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Return 1 if pending else 0 */ - return NVIC_GetPendingIRQ(IRQn); -} - -/** - * @brief Clears the pending bit of an external interrupt. - * @param IRQn External interrupt number. - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval None - */ -void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Clear pending interrupt */ - NVIC_ClearPendingIRQ(IRQn); -} - -/** - * @brief Gets active interrupt ( reads the active register in NVIC and returns the active bit). - * @param IRQn External interrupt number - * This parameter can be an enumerator of IRQn_Type enumeration - * (For the complete STM32 Devices IRQ Channels list, please refer to the appropriate CMSIS device file (stm32f4xxxx.h)) - * @retval status: - 0 Interrupt status is not pending. - * - 1 Interrupt status is pending. - */ -uint32_t HAL_NVIC_GetActive(IRQn_Type IRQn) -{ - /* Check the parameters */ - assert_param(IS_NVIC_DEVICE_IRQ(IRQn)); - - /* Return 1 if active else 0 */ - return NVIC_GetActive(IRQn); -} - -/** - * @brief Configures the SysTick clock source. - * @param CLKSource specifies the SysTick clock source. - * This parameter can be one of the following values: - * @arg SYSTICK_CLKSOURCE_HCLK_DIV8: AHB clock divided by 8 selected as SysTick clock source. - * @arg SYSTICK_CLKSOURCE_HCLK: AHB clock selected as SysTick clock source. - * @retval None - */ -void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource) -{ - /* Check the parameters */ - assert_param(IS_SYSTICK_CLK_SOURCE(CLKSource)); - if (CLKSource == SYSTICK_CLKSOURCE_HCLK) - { - SysTick->CTRL |= SYSTICK_CLKSOURCE_HCLK; - } - else - { - SysTick->CTRL &= ~SYSTICK_CLKSOURCE_HCLK; - } -} - -/** - * @brief This function handles SYSTICK interrupt request. - * @retval None - */ -void HAL_SYSTICK_IRQHandler(void) -{ - HAL_SYSTICK_Callback(); -} - -/** - * @brief SYSTICK callback. - * @retval None - */ -__weak void HAL_SYSTICK_Callback(void) -{ - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SYSTICK_Callback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_CORTEX_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c deleted file mode 100644 index 652eeda37db4620..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c +++ /dev/null @@ -1,330 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_crc.c - * @author MCD Application Team - * @brief CRC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Cyclic Redundancy Check (CRC) peripheral: - * + Initialization and de-initialization functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - =============================================================================== - ##### How to use this driver ##### - =============================================================================== - [..] - (+) Enable CRC AHB clock using __HAL_RCC_CRC_CLK_ENABLE(); - (+) Initialize CRC calculator - (++) specify generating polynomial (peripheral default or non-default one) - (++) specify initialization value (peripheral default or non-default one) - (++) specify input data format - (++) specify input or output data inversion mode if any - (+) Use HAL_CRC_Accumulate() function to compute the CRC value of the - input data buffer starting with the previously computed CRC as - initialization value - (+) Use HAL_CRC_Calculate() function to compute the CRC value of the - input data buffer starting with the defined initialization value - (default or non-default) to initiate CRC calculation - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup CRC CRC - * @brief CRC HAL module driver. - * @{ - */ - -#ifdef HAL_CRC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup CRC_Exported_Functions CRC Exported Functions - * @{ - */ - -/** @defgroup CRC_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions. - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize the CRC according to the specified parameters - in the CRC_InitTypeDef and create the associated handle - (+) DeInitialize the CRC peripheral - (+) Initialize the CRC MSP (MCU Specific Package) - (+) DeInitialize the CRC MSP - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the CRC according to the specified - * parameters in the CRC_InitTypeDef and create the associated handle. - * @param hcrc CRC handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc) -{ - /* Check the CRC handle allocation */ - if (hcrc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CRC_ALL_INSTANCE(hcrc->Instance)); - - if (hcrc->State == HAL_CRC_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hcrc->Lock = HAL_UNLOCKED; - /* Init the low level hardware */ - HAL_CRC_MspInit(hcrc); - } - - /* Change CRC peripheral state */ - hcrc->State = HAL_CRC_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief DeInitialize the CRC peripheral. - * @param hcrc CRC handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc) -{ - /* Check the CRC handle allocation */ - if (hcrc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_CRC_ALL_INSTANCE(hcrc->Instance)); - - /* Check the CRC peripheral state */ - if (hcrc->State == HAL_CRC_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Change CRC peripheral state */ - hcrc->State = HAL_CRC_STATE_BUSY; - - /* Reset CRC calculation unit */ - __HAL_CRC_DR_RESET(hcrc); - - /* Reset IDR register content */ - CLEAR_BIT(hcrc->Instance->IDR, CRC_IDR_IDR); - - /* DeInit the low level hardware */ - HAL_CRC_MspDeInit(hcrc); - - /* Change CRC peripheral state */ - hcrc->State = HAL_CRC_STATE_RESET; - - /* Process unlocked */ - __HAL_UNLOCK(hcrc); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initializes the CRC MSP. - * @param hcrc CRC handle - * @retval None - */ -__weak void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcrc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CRC_MspInit can be implemented in the user file - */ -} - -/** - * @brief DeInitialize the CRC MSP. - * @param hcrc CRC handle - * @retval None - */ -__weak void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcrc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CRC_MspDeInit can be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup CRC_Exported_Functions_Group2 Peripheral Control functions - * @brief management functions. - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) compute the 32-bit CRC value of a 32-bit data buffer - using combination of the previous CRC value and the new one. - - [..] or - - (+) compute the 32-bit CRC value of a 32-bit data buffer - independently of the previous CRC value. - -@endverbatim - * @{ - */ - -/** - * @brief Compute the 32-bit CRC value of a 32-bit data buffer - * starting with the previously computed CRC as initialization value. - * @param hcrc CRC handle - * @param pBuffer pointer to the input data buffer. - * @param BufferLength input data buffer length (number of uint32_t words). - * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits) - */ -uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength) -{ - uint32_t index; /* CRC input data buffer index */ - uint32_t temp = 0U; /* CRC output (read from hcrc->Instance->DR register) */ - - /* Change CRC peripheral state */ - hcrc->State = HAL_CRC_STATE_BUSY; - - /* Enter Data to the CRC calculator */ - for (index = 0U; index < BufferLength; index++) - { - hcrc->Instance->DR = pBuffer[index]; - } - temp = hcrc->Instance->DR; - - /* Change CRC peripheral state */ - hcrc->State = HAL_CRC_STATE_READY; - - /* Return the CRC computed value */ - return temp; -} - -/** - * @brief Compute the 32-bit CRC value of a 32-bit data buffer - * starting with hcrc->Instance->INIT as initialization value. - * @param hcrc CRC handle - * @param pBuffer pointer to the input data buffer. - * @param BufferLength input data buffer length (number of uint32_t words). - * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits) - */ -uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength) -{ - uint32_t index; /* CRC input data buffer index */ - uint32_t temp = 0U; /* CRC output (read from hcrc->Instance->DR register) */ - - /* Change CRC peripheral state */ - hcrc->State = HAL_CRC_STATE_BUSY; - - /* Reset CRC Calculation Unit (hcrc->Instance->INIT is - * written in hcrc->Instance->DR) */ - __HAL_CRC_DR_RESET(hcrc); - - /* Enter 32-bit input data to the CRC calculator */ - for (index = 0U; index < BufferLength; index++) - { - hcrc->Instance->DR = pBuffer[index]; - } - temp = hcrc->Instance->DR; - - /* Change CRC peripheral state */ - hcrc->State = HAL_CRC_STATE_READY; - - /* Return the CRC computed value */ - return temp; -} - -/** - * @} - */ - -/** @defgroup CRC_Exported_Functions_Group3 Peripheral State functions - * @brief Peripheral State functions. - * -@verbatim - =============================================================================== - ##### Peripheral State functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Return the CRC handle state. - * @param hcrc CRC handle - * @retval HAL state - */ -HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc) -{ - /* Return CRC handle state */ - return hcrc->State; -} - -/** - * @} - */ - -/** - * @} - */ - - -#endif /* HAL_CRC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp.c deleted file mode 100644 index efb64e596a6292e..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp.c +++ /dev/null @@ -1,7133 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cryp.c - * @author MCD Application Team - * @brief CRYP HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Cryptography (CRYP) peripheral: - * + Initialization, de-initialization, set config and get config functions - * + DES/TDES, AES processing functions - * + DMA callback functions - * + CRYP IRQ handler management - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The CRYP HAL driver can be used in CRYP or TinyAES IP as follows: - - (#)Initialize the CRYP low level resources by implementing the HAL_CRYP_MspInit(): - (##) Enable the CRYP interface clock using __HAL_RCC_CRYP_CLK_ENABLE()or __HAL_RCC_AES_CLK_ENABLE for TinyAES IP - (##) In case of using interrupts (e.g. HAL_CRYP_Encrypt_IT()) - (+++) Configure the CRYP interrupt priority using HAL_NVIC_SetPriority() - (+++) Enable the CRYP IRQ handler using HAL_NVIC_EnableIRQ() - (+++) In CRYP IRQ handler, call HAL_CRYP_IRQHandler() - (##) In case of using DMA to control data transfer (e.g. HAL_CRYP_Encrypt_DMA()) - (+++) Enable the DMAx interface clock using __RCC_DMAx_CLK_ENABLE() - (+++) Configure and enable two DMA streams one for managing data transfer from - memory to peripheral (input stream) and another stream for managing data - transfer from peripheral to memory (output stream) - (+++) Associate the initialized DMA handle to the CRYP DMA handle - using __HAL_LINKDMA() - (+++) Configure the priority and enable the NVIC for the transfer complete - interrupt on the two DMA Streams. The output stream should have higher - priority than the input stream HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ() - - (#)Initialize the CRYP according to the specified parameters : - (##) The data type: 1-bit, 8-bit, 16-bit or 32-bit. - (##) The key size: 128, 192 or 256. - (##) The AlgoMode DES/ TDES Algorithm ECB/CBC or AES Algorithm ECB/CBC/CTR/GCM or CCM. - (##) The initialization vector (counter). It is not used in ECB mode. - (##) The key buffer used for encryption/decryption. - (##) The Header used only in AES GCM and CCM Algorithm for authentication. - (##) The HeaderSize The size of header buffer in word. - (##) The B0 block is the first authentication block used only in AES CCM mode. - - (#)Three processing (encryption/decryption) functions are available: - (##) Polling mode: encryption and decryption APIs are blocking functions - i.e. they process the data and wait till the processing is finished, - e.g. HAL_CRYP_Encrypt & HAL_CRYP_Decrypt - (##) Interrupt mode: encryption and decryption APIs are not blocking functions - i.e. they process the data under interrupt, - e.g. HAL_CRYP_Encrypt_IT & HAL_CRYP_Decrypt_IT - (##) DMA mode: encryption and decryption APIs are not blocking functions - i.e. the data transfer is ensured by DMA, - e.g. HAL_CRYP_Encrypt_DMA & HAL_CRYP_Decrypt_DMA - - (#)When the processing function is called at first time after HAL_CRYP_Init() - the CRYP peripheral is configured and processes the buffer in input. - At second call, no need to Initialize the CRYP, user have to get current configuration via - HAL_CRYP_GetConfig() API, then only HAL_CRYP_SetConfig() is requested to set - new parametres, finally user can start encryption/decryption. - - (#)Call HAL_CRYP_DeInit() to deinitialize the CRYP peripheral. - - (#)To process a single message with consecutive calls to HAL_CRYP_Encrypt() or HAL_CRYP_Decrypt() - without having to configure again the Key or the Initialization Vector between each API call, - the field KeyIVConfigSkip of the initialization structure must be set to CRYP_KEYIVCONFIG_ONCE. - Same is true for consecutive calls of HAL_CRYP_Encrypt_IT(), HAL_CRYP_Decrypt_IT(), HAL_CRYP_Encrypt_DMA() - or HAL_CRYP_Decrypt_DMA(). - - [..] - The cryptographic processor supports following standards: - (#) The data encryption standard (DES) and Triple-DES (TDES) supported only by CRYP1 IP: - (##)64-bit data block processing - (##) chaining modes supported : - (+++) Electronic Code Book(ECB) - (+++) Cipher Block Chaining (CBC) - (##) keys length supported :64-bit, 128-bit and 192-bit. - (#) The advanced encryption standard (AES) supported by CRYP1 & TinyAES IP: - (##)128-bit data block processing - (##) chaining modes supported : - (+++) Electronic Code Book(ECB) - (+++) Cipher Block Chaining (CBC) - (+++) Counter mode (CTR) - (+++) Galois/counter mode (GCM/GMAC) - (+++) Counter with Cipher Block Chaining-Message(CCM) - (##) keys length Supported : - (+++) for CRYP1 IP: 128-bit, 192-bit and 256-bit. - (+++) for TinyAES IP: 128-bit and 256-bit - - [..] This section describes the AES Galois/counter mode (GCM) supported by both CRYP1 IP: - (#) Algorithm supported : - (##) Galois/counter mode (GCM) - (##) Galois message authentication code (GMAC) :is exactly the same as - GCM algorithm composed only by an header. - (#) Four phases are performed in GCM : - (##) Init phase: IP prepares the GCM hash subkey (H) and do the IV processing - (##) Header phase: IP processes the Additional Authenticated Data (AAD), with hash - computation only. - (##) Payload phase: IP processes the plaintext (P) with hash computation + keystream - encryption + data XORing. It works in a similar way for ciphertext (C). - (##) Final phase: IP generates the authenticated tag (T) using the last block of data. - (#) structure of message construction in GCM is defined as below : - (##) 16 bytes Initial Counter Block (ICB)composed of IV and counter - (##) The authenticated header A (also knows as Additional Authentication Data AAD) - this part of the message is only authenticated, not encrypted. - (##) The plaintext message P is both authenticated and encrypted as ciphertext. - GCM standard specifies that ciphertext has same bit length as the plaintext. - (##) The last block is composed of the length of A (on 64 bits) and the length of ciphertext - (on 64 bits) - - [..] This section describe The AES Counter with Cipher Block Chaining-Message - Authentication Code (CCM) supported by both CRYP1 IP: - (#) Specific parameters for CCM : - - (##) B0 block : According to NIST Special Publication 800-38C, - The first block B0 is formatted as follows, where l(m) is encoded in - most-significant-byte first order(see below table 3) - - (+++) Q: a bit string representation of the octet length of P (plaintext) - (+++) q The octet length of the binary representation of the octet length of the payload - (+++) A nonce (N), n The octet length of the where n+q=15. - (+++) Flags: most significant octet containing four flags for control information, - (+++) t The octet length of the MAC. - (##) B1 block (header) : associated data length(a) concatenated with Associated Data (A) - the associated data length expressed in bytes (a) defined as below: - (+++) If 0 < a < 216-28, then it is encoded as [a]16, i.e. two octets - (+++) If 216-28 < a < 232, then it is encoded as 0xff || 0xfe || [a]32, i.e. six octets - (+++) If 232 < a < 264, then it is encoded as 0xff || 0xff || [a]64, i.e. ten octets - (##) CTRx block : control blocks - (+++) Generation of CTR1 from first block B0 information : - equal to B0 with first 5 bits zeroed and most significant bits storing octet - length of P also zeroed, then incremented by one ( see below Table 4) - (+++) Generation of CTR0: same as CTR1 with bit[0] set to zero. - - (#) Four phases are performed in CCM for CRYP1 IP: - (##) Init phase: IP prepares the GCM hash subkey (H) and do the IV processing - (##) Header phase: IP processes the Additional Authenticated Data (AAD), with hash - computation only. - (##) Payload phase: IP processes the plaintext (P) with hash computation + keystream - encryption + data XORing. It works in a similar way for ciphertext (C). - (##) Final phase: IP generates the authenticated tag (T) using the last block of data. - - *** Callback registration *** - ============================================= - - The compilation define USE_HAL_CRYP_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Functions @ref HAL_CRYP_RegisterCallback() or HAL_CRYP_RegisterXXXCallback() - to register an interrupt callback. - - Function @ref HAL_CRYP_RegisterCallback() allows to register following callbacks: - (+) InCpltCallback : Input FIFO transfer completed callback. - (+) OutCpltCallback : Output FIFO transfer completed callback. - (+) ErrorCallback : callback for error detection. - (+) MspInitCallback : CRYP MspInit. - (+) MspDeInitCallback : CRYP MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function @ref HAL_CRYP_UnRegisterCallback() to reset a callback to the default - weak function. - @ref HAL_CRYP_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) InCpltCallback : Input FIFO transfer completed callback. - (+) OutCpltCallback : Output FIFO transfer completed callback. - (+) ErrorCallback : callback for error detection. - (+) MspInitCallback : CRYP MspInit. - (+) MspDeInitCallback : CRYP MspDeInit. - - By default, after the @ref HAL_CRYP_Init() and when the state is HAL_CRYP_STATE_RESET - all callbacks are set to the corresponding weak functions : - examples @ref HAL_CRYP_InCpltCallback() , @ref HAL_CRYP_OutCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak function in the @ref HAL_CRYP_Init()/ @ref HAL_CRYP_DeInit() only when - these callbacks are null (not registered beforehand). - if not, MspInit or MspDeInit are not null, the @ref HAL_CRYP_Init() / @ref HAL_CRYP_DeInit() - keep and use the user MspInit/MspDeInit functions (registered beforehand) - - Callbacks can be registered/unregistered in HAL_CRYP_STATE_READY state only. - Exception done MspInit/MspDeInit callbacks that can be registered/unregistered - in HAL_CRYP_STATE_READY or HAL_CRYP_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_CRYP_RegisterCallback() before calling @ref HAL_CRYP_DeInit() - or @ref HAL_CRYP_Init() function. - - When The compilation define USE_HAL_CRYP_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - Table 1. Initial Counter Block (ICB) - +-------------------------------------------------------+ - | Initialization vector (IV) | Counter | - |----------------|----------------|-----------|---------| - 127 95 63 31 0 - - - Bit Number Register Contents - ---------- --------------- ----------- - 127 ...96 CRYP_IV1R[31:0] ICB[127:96] - 95 ...64 CRYP_IV1L[31:0] B0[95:64] - 63 ... 32 CRYP_IV0R[31:0] ICB[63:32] - 31 ... 0 CRYP_IV0L[31:0] ICB[31:0], where 32-bit counter= 0x2 - - Table 2. GCM last block definition - - +-------------------------------------------------------------------+ - | Bit[0] | Bit[32] | Bit[64] | Bit[96] | - |-----------|--------------------|-----------|----------------------| - | 0x0 | Header length[31:0]| 0x0 | Payload length[31:0] | - |-----------|--------------------|-----------|----------------------| - - Table 3. B0 block - Octet Number Contents - ------------ --------- - 0 Flags - 1 ... 15-q Nonce N - 16-q ... 15 Q - - the Flags field is formatted as follows: - - Bit Number Contents - ---------- ---------------------- - 7 Reserved (always zero) - 6 Adata - 5 ... 3 (t-2)/2 - 2 ... 0 [q-1]3 - - Table 4. CTRx block - Bit Number Register Contents - ---------- --------------- ----------- - 127 ...96 CRYP_IV1R[31:0] B0[127:96], where Q length bits are set to 0, except for - bit 0 that is set to 1 - 95 ...64 CRYP_IV1L[31:0] B0[95:64] - 63 ... 32 CRYP_IV0R[31:0] B0[63:32] - 31 ... 0 CRYP_IV0L[31:0] B0[31:0], where flag bits set to 0 - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (AES) || defined (CRYP) - -/** @defgroup CRYP CRYP - * @brief CRYP HAL module driver. - * @{ - */ - - -#ifdef HAL_CRYP_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup CRYP_Private_Defines - * @{ - */ -#define CRYP_TIMEOUT_KEYPREPARATION 82U /*The latency of key preparation operation is 82 clock cycles.*/ -#define CRYP_TIMEOUT_GCMCCMINITPHASE 299U /* The latency of GCM/CCM init phase to prepare hash subkey is 299 clock cycles.*/ -#define CRYP_TIMEOUT_GCMCCMHEADERPHASE 290U /* The latency of GCM/CCM header phase is 290 clock cycles.*/ - -#define CRYP_PHASE_READY 0x00000001U /*!< CRYP peripheral is ready for initialization. */ -#define CRYP_PHASE_PROCESS 0x00000002U /*!< CRYP peripheral is in processing phase */ - -#if defined(AES) -#define CRYP_OPERATINGMODE_ENCRYPT 0x00000000U /*!< Encryption mode(Mode 1) */ -#define CRYP_OPERATINGMODE_KEYDERIVATION AES_CR_MODE_0 /*!< Key derivation mode only used when performing ECB and CBC decryptions (Mode 2) */ -#define CRYP_OPERATINGMODE_DECRYPT AES_CR_MODE_1 /*!< Decryption (Mode 3) */ -#define CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT AES_CR_MODE /*!< Key derivation and decryption only used when performing ECB and CBC decryptions (Mode 4) */ -#define CRYP_PHASE_INIT 0x00000000U /*!< GCM/GMAC (or CCM) init phase */ -#define CRYP_PHASE_HEADER AES_CR_GCMPH_0 /*!< GCM/GMAC or CCM header phase */ -#define CRYP_PHASE_PAYLOAD AES_CR_GCMPH_1 /*!< GCM(/CCM) payload phase */ -#define CRYP_PHASE_FINAL AES_CR_GCMPH /*!< GCM/GMAC or CCM final phase */ -#else /* CRYP */ -#define CRYP_PHASE_INIT 0x00000000U /*!< GCM/GMAC (or CCM) init phase */ -#define CRYP_PHASE_HEADER CRYP_CR_GCM_CCMPH_0 /*!< GCM/GMAC or CCM header phase */ -#define CRYP_PHASE_PAYLOAD CRYP_CR_GCM_CCMPH_1 /*!< GCM(/CCM) payload phase */ -#define CRYP_PHASE_FINAL CRYP_CR_GCM_CCMPH /*!< GCM/GMAC or CCM final phase */ -#define CRYP_OPERATINGMODE_ENCRYPT 0x00000000U /*!< Encryption mode */ -#define CRYP_OPERATINGMODE_DECRYPT CRYP_CR_ALGODIR /*!< Decryption */ -#endif /* End CRYP or AES */ - -/* CTR1 information to use in CCM algorithm */ -#define CRYP_CCM_CTR1_0 0x07FFFFFFU -#define CRYP_CCM_CTR1_1 0xFFFFFF00U -#define CRYP_CCM_CTR1_2 0x00000001U - - -/** - * @} - */ - - -/* Private macro -------------------------------------------------------------*/ -/** @addtogroup CRYP_Private_Macros - * @{ - */ - -#if defined(CRYP) - -#define CRYP_SET_PHASE(__HANDLE__, __PHASE__) do{(__HANDLE__)->Instance->CR &= (uint32_t)(~CRYP_CR_GCM_CCMPH);\ - (__HANDLE__)->Instance->CR |= (uint32_t)(__PHASE__);\ - }while(0) - -#define HAL_CRYP_FIFO_FLUSH(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRYP_CR_FFLUSH) - -#else /*AES*/ -#define CRYP_SET_PHASE(__HANDLE__, __PHASE__) do{(__HANDLE__)->Instance->CR &= (uint32_t)(~AES_CR_GCMPH);\ - (__HANDLE__)->Instance->CR |= (uint32_t)(__PHASE__);\ - }while(0) -#endif /* End AES or CRYP*/ - - -/** - * @} - */ - -/* Private struct -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup CRYP_Private_Functions_prototypes - * @{ - */ - -static void CRYP_SetDMAConfig(CRYP_HandleTypeDef *hcryp, uint32_t inputaddr, uint16_t Size, uint32_t outputaddr); -static void CRYP_DMAInCplt(DMA_HandleTypeDef *hdma); -static void CRYP_DMAOutCplt(DMA_HandleTypeDef *hdma); -static void CRYP_DMAError(DMA_HandleTypeDef *hdma); -static void CRYP_SetKey(CRYP_HandleTypeDef *hcryp, uint32_t KeySize); -static void CRYP_AES_IT(CRYP_HandleTypeDef *hcryp); -#if defined (CRYP_CR_ALGOMODE_AES_GCM)|| defined (AES) -static HAL_StatusTypeDef CRYP_GCMCCM_SetHeaderPhase(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -static void CRYP_GCMCCM_SetPayloadPhase_IT(CRYP_HandleTypeDef *hcryp); -static void CRYP_GCMCCM_SetHeaderPhase_IT(CRYP_HandleTypeDef *hcryp); -static HAL_StatusTypeDef CRYP_GCMCCM_SetHeaderPhase_DMA(CRYP_HandleTypeDef *hcryp); -static void CRYP_Workaround(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -static HAL_StatusTypeDef CRYP_AESGCM_Process_DMA(CRYP_HandleTypeDef *hcryp); -static HAL_StatusTypeDef CRYP_AESGCM_Process_IT(CRYP_HandleTypeDef *hcryp); -static HAL_StatusTypeDef CRYP_AESGCM_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -static HAL_StatusTypeDef CRYP_AESCCM_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -static HAL_StatusTypeDef CRYP_AESCCM_Process_IT(CRYP_HandleTypeDef *hcryp); -static HAL_StatusTypeDef CRYP_AESCCM_Process_DMA(CRYP_HandleTypeDef *hcryp); -#endif /* AES or GCM CCM defined*/ -static void CRYP_AES_ProcessData(CRYP_HandleTypeDef *hcrypt, uint32_t Timeout); -static HAL_StatusTypeDef CRYP_AES_Encrypt(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -static HAL_StatusTypeDef CRYP_AES_Decrypt(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -static HAL_StatusTypeDef CRYP_AES_Decrypt_IT(CRYP_HandleTypeDef *hcryp); -static HAL_StatusTypeDef CRYP_AES_Encrypt_IT(CRYP_HandleTypeDef *hcryp); -static HAL_StatusTypeDef CRYP_AES_Decrypt_DMA(CRYP_HandleTypeDef *hcryp); -#if defined (CRYP) -static void CRYP_TDES_IT(CRYP_HandleTypeDef *hcryp); -#if defined (CRYP_CR_ALGOMODE_AES_GCM) -static HAL_StatusTypeDef CRYP_WaitOnIFEMFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -#endif /* GCM CCM defined*/ -static HAL_StatusTypeDef CRYP_WaitOnBUSYFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -static HAL_StatusTypeDef CRYP_WaitOnOFNEFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -static HAL_StatusTypeDef CRYP_TDES_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -#else /*AES*/ -static HAL_StatusTypeDef CRYP_WaitOnCCFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout); -#endif /* End CRYP or AES */ - -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ - -/** @defgroup CRYP_Exported_Functions CRYP Exported Functions - * @{ - */ - - -/** @defgroup CRYP_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions. - * -@verbatim - ======================================================================================== - ##### Initialization, de-initialization and Set and Get configuration functions ##### - ======================================================================================== - [..] This section provides functions allowing to: - (+) Initialize the CRYP - (+) DeInitialize the CRYP - (+) Initialize the CRYP MSP - (+) DeInitialize the CRYP MSP - (+) configure CRYP (HAL_CRYP_SetConfig) with the specified parameters in the CRYP_ConfigTypeDef - Parameters which are configured in This section are : - (+) Key size - (+) Data Type : 32,16, 8 or 1bit - (+) AlgoMode : - - for CRYP1 IP : - ECB and CBC in DES/TDES Standard - ECB,CBC,CTR,GCM/GMAC and CCM in AES Standard. - - for TinyAES2 IP, only ECB,CBC,CTR,GCM/GMAC and CCM in AES Standard are supported. - (+) Get CRYP configuration (HAL_CRYP_GetConfig) from the specified parameters in the CRYP_HandleTypeDef - - -@endverbatim - * @{ - */ - - -/** - * @brief Initializes the CRYP according to the specified - * parameters in the CRYP_ConfigTypeDef and creates the associated handle. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_Init(CRYP_HandleTypeDef *hcryp) -{ - /* Check the CRYP handle allocation */ - if (hcryp == NULL) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_CRYP_KEYSIZE(hcryp->Init.KeySize)); - assert_param(IS_CRYP_DATATYPE(hcryp->Init.DataType)); - assert_param(IS_CRYP_ALGORITHM(hcryp->Init.Algorithm)); - assert_param(IS_CRYP_INIT(hcryp->Init.KeyIVConfigSkip)); - -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - if (hcryp->State == HAL_CRYP_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hcryp->Lock = HAL_UNLOCKED; - - hcryp->InCpltCallback = HAL_CRYP_InCpltCallback; /* Legacy weak InCpltCallback */ - hcryp->OutCpltCallback = HAL_CRYP_OutCpltCallback; /* Legacy weak OutCpltCallback */ - hcryp->ErrorCallback = HAL_CRYP_ErrorCallback; /* Legacy weak ErrorCallback */ - - if (hcryp->MspInitCallback == NULL) - { - hcryp->MspInitCallback = HAL_CRYP_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware */ - hcryp->MspInitCallback(hcryp); - } -#else - if (hcryp->State == HAL_CRYP_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hcryp->Lock = HAL_UNLOCKED; - - /* Init the low level hardware */ - HAL_CRYP_MspInit(hcryp); - } -#endif /* (USE_HAL_CRYP_REGISTER_CALLBACKS) */ - - /* Set the key size(This bit field is dont care in the DES or TDES modes) data type and Algorithm */ -#if defined (CRYP) - - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_DATATYPE | CRYP_CR_KEYSIZE | CRYP_CR_ALGOMODE, - hcryp->Init.DataType | hcryp->Init.KeySize | hcryp->Init.Algorithm); - -#else /*AES*/ - - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE | AES_CR_KEYSIZE | AES_CR_CHMOD, - hcryp->Init.DataType | hcryp->Init.KeySize | hcryp->Init.Algorithm); - -#endif /* End AES or CRYP*/ - - /* Reset Error Code field */ - hcryp->ErrorCode = HAL_CRYP_ERROR_NONE; - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Set the default CRYP phase */ - hcryp->Phase = CRYP_PHASE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief De-Initializes the CRYP peripheral. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_DeInit(CRYP_HandleTypeDef *hcryp) -{ - /* Check the CRYP handle allocation */ - if (hcryp == NULL) - { - return HAL_ERROR; - } - - /* Set the default CRYP phase */ - hcryp->Phase = CRYP_PHASE_READY; - - /* Reset CrypInCount and CrypOutCount */ - hcryp->CrypInCount = 0; - hcryp->CrypOutCount = 0; - hcryp->CrypHeaderCount = 0; - - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - - if (hcryp->MspDeInitCallback == NULL) - { - hcryp->MspDeInitCallback = HAL_CRYP_MspDeInit; /* Legacy weak MspDeInit */ - } - /* DeInit the low level hardware */ - hcryp->MspDeInitCallback(hcryp); - -#else - - /* DeInit the low level hardware: CLOCK, NVIC.*/ - HAL_CRYP_MspDeInit(hcryp); - -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hcryp); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Configure the CRYP according to the specified - * parameters in the CRYP_ConfigTypeDef - * @param hcryp: pointer to a CRYP_HandleTypeDef structure - * @param pConf: pointer to a CRYP_ConfigTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_SetConfig(CRYP_HandleTypeDef *hcryp, CRYP_ConfigTypeDef *pConf) -{ - /* Check the CRYP handle allocation */ - if ((hcryp == NULL) || (pConf == NULL)) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_CRYP_KEYSIZE(pConf->KeySize)); - assert_param(IS_CRYP_DATATYPE(pConf->DataType)); - assert_param(IS_CRYP_ALGORITHM(pConf->Algorithm)); - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Set CRYP parameters */ - hcryp->Init.DataType = pConf->DataType; - hcryp->Init.pKey = pConf->pKey; - hcryp->Init.Algorithm = pConf->Algorithm; - hcryp->Init.KeySize = pConf->KeySize; - hcryp->Init.pInitVect = pConf->pInitVect; - hcryp->Init.Header = pConf->Header; - hcryp->Init.HeaderSize = pConf->HeaderSize; - hcryp->Init.B0 = pConf->B0; - hcryp->Init.DataWidthUnit = pConf->DataWidthUnit; - hcryp->Init.KeyIVConfigSkip = pConf->KeyIVConfigSkip; - hcryp->Init.HeaderWidthUnit = pConf->HeaderWidthUnit; - - /* Set the key size(This bit field is dont care in the DES or TDES modes) data type, AlgoMode and operating mode*/ -#if defined (CRYP) - - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_DATATYPE | CRYP_CR_KEYSIZE | CRYP_CR_ALGOMODE, - hcryp->Init.DataType | hcryp->Init.KeySize | hcryp->Init.Algorithm); - -#else /*AES*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE | AES_CR_KEYSIZE | AES_CR_CHMOD, - hcryp->Init.DataType | hcryp->Init.KeySize | hcryp->Init.Algorithm); - - /*clear error flags*/ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_ERR_CLEAR); - -#endif /* End AES or CRYP */ - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - - /* Reset Error Code field */ - hcryp->ErrorCode = HAL_CRYP_ERROR_NONE; - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Set the default CRYP phase */ - hcryp->Phase = CRYP_PHASE_READY; - - /* Return function status */ - return HAL_OK; - } - else - { - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - return HAL_ERROR; - } -} - -/** - * @brief Get CRYP Configuration parameters in associated handle. - * @param pConf: pointer to a CRYP_ConfigTypeDef structure - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_GetConfig(CRYP_HandleTypeDef *hcryp, CRYP_ConfigTypeDef *pConf) -{ - /* Check the CRYP handle allocation */ - if ((hcryp == NULL) || (pConf == NULL)) - { - return HAL_ERROR; - } - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Get CRYP parameters */ - pConf->DataType = hcryp->Init.DataType; - pConf->pKey = hcryp->Init.pKey; - pConf->Algorithm = hcryp->Init.Algorithm; - pConf->KeySize = hcryp->Init.KeySize ; - pConf->pInitVect = hcryp->Init.pInitVect; - pConf->Header = hcryp->Init.Header ; - pConf->HeaderSize = hcryp->Init.HeaderSize; - pConf->B0 = hcryp->Init.B0; - pConf->DataWidthUnit = hcryp->Init.DataWidthUnit; - pConf->KeyIVConfigSkip = hcryp->Init.KeyIVConfigSkip; - pConf->HeaderWidthUnit = hcryp->Init.HeaderWidthUnit; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Return function status */ - return HAL_OK; - } - else - { - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - return HAL_ERROR; - } -} -/** - * @brief Initializes the CRYP MSP. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval None - */ -__weak void HAL_CRYP_MspInit(CRYP_HandleTypeDef *hcryp) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcryp); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CRYP_MspInit can be implemented in the user file - */ -} - -/** - * @brief DeInitializes CRYP MSP. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval None - */ -__weak void HAL_CRYP_MspDeInit(CRYP_HandleTypeDef *hcryp) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcryp); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CRYP_MspDeInit can be implemented in the user file - */ -} - -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User CRYP Callback - * To be used instead of the weak predefined callback - * @param hcryp cryp handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_CRYP_INPUT_COMPLETE_CB_ID Input FIFO transfer completed callback ID - * @arg @ref HAL_CRYP_OUTPUT_COMPLETE_CB_ID Output FIFO transfer completed callback ID - * @arg @ref HAL_CRYP_ERROR_CB_ID Error callback ID - * @arg @ref HAL_CRYP_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_CRYP_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_CRYP_RegisterCallback(CRYP_HandleTypeDef *hcryp, HAL_CRYP_CallbackIDTypeDef CallbackID, - pCRYP_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hcryp); - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - switch (CallbackID) - { - case HAL_CRYP_INPUT_COMPLETE_CB_ID : - hcryp->InCpltCallback = pCallback; - break; - - case HAL_CRYP_OUTPUT_COMPLETE_CB_ID : - hcryp->OutCpltCallback = pCallback; - break; - - case HAL_CRYP_ERROR_CB_ID : - hcryp->ErrorCallback = pCallback; - break; - - case HAL_CRYP_MSPINIT_CB_ID : - hcryp->MspInitCallback = pCallback; - break; - - case HAL_CRYP_MSPDEINIT_CB_ID : - hcryp->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hcryp->State == HAL_CRYP_STATE_RESET) - { - switch (CallbackID) - { - case HAL_CRYP_MSPINIT_CB_ID : - hcryp->MspInitCallback = pCallback; - break; - - case HAL_CRYP_MSPDEINIT_CB_ID : - hcryp->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hcryp); - - return status; -} - -/** - * @brief Unregister an CRYP Callback - * CRYP callback is redirected to the weak predefined callback - * @param hcryp cryp handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_CRYP_INPUT_COMPLETE_CB_ID Input FIFO transfer completed callback ID - * @arg @ref HAL_CRYP_OUTPUT_COMPLETE_CB_ID Output FIFO transfer completed callback ID - * @arg @ref HAL_CRYP_ERROR_CB_ID Error callback ID - * @arg @ref HAL_CRYP_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_CRYP_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_CRYP_UnRegisterCallback(CRYP_HandleTypeDef *hcryp, HAL_CRYP_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hcryp); - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - switch (CallbackID) - { - case HAL_CRYP_INPUT_COMPLETE_CB_ID : - hcryp->InCpltCallback = HAL_CRYP_InCpltCallback; /* Legacy weak InCpltCallback */ - break; - - case HAL_CRYP_OUTPUT_COMPLETE_CB_ID : - hcryp->OutCpltCallback = HAL_CRYP_OutCpltCallback; /* Legacy weak OutCpltCallback */ - break; - - case HAL_CRYP_ERROR_CB_ID : - hcryp->ErrorCallback = HAL_CRYP_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_CRYP_MSPINIT_CB_ID : - hcryp->MspInitCallback = HAL_CRYP_MspInit; - break; - - case HAL_CRYP_MSPDEINIT_CB_ID : - hcryp->MspDeInitCallback = HAL_CRYP_MspDeInit; - break; - - default : - /* Update the error code */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hcryp->State == HAL_CRYP_STATE_RESET) - { - switch (CallbackID) - { - case HAL_CRYP_MSPINIT_CB_ID : - hcryp->MspInitCallback = HAL_CRYP_MspInit; - break; - - case HAL_CRYP_MSPDEINIT_CB_ID : - hcryp->MspDeInitCallback = HAL_CRYP_MspDeInit; - break; - - default : - /* Update the error code */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hcryp); - - return status; -} -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup CRYP_Exported_Functions_Group2 Encrypt Decrypt functions - * @brief processing functions. - * -@verbatim - ============================================================================== - ##### Encrypt Decrypt functions ##### - ============================================================================== - [..] This section provides API allowing to Encrypt/Decrypt Data following - Standard DES/TDES or AES, and Algorithm configured by the user: - (+) Standard DES/TDES only supported by CRYP1 IP, below list of Algorithm supported : - - Electronic Code Book(ECB) - - Cipher Block Chaining (CBC) - (+) Standard AES supported by CRYP1 IP & TinyAES, list of Algorithm supported: - - Electronic Code Book(ECB) - - Cipher Block Chaining (CBC) - - Counter mode (CTR) - - Cipher Block Chaining (CBC) - - Counter mode (CTR) - - Galois/counter mode (GCM) - - Counter with Cipher Block Chaining-Message(CCM) - [..] Three processing functions are available: - (+) Polling mode : HAL_CRYP_Encrypt & HAL_CRYP_Decrypt - (+) Interrupt mode : HAL_CRYP_Encrypt_IT & HAL_CRYP_Decrypt_IT - (+) DMA mode : HAL_CRYP_Encrypt_DMA & HAL_CRYP_Decrypt_DMA - -@endverbatim - * @{ - */ - - -/** - * @brief Encryption mode. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Input: Pointer to the input buffer (plaintext) - * @param Size: Length of the plaintext buffer in word. - * @param Output: Pointer to the output buffer(ciphertext) - * @param Timeout: Specify Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_Encrypt(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output, - uint32_t Timeout) -{ - uint32_t algo; - HAL_StatusTypeDef status; - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Change state Busy */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ - hcryp->CrypInCount = 0U; - hcryp->CrypOutCount = 0U; - hcryp->pCrypInBuffPtr = Input; - hcryp->pCrypOutBuffPtr = Output; - - /* Calculate Size parameter in Byte*/ - if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) - { - hcryp->Size = Size * 4U; - } - else - { - hcryp->Size = Size; - } - -#if defined (CRYP) - /* Set Encryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_ENCRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; - - switch (algo) - { - case CRYP_DES_ECB: - case CRYP_DES_CBC: - case CRYP_TDES_ECB: - case CRYP_TDES_CBC: - - /*Set Key */ - hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); - if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); - } - - /*Set Initialization Vector (IV)*/ - if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - } - - /* Flush FIFO */ - HAL_CRYP_FIFO_FLUSH(hcryp); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Statrt DES/TDES encryption process */ - status = CRYP_TDES_Process(hcryp, Timeout); - break; - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES encryption */ - status = CRYP_AES_Encrypt(hcryp, Timeout); - break; - #if defined (CRYP_CR_ALGOMODE_AES_GCM) - case CRYP_AES_GCM: - - /* AES GCM encryption */ - status = CRYP_AESGCM_Process(hcryp, Timeout); - - break; - - case CRYP_AES_CCM: - - /* AES CCM encryption */ - status = CRYP_AESCCM_Process(hcryp, Timeout); - break; - #endif /* GCM CCM defined*/ - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - -#else /*AES*/ - - /* Set the operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & AES_CR_CHMOD; - - switch (algo) - { - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES encryption */ - status = CRYP_AES_Encrypt(hcryp, Timeout); - break; - - case CRYP_AES_GCM_GMAC: - - /* AES GCM encryption */ - status = CRYP_AESGCM_Process(hcryp, Timeout) ; - break; - - case CRYP_AES_CCM: - - /* AES CCM encryption */ - status = CRYP_AESCCM_Process(hcryp, Timeout); - break; - - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } -#endif /*end AES or CRYP */ - - if (status == HAL_OK) - { - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - } - } - else - { - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - return HAL_ERROR; - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Decryption mode. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Input: Pointer to the input buffer (ciphertext ) - * @param Size: Length of the plaintext buffer in word. - * @param Output: Pointer to the output buffer(plaintext) - * @param Timeout: Specify Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_Decrypt(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output, - uint32_t Timeout) -{ - HAL_StatusTypeDef status; - uint32_t algo; - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Change state Busy */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ - hcryp->CrypInCount = 0U; - hcryp->CrypOutCount = 0U; - hcryp->pCrypInBuffPtr = Input; - hcryp->pCrypOutBuffPtr = Output; - - /* Calculate Size parameter in Byte*/ - if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) - { - hcryp->Size = Size * 4U; - } - else - { - hcryp->Size = Size; - } - -#if defined (CRYP) - - /* Set Decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_DECRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; - - switch (algo) - { - case CRYP_DES_ECB: - case CRYP_DES_CBC: - case CRYP_TDES_ECB: - case CRYP_TDES_CBC: - - /*Set Key */ - hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); - if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); - } - - /*Set Initialization Vector (IV)*/ - if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - } - - /* Flush FIFO */ - HAL_CRYP_FIFO_FLUSH(hcryp); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Start DES/TDES decryption process */ - status = CRYP_TDES_Process(hcryp, Timeout); - - break; - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES decryption */ - status = CRYP_AES_Decrypt(hcryp, Timeout); - break; - #if defined (CRYP_CR_ALGOMODE_AES_GCM) - case CRYP_AES_GCM: - - /* AES GCM decryption */ - status = CRYP_AESGCM_Process(hcryp, Timeout) ; - break; - - case CRYP_AES_CCM: - - /* AES CCM decryption */ - status = CRYP_AESCCM_Process(hcryp, Timeout); - break; - #endif /* GCM CCM defined*/ - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - -#else /*AES*/ - - /* Set Decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & AES_CR_CHMOD; - - switch (algo) - { - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES decryption */ - status = CRYP_AES_Decrypt(hcryp, Timeout); - break; - - case CRYP_AES_GCM_GMAC: - - /* AES GCM decryption */ - status = CRYP_AESGCM_Process(hcryp, Timeout) ; - break; - - case CRYP_AES_CCM: - - /* AES CCM decryption */ - status = CRYP_AESCCM_Process(hcryp, Timeout); - break; - - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } -#endif /* End AES or CRYP */ - - if (status == HAL_OK) - { - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - } - } - else - { - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - return HAL_ERROR; - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Encryption in interrupt mode. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Input: Pointer to the input buffer (plaintext) - * @param Size: Length of the plaintext buffer in word - * @param Output: Pointer to the output buffer(ciphertext) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_Encrypt_IT(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output) -{ - uint32_t algo; - HAL_StatusTypeDef status = HAL_OK; - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Change state Busy */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ - hcryp->CrypInCount = 0U; - hcryp->CrypOutCount = 0U; - hcryp->pCrypInBuffPtr = Input; - hcryp->pCrypOutBuffPtr = Output; - - /* Calculate Size parameter in Byte*/ - if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) - { - hcryp->Size = Size * 4U; - } - else - { - hcryp->Size = Size; - } - -#if defined (CRYP) - - /* Set encryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_ENCRYPT); - - /* algo get algorithm selected */ - algo = (hcryp->Instance->CR & CRYP_CR_ALGOMODE); - - switch (algo) - { - case CRYP_DES_ECB: - case CRYP_DES_CBC: - case CRYP_TDES_ECB: - case CRYP_TDES_CBC: - - /*Set Key */ - hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); - if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); - } - /* Set the Initialization Vector*/ - if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - } - - /* Flush FIFO */ - HAL_CRYP_FIFO_FLUSH(hcryp); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Enable interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); - - /* Enable CRYP to start DES/TDES process*/ - __HAL_CRYP_ENABLE(hcryp); - break; - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - status = CRYP_AES_Encrypt_IT(hcryp); - break; - #if defined (CRYP_CR_ALGOMODE_AES_GCM) - case CRYP_AES_GCM: - - status = CRYP_AESGCM_Process_IT(hcryp) ; - break; - - case CRYP_AES_CCM: - - status = CRYP_AESCCM_Process_IT(hcryp); - break; - #endif /* GCM CCM defined*/ - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - status = HAL_ERROR; - break; - } - -#else /* AES */ - - /* Set encryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & AES_CR_CHMOD; - - switch (algo) - { - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES encryption */ - status = CRYP_AES_Encrypt_IT(hcryp); - break; - - case CRYP_AES_GCM_GMAC: - - /* AES GCM encryption */ - status = CRYP_AESGCM_Process_IT(hcryp) ; - break; - - case CRYP_AES_CCM: - - /* AES CCM encryption */ - status = CRYP_AESCCM_Process_IT(hcryp); - break; - - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - status = HAL_ERROR; - break; - } -#endif /*end AES or CRYP*/ - - } - else - { - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - status = HAL_ERROR; - } - - /* Return function status */ - return status; -} - -/** - * @brief Decryption in itnterrupt mode. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Input: Pointer to the input buffer (ciphertext ) - * @param Size: Length of the plaintext buffer in word. - * @param Output: Pointer to the output buffer(plaintext) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_Decrypt_IT(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output) -{ - uint32_t algo; - HAL_StatusTypeDef status = HAL_OK; - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Change state Busy */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ - hcryp->CrypInCount = 0U; - hcryp->CrypOutCount = 0U; - hcryp->pCrypInBuffPtr = Input; - hcryp->pCrypOutBuffPtr = Output; - - /* Calculate Size parameter in Byte*/ - if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) - { - hcryp->Size = Size * 4U; - } - else - { - hcryp->Size = Size; - } - -#if defined (CRYP) - - /* Set decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_DECRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; - - switch (algo) - { - case CRYP_DES_ECB: - case CRYP_DES_CBC: - case CRYP_TDES_ECB: - case CRYP_TDES_CBC: - - /*Set Key */ - hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); - if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); - } - - /* Set the Initialization Vector*/ - if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - } - /* Flush FIFO */ - HAL_CRYP_FIFO_FLUSH(hcryp); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Enable interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); - - /* Enable CRYP and start DES/TDES process*/ - __HAL_CRYP_ENABLE(hcryp); - - break; - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES decryption */ - status = CRYP_AES_Decrypt_IT(hcryp); - break; - #if defined (CRYP_CR_ALGOMODE_AES_GCM) - case CRYP_AES_GCM: - - /* AES GCM decryption */ - status = CRYP_AESGCM_Process_IT(hcryp) ; - break; - - case CRYP_AES_CCM: - - /* AES CCMdecryption */ - status = CRYP_AESCCM_Process_IT(hcryp); - break; - #endif /* GCM CCM defined*/ - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - status = HAL_ERROR; - break; - } - -#else /*AES*/ - - /* Set decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & AES_CR_CHMOD; - - switch (algo) - { - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES decryption */ - status = CRYP_AES_Decrypt_IT(hcryp); - break; - - case CRYP_AES_GCM_GMAC: - - /* AES GCM decryption */ - status = CRYP_AESGCM_Process_IT(hcryp) ; - break; - - case CRYP_AES_CCM: - - /* AES CCM decryption */ - status = CRYP_AESCCM_Process_IT(hcryp); - break; - - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - status = HAL_ERROR; - break; - } -#endif /* End AES or CRYP */ - - } - else - { - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - status = HAL_ERROR; - } - - /* Return function status */ - return status; -} - -/** - * @brief Encryption in DMA mode. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Input: Pointer to the input buffer (plaintext) - * @param Size: Length of the plaintext buffer in word. - * @param Output: Pointer to the output buffer(ciphertext) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_Encrypt_DMA(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output) -{ - uint32_t algo; - HAL_StatusTypeDef status = HAL_OK; - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Change state Busy */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr and pCrypOutBuffPtr parameters*/ - hcryp->CrypInCount = 0U; - hcryp->CrypOutCount = 0U; - hcryp->pCrypInBuffPtr = Input; - hcryp->pCrypOutBuffPtr = Output; - - /* Calculate Size parameter in Byte*/ - if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) - { - hcryp->Size = Size * 4U; - } - else - { - hcryp->Size = Size; - } - -#if defined (CRYP) - - /* Set encryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_ENCRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; - - switch (algo) - { - case CRYP_DES_ECB: - case CRYP_DES_CBC: - case CRYP_TDES_ECB: - case CRYP_TDES_CBC: - - /*Set Key */ - hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); - if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); - } - - /* Set the Initialization Vector*/ - if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - } - - /* Flush FIFO */ - HAL_CRYP_FIFO_FLUSH(hcryp); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Start DMA process transfer for DES/TDES */ - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)(hcryp->Size) / 4U), - (uint32_t)(hcryp->pCrypOutBuffPtr)); - break; - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - } - } - - if (DoKeyIVConfig == 1U) - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set the Initialization Vector*/ - if (hcryp->Init.Algorithm != CRYP_AES_ECB) - { - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1U); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2U); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3U); - } - } /* if (DoKeyIVConfig == 1U) */ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Start DMA process transfer for AES */ - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)(hcryp->Size) / 4U), - (uint32_t)(hcryp->pCrypOutBuffPtr)); - break; - #if defined (CRYP_CR_ALGOMODE_AES_GCM) - case CRYP_AES_GCM: - /* AES GCM encryption */ - status = CRYP_AESGCM_Process_DMA(hcryp) ; - break; - - case CRYP_AES_CCM: - /* AES CCM encryption */ - status = CRYP_AESCCM_Process_DMA(hcryp); - break; - #endif /* GCM CCM defined*/ - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - status = HAL_ERROR; - break; - } - -#else /*AES*/ - /* Set encryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & AES_CR_CHMOD; - - switch (algo) - { - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - } - } - - if (DoKeyIVConfig == 1U) - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set the Initialization Vector*/ - if (hcryp->Init.Algorithm != CRYP_AES_ECB) - { - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); - } - } /* if (DoKeyIVConfig == 1U) */ - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Start DMA process transfer for AES */ - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (hcryp->Size / 4U), (uint32_t)(hcryp->pCrypOutBuffPtr)); - break; - - case CRYP_AES_GCM_GMAC: - /* AES GCM encryption */ - status = CRYP_AESGCM_Process_DMA(hcryp) ; - break; - - case CRYP_AES_CCM: - /* AES CCM encryption */ - status = CRYP_AESCCM_Process_DMA(hcryp); - break; - - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - status = HAL_ERROR; - break; - } -#endif /* End AES or CRYP */ - - } - else - { - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - status = HAL_ERROR; - } - - /* Return function status */ - return status; -} - -/** - * @brief Decryption in DMA mode. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Input: Pointer to the input buffer (ciphertext ) - * @param Size: Length of the plaintext buffer in word - * @param Output: Pointer to the output buffer(plaintext) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYP_Decrypt_DMA(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output) -{ - uint32_t algo; - HAL_StatusTypeDef status = HAL_OK; - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - - /* Change state Busy */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Reset CrypInCount, CrypOutCount and Initialize pCrypInBuffPtr, pCrypOutBuffPtr and Size parameters*/ - hcryp->CrypInCount = 0U; - hcryp->CrypOutCount = 0U; - hcryp->pCrypInBuffPtr = Input; - hcryp->pCrypOutBuffPtr = Output; - - /* Calculate Size parameter in Byte*/ - if (hcryp->Init.DataWidthUnit == CRYP_DATAWIDTHUNIT_WORD) - { - hcryp->Size = Size * 4U; - } - else - { - hcryp->Size = Size; - } - -#if defined (CRYP) - - /* Set decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGODIR, CRYP_OPERATINGMODE_DECRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & CRYP_CR_ALGOMODE; - - switch (algo) - { - case CRYP_DES_ECB: - case CRYP_DES_CBC: - case CRYP_TDES_ECB: - case CRYP_TDES_CBC: - - /*Set Key */ - hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); - if ((hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); - } - - /* Set the Initialization Vector*/ - if ((hcryp->Init.Algorithm == CRYP_DES_CBC) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - } - - /* Flush FIFO */ - HAL_CRYP_FIFO_FLUSH(hcryp); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Start DMA process transfer for DES/TDES */ - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)(hcryp->Size) / 4U), - (uint32_t)(hcryp->pCrypOutBuffPtr)); - break; - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES decryption */ - status = CRYP_AES_Decrypt_DMA(hcryp); - break; - #if defined (CRYP_CR_ALGOMODE_AES_GCM) - case CRYP_AES_GCM: - /* AES GCM decryption */ - status = CRYP_AESGCM_Process_DMA(hcryp) ; - break; - - case CRYP_AES_CCM: - /* AES CCM decryption */ - status = CRYP_AESCCM_Process_DMA(hcryp); - break; - #endif /* GCM CCM defined*/ - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - status = HAL_ERROR; - break; - } - -#else /*AES*/ - - /* Set decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); - - /* algo get algorithm selected */ - algo = hcryp->Instance->CR & AES_CR_CHMOD; - - switch (algo) - { - - case CRYP_AES_ECB: - case CRYP_AES_CBC: - case CRYP_AES_CTR: - - /* AES decryption */ - status = CRYP_AES_Decrypt_DMA(hcryp); - break; - - case CRYP_AES_GCM_GMAC: - /* AES GCM decryption */ - status = CRYP_AESGCM_Process_DMA(hcryp) ; - break; - - case CRYP_AES_CCM: - /* AES CCM decryption */ - status = CRYP_AESCCM_Process_DMA(hcryp); - break; - - default: - hcryp->ErrorCode |= HAL_CRYP_ERROR_NOT_SUPPORTED; - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - status = HAL_ERROR; - break; - } -#endif /* End AES or CRYP */ - } - else - { - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - status = HAL_ERROR; - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup CRYP_Exported_Functions_Group3 CRYP IRQ handler management - * @brief CRYP IRQ handler. - * -@verbatim - ============================================================================== - ##### CRYP IRQ handler management ##### - ============================================================================== -[..] This section provides CRYP IRQ handler and callback functions. - (+) HAL_CRYP_IRQHandler CRYP interrupt request - (+) HAL_CRYP_InCpltCallback input data transfer complete callback - (+) HAL_CRYP_OutCpltCallback output data transfer complete callback - (+) HAL_CRYP_ErrorCallback CRYP error callback - (+) HAL_CRYP_GetState return the CRYP state - (+) HAL_CRYP_GetError return the CRYP error code -@endverbatim - * @{ - */ - -/** - * @brief This function handles cryptographic interrupt request. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval None - */ -void HAL_CRYP_IRQHandler(CRYP_HandleTypeDef *hcryp) -{ - -#if defined (CRYP) - - uint32_t itstatus = hcryp->Instance->MISR; - - if ((itstatus & (CRYP_IT_INI | CRYP_IT_OUTI)) != 0U) - { - if ((hcryp->Init.Algorithm == CRYP_DES_ECB) || (hcryp->Init.Algorithm == CRYP_DES_CBC) - || (hcryp->Init.Algorithm == CRYP_TDES_ECB) || (hcryp->Init.Algorithm == CRYP_TDES_CBC)) - { - CRYP_TDES_IT(hcryp); /* DES or TDES*/ - } - else if ((hcryp->Init.Algorithm == CRYP_AES_ECB) || (hcryp->Init.Algorithm == CRYP_AES_CBC) - || (hcryp->Init.Algorithm == CRYP_AES_CTR)) - { - CRYP_AES_IT(hcryp); /*AES*/ - } - #if defined (CRYP_CR_ALGOMODE_AES_GCM) - else if ((hcryp->Init.Algorithm == CRYP_AES_GCM) || (hcryp->Init.Algorithm == CRYP_CR_ALGOMODE_AES_CCM)) - { - /* if header phase */ - if ((hcryp->Instance->CR & CRYP_PHASE_HEADER) == CRYP_PHASE_HEADER) - { - CRYP_GCMCCM_SetHeaderPhase_IT(hcryp); - } - else /* if payload phase */ - { - CRYP_GCMCCM_SetPayloadPhase_IT(hcryp); - } - } - #endif /* GCM CCM defined*/ - else - { - /* Nothing to do */ - } - } - -#else /*AES*/ - if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_IT_CCF) != RESET) - { - if (__HAL_CRYP_GET_IT_SOURCE(hcryp, CRYP_IT_CCFIE) != RESET) - { - - /* Clear computation complete flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) - { - - /* if header phase */ - if ((hcryp->Instance->CR & CRYP_PHASE_HEADER) == CRYP_PHASE_HEADER) - { - CRYP_GCMCCM_SetHeaderPhase_IT(hcryp); - } - else /* if payload phase */ - { - CRYP_GCMCCM_SetPayloadPhase_IT(hcryp); - } - } - else if (hcryp->Init.Algorithm == CRYP_AES_CCM) - { - /* if header phase */ - if (hcryp->Init.HeaderSize >= hcryp->CrypHeaderCount) - { - CRYP_GCMCCM_SetHeaderPhase_IT(hcryp); - } - else /* if payload phase */ - { - CRYP_GCMCCM_SetPayloadPhase_IT(hcryp); - } - } - else /* AES Algorithm ECB,CBC or CTR*/ - { - CRYP_AES_IT(hcryp); - } - } - } - /* Check if error occurred */ - if (__HAL_CRYP_GET_IT_SOURCE(hcryp, CRYP_IT_ERRIE) != RESET) - { - /* If write Error occurred */ - if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_IT_WRERR) != RESET) - { - hcryp->ErrorCode |= HAL_CRYP_ERROR_WRITE; - } - /* If read Error occurred */ - if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_IT_RDERR) != RESET) - { - hcryp->ErrorCode |= HAL_CRYP_ERROR_READ; - } - } -#endif /* End AES or CRYP */ -} - -/** - * @brief Return the CRYP error code. - * @param hcryp : pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for the CRYP IP - * @retval CRYP error code - */ -uint32_t HAL_CRYP_GetError(CRYP_HandleTypeDef *hcryp) -{ - return hcryp->ErrorCode; -} - -/** - * @brief Returns the CRYP state. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @retval HAL state - */ -HAL_CRYP_STATETypeDef HAL_CRYP_GetState(CRYP_HandleTypeDef *hcryp) -{ - return hcryp->State; -} - -/** - * @brief Input FIFO transfer completed callback. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @retval None - */ -__weak void HAL_CRYP_InCpltCallback(CRYP_HandleTypeDef *hcryp) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcryp); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CRYP_InCpltCallback can be implemented in the user file - */ -} - -/** - * @brief Output FIFO transfer completed callback. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @retval None - */ -__weak void HAL_CRYP_OutCpltCallback(CRYP_HandleTypeDef *hcryp) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcryp); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_CRYP_OutCpltCallback can be implemented in the user file - */ -} - -/** - * @brief CRYP error callback. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @retval None - */ -__weak void HAL_CRYP_ErrorCallback(CRYP_HandleTypeDef *hcryp) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hcryp); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_CRYP_ErrorCallback could be implemented in the user file - */ -} -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup CRYP_Private_Functions - * @{ - */ - -#if defined (CRYP) - -/** - * @brief Encryption in ECB/CBC Algorithm with DES/TDES standard. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Timeout: specify Timeout value - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_TDES_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t temp[2]; /* Temporary CrypOutBuff */ - uint16_t incount; /* Temporary CrypInCount Value */ - uint16_t outcount; /* Temporary CrypOutCount Value */ - uint32_t i; - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - /*Start processing*/ - while ((hcryp->CrypInCount < (hcryp->Size / 4U)) && (outcount < (hcryp->Size / 4U))) - { - /* Temporary CrypInCount Value */ - incount = hcryp->CrypInCount; - /* Write plain data and get cipher data */ - if (((hcryp->Instance->SR & CRYP_FLAG_IFNF) != 0x0U) && (incount < (hcryp->Size / 4U))) - { - /* Write the input block in the IN FIFO */ - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - - /* Wait for OFNE flag to be raised */ - if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state & errorCode*/ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - if (((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) && (outcount < (hcryp->Size / 4U))) - { - /* Read the output block from the Output FIFO and put them in temporary Buffer then get CrypOutBuff from temporary buffer */ - for (i = 0U; i < 2U; i++) - { - temp[i] = hcryp->Instance->DOUT; - } - i = 0U; - while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 2U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } - } - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - } - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief CRYP block input/output data handling under interruption with DES/TDES standard. - * @note The function is called under interruption only, once - * interruptions have been enabled by CRYP_Decrypt_IT() and CRYP_Encrypt_IT(). - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @retval none - */ -static void CRYP_TDES_IT(CRYP_HandleTypeDef *hcryp) -{ - uint32_t temp[2]; /* Temporary CrypOutBuff */ - uint32_t i; - - if (hcryp->State == HAL_CRYP_STATE_BUSY) - { - if (__HAL_CRYP_GET_IT(hcryp, CRYP_IT_INI) != 0x0U) - { - if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_FLAG_INRIS) != 0x0U) - { - /* Write input block in the IN FIFO */ - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - - if (hcryp->CrypInCount == ((uint16_t)(hcryp->Size) / 4U)) - { - /* Disable interruption */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); - /* Call the input data transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - } - if (__HAL_CRYP_GET_IT(hcryp, CRYP_IT_OUTI) != 0x0U) - { - if (__HAL_CRYP_GET_FLAG(hcryp, CRYP_FLAG_OUTRIS) != 0x0U) - { - /* Read the output block from the Output FIFO and put them in temporary Buffer then get CrypOutBuff from temporary buffer */ - for (i = 0U; i < 2U; i++) - { - temp[i] = hcryp->Instance->DOUT; - } - i = 0U; - while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 2U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } - if (hcryp->CrypOutCount == ((uint16_t)(hcryp->Size) / 4U)) - { - /* Disable interruption */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_OUTI); - - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - /* Call output transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Output complete callback*/ - hcryp->OutCpltCallback(hcryp); -#else - /*Call legacy weak Output complete callback*/ - HAL_CRYP_OutCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - } - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } -} - -#endif /* CRYP */ - -/** - * @brief Encryption in ECB/CBC & CTR Algorithm with AES Standard - * @param hcryp: pointer to a CRYP_HandleTypeDef structure - * @param Timeout: specify Timeout value - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AES_Encrypt(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint16_t outcount; /* Temporary CrypOutCount Value */ - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - } - } - - if (DoKeyIVConfig == 1U) - { - - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - if (hcryp->Init.Algorithm != CRYP_AES_ECB) - { - /* Set the Initialization Vector*/ -#if defined (AES) - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#else /* CRYP */ - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#endif /* End AES or CRYP */ - } - } /* if (DoKeyIVConfig == 1U) */ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - while ((hcryp->CrypInCount < (hcryp->Size / 4U)) && (outcount < (hcryp->Size / 4U))) - { - /* Write plain Ddta and get cipher data */ - CRYP_AES_ProcessData(hcryp, Timeout); - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - } - - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Encryption in ECB/CBC & CTR mode with AES Standard using interrupt mode - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AES_Encrypt_IT(CRYP_HandleTypeDef *hcryp) -{ - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - } - } - - if (DoKeyIVConfig == 1U) - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - if (hcryp->Init.Algorithm != CRYP_AES_ECB) - { - /* Set the Initialization Vector*/ -#if defined (AES) - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); - -#else /* CRYP */ - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#endif /* End AES or CRYP */ - } - } /* if (DoKeyIVConfig == 1U) */ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - if (hcryp->Size != 0U) - { -#if defined (AES) - - /* Enable computation complete flag and error interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Write the input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - -#else /* CRYP */ - - /* Enable interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - -#endif /* End AES or CRYP */ - } - else - { - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Decryption in ECB/CBC & CTR mode with AES Standard - * @param hcryp: pointer to a CRYP_HandleTypeDef structure - * @param Timeout: Specify Timeout value - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AES_Decrypt(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint16_t outcount; /* Temporary CrypOutCount Value */ - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - } - } - - if (DoKeyIVConfig == 1U) - { - /* Key preparation for ECB/CBC */ - if (hcryp->Init.Algorithm != CRYP_AES_CTR) - { -#if defined (AES) - if (hcryp->AutoKeyDerivation == DISABLE)/*Mode 2 Key preparation*/ - { - /* Set key preparation for decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION); - - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Wait for CCF flag to be raised */ - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state & error code*/ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - /* Return to decryption operating mode(Mode 3)*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); - } - else /*Mode 4 : decryption & Key preparation*/ - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set decryption & Key preparation operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT); - } -#else /* CRYP */ - /* change ALGOMODE to key preparation for decryption*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_CR_ALGOMODE_AES_KEY); - - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Wait for BUSY flag to be raised */ - if (CRYP_WaitOnBUSYFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Turn back to ALGOMODE of the configuration */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, hcryp->Init.Algorithm); - -#endif /* End AES or CRYP */ - } - else /*Algorithm CTR */ - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - } - - /* Set IV */ - if (hcryp->Init.Algorithm != CRYP_AES_ECB) - { - /* Set the Initialization Vector*/ -#if defined (AES) - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#else /* CRYP */ - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#endif /* End AES or CRYP */ - } - } /* if (DoKeyIVConfig == 1U) */ - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - while ((hcryp->CrypInCount < (hcryp->Size / 4U)) && (outcount < (hcryp->Size / 4U))) - { - /* Write plain data and get cipher data */ - CRYP_AES_ProcessData(hcryp, Timeout); - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - } - - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Return function status */ - return HAL_OK; -} -/** - * @brief Decryption in ECB/CBC & CTR mode with AES Standard using interrupt mode - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AES_Decrypt_IT(CRYP_HandleTypeDef *hcryp) -{ - __IO uint32_t count = 0U; - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - } - } - - if (DoKeyIVConfig == 1U) - { - /* Key preparation for ECB/CBC */ - if (hcryp->Init.Algorithm != CRYP_AES_CTR) - { -#if defined (AES) - if (hcryp->AutoKeyDerivation == DISABLE)/*Mode 2 Key preparation*/ - { - /* Set key preparation for decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION); - - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Wait for CCF flag to be raised */ - count = CRYP_TIMEOUT_KEYPREPARATION; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - /* Return to decryption operating mode(Mode 3)*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); - } - else /*Mode 4 : decryption & key preparation*/ - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set decryption & key preparation operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT); - } -#else /* CRYP */ - - /* change ALGOMODE to key preparation for decryption*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_CR_ALGOMODE_AES_KEY); - - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Wait for BUSY flag to be raised */ - count = CRYP_TIMEOUT_KEYPREPARATION; - do - { - count-- ; - if (count == 0U) - { - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_SET(hcryp->Instance->SR, CRYP_FLAG_BUSY)); - - /* Turn back to ALGOMODE of the configuration */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, hcryp->Init.Algorithm); - -#endif /* End AES or CRYP */ - } - - else /*Algorithm CTR */ - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - } - - /* Set IV */ - if (hcryp->Init.Algorithm != CRYP_AES_ECB) - { - /* Set the Initialization Vector*/ -#if defined (AES) - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#else /* CRYP */ - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#endif /* End AES or CRYP */ - } - } /* if (DoKeyIVConfig == 1U) */ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - if (hcryp->Size != 0U) - { - -#if defined (AES) - - /* Enable computation complete flag and error interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Write the input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - -#else /* CRYP */ - - /* Enable interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - -#endif /* End AES or CRYP */ - } - else - { - /* Process locked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - } - - /* Return function status */ - return HAL_OK; -} -/** - * @brief Decryption in ECB/CBC & CTR mode with AES Standard using DMA mode - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AES_Decrypt_DMA(CRYP_HandleTypeDef *hcryp) -{ - __IO uint32_t count = 0U; - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - } - } - if (DoKeyIVConfig == 1U) - { - /* Key preparation for ECB/CBC */ - if (hcryp->Init.Algorithm != CRYP_AES_CTR) - { -#if defined (AES) - if (hcryp->AutoKeyDerivation == DISABLE)/*Mode 2 key preparation*/ - { - /* Set key preparation for decryption operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION); - - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Wait for CCF flag to be raised */ - count = CRYP_TIMEOUT_KEYPREPARATION; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - /* Return to decryption operating mode(Mode 3)*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_DECRYPT); - } - else /*Mode 4 : decryption & key preparation*/ - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set decryption & Key preparation operating mode*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT); - } -#else /* CRYP */ - /* change ALGOMODE to key preparation for decryption*/ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_CR_ALGOMODE_AES_KEY); - - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Wait for BUSY flag to be raised */ - count = CRYP_TIMEOUT_KEYPREPARATION; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_SET(hcryp->Instance->SR, CRYP_FLAG_BUSY)); - - /* Turn back to ALGOMODE of the configuration */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, hcryp->Init.Algorithm); - -#endif /* End AES or CRYP */ - } - else /*Algorithm CTR */ - { - /* Set the Key*/ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - } - - if (hcryp->Init.Algorithm != CRYP_AES_ECB) - { - /* Set the Initialization Vector*/ -#if defined (AES) - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#else /* CRYP */ - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); -#endif /* End AES or CRYP */ - } - } /* if (DoKeyIVConfig == 1U) */ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - if (hcryp->Size != 0U) - { - /* Set the input and output addresses and start DMA transfer */ - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (hcryp->Size / 4U), (uint32_t)(hcryp->pCrypOutBuffPtr)); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - } - - /* Return function status */ - return HAL_OK; -} - - -/** - * @brief DMA CRYP input data process complete callback. - * @param hdma: DMA handle - * @retval None - */ -static void CRYP_DMAInCplt(DMA_HandleTypeDef *hdma) -{ - CRYP_HandleTypeDef *hcryp = (CRYP_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Disable the DMA transfer for input FIFO request by resetting the DIEN bit - in the DMACR register */ -#if defined (CRYP) - hcryp->Instance->DMACR &= (uint32_t)(~CRYP_DMACR_DIEN); - -#else /* AES */ - CLEAR_BIT(hcryp->Instance->CR, AES_CR_DMAINEN); - - /* TinyAES2, No output on CCM AES, unlock should be done when input data process complete */ - if ((hcryp->Init.Algorithm & CRYP_AES_CCM) == CRYP_AES_CCM) - { - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - /* Change the CRYP state to ready */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - } -#endif /* End AES or CRYP */ - - /* Call input data transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA CRYP output data process complete callback. - * @param hdma: DMA handle - * @retval None - */ -static void CRYP_DMAOutCplt(DMA_HandleTypeDef *hdma) -{ - CRYP_HandleTypeDef *hcryp = (CRYP_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Disable the DMA transfer for output FIFO request by resetting - the DOEN bit in the DMACR register */ - -#if defined (CRYP) - - hcryp->Instance->DMACR &= (uint32_t)(~CRYP_DMACR_DOEN); - #if defined (CRYP_CR_ALGOMODE_AES_GCM) - if ((hcryp->Init.Algorithm & CRYP_AES_GCM) != CRYP_AES_GCM) - { - /* Disable CRYP (not allowed in GCM)*/ - __HAL_CRYP_DISABLE(hcryp); - } - - #else /*NO GCM CCM */ - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - #endif /* GCM CCM defined*/ -#else /* AES */ - - CLEAR_BIT(hcryp->Instance->CR, AES_CR_DMAOUTEN); - - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - if ((hcryp->Init.Algorithm & CRYP_AES_GCM_GMAC) != CRYP_AES_GCM_GMAC) - { - /* Disable CRYP (not allowed in GCM)*/ - __HAL_CRYP_DISABLE(hcryp); - } -#endif /* End AES or CRYP */ - - /* Change the CRYP state to ready */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - /* Call output data transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Output complete callback*/ - hcryp->OutCpltCallback(hcryp); -#else - /*Call legacy weak Output complete callback*/ - HAL_CRYP_OutCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA CRYP communication error callback. - * @param hdma: DMA handle - * @retval None - */ -static void CRYP_DMAError(DMA_HandleTypeDef *hdma) -{ - CRYP_HandleTypeDef *hcryp = (CRYP_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* DMA error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; - -#if defined (AES) - - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - -#endif /* AES */ - - /* Call error callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ -} - -/** - * @brief Set the DMA configuration and start the DMA transfer - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param inputaddr: address of the input buffer - * @param Size: size of the input buffer, must be a multiple of 16. - * @param outputaddr: address of the output buffer - * @retval None - */ -static void CRYP_SetDMAConfig(CRYP_HandleTypeDef *hcryp, uint32_t inputaddr, uint16_t Size, uint32_t outputaddr) -{ - /* Set the CRYP DMA transfer complete callback */ - hcryp->hdmain->XferCpltCallback = CRYP_DMAInCplt; - - /* Set the DMA input error callback */ - hcryp->hdmain->XferErrorCallback = CRYP_DMAError; - - /* Set the CRYP DMA transfer complete callback */ - hcryp->hdmaout->XferCpltCallback = CRYP_DMAOutCplt; - - /* Set the DMA output error callback */ - hcryp->hdmaout->XferErrorCallback = CRYP_DMAError; - -#if defined (CRYP) - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - - /* Enable the input DMA Stream */ - if (HAL_DMA_Start_IT(hcryp->hdmain, inputaddr, (uint32_t)&hcryp->Instance->DIN, Size) != HAL_OK) - { - /* DMA error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; - - /* Call error callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - /* Enable the output DMA Stream */ - if (HAL_DMA_Start_IT(hcryp->hdmaout, (uint32_t)&hcryp->Instance->DOUT, outputaddr, Size) != HAL_OK) - { - /* DMA error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; - - /* Call error callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - /* Enable In/Out DMA request */ - hcryp->Instance->DMACR = CRYP_DMACR_DOEN | CRYP_DMACR_DIEN; - -#else /* AES */ - - if (((hcryp->Init.Algorithm & CRYP_AES_GCM_GMAC) != CRYP_AES_GCM_GMAC) - && ((hcryp->Init.Algorithm & CRYP_AES_CCM) != CRYP_AES_CCM)) - { - /* Enable CRYP (not allowed in GCM & CCM)*/ - __HAL_CRYP_ENABLE(hcryp); - } - - /* Enable the DMA input stream */ - if (HAL_DMA_Start_IT(hcryp->hdmain, inputaddr, (uint32_t)&hcryp->Instance->DINR, Size) != HAL_OK) - { - /* DMA error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; - - /* Call error callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - /* Enable the DMA output stream */ - if (HAL_DMA_Start_IT(hcryp->hdmaout, (uint32_t)&hcryp->Instance->DOUTR, outputaddr, Size) != HAL_OK) - { - /* DMA error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_DMA; - - /* Call error callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - /*AES2v1.1.1 : CCM authentication : no init phase, only header and final phase */ - /* Enable In and Out DMA requests */ - if ((hcryp->Init.Algorithm & CRYP_AES_CCM) == CRYP_AES_CCM) - { - /* Enable only In DMA requests for CCM*/ - SET_BIT(hcryp->Instance->CR, (AES_CR_DMAINEN)); - } - else - { - /* Enable In and Out DMA requests */ - SET_BIT(hcryp->Instance->CR, (AES_CR_DMAINEN | AES_CR_DMAOUTEN)); - } -#endif /* End AES or CRYP */ -} - -/** - * @brief Process Data: Write Input data in polling mode and used in AES functions. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Timeout: Specify Timeout value - * @retval None - */ -static void CRYP_AES_ProcessData(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - - uint32_t temp[4]; /* Temporary CrypOutBuff */ - uint32_t i; -#if defined (CRYP) - uint16_t incount; /* Temporary CrypInCount Value */ - uint16_t outcount; /* Temporary CrypOutCount Value */ -#endif - -#if defined (CRYP) - - /*Temporary CrypOutCount Value*/ - incount = hcryp->CrypInCount; - - if (((hcryp->Instance->SR & CRYP_FLAG_IFNF) != 0x0U) && (incount < (hcryp->Size / 4U))) - { - /* Write the input block in the IN FIFO */ - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - - /* Wait for OFNE flag to be raised */ - if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state & error code*/ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - if (((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) && (outcount < (hcryp->Size / 4U))) - { - /* Read the output block from the Output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer */ - for (i = 0U; i < 4U; i++) - { - temp[i] = hcryp->Instance->DOUT; - } - i = 0U; - while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 4U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } - } - -#else /* AES */ - - /* Write the input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - - /* Wait for CCF flag to be raised */ - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - /* Read the output block from the output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer*/ - for (i = 0U; i < 4U; i++) - { - temp[i] = hcryp->Instance->DOUTR; - } - i = 0U; - while ((hcryp->CrypOutCount < ((hcryp->Size + 3U) / 4U)) && (i < 4U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } -#endif /* End AES or CRYP */ -} - -/** - * @brief Handle CRYP block input/output data handling under interruption. - * @note The function is called under interruption only, once - * interruptions have been enabled by HAL_CRYP_Encrypt_IT or HAL_CRYP_Decrypt_IT. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @retval HAL status - */ -static void CRYP_AES_IT(CRYP_HandleTypeDef *hcryp) -{ - uint32_t temp[4]; /* Temporary CrypOutBuff */ - uint32_t i; -#if defined (CRYP) - uint16_t incount; /* Temporary CrypInCount Value */ - uint16_t outcount; /* Temporary CrypOutCount Value */ -#endif - - if (hcryp->State == HAL_CRYP_STATE_BUSY) - { -#if defined (CRYP) - - /*Temporary CrypOutCount Value*/ - incount = hcryp->CrypInCount; - if (((hcryp->Instance->SR & CRYP_FLAG_IFNF) != 0x0U) && (incount < (hcryp->Size / 4U))) - { - /* Write the input block in the IN FIFO */ - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - if (hcryp->CrypInCount == ((uint16_t)(hcryp->Size) / 4U)) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); - - /* Call the input data transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - if (((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) && (outcount < (hcryp->Size / 4U))) - { - /* Read the output block from the output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer */ - for (i = 0U; i < 4U; i++) - { - temp[i] = hcryp->Instance->DOUT; - } - i = 0U; - while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 4U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } - if (hcryp->CrypOutCount == ((uint16_t)(hcryp->Size) / 4U)) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_OUTI); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Call Output transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Output complete callback*/ - hcryp->OutCpltCallback(hcryp); -#else - /*Call legacy weak Output complete callback*/ - HAL_CRYP_OutCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - -#else /*AES*/ - - /* Read the output block from the output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer*/ - for (i = 0U; i < 4U; i++) - { - temp[i] = hcryp->Instance->DOUTR; - } - i = 0U; - while ((hcryp->CrypOutCount < ((hcryp->Size + 3U) / 4U)) && (i < 4U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } - - if (hcryp->CrypOutCount == (hcryp->Size / 4U)) - { - /* Disable Computation Complete flag and errors interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - - /* Call Output transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Output complete callback*/ - hcryp->OutCpltCallback(hcryp); -#else - /*Call legacy weak Output complete callback*/ - HAL_CRYP_OutCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - else - { - /* Write the input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - - if (hcryp->CrypInCount == (hcryp->Size / 4U)) - { - /* Call Input transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } -#endif /* End AES or CRYP */ - - } - else - { - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Writes Key in Key registers. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param KeySize: Size of Key - * @retval None - */ -static void CRYP_SetKey(CRYP_HandleTypeDef *hcryp, uint32_t KeySize) -{ -#if defined (CRYP) - - switch (KeySize) - { - case CRYP_KEYSIZE_256B: - hcryp->Instance->K0LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K0RR = *(uint32_t *)(hcryp->Init.pKey + 1); - hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 5); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 6); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 7); - break; - case CRYP_KEYSIZE_192B: - hcryp->Instance->K1LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K1RR = *(uint32_t *)(hcryp->Init.pKey + 1); - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 5); - break; - case CRYP_KEYSIZE_128B: - hcryp->Instance->K2LR = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->K2RR = *(uint32_t *)(hcryp->Init.pKey + 1); - hcryp->Instance->K3LR = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->K3RR = *(uint32_t *)(hcryp->Init.pKey + 3); - - break; - default: - break; - } -#else /*AES*/ - switch (KeySize) - { - case CRYP_KEYSIZE_256B: - hcryp->Instance->KEYR7 = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->KEYR6 = *(uint32_t *)(hcryp->Init.pKey + 1); - hcryp->Instance->KEYR5 = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->KEYR4 = *(uint32_t *)(hcryp->Init.pKey + 3); - hcryp->Instance->KEYR3 = *(uint32_t *)(hcryp->Init.pKey + 4); - hcryp->Instance->KEYR2 = *(uint32_t *)(hcryp->Init.pKey + 5); - hcryp->Instance->KEYR1 = *(uint32_t *)(hcryp->Init.pKey + 6); - hcryp->Instance->KEYR0 = *(uint32_t *)(hcryp->Init.pKey + 7); - break; - case CRYP_KEYSIZE_128B: - hcryp->Instance->KEYR3 = *(uint32_t *)(hcryp->Init.pKey); - hcryp->Instance->KEYR2 = *(uint32_t *)(hcryp->Init.pKey + 1); - hcryp->Instance->KEYR1 = *(uint32_t *)(hcryp->Init.pKey + 2); - hcryp->Instance->KEYR0 = *(uint32_t *)(hcryp->Init.pKey + 3); - - break; - default: - break; - } -#endif /* End AES or CRYP */ -} - -#if defined (CRYP_CR_ALGOMODE_AES_GCM)|| defined (AES) -/** - * @brief Encryption/Decryption process in AES GCM mode and prepare the authentication TAG - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Timeout: Timeout duration - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AESGCM_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t tickstart; - uint32_t wordsize = (uint32_t)(hcryp->Size) / 4U ; - uint16_t outcount; /* Temporary CrypOutCount Value */ - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ - } - } - else - { - hcryp->SizesSum = hcryp->Size; - } - - if (DoKeyIVConfig == 1U) - { - /* Reset CrypHeaderCount */ - hcryp->CrypHeaderCount = 0U; - - /****************************** Init phase **********************************/ - - CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - -#if defined(CRYP) - - /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /*Wait for the CRYPEN bit to be cleared*/ - while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - -#else /* AES */ - /* Workaround 1 : only AES. - Datatype configuration must be 32 bits during Init phase. Only, after Init, and before re - enabling the IP, datatype different from 32 bits can be configured.*/ - /* Select DATATYPE 32 */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, CRYP_DATATYPE_32B); - - /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /* just wait for hash computation */ - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked & return error */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - -#endif /* End AES or CRYP */ - - /************************ Header phase *************************************/ - - if (CRYP_GCMCCM_SetHeaderPhase(hcryp, Timeout) != HAL_OK) - { - return HAL_ERROR; - } - - /*************************Payload phase ************************************/ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - -#if defined(CRYP) - - /* Disable the CRYP peripheral */ - __HAL_CRYP_DISABLE(hcryp); - - /* Select payload phase once the header phase is performed */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - -#else /* AES */ - - /* Select payload phase once the header phase is performed */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); - -#endif /* End AES or CRYP */ - } /* if (DoKeyIVConfig == 1U) */ - - if ((hcryp->Size % 16U) != 0U) - { - /* recalculate wordsize */ - wordsize = ((wordsize / 4U) * 4U) ; - } - - /* Get tick */ - tickstart = HAL_GetTick(); - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - /* Write input data and get output Data */ - while ((hcryp->CrypInCount < wordsize) && (outcount < wordsize)) - { - /* Write plain data and get cipher data */ - CRYP_AES_ProcessData(hcryp, Timeout); - - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state & error code */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - - if ((hcryp->Size % 16U) != 0U) - { - /* Workaround 2 : CRYP1 & AES generates correct TAG for GCM mode only when input block size is multiple of - 128 bits. If lthe size of the last block of payload is inferior to 128 bits, when GCM encryption - is selected, then the TAG message will be wrong.*/ - CRYP_Workaround(hcryp, Timeout); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Encryption/Decryption process in AES GCM mode and prepare the authentication TAG in interrupt mode - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AESGCM_Process_IT(CRYP_HandleTypeDef *hcryp) -{ - __IO uint32_t count = 0U; - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ -#if defined(AES) - uint32_t loopcounter; - uint32_t lastwordsize; - uint32_t npblb; -#endif /* AES */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ - } - } - else - { - hcryp->SizesSum = hcryp->Size; - } - - /* Configure Key, IV and process message (header and payload) */ - if (DoKeyIVConfig == 1U) - { - /* Reset CrypHeaderCount */ - hcryp->CrypHeaderCount = 0U; - - /******************************* Init phase *********************************/ - - CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - -#if defined(CRYP) - /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /*Wait for the CRYPEN bit to be cleared*/ - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN); - -#else /* AES */ - - /* Workaround 1 : only AES - Datatype configuration must be 32 bits during INIT phase. Only, after INIT, and before re - enabling the IP, datatype different from 32 bits can be configured.*/ - /* Select DATATYPE 32 */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, CRYP_DATATYPE_32B); - - /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /* just wait for hash computation */ - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - -#endif /* End AES or CRYP */ - - /***************************** Header phase *********************************/ - -#if defined(CRYP) - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* Enable interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - -#else /* AES */ - - /* Workaround 1: only AES , before re-enabling the IP, datatype can be configured*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* Enable computation complete flag and error interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - if (hcryp->Init.HeaderSize == 0U) /*header phase is skipped*/ - { - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Select payload phase once the header phase is performed */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_PAYLOAD); - - /* Write the payload Input block in the IN FIFO */ - if (hcryp->Size == 0U) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - } - else if (hcryp->Size >= 16U) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - if (hcryp->CrypInCount == (hcryp->Size / 4U)) - { - /* Call Input transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - else /* Size < 16Bytes : first block is the last block*/ - { - /* Workaround not implemented*/ - /* Size should be %4 otherwise Tag will be incorrectly generated for GCM Encryption: - Workaround is implemented in polling mode, so if last block of - payload <128bit don't use CRYP_Encrypt_IT otherwise TAG is incorrectly generated for GCM Encryption. */ - - /* Compute the number of padding bytes in last block of payload */ - npblb = 16U - (uint32_t)(hcryp->Size); - - /* Number of valid words (lastwordsize) in last block */ - if ((npblb % 4U) == 0U) - { - lastwordsize = (16U - npblb) / 4U; - } - else - { - lastwordsize = ((16U - npblb) / 4U) + 1U; - } - - /* last block optionally pad the data with zeros*/ - for (loopcounter = 0U; loopcounter < lastwordsize ; loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (loopcounter < 4U) - { - /* pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - } - } - else if ((hcryp->Init.HeaderSize) < 4U) - { - for (loopcounter = 0U; loopcounter < hcryp->Init.HeaderSize ; loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - while (loopcounter < 4U) - { - /* pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Select payload phase once the header phase is performed */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); - - /* Call Input transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - else if ((hcryp->Init.HeaderSize) >= 4U) - { - /* Write the input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++; - } - else - { - /* Nothing to do */ - } - -#endif /* End AES or CRYP */ - } /* end of if (DoKeyIVConfig == 1U) */ - - /* Return function status */ - return HAL_OK; -} - - -/** - * @brief Encryption/Decryption process in AES GCM mode and prepare the authentication TAG using DMA - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AESGCM_Process_DMA(CRYP_HandleTypeDef *hcryp) -{ - __IO uint32_t count = 0U; - uint32_t wordsize; - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ - } - } - else - { - hcryp->SizesSum = hcryp->Size; - } - - if (DoKeyIVConfig == 1U) - { - /* Reset CrypHeaderCount */ - hcryp->CrypHeaderCount = 0U; - - /*************************** Init phase ************************************/ - - CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - -#if defined(CRYP) - /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ - hcryp->Instance->IV0LR = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IV0RR = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IV1LR = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IV1RR = *(uint32_t *)(hcryp->Init.pInitVect + 3); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /*Wait for the CRYPEN bit to be cleared*/ - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN); - -#else /* AES */ - - /*Workaround 1 : only AES - Datatype configuration must be 32 bits during Init phase. Only, after Init, and before re - enabling the IP, datatype different from 32 bits can be configured.*/ - /* Select DATATYPE 32 */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, CRYP_DATATYPE_32B); - - /* Set the initialization vector and the counter : Initial Counter Block (ICB)*/ - hcryp->Instance->IVR3 = *(uint32_t *)(hcryp->Init.pInitVect); - hcryp->Instance->IVR2 = *(uint32_t *)(hcryp->Init.pInitVect + 1); - hcryp->Instance->IVR1 = *(uint32_t *)(hcryp->Init.pInitVect + 2); - hcryp->Instance->IVR0 = *(uint32_t *)(hcryp->Init.pInitVect + 3); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /* just wait for hash computation */ - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - -#endif /* End AES or CRYP */ - - /************************ Header phase *************************************/ - - if (CRYP_GCMCCM_SetHeaderPhase_DMA(hcryp) != HAL_OK) - { - return HAL_ERROR; - } - - /************************ Payload phase ************************************/ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - -#if defined(CRYP) - - /* Disable the CRYP peripheral */ - __HAL_CRYP_DISABLE(hcryp); - -#endif /* CRYP */ - - /* Select payload phase once the header phase is performed */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); - - } /* if (DoKeyIVConfig == 1U) */ - - if (hcryp->Size != 0U) - { - /* CRYP1 IP V < 2.2.1 Size should be %4 otherwise Tag will be incorrectly generated for GCM Encryption: - Workaround is implemented in polling mode, so if last block of - payload <128bit don't use DMA mode otherwise TAG is incorrectly generated . */ - /* Set the input and output addresses and start DMA transfer */ - if ((hcryp->Size % 16U) == 0U) - { - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (hcryp->Size / 4U), (uint32_t)(hcryp->pCrypOutBuffPtr)); - } - else /*to compute last word<128bits, otherwise it will not be encrypted/decrypted */ - { - wordsize = (uint32_t)(hcryp->Size) + (16U - ((uint32_t)(hcryp->Size) % 16U)) ; - - /* Set the input and output addresses and start DMA transfer, pCrypOutBuffPtr size should be %4 */ - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)wordsize / 4U), - (uint32_t)(hcryp->pCrypOutBuffPtr)); - } - } - else - { - /* Process unLocked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state and phase */ - hcryp->State = HAL_CRYP_STATE_READY; - } - - /* Return function status */ - return HAL_OK; -} - - -/** - * @brief AES CCM encryption/decryption processing in polling mode - * for TinyAES IP, no encrypt/decrypt performed, only authentication preparation. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Timeout: Timeout duration - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AESCCM_Process(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t tickstart; - uint32_t wordsize = (uint32_t)(hcryp->Size) / 4U; - uint16_t outcount; /* Temporary CrypOutCount Value */ - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ -#if defined(AES) - uint32_t loopcounter; - uint32_t npblb; - uint32_t lastwordsize; -#endif /* AES */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ - } - } - else - { - hcryp->SizesSum = hcryp->Size; - } - - if (DoKeyIVConfig == 1U) - { - - /* Reset CrypHeaderCount */ - hcryp->CrypHeaderCount = 0U; - -#if defined(CRYP) - - /********************** Init phase ******************************************/ - - CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set the initialization vector (IV) with CTR1 information */ - hcryp->Instance->IV0LR = (hcryp->Init.B0[0]) & CRYP_CCM_CTR1_0; - hcryp->Instance->IV0RR = hcryp->Init.B0[1]; - hcryp->Instance->IV1LR = hcryp->Init.B0[2]; - hcryp->Instance->IV1RR = (hcryp->Init.B0[3] & CRYP_CCM_CTR1_1) | CRYP_CCM_CTR1_2; - - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /*Write B0 packet into CRYP_DIN Register*/ - if (hcryp->Init.DataType == CRYP_DATATYPE_8B) - { - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 1)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 2)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 3)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) - { - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 1), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 2), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 3), 16); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) - { - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 1)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 2)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 3)); - } - else - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 1); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 2); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 3); - } - /* Get tick */ - tickstart = HAL_GetTick(); - - /*Wait for the CRYPEN bit to be cleared*/ - while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } -#else /* AES */ - /*AES2v1.1.1 : CCM authentication : no init phase, only header and final phase */ - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* configured encryption mode */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set the initialization vector with zero values*/ - hcryp->Instance->IVR3 = 0U; - hcryp->Instance->IVR2 = 0U; - hcryp->Instance->IVR1 = 0U; - hcryp->Instance->IVR0 = 0U; - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /*Write the B0 packet into CRYP_DIN*/ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 1); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 2); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 3); - - /* wait until the end of computation */ - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked & return error */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* From that point the whole message must be processed, first the Header then the payload. - First the Header block(B1) : associated data length expressed in bytes concatenated with Associated Data (A)*/ - - if (hcryp->Init.HeaderSize != 0U) - { - if ((hcryp->Init.HeaderSize % 4U) == 0U) - { - /* HeaderSize %4, no padding */ - for (loopcounter = 0U; (loopcounter < hcryp->Init.HeaderSize); loopcounter += 4U) - { - /* Write the Input block in the Data Input register */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - } - else - { - /*Write Header block in the IN FIFO without last block */ - for (loopcounter = 0U; (loopcounter < ((hcryp->Init.HeaderSize) - (hcryp->Init.HeaderSize % 4U))); loopcounter += 4U) - { - /* Write the input block in the data input register */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; (loopcounter < (hcryp->Init.HeaderSize % 4U)); loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - while (loopcounter < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - } - } /* if (DoKeyIVConfig == 1U) */ - /* Then the payload: cleartext payload (not the ciphertext payload). - Write input Data, no output Data to get */ - if (hcryp->Size != 0U) - { - if ((hcryp->Size % 16U) != 0U) - { - /* recalculate wordsize */ - wordsize = ((wordsize / 4U) * 4U) ; - } - - /* Get tick */ - tickstart = HAL_GetTick(); - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - while ((hcryp->CrypInCount < wordsize) && (outcount < wordsize)) - { - /* Write plain data and get cipher data */ - CRYP_AES_ProcessData(hcryp, Timeout); - - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - - if ((hcryp->Size % 16U) != 0U) - { - /* Compute the number of padding bytes in last block of payload */ - npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); - - /* Number of valid words (lastwordsize) in last block */ - if ((npblb % 4U) == 0U) - { - lastwordsize = (16U - npblb) / 4U; - } - else - { - lastwordsize = ((16U - npblb) / 4U) + 1U; - } - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter ++) - { - /* Write the last input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (loopcounter < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0U; - loopcounter++; - } - /* Wait for CCF flag to be raised */ - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - } - } -#endif /* End AES or CRYP */ - -#if defined(CRYP) - - /************************* Header phase *************************************/ - /* Header block(B1) : associated data length expressed in bytes concatenated - with Associated Data (A)*/ - - if (CRYP_GCMCCM_SetHeaderPhase(hcryp, Timeout) != HAL_OK) - { - return HAL_ERROR; - } - - /********************** Payload phase ***************************************/ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Disable the CRYP peripheral */ - __HAL_CRYP_DISABLE(hcryp); - - /* Select payload phase once the header phase is performed */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - } /* if (DoKeyIVConfig == 1U) */ - - if ((hcryp->Size % 16U) != 0U) - { - /* recalculate wordsize */ - wordsize = ((wordsize / 4U) * 4U) ; - } - /* Get tick */ - tickstart = HAL_GetTick(); - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - /* Write input data and get output data */ - while ((hcryp->CrypInCount < wordsize) && (outcount < wordsize)) - { - /* Write plain data and get cipher data */ - CRYP_AES_ProcessData(hcryp, Timeout); - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - - if ((hcryp->Size % 16U) != 0U) - { - /* CRYP Workaround : CRYP1 generates correct TAG during CCM decryption only when ciphertext blocks size is multiple of - 128 bits. If lthe size of the last block of payload is inferior to 128 bits, when CCM decryption - is selected, then the TAG message will be wrong.*/ - CRYP_Workaround(hcryp, Timeout); - } -#endif /* CRYP */ - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief AES CCM encryption/decryption process in interrupt mode - * for TinyAES IP, no encrypt/decrypt performed, only authentication preparation. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AESCCM_Process_IT(CRYP_HandleTypeDef *hcryp) -{ - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ -#if defined(CRYP) - __IO uint32_t count = 0U; -#endif /* CRYP */ - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ - } - } - else - { - hcryp->SizesSum = hcryp->Size; - } - - /* Configure Key, IV and process message (header and payload) */ - if (DoKeyIVConfig == 1U) - { - /* Reset CrypHeaderCount */ - hcryp->CrypHeaderCount = 0U; - -#if defined(CRYP) - - /************ Init phase ************/ - - CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set the initialization vector (IV) with CTR1 information */ - hcryp->Instance->IV0LR = (hcryp->Init.B0[0]) & CRYP_CCM_CTR1_0; - hcryp->Instance->IV0RR = hcryp->Init.B0[1]; - hcryp->Instance->IV1LR = hcryp->Init.B0[2]; - hcryp->Instance->IV1RR = (hcryp->Init.B0[3] & CRYP_CCM_CTR1_1) | CRYP_CCM_CTR1_2; - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /*Write the B0 packet into CRYP_DIN Register*/ - if (hcryp->Init.DataType == CRYP_DATATYPE_8B) - { - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 1)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 2)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 3)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) - { - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 1), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 2), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 3), 16); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) - { - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 1)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 2)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 3)); - } - else - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 1); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 2); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 3); - } - /*Wait for the CRYPEN bit to be cleared*/ - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN); - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - } /* end of if (DoKeyIVConfig == 1U) */ - - /* Enable interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI); - - /* Enable CRYP */ - __HAL_CRYP_ENABLE(hcryp); - -#else /* AES */ - - /*AES2v1.1.1 : CCM authentication : no init phase, only header and final phase */ - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* configured mode and encryption mode */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set the initialization vector with zero values*/ - hcryp->Instance->IVR3 = 0U; - hcryp->Instance->IVR2 = 0U; - hcryp->Instance->IVR1 = 0U; - hcryp->Instance->IVR0 = 0U; - - /* Enable interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /*Write the B0 packet into CRYP_DIN*/ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 1); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 2); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 3); - - } /* end of if (DoKeyIVConfig == 1U) */ -#endif /* End AES or CRYP */ - - /* Return function status */ - return HAL_OK; -} -/** - * @brief AES CCM encryption/decryption process in DMA mode - * for TinyAES IP, no encrypt/decrypt performed, only authentication preparation. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_AESCCM_Process_DMA(CRYP_HandleTypeDef *hcryp) -{ - uint32_t wordsize; - __IO uint32_t count = 0U; - uint32_t DoKeyIVConfig = 1U; /* By default, carry out peripheral Key and IV configuration */ -#if defined(AES) - uint32_t loopcounter; - uint32_t npblb; - uint32_t lastwordsize; -#endif - - if (hcryp->Init.KeyIVConfigSkip == CRYP_KEYIVCONFIG_ONCE) - { - if (hcryp->KeyIVConfig == 1U) - { - /* If the Key and IV configuration has to be done only once - and if it has already been done, skip it */ - DoKeyIVConfig = 0U; - hcryp->SizesSum += hcryp->Size; /* Compute message total payload length */ - } - else - { - /* If the Key and IV configuration has to be done only once - and if it has not been done already, do it and set KeyIVConfig - to keep track it won't have to be done again next time */ - hcryp->KeyIVConfig = 1U; - hcryp->SizesSum = hcryp->Size; /* Merely store payload length */ - } - } - else - { - hcryp->SizesSum = hcryp->Size; - } - - if (DoKeyIVConfig == 1U) - { - - /* Reset CrypHeaderCount */ - hcryp->CrypHeaderCount = 0U; - -#if defined(CRYP) - - /************************** Init phase **************************************/ - - CRYP_SET_PHASE(hcryp, CRYP_PHASE_INIT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set the initialization vector (IV) with CTR1 information */ - hcryp->Instance->IV0LR = (hcryp->Init.B0[0]) & CRYP_CCM_CTR1_0; - hcryp->Instance->IV0RR = hcryp->Init.B0[1]; - hcryp->Instance->IV1LR = hcryp->Init.B0[2]; - hcryp->Instance->IV1RR = (hcryp->Init.B0[3] & CRYP_CCM_CTR1_1) | CRYP_CCM_CTR1_2; - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /*Write the B0 packet into CRYP_DIN Register*/ - if (hcryp->Init.DataType == CRYP_DATATYPE_8B) - { - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 1)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 2)); - hcryp->Instance->DIN = __REV(*(uint32_t *)(hcryp->Init.B0 + 3)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) - { - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 1), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 2), 16); - hcryp->Instance->DIN = __ROR(*(uint32_t *)(hcryp->Init.B0 + 3), 16); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) - { - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 1)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 2)); - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(hcryp->Init.B0 + 3)); - } - else - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 1); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 2); - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.B0 + 3); - } - - /*Wait for the CRYPEN bit to be cleared*/ - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while ((hcryp->Instance->CR & CRYP_CR_CRYPEN) == CRYP_CR_CRYPEN); - -#else /* AES */ - - /*AES2v1.1.1 : CCM authentication : no init phase, only header and final phase */ - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* configured encryption mode */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_MODE, CRYP_OPERATINGMODE_ENCRYPT); - - /* Set the key */ - CRYP_SetKey(hcryp, hcryp->Init.KeySize); - - /* Set the initialization vector with zero values*/ - hcryp->Instance->IVR3 = 0U; - hcryp->Instance->IVR2 = 0U; - hcryp->Instance->IVR1 = 0U; - hcryp->Instance->IVR0 = 0U; - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /*Write the B0 packet into CRYP_DIN*/ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 1); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 2); - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.B0 + 3); - - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* From that point the whole message must be processed, first the Header then the payload. - First the Header block(B1) : associated data length expressed in bytes concatenated with Associated Data (A)*/ - - if (hcryp->Init.HeaderSize != 0U) - { - if ((hcryp->Init.HeaderSize % 4U) == 0U) - { - /* HeaderSize %4, no padding */ - for (loopcounter = 0U; (loopcounter < hcryp->Init.HeaderSize); loopcounter += 4U) - { - /* Write the Input block in the Data Input register */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - /* wait until the end of computation */ - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - } - else - { - /*Write Header block in the IN FIFO without last block */ - for (loopcounter = 0U; (loopcounter < ((hcryp->Init.HeaderSize) - (hcryp->Init.HeaderSize % 4U))); loopcounter += 4U) - { - /* Write the input block in the data input register */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; (loopcounter < (hcryp->Init.HeaderSize % 4U)); loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - while (loopcounter < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - } - } /* if (DoKeyIVConfig == 1U) */ - /* Then the payload: cleartext payload (not the ciphertext payload). - Write input Data, no output Data to get */ - if (hcryp->Size != 0U) - { - if (hcryp->Size >= 16U) - { - if ((hcryp->Size % 16U) == 0U) - { - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (hcryp->Size / 4U), (uint32_t)(hcryp->pCrypOutBuffPtr)); - } - else /*to compute last word<128bits, otherwise it will not be encrypted/decrypted */ - { - wordsize = (uint32_t)(hcryp->Size) + (16U - ((uint32_t)(hcryp->Size) % 16U)) ; - - /* Set the input and output addresses and start DMA transfer, pCrypOutBuffPtr size should be %4 */ - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), ((uint16_t)wordsize / 4U), - (uint32_t)(hcryp->pCrypOutBuffPtr)); - } - } - if ((hcryp->Size < 16U) != 0U) - { - /* Compute the number of padding bytes in last block of payload */ - npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); - - /* Number of valid words (lastwordsize) in last block */ - if ((npblb % 4U) == 0U) - { - lastwordsize = (16U - npblb) / 4U; - } - else - { - lastwordsize = ((16U - npblb) / 4U) + 1U; - } - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter ++) - { - /* Write the last input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (loopcounter < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0U; - loopcounter++; - } - count = CRYP_TIMEOUT_GCMCCMINITPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state and phase */ - hcryp->State = HAL_CRYP_STATE_READY; - } - } - else - { - /* Process unLocked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state and phase */ - hcryp->State = HAL_CRYP_STATE_READY; - } -#endif /* AES */ -#if defined(CRYP) - /********************* Header phase *****************************************/ - - if (CRYP_GCMCCM_SetHeaderPhase_DMA(hcryp) != HAL_OK) - { - return HAL_ERROR; - } - - /******************** Payload phase *****************************************/ - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Disable the CRYP peripheral */ - __HAL_CRYP_DISABLE(hcryp); - - /* Select payload phase once the header phase is performed */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); - - } /* if (DoKeyIVConfig == 1U) */ - if (hcryp->Size != 0U) - { - /* Size should be %4 otherwise Tag will be incorrectly generated for GCM Encryption & CCM Decryption - Workaround is implemented in polling mode, so if last block of - payload <128bit don't use HAL_CRYP_AESGCM_DMA otherwise TAG is incorrectly generated for GCM Encryption. */ - /* Set the input and output addresses and start DMA transfer */ - if ((hcryp->Size % 16U) == 0U) - { - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), hcryp->Size / 4U, (uint32_t)(hcryp->pCrypOutBuffPtr)); - } - else - { - wordsize = (uint32_t)(hcryp->Size) + 16U - ((uint32_t)(hcryp->Size) % 16U) ; - - /* Set the input and output addresses and start DMA transfer, pCrypOutBuffPtr size should be %4*/ - CRYP_SetDMAConfig(hcryp, (uint32_t)(hcryp->pCrypInBuffPtr), (uint16_t)wordsize / 4U, - (uint32_t)(hcryp->pCrypOutBuffPtr)); - } - } - else /*Size = 0*/ - { - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state and phase */ - hcryp->State = HAL_CRYP_STATE_READY; - } -#endif /* CRYP */ - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Sets the payload phase in iterrupt mode - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @retval state - */ -static void CRYP_GCMCCM_SetPayloadPhase_IT(CRYP_HandleTypeDef *hcryp) -{ - uint32_t loopcounter; - uint32_t temp[4]; /* Temporary CrypOutBuff */ - uint32_t lastwordsize; - uint32_t npblb; - uint32_t i; -#if defined(AES) - uint16_t outcount; /* Temporary CrypOutCount Value */ -#endif /* AES */ - - /***************************** Payload phase *******************************/ - -#if defined(CRYP) - if (hcryp->Size == 0U) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - } - - else if (((hcryp->Size / 4U) - (hcryp->CrypInCount)) >= 4U) - { - /* Write the input block in the IN FIFO */ - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - if (((hcryp->Size / 4U) == hcryp->CrypInCount) && ((hcryp->Size % 16U) == 0U)) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); - - /* Call the input data transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - if (hcryp->CrypOutCount < (hcryp->Size / 4U)) - { - /* Read the output block from the Output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer */ - for (i = 0U; i < 4U; i++) - { - temp[i] = hcryp->Instance->DOUT; - } - i = 0U; - while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 4U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } - if (((hcryp->Size / 4U) == hcryp->CrypOutCount) && ((hcryp->Size % 16U) == 0U)) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_OUTI); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Call output transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Output complete callback*/ - hcryp->OutCpltCallback(hcryp); -#else - /*Call legacy weak Output complete callback*/ - HAL_CRYP_OutCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - } - else if ((hcryp->Size % 16U) != 0U) - { - /* Size should be %4 in word and %16 in byte otherwise TAG will be incorrectly generated for GCM Encryption & CCM Decryption - Workaround is implemented in polling mode, so if last block of - payload <128bit don't use CRYP_AESGCM_Encrypt_IT otherwise TAG is incorrectly generated. */ - - /* Compute the number of padding bytes in last block of payload */ - npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); - - /* Number of valid words (lastwordsize) in last block */ - if ((npblb % 4U) == 0U) - { - lastwordsize = (16U - npblb) / 4U; - } - else - { - lastwordsize = ((16U - npblb) / 4U) + 1U; - } - - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter++) - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (loopcounter < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DIN = 0x0U; - loopcounter++; - } - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); - - if ((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) - { - for (i = 0U; i < 4U; i++) - { - temp[i] = hcryp->Instance->DOUT; - } - if (((hcryp->Size) / 4U) == 0U) - { - for (i = 0U; i < ((uint32_t)(hcryp->Size) % 4U); i++) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - } - } - i = 0x0U; - while (((hcryp->CrypOutCount < ((hcryp->Size) / 4U))) && (i < 4U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } - } - if (hcryp->CrypOutCount >= (hcryp->Size / 4U)) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_OUTI | CRYP_IT_INI); - - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Call output transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Output complete callback*/ - hcryp->OutCpltCallback(hcryp); -#else - /*Call legacy weak Output complete callback*/ - HAL_CRYP_OutCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - else - { - /* Nothing to do */ - } -#else /* AES */ - - /* Read the output block from the output FIFO and put them in temporary buffer then get CrypOutBuff from temporary buffer*/ - for (i = 0U; i < 4U; i++) - { - temp[i] = hcryp->Instance->DOUTR; - } - i = 0U; - while ((hcryp->CrypOutCount < ((hcryp->Size + 3U) / 4U)) && (i < 4U)) - { - *(uint32_t *)(hcryp->pCrypOutBuffPtr + hcryp->CrypOutCount) = temp[i]; - hcryp->CrypOutCount++; - i++; - } - /*Temporary CrypOutCount Value*/ - outcount = hcryp->CrypOutCount; - - if ((hcryp->CrypOutCount >= (hcryp->Size / 4U)) && ((outcount * 4U) >= hcryp->Size)) - { - /* Disable computation complete flag and errors interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Call output transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Output complete callback*/ - hcryp->OutCpltCallback(hcryp); -#else - /*Call legacy weak Output complete callback*/ - HAL_CRYP_OutCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - - else if (((hcryp->Size / 4U) - (hcryp->CrypInCount)) >= 4U) - { - /* Write the input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - if ((hcryp->CrypInCount == (hcryp->Size / 4U)) && ((hcryp->Size % 16U) == 0U)) - { - /* Call Input transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - else /* Last block of payload < 128bit*/ - { - /* Workaround not implemented, Size should be %4 otherwise Tag will be incorrectly - generated for GCM Encryption & CCM Decryption. Workaround is implemented in polling mode, so if last block of - payload <128bit don't use CRYP_Encrypt_IT otherwise TAG is incorrectly generated for GCM Encryption & CCM Decryption. */ - - /* Compute the number of padding bytes in last block of payload */ - npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); - - /* Number of valid words (lastwordsize) in last block */ - if ((npblb % 4U) == 0U) - { - lastwordsize = (16U - npblb) / 4U; - } - else - { - lastwordsize = ((16U - npblb) / 4U) + 1U; - } - - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (loopcounter < 4U) - { - /* pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - } -#endif /* AES */ - -} - - -/** - * @brief Sets the header phase in polling mode - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module(Header & HeaderSize) - * @param Timeout: Timeout value - * @retval state - */ -static HAL_StatusTypeDef CRYP_GCMCCM_SetHeaderPhase(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t loopcounter; - uint32_t size_in_bytes; - uint32_t tmp; - uint32_t mask[12] = {0x0U, 0xFF000000U, 0xFFFF0000U, 0xFFFFFF00U, /* 32-bit data type */ - 0x0U, 0x0000FF00U, 0x0000FFFFU, 0xFF00FFFFU, /* 16-bit data type */ - 0x0U, 0x000000FFU, 0x0000FFFFU, 0x00FFFFFFU}; /* 8-bit data type */ - - /***************************** Header phase for GCM/GMAC or CCM *********************************/ - - if (hcryp->Init.HeaderWidthUnit == CRYP_HEADERWIDTHUNIT_WORD) - { - size_in_bytes = hcryp->Init.HeaderSize * 4U; - } - else - { - size_in_bytes = hcryp->Init.HeaderSize; - } - - if (size_in_bytes != 0U) - { - -#if defined(CRYP) - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - if ((size_in_bytes % 16U) == 0U) - { - /* HeaderSize %4, no padding */ - for (loopcounter = 0U; (loopcounter < (size_in_bytes / 4U)); loopcounter += 4U) - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - /* Wait for IFEM to be raised */ - if (CRYP_WaitOnIFEMFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - else - { - /*Write header block in the IN FIFO without last block */ - for (loopcounter = 0U; (loopcounter < ((size_in_bytes / 16U) * 4U)); loopcounter += 4U) - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - /* Wait for IFEM to be raised */ - if (CRYP_WaitOnIFEMFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; (loopcounter < ((size_in_bytes / 4U) % 4U)); loopcounter++) - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - /* If the header size is a multiple of words */ - if ((size_in_bytes % 4U) == 0U) - { - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DIN = 0x0U; - loopcounter++; - } - } - else - { - /* Enter last bytes, padded with zeroes */ - tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - tmp &= mask[(hcryp->Init.DataType * 2U) + (size_in_bytes % 4U)]; - hcryp->Instance->DIN = tmp; - loopcounter++; - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DIN = 0x0U; - loopcounter++; - } - } - /* Wait for CCF IFEM to be raised */ - if (CRYP_WaitOnIFEMFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - /* Wait until the complete message has been processed */ - if (CRYP_WaitOnBUSYFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked & return error */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - -#else /* AES */ - - if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) - { - /* Workaround 1 :only AES before re-enabling the IP, datatype can be configured.*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - } - /* If size_in_bytes is a multiple of blocks (a multiple of four 32-bits words ) */ - if ((size_in_bytes % 16U) == 0U) - { - /* No padding */ - for (loopcounter = 0U; (loopcounter < (size_in_bytes / 4U)); loopcounter += 4U) - { - /* Write the input block in the data input register */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - } - else - { - /*Write header block in the IN FIFO without last block */ - for (loopcounter = 0U; (loopcounter < ((size_in_bytes / 16U) * 4U)); loopcounter += 4U) - { - /* Write the input block in the data input register */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - /* Write last complete words */ - for (loopcounter = 0U; (loopcounter < ((size_in_bytes / 4U) % 4U)); loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - /* If the header size is a multiple of words */ - if ((size_in_bytes % 4U) == 0U) - { - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - } - else - { - /* Enter last bytes, padded with zeroes */ - tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - tmp &= mask[(hcryp->Init.DataType * 2U) + (size_in_bytes % 4U)]; - hcryp->Instance->DINR = tmp; - loopcounter++; - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - } - - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } -#endif /* End AES or CRYP */ - } - else - { -#if defined(AES) - if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) - { - /*Workaround 1: only AES, before re-enabling the IP, datatype can be configured.*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - } -#endif /* AES */ - } - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Sets the header phase when using DMA in process - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module(Header & HeaderSize) - * @retval None - */ -static HAL_StatusTypeDef CRYP_GCMCCM_SetHeaderPhase_DMA(CRYP_HandleTypeDef *hcryp) -{ - __IO uint32_t count = 0U; - uint32_t loopcounter; - uint32_t headersize_in_bytes; - uint32_t tmp; - uint32_t mask[12] = {0x0U, 0xFF000000U, 0xFFFF0000U, 0xFFFFFF00U, /* 32-bit data type */ - 0x0U, 0x0000FF00U, 0x0000FFFFU, 0xFF00FFFFU, /* 16-bit data type */ - 0x0U, 0x000000FFU, 0x0000FFFFU, 0x00FFFFFFU}; /* 8-bit data type */ - - /***************************** Header phase for GCM/GMAC or CCM *********************************/ - if (hcryp->Init.HeaderWidthUnit == CRYP_HEADERWIDTHUNIT_WORD) - { - headersize_in_bytes = hcryp->Init.HeaderSize * 4U; - } - else - { - headersize_in_bytes = hcryp->Init.HeaderSize; - } - - if (headersize_in_bytes != 0U) - { - -#if defined(CRYP) - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - if ((headersize_in_bytes % 16U) == 0U) - { - /* HeaderSize %4, no padding */ - for (loopcounter = 0U; (loopcounter < (headersize_in_bytes / 4U)); loopcounter += 4U) - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - /* Wait for IFEM to be raised */ - count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_IFEM)); - } - } - else - { - /*Write header block in the IN FIFO without last block */ - for (loopcounter = 0U; (loopcounter < ((headersize_in_bytes / 16U) * 4U)); loopcounter += 4U) - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - /* Wait for IFEM to be raised */ - count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_IFEM)); - } - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; (loopcounter < ((headersize_in_bytes / 4U) % 4U)); loopcounter++) - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - /* If the header size is a multiple of words */ - if ((headersize_in_bytes % 4U) == 0U) - { - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DIN = 0x0U; - loopcounter++; - } - } - else - { - /* Enter last bytes, padded with zeroes */ - tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - tmp &= mask[(hcryp->Init.DataType * 2U) + (headersize_in_bytes % 4U)]; - hcryp->Instance->DIN = tmp; - loopcounter++; - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DIN = 0x0U; - loopcounter++; - } - } - /* Wait for IFEM to be raised */ - count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_IFEM)); - } - /* Wait until the complete message has been processed */ - count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_SET(hcryp->Instance->SR, CRYP_FLAG_BUSY)); - -#else /* AES */ - - if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) - { - /* Workaround 1: only AES, before re-enabling the IP, datatype can be configured.*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - } - if ((headersize_in_bytes % 16U) == 0U) - { - /* HeaderSize %4, no padding */ - for (loopcounter = 0U; (loopcounter < (headersize_in_bytes / 4U)); loopcounter += 4U) - { - /* Write the input block in the data input register */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - /*Wait on CCF flag*/ - count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - } - else - { - /*Write header block in the IN FIFO without last block */ - for (loopcounter = 0U; (loopcounter < ((headersize_in_bytes / 16U) * 4U)); loopcounter += 4U) - { - /* Write the Input block in the Data Input register */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - - /*Wait on CCF flag*/ - count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; (loopcounter < ((headersize_in_bytes /4U) % 4U)); loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - /* If the header size is a multiple of words */ - if ((headersize_in_bytes % 4U) == 0U) - { - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - } - else - { - /* Enter last bytes, padded with zeroes */ - tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - tmp &= mask[(hcryp->Init.DataType * 2U) + (headersize_in_bytes % 4U)]; - hcryp->Instance->DINR = tmp; - loopcounter++; - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - } - /*Wait on CCF flag*/ - count = CRYP_TIMEOUT_GCMCCMHEADERPHASE; - do - { - count-- ; - if (count == 0U) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)); - - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - } -#endif /* End AES or CRYP */ - } - else - { -#if defined(AES) - if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) - { - /*Workaround 1: only AES, before re-enabling the IP, datatype can be configured.*/ - MODIFY_REG(hcryp->Instance->CR, AES_CR_DATATYPE, hcryp->Init.DataType); - - /* Select header phase */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_HEADER); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - } -#endif /* AES */ - } - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Sets the header phase in interrupt mode - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module(Header & HeaderSize) - * @retval None - */ -static void CRYP_GCMCCM_SetHeaderPhase_IT(CRYP_HandleTypeDef *hcryp) -{ - uint32_t loopcounter; -#if defined(AES) - uint32_t lastwordsize; - uint32_t npblb; -#endif - uint32_t headersize_in_bytes; - uint32_t tmp; - uint32_t mask[12] = {0x0U, 0xFF000000U, 0xFFFF0000U, 0xFFFFFF00U, /* 32-bit data type */ - 0x0U, 0x0000FF00U, 0x0000FFFFU, 0xFF00FFFFU, /* 16-bit data type */ - 0x0U, 0x000000FFU, 0x0000FFFFU, 0x00FFFFFFU}; /* 8-bit data type */ - - if (hcryp->Init.HeaderWidthUnit == CRYP_HEADERWIDTHUNIT_WORD) - { - headersize_in_bytes = hcryp->Init.HeaderSize * 4U; - } - else - { - headersize_in_bytes = hcryp->Init.HeaderSize; - } - - /***************************** Header phase *********************************/ - -#if defined(CRYP) - if (headersize_in_bytes <= ((uint32_t)(hcryp->CrypHeaderCount) * 4U)) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_INI); - - /* Disable the CRYP peripheral */ - __HAL_CRYP_DISABLE(hcryp); - - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Select payload phase once the header phase is performed */ - CRYP_SET_PHASE(hcryp, CRYP_PHASE_PAYLOAD); - - /* Enable Interrupts */ - __HAL_CRYP_ENABLE_IT(hcryp, CRYP_IT_INI | CRYP_IT_OUTI); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - } - else if (((headersize_in_bytes / 4U) - (hcryp->CrypHeaderCount)) >= 4U) - - { - /* HeaderSize %4, no padding */ - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - else - { - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; loopcounter < ((headersize_in_bytes / 4U) % 4U); loopcounter++) - { - hcryp->Instance->DIN = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - if ((headersize_in_bytes % 4U) == 0U) - { - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DIN = 0x0U; - loopcounter++; - hcryp->CrypHeaderCount++; - } - } - else - { - /* Enter last bytes, padded with zeros */ - tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - tmp &= mask[(hcryp->Init.DataType * 2U) + (headersize_in_bytes % 4U)]; - hcryp->Instance->DIN = tmp; - loopcounter++; - hcryp->CrypHeaderCount++; - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DIN = 0x0U; - loopcounter++; - hcryp->CrypHeaderCount++; - } - } - } -#else /* AES */ - - if (headersize_in_bytes <= ((uint32_t)(hcryp->CrypHeaderCount) * 4U)) - { - /* Set the phase */ - hcryp->Phase = CRYP_PHASE_PROCESS; - - /* Payload phase not supported in CCM AES2 */ - if (hcryp->Init.Algorithm == CRYP_AES_GCM_GMAC) - { - /* Select payload phase once the header phase is performed */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_PAYLOAD); - } - if (hcryp->Init.Algorithm == CRYP_AES_CCM) - { - /* Increment CrypHeaderCount to pass in CRYP_GCMCCM_SetPayloadPhase_IT */ - hcryp->CrypHeaderCount++; - } - /* Write the payload Input block in the IN FIFO */ - if (hcryp->Size == 0U) - { - /* Disable interrupts */ - __HAL_CRYP_DISABLE_IT(hcryp, CRYP_IT_CCFIE | CRYP_IT_ERRIE); - - /* Change the CRYP state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - } - else if (hcryp->Size >= 16U) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - - if ((hcryp->CrypInCount == (hcryp->Size / 4U)) && ((hcryp->Size % 16U) == 0U)) - { - /* Call the input data transfer complete callback */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered Input complete callback*/ - hcryp->InCpltCallback(hcryp); -#else - /*Call legacy weak Input complete callback*/ - HAL_CRYP_InCpltCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - else /* Size < 4 words : first block is the last block*/ - { - /* Workaround not implemented, Size should be %4 otherwise Tag will be incorrectly - generated for GCM Encryption. Workaround is implemented in polling mode, so if last block of - payload <128bit don't use CRYP_Encrypt_IT otherwise TAG is incorrectly generated for GCM Encryption. */ - - /* Compute the number of padding bytes in last block of payload */ - npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); - - /* Number of valid words (lastwordsize) in last block */ - if ((npblb % 4U) == 0U) - { - lastwordsize = (16U - npblb) / 4U; - } - else - { - lastwordsize = ((16U - npblb) / 4U) + 1U; - } - - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; loopcounter < lastwordsize; loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (loopcounter < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0x0U; - loopcounter++; - } - } - } - else if (((headersize_in_bytes / 4U) - (hcryp->CrypHeaderCount)) >= 4U) - { - /* Write the input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++; - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++; - } - else /*HeaderSize < 4 or HeaderSize >4 & HeaderSize %4 != 0*/ - { - /* Last block optionally pad the data with zeros*/ - for (loopcounter = 0U; loopcounter < ((headersize_in_bytes / 4U) % 4U); loopcounter++) - { - hcryp->Instance->DINR = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - hcryp->CrypHeaderCount++ ; - } - /* If the header size is a multiple of words */ - if ((headersize_in_bytes % 4U) == 0U) - { - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DINR = 0x0U; - loopcounter++; - hcryp->CrypHeaderCount++; - } - } - else - { - /* Enter last bytes, padded with zeros */ - tmp = *(uint32_t *)(hcryp->Init.Header + hcryp->CrypHeaderCount); - tmp &= mask[(hcryp->Init.DataType * 2U) + (headersize_in_bytes % 4U)]; - hcryp->Instance->DINR = tmp; - loopcounter++; - hcryp->CrypHeaderCount++; - /* Pad the data with zeros to have a complete block */ - while (loopcounter < 4U) - { - hcryp->Instance->DINR = 0x0U; - loopcounter++; - hcryp->CrypHeaderCount++; - } - } - } -#endif /* End AES or CRYP */ -} - - -/** - * @brief Workaround used for GCM/CCM mode. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param Timeout: specify Timeout value - * @retval None - */ -static void CRYP_Workaround(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t lastwordsize; - uint32_t npblb; -#if defined(CRYP) - uint32_t iv1temp; - uint32_t temp[4] = {0}; - uint32_t temp2[4] = {0}; -#endif /* CRYP */ - uint32_t intermediate_data[4] = {0}; - uint32_t index; - - /* Compute the number of padding bytes in last block of payload */ - npblb = ((((uint32_t)(hcryp->Size) / 16U) + 1U) * 16U) - (uint32_t)(hcryp->Size); - - /* Number of valid words (lastwordsize) in last block */ - if ((npblb % 4U) == 0U) - { - lastwordsize = (16U - npblb) / 4U; - } - else - { - lastwordsize = ((16U - npblb) / 4U) + 1U; - } - -#if defined(CRYP) - - /* Workaround 2, case GCM encryption */ - if (hcryp->Init.Algorithm == CRYP_AES_GCM) - { - if ((hcryp->Instance->CR & CRYP_CR_ALGODIR) == CRYP_OPERATINGMODE_ENCRYPT) - { - /*Workaround in order to properly compute authentication tags while doing - a GCM encryption with the last block of payload size inferior to 128 bits*/ - /* Disable CRYP to start the final phase */ - __HAL_CRYP_DISABLE(hcryp); - - /*Update CRYP_IV1R register and ALGOMODE*/ - hcryp->Instance->IV1RR = ((hcryp->Instance->CSGCMCCM7R) - 1U); - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_AES_CTR); - - /* Enable CRYP to start the final phase */ - __HAL_CRYP_ENABLE(hcryp); - } - /* Last block optionally pad the data with zeros*/ - for (index = 0; index < lastwordsize; index ++) - { - /* Write the last input block in the IN FIFO */ - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (index < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DIN = 0U; - index++; - } - /* Wait for OFNE flag to be raised */ - if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - if ((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) - { - for (index = 0U; index < 4U; index++) - { - /* Read the output block from the output FIFO */ - intermediate_data[index] = hcryp->Instance->DOUT; - - /* Intermediate data buffer to be used in for the workaround*/ - *(uint32_t *)(hcryp->pCrypOutBuffPtr + (hcryp->CrypOutCount)) = intermediate_data[index]; - hcryp->CrypOutCount++; - } - } - - if ((hcryp->Instance->CR & CRYP_CR_ALGODIR) == CRYP_OPERATINGMODE_ENCRYPT) - { - /*workaround in order to properly compute authentication tags while doing - a GCM encryption with the last block of payload size inferior to 128 bits*/ - /* Change the AES mode to GCM mode and Select Final phase */ - /* configured CHMOD GCM */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_AES_GCM); - - /* configured final phase */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_GCM_CCMPH, CRYP_PHASE_FINAL); - - if ((hcryp->Instance->CR & CRYP_CR_DATATYPE) == CRYP_DATATYPE_32B) - { - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= 0xFFFFFF00U; - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= 0xFFFF0000U; - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= 0xFF000000U; - } - } - else if ((hcryp->Instance->CR & CRYP_CR_DATATYPE) == CRYP_DATATYPE_8B) - { - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= __REV(0xFFFFFF00U); - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= __REV(0xFFFF0000U); - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= __REV(0xFF000000U); - } - } - else if ((hcryp->Instance->CR & CRYP_CR_DATATYPE) == CRYP_DATATYPE_16B) - { - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= __ROR((0xFFFFFF00U), 16); - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= __ROR((0xFFFF0000U), 16); - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= __ROR((0xFF000000U), 16); - } - } - else /*CRYP_DATATYPE_1B*/ - { - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= __RBIT(0xFFFFFF00U); - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= __RBIT(0xFFFF0000U); - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= __RBIT(0xFF000000U); - } - } - for (index = 0U; index < lastwordsize; index ++) - { - /*Write the intermediate_data in the IN FIFO */ - hcryp->Instance->DIN = intermediate_data[index]; - } - while (index < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DIN = 0x0U; - index++; - } - /* Wait for OFNE flag to be raised */ - if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - - if ((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) - { - for (index = 0U; index < 4U; index++) - { - intermediate_data[index] = hcryp->Instance->DOUT; - } - } - } - } /* End of GCM encryption */ - else - { - /* Workaround 2, case CCM decryption, in order to properly compute - authentication tags while doing a CCM decryption with the last block - of payload size inferior to 128 bits*/ - - if ((hcryp->Instance->CR & CRYP_CR_ALGODIR) == CRYP_OPERATINGMODE_DECRYPT) - { - iv1temp = hcryp->Instance->CSGCMCCM7R; - - /* Disable CRYP to start the final phase */ - __HAL_CRYP_DISABLE(hcryp); - - temp[0] = hcryp->Instance->CSGCMCCM0R; - temp[1] = hcryp->Instance->CSGCMCCM1R; - temp[2] = hcryp->Instance->CSGCMCCM2R; - temp[3] = hcryp->Instance->CSGCMCCM3R; - - hcryp->Instance->IV1RR = iv1temp; - - /* Configured CHMOD CTR */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_AES_CTR); - - /* Enable CRYP to start the final phase */ - __HAL_CRYP_ENABLE(hcryp); - } - /* Last block optionally pad the data with zeros*/ - for (index = 0; index < lastwordsize; index ++) - { - /* Write the last Input block in the IN FIFO */ - hcryp->Instance->DIN = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (index < 4U) - { - /* Pad the data with zeros to have a complete block */ - hcryp->Instance->DIN = 0U; - index++; - } - /* Wait for OFNE flag to be raised */ - if (CRYP_WaitOnOFNEFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - - if ((hcryp->Instance->SR & CRYP_FLAG_OFNE) != 0x0U) - { - for (index = 0U; index < 4U; index++) - { - /* Read the Output block from the Output FIFO */ - intermediate_data[index] = hcryp->Instance->DOUT; - - /*intermediate data buffer to be used in for the workaround*/ - *(uint32_t *)(hcryp->pCrypOutBuffPtr + (hcryp->CrypOutCount)) = intermediate_data[index]; - hcryp->CrypOutCount++; - } - } - - if ((hcryp->Instance->CR & CRYP_CR_ALGODIR) == CRYP_OPERATINGMODE_DECRYPT) - { - temp2[0] = hcryp->Instance->CSGCMCCM0R; - temp2[1] = hcryp->Instance->CSGCMCCM1R; - temp2[2] = hcryp->Instance->CSGCMCCM2R; - temp2[3] = hcryp->Instance->CSGCMCCM3R; - - /* configured CHMOD CCM */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_ALGOMODE, CRYP_AES_CCM); - - /* configured Header phase */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_GCM_CCMPH, CRYP_PHASE_HEADER); - - /*set to zero the bits corresponding to the padded bits*/ - for (index = lastwordsize; index < 4U; index ++) - { - intermediate_data[index] = 0U; - } - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= 0xFFFFFF00U; - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= 0xFFFF0000U; - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= 0xFF000000U; - } - for (index = 0U; index < 4U ; index ++) - { - intermediate_data[index] ^= temp[index]; - intermediate_data[index] ^= temp2[index]; - } - for (index = 0U; index < 4U; index ++) - { - /* Write the last Input block in the IN FIFO */ - hcryp->Instance->DIN = intermediate_data[index] ; - } - - /* Wait for BUSY flag to be raised */ - if (CRYP_WaitOnBUSYFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - } - } /* End of CCM WKA*/ - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); - -#else /* AES */ - - /*Workaround 2: case GCM encryption, during payload phase and before inserting - the last block of paylaod, which size is inferior to 128 bits */ - - if ((hcryp->Instance->CR & AES_CR_MODE) == CRYP_OPERATINGMODE_ENCRYPT) - { - /* configured CHMOD CTR */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_CHMOD, CRYP_AES_CTR); - } - /* last block optionally pad the data with zeros*/ - for (index = 0U; index < lastwordsize; index ++) - { - /* Write the last Input block in the IN FIFO */ - hcryp->Instance->DINR = *(uint32_t *)(hcryp->pCrypInBuffPtr + hcryp->CrypInCount); - hcryp->CrypInCount++; - } - while (index < 4U) - { - /* pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0U; - index++; - } - /* Wait for CCF flag to be raised */ - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - hcryp->State = HAL_CRYP_STATE_READY; - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - for (index = 0U; index < 4U; index++) - { - /* Read the Output block from the Output FIFO */ - intermediate_data[index] = hcryp->Instance->DOUTR; - - /*intermediate data buffer to be used in the workaround*/ - *(uint32_t *)(hcryp->pCrypOutBuffPtr + (hcryp->CrypOutCount)) = intermediate_data[index]; - hcryp->CrypOutCount++; - } - - if ((hcryp->Instance->CR & AES_CR_MODE) == CRYP_OPERATINGMODE_ENCRYPT) - { - /* configured CHMOD GCM */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_CHMOD, CRYP_AES_GCM_GMAC); - - /* Select final phase */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_FINAL); - - if ((hcryp->Instance->CR & AES_CR_DATATYPE) == CRYP_DATATYPE_32B) - { - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= 0xFFFFFF00U; - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= 0xFFFF0000U; - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= 0xFF000000U; - } - } - else if ((hcryp->Instance->CR & AES_CR_DATATYPE) == CRYP_DATATYPE_8B) - { - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= __REV(0xFFFFFF00U); - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= __REV(0xFFFF0000U); - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= __REV(0xFF000000U); - } - } - else if ((hcryp->Instance->CR & AES_CR_DATATYPE) == CRYP_DATATYPE_16B) - { - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= __ROR((0xFFFFFF00U), 16); - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= __ROR((0xFFFF0000U), 16); - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= __ROR((0xFF000000U), 16); - } - } - else /*CRYP_DATATYPE_1B*/ - { - if ((npblb % 4U) == 1U) - { - intermediate_data[lastwordsize - 1U] &= __RBIT(0xFFFFFF00U); - } - if ((npblb % 4U) == 2U) - { - intermediate_data[lastwordsize - 1U] &= __RBIT(0xFFFF0000U); - } - if ((npblb % 4U) == 3U) - { - intermediate_data[lastwordsize - 1U] &= __RBIT(0xFF000000U); - } - } - - /*Write the intermediate_data in the IN FIFO */ - for (index = 0U; index < lastwordsize; index ++) - { - hcryp->Instance->DINR = intermediate_data[index]; - } - while (index < 4U) - { - /* pad the data with zeros to have a complete block */ - hcryp->Instance->DINR = 0U; - index++; - } - /* Wait for CCF flag to be raised */ - if (CRYP_WaitOnCCFlag(hcryp, Timeout) != HAL_OK) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hcryp); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1U) - /*Call registered error callback*/ - hcryp->ErrorCallback(hcryp); -#else - /*Call legacy weak error callback*/ - HAL_CRYP_ErrorCallback(hcryp); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - } - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - - for (index = 0U; index < 4U; index++) - { - intermediate_data[index] = hcryp->Instance->DOUTR; - } - }/*End of Workaround 2*/ -#endif /* End AES or CRYP */ -} -#endif /* AES or GCM CCM defined*/ -#if defined (CRYP) -#if defined (CRYP_CR_ALGOMODE_AES_GCM) -/** - * @brief Handle CRYP hardware block Timeout when waiting for IFEM flag to be raised. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @param Timeout: Timeout duration. - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_WaitOnIFEMFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t tickstart; - - /* Get timeout */ - tickstart = HAL_GetTick(); - - while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_IFEM)) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - return HAL_ERROR; - } - } - } - return HAL_OK; -} -#endif /* GCM CCM defined*/ -/** - * @brief Handle CRYP hardware block Timeout when waiting for BUSY flag to be raised. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @param Timeout: Timeout duration. - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_WaitOnBUSYFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t tickstart; - - /* Get timeout */ - tickstart = HAL_GetTick(); - - while (HAL_IS_BIT_SET(hcryp->Instance->SR, CRYP_FLAG_BUSY)) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - return HAL_ERROR; - } - } - } - return HAL_OK; -} - - -/** - * @brief Handle CRYP hardware block Timeout when waiting for OFNE flag to be raised. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @param Timeout: Timeout duration. - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_WaitOnOFNEFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t tickstart; - - /* Get timeout */ - tickstart = HAL_GetTick(); - - while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_OFNE)) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -#else /* AES */ - -/** - * @brief Handle CRYP hardware block Timeout when waiting for CCF flag to be raised. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module. - * @param Timeout: Timeout duration. - * @retval HAL status - */ -static HAL_StatusTypeDef CRYP_WaitOnCCFlag(CRYP_HandleTypeDef *hcryp, uint32_t Timeout) -{ - uint32_t tickstart; - - /* Get timeout */ - tickstart = HAL_GetTick(); - - while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -#endif /* End AES or CRYP */ - - -/** - * @} - */ - - - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_CRYP_MODULE_ENABLED */ - - -/** - * @} - */ -#endif /* TinyAES or CRYP*/ -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp_ex.c deleted file mode 100644 index 43b238a13bde202..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cryp_ex.c +++ /dev/null @@ -1,681 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cryp_ex.c - * @author MCD Application Team - * @brief Extended CRYP HAL module driver - * This file provides firmware functions to manage the following - * functionalities of CRYP extension peripheral: - * + Extended AES processing functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The CRYP extension HAL driver can be used as follows: - (#)After AES-GCM or AES-CCM Encryption/Decryption user can start following API - to get the authentication messages : - (##) HAL_CRYPEx_AESGCM_GenerateAuthTAG - (##) HAL_CRYPEx_AESCCM_GenerateAuthTAG - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (AES) || defined (CRYP) -#if defined (CRYP_CR_ALGOMODE_AES_GCM)|| defined (AES) -/** @defgroup CRYPEx CRYPEx - * @brief CRYP Extension HAL module driver. - * @{ - */ - - -#ifdef HAL_CRYP_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup CRYPEx_Private_Defines - * @{ - */ -#if defined(AES) -#define CRYP_PHASE_INIT 0x00000000U /*!< GCM/GMAC (or CCM) init phase */ -#define CRYP_PHASE_HEADER AES_CR_GCMPH_0 /*!< GCM/GMAC or CCM header phase */ -#define CRYP_PHASE_PAYLOAD AES_CR_GCMPH_1 /*!< GCM(/CCM) payload phase */ -#define CRYP_PHASE_FINAL AES_CR_GCMPH /*!< GCM/GMAC or CCM final phase */ - -#define CRYP_OPERATINGMODE_ENCRYPT 0x00000000U /*!< Encryption mode */ -#define CRYP_OPERATINGMODE_KEYDERIVATION AES_CR_MODE_0 /*!< Key derivation mode only used when performing ECB and CBC decryptions */ -#define CRYP_OPERATINGMODE_DECRYPT AES_CR_MODE_1 /*!< Decryption */ -#define CRYP_OPERATINGMODE_KEYDERIVATION_DECRYPT AES_CR_MODE /*!< Key derivation and decryption only used when performing ECB and CBC decryptions */ - -#else /* CRYP */ - -#define CRYP_PHASE_INIT 0x00000000U -#define CRYP_PHASE_HEADER CRYP_CR_GCM_CCMPH_0 -#define CRYP_PHASE_PAYLOAD CRYP_CR_GCM_CCMPH_1 -#define CRYP_PHASE_FINAL CRYP_CR_GCM_CCMPH - -#define CRYP_OPERATINGMODE_ENCRYPT 0x00000000U -#define CRYP_OPERATINGMODE_DECRYPT CRYP_CR_ALGODIR -#endif /* End AES or CRYP */ - -#define CRYPEx_PHASE_PROCESS 0x02U /*!< CRYP peripheral is in processing phase */ -#define CRYPEx_PHASE_FINAL 0x03U /*!< CRYP peripheral is in final phase this is relevant only with CCM and GCM modes */ - -/* CTR0 information to use in CCM algorithm */ -#define CRYP_CCM_CTR0_0 0x07FFFFFFU -#define CRYP_CCM_CTR0_3 0xFFFFFF00U - - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - - - -/* Exported functions---------------------------------------------------------*/ -/** @addtogroup CRYPEx_Exported_Functions - * @{ - */ - -/** @defgroup CRYPEx_Exported_Functions_Group1 Extended AES processing functions - * @brief Extended processing functions. - * -@verbatim - ============================================================================== - ##### Extended AES processing functions ##### - ============================================================================== - [..] This section provides functions allowing to generate the authentication - TAG in Polling mode - (#)HAL_CRYPEx_AESGCM_GenerateAuthTAG - (#)HAL_CRYPEx_AESCCM_GenerateAuthTAG - they should be used after Encrypt/Decrypt operation. - -@endverbatim - * @{ - */ - - -/** - * @brief generate the GCM authentication TAG. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param AuthTag: Pointer to the authentication buffer - * @param Timeout: Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYPEx_AESGCM_GenerateAuthTAG(CRYP_HandleTypeDef *hcryp, uint32_t *AuthTag, uint32_t Timeout) -{ - uint32_t tickstart; - /* Assume first Init.HeaderSize is in words */ - uint64_t headerlength = (uint64_t)(hcryp->Init.HeaderSize) * 32U; /* Header length in bits */ - uint64_t inputlength = (uint64_t)hcryp->SizesSum * 8U; /* Input length in bits */ - uint32_t tagaddr = (uint32_t)AuthTag; - - /* Correct headerlength if Init.HeaderSize is actually in bytes */ - if (hcryp->Init.HeaderWidthUnit == CRYP_HEADERWIDTHUNIT_BYTE) - { - headerlength /= 4U; - } - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Check if initialization phase has already been performed */ - if (hcryp->Phase == CRYPEx_PHASE_PROCESS) - { - /* Change the CRYP phase */ - hcryp->Phase = CRYPEx_PHASE_FINAL; - } - else /* Initialization phase has not been performed*/ - { - /* Disable the Peripheral */ - __HAL_CRYP_DISABLE(hcryp); - - /* Sequence error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_AUTH_TAG_SEQUENCE; - - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - -#if defined(CRYP) - - /* Disable CRYP to start the final phase */ - __HAL_CRYP_DISABLE(hcryp); - - /* Select final phase */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_GCM_CCMPH, CRYP_PHASE_FINAL); - - /*ALGODIR bit must be set to 0.*/ - hcryp->Instance->CR &= ~CRYP_CR_ALGODIR; - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /* Write the number of bits in header (64 bits) followed by the number of bits - in the payload */ - if (hcryp->Init.DataType == CRYP_DATATYPE_1B) - { - hcryp->Instance->DIN = 0U; - hcryp->Instance->DIN = __RBIT((uint32_t)(headerlength)); - hcryp->Instance->DIN = 0U; - hcryp->Instance->DIN = __RBIT((uint32_t)(inputlength)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_8B) - { - hcryp->Instance->DIN = 0U; - hcryp->Instance->DIN = __REV((uint32_t)(headerlength)); - hcryp->Instance->DIN = 0U; - hcryp->Instance->DIN = __REV((uint32_t)(inputlength)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) - { - hcryp->Instance->DIN = 0U; - hcryp->Instance->DIN = __ROR((uint32_t)headerlength, 16U); - hcryp->Instance->DIN = 0U; - hcryp->Instance->DIN = __ROR((uint32_t)inputlength, 16U); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_32B) - { - hcryp->Instance->DIN = 0U; - hcryp->Instance->DIN = (uint32_t)(headerlength); - hcryp->Instance->DIN = 0U; - hcryp->Instance->DIN = (uint32_t)(inputlength); - } - else - { - /* Nothing to do */ - } - - /* Wait for OFNE flag to be raised */ - tickstart = HAL_GetTick(); - while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_OFNE)) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP Peripheral Clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - - /* Read the authentication TAG in the output FIFO */ - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; - -#else /* AES*/ - - /* Select final phase */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_FINAL); - - /* Write the number of bits in header (64 bits) followed by the number of bits - in the payload */ - if (hcryp->Init.DataType == CRYP_DATATYPE_1B) - { - hcryp->Instance->DINR = 0U; - hcryp->Instance->DINR = __RBIT((uint32_t)(headerlength)); - hcryp->Instance->DINR = 0U; - hcryp->Instance->DINR = __RBIT((uint32_t)(inputlength)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_8B) - { - hcryp->Instance->DINR = 0U; - hcryp->Instance->DINR = __REV((uint32_t)(headerlength)); - hcryp->Instance->DINR = 0U; - hcryp->Instance->DINR = __REV((uint32_t)(inputlength)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) - { - hcryp->Instance->DINR = 0U; - hcryp->Instance->DINR = __ROR((uint32_t)headerlength, 16U); - hcryp->Instance->DINR = 0U; - hcryp->Instance->DINR = __ROR((uint32_t)inputlength, 16U); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_32B) - { - hcryp->Instance->DINR = 0U; - hcryp->Instance->DINR = (uint32_t)(headerlength); - hcryp->Instance->DINR = 0U; - hcryp->Instance->DINR = (uint32_t)(inputlength); - } - else - { - /* Nothing to do */ - } - /* Wait for CCF flag to be raised */ - tickstart = HAL_GetTick(); - while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP peripheral clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - - /* Read the authentication TAG in the output FIFO */ - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; - - /* Clear CCF flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - -#endif /* End AES or CRYP */ - - /* Disable the peripheral */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - } - else - { - /* Busy error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_BUSY; - return HAL_ERROR; - } - /* Return function status */ - return HAL_OK; -} - -/** - * @brief AES CCM Authentication TAG generation. - * @param hcryp: pointer to a CRYP_HandleTypeDef structure that contains - * the configuration information for CRYP module - * @param AuthTag: Pointer to the authentication buffer - * @param Timeout: Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_CRYPEx_AESCCM_GenerateAuthTAG(CRYP_HandleTypeDef *hcryp, uint32_t *AuthTag, uint32_t Timeout) -{ - uint32_t tagaddr = (uint32_t)AuthTag; - uint32_t ctr0 [4] = {0}; - uint32_t ctr0addr = (uint32_t)ctr0; - uint32_t tickstart; - - if (hcryp->State == HAL_CRYP_STATE_READY) - { - /* Process locked */ - __HAL_LOCK(hcryp); - - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_BUSY; - - /* Check if initialization phase has already been performed */ - if (hcryp->Phase == CRYPEx_PHASE_PROCESS) - { - /* Change the CRYP phase */ - hcryp->Phase = CRYPEx_PHASE_FINAL; - } - else /* Initialization phase has not been performed*/ - { - /* Disable the peripheral */ - __HAL_CRYP_DISABLE(hcryp); - - /* Sequence error code field */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_AUTH_TAG_SEQUENCE; - - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - -#if defined(CRYP) - - /* Disable CRYP to start the final phase */ - __HAL_CRYP_DISABLE(hcryp); - - /* Select final phase & ALGODIR bit must be set to 0. */ - MODIFY_REG(hcryp->Instance->CR, CRYP_CR_GCM_CCMPH | CRYP_CR_ALGODIR, CRYP_PHASE_FINAL | CRYP_OPERATINGMODE_ENCRYPT); - - /* Enable the CRYP peripheral */ - __HAL_CRYP_ENABLE(hcryp); - - /* Write the counter block in the IN FIFO, CTR0 information from B0 - data has to be swapped according to the DATATYPE*/ - ctr0[0] = (hcryp->Init.B0[0]) & CRYP_CCM_CTR0_0; - ctr0[1] = hcryp->Init.B0[1]; - ctr0[2] = hcryp->Init.B0[2]; - ctr0[3] = hcryp->Init.B0[3] & CRYP_CCM_CTR0_3; - - if (hcryp->Init.DataType == CRYP_DATATYPE_8B) - { - hcryp->Instance->DIN = __REV(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DIN = __REV(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DIN = __REV(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DIN = __REV(*(uint32_t *)(ctr0addr)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) - { - hcryp->Instance->DIN = __ROR(*(uint32_t *)(ctr0addr), 16U); - ctr0addr += 4U; - hcryp->Instance->DIN = __ROR(*(uint32_t *)(ctr0addr), 16U); - ctr0addr += 4U; - hcryp->Instance->DIN = __ROR(*(uint32_t *)(ctr0addr), 16U); - ctr0addr += 4U; - hcryp->Instance->DIN = __ROR(*(uint32_t *)(ctr0addr), 16U); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) - { - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DIN = __RBIT(*(uint32_t *)(ctr0addr)); - } - else - { - hcryp->Instance->DIN = *(uint32_t *)(ctr0addr); - ctr0addr += 4U; - hcryp->Instance->DIN = *(uint32_t *)(ctr0addr); - ctr0addr += 4U; - hcryp->Instance->DIN = *(uint32_t *)(ctr0addr); - ctr0addr += 4U; - hcryp->Instance->DIN = *(uint32_t *)(ctr0addr); - } - /* Wait for OFNE flag to be raised */ - tickstart = HAL_GetTick(); - while (HAL_IS_BIT_CLR(hcryp->Instance->SR, CRYP_FLAG_OFNE)) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP peripheral Clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - - /* Read the Auth TAG in the IN FIFO */ - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUT; - -#else /* AES */ - - /* Select final phase */ - MODIFY_REG(hcryp->Instance->CR, AES_CR_GCMPH, CRYP_PHASE_FINAL); - - /* Write the counter block in the IN FIFO, CTR0 information from B0 - data has to be swapped according to the DATATYPE*/ - if (hcryp->Init.DataType == CRYP_DATATYPE_8B) - { - ctr0[0] = (__REV(hcryp->Init.B0[0]) & CRYP_CCM_CTR0_0); - ctr0[1] = __REV(hcryp->Init.B0[1]); - ctr0[2] = __REV(hcryp->Init.B0[2]); - ctr0[3] = (__REV(hcryp->Init.B0[3])& CRYP_CCM_CTR0_3); - - hcryp->Instance->DINR = __REV(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DINR = __REV(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DINR = __REV(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DINR = __REV(*(uint32_t *)(ctr0addr)); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_16B) - { - ctr0[0] = (__ROR((hcryp->Init.B0[0]), 16U)& CRYP_CCM_CTR0_0); - ctr0[1] = __ROR((hcryp->Init.B0[1]), 16U); - ctr0[2] = __ROR((hcryp->Init.B0[2]), 16U); - ctr0[3] = (__ROR((hcryp->Init.B0[3]), 16U)& CRYP_CCM_CTR0_3); - - hcryp->Instance->DINR = __ROR(*(uint32_t *)(ctr0addr), 16U); - ctr0addr += 4U; - hcryp->Instance->DINR = __ROR(*(uint32_t *)(ctr0addr), 16U); - ctr0addr += 4U; - hcryp->Instance->DINR = __ROR(*(uint32_t *)(ctr0addr), 16U); - ctr0addr += 4U; - hcryp->Instance->DINR = __ROR(*(uint32_t *)(ctr0addr), 16U); - } - else if (hcryp->Init.DataType == CRYP_DATATYPE_1B) - { - ctr0[0] = (__RBIT(hcryp->Init.B0[0])& CRYP_CCM_CTR0_0); - ctr0[1] = __RBIT(hcryp->Init.B0[1]); - ctr0[2] = __RBIT(hcryp->Init.B0[2]); - ctr0[3] = (__RBIT(hcryp->Init.B0[3])& CRYP_CCM_CTR0_3); - - hcryp->Instance->DINR = __RBIT(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DINR = __RBIT(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DINR = __RBIT(*(uint32_t *)(ctr0addr)); - ctr0addr += 4U; - hcryp->Instance->DINR = __RBIT(*(uint32_t *)(ctr0addr)); - } - else - { - ctr0[0] = (hcryp->Init.B0[0]) & CRYP_CCM_CTR0_0; - ctr0[1] = hcryp->Init.B0[1]; - ctr0[2] = hcryp->Init.B0[2]; - ctr0[3] = hcryp->Init.B0[3] & CRYP_CCM_CTR0_3; - - hcryp->Instance->DINR = *(uint32_t *)(ctr0addr); - ctr0addr += 4U; - hcryp->Instance->DINR = *(uint32_t *)(ctr0addr); - ctr0addr += 4U; - hcryp->Instance->DINR = *(uint32_t *)(ctr0addr); - ctr0addr += 4U; - hcryp->Instance->DINR = *(uint32_t *)(ctr0addr); - } - - /* Wait for CCF flag to be raised */ - tickstart = HAL_GetTick(); - while (HAL_IS_BIT_CLR(hcryp->Instance->SR, AES_SR_CCF)) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Disable the CRYP peripheral Clock */ - __HAL_CRYP_DISABLE(hcryp); - - /* Change state */ - hcryp->ErrorCode |= HAL_CRYP_ERROR_TIMEOUT; - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - return HAL_ERROR; - } - } - } - - /* Read the authentication TAG in the output FIFO */ - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; - tagaddr += 4U; - *(uint32_t *)(tagaddr) = hcryp->Instance->DOUTR; - - /* Clear CCF Flag */ - __HAL_CRYP_CLEAR_FLAG(hcryp, CRYP_CCF_CLEAR); - -#endif /* End of AES || CRYP */ - - /* Change the CRYP peripheral state */ - hcryp->State = HAL_CRYP_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hcryp); - - /* Disable CRYP */ - __HAL_CRYP_DISABLE(hcryp); - } - else - { - /* Busy error code field */ - hcryp->ErrorCode = HAL_CRYP_ERROR_BUSY; - return HAL_ERROR; - } - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -#if defined (AES) -/** @defgroup CRYPEx_Exported_Functions_Group2 Key Derivation functions - * @brief AutoKeyDerivation functions - * -@verbatim - ============================================================================== - ##### Key Derivation functions ##### - ============================================================================== - [..] This section provides functions allowing to Enable or Disable the - the AutoKeyDerivation parameter in CRYP_HandleTypeDef structure - These function are allowed only in TinyAES IP. - -@endverbatim - * @{ - */ - -/** - * @brief AES enable key derivation functions - * @param hcryp: pointer to a CRYP_HandleTypeDef structure. - * @retval None - */ -void HAL_CRYPEx_EnableAutoKeyDerivation(CRYP_HandleTypeDef *hcryp) -{ - if (hcryp->State == HAL_CRYP_STATE_READY) - { - hcryp->AutoKeyDerivation = ENABLE; - } - else - { - /* Busy error code field */ - hcryp->ErrorCode = HAL_CRYP_ERROR_BUSY; - } -} -/** - * @brief AES disable key derivation functions - * @param hcryp: pointer to a CRYP_HandleTypeDef structure. - * @retval None - */ -void HAL_CRYPEx_DisableAutoKeyDerivation(CRYP_HandleTypeDef *hcryp) -{ - if (hcryp->State == HAL_CRYP_STATE_READY) - { - hcryp->AutoKeyDerivation = DISABLE; - } - else - { - /* Busy error code field */ - hcryp->ErrorCode = HAL_CRYP_ERROR_BUSY; - } -} - -/** - * @} - */ -#endif /* AES or GCM CCM defined*/ -#endif /* AES */ -#endif /* HAL_CRYP_MODULE_ENABLED */ - -/** - * @} - */ -#endif /* TinyAES or CRYP*/ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac.c deleted file mode 100644 index 5efc497f777d259..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac.c +++ /dev/null @@ -1,1342 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dac.c - * @author MCD Application Team - * @brief DAC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Digital to Analog Converter (DAC) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Errors functions - * - * - @verbatim - ============================================================================== - ##### DAC Peripheral features ##### - ============================================================================== - [..] - *** DAC Channels *** - ==================== - [..] - STM32F4 devices integrate two 12-bit Digital Analog Converters - - The 2 converters (i.e. channel1 & channel2) - can be used independently or simultaneously (dual mode): - (#) DAC channel1 with DAC_OUT1 (PA4) as output - (#) DAC channel2 with DAC_OUT2 (PA5) as output - - *** DAC Triggers *** - ==================== - [..] - Digital to Analog conversion can be non-triggered using DAC_TRIGGER_NONE - and DAC_OUT1/DAC_OUT2 is available once writing to DHRx register. - [..] - Digital to Analog conversion can be triggered by: - (#) External event: EXTI Line 9 (any GPIOx_PIN_9) using DAC_TRIGGER_EXT_IT9. - The used pin (GPIOx_PIN_9) must be configured in input mode. - - (#) Timers TRGO: TIM2, TIM4, TIM5, TIM6, TIM7 and TIM8 - (DAC_TRIGGER_T2_TRGO, DAC_TRIGGER_T4_TRGO...) - - (#) Software using DAC_TRIGGER_SOFTWARE - - *** DAC Buffer mode feature *** - =============================== - [..] - Each DAC channel integrates an output buffer that can be used to - reduce the output impedance, and to drive external loads directly - without having to add an external operational amplifier. - To enable, the output buffer use - sConfig.DAC_OutputBuffer = DAC_OUTPUTBUFFER_ENABLE; - [..] - (@) Refer to the device datasheet for more details about output - impedance value with and without output buffer. - - *** DAC wave generation feature *** - =================================== - [..] - Both DAC channels can be used to generate - (#) Noise wave - (#) Triangle wave - - *** DAC data format *** - ======================= - [..] - The DAC data format can be: - (#) 8-bit right alignment using DAC_ALIGN_8B_R - (#) 12-bit left alignment using DAC_ALIGN_12B_L - (#) 12-bit right alignment using DAC_ALIGN_12B_R - - *** DAC data value to voltage correspondence *** - ================================================ - [..] - The analog output voltage on each DAC channel pin is determined - by the following equation: - [..] - DAC_OUTx = VREF+ * DOR / 4095 - (+) with DOR is the Data Output Register - [..] - VREF+ is the input voltage reference (refer to the device datasheet) - [..] - e.g. To set DAC_OUT1 to 0.7V, use - (+) Assuming that VREF+ = 3.3V, DAC_OUT1 = (3.3 * 868) / 4095 = 0.7V - - *** DMA requests *** - ===================== - [..] - A DMA request can be generated when an external trigger (but not a software trigger) - occurs if DMA1 requests are enabled using HAL_DAC_Start_DMA(). - DMA1 requests are mapped as following: - (#) DAC channel1 mapped on DMA1 Stream5 channel7 which must be - already configured - (#) DAC channel2 mapped on DMA1 Stream6 channel7 which must be - already configured - - [..] - (@) For Dual mode and specific signal (Triangle and noise) generation please - refer to Extended Features Driver description - - ##### How to use this driver ##### - ============================================================================== - [..] - (+) DAC APB clock must be enabled to get write access to DAC - registers using HAL_DAC_Init() - (+) Configure DAC_OUTx (DAC_OUT1: PA4, DAC_OUT2: PA5) in analog mode. - (+) Configure the DAC channel using HAL_DAC_ConfigChannel() function. - (+) Enable the DAC channel using HAL_DAC_Start() or HAL_DAC_Start_DMA() functions. - - - *** Polling mode IO operation *** - ================================= - [..] - (+) Start the DAC peripheral using HAL_DAC_Start() - (+) To read the DAC last data output value, use the HAL_DAC_GetValue() function. - (+) Stop the DAC peripheral using HAL_DAC_Stop() - - *** DMA mode IO operation *** - ============================== - [..] - (+) Start the DAC peripheral using HAL_DAC_Start_DMA(), at this stage the user specify the length - of data to be transferred at each end of conversion - First issued trigger will start the conversion of the value previously set by HAL_DAC_SetValue(). - (+) At the middle of data transfer HAL_DAC_ConvHalfCpltCallbackCh1() or HAL_DACEx_ConvHalfCpltCallbackCh2() - function is executed and user can add his own code by customization of function pointer - HAL_DAC_ConvHalfCpltCallbackCh1() or HAL_DACEx_ConvHalfCpltCallbackCh2() - (+) At The end of data transfer HAL_DAC_ConvCpltCallbackCh1() or HAL_DACEx_ConvHalfCpltCallbackCh2() - function is executed and user can add his own code by customization of function pointer - HAL_DAC_ConvCpltCallbackCh1() or HAL_DACEx_ConvHalfCpltCallbackCh2() - (+) In case of transfer Error, HAL_DAC_ErrorCallbackCh1() function is executed and user can - add his own code by customization of function pointer HAL_DAC_ErrorCallbackCh1 - (+) In case of DMA underrun, DAC interruption triggers and execute internal function HAL_DAC_IRQHandler. - HAL_DAC_DMAUnderrunCallbackCh1() or HAL_DACEx_DMAUnderrunCallbackCh2() - function is executed and user can add his own code by customization of function pointer - HAL_DAC_DMAUnderrunCallbackCh1() or HAL_DACEx_DMAUnderrunCallbackCh2() and - add his own code by customization of function pointer HAL_DAC_ErrorCallbackCh1() - (+) Stop the DAC peripheral using HAL_DAC_Stop_DMA() - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_DAC_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions HAL_DAC_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) ConvCpltCallbackCh1 : callback when a half transfer is completed on Ch1. - (+) ConvHalfCpltCallbackCh1 : callback when a transfer is completed on Ch1. - (+) ErrorCallbackCh1 : callback when an error occurs on Ch1. - (+) DMAUnderrunCallbackCh1 : callback when an underrun error occurs on Ch1. - (+) ConvCpltCallbackCh2 : callback when a half transfer is completed on Ch2. - (+) ConvHalfCpltCallbackCh2 : callback when a transfer is completed on Ch2. - (+) ErrorCallbackCh2 : callback when an error occurs on Ch2. - (+) DMAUnderrunCallbackCh2 : callback when an underrun error occurs on Ch2. - (+) MspInitCallback : DAC MspInit. - (+) MspDeInitCallback : DAC MspdeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function HAL_DAC_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) ConvCpltCallbackCh1 : callback when a half transfer is completed on Ch1. - (+) ConvHalfCpltCallbackCh1 : callback when a transfer is completed on Ch1. - (+) ErrorCallbackCh1 : callback when an error occurs on Ch1. - (+) DMAUnderrunCallbackCh1 : callback when an underrun error occurs on Ch1. - (+) ConvCpltCallbackCh2 : callback when a half transfer is completed on Ch2. - (+) ConvHalfCpltCallbackCh2 : callback when a transfer is completed on Ch2. - (+) ErrorCallbackCh2 : callback when an error occurs on Ch2. - (+) DMAUnderrunCallbackCh2 : callback when an underrun error occurs on Ch2. - (+) MspInitCallback : DAC MspInit. - (+) MspDeInitCallback : DAC MspdeInit. - (+) All Callbacks - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the HAL_DAC_Init and if the state is HAL_DAC_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the HAL_DAC_Init - and HAL_DAC_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_DAC_Init and HAL_DAC_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_DAC_RegisterCallback before calling HAL_DAC_DeInit - or HAL_DAC_Init function. - - When The compilation define USE_HAL_DAC_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - *** DAC HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in DAC HAL driver. - - (+) __HAL_DAC_ENABLE : Enable the DAC peripheral - (+) __HAL_DAC_DISABLE : Disable the DAC peripheral - (+) __HAL_DAC_CLEAR_FLAG: Clear the DAC's pending flags - (+) __HAL_DAC_GET_FLAG: Get the selected DAC's flag status - - [..] - (@) You can refer to the DAC HAL driver header file for more useful macros - -@endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_DAC_MODULE_ENABLED -#if defined(DAC) - -/** @defgroup DAC DAC - * @brief DAC driver modules - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions -------------------------------------------------------*/ - -/** @defgroup DAC_Exported_Functions DAC Exported Functions - * @{ - */ - -/** @defgroup DAC_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the DAC. - (+) De-initialize the DAC. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the DAC peripheral according to the specified parameters - * in the DAC_InitStruct and initialize the associated handle. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DAC_Init(DAC_HandleTypeDef *hdac) -{ - /* Check DAC handle */ - if (hdac == NULL) - { - return HAL_ERROR; - } - /* Check the parameters */ - assert_param(IS_DAC_ALL_INSTANCE(hdac->Instance)); - - if (hdac->State == HAL_DAC_STATE_RESET) - { -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - /* Init the DAC Callback settings */ - hdac->ConvCpltCallbackCh1 = HAL_DAC_ConvCpltCallbackCh1; - hdac->ConvHalfCpltCallbackCh1 = HAL_DAC_ConvHalfCpltCallbackCh1; - hdac->ErrorCallbackCh1 = HAL_DAC_ErrorCallbackCh1; - hdac->DMAUnderrunCallbackCh1 = HAL_DAC_DMAUnderrunCallbackCh1; -#if defined(DAC_CHANNEL2_SUPPORT) - hdac->ConvCpltCallbackCh2 = HAL_DACEx_ConvCpltCallbackCh2; - hdac->ConvHalfCpltCallbackCh2 = HAL_DACEx_ConvHalfCpltCallbackCh2; - hdac->ErrorCallbackCh2 = HAL_DACEx_ErrorCallbackCh2; - hdac->DMAUnderrunCallbackCh2 = HAL_DACEx_DMAUnderrunCallbackCh2; -#endif /* DAC_CHANNEL2_SUPPORT */ - if (hdac->MspInitCallback == NULL) - { - hdac->MspInitCallback = HAL_DAC_MspInit; - } -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - - /* Allocate lock resource and initialize it */ - hdac->Lock = HAL_UNLOCKED; - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - /* Init the low level hardware */ - hdac->MspInitCallback(hdac); -#else - /* Init the low level hardware */ - HAL_DAC_MspInit(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - } - - /* Initialize the DAC state*/ - hdac->State = HAL_DAC_STATE_BUSY; - - /* Set DAC error code to none */ - hdac->ErrorCode = HAL_DAC_ERROR_NONE; - - /* Initialize the DAC state*/ - hdac->State = HAL_DAC_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Deinitialize the DAC peripheral registers to their default reset values. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DAC_DeInit(DAC_HandleTypeDef *hdac) -{ - /* Check DAC handle */ - if (hdac == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_DAC_ALL_INSTANCE(hdac->Instance)); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_BUSY; - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - if (hdac->MspDeInitCallback == NULL) - { - hdac->MspDeInitCallback = HAL_DAC_MspDeInit; - } - /* DeInit the low level hardware */ - hdac->MspDeInitCallback(hdac); -#else - /* DeInit the low level hardware */ - HAL_DAC_MspDeInit(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - - /* Set DAC error code to none */ - hdac->ErrorCode = HAL_DAC_ERROR_NONE; - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hdac); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initialize the DAC MSP. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DAC_MspInit(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DAC_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize the DAC MSP. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DAC_MspDeInit(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DAC_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup DAC_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Start conversion. - (+) Stop conversion. - (+) Start conversion and enable DMA transfer. - (+) Stop conversion and disable DMA transfer. - (+) Get result of conversion. - -@endverbatim - * @{ - */ - -/** - * @brief Enables DAC and starts conversion of channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DAC_Start(DAC_HandleTypeDef *hdac, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(Channel)); - - /* Process locked */ - __HAL_LOCK(hdac); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_BUSY; - - /* Enable the Peripheral */ - __HAL_DAC_ENABLE(hdac, Channel); - - if (Channel == DAC_CHANNEL_1) - { - /* Check if software trigger enabled */ - if ((hdac->Instance->CR & (DAC_CR_TEN1 | DAC_CR_TSEL1)) == DAC_TRIGGER_SOFTWARE) - { - /* Enable the selected DAC software conversion */ - SET_BIT(hdac->Instance->SWTRIGR, DAC_SWTRIGR_SWTRIG1); - } - } -#if defined(DAC_CHANNEL2_SUPPORT) - else - { - /* Check if software trigger enabled */ - if ((hdac->Instance->CR & (DAC_CR_TEN2 | DAC_CR_TSEL2)) == (DAC_TRIGGER_SOFTWARE << (Channel & 0x10UL))) - { - /* Enable the selected DAC software conversion*/ - SET_BIT(hdac->Instance->SWTRIGR, DAC_SWTRIGR_SWTRIG2); - } - } -#endif /* DAC_CHANNEL2_SUPPORT */ - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdac); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Disables DAC and stop conversion of channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DAC_Stop(DAC_HandleTypeDef *hdac, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(Channel)); - - /* Disable the Peripheral */ - __HAL_DAC_DISABLE(hdac, Channel); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Enables DAC and starts conversion of channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to DAC peripheral - * @param Alignment Specifies the data alignment for DAC channel. - * This parameter can be one of the following values: - * @arg DAC_ALIGN_8B_R: 8bit right data alignment selected - * @arg DAC_ALIGN_12B_L: 12bit left data alignment selected - * @arg DAC_ALIGN_12B_R: 12bit right data alignment selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DAC_Start_DMA(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t *pData, uint32_t Length, - uint32_t Alignment) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(Channel)); - assert_param(IS_DAC_ALIGN(Alignment)); - - /* Process locked */ - __HAL_LOCK(hdac); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_BUSY; - - if (Channel == DAC_CHANNEL_1) - { - /* Set the DMA transfer complete callback for channel1 */ - hdac->DMA_Handle1->XferCpltCallback = DAC_DMAConvCpltCh1; - - /* Set the DMA half transfer complete callback for channel1 */ - hdac->DMA_Handle1->XferHalfCpltCallback = DAC_DMAHalfConvCpltCh1; - - /* Set the DMA error callback for channel1 */ - hdac->DMA_Handle1->XferErrorCallback = DAC_DMAErrorCh1; - - /* Enable the selected DAC channel1 DMA request */ - SET_BIT(hdac->Instance->CR, DAC_CR_DMAEN1); - - /* Case of use of channel 1 */ - switch (Alignment) - { - case DAC_ALIGN_12B_R: - /* Get DHR12R1 address */ - tmpreg = (uint32_t)&hdac->Instance->DHR12R1; - break; - case DAC_ALIGN_12B_L: - /* Get DHR12L1 address */ - tmpreg = (uint32_t)&hdac->Instance->DHR12L1; - break; - case DAC_ALIGN_8B_R: - /* Get DHR8R1 address */ - tmpreg = (uint32_t)&hdac->Instance->DHR8R1; - break; - default: - break; - } - } -#if defined(DAC_CHANNEL2_SUPPORT) - else - { - /* Set the DMA transfer complete callback for channel2 */ - hdac->DMA_Handle2->XferCpltCallback = DAC_DMAConvCpltCh2; - - /* Set the DMA half transfer complete callback for channel2 */ - hdac->DMA_Handle2->XferHalfCpltCallback = DAC_DMAHalfConvCpltCh2; - - /* Set the DMA error callback for channel2 */ - hdac->DMA_Handle2->XferErrorCallback = DAC_DMAErrorCh2; - - /* Enable the selected DAC channel2 DMA request */ - SET_BIT(hdac->Instance->CR, DAC_CR_DMAEN2); - - /* Case of use of channel 2 */ - switch (Alignment) - { - case DAC_ALIGN_12B_R: - /* Get DHR12R2 address */ - tmpreg = (uint32_t)&hdac->Instance->DHR12R2; - break; - case DAC_ALIGN_12B_L: - /* Get DHR12L2 address */ - tmpreg = (uint32_t)&hdac->Instance->DHR12L2; - break; - case DAC_ALIGN_8B_R: - /* Get DHR8R2 address */ - tmpreg = (uint32_t)&hdac->Instance->DHR8R2; - break; - default: - break; - } - } -#endif /* DAC_CHANNEL2_SUPPORT */ - - /* Enable the DMA Stream */ - if (Channel == DAC_CHANNEL_1) - { - /* Enable the DAC DMA underrun interrupt */ - __HAL_DAC_ENABLE_IT(hdac, DAC_IT_DMAUDR1); - - /* Enable the DMA Stream */ - status = HAL_DMA_Start_IT(hdac->DMA_Handle1, (uint32_t)pData, tmpreg, Length); - } -#if defined(DAC_CHANNEL2_SUPPORT) - else - { - /* Enable the DAC DMA underrun interrupt */ - __HAL_DAC_ENABLE_IT(hdac, DAC_IT_DMAUDR2); - - /* Enable the DMA Stream */ - status = HAL_DMA_Start_IT(hdac->DMA_Handle2, (uint32_t)pData, tmpreg, Length); - } -#endif /* DAC_CHANNEL2_SUPPORT */ - - /* Process Unlocked */ - __HAL_UNLOCK(hdac); - - if (status == HAL_OK) - { - /* Enable the Peripheral */ - __HAL_DAC_ENABLE(hdac, Channel); - } - else - { - hdac->ErrorCode |= HAL_DAC_ERROR_DMA; - } - - /* Return function status */ - return status; -} - -/** - * @brief Disables DAC and stop conversion of channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DAC_Stop_DMA(DAC_HandleTypeDef *hdac, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(Channel)); - - /* Disable the selected DAC channel DMA request */ - hdac->Instance->CR &= ~(DAC_CR_DMAEN1 << (Channel & 0x10UL)); - - /* Disable the Peripheral */ - __HAL_DAC_DISABLE(hdac, Channel); - - /* Disable the DMA Stream */ - - /* Channel1 is used */ - if (Channel == DAC_CHANNEL_1) - { - /* Disable the DMA Stream */ - (void)HAL_DMA_Abort(hdac->DMA_Handle1); - - /* Disable the DAC DMA underrun interrupt */ - __HAL_DAC_DISABLE_IT(hdac, DAC_IT_DMAUDR1); - } -#if defined(DAC_CHANNEL2_SUPPORT) - else /* Channel2 is used for */ - { - /* Disable the DMA Stream */ - (void)HAL_DMA_Abort(hdac->DMA_Handle2); - - /* Disable the DAC DMA underrun interrupt */ - __HAL_DAC_DISABLE_IT(hdac, DAC_IT_DMAUDR2); - } -#endif /* DAC_CHANNEL2_SUPPORT */ - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Handles DAC interrupt request - * This function uses the interruption of DMA - * underrun. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -void HAL_DAC_IRQHandler(DAC_HandleTypeDef *hdac) -{ - if (__HAL_DAC_GET_IT_SOURCE(hdac, DAC_IT_DMAUDR1)) - { - /* Check underrun flag of DAC channel 1 */ - if (__HAL_DAC_GET_FLAG(hdac, DAC_FLAG_DMAUDR1)) - { - /* Change DAC state to error state */ - hdac->State = HAL_DAC_STATE_ERROR; - - /* Set DAC error code to channel1 DMA underrun error */ - SET_BIT(hdac->ErrorCode, HAL_DAC_ERROR_DMAUNDERRUNCH1); - - /* Clear the underrun flag */ - __HAL_DAC_CLEAR_FLAG(hdac, DAC_FLAG_DMAUDR1); - - /* Disable the selected DAC channel1 DMA request */ - CLEAR_BIT(hdac->Instance->CR, DAC_CR_DMAEN1); - - /* Error callback */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - hdac->DMAUnderrunCallbackCh1(hdac); -#else - HAL_DAC_DMAUnderrunCallbackCh1(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - } - } - -#if defined(DAC_CHANNEL2_SUPPORT) - if (__HAL_DAC_GET_IT_SOURCE(hdac, DAC_IT_DMAUDR2)) - { - /* Check underrun flag of DAC channel 2 */ - if (__HAL_DAC_GET_FLAG(hdac, DAC_FLAG_DMAUDR2)) - { - /* Change DAC state to error state */ - hdac->State = HAL_DAC_STATE_ERROR; - - /* Set DAC error code to channel2 DMA underrun error */ - SET_BIT(hdac->ErrorCode, HAL_DAC_ERROR_DMAUNDERRUNCH2); - - /* Clear the underrun flag */ - __HAL_DAC_CLEAR_FLAG(hdac, DAC_FLAG_DMAUDR2); - - /* Disable the selected DAC channel2 DMA request */ - CLEAR_BIT(hdac->Instance->CR, DAC_CR_DMAEN2); - - /* Error callback */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - hdac->DMAUnderrunCallbackCh2(hdac); -#else - HAL_DACEx_DMAUnderrunCallbackCh2(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - } - } -#endif /* DAC_CHANNEL2_SUPPORT */ -} - -/** - * @brief Set the specified data holding register value for DAC channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @param Alignment Specifies the data alignment. - * This parameter can be one of the following values: - * @arg DAC_ALIGN_8B_R: 8bit right data alignment selected - * @arg DAC_ALIGN_12B_L: 12bit left data alignment selected - * @arg DAC_ALIGN_12B_R: 12bit right data alignment selected - * @param Data Data to be loaded in the selected data holding register. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DAC_SetValue(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Alignment, uint32_t Data) -{ - __IO uint32_t tmp = 0UL; - - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(Channel)); - assert_param(IS_DAC_ALIGN(Alignment)); - assert_param(IS_DAC_DATA(Data)); - - tmp = (uint32_t)hdac->Instance; - if (Channel == DAC_CHANNEL_1) - { - tmp += DAC_DHR12R1_ALIGNMENT(Alignment); - } -#if defined(DAC_CHANNEL2_SUPPORT) - else - { - tmp += DAC_DHR12R2_ALIGNMENT(Alignment); - } -#endif /* DAC_CHANNEL2_SUPPORT */ - - /* Set the DAC channel selected data holding register */ - *(__IO uint32_t *) tmp = Data; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Conversion complete callback in non-blocking mode for Channel1 - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DAC_ConvCpltCallbackCh1(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DAC_ConvCpltCallbackCh1 could be implemented in the user file - */ -} - -/** - * @brief Conversion half DMA transfer callback in non-blocking mode for Channel1 - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DAC_ConvHalfCpltCallbackCh1(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DAC_ConvHalfCpltCallbackCh1 could be implemented in the user file - */ -} - -/** - * @brief Error DAC callback for Channel1. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DAC_ErrorCallbackCh1(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DAC_ErrorCallbackCh1 could be implemented in the user file - */ -} - -/** - * @brief DMA underrun DAC callback for channel1. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DAC_DMAUnderrunCallbackCh1(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DAC_DMAUnderrunCallbackCh1 could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup DAC_Exported_Functions_Group3 Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Configure channels. - (+) Set the specified data holding register value for DAC channel. - -@endverbatim - * @{ - */ - -/** - * @brief Returns the last data output value of the selected DAC channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @retval The selected DAC channel data output value. - */ -uint32_t HAL_DAC_GetValue(DAC_HandleTypeDef *hdac, uint32_t Channel) -{ - uint32_t result = 0; - - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(Channel)); - - if (Channel == DAC_CHANNEL_1) - { - result = hdac->Instance->DOR1; - } -#if defined(DAC_CHANNEL2_SUPPORT) - else - { - result = hdac->Instance->DOR2; - } -#endif /* DAC_CHANNEL2_SUPPORT */ - /* Returns the DAC channel data output register value */ - return result; -} - -/** - * @brief Configures the selected DAC channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param sConfig DAC configuration structure. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DAC_ConfigChannel(DAC_HandleTypeDef *hdac, DAC_ChannelConfTypeDef *sConfig, uint32_t Channel) -{ - uint32_t tmpreg1; - uint32_t tmpreg2; - - /* Check the DAC parameters */ - assert_param(IS_DAC_TRIGGER(sConfig->DAC_Trigger)); - assert_param(IS_DAC_OUTPUT_BUFFER_STATE(sConfig->DAC_OutputBuffer)); - assert_param(IS_DAC_CHANNEL(Channel)); - - /* Process locked */ - __HAL_LOCK(hdac); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_BUSY; - - /* Get the DAC CR value */ - tmpreg1 = hdac->Instance->CR; - /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */ - tmpreg1 &= ~(((uint32_t)(DAC_CR_MAMP1 | DAC_CR_WAVE1 | DAC_CR_TSEL1 | DAC_CR_TEN1 | DAC_CR_BOFF1)) << (Channel & 0x10UL)); - /* Configure for the selected DAC channel: buffer output, trigger */ - /* Set TSELx and TENx bits according to DAC_Trigger value */ - /* Set BOFFx bit according to DAC_OutputBuffer value */ - tmpreg2 = (sConfig->DAC_Trigger | sConfig->DAC_OutputBuffer); - /* Calculate CR register value depending on DAC_Channel */ - tmpreg1 |= tmpreg2 << (Channel & 0x10UL); - /* Write to DAC CR */ - hdac->Instance->CR = tmpreg1; - /* Disable wave generation */ - CLEAR_BIT(hdac->Instance->CR, (DAC_CR_WAVE1 << (Channel & 0x10UL))); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdac); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup DAC_Exported_Functions_Group4 Peripheral State and Errors functions - * @brief Peripheral State and Errors functions - * -@verbatim - ============================================================================== - ##### Peripheral State and Errors functions ##### - ============================================================================== - [..] - This subsection provides functions allowing to - (+) Check the DAC state. - (+) Check the DAC Errors. - -@endverbatim - * @{ - */ - -/** - * @brief return the DAC handle state - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval HAL state - */ -HAL_DAC_StateTypeDef HAL_DAC_GetState(DAC_HandleTypeDef *hdac) -{ - /* Return DAC handle state */ - return hdac->State; -} - - -/** - * @brief Return the DAC error code - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval DAC Error Code - */ -uint32_t HAL_DAC_GetError(DAC_HandleTypeDef *hdac) -{ - return hdac->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup DAC_Exported_Functions - * @{ - */ - -/** @addtogroup DAC_Exported_Functions_Group1 - * @{ - */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User DAC Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hdac DAC handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_DAC_ERROR_INVALID_CALLBACK DAC Error Callback ID - * @arg @ref HAL_DAC_CH1_COMPLETE_CB_ID DAC CH1 Complete Callback ID - * @arg @ref HAL_DAC_CH1_HALF_COMPLETE_CB_ID DAC CH1 Half Complete Callback ID - * @arg @ref HAL_DAC_CH1_ERROR_ID DAC CH1 Error Callback ID - * @arg @ref HAL_DAC_CH1_UNDERRUN_CB_ID DAC CH1 UnderRun Callback ID - * @arg @ref HAL_DAC_CH2_COMPLETE_CB_ID DAC CH2 Complete Callback ID - * @arg @ref HAL_DAC_CH2_HALF_COMPLETE_CB_ID DAC CH2 Half Complete Callback ID - * @arg @ref HAL_DAC_CH2_ERROR_ID DAC CH2 Error Callback ID - * @arg @ref HAL_DAC_CH2_UNDERRUN_CB_ID DAC CH2 UnderRun Callback ID - * @arg @ref HAL_DAC_MSPINIT_CB_ID DAC MSP Init Callback ID - * @arg @ref HAL_DAC_MSPDEINIT_CB_ID DAC MSP DeInit Callback ID - * - * @param pCallback pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_DAC_RegisterCallback(DAC_HandleTypeDef *hdac, HAL_DAC_CallbackIDTypeDef CallbackID, - pDAC_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hdac); - - if (hdac->State == HAL_DAC_STATE_READY) - { - switch (CallbackID) - { - case HAL_DAC_CH1_COMPLETE_CB_ID : - hdac->ConvCpltCallbackCh1 = pCallback; - break; - case HAL_DAC_CH1_HALF_COMPLETE_CB_ID : - hdac->ConvHalfCpltCallbackCh1 = pCallback; - break; - case HAL_DAC_CH1_ERROR_ID : - hdac->ErrorCallbackCh1 = pCallback; - break; - case HAL_DAC_CH1_UNDERRUN_CB_ID : - hdac->DMAUnderrunCallbackCh1 = pCallback; - break; -#if defined(DAC_CHANNEL2_SUPPORT) - case HAL_DAC_CH2_COMPLETE_CB_ID : - hdac->ConvCpltCallbackCh2 = pCallback; - break; - case HAL_DAC_CH2_HALF_COMPLETE_CB_ID : - hdac->ConvHalfCpltCallbackCh2 = pCallback; - break; - case HAL_DAC_CH2_ERROR_ID : - hdac->ErrorCallbackCh2 = pCallback; - break; - case HAL_DAC_CH2_UNDERRUN_CB_ID : - hdac->DMAUnderrunCallbackCh2 = pCallback; - break; -#endif /* DAC_CHANNEL2_SUPPORT */ - case HAL_DAC_MSPINIT_CB_ID : - hdac->MspInitCallback = pCallback; - break; - case HAL_DAC_MSPDEINIT_CB_ID : - hdac->MspDeInitCallback = pCallback; - break; - default : - /* Update the error code */ - hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (hdac->State == HAL_DAC_STATE_RESET) - { - switch (CallbackID) - { - case HAL_DAC_MSPINIT_CB_ID : - hdac->MspInitCallback = pCallback; - break; - case HAL_DAC_MSPDEINIT_CB_ID : - hdac->MspDeInitCallback = pCallback; - break; - default : - /* Update the error code */ - hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdac); - return status; -} - -/** - * @brief Unregister a User DAC Callback - * DAC Callback is redirected to the weak (surcharged) predefined callback - * @param hdac DAC handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_DAC_CH1_COMPLETE_CB_ID DAC CH1 transfer Complete Callback ID - * @arg @ref HAL_DAC_CH1_HALF_COMPLETE_CB_ID DAC CH1 Half Complete Callback ID - * @arg @ref HAL_DAC_CH1_ERROR_ID DAC CH1 Error Callback ID - * @arg @ref HAL_DAC_CH1_UNDERRUN_CB_ID DAC CH1 UnderRun Callback ID - * @arg @ref HAL_DAC_CH2_COMPLETE_CB_ID DAC CH2 Complete Callback ID - * @arg @ref HAL_DAC_CH2_HALF_COMPLETE_CB_ID DAC CH2 Half Complete Callback ID - * @arg @ref HAL_DAC_CH2_ERROR_ID DAC CH2 Error Callback ID - * @arg @ref HAL_DAC_CH2_UNDERRUN_CB_ID DAC CH2 UnderRun Callback ID - * @arg @ref HAL_DAC_MSPINIT_CB_ID DAC MSP Init Callback ID - * @arg @ref HAL_DAC_MSPDEINIT_CB_ID DAC MSP DeInit Callback ID - * @arg @ref HAL_DAC_ALL_CB_ID DAC All callbacks - * @retval status - */ -HAL_StatusTypeDef HAL_DAC_UnRegisterCallback(DAC_HandleTypeDef *hdac, HAL_DAC_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdac); - - if (hdac->State == HAL_DAC_STATE_READY) - { - switch (CallbackID) - { - case HAL_DAC_CH1_COMPLETE_CB_ID : - hdac->ConvCpltCallbackCh1 = HAL_DAC_ConvCpltCallbackCh1; - break; - case HAL_DAC_CH1_HALF_COMPLETE_CB_ID : - hdac->ConvHalfCpltCallbackCh1 = HAL_DAC_ConvHalfCpltCallbackCh1; - break; - case HAL_DAC_CH1_ERROR_ID : - hdac->ErrorCallbackCh1 = HAL_DAC_ErrorCallbackCh1; - break; - case HAL_DAC_CH1_UNDERRUN_CB_ID : - hdac->DMAUnderrunCallbackCh1 = HAL_DAC_DMAUnderrunCallbackCh1; - break; -#if defined(DAC_CHANNEL2_SUPPORT) - case HAL_DAC_CH2_COMPLETE_CB_ID : - hdac->ConvCpltCallbackCh2 = HAL_DACEx_ConvCpltCallbackCh2; - break; - case HAL_DAC_CH2_HALF_COMPLETE_CB_ID : - hdac->ConvHalfCpltCallbackCh2 = HAL_DACEx_ConvHalfCpltCallbackCh2; - break; - case HAL_DAC_CH2_ERROR_ID : - hdac->ErrorCallbackCh2 = HAL_DACEx_ErrorCallbackCh2; - break; - case HAL_DAC_CH2_UNDERRUN_CB_ID : - hdac->DMAUnderrunCallbackCh2 = HAL_DACEx_DMAUnderrunCallbackCh2; - break; -#endif /* DAC_CHANNEL2_SUPPORT */ - case HAL_DAC_MSPINIT_CB_ID : - hdac->MspInitCallback = HAL_DAC_MspInit; - break; - case HAL_DAC_MSPDEINIT_CB_ID : - hdac->MspDeInitCallback = HAL_DAC_MspDeInit; - break; - case HAL_DAC_ALL_CB_ID : - hdac->ConvCpltCallbackCh1 = HAL_DAC_ConvCpltCallbackCh1; - hdac->ConvHalfCpltCallbackCh1 = HAL_DAC_ConvHalfCpltCallbackCh1; - hdac->ErrorCallbackCh1 = HAL_DAC_ErrorCallbackCh1; - hdac->DMAUnderrunCallbackCh1 = HAL_DAC_DMAUnderrunCallbackCh1; -#if defined(DAC_CHANNEL2_SUPPORT) - hdac->ConvCpltCallbackCh2 = HAL_DACEx_ConvCpltCallbackCh2; - hdac->ConvHalfCpltCallbackCh2 = HAL_DACEx_ConvHalfCpltCallbackCh2; - hdac->ErrorCallbackCh2 = HAL_DACEx_ErrorCallbackCh2; - hdac->DMAUnderrunCallbackCh2 = HAL_DACEx_DMAUnderrunCallbackCh2; -#endif /* DAC_CHANNEL2_SUPPORT */ - hdac->MspInitCallback = HAL_DAC_MspInit; - hdac->MspDeInitCallback = HAL_DAC_MspDeInit; - break; - default : - /* Update the error code */ - hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (hdac->State == HAL_DAC_STATE_RESET) - { - switch (CallbackID) - { - case HAL_DAC_MSPINIT_CB_ID : - hdac->MspInitCallback = HAL_DAC_MspInit; - break; - case HAL_DAC_MSPDEINIT_CB_ID : - hdac->MspDeInitCallback = HAL_DAC_MspDeInit; - break; - default : - /* Update the error code */ - hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hdac->ErrorCode |= HAL_DAC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdac); - return status; -} -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup DAC_Private_Functions - * @{ - */ - -/** - * @brief DMA conversion complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -void DAC_DMAConvCpltCh1(DMA_HandleTypeDef *hdma) -{ - DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - hdac->ConvCpltCallbackCh1(hdac); -#else - HAL_DAC_ConvCpltCallbackCh1(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - - hdac->State = HAL_DAC_STATE_READY; -} - -/** - * @brief DMA half transfer complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -void DAC_DMAHalfConvCpltCh1(DMA_HandleTypeDef *hdma) -{ - DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* Conversion complete callback */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - hdac->ConvHalfCpltCallbackCh1(hdac); -#else - HAL_DAC_ConvHalfCpltCallbackCh1(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA error callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -void DAC_DMAErrorCh1(DMA_HandleTypeDef *hdma) -{ - DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Set DAC error code to DMA error */ - hdac->ErrorCode |= HAL_DAC_ERROR_DMA; - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - hdac->ErrorCallbackCh1(hdac); -#else - HAL_DAC_ErrorCallbackCh1(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - - hdac->State = HAL_DAC_STATE_READY; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -#endif /* HAL_DAC_MODULE_ENABLED */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac_ex.c deleted file mode 100644 index 4a05998fef4d101..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dac_ex.c +++ /dev/null @@ -1,496 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dac_ex.c - * @author MCD Application Team - * @brief Extended DAC HAL module driver. - * This file provides firmware functions to manage the extended - * functionalities of the DAC peripheral. - * - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - - *** Dual mode IO operation *** - ============================== - [..] - (+) When Dual mode is enabled (i.e. DAC Channel1 and Channel2 are used simultaneously) : - Use HAL_DACEx_DualGetValue() to get digital data to be converted and use - HAL_DACEx_DualSetValue() to set digital value to converted simultaneously in - Channel 1 and Channel 2. - - *** Signal generation operation *** - =================================== - [..] - (+) Use HAL_DACEx_TriangleWaveGenerate() to generate Triangle signal. - (+) Use HAL_DACEx_NoiseWaveGenerate() to generate Noise signal. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_DAC_MODULE_ENABLED - -#if defined(DAC) - -/** @defgroup DACEx DACEx - * @brief DAC Extended HAL module driver - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup DACEx_Exported_Functions DACEx Exported Functions - * @{ - */ - -/** @defgroup DACEx_Exported_Functions_Group2 IO operation functions - * @brief Extended IO operation functions - * -@verbatim - ============================================================================== - ##### Extended features functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Start conversion. - (+) Stop conversion. - (+) Start conversion and enable DMA transfer. - (+) Stop conversion and disable DMA transfer. - (+) Get result of conversion. - (+) Get result of dual mode conversion. - -@endverbatim - * @{ - */ - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Enables DAC and starts conversion of both channels. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DACEx_DualStart(DAC_HandleTypeDef *hdac) -{ - uint32_t tmp_swtrig = 0UL; - - - /* Process locked */ - __HAL_LOCK(hdac); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_BUSY; - - /* Enable the Peripheral */ - __HAL_DAC_ENABLE(hdac, DAC_CHANNEL_1); - __HAL_DAC_ENABLE(hdac, DAC_CHANNEL_2); - - /* Check if software trigger enabled */ - if ((hdac->Instance->CR & (DAC_CR_TEN1 | DAC_CR_TSEL1)) == DAC_TRIGGER_SOFTWARE) - { - tmp_swtrig |= DAC_SWTRIGR_SWTRIG1; - } - if ((hdac->Instance->CR & (DAC_CR_TEN2 | DAC_CR_TSEL2)) == (DAC_TRIGGER_SOFTWARE << (DAC_CHANNEL_2 & 0x10UL))) - { - tmp_swtrig |= DAC_SWTRIGR_SWTRIG2; - } - /* Enable the selected DAC software conversion*/ - SET_BIT(hdac->Instance->SWTRIGR, tmp_swtrig); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdac); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Disables DAC and stop conversion of both channels. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DACEx_DualStop(DAC_HandleTypeDef *hdac) -{ - - /* Disable the Peripheral */ - __HAL_DAC_DISABLE(hdac, DAC_CHANNEL_1); - __HAL_DAC_DISABLE(hdac, DAC_CHANNEL_2); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_READY; - - /* Return function status */ - return HAL_OK; -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Enable or disable the selected DAC channel wave generation. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @param Amplitude Select max triangle amplitude. - * This parameter can be one of the following values: - * @arg DAC_TRIANGLEAMPLITUDE_1: Select max triangle amplitude of 1 - * @arg DAC_TRIANGLEAMPLITUDE_3: Select max triangle amplitude of 3 - * @arg DAC_TRIANGLEAMPLITUDE_7: Select max triangle amplitude of 7 - * @arg DAC_TRIANGLEAMPLITUDE_15: Select max triangle amplitude of 15 - * @arg DAC_TRIANGLEAMPLITUDE_31: Select max triangle amplitude of 31 - * @arg DAC_TRIANGLEAMPLITUDE_63: Select max triangle amplitude of 63 - * @arg DAC_TRIANGLEAMPLITUDE_127: Select max triangle amplitude of 127 - * @arg DAC_TRIANGLEAMPLITUDE_255: Select max triangle amplitude of 255 - * @arg DAC_TRIANGLEAMPLITUDE_511: Select max triangle amplitude of 511 - * @arg DAC_TRIANGLEAMPLITUDE_1023: Select max triangle amplitude of 1023 - * @arg DAC_TRIANGLEAMPLITUDE_2047: Select max triangle amplitude of 2047 - * @arg DAC_TRIANGLEAMPLITUDE_4095: Select max triangle amplitude of 4095 - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DACEx_TriangleWaveGenerate(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Amplitude) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(Channel)); - assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(Amplitude)); - - /* Process locked */ - __HAL_LOCK(hdac); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_BUSY; - - /* Enable the triangle wave generation for the selected DAC channel */ - MODIFY_REG(hdac->Instance->CR, ((DAC_CR_WAVE1) | (DAC_CR_MAMP1)) << (Channel & 0x10UL), - (DAC_CR_WAVE1_1 | Amplitude) << (Channel & 0x10UL)); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdac); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Enable or disable the selected DAC channel wave generation. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Channel The selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_CHANNEL_1: DAC Channel1 selected - * @arg DAC_CHANNEL_2: DAC Channel2 selected - * @param Amplitude Unmask DAC channel LFSR for noise wave generation. - * This parameter can be one of the following values: - * @arg DAC_LFSRUNMASK_BIT0: Unmask DAC channel LFSR bit0 for noise wave generation - * @arg DAC_LFSRUNMASK_BITS1_0: Unmask DAC channel LFSR bit[1:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS2_0: Unmask DAC channel LFSR bit[2:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS3_0: Unmask DAC channel LFSR bit[3:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS4_0: Unmask DAC channel LFSR bit[4:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS5_0: Unmask DAC channel LFSR bit[5:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS6_0: Unmask DAC channel LFSR bit[6:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS7_0: Unmask DAC channel LFSR bit[7:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS8_0: Unmask DAC channel LFSR bit[8:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS9_0: Unmask DAC channel LFSR bit[9:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS10_0: Unmask DAC channel LFSR bit[10:0] for noise wave generation - * @arg DAC_LFSRUNMASK_BITS11_0: Unmask DAC channel LFSR bit[11:0] for noise wave generation - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DACEx_NoiseWaveGenerate(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Amplitude) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(Channel)); - assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(Amplitude)); - - /* Process locked */ - __HAL_LOCK(hdac); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_BUSY; - - /* Enable the noise wave generation for the selected DAC channel */ - MODIFY_REG(hdac->Instance->CR, ((DAC_CR_WAVE1) | (DAC_CR_MAMP1)) << (Channel & 0x10UL), - (DAC_CR_WAVE1_0 | Amplitude) << (Channel & 0x10UL)); - - /* Change DAC state */ - hdac->State = HAL_DAC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdac); - - /* Return function status */ - return HAL_OK; -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Set the specified data holding register value for dual DAC channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @param Alignment Specifies the data alignment for dual channel DAC. - * This parameter can be one of the following values: - * DAC_ALIGN_8B_R: 8bit right data alignment selected - * DAC_ALIGN_12B_L: 12bit left data alignment selected - * DAC_ALIGN_12B_R: 12bit right data alignment selected - * @param Data1 Data for DAC Channel1 to be loaded in the selected data holding register. - * @param Data2 Data for DAC Channel2 to be loaded in the selected data holding register. - * @note In dual mode, a unique register access is required to write in both - * DAC channels at the same time. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DACEx_DualSetValue(DAC_HandleTypeDef *hdac, uint32_t Alignment, uint32_t Data1, uint32_t Data2) -{ - uint32_t data; - uint32_t tmp; - - /* Check the parameters */ - assert_param(IS_DAC_ALIGN(Alignment)); - assert_param(IS_DAC_DATA(Data1)); - assert_param(IS_DAC_DATA(Data2)); - - /* Calculate and set dual DAC data holding register value */ - if (Alignment == DAC_ALIGN_8B_R) - { - data = ((uint32_t)Data2 << 8U) | Data1; - } - else - { - data = ((uint32_t)Data2 << 16U) | Data1; - } - - tmp = (uint32_t)hdac->Instance; - tmp += DAC_DHR12RD_ALIGNMENT(Alignment); - - /* Set the dual DAC selected data holding register */ - *(__IO uint32_t *)tmp = data; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Conversion complete callback in non-blocking mode for Channel2. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DACEx_ConvCpltCallbackCh2(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DACEx_ConvCpltCallbackCh2 could be implemented in the user file - */ -} - -/** - * @brief Conversion half DMA transfer callback in non-blocking mode for Channel2. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DACEx_ConvHalfCpltCallbackCh2(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DACEx_ConvHalfCpltCallbackCh2 could be implemented in the user file - */ -} - -/** - * @brief Error DAC callback for Channel2. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DACEx_ErrorCallbackCh2(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DACEx_ErrorCallbackCh2 could be implemented in the user file - */ -} - -/** - * @brief DMA underrun DAC callback for Channel2. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval None - */ -__weak void HAL_DACEx_DMAUnderrunCallbackCh2(DAC_HandleTypeDef *hdac) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdac); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DACEx_DMAUnderrunCallbackCh2 could be implemented in the user file - */ -} -#endif /* DAC_CHANNEL2_SUPPORT */ - - -/** - * @} - */ - -/** @defgroup DACEx_Exported_Functions_Group3 Peripheral Control functions - * @brief Extended Peripheral Control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Set the specified data holding register value for DAC channel. - -@endverbatim - * @{ - */ - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Return the last data output value of the selected DAC channel. - * @param hdac pointer to a DAC_HandleTypeDef structure that contains - * the configuration information for the specified DAC. - * @retval The selected DAC channel data output value. - */ -uint32_t HAL_DACEx_DualGetValue(DAC_HandleTypeDef *hdac) -{ - uint32_t tmp = 0UL; - - tmp |= hdac->Instance->DOR1; - - tmp |= hdac->Instance->DOR2 << 16UL; - - /* Returns the DAC channel data output register value */ - return tmp; -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DACEx_Private_Functions DACEx private functions - * @brief Extended private functions - * @{ - */ - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief DMA conversion complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -void DAC_DMAConvCpltCh2(DMA_HandleTypeDef *hdma) -{ - DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - hdac->ConvCpltCallbackCh2(hdac); -#else - HAL_DACEx_ConvCpltCallbackCh2(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - - hdac->State = HAL_DAC_STATE_READY; -} - -/** - * @brief DMA half transfer complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -void DAC_DMAHalfConvCpltCh2(DMA_HandleTypeDef *hdma) -{ - DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* Conversion complete callback */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - hdac->ConvHalfCpltCallbackCh2(hdac); -#else - HAL_DACEx_ConvHalfCpltCallbackCh2(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA error callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -void DAC_DMAErrorCh2(DMA_HandleTypeDef *hdma) -{ - DAC_HandleTypeDef *hdac = (DAC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Set DAC error code to DMA error */ - hdac->ErrorCode |= HAL_DAC_ERROR_DMA; - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - hdac->ErrorCallbackCh2(hdac); -#else - HAL_DACEx_ErrorCallbackCh2(hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - - hdac->State = HAL_DAC_STATE_READY; -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -#endif /* HAL_DAC_MODULE_ENABLED */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi.c deleted file mode 100644 index aa237c684366732..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi.c +++ /dev/null @@ -1,1164 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dcmi.c - * @author MCD Application Team - * @brief DCMI HAL module driver - * This file provides firmware functions to manage the following - * functionalities of the Digital Camera Interface (DCMI) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Error functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The sequence below describes how to use this driver to capture image - from a camera module connected to the DCMI Interface. - This sequence does not take into account the configuration of the - camera module, which should be made before to configure and enable - the DCMI to capture images. - - (#) Program the required configuration through following parameters: - horizontal and vertical polarity, pixel clock polarity, Capture Rate, - Synchronization Mode, code of the frame delimiter and data width - using HAL_DCMI_Init() function. - - (#) Configure the DMA2_Stream1 channel1 to transfer Data from DCMI DR - register to the destination memory buffer. - - (#) Program the required configuration through following parameters: - DCMI mode, destination memory Buffer address and the data length - and enable capture using HAL_DCMI_Start_DMA() function. - - (#) Optionally, configure and Enable the CROP feature to select a rectangular - window from the received image using HAL_DCMI_ConfigCrop() - and HAL_DCMI_EnableCROP() functions - - (#) The capture can be stopped using HAL_DCMI_Stop() function. - - (#) To control DCMI state you can use the function HAL_DCMI_GetState(). - - *** DCMI HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in DCMI HAL driver. - - (+) __HAL_DCMI_ENABLE: Enable the DCMI peripheral. - (+) __HAL_DCMI_DISABLE: Disable the DCMI peripheral. - (+) __HAL_DCMI_GET_FLAG: Get the DCMI pending flags. - (+) __HAL_DCMI_CLEAR_FLAG: Clear the DCMI pending flags. - (+) __HAL_DCMI_ENABLE_IT: Enable the specified DCMI interrupts. - (+) __HAL_DCMI_DISABLE_IT: Disable the specified DCMI interrupts. - (+) __HAL_DCMI_GET_IT_SOURCE: Check whether the specified DCMI interrupt has occurred or not. - - [..] - (@) You can refer to the DCMI HAL driver header file for more useful macros - - *** Callback registration *** - ============================= - - The compilation define USE_HAL_DCMI_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use functions HAL_DCMI_RegisterCallback() to register a user callback. - - Function HAL_DCMI_RegisterCallback() allows to register following callbacks: - (+) FrameEventCallback : DCMI Frame Event. - (+) VsyncEventCallback : DCMI Vsync Event. - (+) LineEventCallback : DCMI Line Event. - (+) ErrorCallback : DCMI error. - (+) MspInitCallback : DCMI MspInit. - (+) MspDeInitCallback : DCMI MspDeInit. - This function takes as parameters the HAL peripheral handle, the callback ID - and a pointer to the user callback function. - - Use function HAL_DCMI_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - HAL_DCMI_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the callback ID. - This function allows to reset following callbacks: - (+) FrameEventCallback : DCMI Frame Event. - (+) VsyncEventCallback : DCMI Vsync Event. - (+) LineEventCallback : DCMI Line Event. - (+) ErrorCallback : DCMI error. - (+) MspInitCallback : DCMI MspInit. - (+) MspDeInitCallback : DCMI MspDeInit. - - By default, after the HAL_DCMI_Init and if the state is HAL_DCMI_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions: - examples FrameEventCallback(), HAL_DCMI_ErrorCallback(). - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the HAL_DCMI_Init - and HAL_DCMI_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_DCMI_Init and HAL_DCMI_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_DCMI_RegisterCallback before calling HAL_DCMI_DeInit - or HAL_DCMI_Init function. - - When the compilation define USE_HAL_DCMI_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -/** @defgroup DCMI DCMI - * @brief DCMI HAL module driver - * @{ - */ - -#ifdef HAL_DCMI_MODULE_ENABLED - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -#define HAL_TIMEOUT_DCMI_STOP 14U /* Set timeout to 1s */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -static void DCMI_DMAXferCplt(DMA_HandleTypeDef *hdma); -static void DCMI_DMAError(DMA_HandleTypeDef *hdma); - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup DCMI_Exported_Functions DCMI Exported Functions - * @{ - */ - -/** @defgroup DCMI_Exported_Functions_Group1 Initialization and Configuration functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the DCMI - (+) De-initialize the DCMI - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the DCMI according to the specified - * parameters in the DCMI_InitTypeDef and create the associated handle. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL status - */ -__weak HAL_StatusTypeDef HAL_DCMI_Init(DCMI_HandleTypeDef *hdcmi) -{ - /* Check the DCMI peripheral state */ - if(hdcmi == NULL) - { - return HAL_ERROR; - } - - /* Check function parameters */ - assert_param(IS_DCMI_ALL_INSTANCE(hdcmi->Instance)); - assert_param(IS_DCMI_PCKPOLARITY(hdcmi->Init.PCKPolarity)); - assert_param(IS_DCMI_VSPOLARITY(hdcmi->Init.VSPolarity)); - assert_param(IS_DCMI_HSPOLARITY(hdcmi->Init.HSPolarity)); - assert_param(IS_DCMI_SYNCHRO(hdcmi->Init.SynchroMode)); - assert_param(IS_DCMI_CAPTURE_RATE(hdcmi->Init.CaptureRate)); - assert_param(IS_DCMI_EXTENDED_DATA(hdcmi->Init.ExtendedDataMode)); - assert_param(IS_DCMI_MODE_JPEG(hdcmi->Init.JPEGMode)); - - if(hdcmi->State == HAL_DCMI_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hdcmi->Lock = HAL_UNLOCKED; - /* Init the low level hardware */ - /* Init the DCMI Callback settings */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - hdcmi->FrameEventCallback = HAL_DCMI_FrameEventCallback; /* Legacy weak FrameEventCallback */ - hdcmi->VsyncEventCallback = HAL_DCMI_VsyncEventCallback; /* Legacy weak VsyncEventCallback */ - hdcmi->LineEventCallback = HAL_DCMI_LineEventCallback; /* Legacy weak LineEventCallback */ - hdcmi->ErrorCallback = HAL_DCMI_ErrorCallback; /* Legacy weak ErrorCallback */ - - if(hdcmi->MspInitCallback == NULL) - { - /* Legacy weak MspInit Callback */ - hdcmi->MspInitCallback = HAL_DCMI_MspInit; - } - /* Initialize the low level hardware (MSP) */ - hdcmi->MspInitCallback(hdcmi); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_DCMI_MspInit(hdcmi); -#endif /* (USE_HAL_DCMI_REGISTER_CALLBACKS) */ - HAL_DCMI_MspInit(hdcmi); - } - - /* Change the DCMI state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - - /* Set DCMI parameters */ - /* Configures the HS, VS, DE and PC polarity */ - hdcmi->Instance->CR &= ~(DCMI_CR_PCKPOL | DCMI_CR_HSPOL | DCMI_CR_VSPOL | DCMI_CR_EDM_0 | - DCMI_CR_EDM_1 | DCMI_CR_FCRC_0 | DCMI_CR_FCRC_1 | DCMI_CR_JPEG | - DCMI_CR_ESS); - hdcmi->Instance->CR |= (uint32_t)(hdcmi->Init.SynchroMode | hdcmi->Init.CaptureRate | \ - hdcmi->Init.VSPolarity | hdcmi->Init.HSPolarity | \ - hdcmi->Init.PCKPolarity | hdcmi->Init.ExtendedDataMode | \ - hdcmi->Init.JPEGMode); - - if(hdcmi->Init.SynchroMode == DCMI_SYNCHRO_EMBEDDED) - { - hdcmi->Instance->ESCR = (((uint32_t)hdcmi->Init.SyncroCode.FrameStartCode) | - ((uint32_t)hdcmi->Init.SyncroCode.LineStartCode << DCMI_POSITION_ESCR_LSC)| - ((uint32_t)hdcmi->Init.SyncroCode.LineEndCode << DCMI_POSITION_ESCR_LEC) | - ((uint32_t)hdcmi->Init.SyncroCode.FrameEndCode << DCMI_POSITION_ESCR_FEC)); - } - - /* Enable the Line, Vsync, Error and Overrun interrupts */ - __HAL_DCMI_ENABLE_IT(hdcmi, DCMI_IT_LINE | DCMI_IT_VSYNC | DCMI_IT_ERR | DCMI_IT_OVR); - - /* Update error code */ - hdcmi->ErrorCode = HAL_DCMI_ERROR_NONE; - - /* Initialize the DCMI state*/ - hdcmi->State = HAL_DCMI_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Deinitializes the DCMI peripheral registers to their default reset - * values. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL status - */ - -HAL_StatusTypeDef HAL_DCMI_DeInit(DCMI_HandleTypeDef *hdcmi) -{ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - if(hdcmi->MspDeInitCallback == NULL) - { - hdcmi->MspDeInitCallback = HAL_DCMI_MspDeInit; - } - /* De-Initialize the low level hardware (MSP) */ - hdcmi->MspDeInitCallback(hdcmi); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ - HAL_DCMI_MspDeInit(hdcmi); -#endif /* (USE_HAL_DCMI_REGISTER_CALLBACKS) */ - - /* Update error code */ - hdcmi->ErrorCode = HAL_DCMI_ERROR_NONE; - - /* Initialize the DCMI state*/ - hdcmi->State = HAL_DCMI_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hdcmi); - - return HAL_OK; -} - -/** - * @brief Initializes the DCMI MSP. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval None - */ -__weak void HAL_DCMI_MspInit(DCMI_HandleTypeDef* hdcmi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdcmi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DCMI_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes the DCMI MSP. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval None - */ -__weak void HAL_DCMI_MspDeInit(DCMI_HandleTypeDef* hdcmi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdcmi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DCMI_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ -/** @defgroup DCMI_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure destination address and data length and - Enables DCMI DMA request and enables DCMI capture - (+) Stop the DCMI capture. - (+) Handles DCMI interrupt request. - -@endverbatim - * @{ - */ - -/** - * @brief Enables DCMI DMA request and enables DCMI capture - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @param DCMI_Mode DCMI capture mode snapshot or continuous grab. - * @param pData The destination memory Buffer address (LCD Frame buffer). - * @param Length The length of capture to be transferred. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_Start_DMA(DCMI_HandleTypeDef* hdcmi, uint32_t DCMI_Mode, uint32_t pData, uint32_t Length) -{ - /* Initialize the second memory address */ - uint32_t SecondMemAddress = 0U; - - /* Check function parameters */ - assert_param(IS_DCMI_CAPTURE_MODE(DCMI_Mode)); - - /* Process Locked */ - __HAL_LOCK(hdcmi); - - /* Lock the DCMI peripheral state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - - /* Enable DCMI by setting DCMIEN bit */ - __HAL_DCMI_ENABLE(hdcmi); - - /* Configure the DCMI Mode */ - hdcmi->Instance->CR &= ~(DCMI_CR_CM); - hdcmi->Instance->CR |= (uint32_t)(DCMI_Mode); - - /* Set the DMA memory0 conversion complete callback */ - hdcmi->DMA_Handle->XferCpltCallback = DCMI_DMAXferCplt; - - /* Set the DMA error callback */ - hdcmi->DMA_Handle->XferErrorCallback = DCMI_DMAError; - - /* Set the dma abort callback */ - hdcmi->DMA_Handle->XferAbortCallback = NULL; - - /* Reset transfer counters value */ - hdcmi->XferCount = 0U; - hdcmi->XferTransferNumber = 0U; - - if(Length <= 0xFFFFU) - { - /* Enable the DMA Stream */ - HAL_DMA_Start_IT(hdcmi->DMA_Handle, (uint32_t)&hdcmi->Instance->DR, (uint32_t)pData, Length); - } - else /* DCMI_DOUBLE_BUFFER Mode */ - { - /* Set the DMA memory1 conversion complete callback */ - hdcmi->DMA_Handle->XferM1CpltCallback = DCMI_DMAXferCplt; - - /* Initialize transfer parameters */ - hdcmi->XferCount = 1U; - hdcmi->XferSize = Length; - hdcmi->pBuffPtr = pData; - - /* Get the number of buffer */ - while(hdcmi->XferSize > 0xFFFFU) - { - hdcmi->XferSize = (hdcmi->XferSize/2U); - hdcmi->XferCount = hdcmi->XferCount*2U; - } - - /* Update DCMI counter and transfer number*/ - hdcmi->XferCount = (hdcmi->XferCount - 2U); - hdcmi->XferTransferNumber = hdcmi->XferCount; - - /* Update second memory address */ - SecondMemAddress = (uint32_t)(pData + (4U*hdcmi->XferSize)); - - /* Start DMA multi buffer transfer */ - HAL_DMAEx_MultiBufferStart_IT(hdcmi->DMA_Handle, (uint32_t)&hdcmi->Instance->DR, (uint32_t)pData, SecondMemAddress, hdcmi->XferSize); - } - - /* Enable Capture */ - hdcmi->Instance->CR |= DCMI_CR_CAPTURE; - - /* Release Lock */ - __HAL_UNLOCK(hdcmi); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Disable DCMI DMA request and Disable DCMI capture - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_Stop(DCMI_HandleTypeDef* hdcmi) -{ - __IO uint32_t count = SystemCoreClock / HAL_TIMEOUT_DCMI_STOP; - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdcmi); - - /* Lock the DCMI peripheral state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - - /* Disable Capture */ - hdcmi->Instance->CR &= ~(DCMI_CR_CAPTURE); - - /* Check if the DCMI capture effectively disabled */ - do - { - if (count-- == 0U) - { - /* Update error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_TIMEOUT; - - status = HAL_TIMEOUT; - break; - } - } - while((hdcmi->Instance->CR & DCMI_CR_CAPTURE) != 0U); - - /* Disable the DCMI */ - __HAL_DCMI_DISABLE(hdcmi); - - /* Disable the DMA */ - HAL_DMA_Abort(hdcmi->DMA_Handle); - - /* Update error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_NONE; - - /* Change DCMI state */ - hdcmi->State = HAL_DCMI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdcmi); - - /* Return function status */ - return status; -} - -/** - * @brief Suspend DCMI capture - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_Suspend(DCMI_HandleTypeDef* hdcmi) -{ - __IO uint32_t count = SystemCoreClock / HAL_TIMEOUT_DCMI_STOP; - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdcmi); - - if(hdcmi->State == HAL_DCMI_STATE_BUSY) - { - /* Change DCMI state */ - hdcmi->State = HAL_DCMI_STATE_SUSPENDED; - - /* Disable Capture */ - hdcmi->Instance->CR &= ~(DCMI_CR_CAPTURE); - - /* Check if the DCMI capture effectively disabled */ - do - { - if (count-- == 0U) - { - /* Update error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_TIMEOUT; - - /* Change DCMI state */ - hdcmi->State = HAL_DCMI_STATE_READY; - - status = HAL_TIMEOUT; - break; - } - } - while((hdcmi->Instance->CR & DCMI_CR_CAPTURE) != 0); - } - /* Process Unlocked */ - __HAL_UNLOCK(hdcmi); - - /* Return function status */ - return status; -} - -/** - * @brief Resume DCMI capture - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_Resume(DCMI_HandleTypeDef* hdcmi) -{ - /* Process locked */ - __HAL_LOCK(hdcmi); - - if(hdcmi->State == HAL_DCMI_STATE_SUSPENDED) - { - /* Change DCMI state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - - /* Disable Capture */ - hdcmi->Instance->CR |= DCMI_CR_CAPTURE; - } - /* Process Unlocked */ - __HAL_UNLOCK(hdcmi); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Handles DCMI interrupt request. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for the DCMI. - * @retval None - */ -void HAL_DCMI_IRQHandler(DCMI_HandleTypeDef *hdcmi) -{ - uint32_t isr_value = READ_REG(hdcmi->Instance->MISR); - - /* Synchronization error interrupt management *******************************/ - if((isr_value & DCMI_FLAG_ERRRI) == DCMI_FLAG_ERRRI) - { - /* Clear the Synchronization error flag */ - __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_ERRRI); - - /* Update error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_SYNC; - - /* Change DCMI state */ - hdcmi->State = HAL_DCMI_STATE_ERROR; - - /* Set the synchronization error callback */ - hdcmi->DMA_Handle->XferAbortCallback = DCMI_DMAError; - - /* Abort the DMA Transfer */ - HAL_DMA_Abort_IT(hdcmi->DMA_Handle); - } - /* Overflow interrupt management ********************************************/ - if((isr_value & DCMI_FLAG_OVRRI) == DCMI_FLAG_OVRRI) - { - /* Clear the Overflow flag */ - __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_OVRRI); - - /* Update error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_OVR; - - /* Change DCMI state */ - hdcmi->State = HAL_DCMI_STATE_ERROR; - - /* Set the overflow callback */ - hdcmi->DMA_Handle->XferAbortCallback = DCMI_DMAError; - - /* Abort the DMA Transfer */ - HAL_DMA_Abort_IT(hdcmi->DMA_Handle); - } - /* Line Interrupt management ************************************************/ - if((isr_value & DCMI_FLAG_LINERI) == DCMI_FLAG_LINERI) - { - /* Clear the Line interrupt flag */ - __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_LINERI); - - /* Line interrupt Callback */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - /*Call registered DCMI line event callback*/ - hdcmi->LineEventCallback(hdcmi); -#else - HAL_DCMI_LineEventCallback(hdcmi); -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ - } - /* VSYNC interrupt management ***********************************************/ - if((isr_value & DCMI_FLAG_VSYNCRI) == DCMI_FLAG_VSYNCRI) - { - /* Clear the VSYNC flag */ - __HAL_DCMI_CLEAR_FLAG(hdcmi, DCMI_FLAG_VSYNCRI); - - /* VSYNC Callback */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - /*Call registered DCMI vsync event callback*/ - hdcmi->VsyncEventCallback(hdcmi); -#else - HAL_DCMI_VsyncEventCallback(hdcmi); -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ - } - /* FRAME interrupt management ***********************************************/ - if((isr_value & DCMI_FLAG_FRAMERI) == DCMI_FLAG_FRAMERI) - { - /* When snapshot mode, disable Vsync, Error and Overrun interrupts */ - if((hdcmi->Instance->CR & DCMI_CR_CM) == DCMI_MODE_SNAPSHOT) - { - /* Disable the Line, Vsync, Error and Overrun interrupts */ - __HAL_DCMI_DISABLE_IT(hdcmi, DCMI_IT_LINE | DCMI_IT_VSYNC | DCMI_IT_ERR | DCMI_IT_OVR); - } - - /* Disable the Frame interrupt */ - __HAL_DCMI_DISABLE_IT(hdcmi, DCMI_IT_FRAME); - - /* Frame Callback */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - /*Call registered DCMI frame event callback*/ - hdcmi->FrameEventCallback(hdcmi); -#else - HAL_DCMI_FrameEventCallback(hdcmi); -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Error DCMI callback. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval None - */ -__weak void HAL_DCMI_ErrorCallback(DCMI_HandleTypeDef *hdcmi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdcmi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DCMI_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief Line Event callback. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval None - */ -__weak void HAL_DCMI_LineEventCallback(DCMI_HandleTypeDef *hdcmi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdcmi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DCMI_LineEventCallback could be implemented in the user file - */ -} - -/** - * @brief VSYNC Event callback. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval None - */ -__weak void HAL_DCMI_VsyncEventCallback(DCMI_HandleTypeDef *hdcmi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdcmi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DCMI_VsyncEventCallback could be implemented in the user file - */ -} - -/** - * @brief Frame Event callback. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval None - */ -__weak void HAL_DCMI_FrameEventCallback(DCMI_HandleTypeDef *hdcmi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdcmi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DCMI_FrameEventCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup DCMI_Exported_Functions_Group3 Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== -[..] This section provides functions allowing to: - (+) Configure the CROP feature. - (+) Enable/Disable the CROP feature. - -@endverbatim - * @{ - */ - -/** - * @brief Configure the DCMI CROP coordinate. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @param X0 DCMI window X offset - * @param Y0 DCMI window Y offset - * @param XSize DCMI Pixel per line - * @param YSize DCMI Line number - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_ConfigCrop(DCMI_HandleTypeDef *hdcmi, uint32_t X0, uint32_t Y0, uint32_t XSize, uint32_t YSize) -{ - /* Process Locked */ - __HAL_LOCK(hdcmi); - - /* Lock the DCMI peripheral state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - - /* Check the parameters */ - assert_param(IS_DCMI_WINDOW_COORDINATE(X0)); - assert_param(IS_DCMI_WINDOW_COORDINATE(YSize)); - assert_param(IS_DCMI_WINDOW_COORDINATE(XSize)); - assert_param(IS_DCMI_WINDOW_HEIGHT(Y0)); - - /* Configure CROP */ - hdcmi->Instance->CWSIZER = (XSize | (YSize << DCMI_POSITION_CWSIZE_VLINE)); - hdcmi->Instance->CWSTRTR = (X0 | (Y0 << DCMI_POSITION_CWSTRT_VST)); - - /* Initialize the DCMI state*/ - hdcmi->State = HAL_DCMI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdcmi); - - return HAL_OK; -} - -/** - * @brief Disable the Crop feature. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_DisableCrop(DCMI_HandleTypeDef *hdcmi) -{ - /* Process Locked */ - __HAL_LOCK(hdcmi); - - /* Lock the DCMI peripheral state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - - /* Disable DCMI Crop feature */ - hdcmi->Instance->CR &= ~(uint32_t)DCMI_CR_CROP; - - /* Change the DCMI state*/ - hdcmi->State = HAL_DCMI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdcmi); - - return HAL_OK; -} - -/** - * @brief Enable the Crop feature. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_EnableCrop(DCMI_HandleTypeDef *hdcmi) -{ - /* Process Locked */ - __HAL_LOCK(hdcmi); - - /* Lock the DCMI peripheral state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - - /* Enable DCMI Crop feature */ - hdcmi->Instance->CR |= (uint32_t)DCMI_CR_CROP; - - /* Change the DCMI state*/ - hdcmi->State = HAL_DCMI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdcmi); - - return HAL_OK; -} - -/** - * @brief Set embedded synchronization delimiters unmasks. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @param SyncUnmask pointer to a DCMI_SyncUnmaskTypeDef structure that contains - * the embedded synchronization delimiters unmasks. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_ConfigSyncUnmask(DCMI_HandleTypeDef *hdcmi, DCMI_SyncUnmaskTypeDef *SyncUnmask) -{ - /* Process Locked */ - __HAL_LOCK(hdcmi); - - /* Lock the DCMI peripheral state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - - /* Write DCMI embedded synchronization unmask register */ - hdcmi->Instance->ESUR = (((uint32_t)SyncUnmask->FrameStartUnmask) |\ - ((uint32_t)SyncUnmask->LineStartUnmask << DCMI_ESUR_LSU_Pos)|\ - ((uint32_t)SyncUnmask->LineEndUnmask << DCMI_ESUR_LEU_Pos)|\ - ((uint32_t)SyncUnmask->FrameEndUnmask << DCMI_ESUR_FEU_Pos)); - - /* Change the DCMI state*/ - hdcmi->State = HAL_DCMI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdcmi); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup DCMI_Exported_Functions_Group4 Peripheral State functions - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Check the DCMI state. - (+) Get the specific DCMI error flag. - -@endverbatim - * @{ - */ - -/** - * @brief Return the DCMI state - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL state - */ -HAL_DCMI_StateTypeDef HAL_DCMI_GetState(DCMI_HandleTypeDef *hdcmi) -{ - return hdcmi->State; -} - -/** - * @brief Return the DCMI error code - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval DCMI Error Code - */ -uint32_t HAL_DCMI_GetError(DCMI_HandleTypeDef *hdcmi) -{ - return hdcmi->ErrorCode; -} - -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) -/** - * @brief DCMI Callback registering - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @param CallbackID dcmi Callback ID - * @param pCallback pointer to DCMI_CallbackTypeDef structure - * @retval status - */ -HAL_StatusTypeDef HAL_DCMI_RegisterCallback(DCMI_HandleTypeDef *hdcmi, HAL_DCMI_CallbackIDTypeDef CallbackID, pDCMI_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - /* update the error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - else - { - if(hdcmi->State == HAL_DCMI_STATE_READY) - { - switch (CallbackID) - { - case HAL_DCMI_FRAME_EVENT_CB_ID : - hdcmi->FrameEventCallback = pCallback; - break; - - case HAL_DCMI_VSYNC_EVENT_CB_ID : - hdcmi->VsyncEventCallback = pCallback; - break; - - case HAL_DCMI_LINE_EVENT_CB_ID : - hdcmi->LineEventCallback = pCallback; - break; - - case HAL_DCMI_ERROR_CB_ID : - hdcmi->ErrorCallback = pCallback; - break; - - case HAL_DCMI_MSPINIT_CB_ID : - hdcmi->MspInitCallback = pCallback; - break; - - case HAL_DCMI_MSPDEINIT_CB_ID : - hdcmi->MspDeInitCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if(hdcmi->State == HAL_DCMI_STATE_RESET) - { - switch (CallbackID) - { - case HAL_DCMI_MSPINIT_CB_ID : - hdcmi->MspInitCallback = pCallback; - break; - - case HAL_DCMI_MSPDEINIT_CB_ID : - hdcmi->MspDeInitCallback = pCallback; - break; - - default : - /* update the error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update the error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - } - - return status; -} - -/** - * @brief DCMI Callback Unregistering - * @param hdcmi dcmi handle - * @param CallbackID dcmi Callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_DCMI_UnRegisterCallback(DCMI_HandleTypeDef *hdcmi, HAL_DCMI_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(hdcmi->State == HAL_DCMI_STATE_READY) - { - switch (CallbackID) - { - case HAL_DCMI_FRAME_EVENT_CB_ID : - hdcmi->FrameEventCallback = HAL_DCMI_FrameEventCallback; /* Legacy weak FrameEventCallback */ - break; - - case HAL_DCMI_VSYNC_EVENT_CB_ID : - hdcmi->VsyncEventCallback = HAL_DCMI_VsyncEventCallback; /* Legacy weak VsyncEventCallback */ - break; - - case HAL_DCMI_LINE_EVENT_CB_ID : - hdcmi->LineEventCallback = HAL_DCMI_LineEventCallback; /* Legacy weak LineEventCallback */ - break; - - case HAL_DCMI_ERROR_CB_ID : - hdcmi->ErrorCallback = HAL_DCMI_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_DCMI_MSPINIT_CB_ID : - hdcmi->MspInitCallback = HAL_DCMI_MspInit; - break; - - case HAL_DCMI_MSPDEINIT_CB_ID : - hdcmi->MspDeInitCallback = HAL_DCMI_MspDeInit; - break; - - default : - /* update the error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(hdcmi->State == HAL_DCMI_STATE_RESET) - { - switch (CallbackID) - { - case HAL_DCMI_MSPINIT_CB_ID : - hdcmi->MspInitCallback = HAL_DCMI_MspInit; - break; - - case HAL_DCMI_MSPDEINIT_CB_ID : - hdcmi->MspDeInitCallback = HAL_DCMI_MspDeInit; - break; - - default : - /* update the error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update the error code */ - hdcmi->ErrorCode |= HAL_DCMI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - return status; -} -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DCMI_Private_Functions DCMI Private Functions - * @{ - */ - -/** - * @brief DMA conversion complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void DCMI_DMAXferCplt(DMA_HandleTypeDef *hdma) -{ - uint32_t tmp = 0U; - - DCMI_HandleTypeDef* hdcmi = ( DCMI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - if(hdcmi->XferCount != 0U) - { - /* Update memory 0 address location */ - tmp = ((hdcmi->DMA_Handle->Instance->CR) & DMA_SxCR_CT); - if(((hdcmi->XferCount % 2U) == 0U) && (tmp != 0U)) - { - tmp = hdcmi->DMA_Handle->Instance->M0AR; - HAL_DMAEx_ChangeMemory(hdcmi->DMA_Handle, (tmp + (8U*hdcmi->XferSize)), MEMORY0); - hdcmi->XferCount--; - } - /* Update memory 1 address location */ - else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) == 0U) - { - tmp = hdcmi->DMA_Handle->Instance->M1AR; - HAL_DMAEx_ChangeMemory(hdcmi->DMA_Handle, (tmp + (8U*hdcmi->XferSize)), MEMORY1); - hdcmi->XferCount--; - } - } - /* Update memory 0 address location */ - else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) != 0U) - { - hdcmi->DMA_Handle->Instance->M0AR = hdcmi->pBuffPtr; - } - /* Update memory 1 address location */ - else if((hdcmi->DMA_Handle->Instance->CR & DMA_SxCR_CT) == 0U) - { - tmp = hdcmi->pBuffPtr; - hdcmi->DMA_Handle->Instance->M1AR = (tmp + (4U*hdcmi->XferSize)); - hdcmi->XferCount = hdcmi->XferTransferNumber; - } - - /* Check if the frame is transferred */ - if(hdcmi->XferCount == hdcmi->XferTransferNumber) - { - /* Enable the Frame interrupt */ - __HAL_DCMI_ENABLE_IT(hdcmi, DCMI_IT_FRAME); - - /* When snapshot mode, set dcmi state to ready */ - if((hdcmi->Instance->CR & DCMI_CR_CM) == DCMI_MODE_SNAPSHOT) - { - hdcmi->State= HAL_DCMI_STATE_READY; - } - } -} - -/** - * @brief DMA error callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void DCMI_DMAError(DMA_HandleTypeDef *hdma) -{ - DCMI_HandleTypeDef* hdcmi = ( DCMI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - if(hdcmi->DMA_Handle->ErrorCode != HAL_DMA_ERROR_FE) - { - /* Initialize the DCMI state*/ - hdcmi->State = HAL_DCMI_STATE_READY; - } - - /* DCMI error Callback */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - /*Call registered DCMI error callback*/ - hdcmi->ErrorCallback(hdcmi); -#else - HAL_DCMI_ErrorCallback(hdcmi); -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ - -} - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ - STM32F479xx */ -#endif /* HAL_DCMI_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi_ex.c deleted file mode 100644 index b21454c90d9fbe7..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dcmi_ex.c +++ /dev/null @@ -1,185 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dcmi_ex.c - * @author MCD Application Team - * @brief DCMI Extension HAL module driver - * This file provides firmware functions to manage the following - * functionalities of DCMI extension peripheral: - * + Extension features functions - * - @verbatim - ============================================================================== - ##### DCMI peripheral extension features ##### - ============================================================================== - - [..] Comparing to other previous devices, the DCMI interface for STM32F446xx - devices contains the following additional features : - - (+) Support of Black and White cameras - - ##### How to use this driver ##### - ============================================================================== - [..] This driver provides functions to manage the Black and White feature - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -/** @defgroup DCMIEx DCMIEx - * @brief DCMI Extended HAL module driver - * @{ - */ - -#ifdef HAL_DCMI_MODULE_ENABLED - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) ||\ - defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup DCMIEx_Exported_Functions DCMI Extended Exported Functions - * @{ - */ - -/** - * @} - */ - -/** @addtogroup DCMI_Exported_Functions_Group1 Initialization and Configuration functions - * @{ - */ - -/** - * @brief Initializes the DCMI according to the specified - * parameters in the DCMI_InitTypeDef and create the associated handle. - * @param hdcmi pointer to a DCMI_HandleTypeDef structure that contains - * the configuration information for DCMI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DCMI_Init(DCMI_HandleTypeDef *hdcmi) -{ - /* Check the DCMI peripheral state */ - if(hdcmi == NULL) - { - return HAL_ERROR; - } - - /* Check function parameters */ - assert_param(IS_DCMI_ALL_INSTANCE(hdcmi->Instance)); - assert_param(IS_DCMI_PCKPOLARITY(hdcmi->Init.PCKPolarity)); - assert_param(IS_DCMI_VSPOLARITY(hdcmi->Init.VSPolarity)); - assert_param(IS_DCMI_HSPOLARITY(hdcmi->Init.HSPolarity)); - assert_param(IS_DCMI_SYNCHRO(hdcmi->Init.SynchroMode)); - assert_param(IS_DCMI_CAPTURE_RATE(hdcmi->Init.CaptureRate)); - assert_param(IS_DCMI_EXTENDED_DATA(hdcmi->Init.ExtendedDataMode)); - assert_param(IS_DCMI_MODE_JPEG(hdcmi->Init.JPEGMode)); -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - assert_param(IS_DCMI_BYTE_SELECT_MODE(hdcmi->Init.ByteSelectMode)); - assert_param(IS_DCMI_BYTE_SELECT_START(hdcmi->Init.ByteSelectStart)); - assert_param(IS_DCMI_LINE_SELECT_MODE(hdcmi->Init.LineSelectMode)); - assert_param(IS_DCMI_LINE_SELECT_START(hdcmi->Init.LineSelectStart)); -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - if(hdcmi->State == HAL_DCMI_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hdcmi->Lock = HAL_UNLOCKED; - /* Init the low level hardware */ - /* Init the DCMI Callback settings */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - hdcmi->FrameEventCallback = HAL_DCMI_FrameEventCallback; /* Legacy weak FrameEventCallback */ - hdcmi->VsyncEventCallback = HAL_DCMI_VsyncEventCallback; /* Legacy weak VsyncEventCallback */ - hdcmi->LineEventCallback = HAL_DCMI_LineEventCallback; /* Legacy weak LineEventCallback */ - hdcmi->ErrorCallback = HAL_DCMI_ErrorCallback; /* Legacy weak ErrorCallback */ - - if(hdcmi->MspInitCallback == NULL) - { - /* Legacy weak MspInit Callback */ - hdcmi->MspInitCallback = HAL_DCMI_MspInit; - } - /* Initialize the low level hardware (MSP) */ - hdcmi->MspInitCallback(hdcmi); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_DCMI_MspInit(hdcmi); -#endif /* (USE_HAL_DCMI_REGISTER_CALLBACKS) */ - HAL_DCMI_MspInit(hdcmi); - } - - /* Change the DCMI state */ - hdcmi->State = HAL_DCMI_STATE_BUSY; - /* Configures the HS, VS, DE and PC polarity */ - hdcmi->Instance->CR &= ~(DCMI_CR_PCKPOL | DCMI_CR_HSPOL | DCMI_CR_VSPOL | DCMI_CR_EDM_0 |\ - DCMI_CR_EDM_1 | DCMI_CR_FCRC_0 | DCMI_CR_FCRC_1 | DCMI_CR_JPEG |\ - DCMI_CR_ESS -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - | DCMI_CR_BSM_0 | DCMI_CR_BSM_1 | DCMI_CR_OEBS |\ - DCMI_CR_LSM | DCMI_CR_OELS -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - ); - hdcmi->Instance->CR |= (uint32_t)(hdcmi->Init.SynchroMode | hdcmi->Init.CaptureRate |\ - hdcmi->Init.VSPolarity | hdcmi->Init.HSPolarity |\ - hdcmi->Init.PCKPolarity | hdcmi->Init.ExtendedDataMode |\ - hdcmi->Init.JPEGMode -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - | hdcmi->Init.ByteSelectMode |\ - hdcmi->Init.ByteSelectStart | hdcmi->Init.LineSelectMode |\ - hdcmi->Init.LineSelectStart -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - ); - if(hdcmi->Init.SynchroMode == DCMI_SYNCHRO_EMBEDDED) - { - hdcmi->Instance->ESCR = (((uint32_t)hdcmi->Init.SyncroCode.FrameStartCode) | - ((uint32_t)hdcmi->Init.SyncroCode.LineStartCode << DCMI_POSITION_ESCR_LSC)| - ((uint32_t)hdcmi->Init.SyncroCode.LineEndCode << DCMI_POSITION_ESCR_LEC) | - ((uint32_t)hdcmi->Init.SyncroCode.FrameEndCode << DCMI_POSITION_ESCR_FEC)); - - } - - /* Enable the Line, Vsync, Error and Overrun interrupts */ - __HAL_DCMI_ENABLE_IT(hdcmi, DCMI_IT_LINE | DCMI_IT_VSYNC | DCMI_IT_ERR | DCMI_IT_OVR); - - /* Update error code */ - hdcmi->ErrorCode = HAL_DCMI_ERROR_NONE; - - /* Initialize the DCMI state*/ - hdcmi->State = HAL_DCMI_STATE_READY; - - return HAL_OK; -} - -/** - * @} - */ -#endif /* STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx ||\ - STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -#endif /* HAL_DCMI_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dfsdm.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dfsdm.c deleted file mode 100644 index c57ebebf7ff3502..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dfsdm.c +++ /dev/null @@ -1,4425 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dfsdm.c - * @author MCD Application Team - * @brief This file provides firmware functions to manage the following - * functionalities of the Digital Filter for Sigma-Delta Modulators - * (DFSDM) peripherals: - * + Initialization and configuration of channels and filters - * + Regular channels configuration - * + Injected channels configuration - * + Regular/Injected Channels DMA Configuration - * + Interrupts and flags management - * + Analog watchdog feature - * + Short-circuit detector feature - * + Extremes detector feature - * + Clock absence detector feature - * + Break generation on analog watchdog or short-circuit event - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - *** Channel initialization *** - ============================== - [..] - (#) User has first to initialize channels (before filters initialization). - (#) As prerequisite, fill in the HAL_DFSDM_ChannelMspInit() : - (++) Enable DFSDMz clock interface with __HAL_RCC_DFSDMz_CLK_ENABLE(). - (++) Enable the clocks for the DFSDMz GPIOS with __HAL_RCC_GPIOx_CLK_ENABLE(). - (++) Configure these DFSDMz pins in alternate mode using HAL_GPIO_Init(). - (++) If interrupt mode is used, enable and configure DFSDMz_FLT0 global - interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ(). - (#) Configure the output clock, input, serial interface, analog watchdog, - offset and data right bit shift parameters for this channel using the - HAL_DFSDM_ChannelInit() function. - - *** Channel clock absence detector *** - ====================================== - [..] - (#) Start clock absence detector using HAL_DFSDM_ChannelCkabStart() or - HAL_DFSDM_ChannelCkabStart_IT(). - (#) In polling mode, use HAL_DFSDM_ChannelPollForCkab() to detect the clock - absence. - (#) In interrupt mode, HAL_DFSDM_ChannelCkabCallback() will be called if - clock absence is detected. - (#) Stop clock absence detector using HAL_DFSDM_ChannelCkabStop() or - HAL_DFSDM_ChannelCkabStop_IT(). - (#) Please note that the same mode (polling or interrupt) has to be used - for all channels because the channels are sharing the same interrupt. - (#) Please note also that in interrupt mode, if clock absence detector is - stopped for one channel, interrupt will be disabled for all channels. - - *** Channel short circuit detector *** - ====================================== - [..] - (#) Start short circuit detector using HAL_DFSDM_ChannelScdStart() or - or HAL_DFSDM_ChannelScdStart_IT(). - (#) In polling mode, use HAL_DFSDM_ChannelPollForScd() to detect short - circuit. - (#) In interrupt mode, HAL_DFSDM_ChannelScdCallback() will be called if - short circuit is detected. - (#) Stop short circuit detector using HAL_DFSDM_ChannelScdStop() or - or HAL_DFSDM_ChannelScdStop_IT(). - (#) Please note that the same mode (polling or interrupt) has to be used - for all channels because the channels are sharing the same interrupt. - (#) Please note also that in interrupt mode, if short circuit detector is - stopped for one channel, interrupt will be disabled for all channels. - - *** Channel analog watchdog value *** - ===================================== - [..] - (#) Get analog watchdog filter value of a channel using - HAL_DFSDM_ChannelGetAwdValue(). - - *** Channel offset value *** - ===================================== - [..] - (#) Modify offset value of a channel using HAL_DFSDM_ChannelModifyOffset(). - - *** Filter initialization *** - ============================= - [..] - (#) After channel initialization, user has to init filters. - (#) As prerequisite, fill in the HAL_DFSDM_FilterMspInit() : - (++) If interrupt mode is used , enable and configure DFSDMz_FLTx global - interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ(). - Please note that DFSDMz_FLT0 global interrupt could be already - enabled if interrupt is used for channel. - (++) If DMA mode is used, configure DMA with HAL_DMA_Init() and link it - with DFSDMz filter handle using __HAL_LINKDMA(). - (#) Configure the regular conversion, injected conversion and filter - parameters for this filter using the HAL_DFSDM_FilterInit() function. - - *** Filter regular channel conversion *** - ========================================= - [..] - (#) Select regular channel and enable/disable continuous mode using - HAL_DFSDM_FilterConfigRegChannel(). - (#) Start regular conversion using HAL_DFSDM_FilterRegularStart(), - HAL_DFSDM_FilterRegularStart_IT(), HAL_DFSDM_FilterRegularStart_DMA() or - HAL_DFSDM_FilterRegularMsbStart_DMA(). - (#) In polling mode, use HAL_DFSDM_FilterPollForRegConversion() to detect - the end of regular conversion. - (#) In interrupt mode, HAL_DFSDM_FilterRegConvCpltCallback() will be called - at the end of regular conversion. - (#) Get value of regular conversion and corresponding channel using - HAL_DFSDM_FilterGetRegularValue(). - (#) In DMA mode, HAL_DFSDM_FilterRegConvHalfCpltCallback() and - HAL_DFSDM_FilterRegConvCpltCallback() will be called respectively at the - half transfer and at the transfer complete. Please note that - HAL_DFSDM_FilterRegConvHalfCpltCallback() will be called only in DMA - circular mode. - (#) Stop regular conversion using HAL_DFSDM_FilterRegularStop(), - HAL_DFSDM_FilterRegularStop_IT() or HAL_DFSDM_FilterRegularStop_DMA(). - - *** Filter injected channels conversion *** - =========================================== - [..] - (#) Select injected channels using HAL_DFSDM_FilterConfigInjChannel(). - (#) Start injected conversion using HAL_DFSDM_FilterInjectedStart(), - HAL_DFSDM_FilterInjectedStart_IT(), HAL_DFSDM_FilterInjectedStart_DMA() or - HAL_DFSDM_FilterInjectedMsbStart_DMA(). - (#) In polling mode, use HAL_DFSDM_FilterPollForInjConversion() to detect - the end of injected conversion. - (#) In interrupt mode, HAL_DFSDM_FilterInjConvCpltCallback() will be called - at the end of injected conversion. - (#) Get value of injected conversion and corresponding channel using - HAL_DFSDM_FilterGetInjectedValue(). - (#) In DMA mode, HAL_DFSDM_FilterInjConvHalfCpltCallback() and - HAL_DFSDM_FilterInjConvCpltCallback() will be called respectively at the - half transfer and at the transfer complete. Please note that - HAL_DFSDM_FilterInjConvCpltCallback() will be called only in DMA - circular mode. - (#) Stop injected conversion using HAL_DFSDM_FilterInjectedStop(), - HAL_DFSDM_FilterInjectedStop_IT() or HAL_DFSDM_FilterInjectedStop_DMA(). - - *** Filter analog watchdog *** - ============================== - [..] - (#) Start filter analog watchdog using HAL_DFSDM_FilterAwdStart_IT(). - (#) HAL_DFSDM_FilterAwdCallback() will be called if analog watchdog occurs. - (#) Stop filter analog watchdog using HAL_DFSDM_FilterAwdStop_IT(). - - *** Filter extreme detector *** - =============================== - [..] - (#) Start filter extreme detector using HAL_DFSDM_FilterExdStart(). - (#) Get extreme detector maximum value using HAL_DFSDM_FilterGetExdMaxValue(). - (#) Get extreme detector minimum value using HAL_DFSDM_FilterGetExdMinValue(). - (#) Start filter extreme detector using HAL_DFSDM_FilterExdStop(). - - *** Filter conversion time *** - ============================== - [..] - (#) Get conversion time value using HAL_DFSDM_FilterGetConvTimeValue(). - - *** Callback registration *** - ============================= - [..] - The compilation define USE_HAL_DFSDM_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use functions HAL_DFSDM_Channel_RegisterCallback(), - HAL_DFSDM_Filter_RegisterCallback() or - HAL_DFSDM_Filter_RegisterAwdCallback() to register a user callback. - - [..] - Function HAL_DFSDM_Channel_RegisterCallback() allows to register - following callbacks: - (+) CkabCallback : DFSDM channel clock absence detection callback. - (+) ScdCallback : DFSDM channel short circuit detection callback. - (+) MspInitCallback : DFSDM channel MSP init callback. - (+) MspDeInitCallback : DFSDM channel MSP de-init callback. - [..] - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - Function HAL_DFSDM_Filter_RegisterCallback() allows to register - following callbacks: - (+) RegConvCpltCallback : DFSDM filter regular conversion complete callback. - (+) RegConvHalfCpltCallback : DFSDM filter half regular conversion complete callback. - (+) InjConvCpltCallback : DFSDM filter injected conversion complete callback. - (+) InjConvHalfCpltCallback : DFSDM filter half injected conversion complete callback. - (+) ErrorCallback : DFSDM filter error callback. - (+) MspInitCallback : DFSDM filter MSP init callback. - (+) MspDeInitCallback : DFSDM filter MSP de-init callback. - [..] - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - For specific DFSDM filter analog watchdog callback use dedicated register callback: - HAL_DFSDM_Filter_RegisterAwdCallback(). - - [..] - Use functions HAL_DFSDM_Channel_UnRegisterCallback() or - HAL_DFSDM_Filter_UnRegisterCallback() to reset a callback to the default - weak function. - - [..] - HAL_DFSDM_Channel_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - [..] - This function allows to reset following callbacks: - (+) CkabCallback : DFSDM channel clock absence detection callback. - (+) ScdCallback : DFSDM channel short circuit detection callback. - (+) MspInitCallback : DFSDM channel MSP init callback. - (+) MspDeInitCallback : DFSDM channel MSP de-init callback. - - [..] - HAL_DFSDM_Filter_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - [..] - This function allows to reset following callbacks: - (+) RegConvCpltCallback : DFSDM filter regular conversion complete callback. - (+) RegConvHalfCpltCallback : DFSDM filter half regular conversion complete callback. - (+) InjConvCpltCallback : DFSDM filter injected conversion complete callback. - (+) InjConvHalfCpltCallback : DFSDM filter half injected conversion complete callback. - (+) ErrorCallback : DFSDM filter error callback. - (+) MspInitCallback : DFSDM filter MSP init callback. - (+) MspDeInitCallback : DFSDM filter MSP de-init callback. - - [..] - For specific DFSDM filter analog watchdog callback use dedicated unregister callback: - HAL_DFSDM_Filter_UnRegisterAwdCallback(). - - [..] - By default, after the call of init function and if the state is RESET - all callbacks are reset to the corresponding legacy weak functions: - examples HAL_DFSDM_ChannelScdCallback(), HAL_DFSDM_FilterErrorCallback(). - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak functions in the init and de-init only when these - callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the init and de-init keep and use - the user MspInit/MspDeInit callbacks (registered beforehand) - - [..] - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the init/de-init. - In that case first register the MspInit/MspDeInit user callbacks using - HAL_DFSDM_Channel_RegisterCallback() or - HAL_DFSDM_Filter_RegisterCallback() before calling init or de-init function. - - [..] - When The compilation define USE_HAL_DFSDM_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#ifdef HAL_DFSDM_MODULE_ENABLED -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup DFSDM DFSDM - * @brief DFSDM HAL driver module - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup DFSDM_Private_Define DFSDM Private Define - * @{ - */ - -#define DFSDM_FLTCR1_MSB_RCH_OFFSET 8U - -#define DFSDM_MSB_MASK 0xFFFF0000U -#define DFSDM_LSB_MASK 0x0000FFFFU -#define DFSDM_CKAB_TIMEOUT 5000U -#define DFSDM1_CHANNEL_NUMBER 4U -#if defined (DFSDM2_Channel0) -#define DFSDM2_CHANNEL_NUMBER 8U -#endif /* DFSDM2_Channel0 */ - -/** - * @} - */ -/** @addtogroup DFSDM_Private_Macros -* @{ -*/ - -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup DFSDM_Private_Variables DFSDM Private Variables - * @{ - */ -__IO uint32_t v_dfsdm1ChannelCounter = 0U; -DFSDM_Channel_HandleTypeDef* a_dfsdm1ChannelHandle[DFSDM1_CHANNEL_NUMBER] = {NULL}; - -#if defined (DFSDM2_Channel0) -__IO uint32_t v_dfsdm2ChannelCounter = 0U; -DFSDM_Channel_HandleTypeDef* a_dfsdm2ChannelHandle[DFSDM2_CHANNEL_NUMBER] = {NULL}; -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup DFSDM_Private_Functions DFSDM Private Functions - * @{ - */ -static uint32_t DFSDM_GetInjChannelsNbr(uint32_t Channels); -static uint32_t DFSDM_GetChannelFromInstance(DFSDM_Channel_TypeDef* Instance); -static void DFSDM_RegConvStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -static void DFSDM_RegConvStop(DFSDM_Filter_HandleTypeDef* hdfsdm_filter); -static void DFSDM_InjConvStart(DFSDM_Filter_HandleTypeDef* hdfsdm_filter); -static void DFSDM_InjConvStop(DFSDM_Filter_HandleTypeDef* hdfsdm_filter); -static void DFSDM_DMARegularHalfConvCplt(DMA_HandleTypeDef *hdma); -static void DFSDM_DMARegularConvCplt(DMA_HandleTypeDef *hdma); -static void DFSDM_DMAInjectedHalfConvCplt(DMA_HandleTypeDef *hdma); -static void DFSDM_DMAInjectedConvCplt(DMA_HandleTypeDef *hdma); -static void DFSDM_DMAError(DMA_HandleTypeDef *hdma); - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DFSDM_Exported_Functions DFSDM Exported Functions - * @{ - */ - -/** @defgroup DFSDM_Exported_Functions_Group1_Channel Channel initialization and de-initialization functions - * @brief Channel initialization and de-initialization functions - * -@verbatim - ============================================================================== - ##### Channel initialization and de-initialization functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Initialize the DFSDM channel. - (+) De-initialize the DFSDM channel. -@endverbatim - * @{ - */ - -/** - * @brief Initialize the DFSDM channel according to the specified parameters - * in the DFSDM_ChannelInitTypeDef structure and initialize the associated handle. - * @param hdfsdm_channel DFSDM channel handle. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ -#if defined(DFSDM2_Channel0) - __IO uint32_t* channelCounterPtr; - DFSDM_Channel_HandleTypeDef **channelHandleTable; - DFSDM_Channel_TypeDef* channel0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check DFSDM Channel handle */ - if(hdfsdm_channel == NULL) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - assert_param(IS_FUNCTIONAL_STATE(hdfsdm_channel->Init.OutputClock.Activation)); - assert_param(IS_DFSDM_CHANNEL_INPUT(hdfsdm_channel->Init.Input.Multiplexer)); - assert_param(IS_DFSDM_CHANNEL_DATA_PACKING(hdfsdm_channel->Init.Input.DataPacking)); - assert_param(IS_DFSDM_CHANNEL_INPUT_PINS(hdfsdm_channel->Init.Input.Pins)); - assert_param(IS_DFSDM_CHANNEL_SERIAL_INTERFACE_TYPE(hdfsdm_channel->Init.SerialInterface.Type)); - assert_param(IS_DFSDM_CHANNEL_SPI_CLOCK(hdfsdm_channel->Init.SerialInterface.SpiClock)); - assert_param(IS_DFSDM_CHANNEL_FILTER_ORDER(hdfsdm_channel->Init.Awd.FilterOrder)); - assert_param(IS_DFSDM_CHANNEL_FILTER_OVS_RATIO(hdfsdm_channel->Init.Awd.Oversampling)); - assert_param(IS_DFSDM_CHANNEL_OFFSET(hdfsdm_channel->Init.Offset)); - assert_param(IS_DFSDM_CHANNEL_RIGHT_BIT_SHIFT(hdfsdm_channel->Init.RightBitShift)); - -#if defined(DFSDM2_Channel0) - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - channelCounterPtr = &v_dfsdm1ChannelCounter; - channelHandleTable = a_dfsdm1ChannelHandle; - channel0Instance = DFSDM1_Channel0; - } - else - { - channelCounterPtr = &v_dfsdm2ChannelCounter; - channelHandleTable = a_dfsdm2ChannelHandle; - channel0Instance = DFSDM2_Channel0; - } - - /* Check that channel has not been already initialized */ - if(channelHandleTable[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] != NULL) - { - return HAL_ERROR; - } - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - /* Reset callback pointers to the weak predefined callbacks */ - hdfsdm_channel->CkabCallback = HAL_DFSDM_ChannelCkabCallback; - hdfsdm_channel->ScdCallback = HAL_DFSDM_ChannelScdCallback; - - /* Call MSP init function */ - if(hdfsdm_channel->MspInitCallback == NULL) - { - hdfsdm_channel->MspInitCallback = HAL_DFSDM_ChannelMspInit; - } - hdfsdm_channel->MspInitCallback(hdfsdm_channel); -#else - /* Call MSP init function */ - HAL_DFSDM_ChannelMspInit(hdfsdm_channel); -#endif - - /* Update the channel counter */ - (*channelCounterPtr)++; - - /* Configure output serial clock and enable global DFSDM interface only for first channel */ - if(*channelCounterPtr == 1U) - { - assert_param(IS_DFSDM_CHANNEL_OUTPUT_CLOCK(hdfsdm_channel->Init.OutputClock.Selection)); - /* Set the output serial clock source */ - channel0Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKOUTSRC); - channel0Instance->CHCFGR1 |= hdfsdm_channel->Init.OutputClock.Selection; - - /* Reset clock divider */ - channel0Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKOUTDIV); - if(hdfsdm_channel->Init.OutputClock.Activation == ENABLE) - { - assert_param(IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(hdfsdm_channel->Init.OutputClock.Divider)); - /* Set the output clock divider */ - channel0Instance->CHCFGR1 |= (uint32_t) ((hdfsdm_channel->Init.OutputClock.Divider - 1U) << - DFSDM_CHCFGR1_CKOUTDIV_Pos); - } - - /* enable the DFSDM global interface */ - channel0Instance->CHCFGR1 |= DFSDM_CHCFGR1_DFSDMEN; - } - - /* Set channel input parameters */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_DATPACK | DFSDM_CHCFGR1_DATMPX | - DFSDM_CHCFGR1_CHINSEL); - hdfsdm_channel->Instance->CHCFGR1 |= (hdfsdm_channel->Init.Input.Multiplexer | - hdfsdm_channel->Init.Input.DataPacking | - hdfsdm_channel->Init.Input.Pins); - - /* Set serial interface parameters */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_SITP | DFSDM_CHCFGR1_SPICKSEL); - hdfsdm_channel->Instance->CHCFGR1 |= (hdfsdm_channel->Init.SerialInterface.Type | - hdfsdm_channel->Init.SerialInterface.SpiClock); - - /* Set analog watchdog parameters */ - hdfsdm_channel->Instance->CHAWSCDR &= ~(DFSDM_CHAWSCDR_AWFORD | DFSDM_CHAWSCDR_AWFOSR); - hdfsdm_channel->Instance->CHAWSCDR |= (hdfsdm_channel->Init.Awd.FilterOrder | - ((hdfsdm_channel->Init.Awd.Oversampling - 1U) << DFSDM_CHAWSCDR_AWFOSR_Pos)); - - /* Set channel offset and right bit shift */ - hdfsdm_channel->Instance->CHCFGR2 &= ~(DFSDM_CHCFGR2_OFFSET | DFSDM_CHCFGR2_DTRBS); - hdfsdm_channel->Instance->CHCFGR2 |= (((uint32_t) hdfsdm_channel->Init.Offset << DFSDM_CHCFGR2_OFFSET_Pos) | - (hdfsdm_channel->Init.RightBitShift << DFSDM_CHCFGR2_DTRBS_Pos)); - - /* Enable DFSDM channel */ - hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CHEN; - - /* Set DFSDM Channel to ready state */ - hdfsdm_channel->State = HAL_DFSDM_CHANNEL_STATE_READY; - - /* Store channel handle in DFSDM channel handle table */ - channelHandleTable[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] = hdfsdm_channel; - -#else - /* Check that channel has not been already initialized */ - if(a_dfsdm1ChannelHandle[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] != NULL) - { - return HAL_ERROR; - } - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - /* Reset callback pointers to the weak predefined callbacks */ - hdfsdm_channel->CkabCallback = HAL_DFSDM_ChannelCkabCallback; - hdfsdm_channel->ScdCallback = HAL_DFSDM_ChannelScdCallback; - - /* Call MSP init function */ - if(hdfsdm_channel->MspInitCallback == NULL) - { - hdfsdm_channel->MspInitCallback = HAL_DFSDM_ChannelMspInit; - } - hdfsdm_channel->MspInitCallback(hdfsdm_channel); -#else - /* Call MSP init function */ - HAL_DFSDM_ChannelMspInit(hdfsdm_channel); -#endif - - /* Update the channel counter */ - v_dfsdm1ChannelCounter++; - - /* Configure output serial clock and enable global DFSDM interface only for first channel */ - if(v_dfsdm1ChannelCounter == 1U) - { - assert_param(IS_DFSDM_CHANNEL_OUTPUT_CLOCK(hdfsdm_channel->Init.OutputClock.Selection)); - /* Set the output serial clock source */ - DFSDM1_Channel0->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKOUTSRC); - DFSDM1_Channel0->CHCFGR1 |= hdfsdm_channel->Init.OutputClock.Selection; - - /* Reset clock divider */ - DFSDM1_Channel0->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKOUTDIV); - if(hdfsdm_channel->Init.OutputClock.Activation == ENABLE) - { - assert_param(IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(hdfsdm_channel->Init.OutputClock.Divider)); - /* Set the output clock divider */ - DFSDM1_Channel0->CHCFGR1 |= (uint32_t) ((hdfsdm_channel->Init.OutputClock.Divider - 1U) << - DFSDM_CHCFGR1_CKOUTDIV_Pos); - } - - /* enable the DFSDM global interface */ - DFSDM1_Channel0->CHCFGR1 |= DFSDM_CHCFGR1_DFSDMEN; - } - - /* Set channel input parameters */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_DATPACK | DFSDM_CHCFGR1_DATMPX | - DFSDM_CHCFGR1_CHINSEL); - hdfsdm_channel->Instance->CHCFGR1 |= (hdfsdm_channel->Init.Input.Multiplexer | - hdfsdm_channel->Init.Input.DataPacking | - hdfsdm_channel->Init.Input.Pins); - - /* Set serial interface parameters */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_SITP | DFSDM_CHCFGR1_SPICKSEL); - hdfsdm_channel->Instance->CHCFGR1 |= (hdfsdm_channel->Init.SerialInterface.Type | - hdfsdm_channel->Init.SerialInterface.SpiClock); - - /* Set analog watchdog parameters */ - hdfsdm_channel->Instance->CHAWSCDR &= ~(DFSDM_CHAWSCDR_AWFORD | DFSDM_CHAWSCDR_AWFOSR); - hdfsdm_channel->Instance->CHAWSCDR |= (hdfsdm_channel->Init.Awd.FilterOrder | - ((hdfsdm_channel->Init.Awd.Oversampling - 1U) << DFSDM_CHAWSCDR_AWFOSR_Pos)); - - /* Set channel offset and right bit shift */ - hdfsdm_channel->Instance->CHCFGR2 &= ~(DFSDM_CHCFGR2_OFFSET | DFSDM_CHCFGR2_DTRBS); - hdfsdm_channel->Instance->CHCFGR2 |= (((uint32_t) hdfsdm_channel->Init.Offset << DFSDM_CHCFGR2_OFFSET_Pos) | - (hdfsdm_channel->Init.RightBitShift << DFSDM_CHCFGR2_DTRBS_Pos)); - - /* Enable DFSDM channel */ - hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CHEN; - - /* Set DFSDM Channel to ready state */ - hdfsdm_channel->State = HAL_DFSDM_CHANNEL_STATE_READY; - - /* Store channel handle in DFSDM channel handle table */ - a_dfsdm1ChannelHandle[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] = hdfsdm_channel; -#endif /* DFSDM2_Channel0 */ - - return HAL_OK; -} - -/** - * @brief De-initialize the DFSDM channel. - * @param hdfsdm_channel DFSDM channel handle. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ -#if defined(DFSDM2_Channel0) - __IO uint32_t* channelCounterPtr; - DFSDM_Channel_HandleTypeDef **channelHandleTable; - DFSDM_Channel_TypeDef* channel0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check DFSDM Channel handle */ - if(hdfsdm_channel == NULL) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - -#if defined(DFSDM2_Channel0) - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - channelCounterPtr = &v_dfsdm1ChannelCounter; - channelHandleTable = a_dfsdm1ChannelHandle; - channel0Instance = DFSDM1_Channel0; - } - else - { - channelCounterPtr = &v_dfsdm2ChannelCounter; - channelHandleTable = a_dfsdm2ChannelHandle; - channel0Instance = DFSDM2_Channel0; - } - - /* Check that channel has not been already deinitialized */ - if(channelHandleTable[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] == NULL) - { - return HAL_ERROR; - } - - /* Disable the DFSDM channel */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CHEN); - - /* Update the channel counter */ - (*channelCounterPtr)--; - - /* Disable global DFSDM at deinit of last channel */ - if(*channelCounterPtr == 0U) - { - channel0Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_DFSDMEN); - } - - /* Call MSP deinit function */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - if(hdfsdm_channel->MspDeInitCallback == NULL) - { - hdfsdm_channel->MspDeInitCallback = HAL_DFSDM_ChannelMspDeInit; - } - hdfsdm_channel->MspDeInitCallback(hdfsdm_channel); -#else - HAL_DFSDM_ChannelMspDeInit(hdfsdm_channel); -#endif - - /* Set DFSDM Channel in reset state */ - hdfsdm_channel->State = HAL_DFSDM_CHANNEL_STATE_RESET; - - /* Reset channel handle in DFSDM channel handle table */ - channelHandleTable[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] = NULL; -#else - /* Check that channel has not been already deinitialized */ - if(a_dfsdm1ChannelHandle[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] == NULL) - { - return HAL_ERROR; - } - - /* Disable the DFSDM channel */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CHEN); - - /* Update the channel counter */ - v_dfsdm1ChannelCounter--; - - /* Disable global DFSDM at deinit of last channel */ - if(v_dfsdm1ChannelCounter == 0U) - { - DFSDM1_Channel0->CHCFGR1 &= ~(DFSDM_CHCFGR1_DFSDMEN); - } - - /* Call MSP deinit function */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - if(hdfsdm_channel->MspDeInitCallback == NULL) - { - hdfsdm_channel->MspDeInitCallback = HAL_DFSDM_ChannelMspDeInit; - } - hdfsdm_channel->MspDeInitCallback(hdfsdm_channel); -#else - HAL_DFSDM_ChannelMspDeInit(hdfsdm_channel); -#endif - - /* Set DFSDM Channel in reset state */ - hdfsdm_channel->State = HAL_DFSDM_CHANNEL_STATE_RESET; - - /* Reset channel handle in DFSDM channel handle table */ - a_dfsdm1ChannelHandle[DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance)] = (DFSDM_Channel_HandleTypeDef *) NULL; -#endif /* defined(DFSDM2_Channel0) */ - - return HAL_OK; -} - -/** - * @brief Initialize the DFSDM channel MSP. - * @param hdfsdm_channel DFSDM channel handle. - * @retval None - */ -__weak void HAL_DFSDM_ChannelMspInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_channel); - /* NOTE : This function should not be modified, when the function is needed, - the HAL_DFSDM_ChannelMspInit could be implemented in the user file. - */ -} - -/** - * @brief De-initialize the DFSDM channel MSP. - * @param hdfsdm_channel DFSDM channel handle. - * @retval None - */ -__weak void HAL_DFSDM_ChannelMspDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_channel); - /* NOTE : This function should not be modified, when the function is needed, - the HAL_DFSDM_ChannelMspDeInit could be implemented in the user file. - */ -} - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/** - * @brief Register a user DFSDM channel callback - * to be used instead of the weak predefined callback. - * @param hdfsdm_channel DFSDM channel handle. - * @param CallbackID ID of the callback to be registered. - * This parameter can be one of the following values: - * @arg @ref HAL_DFSDM_CHANNEL_CKAB_CB_ID clock absence detection callback ID. - * @arg @ref HAL_DFSDM_CHANNEL_SCD_CB_ID short circuit detection callback ID. - * @arg @ref HAL_DFSDM_CHANNEL_MSPINIT_CB_ID MSP init callback ID. - * @arg @ref HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID MSP de-init callback ID. - * @param pCallback pointer to the callback function. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_Channel_RegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID, - pDFSDM_Channel_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - /* update return status */ - status = HAL_ERROR; - } - else - { - if(HAL_DFSDM_CHANNEL_STATE_READY == hdfsdm_channel->State) - { - switch (CallbackID) - { - case HAL_DFSDM_CHANNEL_CKAB_CB_ID : - hdfsdm_channel->CkabCallback = pCallback; - break; - case HAL_DFSDM_CHANNEL_SCD_CB_ID : - hdfsdm_channel->ScdCallback = pCallback; - break; - case HAL_DFSDM_CHANNEL_MSPINIT_CB_ID : - hdfsdm_channel->MspInitCallback = pCallback; - break; - case HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID : - hdfsdm_channel->MspDeInitCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(HAL_DFSDM_CHANNEL_STATE_RESET == hdfsdm_channel->State) - { - switch (CallbackID) - { - case HAL_DFSDM_CHANNEL_MSPINIT_CB_ID : - hdfsdm_channel->MspInitCallback = pCallback; - break; - case HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID : - hdfsdm_channel->MspDeInitCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - } - return status; -} - -/** - * @brief Unregister a user DFSDM channel callback. - * DFSDM channel callback is redirected to the weak predefined callback. - * @param hdfsdm_channel DFSDM channel handle. - * @param CallbackID ID of the callback to be unregistered. - * This parameter can be one of the following values: - * @arg @ref HAL_DFSDM_CHANNEL_CKAB_CB_ID clock absence detection callback ID. - * @arg @ref HAL_DFSDM_CHANNEL_SCD_CB_ID short circuit detection callback ID. - * @arg @ref HAL_DFSDM_CHANNEL_MSPINIT_CB_ID MSP init callback ID. - * @arg @ref HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID MSP de-init callback ID. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_Channel_UnRegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(HAL_DFSDM_CHANNEL_STATE_READY == hdfsdm_channel->State) - { - switch (CallbackID) - { - case HAL_DFSDM_CHANNEL_CKAB_CB_ID : - hdfsdm_channel->CkabCallback = HAL_DFSDM_ChannelCkabCallback; - break; - case HAL_DFSDM_CHANNEL_SCD_CB_ID : - hdfsdm_channel->ScdCallback = HAL_DFSDM_ChannelScdCallback; - break; - case HAL_DFSDM_CHANNEL_MSPINIT_CB_ID : - hdfsdm_channel->MspInitCallback = HAL_DFSDM_ChannelMspInit; - break; - case HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID : - hdfsdm_channel->MspDeInitCallback = HAL_DFSDM_ChannelMspDeInit; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(HAL_DFSDM_CHANNEL_STATE_RESET == hdfsdm_channel->State) - { - switch (CallbackID) - { - case HAL_DFSDM_CHANNEL_MSPINIT_CB_ID : - hdfsdm_channel->MspInitCallback = HAL_DFSDM_ChannelMspInit; - break; - case HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID : - hdfsdm_channel->MspDeInitCallback = HAL_DFSDM_ChannelMspDeInit; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - return status; -} -#endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group2_Channel Channel operation functions - * @brief Channel operation functions - * -@verbatim - ============================================================================== - ##### Channel operation functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Manage clock absence detector feature. - (+) Manage short circuit detector feature. - (+) Get analog watchdog value. - (+) Modify offset value. -@endverbatim - * @{ - */ - -/** - * @brief This function allows to start clock absence detection in polling mode. - * @note Same mode has to be used for all channels. - * @note If clock is not available on this channel during 5 seconds, - * clock absence detection will not be activated and function - * will return HAL_TIMEOUT error. - * @param hdfsdm_channel DFSDM channel handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tickstart; - uint32_t channel; - -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { -#if defined (DFSDM2_Channel0) - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - /* Get channel number from channel instance */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Clear clock absence flag */ - while((((filter0Instance->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) != 0U) - { - filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - - /* Check the Timeout */ - if((HAL_GetTick()-tickstart) > DFSDM_CKAB_TIMEOUT) - { - /* Set timeout status */ - status = HAL_TIMEOUT; - break; - } - } -#else - /* Get channel number from channel instance */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Clear clock absence flag */ - while((((DFSDM1_Filter0->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) != 0U) - { - DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - - /* Check the Timeout */ - if((HAL_GetTick()-tickstart) > DFSDM_CKAB_TIMEOUT) - { - /* Set timeout status */ - status = HAL_TIMEOUT; - break; - } - } -#endif /* DFSDM2_Channel0 */ - - if(status == HAL_OK) - { - /* Start clock absence detection */ - hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CKABEN; - } - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to poll for the clock absence detection. - * @param hdfsdm_channel DFSDM channel handle. - * @param Timeout Timeout value in milliseconds. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelPollForCkab(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - uint32_t Timeout) -{ - uint32_t tickstart; - uint32_t channel; -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - return HAL_ERROR; - } - else - { -#if defined(DFSDM2_Channel0) - - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - - /* Get channel number from channel instance */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Wait clock absence detection */ - while((((filter0Instance->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) == 0U) - { - /* Check the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U) || ((HAL_GetTick()-tickstart) > Timeout)) - { - /* Return timeout status */ - return HAL_TIMEOUT; - } - } - } - - /* Clear clock absence detection flag */ - filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); -#else - /* Get channel number from channel instance */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Wait clock absence detection */ - while((((DFSDM1_Filter0->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) == 0U) - { - /* Check the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if(((HAL_GetTick()-tickstart) > Timeout) || (Timeout == 0U)) - { - /* Return timeout status */ - return HAL_TIMEOUT; - } - } - } - - /* Clear clock absence detection flag */ - DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); -#endif /* defined(DFSDM2_Channel0) */ - /* Return function status */ - return HAL_OK; - } -} - -/** - * @brief This function allows to stop clock absence detection in polling mode. - * @param hdfsdm_channel DFSDM channel handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t channel; -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { -#if defined(DFSDM2_Channel0) - - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - - /* Stop clock absence detection */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKABEN); - - /* Clear clock absence flag */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - -#else - /* Stop clock absence detection */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKABEN); - - /* Clear clock absence flag */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); -#endif /* DFSDM2_Channel0 */ - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start clock absence detection in interrupt mode. - * @note Same mode has to be used for all channels. - * @note If clock is not available on this channel during 5 seconds, - * clock absence detection will not be activated and function - * will return HAL_TIMEOUT error. - * @param hdfsdm_channel DFSDM channel handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t channel; - uint32_t tickstart; -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { -#if defined(DFSDM2_Channel0) - - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - - /* Get channel number from channel instance */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Clear clock absence flag */ - while((((filter0Instance->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) != 0U) - { - filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - - /* Check the Timeout */ - if((HAL_GetTick()-tickstart) > DFSDM_CKAB_TIMEOUT) - { - /* Set timeout status */ - status = HAL_TIMEOUT; - break; - } - } - - if(status == HAL_OK) - { - /* Activate clock absence detection interrupt */ - filter0Instance->FLTCR2 |= DFSDM_FLTCR2_CKABIE; - - /* Start clock absence detection */ - hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CKABEN; - } -#else - /* Get channel number from channel instance */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Clear clock absence flag */ - while((((DFSDM1_Filter0->FLTISR & DFSDM_FLTISR_CKABF) >> (DFSDM_FLTISR_CKABF_Pos + channel)) & 1U) != 0U) - { - DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - - /* Check the Timeout */ - if((HAL_GetTick()-tickstart) > DFSDM_CKAB_TIMEOUT) - { - /* Set timeout status */ - status = HAL_TIMEOUT; - break; - } - } - - if(status == HAL_OK) - { - /* Activate clock absence detection interrupt */ - DFSDM1_Filter0->FLTCR2 |= DFSDM_FLTCR2_CKABIE; - - /* Start clock absence detection */ - hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_CKABEN; - } - -#endif /* defined(DFSDM2_Channel0) */ - } - /* Return function status */ - return status; -} - -/** - * @brief Clock absence detection callback. - * @param hdfsdm_channel DFSDM channel handle. - * @retval None - */ -__weak void HAL_DFSDM_ChannelCkabCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_channel); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DFSDM_ChannelCkabCallback could be implemented in the user file - */ -} - -/** - * @brief This function allows to stop clock absence detection in interrupt mode. - * @note Interrupt will be disabled for all channels - * @param hdfsdm_channel DFSDM channel handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t channel; -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { -#if defined(DFSDM2_Channel0) - - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - - /* Stop clock absence detection */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKABEN); - - /* Clear clock absence flag */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - - /* Disable clock absence detection interrupt */ - filter0Instance->FLTCR2 &= ~(DFSDM_FLTCR2_CKABIE); -#else - - /* Stop clock absence detection */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_CKABEN); - - /* Clear clock absence flag */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - - /* Disable clock absence detection interrupt */ - DFSDM1_Filter0->FLTCR2 &= ~(DFSDM_FLTCR2_CKABIE); -#endif /* DFSDM2_Channel0 */ - } - - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start short circuit detection in polling mode. - * @note Same mode has to be used for all channels - * @param hdfsdm_channel DFSDM channel handle. - * @param Threshold Short circuit detector threshold. - * This parameter must be a number between Min_Data = 0 and Max_Data = 255. - * @param BreakSignal Break signals assigned to short circuit event. - * This parameter can be a values combination of @ref DFSDM_BreakSignals. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - uint32_t Threshold, - uint32_t BreakSignal) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - assert_param(IS_DFSDM_CHANNEL_SCD_THRESHOLD(Threshold)); - assert_param(IS_DFSDM_BREAK_SIGNALS(BreakSignal)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Configure threshold and break signals */ - hdfsdm_channel->Instance->CHAWSCDR &= ~(DFSDM_CHAWSCDR_BKSCD | DFSDM_CHAWSCDR_SCDT); - hdfsdm_channel->Instance->CHAWSCDR |= ((BreakSignal << DFSDM_CHAWSCDR_BKSCD_Pos) | \ - Threshold); - - /* Start short circuit detection */ - hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_SCDEN; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to poll for the short circuit detection. - * @param hdfsdm_channel DFSDM channel handle. - * @param Timeout Timeout value in milliseconds. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelPollForScd(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - uint32_t Timeout) -{ - uint32_t tickstart; - uint32_t channel; -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - return HAL_ERROR; - } - else - { - /* Get channel number from channel instance */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - -#if defined(DFSDM2_Channel0) - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Wait short circuit detection */ - while(((filter0Instance->FLTISR & DFSDM_FLTISR_SCDF) >> (DFSDM_FLTISR_SCDF_Pos + channel)) == 0U) - { - /* Check the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U) || ((HAL_GetTick()-tickstart) > Timeout)) - { - /* Return timeout status */ - return HAL_TIMEOUT; - } - } - } - - /* Clear short circuit detection flag */ - filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); - -#else - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Wait short circuit detection */ - while(((DFSDM1_Filter0->FLTISR & DFSDM_FLTISR_SCDF) >> (DFSDM_FLTISR_SCDF_Pos + channel)) == 0U) - { - /* Check the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if(((HAL_GetTick()-tickstart) > Timeout) || (Timeout == 0U)) - { - /* Return timeout status */ - return HAL_TIMEOUT; - } - } - } - - /* Clear short circuit detection flag */ - DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); -#endif /* DFSDM2_Channel0 */ - - /* Return function status */ - return HAL_OK; - } -} - -/** - * @brief This function allows to stop short circuit detection in polling mode. - * @param hdfsdm_channel DFSDM channel handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t channel; -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Stop short circuit detection */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_SCDEN); - - /* Clear short circuit detection flag */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); - -#if defined(DFSDM2_Channel0) - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - - filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); -#else - DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); -#endif /* DFSDM2_Channel0*/ - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start short circuit detection in interrupt mode. - * @note Same mode has to be used for all channels - * @param hdfsdm_channel DFSDM channel handle. - * @param Threshold Short circuit detector threshold. - * This parameter must be a number between Min_Data = 0 and Max_Data = 255. - * @param BreakSignal Break signals assigned to short circuit event. - * This parameter can be a values combination of @ref DFSDM_BreakSignals. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - uint32_t Threshold, - uint32_t BreakSignal) -{ - HAL_StatusTypeDef status = HAL_OK; -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - assert_param(IS_DFSDM_CHANNEL_SCD_THRESHOLD(Threshold)); - assert_param(IS_DFSDM_BREAK_SIGNALS(BreakSignal)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { -#if defined(DFSDM2_Channel0) - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - /* Activate short circuit detection interrupt */ - filter0Instance->FLTCR2 |= DFSDM_FLTCR2_SCDIE; -#else - /* Activate short circuit detection interrupt */ - DFSDM1_Filter0->FLTCR2 |= DFSDM_FLTCR2_SCDIE; -#endif /* DFSDM2_Channel0 */ - - /* Configure threshold and break signals */ - hdfsdm_channel->Instance->CHAWSCDR &= ~(DFSDM_CHAWSCDR_BKSCD | DFSDM_CHAWSCDR_SCDT); - hdfsdm_channel->Instance->CHAWSCDR |= ((BreakSignal << DFSDM_CHAWSCDR_BKSCD_Pos) | \ - Threshold); - - /* Start short circuit detection */ - hdfsdm_channel->Instance->CHCFGR1 |= DFSDM_CHCFGR1_SCDEN; - } - /* Return function status */ - return status; -} - -/** - * @brief Short circuit detection callback. - * @param hdfsdm_channel DFSDM channel handle. - * @retval None - */ -__weak void HAL_DFSDM_ChannelScdCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_channel); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DFSDM_ChannelScdCallback could be implemented in the user file - */ -} - -/** - * @brief This function allows to stop short circuit detection in interrupt mode. - * @note Interrupt will be disabled for all channels - * @param hdfsdm_channel DFSDM channel handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t channel; -#if defined(DFSDM2_Channel0) - DFSDM_Filter_TypeDef* filter0Instance; -#endif /* defined(DFSDM2_Channel0) */ - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Stop short circuit detection */ - hdfsdm_channel->Instance->CHCFGR1 &= ~(DFSDM_CHCFGR1_SCDEN); - - /* Clear short circuit detection flag */ - channel = DFSDM_GetChannelFromInstance(hdfsdm_channel->Instance); -#if defined(DFSDM2_Channel0) - /* Get channel counter, channel handle table and channel 0 instance */ - if(IS_DFSDM1_CHANNEL_INSTANCE(hdfsdm_channel->Instance)) - { - filter0Instance = DFSDM1_Filter0; - } - else - { - filter0Instance = DFSDM2_Filter0; - } - - filter0Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); - - /* Disable short circuit detection interrupt */ - filter0Instance->FLTCR2 &= ~(DFSDM_FLTCR2_SCDIE); -#else - DFSDM1_Filter0->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); - - /* Disable short circuit detection interrupt */ - DFSDM1_Filter0->FLTCR2 &= ~(DFSDM_FLTCR2_SCDIE); -#endif /* DFSDM2_Channel0 */ - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to get channel analog watchdog value. - * @param hdfsdm_channel DFSDM channel handle. - * @retval Channel analog watchdog value. - */ -int16_t HAL_DFSDM_ChannelGetAwdValue(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - return (int16_t) hdfsdm_channel->Instance->CHWDATAR; -} - -/** - * @brief This function allows to modify channel offset value. - * @param hdfsdm_channel DFSDM channel handle. - * @param Offset DFSDM channel offset. - * This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_ChannelModifyOffset(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - int32_t Offset) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_CHANNEL_ALL_INSTANCE(hdfsdm_channel->Instance)); - assert_param(IS_DFSDM_CHANNEL_OFFSET(Offset)); - - /* Check DFSDM channel state */ - if(hdfsdm_channel->State != HAL_DFSDM_CHANNEL_STATE_READY) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Modify channel offset */ - hdfsdm_channel->Instance->CHCFGR2 &= ~(DFSDM_CHCFGR2_OFFSET); - hdfsdm_channel->Instance->CHCFGR2 |= ((uint32_t) Offset << DFSDM_CHCFGR2_OFFSET_Pos); - } - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group3_Channel Channel state function - * @brief Channel state function - * -@verbatim - ============================================================================== - ##### Channel state function ##### - ============================================================================== - [..] This section provides function allowing to: - (+) Get channel handle state. -@endverbatim - * @{ - */ - -/** - * @brief This function allows to get the current DFSDM channel handle state. - * @param hdfsdm_channel DFSDM channel handle. - * @retval DFSDM channel state. - */ -HAL_DFSDM_Channel_StateTypeDef HAL_DFSDM_ChannelGetState(DFSDM_Channel_HandleTypeDef *hdfsdm_channel) -{ - /* Return DFSDM channel handle state */ - return hdfsdm_channel->State; -} - -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group1_Filter Filter initialization and de-initialization functions - * @brief Filter initialization and de-initialization functions - * -@verbatim - ============================================================================== - ##### Filter initialization and de-initialization functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Initialize the DFSDM filter. - (+) De-initialize the DFSDM filter. -@endverbatim - * @{ - */ - -/** - * @brief Initialize the DFSDM filter according to the specified parameters - * in the DFSDM_FilterInitTypeDef structure and initialize the associated handle. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_FilterInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Check DFSDM Channel handle */ - if(hdfsdm_filter == NULL) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(IS_DFSDM_FILTER_REG_TRIGGER(hdfsdm_filter->Init.RegularParam.Trigger)); - assert_param(IS_FUNCTIONAL_STATE(hdfsdm_filter->Init.RegularParam.FastMode)); - assert_param(IS_FUNCTIONAL_STATE(hdfsdm_filter->Init.RegularParam.DmaMode)); - assert_param(IS_DFSDM_FILTER_INJ_TRIGGER(hdfsdm_filter->Init.InjectedParam.Trigger)); - assert_param(IS_FUNCTIONAL_STATE(hdfsdm_filter->Init.InjectedParam.ScanMode)); - assert_param(IS_FUNCTIONAL_STATE(hdfsdm_filter->Init.InjectedParam.DmaMode)); - assert_param(IS_DFSDM_FILTER_SINC_ORDER(hdfsdm_filter->Init.FilterParam.SincOrder)); - assert_param(IS_DFSDM_FILTER_OVS_RATIO(hdfsdm_filter->Init.FilterParam.Oversampling)); - assert_param(IS_DFSDM_FILTER_INTEGRATOR_OVS_RATIO(hdfsdm_filter->Init.FilterParam.IntOversampling)); - - /* Check parameters compatibility */ - if((hdfsdm_filter->Instance == DFSDM1_Filter0) && - ((hdfsdm_filter->Init.RegularParam.Trigger == DFSDM_FILTER_SYNC_TRIGGER) || - (hdfsdm_filter->Init.InjectedParam.Trigger == DFSDM_FILTER_SYNC_TRIGGER))) - { - return HAL_ERROR; - } -#if defined (DFSDM2_Channel0) - if((hdfsdm_filter->Instance == DFSDM2_Filter0) && - ((hdfsdm_filter->Init.RegularParam.Trigger == DFSDM_FILTER_SYNC_TRIGGER) || - (hdfsdm_filter->Init.InjectedParam.Trigger == DFSDM_FILTER_SYNC_TRIGGER))) - { - return HAL_ERROR; - } -#endif /* DFSDM2_Channel0 */ - - /* Initialize DFSDM filter variables with default values */ - hdfsdm_filter->RegularContMode = DFSDM_CONTINUOUS_CONV_OFF; - hdfsdm_filter->InjectedChannelsNbr = 1U; - hdfsdm_filter->InjConvRemaining = 1U; - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_NONE; - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - /* Reset callback pointers to the weak predefined callbacks */ - hdfsdm_filter->AwdCallback = HAL_DFSDM_FilterAwdCallback; - hdfsdm_filter->RegConvCpltCallback = HAL_DFSDM_FilterRegConvCpltCallback; - hdfsdm_filter->RegConvHalfCpltCallback = HAL_DFSDM_FilterRegConvHalfCpltCallback; - hdfsdm_filter->InjConvCpltCallback = HAL_DFSDM_FilterInjConvCpltCallback; - hdfsdm_filter->InjConvHalfCpltCallback = HAL_DFSDM_FilterInjConvHalfCpltCallback; - hdfsdm_filter->ErrorCallback = HAL_DFSDM_FilterErrorCallback; - - /* Call MSP init function */ - if(hdfsdm_filter->MspInitCallback == NULL) - { - hdfsdm_filter->MspInitCallback = HAL_DFSDM_FilterMspInit; - } - hdfsdm_filter->MspInitCallback(hdfsdm_filter); -#else - /* Call MSP init function */ - HAL_DFSDM_FilterMspInit(hdfsdm_filter); -#endif - - /* Set regular parameters */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_RSYNC); - if(hdfsdm_filter->Init.RegularParam.FastMode == ENABLE) - { - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_FAST; - } - else - { - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_FAST); - } - - if(hdfsdm_filter->Init.RegularParam.DmaMode == ENABLE) - { - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RDMAEN; - } - else - { - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_RDMAEN); - } - - /* Set injected parameters */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JSYNC | DFSDM_FLTCR1_JEXTEN | DFSDM_FLTCR1_JEXTSEL); - if(hdfsdm_filter->Init.InjectedParam.Trigger == DFSDM_FILTER_EXT_TRIGGER) - { - assert_param(IS_DFSDM_FILTER_EXT_TRIG(hdfsdm_filter->Init.InjectedParam.ExtTrigger)); - assert_param(IS_DFSDM_FILTER_EXT_TRIG_EDGE(hdfsdm_filter->Init.InjectedParam.ExtTriggerEdge)); - hdfsdm_filter->Instance->FLTCR1 |= (hdfsdm_filter->Init.InjectedParam.ExtTrigger); - } - - if(hdfsdm_filter->Init.InjectedParam.ScanMode == ENABLE) - { - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSCAN; - } - else - { - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JSCAN); - } - - if(hdfsdm_filter->Init.InjectedParam.DmaMode == ENABLE) - { - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JDMAEN; - } - else - { - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JDMAEN); - } - - /* Set filter parameters */ - hdfsdm_filter->Instance->FLTFCR &= ~(DFSDM_FLTFCR_FORD | DFSDM_FLTFCR_FOSR | DFSDM_FLTFCR_IOSR); - hdfsdm_filter->Instance->FLTFCR |= (hdfsdm_filter->Init.FilterParam.SincOrder | - ((hdfsdm_filter->Init.FilterParam.Oversampling - 1U) << DFSDM_FLTFCR_FOSR_Pos) | - (hdfsdm_filter->Init.FilterParam.IntOversampling - 1U)); - - /* Store regular and injected triggers and injected scan mode*/ - hdfsdm_filter->RegularTrigger = hdfsdm_filter->Init.RegularParam.Trigger; - hdfsdm_filter->InjectedTrigger = hdfsdm_filter->Init.InjectedParam.Trigger; - hdfsdm_filter->ExtTriggerEdge = hdfsdm_filter->Init.InjectedParam.ExtTriggerEdge; - hdfsdm_filter->InjectedScanMode = hdfsdm_filter->Init.InjectedParam.ScanMode; - - /* Enable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; - - /* Set DFSDM filter to ready state */ - hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_READY; - - return HAL_OK; -} - -/** - * @brief De-initializes the DFSDM filter. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_FilterDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Check DFSDM filter handle */ - if(hdfsdm_filter == NULL) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Disable the DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); - - /* Call MSP deinit function */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - if(hdfsdm_filter->MspDeInitCallback == NULL) - { - hdfsdm_filter->MspDeInitCallback = HAL_DFSDM_FilterMspDeInit; - } - hdfsdm_filter->MspDeInitCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterMspDeInit(hdfsdm_filter); -#endif - - /* Set DFSDM filter in reset state */ - hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_RESET; - - return HAL_OK; -} - -/** - * @brief Initializes the DFSDM filter MSP. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -__weak void HAL_DFSDM_FilterMspInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_filter); - /* NOTE : This function should not be modified, when the function is needed, - the HAL_DFSDM_FilterMspInit could be implemented in the user file. - */ -} - -/** - * @brief De-initializes the DFSDM filter MSP. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -__weak void HAL_DFSDM_FilterMspDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_filter); - /* NOTE : This function should not be modified, when the function is needed, - the HAL_DFSDM_FilterMspDeInit could be implemented in the user file. - */ -} - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/** - * @brief Register a user DFSDM filter callback - * to be used instead of the weak predefined callback. - * @param hdfsdm_filter DFSDM filter handle. - * @param CallbackID ID of the callback to be registered. - * This parameter can be one of the following values: - * @arg @ref HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID regular conversion complete callback ID. - * @arg @ref HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID half regular conversion complete callback ID. - * @arg @ref HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID injected conversion complete callback ID. - * @arg @ref HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID half injected conversion complete callback ID. - * @arg @ref HAL_DFSDM_FILTER_ERROR_CB_ID error callback ID. - * @arg @ref HAL_DFSDM_FILTER_MSPINIT_CB_ID MSP init callback ID. - * @arg @ref HAL_DFSDM_FILTER_MSPDEINIT_CB_ID MSP de-init callback ID. - * @param pCallback pointer to the callback function. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID, - pDFSDM_Filter_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - else - { - if(HAL_DFSDM_FILTER_STATE_READY == hdfsdm_filter->State) - { - switch (CallbackID) - { - case HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID : - hdfsdm_filter->RegConvCpltCallback = pCallback; - break; - case HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID : - hdfsdm_filter->RegConvHalfCpltCallback = pCallback; - break; - case HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID : - hdfsdm_filter->InjConvCpltCallback = pCallback; - break; - case HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID : - hdfsdm_filter->InjConvHalfCpltCallback = pCallback; - break; - case HAL_DFSDM_FILTER_ERROR_CB_ID : - hdfsdm_filter->ErrorCallback = pCallback; - break; - case HAL_DFSDM_FILTER_MSPINIT_CB_ID : - hdfsdm_filter->MspInitCallback = pCallback; - break; - case HAL_DFSDM_FILTER_MSPDEINIT_CB_ID : - hdfsdm_filter->MspDeInitCallback = pCallback; - break; - default : - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(HAL_DFSDM_FILTER_STATE_RESET == hdfsdm_filter->State) - { - switch (CallbackID) - { - case HAL_DFSDM_FILTER_MSPINIT_CB_ID : - hdfsdm_filter->MspInitCallback = pCallback; - break; - case HAL_DFSDM_FILTER_MSPDEINIT_CB_ID : - hdfsdm_filter->MspDeInitCallback = pCallback; - break; - default : - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - } - return status; -} - -/** - * @brief Unregister a user DFSDM filter callback. - * DFSDM filter callback is redirected to the weak predefined callback. - * @param hdfsdm_filter DFSDM filter handle. - * @param CallbackID ID of the callback to be unregistered. - * This parameter can be one of the following values: - * @arg @ref HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID regular conversion complete callback ID. - * @arg @ref HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID half regular conversion complete callback ID. - * @arg @ref HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID injected conversion complete callback ID. - * @arg @ref HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID half injected conversion complete callback ID. - * @arg @ref HAL_DFSDM_FILTER_ERROR_CB_ID error callback ID. - * @arg @ref HAL_DFSDM_FILTER_MSPINIT_CB_ID MSP init callback ID. - * @arg @ref HAL_DFSDM_FILTER_MSPDEINIT_CB_ID MSP de-init callback ID. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(HAL_DFSDM_FILTER_STATE_READY == hdfsdm_filter->State) - { - switch (CallbackID) - { - case HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID : - hdfsdm_filter->RegConvCpltCallback = HAL_DFSDM_FilterRegConvCpltCallback; - break; - case HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID : - hdfsdm_filter->RegConvHalfCpltCallback = HAL_DFSDM_FilterRegConvHalfCpltCallback; - break; - case HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID : - hdfsdm_filter->InjConvCpltCallback = HAL_DFSDM_FilterInjConvCpltCallback; - break; - case HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID : - hdfsdm_filter->InjConvHalfCpltCallback = HAL_DFSDM_FilterInjConvHalfCpltCallback; - break; - case HAL_DFSDM_FILTER_ERROR_CB_ID : - hdfsdm_filter->ErrorCallback = HAL_DFSDM_FilterErrorCallback; - break; - case HAL_DFSDM_FILTER_MSPINIT_CB_ID : - hdfsdm_filter->MspInitCallback = HAL_DFSDM_FilterMspInit; - break; - case HAL_DFSDM_FILTER_MSPDEINIT_CB_ID : - hdfsdm_filter->MspDeInitCallback = HAL_DFSDM_FilterMspDeInit; - break; - default : - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(HAL_DFSDM_FILTER_STATE_RESET == hdfsdm_filter->State) - { - switch (CallbackID) - { - case HAL_DFSDM_FILTER_MSPINIT_CB_ID : - hdfsdm_filter->MspInitCallback = HAL_DFSDM_FilterMspInit; - break; - case HAL_DFSDM_FILTER_MSPDEINIT_CB_ID : - hdfsdm_filter->MspDeInitCallback = HAL_DFSDM_FilterMspDeInit; - break; - default : - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - return status; -} - -/** - * @brief Register a user DFSDM filter analog watchdog callback - * to be used instead of the weak predefined callback. - * @param hdfsdm_filter DFSDM filter handle. - * @param pCallback pointer to the DFSDM filter analog watchdog callback function. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - pDFSDM_Filter_AwdCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - else - { - if(HAL_DFSDM_FILTER_STATE_READY == hdfsdm_filter->State) - { - hdfsdm_filter->AwdCallback = pCallback; - } - else - { - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - } - return status; -} - -/** - * @brief Unregister a user DFSDM filter analog watchdog callback. - * DFSDM filter AWD callback is redirected to the weak predefined callback. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(HAL_DFSDM_FILTER_STATE_READY == hdfsdm_filter->State) - { - hdfsdm_filter->AwdCallback = HAL_DFSDM_FilterAwdCallback; - } - else - { - /* update the error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - return status; -} -#endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group2_Filter Filter control functions - * @brief Filter control functions - * -@verbatim - ============================================================================== - ##### Filter control functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Select channel and enable/disable continuous mode for regular conversion. - (+) Select channels for injected conversion. -@endverbatim - * @{ - */ - -/** - * @brief This function allows to select channel and to enable/disable - * continuous mode for regular conversion. - * @param hdfsdm_filter DFSDM filter handle. - * @param Channel Channel for regular conversion. - * This parameter can be a value of @ref DFSDM_Channel_Selection. - * @param ContinuousMode Enable/disable continuous mode for regular conversion. - * This parameter can be a value of @ref DFSDM_ContinuousMode. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterConfigRegChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel, - uint32_t ContinuousMode) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(IS_DFSDM_REGULAR_CHANNEL(Channel)); - assert_param(IS_DFSDM_CONTINUOUS_MODE(ContinuousMode)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_RESET) && - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_ERROR)) - { - /* Configure channel and continuous mode for regular conversion */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_RCH | DFSDM_FLTCR1_RCONT); - if(ContinuousMode == DFSDM_CONTINUOUS_CONV_ON) - { - hdfsdm_filter->Instance->FLTCR1 |= (uint32_t) (((Channel & DFSDM_MSB_MASK) << DFSDM_FLTCR1_MSB_RCH_OFFSET) | - DFSDM_FLTCR1_RCONT); - } - else - { - hdfsdm_filter->Instance->FLTCR1 |= (uint32_t) ((Channel & DFSDM_MSB_MASK) << DFSDM_FLTCR1_MSB_RCH_OFFSET); - } - /* Store continuous mode information */ - hdfsdm_filter->RegularContMode = ContinuousMode; - } - else - { - status = HAL_ERROR; - } - - /* Return function status */ - return status; -} - -/** - * @brief This function allows to select channels for injected conversion. - * @param hdfsdm_filter DFSDM filter handle. - * @param Channel Channels for injected conversion. - * This parameter can be a values combination of @ref DFSDM_Channel_Selection. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterConfigInjChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(IS_DFSDM_INJECTED_CHANNEL(Channel)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_RESET) && - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_ERROR)) - { - /* Configure channel for injected conversion */ - hdfsdm_filter->Instance->FLTJCHGR = (uint32_t) (Channel & DFSDM_LSB_MASK); - /* Store number of injected channels */ - hdfsdm_filter->InjectedChannelsNbr = DFSDM_GetInjChannelsNbr(Channel); - /* Update number of injected channels remaining */ - hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ - hdfsdm_filter->InjectedChannelsNbr : 1U; - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group3_Filter Filter operation functions - * @brief Filter operation functions - * -@verbatim - ============================================================================== - ##### Filter operation functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Start conversion of regular/injected channel. - (+) Poll for the end of regular/injected conversion. - (+) Stop conversion of regular/injected channel. - (+) Start conversion of regular/injected channel and enable interrupt. - (+) Call the callback functions at the end of regular/injected conversions. - (+) Stop conversion of regular/injected channel and disable interrupt. - (+) Start conversion of regular/injected channel and enable DMA transfer. - (+) Stop conversion of regular/injected channel and disable DMA transfer. - (+) Start analog watchdog and enable interrupt. - (+) Call the callback function when analog watchdog occurs. - (+) Stop analog watchdog and disable interrupt. - (+) Start extreme detector. - (+) Stop extreme detector. - (+) Get result of regular channel conversion. - (+) Get result of injected channel conversion. - (+) Get extreme detector maximum and minimum values. - (+) Get conversion time. - (+) Handle DFSDM interrupt request. -@endverbatim - * @{ - */ - -/** - * @brief This function allows to start regular conversion in polling mode. - * @note This function should be called only when DFSDM filter instance is - * in idle state or if injected conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ)) - { - /* Start regular conversion */ - DFSDM_RegConvStart(hdfsdm_filter); - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to poll for the end of regular conversion. - * @note This function should be called only if regular conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @param Timeout Timeout value in milliseconds. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterPollForRegConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Timeout) -{ - uint32_t tickstart; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG) && \ - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) - { - /* Return error status */ - return HAL_ERROR; - } - else - { - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Wait end of regular conversion */ - while((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_REOCF) != DFSDM_FLTISR_REOCF) - { - /* Check the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if(((HAL_GetTick()-tickstart) > Timeout) || (Timeout == 0U)) - { - /* Return timeout status */ - return HAL_TIMEOUT; - } - } - } - /* Check if overrun occurs */ - if((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_ROVRF) == DFSDM_FLTISR_ROVRF) - { - /* Update error code and call error callback */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_REGULAR_OVERRUN; -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->ErrorCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); -#endif - - /* Clear regular overrun flag */ - hdfsdm_filter->Instance->FLTICR = DFSDM_FLTICR_CLRROVRF; - } - /* Update DFSDM filter state only if not continuous conversion and SW trigger */ - if((hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ - (hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER)) - { - hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG) ? \ - HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_INJ; - } - /* Return function status */ - return HAL_OK; - } -} - -/** - * @brief This function allows to stop regular conversion in polling mode. - * @note This function should be called only if regular conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG) && \ - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Stop regular conversion */ - DFSDM_RegConvStop(hdfsdm_filter); - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start regular conversion in interrupt mode. - * @note This function should be called only when DFSDM filter instance is - * in idle state or if injected conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ)) - { - /* Enable interrupts for regular conversions */ - hdfsdm_filter->Instance->FLTCR2 |= (DFSDM_FLTCR2_REOCIE | DFSDM_FLTCR2_ROVRIE); - - /* Start regular conversion */ - DFSDM_RegConvStart(hdfsdm_filter); - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to stop regular conversion in interrupt mode. - * @note This function should be called only if regular conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG) && \ - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Disable interrupts for regular conversions */ - hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_REOCIE | DFSDM_FLTCR2_ROVRIE); - - /* Stop regular conversion */ - DFSDM_RegConvStop(hdfsdm_filter); - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start regular conversion in DMA mode. - * @note This function should be called only when DFSDM filter instance is - * in idle state or if injected conversion is ongoing. - * Please note that data on buffer will contain signed regular conversion - * value on 24 most significant bits and corresponding channel on 3 least - * significant bits. - * @param hdfsdm_filter DFSDM filter handle. - * @param pData The destination buffer address. - * @param Length The length of data to be transferred from DFSDM filter to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - int32_t *pData, - uint32_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check destination address and length */ - if((pData == NULL) || (Length == 0U)) - { - status = HAL_ERROR; - } - /* Check that DMA is enabled for regular conversion */ - else if((hdfsdm_filter->Instance->FLTCR1 & DFSDM_FLTCR1_RDMAEN) != DFSDM_FLTCR1_RDMAEN) - { - status = HAL_ERROR; - } - /* Check parameters compatibility */ - else if((hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) && \ - (hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ - (hdfsdm_filter->hdmaReg->Init.Mode == DMA_NORMAL) && \ - (Length != 1U)) - { - status = HAL_ERROR; - } - else if((hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) && \ - (hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ - (hdfsdm_filter->hdmaReg->Init.Mode == DMA_CIRCULAR)) - { - status = HAL_ERROR; - } - /* Check DFSDM filter state */ - else if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ)) - { - /* Set callbacks on DMA handler */ - hdfsdm_filter->hdmaReg->XferCpltCallback = DFSDM_DMARegularConvCplt; - hdfsdm_filter->hdmaReg->XferErrorCallback = DFSDM_DMAError; - hdfsdm_filter->hdmaReg->XferHalfCpltCallback = (hdfsdm_filter->hdmaReg->Init.Mode == DMA_CIRCULAR) ?\ - DFSDM_DMARegularHalfConvCplt : NULL; - - /* Start DMA in interrupt mode */ - if(HAL_DMA_Start_IT(hdfsdm_filter->hdmaReg, (uint32_t)&hdfsdm_filter->Instance->FLTRDATAR, \ - (uint32_t) pData, Length) != HAL_OK) - { - /* Set DFSDM filter in error state */ - hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; - status = HAL_ERROR; - } - else - { - /* Start regular conversion */ - DFSDM_RegConvStart(hdfsdm_filter); - } - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start regular conversion in DMA mode and to get - * only the 16 most significant bits of conversion. - * @note This function should be called only when DFSDM filter instance is - * in idle state or if injected conversion is ongoing. - * Please note that data on buffer will contain signed 16 most significant - * bits of regular conversion. - * @param hdfsdm_filter DFSDM filter handle. - * @param pData The destination buffer address. - * @param Length The length of data to be transferred from DFSDM filter to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - int16_t *pData, - uint32_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check destination address and length */ - if((pData == NULL) || (Length == 0U)) - { - status = HAL_ERROR; - } - /* Check that DMA is enabled for regular conversion */ - else if((hdfsdm_filter->Instance->FLTCR1 & DFSDM_FLTCR1_RDMAEN) != DFSDM_FLTCR1_RDMAEN) - { - status = HAL_ERROR; - } - /* Check parameters compatibility */ - else if((hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) && \ - (hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ - (hdfsdm_filter->hdmaReg->Init.Mode == DMA_NORMAL) && \ - (Length != 1U)) - { - status = HAL_ERROR; - } - else if((hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) && \ - (hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ - (hdfsdm_filter->hdmaReg->Init.Mode == DMA_CIRCULAR)) - { - status = HAL_ERROR; - } - /* Check DFSDM filter state */ - else if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ)) - { - /* Set callbacks on DMA handler */ - hdfsdm_filter->hdmaReg->XferCpltCallback = DFSDM_DMARegularConvCplt; - hdfsdm_filter->hdmaReg->XferErrorCallback = DFSDM_DMAError; - hdfsdm_filter->hdmaReg->XferHalfCpltCallback = (hdfsdm_filter->hdmaReg->Init.Mode == DMA_CIRCULAR) ?\ - DFSDM_DMARegularHalfConvCplt : NULL; - - /* Start DMA in interrupt mode */ - if(HAL_DMA_Start_IT(hdfsdm_filter->hdmaReg, (uint32_t)(&hdfsdm_filter->Instance->FLTRDATAR) + 2U, \ - (uint32_t) pData, Length) != HAL_OK) - { - /* Set DFSDM filter in error state */ - hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; - status = HAL_ERROR; - } - else - { - /* Start regular conversion */ - DFSDM_RegConvStart(hdfsdm_filter); - } - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to stop regular conversion in DMA mode. - * @note This function should be called only if regular conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG) && \ - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Stop current DMA transfer */ - if(HAL_DMA_Abort(hdfsdm_filter->hdmaReg) != HAL_OK) - { - /* Set DFSDM filter in error state */ - hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; - status = HAL_ERROR; - } - else - { - /* Stop regular conversion */ - DFSDM_RegConvStop(hdfsdm_filter); - } - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to get regular conversion value. - * @param hdfsdm_filter DFSDM filter handle. - * @param Channel Corresponding channel of regular conversion. - * @retval Regular conversion value - */ -int32_t HAL_DFSDM_FilterGetRegularValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t *Channel) -{ - uint32_t reg = 0U; - int32_t value = 0; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(Channel != NULL); - - /* Get value of data register for regular channel */ - reg = hdfsdm_filter->Instance->FLTRDATAR; - - /* Extract channel and regular conversion value */ - *Channel = (reg & DFSDM_FLTRDATAR_RDATACH); - value = ((int32_t)(reg & DFSDM_FLTRDATAR_RDATA) >> DFSDM_FLTRDATAR_RDATA_Pos); - - /* return regular conversion value */ - return value; -} - -/** - * @brief This function allows to start injected conversion in polling mode. - * @note This function should be called only when DFSDM filter instance is - * in idle state or if regular conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG)) - { - /* Start injected conversion */ - DFSDM_InjConvStart(hdfsdm_filter); - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to poll for the end of injected conversion. - * @note This function should be called only if injected conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @param Timeout Timeout value in milliseconds. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterPollForInjConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Timeout) -{ - uint32_t tickstart; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_INJ) && \ - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) - { - /* Return error status */ - return HAL_ERROR; - } - else - { - /* Get timeout */ - tickstart = HAL_GetTick(); - - /* Wait end of injected conversions */ - while((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_JEOCF) != DFSDM_FLTISR_JEOCF) - { - /* Check the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if( ((HAL_GetTick()-tickstart) > Timeout) || (Timeout == 0U)) - { - /* Return timeout status */ - return HAL_TIMEOUT; - } - } - } - /* Check if overrun occurs */ - if((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_JOVRF) == DFSDM_FLTISR_JOVRF) - { - /* Update error code and call error callback */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INJECTED_OVERRUN; -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->ErrorCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); -#endif - - /* Clear injected overrun flag */ - hdfsdm_filter->Instance->FLTICR = DFSDM_FLTICR_CLRJOVRF; - } - - /* Update remaining injected conversions */ - hdfsdm_filter->InjConvRemaining--; - if(hdfsdm_filter->InjConvRemaining == 0U) - { - /* Update DFSDM filter state only if trigger is software */ - if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) - { - hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ) ? \ - HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_REG; - } - - /* end of injected sequence, reset the value */ - hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ - hdfsdm_filter->InjectedChannelsNbr : 1U; - } - - /* Return function status */ - return HAL_OK; - } -} - -/** - * @brief This function allows to stop injected conversion in polling mode. - * @note This function should be called only if injected conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_INJ) && \ - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Stop injected conversion */ - DFSDM_InjConvStop(hdfsdm_filter); - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start injected conversion in interrupt mode. - * @note This function should be called only when DFSDM filter instance is - * in idle state or if regular conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG)) - { - /* Enable interrupts for injected conversions */ - hdfsdm_filter->Instance->FLTCR2 |= (DFSDM_FLTCR2_JEOCIE | DFSDM_FLTCR2_JOVRIE); - - /* Start injected conversion */ - DFSDM_InjConvStart(hdfsdm_filter); - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to stop injected conversion in interrupt mode. - * @note This function should be called only if injected conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_INJ) && \ - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Disable interrupts for injected conversions */ - hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_JEOCIE | DFSDM_FLTCR2_JOVRIE); - - /* Stop injected conversion */ - DFSDM_InjConvStop(hdfsdm_filter); - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start injected conversion in DMA mode. - * @note This function should be called only when DFSDM filter instance is - * in idle state or if regular conversion is ongoing. - * Please note that data on buffer will contain signed injected conversion - * value on 24 most significant bits and corresponding channel on 3 least - * significant bits. - * @param hdfsdm_filter DFSDM filter handle. - * @param pData The destination buffer address. - * @param Length The length of data to be transferred from DFSDM filter to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - int32_t *pData, - uint32_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check destination address and length */ - if((pData == NULL) || (Length == 0U)) - { - status = HAL_ERROR; - } - /* Check that DMA is enabled for injected conversion */ - else if((hdfsdm_filter->Instance->FLTCR1 & DFSDM_FLTCR1_JDMAEN) != DFSDM_FLTCR1_JDMAEN) - { - status = HAL_ERROR; - } - /* Check parameters compatibility */ - else if((hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) && \ - (hdfsdm_filter->hdmaInj->Init.Mode == DMA_NORMAL) && \ - (Length > hdfsdm_filter->InjConvRemaining)) - { - status = HAL_ERROR; - } - else if((hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) && \ - (hdfsdm_filter->hdmaInj->Init.Mode == DMA_CIRCULAR)) - { - status = HAL_ERROR; - } - /* Check DFSDM filter state */ - else if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG)) - { - /* Set callbacks on DMA handler */ - hdfsdm_filter->hdmaInj->XferCpltCallback = DFSDM_DMAInjectedConvCplt; - hdfsdm_filter->hdmaInj->XferErrorCallback = DFSDM_DMAError; - hdfsdm_filter->hdmaInj->XferHalfCpltCallback = (hdfsdm_filter->hdmaInj->Init.Mode == DMA_CIRCULAR) ?\ - DFSDM_DMAInjectedHalfConvCplt : NULL; - - /* Start DMA in interrupt mode */ - if(HAL_DMA_Start_IT(hdfsdm_filter->hdmaInj, (uint32_t)&hdfsdm_filter->Instance->FLTJDATAR, \ - (uint32_t) pData, Length) != HAL_OK) - { - /* Set DFSDM filter in error state */ - hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; - status = HAL_ERROR; - } - else - { - /* Start injected conversion */ - DFSDM_InjConvStart(hdfsdm_filter); - } - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start injected conversion in DMA mode and to get - * only the 16 most significant bits of conversion. - * @note This function should be called only when DFSDM filter instance is - * in idle state or if regular conversion is ongoing. - * Please note that data on buffer will contain signed 16 most significant - * bits of injected conversion. - * @param hdfsdm_filter DFSDM filter handle. - * @param pData The destination buffer address. - * @param Length The length of data to be transferred from DFSDM filter to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - int16_t *pData, - uint32_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check destination address and length */ - if((pData == NULL) || (Length == 0U)) - { - status = HAL_ERROR; - } - /* Check that DMA is enabled for injected conversion */ - else if((hdfsdm_filter->Instance->FLTCR1 & DFSDM_FLTCR1_JDMAEN) != DFSDM_FLTCR1_JDMAEN) - { - status = HAL_ERROR; - } - /* Check parameters compatibility */ - else if((hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) && \ - (hdfsdm_filter->hdmaInj->Init.Mode == DMA_NORMAL) && \ - (Length > hdfsdm_filter->InjConvRemaining)) - { - status = HAL_ERROR; - } - else if((hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) && \ - (hdfsdm_filter->hdmaInj->Init.Mode == DMA_CIRCULAR)) - { - status = HAL_ERROR; - } - /* Check DFSDM filter state */ - else if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG)) - { - /* Set callbacks on DMA handler */ - hdfsdm_filter->hdmaInj->XferCpltCallback = DFSDM_DMAInjectedConvCplt; - hdfsdm_filter->hdmaInj->XferErrorCallback = DFSDM_DMAError; - hdfsdm_filter->hdmaInj->XferHalfCpltCallback = (hdfsdm_filter->hdmaInj->Init.Mode == DMA_CIRCULAR) ?\ - DFSDM_DMAInjectedHalfConvCplt : NULL; - - /* Start DMA in interrupt mode */ - if(HAL_DMA_Start_IT(hdfsdm_filter->hdmaInj, (uint32_t)(&hdfsdm_filter->Instance->FLTJDATAR) + 2U, \ - (uint32_t) pData, Length) != HAL_OK) - { - /* Set DFSDM filter in error state */ - hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; - status = HAL_ERROR; - } - else - { - /* Start injected conversion */ - DFSDM_InjConvStart(hdfsdm_filter); - } - } - else - { - status = HAL_ERROR; - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to stop injected conversion in DMA mode. - * @note This function should be called only if injected conversion is ongoing. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_INJ) && \ - (hdfsdm_filter->State != HAL_DFSDM_FILTER_STATE_REG_INJ)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Stop current DMA transfer */ - if(HAL_DMA_Abort(hdfsdm_filter->hdmaInj) != HAL_OK) - { - /* Set DFSDM filter in error state */ - hdfsdm_filter->State = HAL_DFSDM_FILTER_STATE_ERROR; - status = HAL_ERROR; - } - else - { - /* Stop regular conversion */ - DFSDM_InjConvStop(hdfsdm_filter); - } - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to get injected conversion value. - * @param hdfsdm_filter DFSDM filter handle. - * @param Channel Corresponding channel of injected conversion. - * @retval Injected conversion value - */ -int32_t HAL_DFSDM_FilterGetInjectedValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t *Channel) -{ - uint32_t reg = 0U; - int32_t value = 0; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(Channel != NULL); - - /* Get value of data register for injected channel */ - reg = hdfsdm_filter->Instance->FLTJDATAR; - - /* Extract channel and injected conversion value */ - *Channel = (reg & DFSDM_FLTJDATAR_JDATACH); - value = ((int32_t)(reg & DFSDM_FLTJDATAR_JDATA) >> DFSDM_FLTJDATAR_JDATA_Pos); - - /* return regular conversion value */ - return value; -} - -/** - * @brief This function allows to start filter analog watchdog in interrupt mode. - * @param hdfsdm_filter DFSDM filter handle. - * @param awdParam DFSDM filter analog watchdog parameters. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterAwdStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - DFSDM_Filter_AwdParamTypeDef *awdParam) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(IS_DFSDM_FILTER_AWD_DATA_SOURCE(awdParam->DataSource)); - assert_param(IS_DFSDM_INJECTED_CHANNEL(awdParam->Channel)); - assert_param(IS_DFSDM_FILTER_AWD_THRESHOLD(awdParam->HighThreshold)); - assert_param(IS_DFSDM_FILTER_AWD_THRESHOLD(awdParam->LowThreshold)); - assert_param(IS_DFSDM_BREAK_SIGNALS(awdParam->HighBreakSignal)); - assert_param(IS_DFSDM_BREAK_SIGNALS(awdParam->LowBreakSignal)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_RESET) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_ERROR)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Set analog watchdog data source */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_AWFSEL); - hdfsdm_filter->Instance->FLTCR1 |= awdParam->DataSource; - - /* Set thresholds and break signals */ - hdfsdm_filter->Instance->FLTAWHTR &= ~(DFSDM_FLTAWHTR_AWHT | DFSDM_FLTAWHTR_BKAWH); - hdfsdm_filter->Instance->FLTAWHTR |= (((uint32_t) awdParam->HighThreshold << DFSDM_FLTAWHTR_AWHT_Pos) | \ - awdParam->HighBreakSignal); - hdfsdm_filter->Instance->FLTAWLTR &= ~(DFSDM_FLTAWLTR_AWLT | DFSDM_FLTAWLTR_BKAWL); - hdfsdm_filter->Instance->FLTAWLTR |= (((uint32_t) awdParam->LowThreshold << DFSDM_FLTAWLTR_AWLT_Pos) | \ - awdParam->LowBreakSignal); - - /* Set channels and interrupt for analog watchdog */ - hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_AWDCH); - hdfsdm_filter->Instance->FLTCR2 |= (((awdParam->Channel & DFSDM_LSB_MASK) << DFSDM_FLTCR2_AWDCH_Pos) | \ - DFSDM_FLTCR2_AWDIE); - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to stop filter analog watchdog in interrupt mode. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterAwdStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_RESET) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_ERROR)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Reset channels for analog watchdog and deactivate interrupt */ - hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_AWDCH | DFSDM_FLTCR2_AWDIE); - - /* Clear all analog watchdog flags */ - hdfsdm_filter->Instance->FLTAWCFR = (DFSDM_FLTAWCFR_CLRAWHTF | DFSDM_FLTAWCFR_CLRAWLTF); - - /* Reset thresholds and break signals */ - hdfsdm_filter->Instance->FLTAWHTR &= ~(DFSDM_FLTAWHTR_AWHT | DFSDM_FLTAWHTR_BKAWH); - hdfsdm_filter->Instance->FLTAWLTR &= ~(DFSDM_FLTAWLTR_AWLT | DFSDM_FLTAWLTR_BKAWL); - - /* Reset analog watchdog data source */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_AWFSEL); - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to start extreme detector feature. - * @param hdfsdm_filter DFSDM filter handle. - * @param Channel Channels where extreme detector is enabled. - * This parameter can be a values combination of @ref DFSDM_Channel_Selection. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterExdStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(IS_DFSDM_INJECTED_CHANNEL(Channel)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_RESET) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_ERROR)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Set channels for extreme detector */ - hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_EXCH); - hdfsdm_filter->Instance->FLTCR2 |= ((Channel & DFSDM_LSB_MASK) << DFSDM_FLTCR2_EXCH_Pos); - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to stop extreme detector feature. - * @param hdfsdm_filter DFSDM filter handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DFSDM_FilterExdStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - HAL_StatusTypeDef status = HAL_OK; - __IO uint32_t reg1; - __IO uint32_t reg2; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Check DFSDM filter state */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_RESET) || \ - (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_ERROR)) - { - /* Return error status */ - status = HAL_ERROR; - } - else - { - /* Reset channels for extreme detector */ - hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_EXCH); - - /* Clear extreme detector values */ - reg1 = hdfsdm_filter->Instance->FLTEXMAX; - reg2 = hdfsdm_filter->Instance->FLTEXMIN; - UNUSED(reg1); /* To avoid GCC warning */ - UNUSED(reg2); /* To avoid GCC warning */ - } - /* Return function status */ - return status; -} - -/** - * @brief This function allows to get extreme detector maximum value. - * @param hdfsdm_filter DFSDM filter handle. - * @param Channel Corresponding channel. - * @retval Extreme detector maximum value - * This value is between Min_Data = -8388608 and Max_Data = 8388607. - */ -int32_t HAL_DFSDM_FilterGetExdMaxValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t *Channel) -{ - uint32_t reg = 0U; - int32_t value = 0; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(Channel != NULL); - - /* Get value of extreme detector maximum register */ - reg = hdfsdm_filter->Instance->FLTEXMAX; - - /* Extract channel and extreme detector maximum value */ - *Channel = (reg & DFSDM_FLTEXMAX_EXMAXCH); - value = ((int32_t)(reg & DFSDM_FLTEXMAX_EXMAX) >> DFSDM_FLTEXMAX_EXMAX_Pos); - - /* return extreme detector maximum value */ - return value; -} - -/** - * @brief This function allows to get extreme detector minimum value. - * @param hdfsdm_filter DFSDM filter handle. - * @param Channel Corresponding channel. - * @retval Extreme detector minimum value - * This value is between Min_Data = -8388608 and Max_Data = 8388607. - */ -int32_t HAL_DFSDM_FilterGetExdMinValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t *Channel) -{ - uint32_t reg = 0U; - int32_t value = 0; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - assert_param(Channel != NULL); - - /* Get value of extreme detector minimum register */ - reg = hdfsdm_filter->Instance->FLTEXMIN; - - /* Extract channel and extreme detector minimum value */ - *Channel = (reg & DFSDM_FLTEXMIN_EXMINCH); - value = ((int32_t)(reg & DFSDM_FLTEXMIN_EXMIN) >> DFSDM_FLTEXMIN_EXMIN_Pos); - - /* return extreme detector minimum value */ - return value; -} - -/** - * @brief This function allows to get conversion time value. - * @param hdfsdm_filter DFSDM filter handle. - * @retval Conversion time value - * @note To get time in second, this value has to be divided by DFSDM clock frequency. - */ -uint32_t HAL_DFSDM_FilterGetConvTimeValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - uint32_t reg = 0U; - uint32_t value = 0U; - - /* Check parameters */ - assert_param(IS_DFSDM_FILTER_ALL_INSTANCE(hdfsdm_filter->Instance)); - - /* Get value of conversion timer register */ - reg = hdfsdm_filter->Instance->FLTCNVTIMR; - - /* Extract conversion time value */ - value = ((reg & DFSDM_FLTCNVTIMR_CNVCNT) >> DFSDM_FLTCNVTIMR_CNVCNT_Pos); - - /* return extreme detector minimum value */ - return value; -} - -/** - * @brief This function handles the DFSDM interrupts. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -void HAL_DFSDM_IRQHandler(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Check if overrun occurs during regular conversion */ - if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_ROVRF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_ROVRIE) != 0U)) - { - /* Clear regular overrun flag */ - hdfsdm_filter->Instance->FLTICR = DFSDM_FLTICR_CLRROVRF; - - /* Update error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_REGULAR_OVERRUN; - - /* Call error callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->ErrorCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); -#endif - } - /* Check if overrun occurs during injected conversion */ - else if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_JOVRF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_JOVRIE) != 0U)) - { - /* Clear injected overrun flag */ - hdfsdm_filter->Instance->FLTICR = DFSDM_FLTICR_CLRJOVRF; - - /* Update error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_INJECTED_OVERRUN; - - /* Call error callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->ErrorCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); -#endif - } - /* Check if end of regular conversion */ - else if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_REOCF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_REOCIE) != 0U)) - { - /* Call regular conversion complete callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->RegConvCpltCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterRegConvCpltCallback(hdfsdm_filter); -#endif - - /* End of conversion if mode is not continuous and software trigger */ - if((hdfsdm_filter->RegularContMode == DFSDM_CONTINUOUS_CONV_OFF) && \ - (hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER)) - { - /* Disable interrupts for regular conversions */ - hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_REOCIE); - - /* Update DFSDM filter state */ - hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG) ? \ - HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_INJ; - } - } - /* Check if end of injected conversion */ - else if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_JEOCF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_JEOCIE) != 0U)) - { - /* Call injected conversion complete callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->InjConvCpltCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterInjConvCpltCallback(hdfsdm_filter); -#endif - - /* Update remaining injected conversions */ - hdfsdm_filter->InjConvRemaining--; - if(hdfsdm_filter->InjConvRemaining == 0U) - { - /* End of conversion if trigger is software */ - if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) - { - /* Disable interrupts for injected conversions */ - hdfsdm_filter->Instance->FLTCR2 &= ~(DFSDM_FLTCR2_JEOCIE); - - /* Update DFSDM filter state */ - hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ) ? \ - HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_REG; - } - /* end of injected sequence, reset the value */ - hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ - hdfsdm_filter->InjectedChannelsNbr : 1U; - } - } - /* Check if analog watchdog occurs */ - else if(((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_AWDF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_AWDIE) != 0U)) - { - uint32_t reg = 0U; - uint32_t threshold = 0U; - uint32_t channel = 0U; - - /* Get channel and threshold */ - reg = hdfsdm_filter->Instance->FLTAWSR; - threshold = ((reg & DFSDM_FLTAWSR_AWLTF) != 0U) ? DFSDM_AWD_LOW_THRESHOLD : DFSDM_AWD_HIGH_THRESHOLD; - if(threshold == DFSDM_AWD_HIGH_THRESHOLD) - { - reg = reg >> DFSDM_FLTAWSR_AWHTF_Pos; - } - while((reg & 1U) == 0U) - { - channel++; - reg = reg >> 1U; - } - /* Clear analog watchdog flag */ - hdfsdm_filter->Instance->FLTAWCFR = (threshold == DFSDM_AWD_HIGH_THRESHOLD) ? \ - (1U << (DFSDM_FLTAWSR_AWHTF_Pos + channel)) : \ - (1U << channel); - - /* Call analog watchdog callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->AwdCallback(hdfsdm_filter, channel, threshold); -#else - HAL_DFSDM_FilterAwdCallback(hdfsdm_filter, channel, threshold); -#endif - } - /* Check if clock absence occurs */ - else if((hdfsdm_filter->Instance == DFSDM1_Filter0) && \ - ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_CKABF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_CKABIE) != 0U)) - { - uint32_t reg = 0U; - uint32_t channel = 0U; - - reg = ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_CKABF) >> DFSDM_FLTISR_CKABF_Pos); - - while(channel < DFSDM1_CHANNEL_NUMBER) - { - /* Check if flag is set and corresponding channel is enabled */ - if(((reg & 1U) != 0U) && (a_dfsdm1ChannelHandle[channel] != NULL)) - { - /* Check clock absence has been enabled for this channel */ - if((a_dfsdm1ChannelHandle[channel]->Instance->CHCFGR1 & DFSDM_CHCFGR1_CKABEN) != 0U) - { - /* Clear clock absence flag */ - hdfsdm_filter->Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - - /* Call clock absence callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - a_dfsdm1ChannelHandle[channel]->CkabCallback(a_dfsdm1ChannelHandle[channel]); -#else - HAL_DFSDM_ChannelCkabCallback(a_dfsdm1ChannelHandle[channel]); -#endif - } - } - channel++; - reg = reg >> 1U; - } - } -#if defined (DFSDM2_Channel0) - /* Check if clock absence occurs */ - else if((hdfsdm_filter->Instance == DFSDM2_Filter0) && \ - ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_CKABF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_CKABIE) != 0U)) - { - uint32_t reg = 0U; - uint32_t channel = 0U; - - reg = ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_CKABF) >> DFSDM_FLTISR_CKABF_Pos); - - while(channel < DFSDM2_CHANNEL_NUMBER) - { - /* Check if flag is set and corresponding channel is enabled */ - if(((reg & 1U) != 0U) && (a_dfsdm2ChannelHandle[channel] != NULL)) - { - /* Check clock absence has been enabled for this channel */ - if((a_dfsdm2ChannelHandle[channel]->Instance->CHCFGR1 & DFSDM_CHCFGR1_CKABEN) != 0U) - { - /* Clear clock absence flag */ - hdfsdm_filter->Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRCKABF_Pos + channel)); - - /* Call clock absence callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - a_dfsdm2ChannelHandle[channel]->CkabCallback(a_dfsdm2ChannelHandle[channel]); -#else - HAL_DFSDM_ChannelCkabCallback(a_dfsdm2ChannelHandle[channel]); -#endif - } - } - channel++; - reg = reg >> 1U; - } - } -#endif /* DFSDM2_Channel0 */ - /* Check if short circuit detection occurs */ - else if((hdfsdm_filter->Instance == DFSDM1_Filter0) && \ - ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_SCDF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_SCDIE) != 0U)) - { - uint32_t reg = 0U; - uint32_t channel = 0U; - - /* Get channel */ - reg = ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_SCDF) >> DFSDM_FLTISR_SCDF_Pos); - while((reg & 1U) == 0U) - { - channel++; - reg = reg >> 1U; - } - - /* Clear short circuit detection flag */ - hdfsdm_filter->Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); - - /* Call short circuit detection callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - a_dfsdm1ChannelHandle[channel]->ScdCallback(a_dfsdm1ChannelHandle[channel]); -#else - HAL_DFSDM_ChannelScdCallback(a_dfsdm1ChannelHandle[channel]); -#endif - } -#if defined (DFSDM2_Channel0) - /* Check if short circuit detection occurs */ - else if((hdfsdm_filter->Instance == DFSDM2_Filter0) && \ - ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_SCDF) != 0U) && \ - ((hdfsdm_filter->Instance->FLTCR2 & DFSDM_FLTCR2_SCDIE) != 0U)) - { - uint32_t reg = 0U; - uint32_t channel = 0U; - - /* Get channel */ - reg = ((hdfsdm_filter->Instance->FLTISR & DFSDM_FLTISR_SCDF) >> DFSDM_FLTISR_SCDF_Pos); - while((reg & 1U) == 0U) - { - channel++; - reg = reg >> 1U; - } - - /* Clear short circuit detection flag */ - hdfsdm_filter->Instance->FLTICR = (1U << (DFSDM_FLTICR_CLRSCDF_Pos + channel)); - - /* Call short circuit detection callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - a_dfsdm2ChannelHandle[channel]->ScdCallback(a_dfsdm2ChannelHandle[channel]); -#else - HAL_DFSDM_ChannelScdCallback(a_dfsdm2ChannelHandle[channel]); -#endif - } -#endif /* DFSDM2_Channel0 */ -} - -/** - * @brief Regular conversion complete callback. - * @note In interrupt mode, user has to read conversion value in this function - * using HAL_DFSDM_FilterGetRegularValue. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -__weak void HAL_DFSDM_FilterRegConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_filter); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DFSDM_FilterRegConvCpltCallback could be implemented in the user file. - */ -} - -/** - * @brief Half regular conversion complete callback. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -__weak void HAL_DFSDM_FilterRegConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_filter); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DFSDM_FilterRegConvHalfCpltCallback could be implemented in the user file. - */ -} - -/** - * @brief Injected conversion complete callback. - * @note In interrupt mode, user has to read conversion value in this function - * using HAL_DFSDM_FilterGetInjectedValue. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -__weak void HAL_DFSDM_FilterInjConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_filter); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DFSDM_FilterInjConvCpltCallback could be implemented in the user file. - */ -} - -/** - * @brief Half injected conversion complete callback. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -__weak void HAL_DFSDM_FilterInjConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_filter); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DFSDM_FilterInjConvHalfCpltCallback could be implemented in the user file. - */ -} - -/** - * @brief Filter analog watchdog callback. - * @param hdfsdm_filter DFSDM filter handle. - * @param Channel Corresponding channel. - * @param Threshold Low or high threshold has been reached. - * @retval None - */ -__weak void HAL_DFSDM_FilterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel, uint32_t Threshold) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_filter); - UNUSED(Channel); - UNUSED(Threshold); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DFSDM_FilterAwdCallback could be implemented in the user file. - */ -} - -/** - * @brief Error callback. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -__weak void HAL_DFSDM_FilterErrorCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdfsdm_filter); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_DFSDM_FilterErrorCallback could be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group4_Filter Filter state functions - * @brief Filter state functions - * -@verbatim - ============================================================================== - ##### Filter state functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Get the DFSDM filter state. - (+) Get the DFSDM filter error. -@endverbatim - * @{ - */ - -/** - * @brief This function allows to get the current DFSDM filter handle state. - * @param hdfsdm_filter DFSDM filter handle. - * @retval DFSDM filter state. - */ -HAL_DFSDM_Filter_StateTypeDef HAL_DFSDM_FilterGetState(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - /* Return DFSDM filter handle state */ - return hdfsdm_filter->State; -} - -/** - * @brief This function allows to get the current DFSDM filter error. - * @param hdfsdm_filter DFSDM filter handle. - * @retval DFSDM filter error code. - */ -uint32_t HAL_DFSDM_FilterGetError(DFSDM_Filter_HandleTypeDef *hdfsdm_filter) -{ - return hdfsdm_filter->ErrorCode; -} - -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group5_Filter MultiChannel operation functions - * @brief Filter state functions - * -@verbatim - ============================================================================== - ##### Filter MultiChannel operation functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Control the DFSDM Multi channel delay block -@endverbatim - * @{ - */ -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** - * @brief Select the DFSDM2 as clock source for the bitstream clock. - * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called - * before HAL_DFSDM_BitstreamClock_Start() - */ -void HAL_DFSDM_BitstreamClock_Start(void) -{ - uint32_t tmp = 0; - - tmp = SYSCFG->MCHDLYCR; - tmp = (tmp &(~SYSCFG_MCHDLYCR_BSCKSEL)); - - SYSCFG->MCHDLYCR = (tmp|SYSCFG_MCHDLYCR_BSCKSEL); -} - -/** - * @brief Stop the DFSDM2 as clock source for the bitstream clock. - * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called - * before HAL_DFSDM_BitstreamClock_Stop() - * @retval None - */ -void HAL_DFSDM_BitstreamClock_Stop(void) -{ - uint32_t tmp = 0U; - - tmp = SYSCFG->MCHDLYCR; - tmp = (tmp &(~SYSCFG_MCHDLYCR_BSCKSEL)); - - SYSCFG->MCHDLYCR = tmp; -} - -/** - * @brief Disable Delay Clock for DFSDM1/2. - * @param MCHDLY HAL_MCHDLY_CLOCK_DFSDM2. - * HAL_MCHDLY_CLOCK_DFSDM1. - * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called - * before HAL_DFSDM_DisableDelayClock() - * @retval None - */ -void HAL_DFSDM_DisableDelayClock(uint32_t MCHDLY) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_DELAY_CLOCK(MCHDLY)); - - tmp = SYSCFG->MCHDLYCR; - if(MCHDLY == HAL_MCHDLY_CLOCK_DFSDM2) - { - tmp = tmp &(~SYSCFG_MCHDLYCR_MCHDLY2EN); - } - else - { - tmp = tmp &(~SYSCFG_MCHDLYCR_MCHDLY1EN); - } - - SYSCFG->MCHDLYCR = tmp; -} - -/** - * @brief Enable Delay Clock for DFSDM1/2. - * @param MCHDLY HAL_MCHDLY_CLOCK_DFSDM2. - * HAL_MCHDLY_CLOCK_DFSDM1. - * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called - * before HAL_DFSDM_EnableDelayClock() - * @retval None - */ -void HAL_DFSDM_EnableDelayClock(uint32_t MCHDLY) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_DELAY_CLOCK(MCHDLY)); - - tmp = SYSCFG->MCHDLYCR; - tmp = tmp & ~MCHDLY; - - SYSCFG->MCHDLYCR = (tmp|MCHDLY); -} - -/** - * @brief Select the source for CKin signals for DFSDM1/2. - * @param source DFSDM2_CKIN_PAD. - * DFSDM2_CKIN_DM. - * DFSDM1_CKIN_PAD. - * DFSDM1_CKIN_DM. - * @retval None - */ -void HAL_DFSDM_ClockIn_SourceSelection(uint32_t source) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_CLOCKIN_SELECTION(source)); - - tmp = SYSCFG->MCHDLYCR; - - if((source == HAL_DFSDM2_CKIN_PAD) || (source == HAL_DFSDM2_CKIN_DM)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CFG); - - if(source == HAL_DFSDM2_CKIN_PAD) - { - source = 0x000000U; - } - } - else - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1CFG); - } - - SYSCFG->MCHDLYCR = (source|tmp); -} - -/** - * @brief Select the source for CKOut signals for DFSDM1/2. - * @param source: DFSDM2_CKOUT_DFSDM2. - * DFSDM2_CKOUT_M27. - * DFSDM1_CKOUT_DFSDM1. - * DFSDM1_CKOUT_M27. - * @retval None - */ -void HAL_DFSDM_ClockOut_SourceSelection(uint32_t source) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_CLOCKOUT_SELECTION(source)); - - tmp = SYSCFG->MCHDLYCR; - - if((source == HAL_DFSDM2_CKOUT_DFSDM2) || (source == HAL_DFSDM2_CKOUT_M27)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CKOSEL); - - if(source == HAL_DFSDM2_CKOUT_DFSDM2) - { - source = 0x000U; - } - } - else - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1CKOSEL); - } - - SYSCFG->MCHDLYCR = (source|tmp); -} - -/** - * @brief Select the source for DataIn0 signals for DFSDM1/2. - * @param source DATAIN0_DFSDM2_PAD. - * DATAIN0_DFSDM2_DATAIN1. - * DATAIN0_DFSDM1_PAD. - * DATAIN0_DFSDM1_DATAIN1. - * @retval None - */ -void HAL_DFSDM_DataIn0_SourceSelection(uint32_t source) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_DATAIN0_SRC_SELECTION(source)); - - tmp = SYSCFG->MCHDLYCR; - - if((source == HAL_DATAIN0_DFSDM2_PAD)|| (source == HAL_DATAIN0_DFSDM2_DATAIN1)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2D0SEL); - if(source == HAL_DATAIN0_DFSDM2_PAD) - { - source = 0x00000U; - } - } - else - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1D0SEL); - } - SYSCFG->MCHDLYCR = (source|tmp); -} - -/** - * @brief Select the source for DataIn2 signals for DFSDM1/2. - * @param source DATAIN2_DFSDM2_PAD. - * DATAIN2_DFSDM2_DATAIN3. - * DATAIN2_DFSDM1_PAD. - * DATAIN2_DFSDM1_DATAIN3. - * @retval None - */ -void HAL_DFSDM_DataIn2_SourceSelection(uint32_t source) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_DATAIN2_SRC_SELECTION(source)); - - tmp = SYSCFG->MCHDLYCR; - - if((source == HAL_DATAIN2_DFSDM2_PAD)|| (source == HAL_DATAIN2_DFSDM2_DATAIN3)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2D2SEL); - if (source == HAL_DATAIN2_DFSDM2_PAD) - { - source = 0x0000U; - } - } - else - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1D2SEL); - } - SYSCFG->MCHDLYCR = (source|tmp); -} - -/** - * @brief Select the source for DataIn4 signals for DFSDM2. - * @param source DATAIN4_DFSDM2_PAD. - * DATAIN4_DFSDM2_DATAIN5 - * @retval None - */ -void HAL_DFSDM_DataIn4_SourceSelection(uint32_t source) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_DATAIN4_SRC_SELECTION(source)); - - tmp = SYSCFG->MCHDLYCR; - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2D4SEL); - - SYSCFG->MCHDLYCR = (source|tmp); -} - -/** - * @brief Select the source for DataIn6 signals for DFSDM2. - * @param source DATAIN6_DFSDM2_PAD. - * DATAIN6_DFSDM2_DATAIN7. - * @retval None - */ -void HAL_DFSDM_DataIn6_SourceSelection(uint32_t source) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_DATAIN6_SRC_SELECTION(source)); - - tmp = SYSCFG->MCHDLYCR; - - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2D6SEL); - - SYSCFG->MCHDLYCR = (source|tmp); -} - -/** - * @brief Configure the distribution of the bitstream clock gated from TIM4_OC - * for DFSDM1 or TIM3_OC for DFSDM2 - * @param source DFSDM1_CLKIN0_TIM4OC2 - * DFSDM1_CLKIN2_TIM4OC2 - * DFSDM1_CLKIN1_TIM4OC1 - * DFSDM1_CLKIN3_TIM4OC1 - * DFSDM2_CLKIN0_TIM3OC4 - * DFSDM2_CLKIN4_TIM3OC4 - * DFSDM2_CLKIN1_TIM3OC3 - * DFSDM2_CLKIN5_TIM3OC3 - * DFSDM2_CLKIN2_TIM3OC2 - * DFSDM2_CLKIN6_TIM3OC2 - * DFSDM2_CLKIN3_TIM3OC1 - * DFSDM2_CLKIN7_TIM3OC1 - * @retval None - */ -void HAL_DFSDM_BitStreamClkDistribution_Config(uint32_t source) -{ - uint32_t tmp = 0U; - - assert_param(IS_DFSDM_BITSTREM_CLK_DISTRIBUTION(source)); - - tmp = SYSCFG->MCHDLYCR; - - if ((source == HAL_DFSDM1_CLKIN0_TIM4OC2) || (source == HAL_DFSDM1_CLKIN2_TIM4OC2)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1CK02SEL); - } - else if ((source == HAL_DFSDM1_CLKIN1_TIM4OC1) || (source == HAL_DFSDM1_CLKIN3_TIM4OC1)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM1CK13SEL); - } - else if ((source == HAL_DFSDM2_CLKIN0_TIM3OC4) || (source == HAL_DFSDM2_CLKIN4_TIM3OC4)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CK04SEL); - } - else if ((source == HAL_DFSDM2_CLKIN1_TIM3OC3) || (source == HAL_DFSDM2_CLKIN5_TIM3OC3)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CK15SEL); - - }else if ((source == HAL_DFSDM2_CLKIN2_TIM3OC2) || (source == HAL_DFSDM2_CLKIN6_TIM3OC2)) - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CK26SEL); - } - else - { - tmp = (tmp & ~SYSCFG_MCHDLYCR_DFSDM2CK37SEL); - } - - if((source == HAL_DFSDM1_CLKIN0_TIM4OC2) ||(source == HAL_DFSDM1_CLKIN1_TIM4OC1)|| - (source == HAL_DFSDM2_CLKIN0_TIM3OC4) ||(source == HAL_DFSDM2_CLKIN1_TIM3OC3)|| - (source == HAL_DFSDM2_CLKIN2_TIM3OC2) ||(source == HAL_DFSDM2_CLKIN3_TIM3OC1)) - { - source = 0x0000U; - } - - SYSCFG->MCHDLYCR = (source|tmp); -} - -/** - * @brief Configure multi channel delay block: Use DFSDM2 audio clock source as input - * clock for DFSDM1 and DFSDM2 filters to Synchronize DFSDMx filters. - * Set the path of the DFSDM2 clock output (dfsdm2_ckout) to the - * DFSDM1/2 CkInx and data inputs channels by configuring following MCHDLY muxes - * or demuxes: M1, M2, M3, M4, M5, M6, M7, M8, DM1, DM2, DM3, DM4, DM5, DM6, - * M9, M10, M11, M12, M13, M14, M15, M16, M17, M18, M19, M20 based on the - * contains of the DFSDM_MultiChannelConfigTypeDef structure - * @param mchdlystruct Structure of multi channel configuration - * @retval None - * @note The SYSCFG clock marco __HAL_RCC_SYSCFG_CLK_ENABLE() must be called - * before HAL_DFSDM_ConfigMultiChannelDelay() - * @note The HAL_DFSDM_ConfigMultiChannelDelay() function clears the SYSCFG-MCHDLYCR - * register before setting the new configuration. - */ -void HAL_DFSDM_ConfigMultiChannelDelay(DFSDM_MultiChannelConfigTypeDef* mchdlystruct) -{ - uint32_t mchdlyreg = 0U; - - assert_param(IS_DFSDM_DFSDM1_CLKOUT(mchdlystruct->DFSDM1ClockOut)); - assert_param(IS_DFSDM_DFSDM2_CLKOUT(mchdlystruct->DFSDM2ClockOut)); - assert_param(IS_DFSDM_DFSDM1_CLKIN(mchdlystruct->DFSDM1ClockIn)); - assert_param(IS_DFSDM_DFSDM2_CLKIN(mchdlystruct->DFSDM2ClockIn)); - assert_param(IS_DFSDM_DFSDM1_BIT_CLK((mchdlystruct->DFSDM1BitClkDistribution))); - assert_param(IS_DFSDM_DFSDM2_BIT_CLK(mchdlystruct->DFSDM2BitClkDistribution)); - assert_param(IS_DFSDM_DFSDM1_DATA_DISTRIBUTION(mchdlystruct->DFSDM1DataDistribution)); - assert_param(IS_DFSDM_DFSDM2_DATA_DISTRIBUTION(mchdlystruct->DFSDM2DataDistribution)); - - mchdlyreg = (SYSCFG->MCHDLYCR & 0x80103U); - - SYSCFG->MCHDLYCR = (mchdlyreg |(mchdlystruct->DFSDM1ClockOut)|(mchdlystruct->DFSDM2ClockOut)| - (mchdlystruct->DFSDM1ClockIn)|(mchdlystruct->DFSDM2ClockIn)| - (mchdlystruct->DFSDM1BitClkDistribution)| (mchdlystruct->DFSDM2BitClkDistribution)| - (mchdlystruct->DFSDM1DataDistribution)| (mchdlystruct->DFSDM2DataDistribution)); - -} -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ -/** - * @} - */ -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup DFSDM_Private_Functions DFSDM Private Functions - * @{ - */ - -/** - * @brief DMA half transfer complete callback for regular conversion. - * @param hdma DMA handle. - * @retval None - */ -static void DFSDM_DMARegularHalfConvCplt(DMA_HandleTypeDef *hdma) -{ - /* Get DFSDM filter handle */ - DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; - - /* Call regular half conversion complete callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->RegConvHalfCpltCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterRegConvHalfCpltCallback(hdfsdm_filter); -#endif -} - -/** - * @brief DMA transfer complete callback for regular conversion. - * @param hdma DMA handle. - * @retval None - */ -static void DFSDM_DMARegularConvCplt(DMA_HandleTypeDef *hdma) -{ - /* Get DFSDM filter handle */ - DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; - - /* Call regular conversion complete callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->RegConvCpltCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterRegConvCpltCallback(hdfsdm_filter); -#endif -} - -/** - * @brief DMA half transfer complete callback for injected conversion. - * @param hdma DMA handle. - * @retval None - */ -static void DFSDM_DMAInjectedHalfConvCplt(DMA_HandleTypeDef *hdma) -{ - /* Get DFSDM filter handle */ - DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; - - /* Call injected half conversion complete callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->InjConvHalfCpltCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterInjConvHalfCpltCallback(hdfsdm_filter); -#endif -} - -/** - * @brief DMA transfer complete callback for injected conversion. - * @param hdma DMA handle. - * @retval None - */ -static void DFSDM_DMAInjectedConvCplt(DMA_HandleTypeDef *hdma) -{ - /* Get DFSDM filter handle */ - DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; - - /* Call injected conversion complete callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->InjConvCpltCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterInjConvCpltCallback(hdfsdm_filter); -#endif -} - -/** - * @brief DMA error callback. - * @param hdma DMA handle. - * @retval None - */ -static void DFSDM_DMAError(DMA_HandleTypeDef *hdma) -{ - /* Get DFSDM filter handle */ - DFSDM_Filter_HandleTypeDef* hdfsdm_filter = (DFSDM_Filter_HandleTypeDef*) ((DMA_HandleTypeDef*)hdma)->Parent; - - /* Update error code */ - hdfsdm_filter->ErrorCode = DFSDM_FILTER_ERROR_DMA; - - /* Call error callback */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - hdfsdm_filter->ErrorCallback(hdfsdm_filter); -#else - HAL_DFSDM_FilterErrorCallback(hdfsdm_filter); -#endif -} - -/** - * @brief This function allows to get the number of injected channels. - * @param Channels bitfield of injected channels. - * @retval Number of injected channels. - */ -static uint32_t DFSDM_GetInjChannelsNbr(uint32_t Channels) -{ - uint32_t nbChannels = 0U; - uint32_t tmp; - - /* Get the number of channels from bitfield */ - tmp = (uint32_t) (Channels & DFSDM_LSB_MASK); - while(tmp != 0U) - { - if((tmp & 1U) != 0U) - { - nbChannels++; - } - tmp = (uint32_t) (tmp >> 1U); - } - return nbChannels; -} - -/** - * @brief This function allows to get the channel number from channel instance. - * @param Instance DFSDM channel instance. - * @retval Channel number. - */ -static uint32_t DFSDM_GetChannelFromInstance(DFSDM_Channel_TypeDef* Instance) -{ - uint32_t channel; - - /* Get channel from instance */ -#if defined(DFSDM2_Channel0) - if((Instance == DFSDM1_Channel0) || (Instance == DFSDM2_Channel0)) - { - channel = 0U; - } - else if((Instance == DFSDM1_Channel1) || (Instance == DFSDM2_Channel1)) - { - channel = 1U; - } - else if((Instance == DFSDM1_Channel2) || (Instance == DFSDM2_Channel2)) - { - channel = 2U; - } - else if((Instance == DFSDM1_Channel3) || (Instance == DFSDM2_Channel3)) - { - channel = 3U; - } - else if(Instance == DFSDM2_Channel4) - { - channel = 4U; - } - else if(Instance == DFSDM2_Channel5) - { - channel = 5U; - } - else if(Instance == DFSDM2_Channel6) - { - channel = 6U; - } - else /* DFSDM2_Channel7 */ - { - channel = 7U; - } - -#else - if(Instance == DFSDM1_Channel0) - { - channel = 0U; - } - else if(Instance == DFSDM1_Channel1) - { - channel = 1U; - } - else if(Instance == DFSDM1_Channel2) - { - channel = 2U; - } - else /* DFSDM1_Channel3 */ - { - channel = 3U; - } -#endif /* defined(DFSDM2_Channel0) */ - - return channel; -} - -/** - * @brief This function allows to really start regular conversion. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -static void DFSDM_RegConvStart(DFSDM_Filter_HandleTypeDef* hdfsdm_filter) -{ - /* Check regular trigger */ - if(hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER) - { - /* Software start of regular conversion */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RSWSTART; - } - else /* synchronous trigger */ - { - /* Disable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); - - /* Set RSYNC bit in DFSDM_FLTCR1 register */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RSYNC; - - /* Enable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; - - /* If injected conversion was in progress, restart it */ - if(hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ) - { - if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) - { - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSWSTART; - } - /* Update remaining injected conversions */ - hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ - hdfsdm_filter->InjectedChannelsNbr : 1U; - } - } - /* Update DFSDM filter state */ - hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) ? \ - HAL_DFSDM_FILTER_STATE_REG : HAL_DFSDM_FILTER_STATE_REG_INJ; -} - -/** - * @brief This function allows to really stop regular conversion. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -static void DFSDM_RegConvStop(DFSDM_Filter_HandleTypeDef* hdfsdm_filter) -{ - /* Disable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); - - /* If regular trigger was synchronous, reset RSYNC bit in DFSDM_FLTCR1 register */ - if(hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SYNC_TRIGGER) - { - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_RSYNC); - } - - /* Enable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; - - /* If injected conversion was in progress, restart it */ - if(hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG_INJ) - { - if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) - { - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSWSTART; - } - /* Update remaining injected conversions */ - hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ - hdfsdm_filter->InjectedChannelsNbr : 1U; - } - - /* Update DFSDM filter state */ - hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG) ? \ - HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_INJ; -} - -/** - * @brief This function allows to really start injected conversion. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -static void DFSDM_InjConvStart(DFSDM_Filter_HandleTypeDef* hdfsdm_filter) -{ - /* Check injected trigger */ - if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SW_TRIGGER) - { - /* Software start of injected conversion */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSWSTART; - } - else /* external or synchronous trigger */ - { - /* Disable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); - - if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SYNC_TRIGGER) - { - /* Set JSYNC bit in DFSDM_FLTCR1 register */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_JSYNC; - } - else /* external trigger */ - { - /* Set JEXTEN[1:0] bits in DFSDM_FLTCR1 register */ - hdfsdm_filter->Instance->FLTCR1 |= hdfsdm_filter->ExtTriggerEdge; - } - - /* Enable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; - - /* If regular conversion was in progress, restart it */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG) && \ - (hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER)) - { - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RSWSTART; - } - } - /* Update DFSDM filter state */ - hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_READY) ? \ - HAL_DFSDM_FILTER_STATE_INJ : HAL_DFSDM_FILTER_STATE_REG_INJ; -} - -/** - * @brief This function allows to really stop injected conversion. - * @param hdfsdm_filter DFSDM filter handle. - * @retval None - */ -static void DFSDM_InjConvStop(DFSDM_Filter_HandleTypeDef* hdfsdm_filter) -{ - /* Disable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN); - - /* If injected trigger was synchronous, reset JSYNC bit in DFSDM_FLTCR1 register */ - if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_SYNC_TRIGGER) - { - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JSYNC); - } - else if(hdfsdm_filter->InjectedTrigger == DFSDM_FILTER_EXT_TRIGGER) - { - /* Reset JEXTEN[1:0] bits in DFSDM_FLTCR1 register */ - hdfsdm_filter->Instance->FLTCR1 &= ~(DFSDM_FLTCR1_JEXTEN); - } - - else - { - /* Nothing to do */ - } - /* Enable DFSDM filter */ - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_DFEN; - - /* If regular conversion was in progress, restart it */ - if((hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_REG_INJ) && \ - (hdfsdm_filter->RegularTrigger == DFSDM_FILTER_SW_TRIGGER)) - { - hdfsdm_filter->Instance->FLTCR1 |= DFSDM_FLTCR1_RSWSTART; - } - - /* Update remaining injected conversions */ - hdfsdm_filter->InjConvRemaining = (hdfsdm_filter->InjectedScanMode == ENABLE) ? \ - hdfsdm_filter->InjectedChannelsNbr : 1U; - - /* Update DFSDM filter state */ - hdfsdm_filter->State = (hdfsdm_filter->State == HAL_DFSDM_FILTER_STATE_INJ) ? \ - HAL_DFSDM_FILTER_STATE_READY : HAL_DFSDM_FILTER_STATE_REG; -} -/** - * @} - */ -/* End of private functions --------------------------------------------------*/ - -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -#endif /* HAL_DFSDM_MODULE_ENABLED */ -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c deleted file mode 100644 index 9b4f8d8c2f6271f..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c +++ /dev/null @@ -1,1305 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma.c - * @author MCD Application Team - * @brief DMA HAL module driver. - * - * This file provides firmware functions to manage the following - * functionalities of the Direct Memory Access (DMA) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral State and errors functions - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Enable and configure the peripheral to be connected to the DMA Stream - (except for internal SRAM/FLASH memories: no initialization is - necessary) please refer to Reference manual for connection between peripherals - and DMA requests. - - (#) For a given Stream, program the required configuration through the following parameters: - Transfer Direction, Source and Destination data formats, - Circular, Normal or peripheral flow control mode, Stream Priority level, - Source and Destination Increment mode, FIFO mode and its Threshold (if needed), - Burst mode for Source and/or Destination (if needed) using HAL_DMA_Init() function. - - -@- Prior to HAL_DMA_Init() the clock must be enabled for DMA through the following macros: - __HAL_RCC_DMA1_CLK_ENABLE() or __HAL_RCC_DMA2_CLK_ENABLE(). - - *** Polling mode IO operation *** - ================================= - [..] - (+) Use HAL_DMA_Start() to start DMA transfer after the configuration of Source - address and destination address and the Length of data to be transferred. - (+) Use HAL_DMA_PollForTransfer() to poll for the end of current transfer, in this - case a fixed Timeout can be configured by User depending from his application. - (+) Use HAL_DMA_Abort() function to abort the current transfer. - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Configure the DMA interrupt priority using HAL_NVIC_SetPriority() - (+) Enable the DMA IRQ handler using HAL_NVIC_EnableIRQ() - (+) Use HAL_DMA_Start_IT() to start DMA transfer after the configuration of - Source address and destination address and the Length of data to be transferred. In this - case the DMA interrupt is configured - (+) Use HAL_DMA_IRQHandler() called under DMA_IRQHandler() Interrupt subroutine - (+) At the end of data transfer HAL_DMA_IRQHandler() function is executed and user can - add his own function by customization of function pointer XferCpltCallback and - XferErrorCallback (i.e a member of DMA handle structure). - [..] - (#) Use HAL_DMA_GetState() function to return the DMA state and HAL_DMA_GetError() in case of error - detection. - - (#) Use HAL_DMA_Abort_IT() function to abort the current transfer - - -@- In Memory-to-Memory transfer mode, Circular mode is not allowed. - - -@- The FIFO is used mainly to reduce bus usage and to allow data packing/unpacking: it is - possible to set different Data Sizes for the Peripheral and the Memory (ie. you can set - Half-Word data size for the peripheral to access its data register and set Word data size - for the Memory to gain in access time. Each two half words will be packed and written in - a single access to a Word in the Memory). - - -@- When FIFO is disabled, it is not allowed to configure different Data Sizes for Source - and Destination. In this case the Peripheral Data Size will be applied to both Source - and Destination. - - *** DMA HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in DMA HAL driver. - - (+) __HAL_DMA_ENABLE: Enable the specified DMA Stream. - (+) __HAL_DMA_DISABLE: Disable the specified DMA Stream. - (+) __HAL_DMA_GET_IT_SOURCE: Check whether the specified DMA Stream interrupt has occurred or not. - - [..] - (@) You can refer to the DMA HAL driver header file for more useful macros - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup DMA DMA - * @brief DMA HAL module driver - * @{ - */ - -#ifdef HAL_DMA_MODULE_ENABLED - -/* Private types -------------------------------------------------------------*/ -typedef struct -{ - __IO uint32_t ISR; /*!< DMA interrupt status register */ - __IO uint32_t Reserved0; - __IO uint32_t IFCR; /*!< DMA interrupt flag clear register */ -} DMA_Base_Registers; - -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @addtogroup DMA_Private_Constants - * @{ - */ - #define HAL_TIMEOUT_DMA_ABORT 5U /* 5 ms */ -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup DMA_Private_Functions - * @{ - */ -static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma); - -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ -/** @addtogroup DMA_Exported_Functions - * @{ - */ - -/** @addtogroup DMA_Exported_Functions_Group1 - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] - This section provides functions allowing to initialize the DMA Stream source - and destination addresses, incrementation and data sizes, transfer direction, - circular/normal mode selection, memory-to-memory mode selection and Stream priority value. - [..] - The HAL_DMA_Init() function follows the DMA configuration procedures as described in - reference manual. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the DMA according to the specified - * parameters in the DMA_InitTypeDef and create the associated handle. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma) -{ - uint32_t tmp = 0U; - uint32_t tickstart = HAL_GetTick(); - DMA_Base_Registers *regs; - - /* Check the DMA peripheral state */ - if(hdma == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance)); - assert_param(IS_DMA_CHANNEL(hdma->Init.Channel)); - assert_param(IS_DMA_DIRECTION(hdma->Init.Direction)); - assert_param(IS_DMA_PERIPHERAL_INC_STATE(hdma->Init.PeriphInc)); - assert_param(IS_DMA_MEMORY_INC_STATE(hdma->Init.MemInc)); - assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(hdma->Init.PeriphDataAlignment)); - assert_param(IS_DMA_MEMORY_DATA_SIZE(hdma->Init.MemDataAlignment)); - assert_param(IS_DMA_MODE(hdma->Init.Mode)); - assert_param(IS_DMA_PRIORITY(hdma->Init.Priority)); - assert_param(IS_DMA_FIFO_MODE_STATE(hdma->Init.FIFOMode)); - /* Check the memory burst, peripheral burst and FIFO threshold parameters only - when FIFO mode is enabled */ - if(hdma->Init.FIFOMode != DMA_FIFOMODE_DISABLE) - { - assert_param(IS_DMA_FIFO_THRESHOLD(hdma->Init.FIFOThreshold)); - assert_param(IS_DMA_MEMORY_BURST(hdma->Init.MemBurst)); - assert_param(IS_DMA_PERIPHERAL_BURST(hdma->Init.PeriphBurst)); - } - - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Allocate lock resource */ - __HAL_UNLOCK(hdma); - - /* Disable the peripheral */ - __HAL_DMA_DISABLE(hdma); - - /* Check if the DMA Stream is effectively disabled */ - while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) - { - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) - { - /* Update error code */ - hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_TIMEOUT; - - return HAL_TIMEOUT; - } - } - - /* Get the CR register value */ - tmp = hdma->Instance->CR; - - /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC, DIR, CT and DBM bits */ - tmp &= ((uint32_t)~(DMA_SxCR_CHSEL | DMA_SxCR_MBURST | DMA_SxCR_PBURST | \ - DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \ - DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \ - DMA_SxCR_DIR | DMA_SxCR_CT | DMA_SxCR_DBM)); - - /* Prepare the DMA Stream configuration */ - tmp |= hdma->Init.Channel | hdma->Init.Direction | - hdma->Init.PeriphInc | hdma->Init.MemInc | - hdma->Init.PeriphDataAlignment | hdma->Init.MemDataAlignment | - hdma->Init.Mode | hdma->Init.Priority; - - /* the Memory burst and peripheral burst are not used when the FIFO is disabled */ - if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) - { - /* Get memory burst and peripheral burst */ - tmp |= hdma->Init.MemBurst | hdma->Init.PeriphBurst; - } - - /* Write to DMA Stream CR register */ - hdma->Instance->CR = tmp; - - /* Get the FCR register value */ - tmp = hdma->Instance->FCR; - - /* Clear Direct mode and FIFO threshold bits */ - tmp &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH); - - /* Prepare the DMA Stream FIFO configuration */ - tmp |= hdma->Init.FIFOMode; - - /* The FIFO threshold is not used when the FIFO mode is disabled */ - if(hdma->Init.FIFOMode == DMA_FIFOMODE_ENABLE) - { - /* Get the FIFO threshold */ - tmp |= hdma->Init.FIFOThreshold; - - /* Check compatibility between FIFO threshold level and size of the memory burst */ - /* for INCR4, INCR8, INCR16 bursts */ - if (hdma->Init.MemBurst != DMA_MBURST_SINGLE) - { - if (DMA_CheckFifoParam(hdma) != HAL_OK) - { - /* Update error code */ - hdma->ErrorCode = HAL_DMA_ERROR_PARAM; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - return HAL_ERROR; - } - } - } - - /* Write to DMA Stream FCR */ - hdma->Instance->FCR = tmp; - - /* Initialize StreamBaseAddress and StreamIndex parameters to be used to calculate - DMA steam Base Address needed by HAL_DMA_IRQHandler() and HAL_DMA_PollForTransfer() */ - regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); - - /* Clear all interrupt flags */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Initialize the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Initialize the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the DMA peripheral - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma) -{ - DMA_Base_Registers *regs; - - /* Check the DMA peripheral state */ - if(hdma == NULL) - { - return HAL_ERROR; - } - - /* Check the DMA peripheral state */ - if(hdma->State == HAL_DMA_STATE_BUSY) - { - /* Return error status */ - return HAL_BUSY; - } - - /* Check the parameters */ - assert_param(IS_DMA_STREAM_ALL_INSTANCE(hdma->Instance)); - - /* Disable the selected DMA Streamx */ - __HAL_DMA_DISABLE(hdma); - - /* Reset DMA Streamx control register */ - hdma->Instance->CR = 0U; - - /* Reset DMA Streamx number of data to transfer register */ - hdma->Instance->NDTR = 0U; - - /* Reset DMA Streamx peripheral address register */ - hdma->Instance->PAR = 0U; - - /* Reset DMA Streamx memory 0 address register */ - hdma->Instance->M0AR = 0U; - - /* Reset DMA Streamx memory 1 address register */ - hdma->Instance->M1AR = 0U; - - /* Reset DMA Streamx FIFO control register */ - hdma->Instance->FCR = 0x00000021U; - - /* Get DMA steam Base Address */ - regs = (DMA_Base_Registers *)DMA_CalcBaseAndBitshift(hdma); - - /* Clean all callbacks */ - hdma->XferCpltCallback = NULL; - hdma->XferHalfCpltCallback = NULL; - hdma->XferM1CpltCallback = NULL; - hdma->XferM1HalfCpltCallback = NULL; - hdma->XferErrorCallback = NULL; - hdma->XferAbortCallback = NULL; - - /* Clear all interrupt flags at correct offset within the register */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Reset the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Reset the DMA state */ - hdma->State = HAL_DMA_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hdma); - - return HAL_OK; -} - -/** - * @} - */ - -/** @addtogroup DMA_Exported_Functions_Group2 - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure the source, destination address and data length and Start DMA transfer - (+) Configure the source, destination address and data length and - Start DMA transfer with interrupt - (+) Abort DMA transfer - (+) Poll for transfer complete - (+) Handle DMA interrupt request - -@endverbatim - * @{ - */ - -/** - * @brief Starts the DMA Transfer. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Start(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_DMA_BUFFER_SIZE(DataLength)); - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Initialize the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Configure the source, destination address and the data length */ - DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); - - /* Enable the Peripheral */ - __HAL_DMA_ENABLE(hdma); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdma); - - /* Return error status */ - status = HAL_BUSY; - } - return status; -} - -/** - * @brief Start the DMA Transfer with interrupt enabled. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* calculate DMA base and stream number */ - DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; - - /* Check the parameters */ - assert_param(IS_DMA_BUFFER_SIZE(DataLength)); - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Initialize the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Configure the source, destination address and the data length */ - DMA_SetConfig(hdma, SrcAddress, DstAddress, DataLength); - - /* Clear all interrupt flags at correct offset within the register */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Enable Common interrupts*/ - hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME; - - if(hdma->XferHalfCpltCallback != NULL) - { - hdma->Instance->CR |= DMA_IT_HT; - } - - /* Enable the Peripheral */ - __HAL_DMA_ENABLE(hdma); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdma); - - /* Return error status */ - status = HAL_BUSY; - } - - return status; -} - -/** - * @brief Aborts the DMA Transfer. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * - * @note After disabling a DMA Stream, a check for wait until the DMA Stream is - * effectively disabled is added. If a Stream is disabled - * while a data transfer is ongoing, the current data will be transferred - * and the Stream will be effectively disabled only after the transfer of - * this single data is finished. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma) -{ - /* calculate DMA base and stream number */ - DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; - - uint32_t tickstart = HAL_GetTick(); - - if(hdma->State != HAL_DMA_STATE_BUSY) - { - hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - return HAL_ERROR; - } - else - { - /* Disable all the transfer interrupts */ - hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); - hdma->Instance->FCR &= ~(DMA_IT_FE); - - if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) - { - hdma->Instance->CR &= ~(DMA_IT_HT); - } - - /* Disable the stream */ - __HAL_DMA_DISABLE(hdma); - - /* Check if the DMA Stream is effectively disabled */ - while((hdma->Instance->CR & DMA_SxCR_EN) != RESET) - { - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > HAL_TIMEOUT_DMA_ABORT) - { - /* Update error code */ - hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - return HAL_TIMEOUT; - } - } - - /* Clear all interrupt flags at correct offset within the register */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Change the DMA state*/ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - } - return HAL_OK; -} - -/** - * @brief Aborts the DMA Transfer in Interrupt mode. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma) -{ - if(hdma->State != HAL_DMA_STATE_BUSY) - { - hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; - return HAL_ERROR; - } - else - { - /* Set Abort State */ - hdma->State = HAL_DMA_STATE_ABORT; - - /* Disable the stream */ - __HAL_DMA_DISABLE(hdma); - } - - return HAL_OK; -} - -/** - * @brief Polling for transfer complete. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param CompleteLevel Specifies the DMA level complete. - * @note The polling mode is kept in this version for legacy. it is recommanded to use the IT model instead. - * This model could be used for debug purpose. - * @note The HAL_DMA_PollForTransfer API cannot be used in circular and double buffering mode (automatic circular mode). - * @param Timeout Timeout duration. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t mask_cpltlevel; - uint32_t tickstart = HAL_GetTick(); - uint32_t tmpisr; - - /* calculate DMA base and stream number */ - DMA_Base_Registers *regs; - - if(HAL_DMA_STATE_BUSY != hdma->State) - { - /* No transfer ongoing */ - hdma->ErrorCode = HAL_DMA_ERROR_NO_XFER; - __HAL_UNLOCK(hdma); - return HAL_ERROR; - } - - /* Polling mode not supported in circular mode and double buffering mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) != RESET) - { - hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; - return HAL_ERROR; - } - - /* Get the level transfer complete flag */ - if(CompleteLevel == HAL_DMA_FULL_TRANSFER) - { - /* Transfer Complete flag */ - mask_cpltlevel = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; - } - else - { - /* Half Transfer Complete flag */ - mask_cpltlevel = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; - } - - regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; - tmpisr = regs->ISR; - - while(((tmpisr & mask_cpltlevel) == RESET) && ((hdma->ErrorCode & HAL_DMA_ERROR_TE) == RESET)) - { - /* Check for the Timeout (Not applicable in circular mode)*/ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - /* Update error code */ - hdma->ErrorCode = HAL_DMA_ERROR_TIMEOUT; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - return HAL_TIMEOUT; - } - } - - /* Get the ISR register value */ - tmpisr = regs->ISR; - - if((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) - { - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_TE; - - /* Clear the transfer error flag */ - regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; - } - - if((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) - { - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_FE; - - /* Clear the FIFO error flag */ - regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; - } - - if((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) - { - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_DME; - - /* Clear the Direct Mode error flag */ - regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; - } - } - - if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) - { - if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) - { - HAL_DMA_Abort(hdma); - - /* Clear the half transfer and transfer complete flags */ - regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; - - /* Change the DMA state */ - hdma->State= HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - return HAL_ERROR; - } - } - - /* Get the level transfer complete flag */ - if(CompleteLevel == HAL_DMA_FULL_TRANSFER) - { - /* Clear the half transfer and transfer complete flags */ - regs->IFCR = (DMA_FLAG_HTIF0_4 | DMA_FLAG_TCIF0_4) << hdma->StreamIndex; - - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - } - else - { - /* Clear the half transfer and transfer complete flags */ - regs->IFCR = (DMA_FLAG_HTIF0_4) << hdma->StreamIndex; - } - - return status; -} - -/** - * @brief Handles DMA interrupt request. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval None - */ -void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma) -{ - uint32_t tmpisr; - __IO uint32_t count = 0U; - uint32_t timeout = SystemCoreClock / 9600U; - - /* calculate DMA base and stream number */ - DMA_Base_Registers *regs = (DMA_Base_Registers *)hdma->StreamBaseAddress; - - tmpisr = regs->ISR; - - /* Transfer Error Interrupt management ***************************************/ - if ((tmpisr & (DMA_FLAG_TEIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TE) != RESET) - { - /* Disable the transfer error interrupt */ - hdma->Instance->CR &= ~(DMA_IT_TE); - - /* Clear the transfer error flag */ - regs->IFCR = DMA_FLAG_TEIF0_4 << hdma->StreamIndex; - - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_TE; - } - } - /* FIFO Error Interrupt management ******************************************/ - if ((tmpisr & (DMA_FLAG_FEIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_FE) != RESET) - { - /* Clear the FIFO error flag */ - regs->IFCR = DMA_FLAG_FEIF0_4 << hdma->StreamIndex; - - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_FE; - } - } - /* Direct Mode Error Interrupt management ***********************************/ - if ((tmpisr & (DMA_FLAG_DMEIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_DME) != RESET) - { - /* Clear the direct mode error flag */ - regs->IFCR = DMA_FLAG_DMEIF0_4 << hdma->StreamIndex; - - /* Update error code */ - hdma->ErrorCode |= HAL_DMA_ERROR_DME; - } - } - /* Half Transfer Complete Interrupt management ******************************/ - if ((tmpisr & (DMA_FLAG_HTIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_HT) != RESET) - { - /* Clear the half transfer complete flag */ - regs->IFCR = DMA_FLAG_HTIF0_4 << hdma->StreamIndex; - - /* Multi_Buffering mode enabled */ - if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) - { - /* Current memory buffer used is Memory 0 */ - if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) - { - if(hdma->XferHalfCpltCallback != NULL) - { - /* Half transfer callback */ - hdma->XferHalfCpltCallback(hdma); - } - } - /* Current memory buffer used is Memory 1 */ - else - { - if(hdma->XferM1HalfCpltCallback != NULL) - { - /* Half transfer callback */ - hdma->XferM1HalfCpltCallback(hdma); - } - } - } - else - { - /* Disable the half transfer interrupt if the DMA mode is not CIRCULAR */ - if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) - { - /* Disable the half transfer interrupt */ - hdma->Instance->CR &= ~(DMA_IT_HT); - } - - if(hdma->XferHalfCpltCallback != NULL) - { - /* Half transfer callback */ - hdma->XferHalfCpltCallback(hdma); - } - } - } - } - /* Transfer Complete Interrupt management ***********************************/ - if ((tmpisr & (DMA_FLAG_TCIF0_4 << hdma->StreamIndex)) != RESET) - { - if(__HAL_DMA_GET_IT_SOURCE(hdma, DMA_IT_TC) != RESET) - { - /* Clear the transfer complete flag */ - regs->IFCR = DMA_FLAG_TCIF0_4 << hdma->StreamIndex; - - if(HAL_DMA_STATE_ABORT == hdma->State) - { - /* Disable all the transfer interrupts */ - hdma->Instance->CR &= ~(DMA_IT_TC | DMA_IT_TE | DMA_IT_DME); - hdma->Instance->FCR &= ~(DMA_IT_FE); - - if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) - { - hdma->Instance->CR &= ~(DMA_IT_HT); - } - - /* Clear all interrupt flags at correct offset within the register */ - regs->IFCR = 0x3FU << hdma->StreamIndex; - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - - if(hdma->XferAbortCallback != NULL) - { - hdma->XferAbortCallback(hdma); - } - return; - } - - if(((hdma->Instance->CR) & (uint32_t)(DMA_SxCR_DBM)) != RESET) - { - /* Current memory buffer used is Memory 0 */ - if((hdma->Instance->CR & DMA_SxCR_CT) == RESET) - { - if(hdma->XferM1CpltCallback != NULL) - { - /* Transfer complete Callback for memory1 */ - hdma->XferM1CpltCallback(hdma); - } - } - /* Current memory buffer used is Memory 1 */ - else - { - if(hdma->XferCpltCallback != NULL) - { - /* Transfer complete Callback for memory0 */ - hdma->XferCpltCallback(hdma); - } - } - } - /* Disable the transfer complete interrupt if the DMA mode is not CIRCULAR */ - else - { - if((hdma->Instance->CR & DMA_SxCR_CIRC) == RESET) - { - /* Disable the transfer complete interrupt */ - hdma->Instance->CR &= ~(DMA_IT_TC); - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - } - - if(hdma->XferCpltCallback != NULL) - { - /* Transfer complete callback */ - hdma->XferCpltCallback(hdma); - } - } - } - } - - /* manage error case */ - if(hdma->ErrorCode != HAL_DMA_ERROR_NONE) - { - if((hdma->ErrorCode & HAL_DMA_ERROR_TE) != RESET) - { - hdma->State = HAL_DMA_STATE_ABORT; - - /* Disable the stream */ - __HAL_DMA_DISABLE(hdma); - - do - { - if (++count > timeout) - { - break; - } - } - while((hdma->Instance->CR & DMA_SxCR_EN) != RESET); - - /* Change the DMA state */ - hdma->State = HAL_DMA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma); - } - - if(hdma->XferErrorCallback != NULL) - { - /* Transfer error callback */ - hdma->XferErrorCallback(hdma); - } - } -} - -/** - * @brief Register callbacks - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param CallbackID User Callback identifer - * a DMA_HandleTypeDef structure as parameter. - * @param pCallback pointer to private callbacsk function which has pointer to - * a DMA_HandleTypeDef structure as parameter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma)) -{ - - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - switch (CallbackID) - { - case HAL_DMA_XFER_CPLT_CB_ID: - hdma->XferCpltCallback = pCallback; - break; - - case HAL_DMA_XFER_HALFCPLT_CB_ID: - hdma->XferHalfCpltCallback = pCallback; - break; - - case HAL_DMA_XFER_M1CPLT_CB_ID: - hdma->XferM1CpltCallback = pCallback; - break; - - case HAL_DMA_XFER_M1HALFCPLT_CB_ID: - hdma->XferM1HalfCpltCallback = pCallback; - break; - - case HAL_DMA_XFER_ERROR_CB_ID: - hdma->XferErrorCallback = pCallback; - break; - - case HAL_DMA_XFER_ABORT_CB_ID: - hdma->XferAbortCallback = pCallback; - break; - - default: - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdma); - - return status; -} - -/** - * @brief UnRegister callbacks - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param CallbackID User Callback identifer - * a HAL_DMA_CallbackIDTypeDef ENUM as parameter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - switch (CallbackID) - { - case HAL_DMA_XFER_CPLT_CB_ID: - hdma->XferCpltCallback = NULL; - break; - - case HAL_DMA_XFER_HALFCPLT_CB_ID: - hdma->XferHalfCpltCallback = NULL; - break; - - case HAL_DMA_XFER_M1CPLT_CB_ID: - hdma->XferM1CpltCallback = NULL; - break; - - case HAL_DMA_XFER_M1HALFCPLT_CB_ID: - hdma->XferM1HalfCpltCallback = NULL; - break; - - case HAL_DMA_XFER_ERROR_CB_ID: - hdma->XferErrorCallback = NULL; - break; - - case HAL_DMA_XFER_ABORT_CB_ID: - hdma->XferAbortCallback = NULL; - break; - - case HAL_DMA_XFER_ALL_CB_ID: - hdma->XferCpltCallback = NULL; - hdma->XferHalfCpltCallback = NULL; - hdma->XferM1CpltCallback = NULL; - hdma->XferM1HalfCpltCallback = NULL; - hdma->XferErrorCallback = NULL; - hdma->XferAbortCallback = NULL; - break; - - default: - status = HAL_ERROR; - break; - } - } - else - { - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdma); - - return status; -} - -/** - * @} - */ - -/** @addtogroup DMA_Exported_Functions_Group3 - * -@verbatim - =============================================================================== - ##### State and Errors functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Check the DMA state - (+) Get error code - -@endverbatim - * @{ - */ - -/** - * @brief Returns the DMA state. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL state - */ -HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma) -{ - return hdma->State; -} - -/** - * @brief Return the DMA error code - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval DMA Error Code - */ -uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma) -{ - return hdma->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup DMA_Private_Functions - * @{ - */ - -/** - * @brief Sets the DMA Transfer parameter. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -static void DMA_SetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) -{ - /* Clear DBM bit */ - hdma->Instance->CR &= (uint32_t)(~DMA_SxCR_DBM); - - /* Configure DMA Stream data length */ - hdma->Instance->NDTR = DataLength; - - /* Memory to Peripheral */ - if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH) - { - /* Configure DMA Stream destination address */ - hdma->Instance->PAR = DstAddress; - - /* Configure DMA Stream source address */ - hdma->Instance->M0AR = SrcAddress; - } - /* Peripheral to Memory */ - else - { - /* Configure DMA Stream source address */ - hdma->Instance->PAR = SrcAddress; - - /* Configure DMA Stream destination address */ - hdma->Instance->M0AR = DstAddress; - } -} - -/** - * @brief Returns the DMA Stream base address depending on stream number - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval Stream base address - */ -static uint32_t DMA_CalcBaseAndBitshift(DMA_HandleTypeDef *hdma) -{ - uint32_t stream_number = (((uint32_t)hdma->Instance & 0xFFU) - 16U) / 24U; - - /* lookup table for necessary bitshift of flags within status registers */ - static const uint8_t flagBitshiftOffset[8U] = {0U, 6U, 16U, 22U, 0U, 6U, 16U, 22U}; - hdma->StreamIndex = flagBitshiftOffset[stream_number]; - - if (stream_number > 3U) - { - /* return pointer to HISR and HIFCR */ - hdma->StreamBaseAddress = (((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)) + 4U); - } - else - { - /* return pointer to LISR and LIFCR */ - hdma->StreamBaseAddress = ((uint32_t)hdma->Instance & (uint32_t)(~0x3FFU)); - } - - return hdma->StreamBaseAddress; -} - -/** - * @brief Check compatibility between FIFO threshold level and size of the memory burst - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @retval HAL status - */ -static HAL_StatusTypeDef DMA_CheckFifoParam(DMA_HandleTypeDef *hdma) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmp = hdma->Init.FIFOThreshold; - - /* Memory Data size equal to Byte */ - if(hdma->Init.MemDataAlignment == DMA_MDATAALIGN_BYTE) - { - switch (tmp) - { - case DMA_FIFO_THRESHOLD_1QUARTERFULL: - case DMA_FIFO_THRESHOLD_3QUARTERSFULL: - if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) - { - status = HAL_ERROR; - } - break; - case DMA_FIFO_THRESHOLD_HALFFULL: - if (hdma->Init.MemBurst == DMA_MBURST_INC16) - { - status = HAL_ERROR; - } - break; - case DMA_FIFO_THRESHOLD_FULL: - break; - default: - break; - } - } - - /* Memory Data size equal to Half-Word */ - else if (hdma->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD) - { - switch (tmp) - { - case DMA_FIFO_THRESHOLD_1QUARTERFULL: - case DMA_FIFO_THRESHOLD_3QUARTERSFULL: - status = HAL_ERROR; - break; - case DMA_FIFO_THRESHOLD_HALFFULL: - if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) - { - status = HAL_ERROR; - } - break; - case DMA_FIFO_THRESHOLD_FULL: - if (hdma->Init.MemBurst == DMA_MBURST_INC16) - { - status = HAL_ERROR; - } - break; - default: - break; - } - } - - /* Memory Data size equal to Word */ - else - { - switch (tmp) - { - case DMA_FIFO_THRESHOLD_1QUARTERFULL: - case DMA_FIFO_THRESHOLD_HALFFULL: - case DMA_FIFO_THRESHOLD_3QUARTERSFULL: - status = HAL_ERROR; - break; - case DMA_FIFO_THRESHOLD_FULL: - if ((hdma->Init.MemBurst & DMA_SxCR_MBURST_1) == DMA_SxCR_MBURST_1) - { - status = HAL_ERROR; - } - break; - default: - break; - } - } - - return status; -} - -/** - * @} - */ - -#endif /* HAL_DMA_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma2d.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma2d.c deleted file mode 100644 index f3582b643d33976..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma2d.c +++ /dev/null @@ -1,2128 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma2d.c - * @author MCD Application Team - * @brief DMA2D HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the DMA2D peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Errors functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Program the required configuration through the following parameters: - the transfer mode, the output color mode and the output offset using - HAL_DMA2D_Init() function. - - (#) Program the required configuration through the following parameters: - the input color mode, the input color, the input alpha value, the alpha mode, - the red/blue swap mode, the inverted alpha mode and the input offset using - HAL_DMA2D_ConfigLayer() function for foreground or/and background layer. - - *** Polling mode IO operation *** - ================================= - [..] - (#) Configure pdata parameter (explained hereafter), destination and data length - and enable the transfer using HAL_DMA2D_Start(). - (#) Wait for end of transfer using HAL_DMA2D_PollForTransfer(), at this stage - user can specify the value of timeout according to his end application. - - *** Interrupt mode IO operation *** - =================================== - [..] - (#) Configure pdata parameter, destination and data length and enable - the transfer using HAL_DMA2D_Start_IT(). - (#) Use HAL_DMA2D_IRQHandler() called under DMA2D_IRQHandler() interrupt subroutine. - (#) At the end of data transfer HAL_DMA2D_IRQHandler() function is executed and user can - add his own function by customization of function pointer XferCpltCallback (member - of DMA2D handle structure). - (#) In case of error, the HAL_DMA2D_IRQHandler() function calls the callback - XferErrorCallback. - - -@- In Register-to-Memory transfer mode, pdata parameter is the register - color, in Memory-to-memory or Memory-to-Memory with pixel format - conversion pdata is the source address. - - -@- Configure the foreground source address, the background source address, - the destination and data length then Enable the transfer using - HAL_DMA2D_BlendingStart() in polling mode and HAL_DMA2D_BlendingStart_IT() - in interrupt mode. - - -@- HAL_DMA2D_BlendingStart() and HAL_DMA2D_BlendingStart_IT() functions - are used if the memory to memory with blending transfer mode is selected. - - (#) Optionally, configure and enable the CLUT using HAL_DMA2D_CLUTLoad() in polling - mode or HAL_DMA2D_CLUTLoad_IT() in interrupt mode. - - (#) Optionally, configure the line watermark in using the API HAL_DMA2D_ProgramLineEvent(). - - (#) Optionally, configure the dead time value in the AHB clock cycle inserted between two - consecutive accesses on the AHB master port in using the API HAL_DMA2D_ConfigDeadTime() - and enable/disable the functionality with the APIs HAL_DMA2D_EnableDeadTime() or - HAL_DMA2D_DisableDeadTime(). - - (#) The transfer can be suspended, resumed and aborted using the following - functions: HAL_DMA2D_Suspend(), HAL_DMA2D_Resume(), HAL_DMA2D_Abort(). - - (#) The CLUT loading can be suspended, resumed and aborted using the following - functions: HAL_DMA2D_CLUTLoading_Suspend(), HAL_DMA2D_CLUTLoading_Resume(), - HAL_DMA2D_CLUTLoading_Abort(). - - (#) To control the DMA2D state, use the following function: HAL_DMA2D_GetState(). - - (#) To read the DMA2D error code, use the following function: HAL_DMA2D_GetError(). - - *** DMA2D HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in DMA2D HAL driver : - - (+) __HAL_DMA2D_ENABLE: Enable the DMA2D peripheral. - (+) __HAL_DMA2D_GET_FLAG: Get the DMA2D pending flags. - (+) __HAL_DMA2D_CLEAR_FLAG: Clear the DMA2D pending flags. - (+) __HAL_DMA2D_ENABLE_IT: Enable the specified DMA2D interrupts. - (+) __HAL_DMA2D_DISABLE_IT: Disable the specified DMA2D interrupts. - (+) __HAL_DMA2D_GET_IT_SOURCE: Check whether the specified DMA2D interrupt is enabled or not. - - *** Callback registration *** - =================================== - [..] - (#) The compilation define USE_HAL_DMA2D_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use function HAL_DMA2D_RegisterCallback() to register a user callback. - - (#) Function HAL_DMA2D_RegisterCallback() allows to register following callbacks: - (+) XferCpltCallback : callback for transfer complete. - (+) XferErrorCallback : callback for transfer error. - (+) LineEventCallback : callback for line event. - (+) CLUTLoadingCpltCallback : callback for CLUT loading completion. - (+) MspInitCallback : DMA2D MspInit. - (+) MspDeInitCallback : DMA2D MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - (#) Use function HAL_DMA2D_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - HAL_DMA2D_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) XferCpltCallback : callback for transfer complete. - (+) XferErrorCallback : callback for transfer error. - (+) LineEventCallback : callback for line event. - (+) CLUTLoadingCpltCallback : callback for CLUT loading completion. - (+) MspInitCallback : DMA2D MspInit. - (+) MspDeInitCallback : DMA2D MspDeInit. - - (#) By default, after the HAL_DMA2D_Init and if the state is HAL_DMA2D_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions: - examples HAL_DMA2D_LineEventCallback(), HAL_DMA2D_CLUTLoadingCpltCallback() - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the HAL_DMA2D_Init - and HAL_DMA2D_DeInit only when these callbacks are null (not registered beforehand) - If not, MspInit or MspDeInit are not null, the HAL_DMA2D_Init and HAL_DMA2D_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - Exception as well for Transfer Completion and Transfer Error callbacks that are not defined - as weak (surcharged) functions. They must be defined by the user to be resorted to. - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_DMA2D_RegisterCallback before calling HAL_DMA2D_DeInit - or HAL_DMA2D_Init function. - - When The compilation define USE_HAL_DMA2D_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - [..] - (@) You can refer to the DMA2D HAL driver header file for more useful macros - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -#ifdef HAL_DMA2D_MODULE_ENABLED -#if defined (DMA2D) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup DMA2D DMA2D - * @brief DMA2D HAL module driver - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup DMA2D_Private_Constants DMA2D Private Constants - * @{ - */ - -/** @defgroup DMA2D_TimeOut DMA2D Time Out - * @{ - */ -#define DMA2D_TIMEOUT_ABORT (1000U) /*!< 1s */ -#define DMA2D_TIMEOUT_SUSPEND (1000U) /*!< 1s */ -/** - * @} - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup DMA2D_Private_Functions DMA2D Private Functions - * @{ - */ -static void DMA2D_SetConfig(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, - uint32_t Height); -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DMA2D_Exported_Functions DMA2D Exported Functions - * @{ - */ - -/** @defgroup DMA2D_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the DMA2D - (+) De-initialize the DMA2D - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the DMA2D according to the specified - * parameters in the DMA2D_InitTypeDef and create the associated handle. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_Init(DMA2D_HandleTypeDef *hdma2d) -{ - /* Check the DMA2D peripheral state */ - if (hdma2d == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_DMA2D_ALL_INSTANCE(hdma2d->Instance)); - assert_param(IS_DMA2D_MODE(hdma2d->Init.Mode)); - assert_param(IS_DMA2D_CMODE(hdma2d->Init.ColorMode)); - assert_param(IS_DMA2D_OFFSET(hdma2d->Init.OutputOffset)); - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) - if (hdma2d->State == HAL_DMA2D_STATE_RESET) - { - /* Reset Callback pointers in HAL_DMA2D_STATE_RESET only */ - hdma2d->LineEventCallback = HAL_DMA2D_LineEventCallback; - hdma2d->CLUTLoadingCpltCallback = HAL_DMA2D_CLUTLoadingCpltCallback; - if (hdma2d->MspInitCallback == NULL) - { - hdma2d->MspInitCallback = HAL_DMA2D_MspInit; - } - - /* Init the low level hardware */ - hdma2d->MspInitCallback(hdma2d); - } -#else - if (hdma2d->State == HAL_DMA2D_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hdma2d->Lock = HAL_UNLOCKED; - /* Init the low level hardware */ - HAL_DMA2D_MspInit(hdma2d); - } -#endif /* (USE_HAL_DMA2D_REGISTER_CALLBACKS) */ - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* DMA2D CR register configuration -------------------------------------------*/ - MODIFY_REG(hdma2d->Instance->CR, DMA2D_CR_MODE, hdma2d->Init.Mode); - - /* DMA2D OPFCCR register configuration ---------------------------------------*/ - MODIFY_REG(hdma2d->Instance->OPFCCR, DMA2D_OPFCCR_CM, hdma2d->Init.ColorMode); - - /* DMA2D OOR register configuration ------------------------------------------*/ - MODIFY_REG(hdma2d->Instance->OOR, DMA2D_OOR_LO, hdma2d->Init.OutputOffset); - - - /* Update error code */ - hdma2d->ErrorCode = HAL_DMA2D_ERROR_NONE; - - /* Initialize the DMA2D state*/ - hdma2d->State = HAL_DMA2D_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Deinitializes the DMA2D peripheral registers to their default reset - * values. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval None - */ - -HAL_StatusTypeDef HAL_DMA2D_DeInit(DMA2D_HandleTypeDef *hdma2d) -{ - - /* Check the DMA2D peripheral state */ - if (hdma2d == NULL) - { - return HAL_ERROR; - } - - /* Before aborting any DMA2D transfer or CLUT loading, check - first whether or not DMA2D clock is enabled */ - if (__HAL_RCC_DMA2D_IS_CLK_ENABLED()) - { - /* Abort DMA2D transfer if any */ - if ((hdma2d->Instance->CR & DMA2D_CR_START) == DMA2D_CR_START) - { - if (HAL_DMA2D_Abort(hdma2d) != HAL_OK) - { - /* Issue when aborting DMA2D transfer */ - return HAL_ERROR; - } - } - else - { - /* Abort background CLUT loading if any */ - if ((hdma2d->Instance->BGPFCCR & DMA2D_BGPFCCR_START) == DMA2D_BGPFCCR_START) - { - if (HAL_DMA2D_CLUTLoading_Abort(hdma2d, 0U) != HAL_OK) - { - /* Issue when aborting background CLUT loading */ - return HAL_ERROR; - } - } - else - { - /* Abort foreground CLUT loading if any */ - if ((hdma2d->Instance->FGPFCCR & DMA2D_FGPFCCR_START) == DMA2D_FGPFCCR_START) - { - if (HAL_DMA2D_CLUTLoading_Abort(hdma2d, 1U) != HAL_OK) - { - /* Issue when aborting foreground CLUT loading */ - return HAL_ERROR; - } - } - } - } - } - - /* Reset DMA2D control registers*/ - hdma2d->Instance->CR = 0U; - hdma2d->Instance->IFCR = 0x3FU; - hdma2d->Instance->FGOR = 0U; - hdma2d->Instance->BGOR = 0U; - hdma2d->Instance->FGPFCCR = 0U; - hdma2d->Instance->BGPFCCR = 0U; - hdma2d->Instance->OPFCCR = 0U; - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) - - if (hdma2d->MspDeInitCallback == NULL) - { - hdma2d->MspDeInitCallback = HAL_DMA2D_MspDeInit; - } - - /* DeInit the low level hardware */ - hdma2d->MspDeInitCallback(hdma2d); - -#else - /* Carry on with de-initialization of low level hardware */ - HAL_DMA2D_MspDeInit(hdma2d); -#endif /* (USE_HAL_DMA2D_REGISTER_CALLBACKS) */ - - /* Update error code */ - hdma2d->ErrorCode = HAL_DMA2D_ERROR_NONE; - - /* Initialize the DMA2D state*/ - hdma2d->State = HAL_DMA2D_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} - -/** - * @brief Initializes the DMA2D MSP. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval None - */ -__weak void HAL_DMA2D_MspInit(DMA2D_HandleTypeDef *hdma2d) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdma2d); - - /* NOTE : This function should not be modified; when the callback is needed, - the HAL_DMA2D_MspInit can be implemented in the user file. - */ -} - -/** - * @brief DeInitializes the DMA2D MSP. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval None - */ -__weak void HAL_DMA2D_MspDeInit(DMA2D_HandleTypeDef *hdma2d) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdma2d); - - /* NOTE : This function should not be modified; when the callback is needed, - the HAL_DMA2D_MspDeInit can be implemented in the user file. - */ -} - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User DMA2D Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hdma2d DMA2D handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_DMA2D_TRANSFERCOMPLETE_CB_ID DMA2D transfer complete Callback ID - * @arg @ref HAL_DMA2D_TRANSFERERROR_CB_ID DMA2D transfer error Callback ID - * @arg @ref HAL_DMA2D_LINEEVENT_CB_ID DMA2D line event Callback ID - * @arg @ref HAL_DMA2D_CLUTLOADINGCPLT_CB_ID DMA2D CLUT loading completion Callback ID - * @arg @ref HAL_DMA2D_MSPINIT_CB_ID DMA2D MspInit callback ID - * @arg @ref HAL_DMA2D_MSPDEINIT_CB_ID DMA2D MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @note No weak predefined callbacks are defined for HAL_DMA2D_TRANSFERCOMPLETE_CB_ID or HAL_DMA2D_TRANSFERERROR_CB_ID - * @retval status - */ -HAL_StatusTypeDef HAL_DMA2D_RegisterCallback(DMA2D_HandleTypeDef *hdma2d, HAL_DMA2D_CallbackIDTypeDef CallbackID, - pDMA2D_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hdma2d); - - if (HAL_DMA2D_STATE_READY == hdma2d->State) - { - switch (CallbackID) - { - case HAL_DMA2D_TRANSFERCOMPLETE_CB_ID : - hdma2d->XferCpltCallback = pCallback; - break; - - case HAL_DMA2D_TRANSFERERROR_CB_ID : - hdma2d->XferErrorCallback = pCallback; - break; - - case HAL_DMA2D_LINEEVENT_CB_ID : - hdma2d->LineEventCallback = pCallback; - break; - - case HAL_DMA2D_CLUTLOADINGCPLT_CB_ID : - hdma2d->CLUTLoadingCpltCallback = pCallback; - break; - - case HAL_DMA2D_MSPINIT_CB_ID : - hdma2d->MspInitCallback = pCallback; - break; - - case HAL_DMA2D_MSPDEINIT_CB_ID : - hdma2d->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_DMA2D_STATE_RESET == hdma2d->State) - { - switch (CallbackID) - { - case HAL_DMA2D_MSPINIT_CB_ID : - hdma2d->MspInitCallback = pCallback; - break; - - case HAL_DMA2D_MSPDEINIT_CB_ID : - hdma2d->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdma2d); - return status; -} - -/** - * @brief Unregister a DMA2D Callback - * DMA2D Callback is redirected to the weak (surcharged) predefined callback - * @param hdma2d DMA2D handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_DMA2D_TRANSFERCOMPLETE_CB_ID DMA2D transfer complete Callback ID - * @arg @ref HAL_DMA2D_TRANSFERERROR_CB_ID DMA2D transfer error Callback ID - * @arg @ref HAL_DMA2D_LINEEVENT_CB_ID DMA2D line event Callback ID - * @arg @ref HAL_DMA2D_CLUTLOADINGCPLT_CB_ID DMA2D CLUT loading completion Callback ID - * @arg @ref HAL_DMA2D_MSPINIT_CB_ID DMA2D MspInit callback ID - * @arg @ref HAL_DMA2D_MSPDEINIT_CB_ID DMA2D MspDeInit callback ID - * @note No weak predefined callbacks are defined for HAL_DMA2D_TRANSFERCOMPLETE_CB_ID or HAL_DMA2D_TRANSFERERROR_CB_ID - * @retval status - */ -HAL_StatusTypeDef HAL_DMA2D_UnRegisterCallback(DMA2D_HandleTypeDef *hdma2d, HAL_DMA2D_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdma2d); - - if (HAL_DMA2D_STATE_READY == hdma2d->State) - { - switch (CallbackID) - { - case HAL_DMA2D_TRANSFERCOMPLETE_CB_ID : - hdma2d->XferCpltCallback = NULL; - break; - - case HAL_DMA2D_TRANSFERERROR_CB_ID : - hdma2d->XferErrorCallback = NULL; - break; - - case HAL_DMA2D_LINEEVENT_CB_ID : - hdma2d->LineEventCallback = HAL_DMA2D_LineEventCallback; - break; - - case HAL_DMA2D_CLUTLOADINGCPLT_CB_ID : - hdma2d->CLUTLoadingCpltCallback = HAL_DMA2D_CLUTLoadingCpltCallback; - break; - - case HAL_DMA2D_MSPINIT_CB_ID : - hdma2d->MspInitCallback = HAL_DMA2D_MspInit; /* Legacy weak (surcharged) Msp Init */ - break; - - case HAL_DMA2D_MSPDEINIT_CB_ID : - hdma2d->MspDeInitCallback = HAL_DMA2D_MspDeInit; /* Legacy weak (surcharged) Msp DeInit */ - break; - - default : - /* Update the error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_DMA2D_STATE_RESET == hdma2d->State) - { - switch (CallbackID) - { - case HAL_DMA2D_MSPINIT_CB_ID : - hdma2d->MspInitCallback = HAL_DMA2D_MspInit; /* Legacy weak (surcharged) Msp Init */ - break; - - case HAL_DMA2D_MSPDEINIT_CB_ID : - hdma2d->MspDeInitCallback = HAL_DMA2D_MspDeInit; /* Legacy weak (surcharged) Msp DeInit */ - break; - - default : - /* Update the error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdma2d); - return status; -} -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - -/** - * @} - */ - - -/** @defgroup DMA2D_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure the pdata, destination address and data size then - start the DMA2D transfer. - (+) Configure the source for foreground and background, destination address - and data size then start a MultiBuffer DMA2D transfer. - (+) Configure the pdata, destination address and data size then - start the DMA2D transfer with interrupt. - (+) Configure the source for foreground and background, destination address - and data size then start a MultiBuffer DMA2D transfer with interrupt. - (+) Abort DMA2D transfer. - (+) Suspend DMA2D transfer. - (+) Resume DMA2D transfer. - (+) Enable CLUT transfer. - (+) Configure CLUT loading then start transfer in polling mode. - (+) Configure CLUT loading then start transfer in interrupt mode. - (+) Abort DMA2D CLUT loading. - (+) Suspend DMA2D CLUT loading. - (+) Resume DMA2D CLUT loading. - (+) Poll for transfer complete. - (+) handle DMA2D interrupt request. - (+) Transfer watermark callback. - (+) CLUT Transfer Complete callback. - - -@endverbatim - * @{ - */ - -/** - * @brief Start the DMA2D Transfer. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param pdata Configure the source memory Buffer address if - * Memory-to-Memory or Memory-to-Memory with pixel format - * conversion mode is selected, or configure - * the color value if Register-to-Memory mode is selected. - * @param DstAddress The destination memory Buffer address. - * @param Width The width of data to be transferred from source - * to destination (expressed in number of pixels per line). - * @param Height The height of data to be transferred from source to destination (expressed in number of lines). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_Start(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, - uint32_t Height) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LINE(Height)); - assert_param(IS_DMA2D_PIXEL(Width)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure the source, destination address and the data size */ - DMA2D_SetConfig(hdma2d, pdata, DstAddress, Width, Height); - - /* Enable the Peripheral */ - __HAL_DMA2D_ENABLE(hdma2d); - - return HAL_OK; -} - -/** - * @brief Start the DMA2D Transfer with interrupt enabled. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param pdata Configure the source memory Buffer address if - * the Memory-to-Memory or Memory-to-Memory with pixel format - * conversion mode is selected, or configure - * the color value if Register-to-Memory mode is selected. - * @param DstAddress The destination memory Buffer address. - * @param Width The width of data to be transferred from source - * to destination (expressed in number of pixels per line). - * @param Height The height of data to be transferred from source to destination (expressed in number of lines). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_Start_IT(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, - uint32_t Height) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LINE(Height)); - assert_param(IS_DMA2D_PIXEL(Width)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure the source, destination address and the data size */ - DMA2D_SetConfig(hdma2d, pdata, DstAddress, Width, Height); - - /* Enable the transfer complete, transfer error and configuration error interrupts */ - __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_TC | DMA2D_IT_TE | DMA2D_IT_CE); - - /* Enable the Peripheral */ - __HAL_DMA2D_ENABLE(hdma2d); - - return HAL_OK; -} - -/** - * @brief Start the multi-source DMA2D Transfer. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param SrcAddress1 The source memory Buffer address for the foreground layer. - * @param SrcAddress2 The source memory Buffer address for the background layer. - * @param DstAddress The destination memory Buffer address. - * @param Width The width of data to be transferred from source - * to destination (expressed in number of pixels per line). - * @param Height The height of data to be transferred from source to destination (expressed in number of lines). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_BlendingStart(DMA2D_HandleTypeDef *hdma2d, uint32_t SrcAddress1, uint32_t SrcAddress2, - uint32_t DstAddress, uint32_t Width, uint32_t Height) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LINE(Height)); - assert_param(IS_DMA2D_PIXEL(Width)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure DMA2D Stream source2 address */ - WRITE_REG(hdma2d->Instance->BGMAR, SrcAddress2); - - /* Configure the source, destination address and the data size */ - DMA2D_SetConfig(hdma2d, SrcAddress1, DstAddress, Width, Height); - - /* Enable the Peripheral */ - __HAL_DMA2D_ENABLE(hdma2d); - - return HAL_OK; -} - -/** - * @brief Start the multi-source DMA2D Transfer with interrupt enabled. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param SrcAddress1 The source memory Buffer address for the foreground layer. - * @param SrcAddress2 The source memory Buffer address for the background layer. - * @param DstAddress The destination memory Buffer address. - * @param Width The width of data to be transferred from source - * to destination (expressed in number of pixels per line). - * @param Height The height of data to be transferred from source to destination (expressed in number of lines). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_BlendingStart_IT(DMA2D_HandleTypeDef *hdma2d, uint32_t SrcAddress1, uint32_t SrcAddress2, - uint32_t DstAddress, uint32_t Width, uint32_t Height) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LINE(Height)); - assert_param(IS_DMA2D_PIXEL(Width)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure DMA2D Stream source2 address */ - WRITE_REG(hdma2d->Instance->BGMAR, SrcAddress2); - - /* Configure the source, destination address and the data size */ - DMA2D_SetConfig(hdma2d, SrcAddress1, DstAddress, Width, Height); - - /* Enable the transfer complete, transfer error and configuration error interrupts */ - __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_TC | DMA2D_IT_TE | DMA2D_IT_CE); - - /* Enable the Peripheral */ - __HAL_DMA2D_ENABLE(hdma2d); - - return HAL_OK; -} - -/** - * @brief Abort the DMA2D Transfer. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_Abort(DMA2D_HandleTypeDef *hdma2d) -{ - uint32_t tickstart; - - /* Abort the DMA2D transfer */ - /* START bit is reset to make sure not to set it again, in the event the HW clears it - between the register read and the register write by the CPU (writing 0 has no - effect on START bitvalue) */ - MODIFY_REG(hdma2d->Instance->CR, DMA2D_CR_ABORT | DMA2D_CR_START, DMA2D_CR_ABORT); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check if the DMA2D is effectively disabled */ - while ((hdma2d->Instance->CR & DMA2D_CR_START) != 0U) - { - if ((HAL_GetTick() - tickstart) > DMA2D_TIMEOUT_ABORT) - { - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; - - /* Change the DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_TIMEOUT; - } - } - - /* Disable the Transfer Complete, Transfer Error and Configuration Error interrupts */ - __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_TC | DMA2D_IT_TE | DMA2D_IT_CE); - - /* Change the DMA2D state*/ - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} - -/** - * @brief Suspend the DMA2D Transfer. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_Suspend(DMA2D_HandleTypeDef *hdma2d) -{ - uint32_t tickstart; - - /* Suspend the DMA2D transfer */ - /* START bit is reset to make sure not to set it again, in the event the HW clears it - between the register read and the register write by the CPU (writing 0 has no - effect on START bitvalue). */ - MODIFY_REG(hdma2d->Instance->CR, DMA2D_CR_SUSP | DMA2D_CR_START, DMA2D_CR_SUSP); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check if the DMA2D is effectively suspended */ - while ((hdma2d->Instance->CR & (DMA2D_CR_SUSP | DMA2D_CR_START)) == DMA2D_CR_START) - { - if ((HAL_GetTick() - tickstart) > DMA2D_TIMEOUT_SUSPEND) - { - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; - - /* Change the DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; - - return HAL_TIMEOUT; - } - } - - /* Check whether or not a transfer is actually suspended and change the DMA2D state accordingly */ - if ((hdma2d->Instance->CR & DMA2D_CR_START) != 0U) - { - hdma2d->State = HAL_DMA2D_STATE_SUSPEND; - } - else - { - /* Make sure SUSP bit is cleared since it is meaningless - when no transfer is on-going */ - CLEAR_BIT(hdma2d->Instance->CR, DMA2D_CR_SUSP); - } - - return HAL_OK; -} - -/** - * @brief Resume the DMA2D Transfer. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_Resume(DMA2D_HandleTypeDef *hdma2d) -{ - /* Check the SUSP and START bits */ - if ((hdma2d->Instance->CR & (DMA2D_CR_SUSP | DMA2D_CR_START)) == (DMA2D_CR_SUSP | DMA2D_CR_START)) - { - /* Ongoing transfer is suspended: change the DMA2D state before resuming */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - } - - /* Resume the DMA2D transfer */ - /* START bit is reset to make sure not to set it again, in the event the HW clears it - between the register read and the register write by the CPU (writing 0 has no - effect on START bitvalue). */ - CLEAR_BIT(hdma2d->Instance->CR, (DMA2D_CR_SUSP | DMA2D_CR_START)); - - return HAL_OK; -} - - -/** - * @brief Enable the DMA2D CLUT Transfer. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_EnableCLUT(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - if (LayerIdx == DMA2D_BACKGROUND_LAYER) - { - /* Enable the background CLUT loading */ - SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); - } - else - { - /* Enable the foreground CLUT loading */ - SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); - } - - return HAL_OK; -} - -/** - * @brief Start DMA2D CLUT Loading. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains - * the configuration information for the color look up table. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_CLUTStartLoad(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef *CLUTCfg, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LAYER(LayerIdx)); - assert_param(IS_DMA2D_CLUT_CM(CLUTCfg->CLUTColorMode)); - assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg->Size)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure the CLUT of the background DMA2D layer */ - if (LayerIdx == DMA2D_BACKGROUND_LAYER) - { - /* Write background CLUT memory address */ - WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg->pCLUT); - - /* Write background CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), - ((CLUTCfg->Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg->CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); - - /* Enable the CLUT loading for the background */ - SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); - } - /* Configure the CLUT of the foreground DMA2D layer */ - else - { - /* Write foreground CLUT memory address */ - WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg->pCLUT); - - /* Write foreground CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), - ((CLUTCfg->Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg->CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); - - /* Enable the CLUT loading for the foreground */ - SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); - } - - return HAL_OK; -} - -/** - * @brief Start DMA2D CLUT Loading with interrupt enabled. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains - * the configuration information for the color look up table. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_CLUTStartLoad_IT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef *CLUTCfg, - uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LAYER(LayerIdx)); - assert_param(IS_DMA2D_CLUT_CM(CLUTCfg->CLUTColorMode)); - assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg->Size)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure the CLUT of the background DMA2D layer */ - if (LayerIdx == DMA2D_BACKGROUND_LAYER) - { - /* Write background CLUT memory address */ - WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg->pCLUT); - - /* Write background CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), - ((CLUTCfg->Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg->CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); - - /* Enable the CLUT Transfer Complete, transfer Error, configuration Error and CLUT Access Error interrupts */ - __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); - - /* Enable the CLUT loading for the background */ - SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); - } - /* Configure the CLUT of the foreground DMA2D layer */ - else - { - /* Write foreground CLUT memory address */ - WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg->pCLUT); - - /* Write foreground CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), - ((CLUTCfg->Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg->CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); - - /* Enable the CLUT Transfer Complete, transfer Error, configuration Error and CLUT Access Error interrupts */ - __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); - - /* Enable the CLUT loading for the foreground */ - SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); - } - - return HAL_OK; -} - -/** - * @brief Start DMA2D CLUT Loading. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains - * the configuration information for the color look up table. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @note API obsolete and maintained for compatibility with legacy. User is - * invited to resort to HAL_DMA2D_CLUTStartLoad() instead to benefit from - * code compactness, code size and improved heap usage. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_CLUTLoad(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LAYER(LayerIdx)); - assert_param(IS_DMA2D_CLUT_CM(CLUTCfg.CLUTColorMode)); - assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg.Size)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure the CLUT of the background DMA2D layer */ - if (LayerIdx == DMA2D_BACKGROUND_LAYER) - { - /* Write background CLUT memory address */ - WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg.pCLUT); - - /* Write background CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), - ((CLUTCfg.Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); - - /* Enable the CLUT loading for the background */ - SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); - } - /* Configure the CLUT of the foreground DMA2D layer */ - else - { - /* Write foreground CLUT memory address */ - WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg.pCLUT); - - /* Write foreground CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), - ((CLUTCfg.Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); - - /* Enable the CLUT loading for the foreground */ - SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); - } - - return HAL_OK; -} - -/** - * @brief Start DMA2D CLUT Loading with interrupt enabled. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains - * the configuration information for the color look up table. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @note API obsolete and maintained for compatibility with legacy. User is - * invited to resort to HAL_DMA2D_CLUTStartLoad_IT() instead to benefit - * from code compactness, code size and improved heap usage. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_CLUTLoad_IT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LAYER(LayerIdx)); - assert_param(IS_DMA2D_CLUT_CM(CLUTCfg.CLUTColorMode)); - assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg.Size)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure the CLUT of the background DMA2D layer */ - if (LayerIdx == DMA2D_BACKGROUND_LAYER) - { - /* Write background CLUT memory address */ - WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg.pCLUT); - - /* Write background CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), - ((CLUTCfg.Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); - - /* Enable the CLUT Transfer Complete, transfer Error, configuration Error and CLUT Access Error interrupts */ - __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); - - /* Enable the CLUT loading for the background */ - SET_BIT(hdma2d->Instance->BGPFCCR, DMA2D_BGPFCCR_START); - } - /* Configure the CLUT of the foreground DMA2D layer */ - else - { - /* Write foreground CLUT memory address */ - WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg.pCLUT); - - /* Write foreground CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), - ((CLUTCfg.Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); - - /* Enable the CLUT Transfer Complete, transfer Error, configuration Error and CLUT Access Error interrupts */ - __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); - - /* Enable the CLUT loading for the foreground */ - SET_BIT(hdma2d->Instance->FGPFCCR, DMA2D_FGPFCCR_START); - } - - return HAL_OK; -} - -/** - * @brief Abort the DMA2D CLUT loading. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Abort(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) -{ - uint32_t tickstart; - const __IO uint32_t *reg = &(hdma2d->Instance->BGPFCCR); /* by default, point at background register */ - - /* Abort the CLUT loading */ - SET_BIT(hdma2d->Instance->CR, DMA2D_CR_ABORT); - - /* If foreground CLUT loading is considered, update local variables */ - if (LayerIdx == DMA2D_FOREGROUND_LAYER) - { - reg = &(hdma2d->Instance->FGPFCCR); - } - - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check if the CLUT loading is aborted */ - while ((*reg & DMA2D_BGPFCCR_START) != 0U) - { - if ((HAL_GetTick() - tickstart) > DMA2D_TIMEOUT_ABORT) - { - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; - - /* Change the DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_TIMEOUT; - } - } - - /* Disable the CLUT Transfer Complete, Transfer Error, Configuration Error and CLUT Access Error interrupts */ - __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_CTC | DMA2D_IT_TE | DMA2D_IT_CE | DMA2D_IT_CAE); - - /* Change the DMA2D state*/ - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} - -/** - * @brief Suspend the DMA2D CLUT loading. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Suspend(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) -{ - uint32_t tickstart; - uint32_t loadsuspended; - const __IO uint32_t *reg = &(hdma2d->Instance->BGPFCCR); /* by default, point at background register */ - - /* Suspend the CLUT loading */ - SET_BIT(hdma2d->Instance->CR, DMA2D_CR_SUSP); - - /* If foreground CLUT loading is considered, update local variables */ - if (LayerIdx == DMA2D_FOREGROUND_LAYER) - { - reg = &(hdma2d->Instance->FGPFCCR); - } - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check if the CLUT loading is suspended */ - /* 1st condition: Suspend Check */ - loadsuspended = ((hdma2d->Instance->CR & DMA2D_CR_SUSP) == DMA2D_CR_SUSP) ? 1UL : 0UL; - /* 2nd condition: Not Start Check */ - loadsuspended |= ((*reg & DMA2D_BGPFCCR_START) != DMA2D_BGPFCCR_START) ? 1UL : 0UL; - while (loadsuspended == 0UL) - { - if ((HAL_GetTick() - tickstart) > DMA2D_TIMEOUT_SUSPEND) - { - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; - - /* Change the DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; - - return HAL_TIMEOUT; - } - /* 1st condition: Suspend Check */ - loadsuspended = ((hdma2d->Instance->CR & DMA2D_CR_SUSP) == DMA2D_CR_SUSP) ? 1UL : 0UL; - /* 2nd condition: Not Start Check */ - loadsuspended |= ((*reg & DMA2D_BGPFCCR_START) != DMA2D_BGPFCCR_START) ? 1UL : 0UL; - } - - /* Check whether or not a transfer is actually suspended and change the DMA2D state accordingly */ - if ((*reg & DMA2D_BGPFCCR_START) != 0U) - { - hdma2d->State = HAL_DMA2D_STATE_SUSPEND; - } - else - { - /* Make sure SUSP bit is cleared since it is meaningless - when no transfer is on-going */ - CLEAR_BIT(hdma2d->Instance->CR, DMA2D_CR_SUSP); - } - - return HAL_OK; -} - -/** - * @brief Resume the DMA2D CLUT loading. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Resume(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) -{ - /* Check the SUSP and START bits for background or foreground CLUT loading */ - if (LayerIdx == DMA2D_BACKGROUND_LAYER) - { - /* Background CLUT loading suspension check */ - if ((hdma2d->Instance->CR & DMA2D_CR_SUSP) == DMA2D_CR_SUSP) - { - if ((hdma2d->Instance->BGPFCCR & DMA2D_BGPFCCR_START) == DMA2D_BGPFCCR_START) - { - /* Ongoing CLUT loading is suspended: change the DMA2D state before resuming */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - } - } - } - else - { - /* Foreground CLUT loading suspension check */ - if ((hdma2d->Instance->CR & DMA2D_CR_SUSP) == DMA2D_CR_SUSP) - { - if ((hdma2d->Instance->FGPFCCR & DMA2D_FGPFCCR_START) == DMA2D_FGPFCCR_START) - { - /* Ongoing CLUT loading is suspended: change the DMA2D state before resuming */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - } - } - } - - /* Resume the CLUT loading */ - CLEAR_BIT(hdma2d->Instance->CR, DMA2D_CR_SUSP); - - return HAL_OK; -} - - -/** - - * @brief Polling for transfer complete or CLUT loading. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_PollForTransfer(DMA2D_HandleTypeDef *hdma2d, uint32_t Timeout) -{ - uint32_t tickstart; - uint32_t layer_start; - __IO uint32_t isrflags = 0x0U; - - /* Polling for DMA2D transfer */ - if ((hdma2d->Instance->CR & DMA2D_CR_START) != 0U) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - while (__HAL_DMA2D_GET_FLAG(hdma2d, DMA2D_FLAG_TC) == 0U) - { - isrflags = READ_REG(hdma2d->Instance->ISR); - if ((isrflags & (DMA2D_FLAG_CE | DMA2D_FLAG_TE)) != 0U) - { - if ((isrflags & DMA2D_FLAG_CE) != 0U) - { - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CE; - } - if ((isrflags & DMA2D_FLAG_TE) != 0U) - { - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TE; - } - /* Clear the transfer and configuration error flags */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CE | DMA2D_FLAG_TE); - - /* Change DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_ERROR; - } - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; - - /* Change the DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; - - /* Process unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_TIMEOUT; - } - } - } - } - /* Polling for CLUT loading (foreground or background) */ - layer_start = hdma2d->Instance->FGPFCCR & DMA2D_FGPFCCR_START; - layer_start |= hdma2d->Instance->BGPFCCR & DMA2D_BGPFCCR_START; - if (layer_start != 0U) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - while (__HAL_DMA2D_GET_FLAG(hdma2d, DMA2D_FLAG_CTC) == 0U) - { - isrflags = READ_REG(hdma2d->Instance->ISR); - if ((isrflags & (DMA2D_FLAG_CAE | DMA2D_FLAG_CE | DMA2D_FLAG_TE)) != 0U) - { - if ((isrflags & DMA2D_FLAG_CAE) != 0U) - { - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CAE; - } - if ((isrflags & DMA2D_FLAG_CE) != 0U) - { - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CE; - } - if ((isrflags & DMA2D_FLAG_TE) != 0U) - { - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TE; - } - /* Clear the CLUT Access Error, Configuration Error and Transfer Error flags */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CAE | DMA2D_FLAG_CE | DMA2D_FLAG_TE); - - /* Change DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_ERROR; - } - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TIMEOUT; - - /* Change the DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_TIMEOUT; - - /* Process unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_TIMEOUT; - } - } - } - } - - /* Clear the transfer complete and CLUT loading flags */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_TC | DMA2D_FLAG_CTC); - - /* Change DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} -/** - * @brief Handle DMA2D interrupt request. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval HAL status - */ -void HAL_DMA2D_IRQHandler(DMA2D_HandleTypeDef *hdma2d) -{ - uint32_t isrflags = READ_REG(hdma2d->Instance->ISR); - uint32_t crflags = READ_REG(hdma2d->Instance->CR); - - /* Transfer Error Interrupt management ***************************************/ - if ((isrflags & DMA2D_FLAG_TE) != 0U) - { - if ((crflags & DMA2D_IT_TE) != 0U) - { - /* Disable the transfer Error interrupt */ - __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_TE); - - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_TE; - - /* Clear the transfer error flag */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_TE); - - /* Change DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - if (hdma2d->XferErrorCallback != NULL) - { - /* Transfer error Callback */ - hdma2d->XferErrorCallback(hdma2d); - } - } - } - /* Configuration Error Interrupt management **********************************/ - if ((isrflags & DMA2D_FLAG_CE) != 0U) - { - if ((crflags & DMA2D_IT_CE) != 0U) - { - /* Disable the Configuration Error interrupt */ - __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_CE); - - /* Clear the Configuration error flag */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CE); - - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CE; - - /* Change DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - if (hdma2d->XferErrorCallback != NULL) - { - /* Transfer error Callback */ - hdma2d->XferErrorCallback(hdma2d); - } - } - } - /* CLUT access Error Interrupt management ***********************************/ - if ((isrflags & DMA2D_FLAG_CAE) != 0U) - { - if ((crflags & DMA2D_IT_CAE) != 0U) - { - /* Disable the CLUT access error interrupt */ - __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_CAE); - - /* Clear the CLUT access error flag */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CAE); - - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_CAE; - - /* Change DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - if (hdma2d->XferErrorCallback != NULL) - { - /* Transfer error Callback */ - hdma2d->XferErrorCallback(hdma2d); - } - } - } - /* Transfer watermark Interrupt management **********************************/ - if ((isrflags & DMA2D_FLAG_TW) != 0U) - { - if ((crflags & DMA2D_IT_TW) != 0U) - { - /* Disable the transfer watermark interrupt */ - __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_TW); - - /* Clear the transfer watermark flag */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_TW); - - /* Transfer watermark Callback */ -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) - hdma2d->LineEventCallback(hdma2d); -#else - HAL_DMA2D_LineEventCallback(hdma2d); -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - - } - } - /* Transfer Complete Interrupt management ************************************/ - if ((isrflags & DMA2D_FLAG_TC) != 0U) - { - if ((crflags & DMA2D_IT_TC) != 0U) - { - /* Disable the transfer complete interrupt */ - __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_TC); - - /* Clear the transfer complete flag */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_TC); - - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_NONE; - - /* Change DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - if (hdma2d->XferCpltCallback != NULL) - { - /* Transfer complete Callback */ - hdma2d->XferCpltCallback(hdma2d); - } - } - } - /* CLUT Transfer Complete Interrupt management ******************************/ - if ((isrflags & DMA2D_FLAG_CTC) != 0U) - { - if ((crflags & DMA2D_IT_CTC) != 0U) - { - /* Disable the CLUT transfer complete interrupt */ - __HAL_DMA2D_DISABLE_IT(hdma2d, DMA2D_IT_CTC); - - /* Clear the CLUT transfer complete flag */ - __HAL_DMA2D_CLEAR_FLAG(hdma2d, DMA2D_FLAG_CTC); - - /* Update error code */ - hdma2d->ErrorCode |= HAL_DMA2D_ERROR_NONE; - - /* Change DMA2D state */ - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - /* CLUT Transfer complete Callback */ -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) - hdma2d->CLUTLoadingCpltCallback(hdma2d); -#else - HAL_DMA2D_CLUTLoadingCpltCallback(hdma2d); -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - } - } - -} - -/** - * @brief Transfer watermark callback. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval None - */ -__weak void HAL_DMA2D_LineEventCallback(DMA2D_HandleTypeDef *hdma2d) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdma2d); - - /* NOTE : This function should not be modified; when the callback is needed, - the HAL_DMA2D_LineEventCallback can be implemented in the user file. - */ -} - -/** - * @brief CLUT Transfer Complete callback. - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval None - */ -__weak void HAL_DMA2D_CLUTLoadingCpltCallback(DMA2D_HandleTypeDef *hdma2d) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdma2d); - - /* NOTE : This function should not be modified; when the callback is needed, - the HAL_DMA2D_CLUTLoadingCpltCallback can be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup DMA2D_Exported_Functions_Group3 Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure the DMA2D foreground or background layer parameters. - (+) Configure the DMA2D CLUT transfer. - (+) Configure the line watermark - (+) Configure the dead time value. - (+) Enable or disable the dead time value functionality. - - -@endverbatim - * @{ - */ - -/** - * @brief Configure the DMA2D Layer according to the specified - * parameters in the DMA2D_HandleTypeDef. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_ConfigLayer(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx) -{ - DMA2D_LayerCfgTypeDef *pLayerCfg; - uint32_t regMask; - uint32_t regValue; - - /* Check the parameters */ - assert_param(IS_DMA2D_LAYER(LayerIdx)); - assert_param(IS_DMA2D_OFFSET(hdma2d->LayerCfg[LayerIdx].InputOffset)); - if (hdma2d->Init.Mode != DMA2D_R2M) - { - assert_param(IS_DMA2D_INPUT_COLOR_MODE(hdma2d->LayerCfg[LayerIdx].InputColorMode)); - if (hdma2d->Init.Mode != DMA2D_M2M) - { - assert_param(IS_DMA2D_ALPHA_MODE(hdma2d->LayerCfg[LayerIdx].AlphaMode)); - } - } - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - pLayerCfg = &hdma2d->LayerCfg[LayerIdx]; - - /* Prepare the value to be written to the BGPFCCR or FGPFCCR register */ - regValue = pLayerCfg->InputColorMode | (pLayerCfg->AlphaMode << DMA2D_BGPFCCR_AM_Pos); - regMask = DMA2D_BGPFCCR_CM | DMA2D_BGPFCCR_AM | DMA2D_BGPFCCR_ALPHA; - - - if ((pLayerCfg->InputColorMode == DMA2D_INPUT_A4) || (pLayerCfg->InputColorMode == DMA2D_INPUT_A8)) - { - regValue |= (pLayerCfg->InputAlpha & DMA2D_BGPFCCR_ALPHA); - } - else - { - regValue |= (pLayerCfg->InputAlpha << DMA2D_BGPFCCR_ALPHA_Pos); - } - - /* Configure the background DMA2D layer */ - if (LayerIdx == DMA2D_BACKGROUND_LAYER) - { - /* Write DMA2D BGPFCCR register */ - MODIFY_REG(hdma2d->Instance->BGPFCCR, regMask, regValue); - - /* DMA2D BGOR register configuration -------------------------------------*/ - WRITE_REG(hdma2d->Instance->BGOR, pLayerCfg->InputOffset); - - /* DMA2D BGCOLR register configuration -------------------------------------*/ - if ((pLayerCfg->InputColorMode == DMA2D_INPUT_A4) || (pLayerCfg->InputColorMode == DMA2D_INPUT_A8)) - { - WRITE_REG(hdma2d->Instance->BGCOLR, pLayerCfg->InputAlpha & (DMA2D_BGCOLR_BLUE | DMA2D_BGCOLR_GREEN | \ - DMA2D_BGCOLR_RED)); - } - } - /* Configure the foreground DMA2D layer */ - else - { - - - /* Write DMA2D FGPFCCR register */ - MODIFY_REG(hdma2d->Instance->FGPFCCR, regMask, regValue); - - /* DMA2D FGOR register configuration -------------------------------------*/ - WRITE_REG(hdma2d->Instance->FGOR, pLayerCfg->InputOffset); - - /* DMA2D FGCOLR register configuration -------------------------------------*/ - if ((pLayerCfg->InputColorMode == DMA2D_INPUT_A4) || (pLayerCfg->InputColorMode == DMA2D_INPUT_A8)) - { - WRITE_REG(hdma2d->Instance->FGCOLR, pLayerCfg->InputAlpha & (DMA2D_FGCOLR_BLUE | DMA2D_FGCOLR_GREEN | \ - DMA2D_FGCOLR_RED)); - } - } - /* Initialize the DMA2D state*/ - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} - -/** - * @brief Configure the DMA2D CLUT Transfer. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param CLUTCfg Pointer to a DMA2D_CLUTCfgTypeDef structure that contains - * the configuration information for the color look up table. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * DMA2D_BACKGROUND_LAYER(0) / DMA2D_FOREGROUND_LAYER(1) - * @note API obsolete and maintained for compatibility with legacy. User is invited - * to resort to HAL_DMA2D_CLUTStartLoad() instead to benefit from code compactness, - * code size and improved heap usage. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_ConfigCLUT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_DMA2D_LAYER(LayerIdx)); - assert_param(IS_DMA2D_CLUT_CM(CLUTCfg.CLUTColorMode)); - assert_param(IS_DMA2D_CLUT_SIZE(CLUTCfg.Size)); - - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Configure the CLUT of the background DMA2D layer */ - if (LayerIdx == DMA2D_BACKGROUND_LAYER) - { - /* Write background CLUT memory address */ - WRITE_REG(hdma2d->Instance->BGCMAR, (uint32_t)CLUTCfg.pCLUT); - - /* Write background CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->BGPFCCR, (DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM), - ((CLUTCfg.Size << DMA2D_BGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_BGPFCCR_CCM_Pos))); - } - /* Configure the CLUT of the foreground DMA2D layer */ - else - { - /* Write foreground CLUT memory address */ - WRITE_REG(hdma2d->Instance->FGCMAR, (uint32_t)CLUTCfg.pCLUT); - - /* Write foreground CLUT size and CLUT color mode */ - MODIFY_REG(hdma2d->Instance->FGPFCCR, (DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM), - ((CLUTCfg.Size << DMA2D_FGPFCCR_CS_Pos) | (CLUTCfg.CLUTColorMode << DMA2D_FGPFCCR_CCM_Pos))); - } - - /* Set the DMA2D state to Ready*/ - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} - - -/** - * @brief Configure the line watermark. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @param Line Line Watermark configuration (maximum 16-bit long value expected). - * @note HAL_DMA2D_ProgramLineEvent() API enables the transfer watermark interrupt. - * @note The transfer watermark interrupt is disabled once it has occurred. - * @retval HAL status - */ - -HAL_StatusTypeDef HAL_DMA2D_ProgramLineEvent(DMA2D_HandleTypeDef *hdma2d, uint32_t Line) -{ - /* Check the parameters */ - if (Line > DMA2D_LWR_LW) - { - return HAL_ERROR; - } - else - { - /* Process locked */ - __HAL_LOCK(hdma2d); - - /* Change DMA2D peripheral state */ - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Sets the Line watermark configuration */ - WRITE_REG(hdma2d->Instance->LWR, Line); - - /* Enable the Line interrupt */ - __HAL_DMA2D_ENABLE_IT(hdma2d, DMA2D_IT_TW); - - /* Initialize the DMA2D state*/ - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; - } -} - -/** - * @brief Enable DMA2D dead time feature. - * @param hdma2d DMA2D handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_EnableDeadTime(DMA2D_HandleTypeDef *hdma2d) -{ - /* Process Locked */ - __HAL_LOCK(hdma2d); - - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Set DMA2D_AMTCR EN bit */ - SET_BIT(hdma2d->Instance->AMTCR, DMA2D_AMTCR_EN); - - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} - -/** - * @brief Disable DMA2D dead time feature. - * @param hdma2d DMA2D handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_DisableDeadTime(DMA2D_HandleTypeDef *hdma2d) -{ - /* Process Locked */ - __HAL_LOCK(hdma2d); - - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Clear DMA2D_AMTCR EN bit */ - CLEAR_BIT(hdma2d->Instance->AMTCR, DMA2D_AMTCR_EN); - - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} - -/** - * @brief Configure dead time. - * @note The dead time value represents the guaranteed minimum number of cycles between - * two consecutive transactions on the AHB bus. - * @param hdma2d DMA2D handle. - * @param DeadTime dead time value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMA2D_ConfigDeadTime(DMA2D_HandleTypeDef *hdma2d, uint8_t DeadTime) -{ - /* Process Locked */ - __HAL_LOCK(hdma2d); - - hdma2d->State = HAL_DMA2D_STATE_BUSY; - - /* Set DMA2D_AMTCR DT field */ - MODIFY_REG(hdma2d->Instance->AMTCR, DMA2D_AMTCR_DT, (((uint32_t) DeadTime) << DMA2D_AMTCR_DT_Pos)); - - hdma2d->State = HAL_DMA2D_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hdma2d); - - return HAL_OK; -} - -/** - * @} - */ - - -/** @defgroup DMA2D_Exported_Functions_Group4 Peripheral State and Error functions - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to: - (+) Get the DMA2D state - (+) Get the DMA2D error code - -@endverbatim - * @{ - */ - -/** - * @brief Return the DMA2D state - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the DMA2D. - * @retval HAL state - */ -HAL_DMA2D_StateTypeDef HAL_DMA2D_GetState(DMA2D_HandleTypeDef *hdma2d) -{ - return hdma2d->State; -} - -/** - * @brief Return the DMA2D error code - * @param hdma2d pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for DMA2D. - * @retval DMA2D Error Code - */ -uint32_t HAL_DMA2D_GetError(DMA2D_HandleTypeDef *hdma2d) -{ - return hdma2d->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - - -/** @defgroup DMA2D_Private_Functions DMA2D Private Functions - * @{ - */ - -/** - * @brief Set the DMA2D transfer parameters. - * @param hdma2d Pointer to a DMA2D_HandleTypeDef structure that contains - * the configuration information for the specified DMA2D. - * @param pdata The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param Width The width of data to be transferred from source to destination. - * @param Height The height of data to be transferred from source to destination. - * @retval HAL status - */ -static void DMA2D_SetConfig(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, - uint32_t Height) -{ - uint32_t tmp; - uint32_t tmp1; - uint32_t tmp2; - uint32_t tmp3; - uint32_t tmp4; - - /* Configure DMA2D data size */ - MODIFY_REG(hdma2d->Instance->NLR, (DMA2D_NLR_NL | DMA2D_NLR_PL), (Height | (Width << DMA2D_NLR_PL_Pos))); - - /* Configure DMA2D destination address */ - WRITE_REG(hdma2d->Instance->OMAR, DstAddress); - - /* Register to memory DMA2D mode selected */ - if (hdma2d->Init.Mode == DMA2D_R2M) - { - tmp1 = pdata & DMA2D_OCOLR_ALPHA_1; - tmp2 = pdata & DMA2D_OCOLR_RED_1; - tmp3 = pdata & DMA2D_OCOLR_GREEN_1; - tmp4 = pdata & DMA2D_OCOLR_BLUE_1; - - /* Prepare the value to be written to the OCOLR register according to the color mode */ - if (hdma2d->Init.ColorMode == DMA2D_OUTPUT_ARGB8888) - { - tmp = (tmp3 | tmp2 | tmp1 | tmp4); - } - else if (hdma2d->Init.ColorMode == DMA2D_OUTPUT_RGB888) - { - tmp = (tmp3 | tmp2 | tmp4); - } - else if (hdma2d->Init.ColorMode == DMA2D_OUTPUT_RGB565) - { - tmp2 = (tmp2 >> 19U); - tmp3 = (tmp3 >> 10U); - tmp4 = (tmp4 >> 3U); - tmp = ((tmp3 << 5U) | (tmp2 << 11U) | tmp4); - } - else if (hdma2d->Init.ColorMode == DMA2D_OUTPUT_ARGB1555) - { - tmp1 = (tmp1 >> 31U); - tmp2 = (tmp2 >> 19U); - tmp3 = (tmp3 >> 11U); - tmp4 = (tmp4 >> 3U); - tmp = ((tmp3 << 5U) | (tmp2 << 10U) | (tmp1 << 15U) | tmp4); - } - else /* Dhdma2d->Init.ColorMode = DMA2D_OUTPUT_ARGB4444 */ - { - tmp1 = (tmp1 >> 28U); - tmp2 = (tmp2 >> 20U); - tmp3 = (tmp3 >> 12U); - tmp4 = (tmp4 >> 4U); - tmp = ((tmp3 << 4U) | (tmp2 << 8U) | (tmp1 << 12U) | tmp4); - } - /* Write to DMA2D OCOLR register */ - WRITE_REG(hdma2d->Instance->OCOLR, tmp); - } - else /* M2M, M2M_PFC or M2M_Blending DMA2D Mode */ - { - /* Configure DMA2D source address */ - WRITE_REG(hdma2d->Instance->FGMAR, pdata); - } -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* DMA2D */ -#endif /* HAL_DMA2D_MODULE_ENABLED */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c deleted file mode 100644 index 6e073768347ad7a..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c +++ /dev/null @@ -1,315 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma_ex.c - * @author MCD Application Team - * @brief DMA Extension HAL module driver - * This file provides firmware functions to manage the following - * functionalities of the DMA Extension peripheral: - * + Extended features functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The DMA Extension HAL driver can be used as follows: - (#) Start a multi buffer transfer using the HAL_DMA_MultiBufferStart() function - for polling mode or HAL_DMA_MultiBufferStart_IT() for interrupt mode. - - -@- In Memory-to-Memory transfer mode, Multi (Double) Buffer mode is not allowed. - -@- When Multi (Double) Buffer mode is enabled the, transfer is circular by default. - -@- In Multi (Double) buffer mode, it is possible to update the base address for - the AHB memory port on the fly (DMA_SxM0AR or DMA_SxM1AR) when the stream is enabled. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup DMAEx DMAEx - * @brief DMA Extended HAL module driver - * @{ - */ - -#ifdef HAL_DMA_MODULE_ENABLED - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private Constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup DMAEx_Private_Functions - * @{ - */ -static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ - -/** @addtogroup DMAEx_Exported_Functions - * @{ - */ - - -/** @addtogroup DMAEx_Exported_Functions_Group1 - * -@verbatim - =============================================================================== - ##### Extended features functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure the source, destination address and data length and - Start MultiBuffer DMA transfer - (+) Configure the source, destination address and data length and - Start MultiBuffer DMA transfer with interrupt - (+) Change on the fly the memory0 or memory1 address. - -@endverbatim - * @{ - */ - - -/** - * @brief Starts the multi_buffer DMA Transfer. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_DMA_BUFFER_SIZE(DataLength)); - - /* Memory-to-memory transfer not supported in double buffering mode */ - if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY) - { - hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; - status = HAL_ERROR; - } - else - { - /* Process Locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Enable the double buffer mode */ - hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM; - - /* Configure DMA Stream destination address */ - hdma->Instance->M1AR = SecondMemAddress; - - /* Configure the source, destination address and the data length */ - DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength); - - /* Enable the peripheral */ - __HAL_DMA_ENABLE(hdma); - } - else - { - /* Return error status */ - status = HAL_BUSY; - } - } - return status; -} - -/** - * @brief Starts the multi_buffer DMA Transfer with interrupt enabled. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_DMA_BUFFER_SIZE(DataLength)); - - /* Memory-to-memory transfer not supported in double buffering mode */ - if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY) - { - hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED; - return HAL_ERROR; - } - - /* Check callback functions */ - if ((NULL == hdma->XferCpltCallback) || (NULL == hdma->XferM1CpltCallback) || (NULL == hdma->XferErrorCallback)) - { - hdma->ErrorCode = HAL_DMA_ERROR_PARAM; - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hdma); - - if(HAL_DMA_STATE_READY == hdma->State) - { - /* Change DMA peripheral state */ - hdma->State = HAL_DMA_STATE_BUSY; - - /* Initialize the error code */ - hdma->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Enable the Double buffer mode */ - hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM; - - /* Configure DMA Stream destination address */ - hdma->Instance->M1AR = SecondMemAddress; - - /* Configure the source, destination address and the data length */ - DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength); - - /* Clear all flags */ - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma)); - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma)); - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma)); - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_DME_FLAG_INDEX(hdma)); - __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_FE_FLAG_INDEX(hdma)); - - /* Enable Common interrupts*/ - hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME; - hdma->Instance->FCR |= DMA_IT_FE; - - if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL)) - { - hdma->Instance->CR |= DMA_IT_HT; - } - - /* Enable the peripheral */ - __HAL_DMA_ENABLE(hdma); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdma); - - /* Return error status */ - status = HAL_BUSY; - } - return status; -} - -/** - * @brief Change the memory0 or memory1 address on the fly. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param Address The new address - * @param memory the memory to be changed, This parameter can be one of - * the following values: - * MEMORY0 / - * MEMORY1 - * @note The MEMORY0 address can be changed only when the current transfer use - * MEMORY1 and the MEMORY1 address can be changed only when the current - * transfer use MEMORY0. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory) -{ - if(memory == MEMORY0) - { - /* change the memory0 address */ - hdma->Instance->M0AR = Address; - } - else - { - /* change the memory1 address */ - hdma->Instance->M1AR = Address; - } - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup DMAEx_Private_Functions - * @{ - */ - -/** - * @brief Set the DMA Transfer parameter. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA Stream. - * @param SrcAddress The source memory Buffer address - * @param DstAddress The destination memory Buffer address - * @param DataLength The length of data to be transferred from source to destination - * @retval HAL status - */ -static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength) -{ - /* Configure DMA Stream data length */ - hdma->Instance->NDTR = DataLength; - - /* Peripheral to Memory */ - if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH) - { - /* Configure DMA Stream destination address */ - hdma->Instance->PAR = DstAddress; - - /* Configure DMA Stream source address */ - hdma->Instance->M0AR = SrcAddress; - } - /* Memory to Peripheral */ - else - { - /* Configure DMA Stream source address */ - hdma->Instance->PAR = SrcAddress; - - /* Configure DMA Stream destination address */ - hdma->Instance->M0AR = DstAddress; - } -} - -/** - * @} - */ - -#endif /* HAL_DMA_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dsi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dsi.c deleted file mode 100644 index da57a8fa69decb6..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dsi.c +++ /dev/null @@ -1,2731 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dsi.c - * @author MCD Application Team - * @brief DSI HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the DSI peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Errors functions - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The DSI HAL driver can be used as follows: - - (#) Declare a DSI_HandleTypeDef handle structure, for example: DSI_HandleTypeDef hdsi; - - (#) Initialize the DSI low level resources by implementing the HAL_DSI_MspInit() API: - (##) Enable the DSI interface clock - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the DSI interrupt priority - (+++) Enable the NVIC DSI IRQ Channel - - (#) Initialize the DSI Host peripheral, the required PLL parameters, number of lances and - TX Escape clock divider by calling the HAL_DSI_Init() API which calls HAL_DSI_MspInit(). - - *** Configuration *** - ========================= - [..] - (#) Use HAL_DSI_ConfigAdaptedCommandMode() function to configure the DSI host in adapted - command mode. - - (#) When operating in video mode , use HAL_DSI_ConfigVideoMode() to configure the DSI host. - - (#) Function HAL_DSI_ConfigCommand() is used to configure the DSI commands behavior in low power mode. - - (#) To configure the DSI PHY timings parameters, use function HAL_DSI_ConfigPhyTimer(). - - (#) The DSI Host can be started/stopped using respectively functions HAL_DSI_Start() and HAL_DSI_Stop(). - Functions HAL_DSI_ShortWrite(), HAL_DSI_LongWrite() and HAL_DSI_Read() allows respectively - to write DSI short packets, long packets and to read DSI packets. - - (#) The DSI Host Offers two Low power modes : - (++) Low Power Mode on data lanes only: Only DSI data lanes are shut down. - It is possible to enter/exit from this mode using respectively functions HAL_DSI_EnterULPMData() - and HAL_DSI_ExitULPMData() - - (++) Low Power Mode on data and clock lanes : All DSI lanes are shut down including data and clock lanes. - It is possible to enter/exit from this mode using respectively functions HAL_DSI_EnterULPM() - and HAL_DSI_ExitULPM() - - (#) To control DSI state you can use the following function: HAL_DSI_GetState() - - *** Error management *** - ======================== - [..] - (#) User can select the DSI errors to be reported/monitored using function HAL_DSI_ConfigErrorMonitor() - When an error occurs, the callback HAL_DSI_ErrorCallback() is asserted and then user can retrieve - the error code by calling function HAL_DSI_GetError() - - *** DSI HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in DSI HAL driver. - - (+) __HAL_DSI_ENABLE: Enable the DSI Host. - (+) __HAL_DSI_DISABLE: Disable the DSI Host. - (+) __HAL_DSI_WRAPPER_ENABLE: Enables the DSI wrapper. - (+) __HAL_DSI_WRAPPER_DISABLE: Disable the DSI wrapper. - (+) __HAL_DSI_PLL_ENABLE: Enables the DSI PLL. - (+) __HAL_DSI_PLL_DISABLE: Disables the DSI PLL. - (+) __HAL_DSI_REG_ENABLE: Enables the DSI regulator. - (+) __HAL_DSI_REG_DISABLE: Disables the DSI regulator. - (+) __HAL_DSI_GET_FLAG: Get the DSI pending flags. - (+) __HAL_DSI_CLEAR_FLAG: Clears the DSI pending flags. - (+) __HAL_DSI_ENABLE_IT: Enables the specified DSI interrupts. - (+) __HAL_DSI_DISABLE_IT: Disables the specified DSI interrupts. - (+) __HAL_DSI_GET_IT_SOURCE: Checks whether the specified DSI interrupt source is enabled or not. - - [..] - (@) You can refer to the DSI HAL driver header file for more useful macros - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_DSI_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Function HAL_DSI_RegisterCallback() to register a callback. - - [..] - Function HAL_DSI_RegisterCallback() allows to register following callbacks: - (+) TearingEffectCallback : DSI Tearing Effect Callback. - (+) EndOfRefreshCallback : DSI End Of Refresh Callback. - (+) ErrorCallback : DSI Error Callback - (+) MspInitCallback : DSI MspInit. - (+) MspDeInitCallback : DSI MspDeInit. - [..] - This function takes as parameters the HAL peripheral handle, the callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_DSI_UnRegisterCallback() to reset a callback to the default - weak function. - HAL_DSI_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the callback ID. - [..] - This function allows to reset following callbacks: - (+) TearingEffectCallback : DSI Tearing Effect Callback. - (+) EndOfRefreshCallback : DSI End Of Refresh Callback. - (+) ErrorCallback : DSI Error Callback - (+) MspInitCallback : DSI MspInit. - (+) MspDeInitCallback : DSI MspDeInit. - - [..] - By default, after the HAL_DSI_Init and when the state is HAL_DSI_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_DSI_TearingEffectCallback(), HAL_DSI_EndOfRefreshCallback(). - Exception done for MspInit and MspDeInit functions that are respectively - reset to the legacy weak (surcharged) functions in the HAL_DSI_Init() - and HAL_DSI_DeInit() only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_DSI_Init() and HAL_DSI_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in HAL_DSI_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_DSI_STATE_READY or HAL_DSI_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_DSI_RegisterCallback() before calling HAL_DSI_DeInit() - or HAL_DSI_Init() function. - - [..] - When The compilation define USE_HAL_DSI_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_DSI_MODULE_ENABLED - -#if defined(DSI) - -/** @addtogroup DSI - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private defines -----------------------------------------------------------*/ -/** @addtogroup DSI_Private_Constants - * @{ - */ -#define DSI_TIMEOUT_VALUE ((uint32_t)1000U) /* 1s */ - -#define DSI_ERROR_ACK_MASK (DSI_ISR0_AE0 | DSI_ISR0_AE1 | DSI_ISR0_AE2 | DSI_ISR0_AE3 | \ - DSI_ISR0_AE4 | DSI_ISR0_AE5 | DSI_ISR0_AE6 | DSI_ISR0_AE7 | \ - DSI_ISR0_AE8 | DSI_ISR0_AE9 | DSI_ISR0_AE10 | DSI_ISR0_AE11 | \ - DSI_ISR0_AE12 | DSI_ISR0_AE13 | DSI_ISR0_AE14 | DSI_ISR0_AE15) -#define DSI_ERROR_PHY_MASK (DSI_ISR0_PE0 | DSI_ISR0_PE1 | DSI_ISR0_PE2 | DSI_ISR0_PE3 | DSI_ISR0_PE4) -#define DSI_ERROR_TX_MASK DSI_ISR1_TOHSTX -#define DSI_ERROR_RX_MASK DSI_ISR1_TOLPRX -#define DSI_ERROR_ECC_MASK (DSI_ISR1_ECCSE | DSI_ISR1_ECCME) -#define DSI_ERROR_CRC_MASK DSI_ISR1_CRCE -#define DSI_ERROR_PSE_MASK DSI_ISR1_PSE -#define DSI_ERROR_EOT_MASK DSI_ISR1_EOTPE -#define DSI_ERROR_OVF_MASK DSI_ISR1_LPWRE -#define DSI_ERROR_GEN_MASK (DSI_ISR1_GCWRE | DSI_ISR1_GPWRE | DSI_ISR1_GPTXE | DSI_ISR1_GPRDE | DSI_ISR1_GPRXE) -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -static void DSI_ConfigPacketHeader(DSI_TypeDef *DSIx, uint32_t ChannelID, uint32_t DataType, uint32_t Data0, - uint32_t Data1); - -static HAL_StatusTypeDef DSI_ShortWrite(DSI_HandleTypeDef *hdsi, - uint32_t ChannelID, - uint32_t Mode, - uint32_t Param1, - uint32_t Param2); - -/* Private functions ---------------------------------------------------------*/ -/** - * @brief Generic DSI packet header configuration - * @param DSIx Pointer to DSI register base - * @param ChannelID Virtual channel ID of the header packet - * @param DataType Packet data type of the header packet - * This parameter can be any value of : - * @arg DSI_SHORT_WRITE_PKT_Data_Type - * @arg DSI_LONG_WRITE_PKT_Data_Type - * @arg DSI_SHORT_READ_PKT_Data_Type - * @arg DSI_MAX_RETURN_PKT_SIZE - * @param Data0 Word count LSB - * @param Data1 Word count MSB - * @retval None - */ -static void DSI_ConfigPacketHeader(DSI_TypeDef *DSIx, - uint32_t ChannelID, - uint32_t DataType, - uint32_t Data0, - uint32_t Data1) -{ - /* Update the DSI packet header with new information */ - DSIx->GHCR = (DataType | (ChannelID << 6U) | (Data0 << 8U) | (Data1 << 16U)); -} - -/** - * @brief write short DCS or short Generic command - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param ChannelID Virtual channel ID. - * @param Mode DSI short packet data type. - * This parameter can be any value of @arg DSI_SHORT_WRITE_PKT_Data_Type. - * @param Param1 DSC command or first generic parameter. - * This parameter can be any value of @arg DSI_DCS_Command or a - * generic command code. - * @param Param2 DSC parameter or second generic parameter. - * @retval HAL status - */ -static HAL_StatusTypeDef DSI_ShortWrite(DSI_HandleTypeDef *hdsi, - uint32_t ChannelID, - uint32_t Mode, - uint32_t Param1, - uint32_t Param2) -{ - uint32_t tickstart; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait for Command FIFO Empty */ - while((hdsi->Instance->GPSR & DSI_GPSR_CMDFE) == 0U) - { - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > DSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Configure the packet to send a short DCS command with 0 or 1 parameter */ - /* Update the DSI packet header with new information */ - hdsi->Instance->GHCR = (Mode | (ChannelID << 6U) | (Param1 << 8U) | (Param2 << 16U)); - - return HAL_OK; -} - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DSI_Exported_Functions - * @{ - */ - -/** @defgroup DSI_Group1 Initialization and Configuration functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the DSI - (+) De-initialize the DSI - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the DSI according to the specified - * parameters in the DSI_InitTypeDef and create the associated handle. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param PLLInit pointer to a DSI_PLLInitTypeDef structure that contains - * the PLL Clock structure definition for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_Init(DSI_HandleTypeDef *hdsi, DSI_PLLInitTypeDef *PLLInit) -{ - uint32_t tickstart; - uint32_t unitIntervalx4; - uint32_t tempIDF; - - /* Check the DSI handle allocation */ - if (hdsi == NULL) - { - return HAL_ERROR; - } - - /* Check function parameters */ - assert_param(IS_DSI_PLL_NDIV(PLLInit->PLLNDIV)); - assert_param(IS_DSI_PLL_IDF(PLLInit->PLLIDF)); - assert_param(IS_DSI_PLL_ODF(PLLInit->PLLODF)); - assert_param(IS_DSI_AUTO_CLKLANE_CONTROL(hdsi->Init.AutomaticClockLaneControl)); - assert_param(IS_DSI_NUMBER_OF_LANES(hdsi->Init.NumberOfLanes)); - -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) - if (hdsi->State == HAL_DSI_STATE_RESET) - { - /* Reset the DSI callback to the legacy weak callbacks */ - hdsi->TearingEffectCallback = HAL_DSI_TearingEffectCallback; /* Legacy weak TearingEffectCallback */ - hdsi->EndOfRefreshCallback = HAL_DSI_EndOfRefreshCallback; /* Legacy weak EndOfRefreshCallback */ - hdsi->ErrorCallback = HAL_DSI_ErrorCallback; /* Legacy weak ErrorCallback */ - - if (hdsi->MspInitCallback == NULL) - { - hdsi->MspInitCallback = HAL_DSI_MspInit; - } - /* Initialize the low level hardware */ - hdsi->MspInitCallback(hdsi); - } -#else - if (hdsi->State == HAL_DSI_STATE_RESET) - { - /* Initialize the low level hardware */ - HAL_DSI_MspInit(hdsi); - } -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - - /* Change DSI peripheral state */ - hdsi->State = HAL_DSI_STATE_BUSY; - - /**************** Turn on the regulator and enable the DSI PLL ****************/ - - /* Enable the regulator */ - __HAL_DSI_REG_ENABLE(hdsi); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until the regulator is ready */ - while (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_RRS) == 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Set the PLL division factors */ - hdsi->Instance->WRPCR &= ~(DSI_WRPCR_PLL_NDIV | DSI_WRPCR_PLL_IDF | DSI_WRPCR_PLL_ODF); - hdsi->Instance->WRPCR |= (((PLLInit->PLLNDIV) << 2U) | ((PLLInit->PLLIDF) << 11U) | ((PLLInit->PLLODF) << 16U)); - - /* Enable the DSI PLL */ - __HAL_DSI_PLL_ENABLE(hdsi); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait for the lock of the PLL */ - while (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_PLLLS) == 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /*************************** Set the PHY parameters ***************************/ - - /* D-PHY clock and digital enable*/ - hdsi->Instance->PCTLR |= (DSI_PCTLR_CKE | DSI_PCTLR_DEN); - - /* Clock lane configuration */ - hdsi->Instance->CLCR &= ~(DSI_CLCR_DPCC | DSI_CLCR_ACR); - hdsi->Instance->CLCR |= (DSI_CLCR_DPCC | hdsi->Init.AutomaticClockLaneControl); - - /* Configure the number of active data lanes */ - hdsi->Instance->PCONFR &= ~DSI_PCONFR_NL; - hdsi->Instance->PCONFR |= hdsi->Init.NumberOfLanes; - - /************************ Set the DSI clock parameters ************************/ - - /* Set the TX escape clock division factor */ - hdsi->Instance->CCR &= ~DSI_CCR_TXECKDIV; - hdsi->Instance->CCR |= hdsi->Init.TXEscapeCkdiv; - - /* Calculate the bit period in high-speed mode in unit of 0.25 ns (UIX4) */ - /* The equation is : UIX4 = IntegerPart( (1000/F_PHY_Mhz) * 4 ) */ - /* Where : F_PHY_Mhz = (NDIV * HSE_Mhz) / (IDF * ODF) */ - tempIDF = (PLLInit->PLLIDF > 0U) ? PLLInit->PLLIDF : 1U; - unitIntervalx4 = (4000000U * tempIDF * ((1UL << (0x3U & PLLInit->PLLODF)))) / ((HSE_VALUE / 1000U) * PLLInit->PLLNDIV); - - /* Set the bit period in high-speed mode */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_UIX4; - hdsi->Instance->WPCR[0U] |= unitIntervalx4; - - /****************************** Error management *****************************/ - - /* Disable all error interrupts and reset the Error Mask */ - hdsi->Instance->IER[0U] = 0U; - hdsi->Instance->IER[1U] = 0U; - hdsi->ErrorMsk = 0U; - - /* Initialise the error code */ - hdsi->ErrorCode = HAL_DSI_ERROR_NONE; - - /* Initialize the DSI state*/ - hdsi->State = HAL_DSI_STATE_READY; - - return HAL_OK; -} - -/** - * @brief De-initializes the DSI peripheral registers to their default reset - * values. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_DeInit(DSI_HandleTypeDef *hdsi) -{ - /* Check the DSI handle allocation */ - if (hdsi == NULL) - { - return HAL_ERROR; - } - - /* Change DSI peripheral state */ - hdsi->State = HAL_DSI_STATE_BUSY; - - /* Disable the DSI wrapper */ - __HAL_DSI_WRAPPER_DISABLE(hdsi); - - /* Disable the DSI host */ - __HAL_DSI_DISABLE(hdsi); - - /* D-PHY clock and digital disable */ - hdsi->Instance->PCTLR &= ~(DSI_PCTLR_CKE | DSI_PCTLR_DEN); - - /* Turn off the DSI PLL */ - __HAL_DSI_PLL_DISABLE(hdsi); - - /* Disable the regulator */ - __HAL_DSI_REG_DISABLE(hdsi); - -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) - if (hdsi->MspDeInitCallback == NULL) - { - hdsi->MspDeInitCallback = HAL_DSI_MspDeInit; - } - /* DeInit the low level hardware */ - hdsi->MspDeInitCallback(hdsi); -#else - /* DeInit the low level hardware */ - HAL_DSI_MspDeInit(hdsi); -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - - /* Initialise the error code */ - hdsi->ErrorCode = HAL_DSI_ERROR_NONE; - - /* Initialize the DSI state*/ - hdsi->State = HAL_DSI_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Enable the error monitor flags - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param ActiveErrors indicates which error interrupts will be enabled. - * This parameter can be any combination of @arg DSI_Error_Data_Type. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ConfigErrorMonitor(DSI_HandleTypeDef *hdsi, uint32_t ActiveErrors) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - hdsi->Instance->IER[0U] = 0U; - hdsi->Instance->IER[1U] = 0U; - - /* Store active errors to the handle */ - hdsi->ErrorMsk = ActiveErrors; - - if ((ActiveErrors & HAL_DSI_ERROR_ACK) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[0U] |= DSI_ERROR_ACK_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_PHY) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[0U] |= DSI_ERROR_PHY_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_TX) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[1U] |= DSI_ERROR_TX_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_RX) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[1U] |= DSI_ERROR_RX_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_ECC) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[1U] |= DSI_ERROR_ECC_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_CRC) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[1U] |= DSI_ERROR_CRC_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_PSE) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[1U] |= DSI_ERROR_PSE_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_EOT) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[1U] |= DSI_ERROR_EOT_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_OVF) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[1U] |= DSI_ERROR_OVF_MASK; - } - - if ((ActiveErrors & HAL_DSI_ERROR_GEN) != 0U) - { - /* Enable the interrupt generation on selected errors */ - hdsi->Instance->IER[1U] |= DSI_ERROR_GEN_MASK; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Initializes the DSI MSP. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval None - */ -__weak void HAL_DSI_MspInit(DSI_HandleTypeDef *hdsi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdsi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DSI_MspInit could be implemented in the user file - */ -} - -/** - * @brief De-initializes the DSI MSP. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval None - */ -__weak void HAL_DSI_MspDeInit(DSI_HandleTypeDef *hdsi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdsi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DSI_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User DSI Callback - * To be used instead of the weak predefined callback - * @param hdsi dsi handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg HAL_DSI_TEARING_EFFECT_CB_ID Tearing Effect Callback ID - * @arg HAL_DSI_ENDOF_REFRESH_CB_ID End Of Refresh Callback ID - * @arg HAL_DSI_ERROR_CB_ID Error Callback ID - * @arg HAL_DSI_MSPINIT_CB_ID MspInit callback ID - * @arg HAL_DSI_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_DSI_RegisterCallback(DSI_HandleTypeDef *hdsi, HAL_DSI_CallbackIDTypeDef CallbackID, - pDSI_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hdsi); - - if (hdsi->State == HAL_DSI_STATE_READY) - { - switch (CallbackID) - { - case HAL_DSI_TEARING_EFFECT_CB_ID : - hdsi->TearingEffectCallback = pCallback; - break; - - case HAL_DSI_ENDOF_REFRESH_CB_ID : - hdsi->EndOfRefreshCallback = pCallback; - break; - - case HAL_DSI_ERROR_CB_ID : - hdsi->ErrorCallback = pCallback; - break; - - case HAL_DSI_MSPINIT_CB_ID : - hdsi->MspInitCallback = pCallback; - break; - - case HAL_DSI_MSPDEINIT_CB_ID : - hdsi->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hdsi->State == HAL_DSI_STATE_RESET) - { - switch (CallbackID) - { - case HAL_DSI_MSPINIT_CB_ID : - hdsi->MspInitCallback = pCallback; - break; - - case HAL_DSI_MSPDEINIT_CB_ID : - hdsi->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdsi); - - return status; -} - -/** - * @brief Unregister a DSI Callback - * DSI callabck is redirected to the weak predefined callback - * @param hdsi dsi handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg HAL_DSI_TEARING_EFFECT_CB_ID Tearing Effect Callback ID - * @arg HAL_DSI_ENDOF_REFRESH_CB_ID End Of Refresh Callback ID - * @arg HAL_DSI_ERROR_CB_ID Error Callback ID - * @arg HAL_DSI_MSPINIT_CB_ID MspInit callback ID - * @arg HAL_DSI_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_DSI_UnRegisterCallback(DSI_HandleTypeDef *hdsi, HAL_DSI_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hdsi); - - if (hdsi->State == HAL_DSI_STATE_READY) - { - switch (CallbackID) - { - case HAL_DSI_TEARING_EFFECT_CB_ID : - hdsi->TearingEffectCallback = HAL_DSI_TearingEffectCallback; /* Legacy weak TearingEffectCallback */ - break; - - case HAL_DSI_ENDOF_REFRESH_CB_ID : - hdsi->EndOfRefreshCallback = HAL_DSI_EndOfRefreshCallback; /* Legacy weak EndOfRefreshCallback */ - break; - - case HAL_DSI_ERROR_CB_ID : - hdsi->ErrorCallback = HAL_DSI_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_DSI_MSPINIT_CB_ID : - hdsi->MspInitCallback = HAL_DSI_MspInit; /* Legcay weak MspInit Callback */ - break; - - case HAL_DSI_MSPDEINIT_CB_ID : - hdsi->MspDeInitCallback = HAL_DSI_MspDeInit; /* Legcay weak MspDeInit Callback */ - break; - - default : - /* Update the error code */ - hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hdsi->State == HAL_DSI_STATE_RESET) - { - switch (CallbackID) - { - case HAL_DSI_MSPINIT_CB_ID : - hdsi->MspInitCallback = HAL_DSI_MspInit; /* Legcay weak MspInit Callback */ - break; - - case HAL_DSI_MSPDEINIT_CB_ID : - hdsi->MspDeInitCallback = HAL_DSI_MspDeInit; /* Legcay weak MspDeInit Callback */ - break; - - default : - /* Update the error code */ - hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hdsi->ErrorCode |= HAL_DSI_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hdsi); - - return status; -} -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup DSI_Group2 IO operation functions - * @brief IO operation functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This section provides function allowing to: - (+) Handle DSI interrupt request - -@endverbatim - * @{ - */ -/** - * @brief Handles DSI interrupt request. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -void HAL_DSI_IRQHandler(DSI_HandleTypeDef *hdsi) -{ - uint32_t ErrorStatus0, ErrorStatus1; - - /* Tearing Effect Interrupt management ***************************************/ - if (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_TE) != 0U) - { - if (__HAL_DSI_GET_IT_SOURCE(hdsi, DSI_IT_TE) != 0U) - { - /* Clear the Tearing Effect Interrupt Flag */ - __HAL_DSI_CLEAR_FLAG(hdsi, DSI_FLAG_TE); - - /* Tearing Effect Callback */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) - /*Call registered Tearing Effect callback */ - hdsi->TearingEffectCallback(hdsi); -#else - /*Call legacy Tearing Effect callback*/ - HAL_DSI_TearingEffectCallback(hdsi); -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - } - } - - /* End of Refresh Interrupt management ***************************************/ - if (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_ER) != 0U) - { - if (__HAL_DSI_GET_IT_SOURCE(hdsi, DSI_IT_ER) != 0U) - { - /* Clear the End of Refresh Interrupt Flag */ - __HAL_DSI_CLEAR_FLAG(hdsi, DSI_FLAG_ER); - - /* End of Refresh Callback */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) - /*Call registered End of refresh callback */ - hdsi->EndOfRefreshCallback(hdsi); -#else - /*Call Legacy End of refresh callback */ - HAL_DSI_EndOfRefreshCallback(hdsi); -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - } - } - - /* Error Interrupts management ***********************************************/ - if (hdsi->ErrorMsk != 0U) - { - ErrorStatus0 = hdsi->Instance->ISR[0U]; - ErrorStatus0 &= hdsi->Instance->IER[0U]; - ErrorStatus1 = hdsi->Instance->ISR[1U]; - ErrorStatus1 &= hdsi->Instance->IER[1U]; - - if ((ErrorStatus0 & DSI_ERROR_ACK_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_ACK; - } - - if ((ErrorStatus0 & DSI_ERROR_PHY_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_PHY; - } - - if ((ErrorStatus1 & DSI_ERROR_TX_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_TX; - } - - if ((ErrorStatus1 & DSI_ERROR_RX_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_RX; - } - - if ((ErrorStatus1 & DSI_ERROR_ECC_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_ECC; - } - - if ((ErrorStatus1 & DSI_ERROR_CRC_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_CRC; - } - - if ((ErrorStatus1 & DSI_ERROR_PSE_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_PSE; - } - - if ((ErrorStatus1 & DSI_ERROR_EOT_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_EOT; - } - - if ((ErrorStatus1 & DSI_ERROR_OVF_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_OVF; - } - - if ((ErrorStatus1 & DSI_ERROR_GEN_MASK) != 0U) - { - hdsi->ErrorCode |= HAL_DSI_ERROR_GEN; - } - - /* Check only selected errors */ - if (hdsi->ErrorCode != HAL_DSI_ERROR_NONE) - { - /* DSI error interrupt callback */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) - /*Call registered Error callback */ - hdsi->ErrorCallback(hdsi); -#else - /*Call Legacy Error callback */ - HAL_DSI_ErrorCallback(hdsi); -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief Tearing Effect DSI callback. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval None - */ -__weak void HAL_DSI_TearingEffectCallback(DSI_HandleTypeDef *hdsi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdsi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DSI_TearingEffectCallback could be implemented in the user file - */ -} - -/** - * @brief End of Refresh DSI callback. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval None - */ -__weak void HAL_DSI_EndOfRefreshCallback(DSI_HandleTypeDef *hdsi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdsi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DSI_EndOfRefreshCallback could be implemented in the user file - */ -} - -/** - * @brief Operation Error DSI callback. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval None - */ -__weak void HAL_DSI_ErrorCallback(DSI_HandleTypeDef *hdsi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdsi); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_DSI_ErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup DSI_Group3 Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure the Generic interface read-back Virtual Channel ID - (+) Select video mode and configure the corresponding parameters - (+) Configure command transmission mode: High-speed or Low-power - (+) Configure the flow control - (+) Configure the DSI PHY timer - (+) Configure the DSI HOST timeout - (+) Configure the DSI HOST timeout - (+) Start/Stop the DSI module - (+) Refresh the display in command mode - (+) Controls the display color mode in Video mode - (+) Control the display shutdown in Video mode - (+) write short DCS or short Generic command - (+) write long DCS or long Generic command - (+) Read command (DCS or generic) - (+) Enter/Exit the Ultra Low Power Mode on data only (D-PHY PLL running) - (+) Enter/Exit the Ultra Low Power Mode on data only and clock (D-PHY PLL turned off) - (+) Start/Stop test pattern generation - (+) Slew-Rate And Delay Tuning - (+) Low-Power Reception Filter Tuning - (+) Activate an additional current path on all lanes to meet the SDDTx parameter - (+) Custom lane pins configuration - (+) Set custom timing for the PHY - (+) Force the Clock/Data Lane in TX Stop Mode - (+) Force LP Receiver in Low-Power Mode - (+) Force Data Lanes in RX Mode after a BTA - (+) Enable a pull-down on the lanes to prevent from floating states when unused - (+) Switch off the contention detection on data lanes - -@endverbatim - * @{ - */ - -/** - * @brief Configure the Generic interface read-back Virtual Channel ID. - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param VirtualChannelID Virtual channel ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_SetGenericVCID(DSI_HandleTypeDef *hdsi, uint32_t VirtualChannelID) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Update the GVCID register */ - hdsi->Instance->GVCIDR &= ~DSI_GVCIDR_VCID; - hdsi->Instance->GVCIDR |= VirtualChannelID; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Select video mode and configure the corresponding parameters - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param VidCfg pointer to a DSI_VidCfgTypeDef structure that contains - * the DSI video mode configuration parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ConfigVideoMode(DSI_HandleTypeDef *hdsi, DSI_VidCfgTypeDef *VidCfg) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check the parameters */ - assert_param(IS_DSI_COLOR_CODING(VidCfg->ColorCoding)); - assert_param(IS_DSI_VIDEO_MODE_TYPE(VidCfg->Mode)); - assert_param(IS_DSI_LP_COMMAND(VidCfg->LPCommandEnable)); - assert_param(IS_DSI_LP_HFP(VidCfg->LPHorizontalFrontPorchEnable)); - assert_param(IS_DSI_LP_HBP(VidCfg->LPHorizontalBackPorchEnable)); - assert_param(IS_DSI_LP_VACTIVE(VidCfg->LPVerticalActiveEnable)); - assert_param(IS_DSI_LP_VFP(VidCfg->LPVerticalFrontPorchEnable)); - assert_param(IS_DSI_LP_VBP(VidCfg->LPVerticalBackPorchEnable)); - assert_param(IS_DSI_LP_VSYNC(VidCfg->LPVerticalSyncActiveEnable)); - assert_param(IS_DSI_FBTAA(VidCfg->FrameBTAAcknowledgeEnable)); - assert_param(IS_DSI_DE_POLARITY(VidCfg->DEPolarity)); - assert_param(IS_DSI_VSYNC_POLARITY(VidCfg->VSPolarity)); - assert_param(IS_DSI_HSYNC_POLARITY(VidCfg->HSPolarity)); - /* Check the LooselyPacked variant only in 18-bit mode */ - if (VidCfg->ColorCoding == DSI_RGB666) - { - assert_param(IS_DSI_LOOSELY_PACKED(VidCfg->LooselyPacked)); - } - - /* Select video mode by resetting CMDM and DSIM bits */ - hdsi->Instance->MCR &= ~DSI_MCR_CMDM; - hdsi->Instance->WCFGR &= ~DSI_WCFGR_DSIM; - - /* Configure the video mode transmission type */ - hdsi->Instance->VMCR &= ~DSI_VMCR_VMT; - hdsi->Instance->VMCR |= VidCfg->Mode; - - /* Configure the video packet size */ - hdsi->Instance->VPCR &= ~DSI_VPCR_VPSIZE; - hdsi->Instance->VPCR |= VidCfg->PacketSize; - - /* Set the chunks number to be transmitted through the DSI link */ - hdsi->Instance->VCCR &= ~DSI_VCCR_NUMC; - hdsi->Instance->VCCR |= VidCfg->NumberOfChunks; - - /* Set the size of the null packet */ - hdsi->Instance->VNPCR &= ~DSI_VNPCR_NPSIZE; - hdsi->Instance->VNPCR |= VidCfg->NullPacketSize; - - /* Select the virtual channel for the LTDC interface traffic */ - hdsi->Instance->LVCIDR &= ~DSI_LVCIDR_VCID; - hdsi->Instance->LVCIDR |= VidCfg->VirtualChannelID; - - /* Configure the polarity of control signals */ - hdsi->Instance->LPCR &= ~(DSI_LPCR_DEP | DSI_LPCR_VSP | DSI_LPCR_HSP); - hdsi->Instance->LPCR |= (VidCfg->DEPolarity | VidCfg->VSPolarity | VidCfg->HSPolarity); - - /* Select the color coding for the host */ - hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_COLC; - hdsi->Instance->LCOLCR |= VidCfg->ColorCoding; - - /* Select the color coding for the wrapper */ - hdsi->Instance->WCFGR &= ~DSI_WCFGR_COLMUX; - hdsi->Instance->WCFGR |= ((VidCfg->ColorCoding) << 1U); - - /* Enable/disable the loosely packed variant to 18-bit configuration */ - if (VidCfg->ColorCoding == DSI_RGB666) - { - hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_LPE; - hdsi->Instance->LCOLCR |= VidCfg->LooselyPacked; - } - - /* Set the Horizontal Synchronization Active (HSA) in lane byte clock cycles */ - hdsi->Instance->VHSACR &= ~DSI_VHSACR_HSA; - hdsi->Instance->VHSACR |= VidCfg->HorizontalSyncActive; - - /* Set the Horizontal Back Porch (HBP) in lane byte clock cycles */ - hdsi->Instance->VHBPCR &= ~DSI_VHBPCR_HBP; - hdsi->Instance->VHBPCR |= VidCfg->HorizontalBackPorch; - - /* Set the total line time (HLINE=HSA+HBP+HACT+HFP) in lane byte clock cycles */ - hdsi->Instance->VLCR &= ~DSI_VLCR_HLINE; - hdsi->Instance->VLCR |= VidCfg->HorizontalLine; - - /* Set the Vertical Synchronization Active (VSA) */ - hdsi->Instance->VVSACR &= ~DSI_VVSACR_VSA; - hdsi->Instance->VVSACR |= VidCfg->VerticalSyncActive; - - /* Set the Vertical Back Porch (VBP)*/ - hdsi->Instance->VVBPCR &= ~DSI_VVBPCR_VBP; - hdsi->Instance->VVBPCR |= VidCfg->VerticalBackPorch; - - /* Set the Vertical Front Porch (VFP)*/ - hdsi->Instance->VVFPCR &= ~DSI_VVFPCR_VFP; - hdsi->Instance->VVFPCR |= VidCfg->VerticalFrontPorch; - - /* Set the Vertical Active period*/ - hdsi->Instance->VVACR &= ~DSI_VVACR_VA; - hdsi->Instance->VVACR |= VidCfg->VerticalActive; - - /* Configure the command transmission mode */ - hdsi->Instance->VMCR &= ~DSI_VMCR_LPCE; - hdsi->Instance->VMCR |= VidCfg->LPCommandEnable; - - /* Low power largest packet size */ - hdsi->Instance->LPMCR &= ~DSI_LPMCR_LPSIZE; - hdsi->Instance->LPMCR |= ((VidCfg->LPLargestPacketSize) << 16U); - - /* Low power VACT largest packet size */ - hdsi->Instance->LPMCR &= ~DSI_LPMCR_VLPSIZE; - hdsi->Instance->LPMCR |= VidCfg->LPVACTLargestPacketSize; - - /* Enable LP transition in HFP period */ - hdsi->Instance->VMCR &= ~DSI_VMCR_LPHFPE; - hdsi->Instance->VMCR |= VidCfg->LPHorizontalFrontPorchEnable; - - /* Enable LP transition in HBP period */ - hdsi->Instance->VMCR &= ~DSI_VMCR_LPHBPE; - hdsi->Instance->VMCR |= VidCfg->LPHorizontalBackPorchEnable; - - /* Enable LP transition in VACT period */ - hdsi->Instance->VMCR &= ~DSI_VMCR_LPVAE; - hdsi->Instance->VMCR |= VidCfg->LPVerticalActiveEnable; - - /* Enable LP transition in VFP period */ - hdsi->Instance->VMCR &= ~DSI_VMCR_LPVFPE; - hdsi->Instance->VMCR |= VidCfg->LPVerticalFrontPorchEnable; - - /* Enable LP transition in VBP period */ - hdsi->Instance->VMCR &= ~DSI_VMCR_LPVBPE; - hdsi->Instance->VMCR |= VidCfg->LPVerticalBackPorchEnable; - - /* Enable LP transition in vertical sync period */ - hdsi->Instance->VMCR &= ~DSI_VMCR_LPVSAE; - hdsi->Instance->VMCR |= VidCfg->LPVerticalSyncActiveEnable; - - /* Enable the request for an acknowledge response at the end of a frame */ - hdsi->Instance->VMCR &= ~DSI_VMCR_FBTAAE; - hdsi->Instance->VMCR |= VidCfg->FrameBTAAcknowledgeEnable; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Select adapted command mode and configure the corresponding parameters - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param CmdCfg pointer to a DSI_CmdCfgTypeDef structure that contains - * the DSI command mode configuration parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ConfigAdaptedCommandMode(DSI_HandleTypeDef *hdsi, DSI_CmdCfgTypeDef *CmdCfg) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check the parameters */ - assert_param(IS_DSI_COLOR_CODING(CmdCfg->ColorCoding)); - assert_param(IS_DSI_TE_SOURCE(CmdCfg->TearingEffectSource)); - assert_param(IS_DSI_TE_POLARITY(CmdCfg->TearingEffectPolarity)); - assert_param(IS_DSI_AUTOMATIC_REFRESH(CmdCfg->AutomaticRefresh)); - assert_param(IS_DSI_VS_POLARITY(CmdCfg->VSyncPol)); - assert_param(IS_DSI_TE_ACK_REQUEST(CmdCfg->TEAcknowledgeRequest)); - assert_param(IS_DSI_DE_POLARITY(CmdCfg->DEPolarity)); - assert_param(IS_DSI_VSYNC_POLARITY(CmdCfg->VSPolarity)); - assert_param(IS_DSI_HSYNC_POLARITY(CmdCfg->HSPolarity)); - - /* Select command mode by setting CMDM and DSIM bits */ - hdsi->Instance->MCR |= DSI_MCR_CMDM; - hdsi->Instance->WCFGR &= ~DSI_WCFGR_DSIM; - hdsi->Instance->WCFGR |= DSI_WCFGR_DSIM; - - /* Select the virtual channel for the LTDC interface traffic */ - hdsi->Instance->LVCIDR &= ~DSI_LVCIDR_VCID; - hdsi->Instance->LVCIDR |= CmdCfg->VirtualChannelID; - - /* Configure the polarity of control signals */ - hdsi->Instance->LPCR &= ~(DSI_LPCR_DEP | DSI_LPCR_VSP | DSI_LPCR_HSP); - hdsi->Instance->LPCR |= (CmdCfg->DEPolarity | CmdCfg->VSPolarity | CmdCfg->HSPolarity); - - /* Select the color coding for the host */ - hdsi->Instance->LCOLCR &= ~DSI_LCOLCR_COLC; - hdsi->Instance->LCOLCR |= CmdCfg->ColorCoding; - - /* Select the color coding for the wrapper */ - hdsi->Instance->WCFGR &= ~DSI_WCFGR_COLMUX; - hdsi->Instance->WCFGR |= ((CmdCfg->ColorCoding) << 1U); - - /* Configure the maximum allowed size for write memory command */ - hdsi->Instance->LCCR &= ~DSI_LCCR_CMDSIZE; - hdsi->Instance->LCCR |= CmdCfg->CommandSize; - - /* Configure the tearing effect source and polarity and select the refresh mode */ - hdsi->Instance->WCFGR &= ~(DSI_WCFGR_TESRC | DSI_WCFGR_TEPOL | DSI_WCFGR_AR | DSI_WCFGR_VSPOL); - hdsi->Instance->WCFGR |= (CmdCfg->TearingEffectSource | CmdCfg->TearingEffectPolarity | CmdCfg->AutomaticRefresh | - CmdCfg->VSyncPol); - - /* Configure the tearing effect acknowledge request */ - hdsi->Instance->CMCR &= ~DSI_CMCR_TEARE; - hdsi->Instance->CMCR |= CmdCfg->TEAcknowledgeRequest; - - /* Enable the Tearing Effect interrupt */ - __HAL_DSI_ENABLE_IT(hdsi, DSI_IT_TE); - - /* Enable the End of Refresh interrupt */ - __HAL_DSI_ENABLE_IT(hdsi, DSI_IT_ER); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Configure command transmission mode: High-speed or Low-power - * and enable/disable acknowledge request after packet transmission - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param LPCmd pointer to a DSI_LPCmdTypeDef structure that contains - * the DSI command transmission mode configuration parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ConfigCommand(DSI_HandleTypeDef *hdsi, DSI_LPCmdTypeDef *LPCmd) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - assert_param(IS_DSI_LP_GSW0P(LPCmd->LPGenShortWriteNoP)); - assert_param(IS_DSI_LP_GSW1P(LPCmd->LPGenShortWriteOneP)); - assert_param(IS_DSI_LP_GSW2P(LPCmd->LPGenShortWriteTwoP)); - assert_param(IS_DSI_LP_GSR0P(LPCmd->LPGenShortReadNoP)); - assert_param(IS_DSI_LP_GSR1P(LPCmd->LPGenShortReadOneP)); - assert_param(IS_DSI_LP_GSR2P(LPCmd->LPGenShortReadTwoP)); - assert_param(IS_DSI_LP_GLW(LPCmd->LPGenLongWrite)); - assert_param(IS_DSI_LP_DSW0P(LPCmd->LPDcsShortWriteNoP)); - assert_param(IS_DSI_LP_DSW1P(LPCmd->LPDcsShortWriteOneP)); - assert_param(IS_DSI_LP_DSR0P(LPCmd->LPDcsShortReadNoP)); - assert_param(IS_DSI_LP_DLW(LPCmd->LPDcsLongWrite)); - assert_param(IS_DSI_LP_MRDP(LPCmd->LPMaxReadPacket)); - assert_param(IS_DSI_ACK_REQUEST(LPCmd->AcknowledgeRequest)); - - /* Select High-speed or Low-power for command transmission */ - hdsi->Instance->CMCR &= ~(DSI_CMCR_GSW0TX | \ - DSI_CMCR_GSW1TX | \ - DSI_CMCR_GSW2TX | \ - DSI_CMCR_GSR0TX | \ - DSI_CMCR_GSR1TX | \ - DSI_CMCR_GSR2TX | \ - DSI_CMCR_GLWTX | \ - DSI_CMCR_DSW0TX | \ - DSI_CMCR_DSW1TX | \ - DSI_CMCR_DSR0TX | \ - DSI_CMCR_DLWTX | \ - DSI_CMCR_MRDPS); - hdsi->Instance->CMCR |= (LPCmd->LPGenShortWriteNoP | \ - LPCmd->LPGenShortWriteOneP | \ - LPCmd->LPGenShortWriteTwoP | \ - LPCmd->LPGenShortReadNoP | \ - LPCmd->LPGenShortReadOneP | \ - LPCmd->LPGenShortReadTwoP | \ - LPCmd->LPGenLongWrite | \ - LPCmd->LPDcsShortWriteNoP | \ - LPCmd->LPDcsShortWriteOneP | \ - LPCmd->LPDcsShortReadNoP | \ - LPCmd->LPDcsLongWrite | \ - LPCmd->LPMaxReadPacket); - - /* Configure the acknowledge request after each packet transmission */ - hdsi->Instance->CMCR &= ~DSI_CMCR_ARE; - hdsi->Instance->CMCR |= LPCmd->AcknowledgeRequest; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Configure the flow control parameters - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param FlowControl flow control feature(s) to be enabled. - * This parameter can be any combination of @arg DSI_FlowControl. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ConfigFlowControl(DSI_HandleTypeDef *hdsi, uint32_t FlowControl) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check the parameters */ - assert_param(IS_DSI_FLOW_CONTROL(FlowControl)); - - /* Set the DSI Host Protocol Configuration Register */ - hdsi->Instance->PCR &= ~DSI_FLOW_CONTROL_ALL; - hdsi->Instance->PCR |= FlowControl; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Configure the DSI PHY timer parameters - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param PhyTimers DSI_PHY_TimerTypeDef structure that contains - * the DSI PHY timing parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ConfigPhyTimer(DSI_HandleTypeDef *hdsi, DSI_PHY_TimerTypeDef *PhyTimers) -{ - uint32_t maxTime; - /* Process locked */ - __HAL_LOCK(hdsi); - - maxTime = (PhyTimers->ClockLaneLP2HSTime > PhyTimers->ClockLaneHS2LPTime) ? PhyTimers->ClockLaneLP2HSTime : - PhyTimers->ClockLaneHS2LPTime; - - /* Clock lane timer configuration */ - - /* In Automatic Clock Lane control mode, the DSI Host can turn off the clock lane between two - High-Speed transmission. - To do so, the DSI Host calculates the time required for the clock lane to change from HighSpeed - to Low-Power and from Low-Power to High-Speed. - This timings are configured by the HS2LP_TIME and LP2HS_TIME in the DSI Host Clock Lane Timer Configuration Register (DSI_CLTCR). - But the DSI Host is not calculating LP2HS_TIME + HS2LP_TIME but 2 x HS2LP_TIME. - - Workaround : Configure HS2LP_TIME and LP2HS_TIME with the same value being the max of HS2LP_TIME or LP2HS_TIME. - */ - hdsi->Instance->CLTCR &= ~(DSI_CLTCR_LP2HS_TIME | DSI_CLTCR_HS2LP_TIME); - hdsi->Instance->CLTCR |= (maxTime | ((maxTime) << 16U)); - - /* Data lane timer configuration */ - hdsi->Instance->DLTCR &= ~(DSI_DLTCR_MRD_TIME | DSI_DLTCR_LP2HS_TIME | DSI_DLTCR_HS2LP_TIME); - hdsi->Instance->DLTCR |= (PhyTimers->DataLaneMaxReadTime | ((PhyTimers->DataLaneLP2HSTime) << 16U) | (( - PhyTimers->DataLaneHS2LPTime) << 24U)); - - /* Configure the wait period to request HS transmission after a stop state */ - hdsi->Instance->PCONFR &= ~DSI_PCONFR_SW_TIME; - hdsi->Instance->PCONFR |= ((PhyTimers->StopWaitTime) << 8U); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Configure the DSI HOST timeout parameters - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param HostTimeouts DSI_HOST_TimeoutTypeDef structure that contains - * the DSI host timeout parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ConfigHostTimeouts(DSI_HandleTypeDef *hdsi, DSI_HOST_TimeoutTypeDef *HostTimeouts) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Set the timeout clock division factor */ - hdsi->Instance->CCR &= ~DSI_CCR_TOCKDIV; - hdsi->Instance->CCR |= ((HostTimeouts->TimeoutCkdiv) << 8U); - - /* High-speed transmission timeout */ - hdsi->Instance->TCCR[0U] &= ~DSI_TCCR0_HSTX_TOCNT; - hdsi->Instance->TCCR[0U] |= ((HostTimeouts->HighSpeedTransmissionTimeout) << 16U); - - /* Low-power reception timeout */ - hdsi->Instance->TCCR[0U] &= ~DSI_TCCR0_LPRX_TOCNT; - hdsi->Instance->TCCR[0U] |= HostTimeouts->LowPowerReceptionTimeout; - - /* High-speed read timeout */ - hdsi->Instance->TCCR[1U] &= ~DSI_TCCR1_HSRD_TOCNT; - hdsi->Instance->TCCR[1U] |= HostTimeouts->HighSpeedReadTimeout; - - /* Low-power read timeout */ - hdsi->Instance->TCCR[2U] &= ~DSI_TCCR2_LPRD_TOCNT; - hdsi->Instance->TCCR[2U] |= HostTimeouts->LowPowerReadTimeout; - - /* High-speed write timeout */ - hdsi->Instance->TCCR[3U] &= ~DSI_TCCR3_HSWR_TOCNT; - hdsi->Instance->TCCR[3U] |= HostTimeouts->HighSpeedWriteTimeout; - - /* High-speed write presp mode */ - hdsi->Instance->TCCR[3U] &= ~DSI_TCCR3_PM; - hdsi->Instance->TCCR[3U] |= HostTimeouts->HighSpeedWritePrespMode; - - /* Low-speed write timeout */ - hdsi->Instance->TCCR[4U] &= ~DSI_TCCR4_LPWR_TOCNT; - hdsi->Instance->TCCR[4U] |= HostTimeouts->LowPowerWriteTimeout; - - /* BTA timeout */ - hdsi->Instance->TCCR[5U] &= ~DSI_TCCR5_BTA_TOCNT; - hdsi->Instance->TCCR[5U] |= HostTimeouts->BTATimeout; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Start the DSI module - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_Start(DSI_HandleTypeDef *hdsi) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Enable the DSI host */ - __HAL_DSI_ENABLE(hdsi); - - /* Enable the DSI wrapper */ - __HAL_DSI_WRAPPER_ENABLE(hdsi); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Stop the DSI module - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_Stop(DSI_HandleTypeDef *hdsi) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Disable the DSI host */ - __HAL_DSI_DISABLE(hdsi); - - /* Disable the DSI wrapper */ - __HAL_DSI_WRAPPER_DISABLE(hdsi); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Refresh the display in command mode - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_Refresh(DSI_HandleTypeDef *hdsi) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Update the display */ - hdsi->Instance->WCR |= DSI_WCR_LTDCEN; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Controls the display color mode in Video mode - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param ColorMode Color mode (full or 8-colors). - * This parameter can be any value of @arg DSI_Color_Mode - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ColorMode(DSI_HandleTypeDef *hdsi, uint32_t ColorMode) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check the parameters */ - assert_param(IS_DSI_COLOR_MODE(ColorMode)); - - /* Update the display color mode */ - hdsi->Instance->WCR &= ~DSI_WCR_COLM; - hdsi->Instance->WCR |= ColorMode; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Control the display shutdown in Video mode - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param Shutdown Shut-down (Display-ON or Display-OFF). - * This parameter can be any value of @arg DSI_ShutDown - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_Shutdown(DSI_HandleTypeDef *hdsi, uint32_t Shutdown) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check the parameters */ - assert_param(IS_DSI_SHUT_DOWN(Shutdown)); - - /* Update the display Shutdown */ - hdsi->Instance->WCR &= ~DSI_WCR_SHTDN; - hdsi->Instance->WCR |= Shutdown; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief write short DCS or short Generic command - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param ChannelID Virtual channel ID. - * @param Mode DSI short packet data type. - * This parameter can be any value of @arg DSI_SHORT_WRITE_PKT_Data_Type. - * @param Param1 DSC command or first generic parameter. - * This parameter can be any value of @arg DSI_DCS_Command or a - * generic command code. - * @param Param2 DSC parameter or second generic parameter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ShortWrite(DSI_HandleTypeDef *hdsi, - uint32_t ChannelID, - uint32_t Mode, - uint32_t Param1, - uint32_t Param2) -{ - HAL_StatusTypeDef status; - /* Check the parameters */ - assert_param(IS_DSI_SHORT_WRITE_PACKET_TYPE(Mode)); - - /* Process locked */ - __HAL_LOCK(hdsi); - - status = DSI_ShortWrite(hdsi, ChannelID, Mode, Param1, Param2); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return status; -} - -/** - * @brief write long DCS or long Generic command - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param ChannelID Virtual channel ID. - * @param Mode DSI long packet data type. - * This parameter can be any value of @arg DSI_LONG_WRITE_PKT_Data_Type. - * @param NbParams Number of parameters. - * @param Param1 DSC command or first generic parameter. - * This parameter can be any value of @arg DSI_DCS_Command or a - * generic command code - * @param ParametersTable Pointer to parameter values table. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_LongWrite(DSI_HandleTypeDef *hdsi, - uint32_t ChannelID, - uint32_t Mode, - uint32_t NbParams, - uint32_t Param1, - uint8_t *ParametersTable) -{ - uint32_t uicounter, nbBytes, count; - uint32_t tickstart; - uint32_t fifoword; - uint8_t *pparams = ParametersTable; - - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check the parameters */ - assert_param(IS_DSI_LONG_WRITE_PACKET_TYPE(Mode)); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait for Command FIFO Empty */ - while ((hdsi->Instance->GPSR & DSI_GPSR_CMDFE) == 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - - /* Set the DCS code on payload byte 1, and the other parameters on the write FIFO command*/ - fifoword = Param1; - nbBytes = (NbParams < 3U) ? NbParams : 3U; - - for (count = 0U; count < nbBytes; count++) - { - fifoword |= (((uint32_t)(*(pparams + count))) << (8U + (8U * count))); - } - hdsi->Instance->GPDR = fifoword; - - uicounter = NbParams - nbBytes; - pparams += nbBytes; - /* Set the Next parameters on the write FIFO command*/ - while (uicounter != 0U) - { - nbBytes = (uicounter < 4U) ? uicounter : 4U; - fifoword = 0U; - for (count = 0U; count < nbBytes; count++) - { - fifoword |= (((uint32_t)(*(pparams + count))) << (8U * count)); - } - hdsi->Instance->GPDR = fifoword; - - uicounter -= nbBytes; - pparams += nbBytes; - } - - /* Configure the packet to send a long DCS command */ - DSI_ConfigPacketHeader(hdsi->Instance, - ChannelID, - Mode, - ((NbParams + 1U) & 0x00FFU), - (((NbParams + 1U) & 0xFF00U) >> 8U)); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Read command (DCS or generic) - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param ChannelNbr Virtual channel ID - * @param Array pointer to a buffer to store the payload of a read back operation. - * @param Size Data size to be read (in byte). - * @param Mode DSI read packet data type. - * This parameter can be any value of @arg DSI_SHORT_READ_PKT_Data_Type. - * @param DCSCmd DCS get/read command. - * @param ParametersTable Pointer to parameter values table. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_Read(DSI_HandleTypeDef *hdsi, - uint32_t ChannelNbr, - uint8_t *Array, - uint32_t Size, - uint32_t Mode, - uint32_t DCSCmd, - uint8_t *ParametersTable) -{ - uint32_t tickstart; - uint8_t *pdata = Array; - uint32_t datasize = Size; - uint32_t fifoword; - uint32_t nbbytes; - uint32_t count; - - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check the parameters */ - assert_param(IS_DSI_READ_PACKET_TYPE(Mode)); - - if (datasize > 2U) - { - /* set max return packet size */ - if (DSI_ShortWrite(hdsi, ChannelNbr, DSI_MAX_RETURN_PKT_SIZE, ((datasize) & 0xFFU), - (((datasize) >> 8U) & 0xFFU)) != HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - } - - /* Configure the packet to read command */ - if (Mode == DSI_DCS_SHORT_PKT_READ) - { - DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, DCSCmd, 0U); - } - else if (Mode == DSI_GEN_SHORT_PKT_READ_P0) - { - DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, 0U, 0U); - } - else if (Mode == DSI_GEN_SHORT_PKT_READ_P1) - { - DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, ParametersTable[0U], 0U); - } - else if (Mode == DSI_GEN_SHORT_PKT_READ_P2) - { - DSI_ConfigPacketHeader(hdsi->Instance, ChannelNbr, Mode, ParametersTable[0U], ParametersTable[1U]); - } - else - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* If DSI fifo is not empty, read requested bytes */ - while (((int32_t)(datasize)) > 0) - { - if ((hdsi->Instance->GPSR & DSI_GPSR_PRDFE) == 0U) - { - fifoword = hdsi->Instance->GPDR; - nbbytes = (datasize < 4U) ? datasize : 4U; - - for (count = 0U; count < nbbytes; count++) - { - *pdata = (uint8_t)(fifoword >> (8U * count)); - pdata++; - datasize--; - } - } - - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Enter the ULPM (Ultra Low Power Mode) with the D-PHY PLL running - * (only data lanes are in ULPM) - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_EnterULPMData(DSI_HandleTypeDef *hdsi) -{ - uint32_t tickstart; - - /* Process locked */ - __HAL_LOCK(hdsi); - - /* ULPS Request on Data Lanes */ - hdsi->Instance->PUCR |= DSI_PUCR_URDL; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until the D-PHY active lanes enter into ULPM */ - if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE) - { - while ((hdsi->Instance->PSR & DSI_PSR_UAN0) != 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - } - else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES) - { - while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1)) != 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Exit the ULPM (Ultra Low Power Mode) with the D-PHY PLL running - * (only data lanes are in ULPM) - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ExitULPMData(DSI_HandleTypeDef *hdsi) -{ - uint32_t tickstart; - - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Exit ULPS on Data Lanes */ - hdsi->Instance->PUCR |= DSI_PUCR_UEDL; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until all active lanes exit ULPM */ - if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE) - { - while ((hdsi->Instance->PSR & DSI_PSR_UAN0) != DSI_PSR_UAN0) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - } - else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES) - { - while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1)) != (DSI_PSR_UAN0 | DSI_PSR_UAN1)) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - - /* wait for 1 ms*/ - HAL_Delay(1U); - - /* De-assert the ULPM requests and the ULPM exit bits */ - hdsi->Instance->PUCR = 0U; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Enter the ULPM (Ultra Low Power Mode) with the D-PHY PLL turned off - * (both data and clock lanes are in ULPM) - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_EnterULPM(DSI_HandleTypeDef *hdsi) -{ - uint32_t tickstart; - - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Clock lane configuration: no more HS request */ - hdsi->Instance->CLCR &= ~DSI_CLCR_DPCC; - - /* Use system PLL as byte lane clock source before stopping DSIPHY clock source */ - __HAL_RCC_DSI_CONFIG(RCC_DSICLKSOURCE_PLLR); - - /* ULPS Request on Clock and Data Lanes */ - hdsi->Instance->PUCR |= (DSI_PUCR_URCL | DSI_PUCR_URDL); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until all active lanes exit ULPM */ - if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE) - { - while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UANC)) != 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - } - else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES) - { - while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1 | DSI_PSR_UANC)) != 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - - /* Turn off the DSI PLL */ - __HAL_DSI_PLL_DISABLE(hdsi); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Exit the ULPM (Ultra Low Power Mode) with the D-PHY PLL turned off - * (both data and clock lanes are in ULPM) - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ExitULPM(DSI_HandleTypeDef *hdsi) -{ - uint32_t tickstart; - - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Turn on the DSI PLL */ - __HAL_DSI_PLL_ENABLE(hdsi); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait for the lock of the PLL */ - while (__HAL_DSI_GET_FLAG(hdsi, DSI_FLAG_PLLLS) == 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - - /* Exit ULPS on Clock and Data Lanes */ - hdsi->Instance->PUCR |= (DSI_PUCR_UECL | DSI_PUCR_UEDL); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until all active lanes exit ULPM */ - if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_ONE_DATA_LANE) - { - while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UANC)) != (DSI_PSR_UAN0 | DSI_PSR_UANC)) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - } - else if ((hdsi->Instance->PCONFR & DSI_PCONFR_NL) == DSI_TWO_DATA_LANES) - { - while ((hdsi->Instance->PSR & (DSI_PSR_UAN0 | DSI_PSR_UAN1 | DSI_PSR_UANC)) != (DSI_PSR_UAN0 | DSI_PSR_UAN1 | - DSI_PSR_UANC)) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > DSI_TIMEOUT_VALUE) - { - /* Process Unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_TIMEOUT; - } - } - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - - /* wait for 1 ms */ - HAL_Delay(1U); - - /* De-assert the ULPM requests and the ULPM exit bits */ - hdsi->Instance->PUCR = 0U; - - /* Switch the lanbyteclock source in the RCC from system PLL to D-PHY */ - __HAL_RCC_DSI_CONFIG(RCC_DSICLKSOURCE_DSIPHY); - - /* Restore clock lane configuration to HS */ - hdsi->Instance->CLCR |= DSI_CLCR_DPCC; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Start test pattern generation - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param Mode Pattern generator mode - * This parameter can be one of the following values: - * 0 : Color bars (horizontal or vertical) - * 1 : BER pattern (vertical only) - * @param Orientation Pattern generator orientation - * This parameter can be one of the following values: - * 0 : Vertical color bars - * 1 : Horizontal color bars - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_PatternGeneratorStart(DSI_HandleTypeDef *hdsi, uint32_t Mode, uint32_t Orientation) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Configure pattern generator mode and orientation */ - hdsi->Instance->VMCR &= ~(DSI_VMCR_PGM | DSI_VMCR_PGO); - hdsi->Instance->VMCR |= ((Mode << 20U) | (Orientation << 24U)); - - /* Enable pattern generator by setting PGE bit */ - hdsi->Instance->VMCR |= DSI_VMCR_PGE; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Stop test pattern generation - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_PatternGeneratorStop(DSI_HandleTypeDef *hdsi) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Disable pattern generator by clearing PGE bit */ - hdsi->Instance->VMCR &= ~DSI_VMCR_PGE; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Set Slew-Rate And Delay Tuning - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param CommDelay Communication delay to be adjusted. - * This parameter can be any value of @arg DSI_Communication_Delay - * @param Lane select between clock or data lanes. - * This parameter can be any value of @arg DSI_Lane_Group - * @param Value Custom value of the slew-rate or delay - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_SetSlewRateAndDelayTuning(DSI_HandleTypeDef *hdsi, uint32_t CommDelay, uint32_t Lane, - uint32_t Value) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_DSI_COMMUNICATION_DELAY(CommDelay)); - assert_param(IS_DSI_LANE_GROUP(Lane)); - - switch (CommDelay) - { - case DSI_SLEW_RATE_HSTX: - if (Lane == DSI_CLOCK_LANE) - { - /* High-Speed Transmission Slew Rate Control on Clock Lane */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_HSTXSRCCL; - hdsi->Instance->WPCR[1U] |= Value << 16U; - } - else if (Lane == DSI_DATA_LANES) - { - /* High-Speed Transmission Slew Rate Control on Data Lanes */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_HSTXSRCDL; - hdsi->Instance->WPCR[1U] |= Value << 18U; - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - break; - case DSI_SLEW_RATE_LPTX: - if (Lane == DSI_CLOCK_LANE) - { - /* Low-Power transmission Slew Rate Compensation on Clock Lane */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_LPSRCCL; - hdsi->Instance->WPCR[1U] |= Value << 6U; - } - else if (Lane == DSI_DATA_LANES) - { - /* Low-Power transmission Slew Rate Compensation on Data Lanes */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_LPSRCDL; - hdsi->Instance->WPCR[1U] |= Value << 8U; - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - break; - case DSI_HS_DELAY: - if (Lane == DSI_CLOCK_LANE) - { - /* High-Speed Transmission Delay on Clock Lane */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_HSTXDCL; - hdsi->Instance->WPCR[1U] |= Value; - } - else if (Lane == DSI_DATA_LANES) - { - /* High-Speed Transmission Delay on Data Lanes */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_HSTXDDL; - hdsi->Instance->WPCR[1U] |= Value << 2U; - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - break; - default: - break; - } - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Low-Power Reception Filter Tuning - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param Frequency cutoff frequency of low-pass filter at the input of LPRX - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_SetLowPowerRXFilter(DSI_HandleTypeDef *hdsi, uint32_t Frequency) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Low-Power RX low-pass Filtering Tuning */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_LPRXFT; - hdsi->Instance->WPCR[1U] |= Frequency << 25U; - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Activate an additional current path on all lanes to meet the SDDTx parameter - * defined in the MIPI D-PHY specification - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param State ENABLE or DISABLE - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_SetSDD(DSI_HandleTypeDef *hdsi, FunctionalState State) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_FUNCTIONAL_STATE(State)); - - /* Activate/Disactivate additional current path on all lanes */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_SDDC; - hdsi->Instance->WPCR[1U] |= ((uint32_t)State << 12U); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Custom lane pins configuration - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param CustomLane Function to be applied on selected lane. - * This parameter can be any value of @arg DSI_CustomLane - * @param Lane select between clock or data lane 0 or data lane 1. - * This parameter can be any value of @arg DSI_Lane_Select - * @param State ENABLE or DISABLE - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_SetLanePinsConfiguration(DSI_HandleTypeDef *hdsi, uint32_t CustomLane, uint32_t Lane, - FunctionalState State) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_DSI_CUSTOM_LANE(CustomLane)); - assert_param(IS_DSI_LANE(Lane)); - assert_param(IS_FUNCTIONAL_STATE(State)); - - switch (CustomLane) - { - case DSI_SWAP_LANE_PINS: - if (Lane == DSI_CLK_LANE) - { - /* Swap pins on clock lane */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_SWCL; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 6U); - } - else if (Lane == DSI_DATA_LANE0) - { - /* Swap pins on data lane 0 */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_SWDL0; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 7U); - } - else if (Lane == DSI_DATA_LANE1) - { - /* Swap pins on data lane 1 */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_SWDL1; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 8U); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - break; - case DSI_INVERT_HS_SIGNAL: - if (Lane == DSI_CLK_LANE) - { - /* Invert HS signal on clock lane */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_HSICL; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 9U); - } - else if (Lane == DSI_DATA_LANE0) - { - /* Invert HS signal on data lane 0 */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_HSIDL0; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 10U); - } - else if (Lane == DSI_DATA_LANE1) - { - /* Invert HS signal on data lane 1 */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_HSIDL1; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 11U); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - break; - default: - break; - } - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Set custom timing for the PHY - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param Timing PHY timing to be adjusted. - * This parameter can be any value of @arg DSI_PHY_Timing - * @param State ENABLE or DISABLE - * @param Value Custom value of the timing - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_SetPHYTimings(DSI_HandleTypeDef *hdsi, uint32_t Timing, FunctionalState State, uint32_t Value) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_DSI_PHY_TIMING(Timing)); - assert_param(IS_FUNCTIONAL_STATE(State)); - - switch (Timing) - { - case DSI_TCLK_POST: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TCLKPOSTEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 27U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[4U] &= ~DSI_WPCR4_TCLKPOST; - hdsi->Instance->WPCR[4U] |= Value & DSI_WPCR4_TCLKPOST; - } - - break; - case DSI_TLPX_CLK: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TLPXCEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 26U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[3U] &= ~DSI_WPCR3_TLPXC; - hdsi->Instance->WPCR[3U] |= (Value << 24U) & DSI_WPCR3_TLPXC; - } - - break; - case DSI_THS_EXIT: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_THSEXITEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 25U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[3U] &= ~DSI_WPCR3_THSEXIT; - hdsi->Instance->WPCR[3U] |= (Value << 16U) & DSI_WPCR3_THSEXIT; - } - - break; - case DSI_TLPX_DATA: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TLPXDEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 24U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[3U] &= ~DSI_WPCR3_TLPXD; - hdsi->Instance->WPCR[3U] |= (Value << 8U) & DSI_WPCR3_TLPXD; - } - - break; - case DSI_THS_ZERO: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_THSZEROEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 23U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[3U] &= ~DSI_WPCR3_THSZERO; - hdsi->Instance->WPCR[3U] |= Value & DSI_WPCR3_THSZERO; - } - - break; - case DSI_THS_TRAIL: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_THSTRAILEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 22U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[2U] &= ~DSI_WPCR2_THSTRAIL; - hdsi->Instance->WPCR[2U] |= (Value << 24U) & DSI_WPCR2_THSTRAIL; - } - - break; - case DSI_THS_PREPARE: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_THSPREPEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 21U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[2U] &= ~DSI_WPCR2_THSPREP; - hdsi->Instance->WPCR[2U] |= (Value << 16U) & DSI_WPCR2_THSPREP; - } - - break; - case DSI_TCLK_ZERO: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TCLKZEROEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 20U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[2U] &= ~DSI_WPCR2_TCLKZERO; - hdsi->Instance->WPCR[2U] |= (Value << 8U) & DSI_WPCR2_TCLKZERO; - } - - break; - case DSI_TCLK_PREPARE: - /* Enable/Disable custom timing setting */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TCLKPREPEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 19U); - - if (State != DISABLE) - { - /* Set custom value */ - hdsi->Instance->WPCR[2U] &= ~DSI_WPCR2_TCLKPREP; - hdsi->Instance->WPCR[2U] |= Value & DSI_WPCR2_TCLKPREP; - } - - break; - default: - break; - } - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Force the Clock/Data Lane in TX Stop Mode - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param Lane select between clock or data lanes. - * This parameter can be any value of @arg DSI_Lane_Group - * @param State ENABLE or DISABLE - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ForceTXStopMode(DSI_HandleTypeDef *hdsi, uint32_t Lane, FunctionalState State) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_DSI_LANE_GROUP(Lane)); - assert_param(IS_FUNCTIONAL_STATE(State)); - - if (Lane == DSI_CLOCK_LANE) - { - /* Force/Unforce the Clock Lane in TX Stop Mode */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_FTXSMCL; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 12U); - } - else if (Lane == DSI_DATA_LANES) - { - /* Force/Unforce the Data Lanes in TX Stop Mode */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_FTXSMDL; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 13U); - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_ERROR; - } - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Force LP Receiver in Low-Power Mode - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param State ENABLE or DISABLE - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ForceRXLowPower(DSI_HandleTypeDef *hdsi, FunctionalState State) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_FUNCTIONAL_STATE(State)); - - /* Force/Unforce LP Receiver in Low-Power Mode */ - hdsi->Instance->WPCR[1U] &= ~DSI_WPCR1_FLPRXLPM; - hdsi->Instance->WPCR[1U] |= ((uint32_t)State << 22U); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Force Data Lanes in RX Mode after a BTA - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param State ENABLE or DISABLE - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_ForceDataLanesInRX(DSI_HandleTypeDef *hdsi, FunctionalState State) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_FUNCTIONAL_STATE(State)); - - /* Force Data Lanes in RX Mode */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_TDDL; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 16U); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Enable a pull-down on the lanes to prevent from floating states when unused - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param State ENABLE or DISABLE - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_SetPullDown(DSI_HandleTypeDef *hdsi, FunctionalState State) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_FUNCTIONAL_STATE(State)); - - /* Enable/Disable pull-down on lanes */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_PDEN; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 18U); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @brief Switch off the contention detection on data lanes - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @param State ENABLE or DISABLE - * @retval HAL status - */ -HAL_StatusTypeDef HAL_DSI_SetContentionDetectionOff(DSI_HandleTypeDef *hdsi, FunctionalState State) -{ - /* Process locked */ - __HAL_LOCK(hdsi); - - /* Check function parameters */ - assert_param(IS_FUNCTIONAL_STATE(State)); - - /* Contention Detection on Data Lanes OFF */ - hdsi->Instance->WPCR[0U] &= ~DSI_WPCR0_CDOFFDL; - hdsi->Instance->WPCR[0U] |= ((uint32_t)State << 14U); - - /* Process unlocked */ - __HAL_UNLOCK(hdsi); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup DSI_Group4 Peripheral State and Errors functions - * @brief Peripheral State and Errors functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Check the DSI state. - (+) Get error code. - -@endverbatim - * @{ - */ - -/** - * @brief Return the DSI state - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval HAL state - */ -HAL_DSI_StateTypeDef HAL_DSI_GetState(DSI_HandleTypeDef *hdsi) -{ - return hdsi->State; -} - -/** - * @brief Return the DSI error code - * @param hdsi pointer to a DSI_HandleTypeDef structure that contains - * the configuration information for the DSI. - * @retval DSI Error Code - */ -uint32_t HAL_DSI_GetError(DSI_HandleTypeDef *hdsi) -{ - /* Get the error code */ - return hdsi->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DSI */ - -#endif /* HAL_DSI_MODULE_ENABLED */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c deleted file mode 100644 index dbaeb3eee437d88..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_eth.c +++ /dev/null @@ -1,2309 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_eth.c - * @author MCD Application Team - * @brief ETH HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Ethernet (ETH) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Errors functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#)Declare a ETH_HandleTypeDef handle structure, for example: - ETH_HandleTypeDef heth; - - (#)Fill parameters of Init structure in heth handle - - (#)Call HAL_ETH_Init() API to initialize the Ethernet peripheral (MAC, DMA, ...) - - (#)Initialize the ETH low level resources through the HAL_ETH_MspInit() API: - (##) Enable the Ethernet interface clock using - (+++) __HAL_RCC_ETHMAC_CLK_ENABLE(); - (+++) __HAL_RCC_ETHMACTX_CLK_ENABLE(); - (+++) __HAL_RCC_ETHMACRX_CLK_ENABLE(); - - (##) Initialize the related GPIO clocks - (##) Configure Ethernet pin-out - (##) Configure Ethernet NVIC interrupt (IT mode) - - (#)Initialize Ethernet DMA Descriptors in chain mode and point to allocated buffers: - (##) HAL_ETH_DMATxDescListInit(); for Transmission process - (##) HAL_ETH_DMARxDescListInit(); for Reception process - - (#)Enable MAC and DMA transmission and reception: - (##) HAL_ETH_Start(); - - (#)Prepare ETH DMA TX Descriptors and give the hand to ETH DMA to transfer - the frame to MAC TX FIFO: - (##) HAL_ETH_TransmitFrame(); - - (#)Poll for a received frame in ETH RX DMA Descriptors and get received - frame parameters - (##) HAL_ETH_GetReceivedFrame(); (should be called into an infinite loop) - - (#) Get a received frame when an ETH RX interrupt occurs: - (##) HAL_ETH_GetReceivedFrame_IT(); (called in IT mode only) - - (#) Communicate with external PHY device: - (##) Read a specific register from the PHY - HAL_ETH_ReadPHYRegister(); - (##) Write data to a specific RHY register: - HAL_ETH_WritePHYRegister(); - - (#) Configure the Ethernet MAC after ETH peripheral initialization - HAL_ETH_ConfigMAC(); all MAC parameters should be filled. - - (#) Configure the Ethernet DMA after ETH peripheral initialization - HAL_ETH_ConfigDMA(); all DMA parameters should be filled. - - -@- The PTP protocol and the DMA descriptors ring mode are not supported - in this driver -*** Callback registration *** - ============================================= - - The compilation define USE_HAL_ETH_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Function @ref HAL_ETH_RegisterCallback() to register an interrupt callback. - - Function @ref HAL_ETH_RegisterCallback() allows to register following callbacks: - (+) TxCpltCallback : Tx Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) DMAErrorCallback : DMA Error Callback. - (+) MspInitCallback : MspInit Callback. - (+) MspDeInitCallback: MspDeInit Callback. - - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function @ref HAL_ETH_UnRegisterCallback() to reset a callback to the default - weak function. - @ref HAL_ETH_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxCpltCallback : Tx Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) DMAErrorCallback : DMA Error Callback. - (+) MspInitCallback : MspInit Callback. - (+) MspDeInitCallback: MspDeInit Callback. - - By default, after the HAL_ETH_Init and when the state is HAL_ETH_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples @ref HAL_ETH_TxCpltCallback(), @ref HAL_ETH_RxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak function in the HAL_ETH_Init/ @ref HAL_ETH_DeInit only when - these callbacks are null (not registered beforehand). - if not, MspInit or MspDeInit are not null, the HAL_ETH_Init/ @ref HAL_ETH_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in HAL_ETH_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_ETH_STATE_READY or HAL_ETH_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_ETH_RegisterCallback() before calling @ref HAL_ETH_DeInit - or HAL_ETH_Init function. - - When The compilation define USE_HAL_ETH_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup ETH ETH - * @brief ETH HAL module driver - * @{ - */ - -#ifdef HAL_ETH_MODULE_ENABLED - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup ETH_Private_Constants ETH Private Constants - * @{ - */ -#define ETH_TIMEOUT_SWRESET 500U -#define ETH_TIMEOUT_LINKED_STATE 5000U -#define ETH_TIMEOUT_AUTONEGO_COMPLETED 5000U - -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup ETH_Private_Functions ETH Private Functions - * @{ - */ -static void ETH_MACDMAConfig(ETH_HandleTypeDef *heth, uint32_t err); -static void ETH_MACAddressConfig(ETH_HandleTypeDef *heth, uint32_t MacAddr, uint8_t *Addr); -static void ETH_MACReceptionEnable(ETH_HandleTypeDef *heth); -static void ETH_MACReceptionDisable(ETH_HandleTypeDef *heth); -static void ETH_MACTransmissionEnable(ETH_HandleTypeDef *heth); -static void ETH_MACTransmissionDisable(ETH_HandleTypeDef *heth); -static void ETH_DMATransmissionEnable(ETH_HandleTypeDef *heth); -static void ETH_DMATransmissionDisable(ETH_HandleTypeDef *heth); -static void ETH_DMAReceptionEnable(ETH_HandleTypeDef *heth); -static void ETH_DMAReceptionDisable(ETH_HandleTypeDef *heth); -static void ETH_FlushTransmitFIFO(ETH_HandleTypeDef *heth); -static void ETH_Delay(uint32_t mdelay); -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -static void ETH_InitCallbacksToDefault(ETH_HandleTypeDef *heth); -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup ETH_Exported_Functions ETH Exported Functions - * @{ - */ - -/** @defgroup ETH_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * - @verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the Ethernet peripheral - (+) De-initialize the Ethernet peripheral - - @endverbatim - * @{ - */ - -/** - * @brief Initializes the Ethernet MAC and DMA according to default - * parameters. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_Init(ETH_HandleTypeDef *heth) -{ - uint32_t tmpreg1 = 0U, phyreg = 0U; - uint32_t hclk = 60000000U; - uint32_t tickstart = 0U; - uint32_t err = ETH_SUCCESS; - - /* Check the ETH peripheral state */ - if(heth == NULL) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_ETH_AUTONEGOTIATION(heth->Init.AutoNegotiation)); - assert_param(IS_ETH_RX_MODE(heth->Init.RxMode)); - assert_param(IS_ETH_CHECKSUM_MODE(heth->Init.ChecksumMode)); - assert_param(IS_ETH_MEDIA_INTERFACE(heth->Init.MediaInterface)); - - if(heth->State == HAL_ETH_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - heth->Lock = HAL_UNLOCKED; -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) - ETH_InitCallbacksToDefault(heth); - - if(heth->MspInitCallback == NULL) - { - /* Init the low level hardware : GPIO, CLOCK, NVIC. */ - heth->MspInitCallback = HAL_ETH_MspInit; - } - heth->MspInitCallback(heth); - -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC. */ - HAL_ETH_MspInit(heth); -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - } - - /* Enable SYSCFG Clock */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - - /* Select MII or RMII Mode*/ - SYSCFG->PMC &= ~(SYSCFG_PMC_MII_RMII_SEL); - SYSCFG->PMC |= (uint32_t)heth->Init.MediaInterface; - - /* Ethernet Software reset */ - /* Set the SWR bit: resets all MAC subsystem internal registers and logic */ - /* After reset all the registers holds their respective reset values */ - (heth->Instance)->DMABMR |= ETH_DMABMR_SR; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait for software reset */ - while (((heth->Instance)->DMABMR & ETH_DMABMR_SR) != (uint32_t)RESET) - { - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > ETH_TIMEOUT_SWRESET) - { - heth->State= HAL_ETH_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Note: The SWR is not performed if the ETH_RX_CLK or the ETH_TX_CLK are - not available, please check your external PHY or the IO configuration */ - return HAL_TIMEOUT; - } - } - - /*-------------------------------- MAC Initialization ----------------------*/ - /* Get the ETHERNET MACMIIAR value */ - tmpreg1 = (heth->Instance)->MACMIIAR; - /* Clear CSR Clock Range CR[2:0] bits */ - tmpreg1 &= ETH_MACMIIAR_CR_MASK; - - /* Get hclk frequency value */ - hclk = HAL_RCC_GetHCLKFreq(); - - /* Set CR bits depending on hclk value */ - if((hclk >= 20000000U)&&(hclk < 35000000U)) - { - /* CSR Clock Range between 20-35 MHz */ - tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div16; - } - else if((hclk >= 35000000U)&&(hclk < 60000000U)) - { - /* CSR Clock Range between 35-60 MHz */ - tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div26; - } - else if((hclk >= 60000000U)&&(hclk < 100000000U)) - { - /* CSR Clock Range between 60-100 MHz */ - tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div42; - } - else if((hclk >= 100000000U)&&(hclk < 150000000U)) - { - /* CSR Clock Range between 100-150 MHz */ - tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div62; - } - else /* ((hclk >= 150000000)&&(hclk <= 183000000)) */ - { - /* CSR Clock Range between 150-183 MHz */ - tmpreg1 |= (uint32_t)ETH_MACMIIAR_CR_Div102; - } - - /* Write to ETHERNET MAC MIIAR: Configure the ETHERNET CSR Clock Range */ - (heth->Instance)->MACMIIAR = (uint32_t)tmpreg1; - - /*-------------------- PHY initialization and configuration ----------------*/ - /* Put the PHY in reset mode */ - if((HAL_ETH_WritePHYRegister(heth, PHY_BCR, PHY_RESET)) != HAL_OK) - { - /* In case of write timeout */ - err = ETH_ERROR; - - /* Config MAC and DMA */ - ETH_MACDMAConfig(heth, err); - - /* Set the ETH peripheral state to READY */ - heth->State = HAL_ETH_STATE_READY; - - /* Return HAL_ERROR */ - return HAL_ERROR; - } - - /* Delay to assure PHY reset */ - HAL_Delay(PHY_RESET_DELAY); - - if((heth->Init).AutoNegotiation != ETH_AUTONEGOTIATION_DISABLE) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* We wait for linked status */ - do - { - HAL_ETH_ReadPHYRegister(heth, PHY_BSR, &phyreg); - - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > ETH_TIMEOUT_LINKED_STATE) - { - /* In case of write timeout */ - err = ETH_ERROR; - - /* Config MAC and DMA */ - ETH_MACDMAConfig(heth, err); - - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - return HAL_TIMEOUT; - } - } while (((phyreg & PHY_LINKED_STATUS) != PHY_LINKED_STATUS)); - - - /* Enable Auto-Negotiation */ - if((HAL_ETH_WritePHYRegister(heth, PHY_BCR, PHY_AUTONEGOTIATION)) != HAL_OK) - { - /* In case of write timeout */ - err = ETH_ERROR; - - /* Config MAC and DMA */ - ETH_MACDMAConfig(heth, err); - - /* Set the ETH peripheral state to READY */ - heth->State = HAL_ETH_STATE_READY; - - /* Return HAL_ERROR */ - return HAL_ERROR; - } - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until the auto-negotiation will be completed */ - do - { - HAL_ETH_ReadPHYRegister(heth, PHY_BSR, &phyreg); - - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > ETH_TIMEOUT_AUTONEGO_COMPLETED) - { - /* In case of write timeout */ - err = ETH_ERROR; - - /* Config MAC and DMA */ - ETH_MACDMAConfig(heth, err); - - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - return HAL_TIMEOUT; - } - - } while (((phyreg & PHY_AUTONEGO_COMPLETE) != PHY_AUTONEGO_COMPLETE)); - - /* Read the result of the auto-negotiation */ - if((HAL_ETH_ReadPHYRegister(heth, PHY_SR, &phyreg)) != HAL_OK) - { - /* In case of write timeout */ - err = ETH_ERROR; - - /* Config MAC and DMA */ - ETH_MACDMAConfig(heth, err); - - /* Set the ETH peripheral state to READY */ - heth->State = HAL_ETH_STATE_READY; - - /* Return HAL_ERROR */ - return HAL_ERROR; - } - - /* Configure the MAC with the Duplex Mode fixed by the auto-negotiation process */ - if((phyreg & PHY_DUPLEX_STATUS) != (uint32_t)RESET) - { - /* Set Ethernet duplex mode to Full-duplex following the auto-negotiation */ - (heth->Init).DuplexMode = ETH_MODE_FULLDUPLEX; - } - else - { - /* Set Ethernet duplex mode to Half-duplex following the auto-negotiation */ - (heth->Init).DuplexMode = ETH_MODE_HALFDUPLEX; - } - /* Configure the MAC with the speed fixed by the auto-negotiation process */ - if((phyreg & PHY_SPEED_STATUS) == PHY_SPEED_STATUS) - { - /* Set Ethernet speed to 10M following the auto-negotiation */ - (heth->Init).Speed = ETH_SPEED_10M; - } - else - { - /* Set Ethernet speed to 100M following the auto-negotiation */ - (heth->Init).Speed = ETH_SPEED_100M; - } - } - else /* AutoNegotiation Disable */ - { - /* Check parameters */ - assert_param(IS_ETH_SPEED(heth->Init.Speed)); - assert_param(IS_ETH_DUPLEX_MODE(heth->Init.DuplexMode)); - - /* Set MAC Speed and Duplex Mode */ - if(HAL_ETH_WritePHYRegister(heth, PHY_BCR, ((uint16_t)((heth->Init).DuplexMode >> 3U) | - (uint16_t)((heth->Init).Speed >> 1U))) != HAL_OK) - { - /* In case of write timeout */ - err = ETH_ERROR; - - /* Config MAC and DMA */ - ETH_MACDMAConfig(heth, err); - - /* Set the ETH peripheral state to READY */ - heth->State = HAL_ETH_STATE_READY; - - /* Return HAL_ERROR */ - return HAL_ERROR; - } - - /* Delay to assure PHY configuration */ - HAL_Delay(PHY_CONFIG_DELAY); - } - - /* Config MAC and DMA */ - ETH_MACDMAConfig(heth, err); - - /* Set ETH HAL State to Ready */ - heth->State= HAL_ETH_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief De-Initializes the ETH peripheral. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_DeInit(ETH_HandleTypeDef *heth) -{ - /* Set the ETH peripheral state to BUSY */ - heth->State = HAL_ETH_STATE_BUSY; - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) - if(heth->MspDeInitCallback == NULL) - { - heth->MspDeInitCallback = HAL_ETH_MspDeInit; - } - /* De-Init the low level hardware : GPIO, CLOCK, NVIC. */ - heth->MspDeInitCallback(heth); -#else - /* De-Init the low level hardware : GPIO, CLOCK, NVIC. */ - HAL_ETH_MspDeInit(heth); -#endif - - /* Set ETH HAL state to Disabled */ - heth->State= HAL_ETH_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initializes the DMA Tx descriptors in chain mode. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param DMATxDescTab Pointer to the first Tx desc list - * @param TxBuff Pointer to the first TxBuffer list - * @param TxBuffCount Number of the used Tx desc in the list - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_DMATxDescListInit(ETH_HandleTypeDef *heth, ETH_DMADescTypeDef *DMATxDescTab, uint8_t *TxBuff, uint32_t TxBuffCount) -{ - uint32_t i = 0U; - ETH_DMADescTypeDef *dmatxdesc; - - /* Process Locked */ - __HAL_LOCK(heth); - - /* Set the ETH peripheral state to BUSY */ - heth->State = HAL_ETH_STATE_BUSY; - - /* Set the DMATxDescToSet pointer with the first one of the DMATxDescTab list */ - heth->TxDesc = DMATxDescTab; - - /* Fill each DMATxDesc descriptor with the right values */ - for(i=0U; i < TxBuffCount; i++) - { - /* Get the pointer on the ith member of the Tx Desc list */ - dmatxdesc = DMATxDescTab + i; - - /* Set Second Address Chained bit */ - dmatxdesc->Status = ETH_DMATXDESC_TCH; - - /* Set Buffer1 address pointer */ - dmatxdesc->Buffer1Addr = (uint32_t)(&TxBuff[i*ETH_TX_BUF_SIZE]); - - if ((heth->Init).ChecksumMode == ETH_CHECKSUM_BY_HARDWARE) - { - /* Set the DMA Tx descriptors checksum insertion */ - dmatxdesc->Status |= ETH_DMATXDESC_CHECKSUMTCPUDPICMPFULL; - } - - /* Initialize the next descriptor with the Next Descriptor Polling Enable */ - if(i < (TxBuffCount-1U)) - { - /* Set next descriptor address register with next descriptor base address */ - dmatxdesc->Buffer2NextDescAddr = (uint32_t)(DMATxDescTab+i+1U); - } - else - { - /* For last descriptor, set next descriptor address register equal to the first descriptor base address */ - dmatxdesc->Buffer2NextDescAddr = (uint32_t) DMATxDescTab; - } - } - - /* Set Transmit Descriptor List Address Register */ - (heth->Instance)->DMATDLAR = (uint32_t) DMATxDescTab; - - /* Set ETH HAL State to Ready */ - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initializes the DMA Rx descriptors in chain mode. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param DMARxDescTab Pointer to the first Rx desc list - * @param RxBuff Pointer to the first RxBuffer list - * @param RxBuffCount Number of the used Rx desc in the list - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_DMARxDescListInit(ETH_HandleTypeDef *heth, ETH_DMADescTypeDef *DMARxDescTab, uint8_t *RxBuff, uint32_t RxBuffCount) -{ - uint32_t i = 0U; - ETH_DMADescTypeDef *DMARxDesc; - - /* Process Locked */ - __HAL_LOCK(heth); - - /* Set the ETH peripheral state to BUSY */ - heth->State = HAL_ETH_STATE_BUSY; - - /* Set the Ethernet RxDesc pointer with the first one of the DMARxDescTab list */ - heth->RxDesc = DMARxDescTab; - - /* Fill each DMARxDesc descriptor with the right values */ - for(i=0U; i < RxBuffCount; i++) - { - /* Get the pointer on the ith member of the Rx Desc list */ - DMARxDesc = DMARxDescTab+i; - - /* Set Own bit of the Rx descriptor Status */ - DMARxDesc->Status = ETH_DMARXDESC_OWN; - - /* Set Buffer1 size and Second Address Chained bit */ - DMARxDesc->ControlBufferSize = ETH_DMARXDESC_RCH | ETH_RX_BUF_SIZE; - - /* Set Buffer1 address pointer */ - DMARxDesc->Buffer1Addr = (uint32_t)(&RxBuff[i*ETH_RX_BUF_SIZE]); - - if((heth->Init).RxMode == ETH_RXINTERRUPT_MODE) - { - /* Enable Ethernet DMA Rx Descriptor interrupt */ - DMARxDesc->ControlBufferSize &= ~ETH_DMARXDESC_DIC; - } - - /* Initialize the next descriptor with the Next Descriptor Polling Enable */ - if(i < (RxBuffCount-1U)) - { - /* Set next descriptor address register with next descriptor base address */ - DMARxDesc->Buffer2NextDescAddr = (uint32_t)(DMARxDescTab+i+1U); - } - else - { - /* For last descriptor, set next descriptor address register equal to the first descriptor base address */ - DMARxDesc->Buffer2NextDescAddr = (uint32_t)(DMARxDescTab); - } - } - - /* Set Receive Descriptor List Address Register */ - (heth->Instance)->DMARDLAR = (uint32_t) DMARxDescTab; - - /* Set ETH HAL State to Ready */ - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initializes the ETH MSP. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -__weak void HAL_ETH_MspInit(ETH_HandleTypeDef *heth) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(heth); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ETH_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes ETH MSP. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -__weak void HAL_ETH_MspDeInit(ETH_HandleTypeDef *heth) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(heth); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ETH_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User ETH Callback - * To be used instead of the weak predefined callback - * @param heth eth handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_ETH_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_ETH_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_ETH_DMA_ERROR_CB_ID DMA Error Callback ID - * @arg @ref HAL_ETH_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_ETH_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_ETH_RegisterCallback(ETH_HandleTypeDef *heth, HAL_ETH_CallbackIDTypeDef CallbackID, pETH_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(heth); - - if(heth->State == HAL_ETH_STATE_READY) - { - switch (CallbackID) - { - case HAL_ETH_TX_COMPLETE_CB_ID : - heth->TxCpltCallback = pCallback; - break; - - case HAL_ETH_RX_COMPLETE_CB_ID : - heth->RxCpltCallback = pCallback; - break; - - case HAL_ETH_DMA_ERROR_CB_ID : - heth->DMAErrorCallback = pCallback; - break; - - case HAL_ETH_MSPINIT_CB_ID : - heth->MspInitCallback = pCallback; - break; - - case HAL_ETH_MSPDEINIT_CB_ID : - heth->MspDeInitCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if(heth->State == HAL_ETH_STATE_RESET) - { - switch (CallbackID) - { - case HAL_ETH_MSPINIT_CB_ID : - heth->MspInitCallback = pCallback; - break; - - case HAL_ETH_MSPDEINIT_CB_ID : - heth->MspDeInitCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(heth); - - return status; -} - -/** - * @brief Unregister an ETH Callback - * ETH callabck is redirected to the weak predefined callback - * @param heth eth handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_ETH_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_ETH_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_ETH_DMA_ERROR_CB_ID DMA Error Callback ID - * @arg @ref HAL_ETH_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_ETH_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_ETH_UnRegisterCallback(ETH_HandleTypeDef *heth, HAL_ETH_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(heth); - - if(heth->State == HAL_ETH_STATE_READY) - { - switch (CallbackID) - { - case HAL_ETH_TX_COMPLETE_CB_ID : - heth->TxCpltCallback = HAL_ETH_TxCpltCallback; - break; - - case HAL_ETH_RX_COMPLETE_CB_ID : - heth->RxCpltCallback = HAL_ETH_RxCpltCallback; - break; - - case HAL_ETH_DMA_ERROR_CB_ID : - heth->DMAErrorCallback = HAL_ETH_ErrorCallback; - break; - - case HAL_ETH_MSPINIT_CB_ID : - heth->MspInitCallback = HAL_ETH_MspInit; - break; - - case HAL_ETH_MSPDEINIT_CB_ID : - heth->MspDeInitCallback = HAL_ETH_MspDeInit; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if(heth->State == HAL_ETH_STATE_RESET) - { - switch (CallbackID) - { - case HAL_ETH_MSPINIT_CB_ID : - heth->MspInitCallback = HAL_ETH_MspInit; - break; - - case HAL_ETH_MSPDEINIT_CB_ID : - heth->MspDeInitCallback = HAL_ETH_MspDeInit; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(heth); - - return status; -} -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup ETH_Exported_Functions_Group2 IO operation functions - * @brief Data transfers functions - * - @verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Transmit a frame - HAL_ETH_TransmitFrame(); - (+) Receive a frame - HAL_ETH_GetReceivedFrame(); - HAL_ETH_GetReceivedFrame_IT(); - (+) Read from an External PHY register - HAL_ETH_ReadPHYRegister(); - (+) Write to an External PHY register - HAL_ETH_WritePHYRegister(); - - @endverbatim - - * @{ - */ - -/** - * @brief Sends an Ethernet frame. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param FrameLength Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_TransmitFrame(ETH_HandleTypeDef *heth, uint32_t FrameLength) -{ - uint32_t bufcount = 0U, size = 0U, i = 0U; - - /* Process Locked */ - __HAL_LOCK(heth); - - /* Set the ETH peripheral state to BUSY */ - heth->State = HAL_ETH_STATE_BUSY; - - if (FrameLength == 0U) - { - /* Set ETH HAL state to READY */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - return HAL_ERROR; - } - - /* Check if the descriptor is owned by the ETHERNET DMA (when set) or CPU (when reset) */ - if(((heth->TxDesc)->Status & ETH_DMATXDESC_OWN) != (uint32_t)RESET) - { - /* OWN bit set */ - heth->State = HAL_ETH_STATE_BUSY_TX; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - return HAL_ERROR; - } - - /* Get the number of needed Tx buffers for the current frame */ - if (FrameLength > ETH_TX_BUF_SIZE) - { - bufcount = FrameLength/ETH_TX_BUF_SIZE; - if (FrameLength % ETH_TX_BUF_SIZE) - { - bufcount++; - } - } - else - { - bufcount = 1U; - } - if (bufcount == 1U) - { - /* Set LAST and FIRST segment */ - heth->TxDesc->Status |=ETH_DMATXDESC_FS|ETH_DMATXDESC_LS; - /* Set frame size */ - heth->TxDesc->ControlBufferSize = (FrameLength & ETH_DMATXDESC_TBS1); - /* Set Own bit of the Tx descriptor Status: gives the buffer back to ETHERNET DMA */ - heth->TxDesc->Status |= ETH_DMATXDESC_OWN; - /* Point to next descriptor */ - heth->TxDesc= (ETH_DMADescTypeDef *)(heth->TxDesc->Buffer2NextDescAddr); - } - else - { - for (i=0U; i< bufcount; i++) - { - /* Clear FIRST and LAST segment bits */ - heth->TxDesc->Status &= ~(ETH_DMATXDESC_FS | ETH_DMATXDESC_LS); - - if (i == 0U) - { - /* Setting the first segment bit */ - heth->TxDesc->Status |= ETH_DMATXDESC_FS; - } - - /* Program size */ - heth->TxDesc->ControlBufferSize = (ETH_TX_BUF_SIZE & ETH_DMATXDESC_TBS1); - - if (i == (bufcount-1U)) - { - /* Setting the last segment bit */ - heth->TxDesc->Status |= ETH_DMATXDESC_LS; - size = FrameLength - (bufcount-1U)*ETH_TX_BUF_SIZE; - heth->TxDesc->ControlBufferSize = (size & ETH_DMATXDESC_TBS1); - } - - /* Set Own bit of the Tx descriptor Status: gives the buffer back to ETHERNET DMA */ - heth->TxDesc->Status |= ETH_DMATXDESC_OWN; - /* point to next descriptor */ - heth->TxDesc = (ETH_DMADescTypeDef *)(heth->TxDesc->Buffer2NextDescAddr); - } - } - - /* When Tx Buffer unavailable flag is set: clear it and resume transmission */ - if (((heth->Instance)->DMASR & ETH_DMASR_TBUS) != (uint32_t)RESET) - { - /* Clear TBUS ETHERNET DMA flag */ - (heth->Instance)->DMASR = ETH_DMASR_TBUS; - /* Resume DMA transmission*/ - (heth->Instance)->DMATPDR = 0U; - } - - /* Set ETH HAL State to Ready */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Checks for received frames. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_GetReceivedFrame(ETH_HandleTypeDef *heth) -{ - uint32_t framelength = 0U; - - /* Process Locked */ - __HAL_LOCK(heth); - - /* Check the ETH state to BUSY */ - heth->State = HAL_ETH_STATE_BUSY; - - /* Check if segment is not owned by DMA */ - /* (((heth->RxDesc->Status & ETH_DMARXDESC_OWN) == (uint32_t)RESET) && ((heth->RxDesc->Status & ETH_DMARXDESC_LS) != (uint32_t)RESET)) */ - if(((heth->RxDesc->Status & ETH_DMARXDESC_OWN) == (uint32_t)RESET)) - { - /* Check if last segment */ - if(((heth->RxDesc->Status & ETH_DMARXDESC_LS) != (uint32_t)RESET)) - { - /* increment segment count */ - (heth->RxFrameInfos).SegCount++; - - /* Check if last segment is first segment: one segment contains the frame */ - if ((heth->RxFrameInfos).SegCount == 1U) - { - (heth->RxFrameInfos).FSRxDesc =heth->RxDesc; - } - - heth->RxFrameInfos.LSRxDesc = heth->RxDesc; - - /* Get the Frame Length of the received packet: substruct 4 bytes of the CRC */ - framelength = (((heth->RxDesc)->Status & ETH_DMARXDESC_FL) >> ETH_DMARXDESC_FRAMELENGTHSHIFT) - 4U; - heth->RxFrameInfos.length = framelength; - - /* Get the address of the buffer start address */ - heth->RxFrameInfos.buffer = ((heth->RxFrameInfos).FSRxDesc)->Buffer1Addr; - /* point to next descriptor */ - heth->RxDesc = (ETH_DMADescTypeDef*) ((heth->RxDesc)->Buffer2NextDescAddr); - - /* Set HAL State to Ready */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; - } - /* Check if first segment */ - else if((heth->RxDesc->Status & ETH_DMARXDESC_FS) != (uint32_t)RESET) - { - (heth->RxFrameInfos).FSRxDesc = heth->RxDesc; - (heth->RxFrameInfos).LSRxDesc = NULL; - (heth->RxFrameInfos).SegCount = 1U; - /* Point to next descriptor */ - heth->RxDesc = (ETH_DMADescTypeDef*) (heth->RxDesc->Buffer2NextDescAddr); - } - /* Check if intermediate segment */ - else - { - (heth->RxFrameInfos).SegCount++; - /* Point to next descriptor */ - heth->RxDesc = (ETH_DMADescTypeDef*) (heth->RxDesc->Buffer2NextDescAddr); - } - } - - /* Set ETH HAL State to Ready */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_ERROR; -} - -/** - * @brief Gets the Received frame in interrupt mode. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_GetReceivedFrame_IT(ETH_HandleTypeDef *heth) -{ - uint32_t descriptorscancounter = 0U; - - /* Process Locked */ - __HAL_LOCK(heth); - - /* Set ETH HAL State to BUSY */ - heth->State = HAL_ETH_STATE_BUSY; - - /* Scan descriptors owned by CPU */ - while (((heth->RxDesc->Status & ETH_DMARXDESC_OWN) == (uint32_t)RESET) && (descriptorscancounter < ETH_RXBUFNB)) - { - /* Just for security */ - descriptorscancounter++; - - /* Check if first segment in frame */ - /* ((heth->RxDesc->Status & ETH_DMARXDESC_FS) != (uint32_t)RESET) && ((heth->RxDesc->Status & ETH_DMARXDESC_LS) == (uint32_t)RESET)) */ - if((heth->RxDesc->Status & (ETH_DMARXDESC_FS | ETH_DMARXDESC_LS)) == (uint32_t)ETH_DMARXDESC_FS) - { - heth->RxFrameInfos.FSRxDesc = heth->RxDesc; - heth->RxFrameInfos.SegCount = 1U; - /* Point to next descriptor */ - heth->RxDesc = (ETH_DMADescTypeDef*) (heth->RxDesc->Buffer2NextDescAddr); - } - /* Check if intermediate segment */ - /* ((heth->RxDesc->Status & ETH_DMARXDESC_LS) == (uint32_t)RESET)&& ((heth->RxDesc->Status & ETH_DMARXDESC_FS) == (uint32_t)RESET)) */ - else if ((heth->RxDesc->Status & (ETH_DMARXDESC_LS | ETH_DMARXDESC_FS)) == (uint32_t)RESET) - { - /* Increment segment count */ - (heth->RxFrameInfos.SegCount)++; - /* Point to next descriptor */ - heth->RxDesc = (ETH_DMADescTypeDef*)(heth->RxDesc->Buffer2NextDescAddr); - } - /* Should be last segment */ - else - { - /* Last segment */ - heth->RxFrameInfos.LSRxDesc = heth->RxDesc; - - /* Increment segment count */ - (heth->RxFrameInfos.SegCount)++; - - /* Check if last segment is first segment: one segment contains the frame */ - if ((heth->RxFrameInfos.SegCount) == 1U) - { - heth->RxFrameInfos.FSRxDesc = heth->RxDesc; - } - - /* Get the Frame Length of the received packet: substruct 4 bytes of the CRC */ - heth->RxFrameInfos.length = (((heth->RxDesc)->Status & ETH_DMARXDESC_FL) >> ETH_DMARXDESC_FRAMELENGTHSHIFT) - 4U; - - /* Get the address of the buffer start address */ - heth->RxFrameInfos.buffer =((heth->RxFrameInfos).FSRxDesc)->Buffer1Addr; - - /* Point to next descriptor */ - heth->RxDesc = (ETH_DMADescTypeDef*) (heth->RxDesc->Buffer2NextDescAddr); - - /* Set HAL State to Ready */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; - } - } - - /* Set HAL State to Ready */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_ERROR; -} - -/** - * @brief This function handles ETH interrupt request. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval HAL status - */ -void HAL_ETH_IRQHandler(ETH_HandleTypeDef *heth) -{ - /* Frame received */ - if (__HAL_ETH_DMA_GET_FLAG(heth, ETH_DMA_FLAG_R)) - { -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) - /*Call registered Receive complete callback*/ - heth->RxCpltCallback(heth); -#else - /* Receive complete callback */ - HAL_ETH_RxCpltCallback(heth); -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - - /* Clear the Eth DMA Rx IT pending bits */ - __HAL_ETH_DMA_CLEAR_IT(heth, ETH_DMA_IT_R); - - /* Set HAL State to Ready */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - } - /* Frame transmitted */ - else if (__HAL_ETH_DMA_GET_FLAG(heth, ETH_DMA_FLAG_T)) - { -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) - /* Call resgistered Transfer complete callback*/ - heth->TxCpltCallback(heth); -#else - /* Transfer complete callback */ - HAL_ETH_TxCpltCallback(heth); -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - - /* Clear the Eth DMA Tx IT pending bits */ - __HAL_ETH_DMA_CLEAR_IT(heth, ETH_DMA_IT_T); - - /* Set HAL State to Ready */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - } - - /* Clear the interrupt flags */ - __HAL_ETH_DMA_CLEAR_IT(heth, ETH_DMA_IT_NIS); - - /* ETH DMA Error */ - if(__HAL_ETH_DMA_GET_FLAG(heth, ETH_DMA_FLAG_AIS)) - { -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) - heth->DMAErrorCallback(heth); -#else - /* Ethernet Error callback */ - HAL_ETH_ErrorCallback(heth); -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - - /* Clear the interrupt flags */ - __HAL_ETH_DMA_CLEAR_IT(heth, ETH_DMA_FLAG_AIS); - - /* Set HAL State to Ready */ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - } -} - -/** - * @brief Tx Transfer completed callbacks. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -__weak void HAL_ETH_TxCpltCallback(ETH_HandleTypeDef *heth) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(heth); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ETH_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callbacks. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -__weak void HAL_ETH_RxCpltCallback(ETH_HandleTypeDef *heth) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(heth); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ETH_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Ethernet transfer error callbacks - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -__weak void HAL_ETH_ErrorCallback(ETH_HandleTypeDef *heth) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(heth); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_ETH_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Reads a PHY register - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param PHYReg PHY register address, is the index of one of the 32 PHY register. - * This parameter can be one of the following values: - * PHY_BCR: Transceiver Basic Control Register, - * PHY_BSR: Transceiver Basic Status Register. - * More PHY register could be read depending on the used PHY - * @param RegValue PHY register value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_ReadPHYRegister(ETH_HandleTypeDef *heth, uint16_t PHYReg, uint32_t *RegValue) -{ - uint32_t tmpreg1 = 0U; - uint32_t tickstart = 0U; - - /* Check parameters */ - assert_param(IS_ETH_PHY_ADDRESS(heth->Init.PhyAddress)); - - /* Check the ETH peripheral state */ - if(heth->State == HAL_ETH_STATE_BUSY_RD) - { - return HAL_BUSY; - } - /* Set ETH HAL State to BUSY_RD */ - heth->State = HAL_ETH_STATE_BUSY_RD; - - /* Get the ETHERNET MACMIIAR value */ - tmpreg1 = heth->Instance->MACMIIAR; - - /* Keep only the CSR Clock Range CR[2:0] bits value */ - tmpreg1 &= ~ETH_MACMIIAR_CR_MASK; - - /* Prepare the MII address register value */ - tmpreg1 |=(((uint32_t)heth->Init.PhyAddress << 11U) & ETH_MACMIIAR_PA); /* Set the PHY device address */ - tmpreg1 |=(((uint32_t)PHYReg<<6U) & ETH_MACMIIAR_MR); /* Set the PHY register address */ - tmpreg1 &= ~ETH_MACMIIAR_MW; /* Set the read mode */ - tmpreg1 |= ETH_MACMIIAR_MB; /* Set the MII Busy bit */ - - /* Write the result value into the MII Address register */ - heth->Instance->MACMIIAR = tmpreg1; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check for the Busy flag */ - while((tmpreg1 & ETH_MACMIIAR_MB) == ETH_MACMIIAR_MB) - { - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > PHY_READ_TO) - { - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - return HAL_TIMEOUT; - } - - tmpreg1 = heth->Instance->MACMIIAR; - } - - /* Get MACMIIDR value */ - *RegValue = (uint16_t)(heth->Instance->MACMIIDR); - - /* Set ETH HAL State to READY */ - heth->State = HAL_ETH_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Writes to a PHY register. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param PHYReg PHY register address, is the index of one of the 32 PHY register. - * This parameter can be one of the following values: - * PHY_BCR: Transceiver Control Register. - * More PHY register could be written depending on the used PHY - * @param RegValue the value to write - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_WritePHYRegister(ETH_HandleTypeDef *heth, uint16_t PHYReg, uint32_t RegValue) -{ - uint32_t tmpreg1 = 0U; - uint32_t tickstart = 0U; - - /* Check parameters */ - assert_param(IS_ETH_PHY_ADDRESS(heth->Init.PhyAddress)); - - /* Check the ETH peripheral state */ - if(heth->State == HAL_ETH_STATE_BUSY_WR) - { - return HAL_BUSY; - } - /* Set ETH HAL State to BUSY_WR */ - heth->State = HAL_ETH_STATE_BUSY_WR; - - /* Get the ETHERNET MACMIIAR value */ - tmpreg1 = heth->Instance->MACMIIAR; - - /* Keep only the CSR Clock Range CR[2:0] bits value */ - tmpreg1 &= ~ETH_MACMIIAR_CR_MASK; - - /* Prepare the MII register address value */ - tmpreg1 |=(((uint32_t)heth->Init.PhyAddress<<11U) & ETH_MACMIIAR_PA); /* Set the PHY device address */ - tmpreg1 |=(((uint32_t)PHYReg<<6U) & ETH_MACMIIAR_MR); /* Set the PHY register address */ - tmpreg1 |= ETH_MACMIIAR_MW; /* Set the write mode */ - tmpreg1 |= ETH_MACMIIAR_MB; /* Set the MII Busy bit */ - - /* Give the value to the MII data register */ - heth->Instance->MACMIIDR = (uint16_t)RegValue; - - /* Write the result value into the MII Address register */ - heth->Instance->MACMIIAR = tmpreg1; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check for the Busy flag */ - while((tmpreg1 & ETH_MACMIIAR_MB) == ETH_MACMIIAR_MB) - { - /* Check for the Timeout */ - if((HAL_GetTick() - tickstart ) > PHY_WRITE_TO) - { - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - return HAL_TIMEOUT; - } - - tmpreg1 = heth->Instance->MACMIIAR; - } - - /* Set ETH HAL State to READY */ - heth->State = HAL_ETH_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup ETH_Exported_Functions_Group3 Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Enable MAC and DMA transmission and reception. - HAL_ETH_Start(); - (+) Disable MAC and DMA transmission and reception. - HAL_ETH_Stop(); - (+) Set the MAC configuration in runtime mode - HAL_ETH_ConfigMAC(); - (+) Set the DMA configuration in runtime mode - HAL_ETH_ConfigDMA(); - -@endverbatim - * @{ - */ - - /** - * @brief Enables Ethernet MAC and DMA reception/transmission - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_Start(ETH_HandleTypeDef *heth) -{ - /* Process Locked */ - __HAL_LOCK(heth); - - /* Set the ETH peripheral state to BUSY */ - heth->State = HAL_ETH_STATE_BUSY; - - /* Enable transmit state machine of the MAC for transmission on the MII */ - ETH_MACTransmissionEnable(heth); - - /* Enable receive state machine of the MAC for reception from the MII */ - ETH_MACReceptionEnable(heth); - - /* Flush Transmit FIFO */ - ETH_FlushTransmitFIFO(heth); - - /* Start DMA transmission */ - ETH_DMATransmissionEnable(heth); - - /* Start DMA reception */ - ETH_DMAReceptionEnable(heth); - - /* Set the ETH state to READY*/ - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop Ethernet MAC and DMA reception/transmission - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_Stop(ETH_HandleTypeDef *heth) -{ - /* Process Locked */ - __HAL_LOCK(heth); - - /* Set the ETH peripheral state to BUSY */ - heth->State = HAL_ETH_STATE_BUSY; - - /* Stop DMA transmission */ - ETH_DMATransmissionDisable(heth); - - /* Stop DMA reception */ - ETH_DMAReceptionDisable(heth); - - /* Disable receive state machine of the MAC for reception from the MII */ - ETH_MACReceptionDisable(heth); - - /* Flush Transmit FIFO */ - ETH_FlushTransmitFIFO(heth); - - /* Disable transmit state machine of the MAC for transmission on the MII */ - ETH_MACTransmissionDisable(heth); - - /* Set the ETH state*/ - heth->State = HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Set ETH MAC Configuration. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param macconf MAC Configuration structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_ConfigMAC(ETH_HandleTypeDef *heth, ETH_MACInitTypeDef *macconf) -{ - uint32_t tmpreg1 = 0U; - - /* Process Locked */ - __HAL_LOCK(heth); - - /* Set the ETH peripheral state to BUSY */ - heth->State= HAL_ETH_STATE_BUSY; - - assert_param(IS_ETH_SPEED(heth->Init.Speed)); - assert_param(IS_ETH_DUPLEX_MODE(heth->Init.DuplexMode)); - - if (macconf != NULL) - { - /* Check the parameters */ - assert_param(IS_ETH_WATCHDOG(macconf->Watchdog)); - assert_param(IS_ETH_JABBER(macconf->Jabber)); - assert_param(IS_ETH_INTER_FRAME_GAP(macconf->InterFrameGap)); - assert_param(IS_ETH_CARRIER_SENSE(macconf->CarrierSense)); - assert_param(IS_ETH_RECEIVE_OWN(macconf->ReceiveOwn)); - assert_param(IS_ETH_LOOPBACK_MODE(macconf->LoopbackMode)); - assert_param(IS_ETH_CHECKSUM_OFFLOAD(macconf->ChecksumOffload)); - assert_param(IS_ETH_RETRY_TRANSMISSION(macconf->RetryTransmission)); - assert_param(IS_ETH_AUTOMATIC_PADCRC_STRIP(macconf->AutomaticPadCRCStrip)); - assert_param(IS_ETH_BACKOFF_LIMIT(macconf->BackOffLimit)); - assert_param(IS_ETH_DEFERRAL_CHECK(macconf->DeferralCheck)); - assert_param(IS_ETH_RECEIVE_ALL(macconf->ReceiveAll)); - assert_param(IS_ETH_SOURCE_ADDR_FILTER(macconf->SourceAddrFilter)); - assert_param(IS_ETH_CONTROL_FRAMES(macconf->PassControlFrames)); - assert_param(IS_ETH_BROADCAST_FRAMES_RECEPTION(macconf->BroadcastFramesReception)); - assert_param(IS_ETH_DESTINATION_ADDR_FILTER(macconf->DestinationAddrFilter)); - assert_param(IS_ETH_PROMISCUOUS_MODE(macconf->PromiscuousMode)); - assert_param(IS_ETH_MULTICAST_FRAMES_FILTER(macconf->MulticastFramesFilter)); - assert_param(IS_ETH_UNICAST_FRAMES_FILTER(macconf->UnicastFramesFilter)); - assert_param(IS_ETH_PAUSE_TIME(macconf->PauseTime)); - assert_param(IS_ETH_ZEROQUANTA_PAUSE(macconf->ZeroQuantaPause)); - assert_param(IS_ETH_PAUSE_LOW_THRESHOLD(macconf->PauseLowThreshold)); - assert_param(IS_ETH_UNICAST_PAUSE_FRAME_DETECT(macconf->UnicastPauseFrameDetect)); - assert_param(IS_ETH_RECEIVE_FLOWCONTROL(macconf->ReceiveFlowControl)); - assert_param(IS_ETH_TRANSMIT_FLOWCONTROL(macconf->TransmitFlowControl)); - assert_param(IS_ETH_VLAN_TAG_COMPARISON(macconf->VLANTagComparison)); - assert_param(IS_ETH_VLAN_TAG_IDENTIFIER(macconf->VLANTagIdentifier)); - - /*------------------------ ETHERNET MACCR Configuration --------------------*/ - /* Get the ETHERNET MACCR value */ - tmpreg1 = (heth->Instance)->MACCR; - /* Clear WD, PCE, PS, TE and RE bits */ - tmpreg1 &= ETH_MACCR_CLEAR_MASK; - - tmpreg1 |= (uint32_t)(macconf->Watchdog | - macconf->Jabber | - macconf->InterFrameGap | - macconf->CarrierSense | - (heth->Init).Speed | - macconf->ReceiveOwn | - macconf->LoopbackMode | - (heth->Init).DuplexMode | - macconf->ChecksumOffload | - macconf->RetryTransmission | - macconf->AutomaticPadCRCStrip | - macconf->BackOffLimit | - macconf->DeferralCheck); - - /* Write to ETHERNET MACCR */ - (heth->Instance)->MACCR = (uint32_t)tmpreg1; - - /* Wait until the write operation will be taken into account : - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACCR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACCR = tmpreg1; - - /*----------------------- ETHERNET MACFFR Configuration --------------------*/ - /* Write to ETHERNET MACFFR */ - (heth->Instance)->MACFFR = (uint32_t)(macconf->ReceiveAll | - macconf->SourceAddrFilter | - macconf->PassControlFrames | - macconf->BroadcastFramesReception | - macconf->DestinationAddrFilter | - macconf->PromiscuousMode | - macconf->MulticastFramesFilter | - macconf->UnicastFramesFilter); - - /* Wait until the write operation will be taken into account : - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACFFR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACFFR = tmpreg1; - - /*--------------- ETHERNET MACHTHR and MACHTLR Configuration ---------------*/ - /* Write to ETHERNET MACHTHR */ - (heth->Instance)->MACHTHR = (uint32_t)macconf->HashTableHigh; - - /* Write to ETHERNET MACHTLR */ - (heth->Instance)->MACHTLR = (uint32_t)macconf->HashTableLow; - /*----------------------- ETHERNET MACFCR Configuration --------------------*/ - - /* Get the ETHERNET MACFCR value */ - tmpreg1 = (heth->Instance)->MACFCR; - /* Clear xx bits */ - tmpreg1 &= ETH_MACFCR_CLEAR_MASK; - - tmpreg1 |= (uint32_t)((macconf->PauseTime << 16U) | - macconf->ZeroQuantaPause | - macconf->PauseLowThreshold | - macconf->UnicastPauseFrameDetect | - macconf->ReceiveFlowControl | - macconf->TransmitFlowControl); - - /* Write to ETHERNET MACFCR */ - (heth->Instance)->MACFCR = (uint32_t)tmpreg1; - - /* Wait until the write operation will be taken into account : - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACFCR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACFCR = tmpreg1; - - /*----------------------- ETHERNET MACVLANTR Configuration -----------------*/ - (heth->Instance)->MACVLANTR = (uint32_t)(macconf->VLANTagComparison | - macconf->VLANTagIdentifier); - - /* Wait until the write operation will be taken into account : - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACVLANTR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACVLANTR = tmpreg1; - } - else /* macconf == NULL : here we just configure Speed and Duplex mode */ - { - /*------------------------ ETHERNET MACCR Configuration --------------------*/ - /* Get the ETHERNET MACCR value */ - tmpreg1 = (heth->Instance)->MACCR; - - /* Clear FES and DM bits */ - tmpreg1 &= ~(0x00004800U); - - tmpreg1 |= (uint32_t)(heth->Init.Speed | heth->Init.DuplexMode); - - /* Write to ETHERNET MACCR */ - (heth->Instance)->MACCR = (uint32_t)tmpreg1; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACCR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACCR = tmpreg1; - } - - /* Set the ETH state to Ready */ - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Sets ETH DMA Configuration. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param dmaconf DMA Configuration structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_ETH_ConfigDMA(ETH_HandleTypeDef *heth, ETH_DMAInitTypeDef *dmaconf) -{ - uint32_t tmpreg1 = 0U; - - /* Process Locked */ - __HAL_LOCK(heth); - - /* Set the ETH peripheral state to BUSY */ - heth->State= HAL_ETH_STATE_BUSY; - - /* Check parameters */ - assert_param(IS_ETH_DROP_TCPIP_CHECKSUM_FRAME(dmaconf->DropTCPIPChecksumErrorFrame)); - assert_param(IS_ETH_RECEIVE_STORE_FORWARD(dmaconf->ReceiveStoreForward)); - assert_param(IS_ETH_FLUSH_RECEIVE_FRAME(dmaconf->FlushReceivedFrame)); - assert_param(IS_ETH_TRANSMIT_STORE_FORWARD(dmaconf->TransmitStoreForward)); - assert_param(IS_ETH_TRANSMIT_THRESHOLD_CONTROL(dmaconf->TransmitThresholdControl)); - assert_param(IS_ETH_FORWARD_ERROR_FRAMES(dmaconf->ForwardErrorFrames)); - assert_param(IS_ETH_FORWARD_UNDERSIZED_GOOD_FRAMES(dmaconf->ForwardUndersizedGoodFrames)); - assert_param(IS_ETH_RECEIVE_THRESHOLD_CONTROL(dmaconf->ReceiveThresholdControl)); - assert_param(IS_ETH_SECOND_FRAME_OPERATE(dmaconf->SecondFrameOperate)); - assert_param(IS_ETH_ADDRESS_ALIGNED_BEATS(dmaconf->AddressAlignedBeats)); - assert_param(IS_ETH_FIXED_BURST(dmaconf->FixedBurst)); - assert_param(IS_ETH_RXDMA_BURST_LENGTH(dmaconf->RxDMABurstLength)); - assert_param(IS_ETH_TXDMA_BURST_LENGTH(dmaconf->TxDMABurstLength)); - assert_param(IS_ETH_ENHANCED_DESCRIPTOR_FORMAT(dmaconf->EnhancedDescriptorFormat)); - assert_param(IS_ETH_DMA_DESC_SKIP_LENGTH(dmaconf->DescriptorSkipLength)); - assert_param(IS_ETH_DMA_ARBITRATION_ROUNDROBIN_RXTX(dmaconf->DMAArbitration)); - - /*----------------------- ETHERNET DMAOMR Configuration --------------------*/ - /* Get the ETHERNET DMAOMR value */ - tmpreg1 = (heth->Instance)->DMAOMR; - /* Clear xx bits */ - tmpreg1 &= ETH_DMAOMR_CLEAR_MASK; - - tmpreg1 |= (uint32_t)(dmaconf->DropTCPIPChecksumErrorFrame | - dmaconf->ReceiveStoreForward | - dmaconf->FlushReceivedFrame | - dmaconf->TransmitStoreForward | - dmaconf->TransmitThresholdControl | - dmaconf->ForwardErrorFrames | - dmaconf->ForwardUndersizedGoodFrames | - dmaconf->ReceiveThresholdControl | - dmaconf->SecondFrameOperate); - - /* Write to ETHERNET DMAOMR */ - (heth->Instance)->DMAOMR = (uint32_t)tmpreg1; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->DMAOMR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->DMAOMR = tmpreg1; - - /*----------------------- ETHERNET DMABMR Configuration --------------------*/ - (heth->Instance)->DMABMR = (uint32_t)(dmaconf->AddressAlignedBeats | - dmaconf->FixedBurst | - dmaconf->RxDMABurstLength | /* !! if 4xPBL is selected for Tx or Rx it is applied for the other */ - dmaconf->TxDMABurstLength | - dmaconf->EnhancedDescriptorFormat | - (dmaconf->DescriptorSkipLength << 2U) | - dmaconf->DMAArbitration | - ETH_DMABMR_USP); /* Enable use of separate PBL for Rx and Tx */ - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->DMABMR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->DMABMR = tmpreg1; - - /* Set the ETH state to Ready */ - heth->State= HAL_ETH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(heth); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup ETH_Exported_Functions_Group4 Peripheral State functions - * @brief Peripheral State functions - * - @verbatim - =============================================================================== - ##### Peripheral State functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - (+) Get the ETH handle state: - HAL_ETH_GetState(); - - - @endverbatim - * @{ - */ - -/** - * @brief Return the ETH HAL state - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval HAL state - */ -HAL_ETH_StateTypeDef HAL_ETH_GetState(ETH_HandleTypeDef *heth) -{ - /* Return ETH state */ - return heth->State; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup ETH_Private_Functions - * @{ - */ - -/** - * @brief Configures Ethernet MAC and DMA with default parameters. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param err Ethernet Init error - * @retval HAL status - */ -static void ETH_MACDMAConfig(ETH_HandleTypeDef *heth, uint32_t err) -{ - ETH_MACInitTypeDef macinit; - ETH_DMAInitTypeDef dmainit; - uint32_t tmpreg1 = 0U; - - if (err != ETH_SUCCESS) /* Auto-negotiation failed */ - { - /* Set Ethernet duplex mode to Full-duplex */ - (heth->Init).DuplexMode = ETH_MODE_FULLDUPLEX; - - /* Set Ethernet speed to 100M */ - (heth->Init).Speed = ETH_SPEED_100M; - } - - /* Ethernet MAC default initialization **************************************/ - macinit.Watchdog = ETH_WATCHDOG_ENABLE; - macinit.Jabber = ETH_JABBER_ENABLE; - macinit.InterFrameGap = ETH_INTERFRAMEGAP_96BIT; - macinit.CarrierSense = ETH_CARRIERSENCE_ENABLE; - macinit.ReceiveOwn = ETH_RECEIVEOWN_ENABLE; - macinit.LoopbackMode = ETH_LOOPBACKMODE_DISABLE; - if(heth->Init.ChecksumMode == ETH_CHECKSUM_BY_HARDWARE) - { - macinit.ChecksumOffload = ETH_CHECKSUMOFFLAOD_ENABLE; - } - else - { - macinit.ChecksumOffload = ETH_CHECKSUMOFFLAOD_DISABLE; - } - macinit.RetryTransmission = ETH_RETRYTRANSMISSION_DISABLE; - macinit.AutomaticPadCRCStrip = ETH_AUTOMATICPADCRCSTRIP_DISABLE; - macinit.BackOffLimit = ETH_BACKOFFLIMIT_10; - macinit.DeferralCheck = ETH_DEFFERRALCHECK_DISABLE; - macinit.ReceiveAll = ETH_RECEIVEAll_DISABLE; - macinit.SourceAddrFilter = ETH_SOURCEADDRFILTER_DISABLE; - macinit.PassControlFrames = ETH_PASSCONTROLFRAMES_BLOCKALL; - macinit.BroadcastFramesReception = ETH_BROADCASTFRAMESRECEPTION_ENABLE; - macinit.DestinationAddrFilter = ETH_DESTINATIONADDRFILTER_NORMAL; - macinit.PromiscuousMode = ETH_PROMISCUOUS_MODE_DISABLE; - macinit.MulticastFramesFilter = ETH_MULTICASTFRAMESFILTER_PERFECT; - macinit.UnicastFramesFilter = ETH_UNICASTFRAMESFILTER_PERFECT; - macinit.HashTableHigh = 0x0U; - macinit.HashTableLow = 0x0U; - macinit.PauseTime = 0x0U; - macinit.ZeroQuantaPause = ETH_ZEROQUANTAPAUSE_DISABLE; - macinit.PauseLowThreshold = ETH_PAUSELOWTHRESHOLD_MINUS4; - macinit.UnicastPauseFrameDetect = ETH_UNICASTPAUSEFRAMEDETECT_DISABLE; - macinit.ReceiveFlowControl = ETH_RECEIVEFLOWCONTROL_DISABLE; - macinit.TransmitFlowControl = ETH_TRANSMITFLOWCONTROL_DISABLE; - macinit.VLANTagComparison = ETH_VLANTAGCOMPARISON_16BIT; - macinit.VLANTagIdentifier = 0x0U; - - /*------------------------ ETHERNET MACCR Configuration --------------------*/ - /* Get the ETHERNET MACCR value */ - tmpreg1 = (heth->Instance)->MACCR; - /* Clear WD, PCE, PS, TE and RE bits */ - tmpreg1 &= ETH_MACCR_CLEAR_MASK; - /* Set the WD bit according to ETH Watchdog value */ - /* Set the JD: bit according to ETH Jabber value */ - /* Set the IFG bit according to ETH InterFrameGap value */ - /* Set the DCRS bit according to ETH CarrierSense value */ - /* Set the FES bit according to ETH Speed value */ - /* Set the DO bit according to ETH ReceiveOwn value */ - /* Set the LM bit according to ETH LoopbackMode value */ - /* Set the DM bit according to ETH Mode value */ - /* Set the IPCO bit according to ETH ChecksumOffload value */ - /* Set the DR bit according to ETH RetryTransmission value */ - /* Set the ACS bit according to ETH AutomaticPadCRCStrip value */ - /* Set the BL bit according to ETH BackOffLimit value */ - /* Set the DC bit according to ETH DeferralCheck value */ - tmpreg1 |= (uint32_t)(macinit.Watchdog | - macinit.Jabber | - macinit.InterFrameGap | - macinit.CarrierSense | - (heth->Init).Speed | - macinit.ReceiveOwn | - macinit.LoopbackMode | - (heth->Init).DuplexMode | - macinit.ChecksumOffload | - macinit.RetryTransmission | - macinit.AutomaticPadCRCStrip | - macinit.BackOffLimit | - macinit.DeferralCheck); - - /* Write to ETHERNET MACCR */ - (heth->Instance)->MACCR = (uint32_t)tmpreg1; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACCR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACCR = tmpreg1; - - /*----------------------- ETHERNET MACFFR Configuration --------------------*/ - /* Set the RA bit according to ETH ReceiveAll value */ - /* Set the SAF and SAIF bits according to ETH SourceAddrFilter value */ - /* Set the PCF bit according to ETH PassControlFrames value */ - /* Set the DBF bit according to ETH BroadcastFramesReception value */ - /* Set the DAIF bit according to ETH DestinationAddrFilter value */ - /* Set the PR bit according to ETH PromiscuousMode value */ - /* Set the PM, HMC and HPF bits according to ETH MulticastFramesFilter value */ - /* Set the HUC and HPF bits according to ETH UnicastFramesFilter value */ - /* Write to ETHERNET MACFFR */ - (heth->Instance)->MACFFR = (uint32_t)(macinit.ReceiveAll | - macinit.SourceAddrFilter | - macinit.PassControlFrames | - macinit.BroadcastFramesReception | - macinit.DestinationAddrFilter | - macinit.PromiscuousMode | - macinit.MulticastFramesFilter | - macinit.UnicastFramesFilter); - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACFFR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACFFR = tmpreg1; - - /*--------------- ETHERNET MACHTHR and MACHTLR Configuration --------------*/ - /* Write to ETHERNET MACHTHR */ - (heth->Instance)->MACHTHR = (uint32_t)macinit.HashTableHigh; - - /* Write to ETHERNET MACHTLR */ - (heth->Instance)->MACHTLR = (uint32_t)macinit.HashTableLow; - /*----------------------- ETHERNET MACFCR Configuration -------------------*/ - - /* Get the ETHERNET MACFCR value */ - tmpreg1 = (heth->Instance)->MACFCR; - /* Clear xx bits */ - tmpreg1 &= ETH_MACFCR_CLEAR_MASK; - - /* Set the PT bit according to ETH PauseTime value */ - /* Set the DZPQ bit according to ETH ZeroQuantaPause value */ - /* Set the PLT bit according to ETH PauseLowThreshold value */ - /* Set the UP bit according to ETH UnicastPauseFrameDetect value */ - /* Set the RFE bit according to ETH ReceiveFlowControl value */ - /* Set the TFE bit according to ETH TransmitFlowControl value */ - tmpreg1 |= (uint32_t)((macinit.PauseTime << 16U) | - macinit.ZeroQuantaPause | - macinit.PauseLowThreshold | - macinit.UnicastPauseFrameDetect | - macinit.ReceiveFlowControl | - macinit.TransmitFlowControl); - - /* Write to ETHERNET MACFCR */ - (heth->Instance)->MACFCR = (uint32_t)tmpreg1; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACFCR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACFCR = tmpreg1; - - /*----------------------- ETHERNET MACVLANTR Configuration ----------------*/ - /* Set the ETV bit according to ETH VLANTagComparison value */ - /* Set the VL bit according to ETH VLANTagIdentifier value */ - (heth->Instance)->MACVLANTR = (uint32_t)(macinit.VLANTagComparison | - macinit.VLANTagIdentifier); - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACVLANTR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACVLANTR = tmpreg1; - - /* Ethernet DMA default initialization ************************************/ - dmainit.DropTCPIPChecksumErrorFrame = ETH_DROPTCPIPCHECKSUMERRORFRAME_ENABLE; - dmainit.ReceiveStoreForward = ETH_RECEIVESTOREFORWARD_ENABLE; - dmainit.FlushReceivedFrame = ETH_FLUSHRECEIVEDFRAME_ENABLE; - dmainit.TransmitStoreForward = ETH_TRANSMITSTOREFORWARD_ENABLE; - dmainit.TransmitThresholdControl = ETH_TRANSMITTHRESHOLDCONTROL_64BYTES; - dmainit.ForwardErrorFrames = ETH_FORWARDERRORFRAMES_DISABLE; - dmainit.ForwardUndersizedGoodFrames = ETH_FORWARDUNDERSIZEDGOODFRAMES_DISABLE; - dmainit.ReceiveThresholdControl = ETH_RECEIVEDTHRESHOLDCONTROL_64BYTES; - dmainit.SecondFrameOperate = ETH_SECONDFRAMEOPERARTE_ENABLE; - dmainit.AddressAlignedBeats = ETH_ADDRESSALIGNEDBEATS_ENABLE; - dmainit.FixedBurst = ETH_FIXEDBURST_ENABLE; - dmainit.RxDMABurstLength = ETH_RXDMABURSTLENGTH_32BEAT; - dmainit.TxDMABurstLength = ETH_TXDMABURSTLENGTH_32BEAT; - dmainit.EnhancedDescriptorFormat = ETH_DMAENHANCEDDESCRIPTOR_ENABLE; - dmainit.DescriptorSkipLength = 0x0U; - dmainit.DMAArbitration = ETH_DMAARBITRATION_ROUNDROBIN_RXTX_1_1; - - /* Get the ETHERNET DMAOMR value */ - tmpreg1 = (heth->Instance)->DMAOMR; - /* Clear xx bits */ - tmpreg1 &= ETH_DMAOMR_CLEAR_MASK; - - /* Set the DT bit according to ETH DropTCPIPChecksumErrorFrame value */ - /* Set the RSF bit according to ETH ReceiveStoreForward value */ - /* Set the DFF bit according to ETH FlushReceivedFrame value */ - /* Set the TSF bit according to ETH TransmitStoreForward value */ - /* Set the TTC bit according to ETH TransmitThresholdControl value */ - /* Set the FEF bit according to ETH ForwardErrorFrames value */ - /* Set the FUF bit according to ETH ForwardUndersizedGoodFrames value */ - /* Set the RTC bit according to ETH ReceiveThresholdControl value */ - /* Set the OSF bit according to ETH SecondFrameOperate value */ - tmpreg1 |= (uint32_t)(dmainit.DropTCPIPChecksumErrorFrame | - dmainit.ReceiveStoreForward | - dmainit.FlushReceivedFrame | - dmainit.TransmitStoreForward | - dmainit.TransmitThresholdControl | - dmainit.ForwardErrorFrames | - dmainit.ForwardUndersizedGoodFrames | - dmainit.ReceiveThresholdControl | - dmainit.SecondFrameOperate); - - /* Write to ETHERNET DMAOMR */ - (heth->Instance)->DMAOMR = (uint32_t)tmpreg1; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->DMAOMR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->DMAOMR = tmpreg1; - - /*----------------------- ETHERNET DMABMR Configuration ------------------*/ - /* Set the AAL bit according to ETH AddressAlignedBeats value */ - /* Set the FB bit according to ETH FixedBurst value */ - /* Set the RPBL and 4*PBL bits according to ETH RxDMABurstLength value */ - /* Set the PBL and 4*PBL bits according to ETH TxDMABurstLength value */ - /* Set the Enhanced DMA descriptors bit according to ETH EnhancedDescriptorFormat value*/ - /* Set the DSL bit according to ETH DesciptorSkipLength value */ - /* Set the PR and DA bits according to ETH DMAArbitration value */ - (heth->Instance)->DMABMR = (uint32_t)(dmainit.AddressAlignedBeats | - dmainit.FixedBurst | - dmainit.RxDMABurstLength | /* !! if 4xPBL is selected for Tx or Rx it is applied for the other */ - dmainit.TxDMABurstLength | - dmainit.EnhancedDescriptorFormat | - (dmainit.DescriptorSkipLength << 2U) | - dmainit.DMAArbitration | - ETH_DMABMR_USP); /* Enable use of separate PBL for Rx and Tx */ - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->DMABMR; - HAL_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->DMABMR = tmpreg1; - - if((heth->Init).RxMode == ETH_RXINTERRUPT_MODE) - { - /* Enable the Ethernet Rx Interrupt */ - __HAL_ETH_DMA_ENABLE_IT((heth), ETH_DMA_IT_NIS | ETH_DMA_IT_R); - } - - /* Initialize MAC address in ethernet MAC */ - ETH_MACAddressConfig(heth, ETH_MAC_ADDRESS0, heth->Init.MACAddr); -} - -/** - * @brief Configures the selected MAC address. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @param MacAddr The MAC address to configure - * This parameter can be one of the following values: - * @arg ETH_MAC_Address0: MAC Address0 - * @arg ETH_MAC_Address1: MAC Address1 - * @arg ETH_MAC_Address2: MAC Address2 - * @arg ETH_MAC_Address3: MAC Address3 - * @param Addr Pointer to MAC address buffer data (6 bytes) - * @retval HAL status - */ -static void ETH_MACAddressConfig(ETH_HandleTypeDef *heth, uint32_t MacAddr, uint8_t *Addr) -{ - uint32_t tmpreg1; - - /* Prevent unused argument(s) compilation warning */ - UNUSED(heth); - - /* Check the parameters */ - assert_param(IS_ETH_MAC_ADDRESS0123(MacAddr)); - - /* Calculate the selected MAC address high register */ - tmpreg1 = ((uint32_t)Addr[5U] << 8U) | (uint32_t)Addr[4U]; - /* Load the selected MAC address high register */ - (*(__IO uint32_t *)((uint32_t)(ETH_MAC_ADDR_HBASE + MacAddr))) = tmpreg1; - /* Calculate the selected MAC address low register */ - tmpreg1 = ((uint32_t)Addr[3U] << 24U) | ((uint32_t)Addr[2U] << 16U) | ((uint32_t)Addr[1U] << 8U) | Addr[0U]; - - /* Load the selected MAC address low register */ - (*(__IO uint32_t *)((uint32_t)(ETH_MAC_ADDR_LBASE + MacAddr))) = tmpreg1; -} - -/** - * @brief Enables the MAC transmission. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_MACTransmissionEnable(ETH_HandleTypeDef *heth) -{ - __IO uint32_t tmpreg1 = 0U; - - /* Enable the MAC transmission */ - (heth->Instance)->MACCR |= ETH_MACCR_TE; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACCR; - ETH_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACCR = tmpreg1; -} - -/** - * @brief Disables the MAC transmission. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_MACTransmissionDisable(ETH_HandleTypeDef *heth) -{ - __IO uint32_t tmpreg1 = 0U; - - /* Disable the MAC transmission */ - (heth->Instance)->MACCR &= ~ETH_MACCR_TE; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACCR; - ETH_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACCR = tmpreg1; -} - -/** - * @brief Enables the MAC reception. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_MACReceptionEnable(ETH_HandleTypeDef *heth) -{ - __IO uint32_t tmpreg1 = 0U; - - /* Enable the MAC reception */ - (heth->Instance)->MACCR |= ETH_MACCR_RE; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACCR; - ETH_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACCR = tmpreg1; -} - -/** - * @brief Disables the MAC reception. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_MACReceptionDisable(ETH_HandleTypeDef *heth) -{ - __IO uint32_t tmpreg1 = 0U; - - /* Disable the MAC reception */ - (heth->Instance)->MACCR &= ~ETH_MACCR_RE; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->MACCR; - ETH_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->MACCR = tmpreg1; -} - -/** - * @brief Enables the DMA transmission. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_DMATransmissionEnable(ETH_HandleTypeDef *heth) -{ - /* Enable the DMA transmission */ - (heth->Instance)->DMAOMR |= ETH_DMAOMR_ST; -} - -/** - * @brief Disables the DMA transmission. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_DMATransmissionDisable(ETH_HandleTypeDef *heth) -{ - /* Disable the DMA transmission */ - (heth->Instance)->DMAOMR &= ~ETH_DMAOMR_ST; -} - -/** - * @brief Enables the DMA reception. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_DMAReceptionEnable(ETH_HandleTypeDef *heth) -{ - /* Enable the DMA reception */ - (heth->Instance)->DMAOMR |= ETH_DMAOMR_SR; -} - -/** - * @brief Disables the DMA reception. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_DMAReceptionDisable(ETH_HandleTypeDef *heth) -{ - /* Disable the DMA reception */ - (heth->Instance)->DMAOMR &= ~ETH_DMAOMR_SR; -} - -/** - * @brief Clears the ETHERNET transmit FIFO. - * @param heth pointer to a ETH_HandleTypeDef structure that contains - * the configuration information for ETHERNET module - * @retval None - */ -static void ETH_FlushTransmitFIFO(ETH_HandleTypeDef *heth) -{ - __IO uint32_t tmpreg1 = 0U; - - /* Set the Flush Transmit FIFO bit */ - (heth->Instance)->DMAOMR |= ETH_DMAOMR_FTF; - - /* Wait until the write operation will be taken into account: - at least four TX_CLK/RX_CLK clock cycles */ - tmpreg1 = (heth->Instance)->DMAOMR; - ETH_Delay(ETH_REG_WRITE_DELAY); - (heth->Instance)->DMAOMR = tmpreg1; -} - -/** - * @brief This function provides delay (in milliseconds) based on CPU cycles method. - * @param mdelay specifies the delay time length, in milliseconds. - * @retval None - */ -static void ETH_Delay(uint32_t mdelay) -{ - __IO uint32_t Delay = mdelay * (SystemCoreClock / 8U / 1000U); - do - { - __NOP(); - } - while (Delay --); -} - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -static void ETH_InitCallbacksToDefault(ETH_HandleTypeDef *heth) -{ - /* Init the ETH Callback settings */ - heth->TxCpltCallback = HAL_ETH_TxCpltCallback; /* Legacy weak TxCpltCallback */ - heth->RxCpltCallback = HAL_ETH_RxCpltCallback; /* Legacy weak RxCpltCallback */ - heth->DMAErrorCallback = HAL_ETH_ErrorCallback; /* Legacy weak DMAErrorCallback */ -} -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx ||\ - STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -#endif /* HAL_ETH_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c deleted file mode 100644 index 099bf1ea250fd84..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c +++ /dev/null @@ -1,549 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_exti.c - * @author MCD Application Team - * @brief EXTI HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Extended Interrupts and events controller (EXTI) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * - @verbatim - ============================================================================== - ##### EXTI Peripheral features ##### - ============================================================================== - [..] - (+) Each Exti line can be configured within this driver. - - (+) Exti line can be configured in 3 different modes - (++) Interrupt - (++) Event - (++) Both of them - - (+) Configurable Exti lines can be configured with 3 different triggers - (++) Rising - (++) Falling - (++) Both of them - - (+) When set in interrupt mode, configurable Exti lines have two different - interrupts pending registers which allow to distinguish which transition - occurs: - (++) Rising edge pending interrupt - (++) Falling - - (+) Exti lines 0 to 15 are linked to gpio pin number 0 to 15. Gpio port can - be selected through multiplexer. - - ##### How to use this driver ##### - ============================================================================== - [..] - - (#) Configure the EXTI line using HAL_EXTI_SetConfigLine(). - (++) Choose the interrupt line number by setting "Line" member from - EXTI_ConfigTypeDef structure. - (++) Configure the interrupt and/or event mode using "Mode" member from - EXTI_ConfigTypeDef structure. - (++) For configurable lines, configure rising and/or falling trigger - "Trigger" member from EXTI_ConfigTypeDef structure. - (++) For Exti lines linked to gpio, choose gpio port using "GPIOSel" - member from GPIO_InitTypeDef structure. - - (#) Get current Exti configuration of a dedicated line using - HAL_EXTI_GetConfigLine(). - (++) Provide exiting handle as parameter. - (++) Provide pointer on EXTI_ConfigTypeDef structure as second parameter. - - (#) Clear Exti configuration of a dedicated line using HAL_EXTI_GetConfigLine(). - (++) Provide exiting handle as parameter. - - (#) Register callback to treat Exti interrupts using HAL_EXTI_RegisterCallback(). - (++) Provide exiting handle as first parameter. - (++) Provide which callback will be registered using one value from - EXTI_CallbackIDTypeDef. - (++) Provide callback function pointer. - - (#) Get interrupt pending bit using HAL_EXTI_GetPending(). - - (#) Clear interrupt pending bit using HAL_EXTI_GetPending(). - - (#) Generate software interrupt using HAL_EXTI_GenerateSWI(). - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2018 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup EXTI - * @{ - */ -/** MISRA C:2012 deviation rule has been granted for following rule: - * Rule-18.1_b - Medium: Array `EXTICR' 1st subscript interval [0,7] may be out - * of bounds [0,3] in following API : - * HAL_EXTI_SetConfigLine - * HAL_EXTI_GetConfigLine - * HAL_EXTI_ClearConfigLine - */ - -#ifdef HAL_EXTI_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private defines -----------------------------------------------------------*/ -/** @defgroup EXTI_Private_Constants EXTI Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup EXTI_Exported_Functions - * @{ - */ - -/** @addtogroup EXTI_Exported_Functions_Group1 - * @brief Configuration functions - * -@verbatim - =============================================================================== - ##### Configuration functions ##### - =============================================================================== - -@endverbatim - * @{ - */ - -/** - * @brief Set configuration of a dedicated Exti line. - * @param hexti Exti handle. - * @param pExtiConfig Pointer on EXTI configuration to be set. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig) -{ - uint32_t regval; - uint32_t linepos; - uint32_t maskline; - - /* Check null pointer */ - if ((hexti == NULL) || (pExtiConfig == NULL)) - { - return HAL_ERROR; - } - - /* Check parameters */ - assert_param(IS_EXTI_LINE(pExtiConfig->Line)); - assert_param(IS_EXTI_MODE(pExtiConfig->Mode)); - - /* Assign line number to handle */ - hexti->Line = pExtiConfig->Line; - - /* Compute line mask */ - linepos = (pExtiConfig->Line & EXTI_PIN_MASK); - maskline = (1uL << linepos); - - /* Configure triggers for configurable lines */ - if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u) - { - assert_param(IS_EXTI_TRIGGER(pExtiConfig->Trigger)); - - /* Configure rising trigger */ - /* Mask or set line */ - if ((pExtiConfig->Trigger & EXTI_TRIGGER_RISING) != 0x00u) - { - EXTI->RTSR |= maskline; - } - else - { - EXTI->RTSR &= ~maskline; - } - - /* Configure falling trigger */ - /* Mask or set line */ - if ((pExtiConfig->Trigger & EXTI_TRIGGER_FALLING) != 0x00u) - { - EXTI->FTSR |= maskline; - } - else - { - EXTI->FTSR &= ~maskline; - } - - - /* Configure gpio port selection in case of gpio exti line */ - if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO) - { - assert_param(IS_EXTI_GPIO_PORT(pExtiConfig->GPIOSel)); - assert_param(IS_EXTI_GPIO_PIN(linepos)); - - regval = SYSCFG->EXTICR[linepos >> 2u]; - regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); - regval |= (pExtiConfig->GPIOSel << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); - SYSCFG->EXTICR[linepos >> 2u] = regval; - } - } - - /* Configure interrupt mode : read current mode */ - /* Mask or set line */ - if ((pExtiConfig->Mode & EXTI_MODE_INTERRUPT) != 0x00u) - { - EXTI->IMR |= maskline; - } - else - { - EXTI->IMR &= ~maskline; - } - - /* Configure event mode : read current mode */ - /* Mask or set line */ - if ((pExtiConfig->Mode & EXTI_MODE_EVENT) != 0x00u) - { - EXTI->EMR |= maskline; - } - else - { - EXTI->EMR &= ~maskline; - } - - return HAL_OK; -} - -/** - * @brief Get configuration of a dedicated Exti line. - * @param hexti Exti handle. - * @param pExtiConfig Pointer on structure to store Exti configuration. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig) -{ - uint32_t regval; - uint32_t linepos; - uint32_t maskline; - - /* Check null pointer */ - if ((hexti == NULL) || (pExtiConfig == NULL)) - { - return HAL_ERROR; - } - - /* Check the parameter */ - assert_param(IS_EXTI_LINE(hexti->Line)); - - /* Store handle line number to configuration structure */ - pExtiConfig->Line = hexti->Line; - - /* Compute line mask */ - linepos = (pExtiConfig->Line & EXTI_PIN_MASK); - maskline = (1uL << linepos); - - /* 1] Get core mode : interrupt */ - - /* Check if selected line is enable */ - if ((EXTI->IMR & maskline) != 0x00u) - { - pExtiConfig->Mode = EXTI_MODE_INTERRUPT; - } - else - { - pExtiConfig->Mode = EXTI_MODE_NONE; - } - - /* Get event mode */ - /* Check if selected line is enable */ - if ((EXTI->EMR & maskline) != 0x00u) - { - pExtiConfig->Mode |= EXTI_MODE_EVENT; - } - - /* Get default Trigger and GPIOSel configuration */ - pExtiConfig->Trigger = EXTI_TRIGGER_NONE; - pExtiConfig->GPIOSel = 0x00u; - - /* 2] Get trigger for configurable lines : rising */ - if ((pExtiConfig->Line & EXTI_CONFIG) != 0x00u) - { - /* Check if configuration of selected line is enable */ - if ((EXTI->RTSR & maskline) != 0x00u) - { - pExtiConfig->Trigger = EXTI_TRIGGER_RISING; - } - - /* Get falling configuration */ - /* Check if configuration of selected line is enable */ - if ((EXTI->FTSR & maskline) != 0x00u) - { - pExtiConfig->Trigger |= EXTI_TRIGGER_FALLING; - } - - /* Get Gpio port selection for gpio lines */ - if ((pExtiConfig->Line & EXTI_GPIO) == EXTI_GPIO) - { - assert_param(IS_EXTI_GPIO_PIN(linepos)); - - regval = SYSCFG->EXTICR[linepos >> 2u]; - pExtiConfig->GPIOSel = ((regval << (SYSCFG_EXTICR1_EXTI1_Pos * (3uL - (linepos & 0x03u)))) >> 24); - } - } - - return HAL_OK; -} - -/** - * @brief Clear whole configuration of a dedicated Exti line. - * @param hexti Exti handle. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti) -{ - uint32_t regval; - uint32_t linepos; - uint32_t maskline; - - /* Check null pointer */ - if (hexti == NULL) - { - return HAL_ERROR; - } - - /* Check the parameter */ - assert_param(IS_EXTI_LINE(hexti->Line)); - - /* compute line mask */ - linepos = (hexti->Line & EXTI_PIN_MASK); - maskline = (1uL << linepos); - - /* 1] Clear interrupt mode */ - EXTI->IMR = (EXTI->IMR & ~maskline); - - /* 2] Clear event mode */ - EXTI->EMR = (EXTI->EMR & ~maskline); - - /* 3] Clear triggers in case of configurable lines */ - if ((hexti->Line & EXTI_CONFIG) != 0x00u) - { - EXTI->RTSR = (EXTI->RTSR & ~maskline); - EXTI->FTSR = (EXTI->FTSR & ~maskline); - - /* Get Gpio port selection for gpio lines */ - if ((hexti->Line & EXTI_GPIO) == EXTI_GPIO) - { - assert_param(IS_EXTI_GPIO_PIN(linepos)); - - regval = SYSCFG->EXTICR[linepos >> 2u]; - regval &= ~(SYSCFG_EXTICR1_EXTI0 << (SYSCFG_EXTICR1_EXTI1_Pos * (linepos & 0x03u))); - SYSCFG->EXTICR[linepos >> 2u] = regval; - } - } - - return HAL_OK; -} - -/** - * @brief Register callback for a dedicated Exti line. - * @param hexti Exti handle. - * @param CallbackID User callback identifier. - * This parameter can be one of @arg @ref EXTI_CallbackIDTypeDef values. - * @param pPendingCbfn function pointer to be stored as callback. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void)) -{ - HAL_StatusTypeDef status = HAL_OK; - - switch (CallbackID) - { - case HAL_EXTI_COMMON_CB_ID: - hexti->PendingCallback = pPendingCbfn; - break; - - default: - status = HAL_ERROR; - break; - } - - return status; -} - -/** - * @brief Store line number as handle private field. - * @param hexti Exti handle. - * @param ExtiLine Exti line number. - * This parameter can be from 0 to @ref EXTI_LINE_NB. - * @retval HAL Status. - */ -HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine) -{ - /* Check the parameters */ - assert_param(IS_EXTI_LINE(ExtiLine)); - - /* Check null pointer */ - if (hexti == NULL) - { - return HAL_ERROR; - } - else - { - /* Store line number as handle private field */ - hexti->Line = ExtiLine; - - return HAL_OK; - } -} - -/** - * @} - */ - -/** @addtogroup EXTI_Exported_Functions_Group2 - * @brief EXTI IO functions. - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - -@endverbatim - * @{ - */ - -/** - * @brief Handle EXTI interrupt request. - * @param hexti Exti handle. - * @retval none. - */ -void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti) -{ - uint32_t regval; - uint32_t maskline; - - /* Compute line mask */ - maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); - - /* Get pending bit */ - regval = (EXTI->PR & maskline); - if (regval != 0x00u) - { - /* Clear pending bit */ - EXTI->PR = maskline; - - /* Call callback */ - if (hexti->PendingCallback != NULL) - { - hexti->PendingCallback(); - } - } -} - -/** - * @brief Get interrupt pending bit of a dedicated line. - * @param hexti Exti handle. - * @param Edge Specify which pending edge as to be checked. - * This parameter can be one of the following values: - * @arg @ref EXTI_TRIGGER_RISING_FALLING - * This parameter is kept for compatibility with other series. - * @retval 1 if interrupt is pending else 0. - */ -uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge) -{ - uint32_t regval; - uint32_t linepos; - uint32_t maskline; - - /* Check parameters */ - assert_param(IS_EXTI_LINE(hexti->Line)); - assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); - assert_param(IS_EXTI_PENDING_EDGE(Edge)); - - /* Compute line mask */ - linepos = (hexti->Line & EXTI_PIN_MASK); - maskline = (1uL << linepos); - - /* return 1 if bit is set else 0 */ - regval = ((EXTI->PR & maskline) >> linepos); - return regval; -} - -/** - * @brief Clear interrupt pending bit of a dedicated line. - * @param hexti Exti handle. - * @param Edge Specify which pending edge as to be clear. - * This parameter can be one of the following values: - * @arg @ref EXTI_TRIGGER_RISING_FALLING - * This parameter is kept for compatibility with other series. - * @retval None. - */ -void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge) -{ - uint32_t maskline; - - /* Check parameters */ - assert_param(IS_EXTI_LINE(hexti->Line)); - assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); - assert_param(IS_EXTI_PENDING_EDGE(Edge)); - - /* Compute line mask */ - maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); - - /* Clear Pending bit */ - EXTI->PR = maskline; -} - -/** - * @brief Generate a software interrupt for a dedicated line. - * @param hexti Exti handle. - * @retval None. - */ -void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti) -{ - uint32_t maskline; - - /* Check parameters */ - assert_param(IS_EXTI_LINE(hexti->Line)); - assert_param(IS_EXTI_CONFIG_LINE(hexti->Line)); - - /* Compute line mask */ - maskline = (1uL << (hexti->Line & EXTI_PIN_MASK)); - - /* Generate Software interrupt */ - EXTI->SWIER = maskline; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_EXTI_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c deleted file mode 100644 index 69b47a6eca79573..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c +++ /dev/null @@ -1,778 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash.c - * @author MCD Application Team - * @brief FLASH HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the internal FLASH memory: - * + Program operations functions - * + Memory Control functions - * + Peripheral Errors functions - * - @verbatim - ============================================================================== - ##### FLASH peripheral features ##### - ============================================================================== - - [..] The Flash memory interface manages CPU AHB I-Code and D-Code accesses - to the Flash memory. It implements the erase and program Flash memory operations - and the read and write protection mechanisms. - - [..] The Flash memory interface accelerates code execution with a system of instruction - prefetch and cache lines. - - [..] The FLASH main features are: - (+) Flash memory read operations - (+) Flash memory program/erase operations - (+) Read / write protections - (+) Prefetch on I-Code - (+) 64 cache lines of 128 bits on I-Code - (+) 8 cache lines of 128 bits on D-Code - - - ##### How to use this driver ##### - ============================================================================== - [..] - This driver provides functions and macros to configure and program the FLASH - memory of all STM32F4xx devices. - - (#) FLASH Memory IO Programming functions: - (++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and - HAL_FLASH_Lock() functions - (++) Program functions: byte, half word, word and double word - (++) There Two modes of programming : - (+++) Polling mode using HAL_FLASH_Program() function - (+++) Interrupt mode using HAL_FLASH_Program_IT() function - - (#) Interrupts and flags management functions : - (++) Handle FLASH interrupts by calling HAL_FLASH_IRQHandler() - (++) Wait for last FLASH operation according to its status - (++) Get error flag status by calling HAL_SetErrorCode() - - [..] - In addition to these functions, this driver includes a set of macros allowing - to handle the following operations: - (+) Set the latency - (+) Enable/Disable the prefetch buffer - (+) Enable/Disable the Instruction cache and the Data cache - (+) Reset the Instruction cache and the Data cache - (+) Enable/Disable the FLASH interrupts - (+) Monitor the FLASH flags status - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FLASH FLASH - * @brief FLASH HAL module driver - * @{ - */ - -#ifdef HAL_FLASH_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup FLASH_Private_Constants - * @{ - */ -#define FLASH_TIMEOUT_VALUE 50000U /* 50 s */ -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @addtogroup FLASH_Private_Variables - * @{ - */ -/* Variable used for Erase sectors under interruption */ -FLASH_ProcessTypeDef pFlash; -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup FLASH_Private_Functions - * @{ - */ -/* Program operations */ -static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data); -static void FLASH_Program_Word(uint32_t Address, uint32_t Data); -static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data); -static void FLASH_Program_Byte(uint32_t Address, uint8_t Data); -static void FLASH_SetErrorCode(void); - -HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Functions FLASH Exported Functions - * @{ - */ - -/** @defgroup FLASH_Exported_Functions_Group1 Programming operation functions - * @brief Programming operation functions - * -@verbatim - =============================================================================== - ##### Programming operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the FLASH - program operations. - -@endverbatim - * @{ - */ - -/** - * @brief Program byte, halfword, word or double word at a specified address - * @param TypeProgram Indicate the way to program at a specified address. - * This parameter can be a value of @ref FLASH_Type_Program - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed - * - * @retval HAL_StatusTypeDef HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data) -{ - HAL_StatusTypeDef status = HAL_ERROR; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if(status == HAL_OK) - { - if(TypeProgram == FLASH_TYPEPROGRAM_BYTE) - { - /*Program byte (8-bit) at a specified address.*/ - FLASH_Program_Byte(Address, (uint8_t) Data); - } - else if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD) - { - /*Program halfword (16-bit) at a specified address.*/ - FLASH_Program_HalfWord(Address, (uint16_t) Data); - } - else if(TypeProgram == FLASH_TYPEPROGRAM_WORD) - { - /*Program word (32-bit) at a specified address.*/ - FLASH_Program_Word(Address, (uint32_t) Data); - } - else - { - /*Program double word (64-bit) at a specified address.*/ - FLASH_Program_DoubleWord(Address, Data); - } - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - /* If the program operation is completed, disable the PG Bit */ - FLASH->CR &= (~FLASH_CR_PG); - } - - /* Process Unlocked */ - __HAL_UNLOCK(&pFlash); - - return status; -} - -/** - * @brief Program byte, halfword, word or double word at a specified address with interrupt enabled. - * @param TypeProgram Indicate the way to program at a specified address. - * This parameter can be a value of @ref FLASH_Type_Program - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_FLASH_TYPEPROGRAM(TypeProgram)); - - /* Enable End of FLASH Operation interrupt */ - __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP); - - /* Enable Error source interrupt */ - __HAL_FLASH_ENABLE_IT(FLASH_IT_ERR); - - pFlash.ProcedureOnGoing = FLASH_PROC_PROGRAM; - pFlash.Address = Address; - - if(TypeProgram == FLASH_TYPEPROGRAM_BYTE) - { - /*Program byte (8-bit) at a specified address.*/ - FLASH_Program_Byte(Address, (uint8_t) Data); - } - else if(TypeProgram == FLASH_TYPEPROGRAM_HALFWORD) - { - /*Program halfword (16-bit) at a specified address.*/ - FLASH_Program_HalfWord(Address, (uint16_t) Data); - } - else if(TypeProgram == FLASH_TYPEPROGRAM_WORD) - { - /*Program word (32-bit) at a specified address.*/ - FLASH_Program_Word(Address, (uint32_t) Data); - } - else - { - /*Program double word (64-bit) at a specified address.*/ - FLASH_Program_DoubleWord(Address, Data); - } - - return status; -} - -/** - * @brief This function handles FLASH interrupt request. - * @retval None - */ -void HAL_FLASH_IRQHandler(void) -{ - uint32_t addresstmp = 0U; - - /* Check FLASH operation error flags */ -#if defined(FLASH_SR_RDERR) - if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ - FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR | FLASH_FLAG_RDERR)) != RESET) -#else - if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ - FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR)) != RESET) -#endif /* FLASH_SR_RDERR */ - { - if(pFlash.ProcedureOnGoing == FLASH_PROC_SECTERASE) - { - /*return the faulty sector*/ - addresstmp = pFlash.Sector; - pFlash.Sector = 0xFFFFFFFFU; - } - else if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE) - { - /*return the faulty bank*/ - addresstmp = pFlash.Bank; - } - else - { - /*return the faulty address*/ - addresstmp = pFlash.Address; - } - - /*Save the Error code*/ - FLASH_SetErrorCode(); - - /* FLASH error interrupt user callback */ - HAL_FLASH_OperationErrorCallback(addresstmp); - - /*Stop the procedure ongoing*/ - pFlash.ProcedureOnGoing = FLASH_PROC_NONE; - } - - /* Check FLASH End of Operation flag */ - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) - { - /* Clear FLASH End of Operation pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP); - - if(pFlash.ProcedureOnGoing == FLASH_PROC_SECTERASE) - { - /*Nb of sector to erased can be decreased*/ - pFlash.NbSectorsToErase--; - - /* Check if there are still sectors to erase*/ - if(pFlash.NbSectorsToErase != 0U) - { - addresstmp = pFlash.Sector; - /*Indicate user which sector has been erased*/ - HAL_FLASH_EndOfOperationCallback(addresstmp); - - /*Increment sector number*/ - pFlash.Sector++; - addresstmp = pFlash.Sector; - FLASH_Erase_Sector(addresstmp, pFlash.VoltageForErase); - } - else - { - /*No more sectors to Erase, user callback can be called.*/ - /*Reset Sector and stop Erase sectors procedure*/ - pFlash.Sector = addresstmp = 0xFFFFFFFFU; - pFlash.ProcedureOnGoing = FLASH_PROC_NONE; - - /* Flush the caches to be sure of the data consistency */ - FLASH_FlushCaches() ; - - /* FLASH EOP interrupt user callback */ - HAL_FLASH_EndOfOperationCallback(addresstmp); - } - } - else - { - if(pFlash.ProcedureOnGoing == FLASH_PROC_MASSERASE) - { - /* MassErase ended. Return the selected bank */ - /* Flush the caches to be sure of the data consistency */ - FLASH_FlushCaches() ; - - /* FLASH EOP interrupt user callback */ - HAL_FLASH_EndOfOperationCallback(pFlash.Bank); - } - else - { - /*Program ended. Return the selected address*/ - /* FLASH EOP interrupt user callback */ - HAL_FLASH_EndOfOperationCallback(pFlash.Address); - } - pFlash.ProcedureOnGoing = FLASH_PROC_NONE; - } - } - - if(pFlash.ProcedureOnGoing == FLASH_PROC_NONE) - { - /* Operation is completed, disable the PG, SER, SNB and MER Bits */ - CLEAR_BIT(FLASH->CR, (FLASH_CR_PG | FLASH_CR_SER | FLASH_CR_SNB | FLASH_MER_BIT)); - - /* Disable End of FLASH Operation interrupt */ - __HAL_FLASH_DISABLE_IT(FLASH_IT_EOP); - - /* Disable Error source interrupt */ - __HAL_FLASH_DISABLE_IT(FLASH_IT_ERR); - - /* Process Unlocked */ - __HAL_UNLOCK(&pFlash); - } -} - -/** - * @brief FLASH end of operation interrupt callback - * @param ReturnValue The value saved in this parameter depends on the ongoing procedure - * Mass Erase: Bank number which has been requested to erase - * Sectors Erase: Sector which has been erased - * (if 0xFFFFFFFFU, it means that all the selected sectors have been erased) - * Program: Address which was selected for data program - * @retval None - */ -__weak void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(ReturnValue); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_FLASH_EndOfOperationCallback could be implemented in the user file - */ -} - -/** - * @brief FLASH operation error interrupt callback - * @param ReturnValue The value saved in this parameter depends on the ongoing procedure - * Mass Erase: Bank number which has been requested to erase - * Sectors Erase: Sector number which returned an error - * Program: Address which was selected for data program - * @retval None - */ -__weak void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(ReturnValue); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_FLASH_OperationErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup FLASH_Exported_Functions_Group2 Peripheral Control functions - * @brief management functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the FLASH - memory operations. - -@endverbatim - * @{ - */ - -/** - * @brief Unlock the FLASH control register access - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_Unlock(void) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET) - { - /* Authorize the FLASH Registers access */ - WRITE_REG(FLASH->KEYR, FLASH_KEY1); - WRITE_REG(FLASH->KEYR, FLASH_KEY2); - - /* Verify Flash is unlocked */ - if(READ_BIT(FLASH->CR, FLASH_CR_LOCK) != RESET) - { - status = HAL_ERROR; - } - } - - return status; -} - -/** - * @brief Locks the FLASH control register access - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_Lock(void) -{ - /* Set the LOCK Bit to lock the FLASH Registers access */ - FLASH->CR |= FLASH_CR_LOCK; - - return HAL_OK; -} - -/** - * @brief Unlock the FLASH Option Control Registers access. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void) -{ - if((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != RESET) - { - /* Authorizes the Option Byte register programming */ - FLASH->OPTKEYR = FLASH_OPT_KEY1; - FLASH->OPTKEYR = FLASH_OPT_KEY2; - } - else - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Lock the FLASH Option Control Registers access. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_OB_Lock(void) -{ - /* Set the OPTLOCK Bit to lock the FLASH Option Byte Registers access */ - FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK; - - return HAL_OK; -} - -/** - * @brief Launch the option byte loading. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASH_OB_Launch(void) -{ - /* Set the OPTSTRT bit in OPTCR register */ - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= FLASH_OPTCR_OPTSTRT; - - /* Wait for last operation to be completed */ - return(FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE)); -} - -/** - * @} - */ - -/** @defgroup FLASH_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief Peripheral Errors functions - * -@verbatim - =============================================================================== - ##### Peripheral Errors functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time Errors of the FLASH peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Get the specific FLASH error flag. - * @retval FLASH_ErrorCode: The returned value can be a combination of: - * @arg HAL_FLASH_ERROR_RD: FLASH Read Protection error flag (PCROP) - * @arg HAL_FLASH_ERROR_PGS: FLASH Programming Sequence error flag - * @arg HAL_FLASH_ERROR_PGP: FLASH Programming Parallelism error flag - * @arg HAL_FLASH_ERROR_PGA: FLASH Programming Alignment error flag - * @arg HAL_FLASH_ERROR_WRP: FLASH Write protected error flag - * @arg HAL_FLASH_ERROR_OPERATION: FLASH operation Error flag - */ -uint32_t HAL_FLASH_GetError(void) -{ - return pFlash.ErrorCode; -} - -/** - * @} - */ - -/** - * @brief Wait for a FLASH operation to complete. - * @param Timeout maximum flash operationtimeout - * @retval HAL Status - */ -HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Clear Error Code */ - pFlash.ErrorCode = HAL_FLASH_ERROR_NONE; - - /* Wait for the FLASH operation to complete by polling on BUSY flag to be reset. - Even if the FLASH operation fails, the BUSY flag will be reset and an error - flag will be set */ - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_FLASH_GET_FLAG(FLASH_FLAG_BSY) != RESET) - { - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - return HAL_TIMEOUT; - } - } - } - - /* Check FLASH End of Operation flag */ - if (__HAL_FLASH_GET_FLAG(FLASH_FLAG_EOP) != RESET) - { - /* Clear FLASH End of Operation pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP); - } -#if defined(FLASH_SR_RDERR) - if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ - FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR | FLASH_FLAG_RDERR)) != RESET) -#else - if(__HAL_FLASH_GET_FLAG((FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | \ - FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR)) != RESET) -#endif /* FLASH_SR_RDERR */ - { - /*Save the error code*/ - FLASH_SetErrorCode(); - return HAL_ERROR; - } - - /* If there is no error flag set */ - return HAL_OK; - -} - -/** - * @brief Program a double word (64-bit) at a specified address. - * @note This function must be used when the device voltage range is from - * 2.7V to 3.6V and Vpp in the range 7V to 9V. - * - * @note If an erase and a program operations are requested simultaneously, - * the erase operation is performed before the program one. - * - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed. - * @retval None - */ -static void FLASH_Program_DoubleWord(uint32_t Address, uint64_t Data) -{ - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - - /* If the previous operation is completed, proceed to program the new data */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_PSIZE_DOUBLE_WORD; - FLASH->CR |= FLASH_CR_PG; - - /* Program first word */ - *(__IO uint32_t*)Address = (uint32_t)Data; - - /* Barrier to ensure programming is performed in 2 steps, in right order - (independently of compiler optimization behavior) */ - __ISB(); - - /* Program second word */ - *(__IO uint32_t*)(Address+4) = (uint32_t)(Data >> 32); -} - - -/** - * @brief Program word (32-bit) at a specified address. - * @note This function must be used when the device voltage range is from - * 2.7V to 3.6V. - * - * @note If an erase and a program operations are requested simultaneously, - * the erase operation is performed before the program one. - * - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed. - * @retval None - */ -static void FLASH_Program_Word(uint32_t Address, uint32_t Data) -{ - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - - /* If the previous operation is completed, proceed to program the new data */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_PSIZE_WORD; - FLASH->CR |= FLASH_CR_PG; - - *(__IO uint32_t*)Address = Data; -} - -/** - * @brief Program a half-word (16-bit) at a specified address. - * @note This function must be used when the device voltage range is from - * 2.1V to 3.6V. - * - * @note If an erase and a program operations are requested simultaneously, - * the erase operation is performed before the program one. - * - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed. - * @retval None - */ -static void FLASH_Program_HalfWord(uint32_t Address, uint16_t Data) -{ - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - - /* If the previous operation is completed, proceed to program the new data */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_PSIZE_HALF_WORD; - FLASH->CR |= FLASH_CR_PG; - - *(__IO uint16_t*)Address = Data; -} - -/** - * @brief Program byte (8-bit) at a specified address. - * @note This function must be used when the device voltage range is from - * 1.8V to 3.6V. - * - * @note If an erase and a program operations are requested simultaneously, - * the erase operation is performed before the program one. - * - * @param Address specifies the address to be programmed. - * @param Data specifies the data to be programmed. - * @retval None - */ -static void FLASH_Program_Byte(uint32_t Address, uint8_t Data) -{ - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - - /* If the previous operation is completed, proceed to program the new data */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_PSIZE_BYTE; - FLASH->CR |= FLASH_CR_PG; - - *(__IO uint8_t*)Address = Data; -} - -/** - * @brief Set the specific FLASH error flag. - * @retval None - */ -static void FLASH_SetErrorCode(void) -{ - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_WRPERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_WRP; - - /* Clear FLASH write protection error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_WRPERR); - } - - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGAERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_PGA; - - /* Clear FLASH Programming alignment error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGAERR); - } - - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGPERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_PGP; - - /* Clear FLASH Programming parallelism error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGPERR); - } - - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_PGSERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_PGS; - - /* Clear FLASH Programming sequence error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_PGSERR); - } -#if defined(FLASH_SR_RDERR) - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_RDERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_RD; - - /* Clear FLASH Proprietary readout protection error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_RDERR); - } -#endif /* FLASH_SR_RDERR */ - if(__HAL_FLASH_GET_FLAG(FLASH_FLAG_OPERR) != RESET) - { - pFlash.ErrorCode |= HAL_FLASH_ERROR_OPERATION; - - /* Clear FLASH Operation error pending bit */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR); - } -} - -/** - * @} - */ - -#endif /* HAL_FLASH_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c deleted file mode 100644 index 628e78958503d65..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c +++ /dev/null @@ -1,1353 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ex.c - * @author MCD Application Team - * @brief Extended FLASH HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the FLASH extension peripheral: - * + Extended programming operations functions - * - @verbatim - ============================================================================== - ##### Flash Extension features ##### - ============================================================================== - - [..] Comparing to other previous devices, the FLASH interface for STM32F427xx/437xx and - STM32F429xx/439xx devices contains the following additional features - - (+) Capacity up to 2 Mbyte with dual bank architecture supporting read-while-write - capability (RWW) - (+) Dual bank memory organization - (+) PCROP protection for all banks - - ##### How to use this driver ##### - ============================================================================== - [..] This driver provides functions to configure and program the FLASH memory - of all STM32F427xx/437xx, STM32F429xx/439xx, STM32F469xx/479xx and STM32F446xx - devices. It includes - (#) FLASH Memory Erase functions: - (++) Lock and Unlock the FLASH interface using HAL_FLASH_Unlock() and - HAL_FLASH_Lock() functions - (++) Erase function: Erase sector, erase all sectors - (++) There are two modes of erase : - (+++) Polling Mode using HAL_FLASHEx_Erase() - (+++) Interrupt Mode using HAL_FLASHEx_Erase_IT() - - (#) Option Bytes Programming functions: Use HAL_FLASHEx_OBProgram() to : - (++) Set/Reset the write protection - (++) Set the Read protection Level - (++) Set the BOR level - (++) Program the user Option Bytes - (#) Advanced Option Bytes Programming functions: Use HAL_FLASHEx_AdvOBProgram() to : - (++) Extended space (bank 2) erase function - (++) Full FLASH space (2 Mo) erase (bank 1 and bank 2) - (++) Dual Boot activation - (++) Write protection configuration for bank 2 - (++) PCROP protection configuration and control for both banks - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FLASHEx FLASHEx - * @brief FLASH HAL Extension module driver - * @{ - */ - -#ifdef HAL_FLASH_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup FLASHEx_Private_Constants - * @{ - */ -#define FLASH_TIMEOUT_VALUE 50000U /* 50 s */ -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @addtogroup FLASHEx_Private_Variables - * @{ - */ -extern FLASH_ProcessTypeDef pFlash; -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup FLASHEx_Private_Functions - * @{ - */ -/* Option bytes control */ -static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t Level); -static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t Iwdg, uint8_t Stop, uint8_t Stdby); -static HAL_StatusTypeDef FLASH_OB_BOR_LevelConfig(uint8_t Level); -static uint8_t FLASH_OB_GetUser(void); -static uint16_t FLASH_OB_GetWRP(void); -static uint8_t FLASH_OB_GetRDP(void); -static uint8_t FLASH_OB_GetBOR(void); - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ - defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t Sector); -static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t Sector); -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx - STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks); -static HAL_StatusTypeDef FLASH_OB_BootConfig(uint8_t BootConfig); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -extern HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup FLASHEx_Exported_Functions FLASHEx Exported Functions - * @{ - */ - -/** @defgroup FLASHEx_Exported_Functions_Group1 Extended IO operation functions - * @brief Extended IO operation functions - * -@verbatim - =============================================================================== - ##### Extended programming operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the Extension FLASH - programming operations. - -@endverbatim - * @{ - */ -/** - * @brief Perform a mass erase or erase the specified FLASH memory sectors - * @param[in] pEraseInit pointer to an FLASH_EraseInitTypeDef structure that - * contains the configuration information for the erasing. - * - * @param[out] SectorError pointer to variable that - * contains the configuration information on faulty sector in case of error - * (0xFFFFFFFFU means that all the sectors have been correctly erased) - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_Erase(FLASH_EraseInitTypeDef *pEraseInit, uint32_t *SectorError) -{ - HAL_StatusTypeDef status = HAL_ERROR; - uint32_t index = 0U; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /*Initialization of SectorError variable*/ - *SectorError = 0xFFFFFFFFU; - - if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE) - { - /*Mass erase to be done*/ - FLASH_MassErase((uint8_t) pEraseInit->VoltageRange, pEraseInit->Banks); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - /* if the erase operation is completed, disable the MER Bit */ - FLASH->CR &= (~FLASH_MER_BIT); - } - else - { - /* Check the parameters */ - assert_param(IS_FLASH_NBSECTORS(pEraseInit->NbSectors + pEraseInit->Sector)); - - /* Erase by sector by sector to be done*/ - for (index = pEraseInit->Sector; index < (pEraseInit->NbSectors + pEraseInit->Sector); index++) - { - FLASH_Erase_Sector(index, (uint8_t) pEraseInit->VoltageRange); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - /* If the erase operation is completed, disable the SER and SNB Bits */ - CLEAR_BIT(FLASH->CR, (FLASH_CR_SER | FLASH_CR_SNB)); - - if (status != HAL_OK) - { - /* In case of error, stop erase procedure and return the faulty sector*/ - *SectorError = index; - break; - } - } - } - /* Flush the caches to be sure of the data consistency */ - FLASH_FlushCaches(); - } - - /* Process Unlocked */ - __HAL_UNLOCK(&pFlash); - - return status; -} - -/** - * @brief Perform a mass erase or erase the specified FLASH memory sectors with interrupt enabled - * @param pEraseInit pointer to an FLASH_EraseInitTypeDef structure that - * contains the configuration information for the erasing. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_Erase_IT(FLASH_EraseInitTypeDef *pEraseInit) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_FLASH_TYPEERASE(pEraseInit->TypeErase)); - - /* Enable End of FLASH Operation interrupt */ - __HAL_FLASH_ENABLE_IT(FLASH_IT_EOP); - - /* Enable Error source interrupt */ - __HAL_FLASH_ENABLE_IT(FLASH_IT_ERR); - - /* Clear pending flags (if any) */ - __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | \ - FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR); - - if (pEraseInit->TypeErase == FLASH_TYPEERASE_MASSERASE) - { - /*Mass erase to be done*/ - pFlash.ProcedureOnGoing = FLASH_PROC_MASSERASE; - pFlash.Bank = pEraseInit->Banks; - FLASH_MassErase((uint8_t) pEraseInit->VoltageRange, pEraseInit->Banks); - } - else - { - /* Erase by sector to be done*/ - - /* Check the parameters */ - assert_param(IS_FLASH_NBSECTORS(pEraseInit->NbSectors + pEraseInit->Sector)); - - pFlash.ProcedureOnGoing = FLASH_PROC_SECTERASE; - pFlash.NbSectorsToErase = pEraseInit->NbSectors; - pFlash.Sector = pEraseInit->Sector; - pFlash.VoltageForErase = (uint8_t)pEraseInit->VoltageRange; - - /*Erase 1st sector and wait for IT*/ - FLASH_Erase_Sector(pEraseInit->Sector, pEraseInit->VoltageRange); - } - - return status; -} - -/** - * @brief Program option bytes - * @param pOBInit pointer to an FLASH_OBInitStruct structure that - * contains the configuration information for the programming. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit) -{ - HAL_StatusTypeDef status = HAL_ERROR; - - /* Process Locked */ - __HAL_LOCK(&pFlash); - - /* Check the parameters */ - assert_param(IS_OPTIONBYTE(pOBInit->OptionType)); - - /*Write protection configuration*/ - if ((pOBInit->OptionType & OPTIONBYTE_WRP) == OPTIONBYTE_WRP) - { - assert_param(IS_WRPSTATE(pOBInit->WRPState)); - if (pOBInit->WRPState == OB_WRPSTATE_ENABLE) - { - /*Enable of Write protection on the selected Sector*/ - status = FLASH_OB_EnableWRP(pOBInit->WRPSector, pOBInit->Banks); - } - else - { - /*Disable of Write protection on the selected Sector*/ - status = FLASH_OB_DisableWRP(pOBInit->WRPSector, pOBInit->Banks); - } - } - - /*Read protection configuration*/ - if ((pOBInit->OptionType & OPTIONBYTE_RDP) == OPTIONBYTE_RDP) - { - status = FLASH_OB_RDP_LevelConfig(pOBInit->RDPLevel); - } - - /*USER configuration*/ - if ((pOBInit->OptionType & OPTIONBYTE_USER) == OPTIONBYTE_USER) - { - status = FLASH_OB_UserConfig(pOBInit->USERConfig & OB_IWDG_SW, - pOBInit->USERConfig & OB_STOP_NO_RST, - pOBInit->USERConfig & OB_STDBY_NO_RST); - } - - /*BOR Level configuration*/ - if ((pOBInit->OptionType & OPTIONBYTE_BOR) == OPTIONBYTE_BOR) - { - status = FLASH_OB_BOR_LevelConfig(pOBInit->BORLevel); - } - - /* Process Unlocked */ - __HAL_UNLOCK(&pFlash); - - return status; -} - -/** - * @brief Get the Option byte configuration - * @param pOBInit pointer to an FLASH_OBInitStruct structure that - * contains the configuration information for the programming. - * - * @retval None - */ -void HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit) -{ - pOBInit->OptionType = OPTIONBYTE_WRP | OPTIONBYTE_RDP | OPTIONBYTE_USER | OPTIONBYTE_BOR; - - /*Get WRP*/ - pOBInit->WRPSector = (uint32_t)FLASH_OB_GetWRP(); - - /*Get RDP Level*/ - pOBInit->RDPLevel = (uint32_t)FLASH_OB_GetRDP(); - - /*Get USER*/ - pOBInit->USERConfig = (uint8_t)FLASH_OB_GetUser(); - - /*Get BOR Level*/ - pOBInit->BORLevel = (uint32_t)FLASH_OB_GetBOR(); -} - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Program option bytes - * @param pAdvOBInit pointer to an FLASH_AdvOBProgramInitTypeDef structure that - * contains the configuration information for the programming. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_AdvOBProgram(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit) -{ - HAL_StatusTypeDef status = HAL_ERROR; - - /* Check the parameters */ - assert_param(IS_OBEX(pAdvOBInit->OptionType)); - - /*Program PCROP option byte*/ - if (((pAdvOBInit->OptionType) & OPTIONBYTE_PCROP) == OPTIONBYTE_PCROP) - { - /* Check the parameters */ - assert_param(IS_PCROPSTATE(pAdvOBInit->PCROPState)); - if ((pAdvOBInit->PCROPState) == OB_PCROP_STATE_ENABLE) - { - /*Enable of Write protection on the selected Sector*/ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - status = FLASH_OB_EnablePCROP(pAdvOBInit->Sectors); -#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - status = FLASH_OB_EnablePCROP(pAdvOBInit->SectorsBank1, pAdvOBInit->SectorsBank2, pAdvOBInit->Banks); -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - } - else - { - /*Disable of Write protection on the selected Sector*/ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - status = FLASH_OB_DisablePCROP(pAdvOBInit->Sectors); -#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - status = FLASH_OB_DisablePCROP(pAdvOBInit->SectorsBank1, pAdvOBInit->SectorsBank2, pAdvOBInit->Banks); -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - } - } - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - /*Program BOOT config option byte*/ - if (((pAdvOBInit->OptionType) & OPTIONBYTE_BOOTCONFIG) == OPTIONBYTE_BOOTCONFIG) - { - status = FLASH_OB_BootConfig(pAdvOBInit->BootConfig); - } -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - - return status; -} - -/** - * @brief Get the OBEX byte configuration - * @param pAdvOBInit pointer to an FLASH_AdvOBProgramInitTypeDef structure that - * contains the configuration information for the programming. - * - * @retval None - */ -void HAL_FLASHEx_AdvOBGetConfig(FLASH_AdvOBProgramInitTypeDef *pAdvOBInit) -{ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /*Get Sector*/ - pAdvOBInit->Sectors = (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); -#else /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - /*Get Sector for Bank1*/ - pAdvOBInit->SectorsBank1 = (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); - - /*Get Sector for Bank2*/ - pAdvOBInit->SectorsBank2 = (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS)); - - /*Get Boot config OB*/ - pAdvOBInit->BootConfig = *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS; -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ -} - -/** - * @brief Select the Protection Mode - * - * @note After PCROP activated Option Byte modification NOT POSSIBLE! excepted - * Global Read Out Protection modification (from level1 to level0) - * @note Once SPRMOD bit is active unprotection of a protected sector is not possible - * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag - * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F401xx/STM32F411xx/STM32F446xx/ - * STM32F469xx/STM32F479xx/STM32F412xx/STM32F413xx devices. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_OB_SelectPCROP(void) -{ - uint8_t optiontmp = 0xFF; - - /* Mask SPRMOD bit */ - optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); - - /* Update Option Byte */ - *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PCROP_SELECTED | optiontmp); - - return HAL_OK; -} - -/** - * @brief Deselect the Protection Mode - * - * @note After PCROP activated Option Byte modification NOT POSSIBLE! excepted - * Global Read Out Protection modification (from level1 to level0) - * @note Once SPRMOD bit is active unprotection of a protected sector is not possible - * @note Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag - * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F401xx/STM32F411xx/STM32F446xx/ - * STM32F469xx/STM32F479xx/STM32F412xx/STM32F413xx devices. - * - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_FLASHEx_OB_DeSelectPCROP(void) -{ - uint8_t optiontmp = 0xFF; - - /* Mask SPRMOD bit */ - optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); - - /* Update Option Byte */ - *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PCROP_DESELECTED | optiontmp); - - return HAL_OK; -} -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE || STM32F410xx ||\ - STM32F411xE || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Returns the FLASH Write Protection Option Bytes value for Bank 2 - * @note This function can be used only for STM32F42xxx/STM32F43xxx/STM32F469xx/STM32F479xx devices. - * @retval The FLASH Write Protection Option Bytes value - */ -uint16_t HAL_FLASHEx_OB_GetBank2WRP(void) -{ - /* Return the FLASH write protection Register value */ - return (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS)); -} -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Full erase of FLASH memory sectors - * @param VoltageRange The device voltage range which defines the erase parallelism. - * This parameter can be one of the following values: - * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, - * the operation will be done by byte (8-bit) - * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, - * the operation will be done by half word (16-bit) - * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, - * the operation will be done by word (32-bit) - * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, - * the operation will be done by double word (64-bit) - * - * @param Banks Banks to be erased - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: Bank1 to be erased - * @arg FLASH_BANK_2: Bank2 to be erased - * @arg FLASH_BANK_BOTH: Bank1 and Bank2 to be erased - * - * @retval HAL Status - */ -static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks) -{ - /* Check the parameters */ - assert_param(IS_VOLTAGERANGE(VoltageRange)); - assert_param(IS_FLASH_BANK(Banks)); - - /* if the previous operation is completed, proceed to erase all sectors */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - - if (Banks == FLASH_BANK_BOTH) - { - /* bank1 & bank2 will be erased*/ - FLASH->CR |= FLASH_MER_BIT; - } - else if (Banks == FLASH_BANK_1) - { - /*Only bank1 will be erased*/ - FLASH->CR |= FLASH_CR_MER1; - } - else - { - /*Only bank2 will be erased*/ - FLASH->CR |= FLASH_CR_MER2; - } - FLASH->CR |= FLASH_CR_STRT | ((uint32_t)VoltageRange << 8U); -} - -/** - * @brief Erase the specified FLASH memory sector - * @param Sector FLASH sector to erase - * The value of this parameter depend on device used within the same series - * @param VoltageRange The device voltage range which defines the erase parallelism. - * This parameter can be one of the following values: - * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, - * the operation will be done by byte (8-bit) - * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, - * the operation will be done by half word (16-bit) - * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, - * the operation will be done by word (32-bit) - * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, - * the operation will be done by double word (64-bit) - * - * @retval None - */ -void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange) -{ - uint32_t tmp_psize = 0U; - - /* Check the parameters */ - assert_param(IS_FLASH_SECTOR(Sector)); - assert_param(IS_VOLTAGERANGE(VoltageRange)); - - if (VoltageRange == FLASH_VOLTAGE_RANGE_1) - { - tmp_psize = FLASH_PSIZE_BYTE; - } - else if (VoltageRange == FLASH_VOLTAGE_RANGE_2) - { - tmp_psize = FLASH_PSIZE_HALF_WORD; - } - else if (VoltageRange == FLASH_VOLTAGE_RANGE_3) - { - tmp_psize = FLASH_PSIZE_WORD; - } - else - { - tmp_psize = FLASH_PSIZE_DOUBLE_WORD; - } - - /* Need to add offset of 4 when sector higher than FLASH_SECTOR_11 */ - if (Sector > FLASH_SECTOR_11) - { - Sector += 4U; - } - /* If the previous operation is completed, proceed to erase the sector */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= tmp_psize; - CLEAR_BIT(FLASH->CR, FLASH_CR_SNB); - FLASH->CR |= FLASH_CR_SER | (Sector << FLASH_CR_SNB_Pos); - FLASH->CR |= FLASH_CR_STRT; -} - -/** - * @brief Enable the write protection of the desired bank1 or bank 2 sectors - * - * @note When the memory read protection level is selected (RDP level = 1), - * it is not possible to program or erase the flash sector i if CortexM4 - * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 - * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). - * - * @param WRPSector specifies the sector(s) to be write protected. - * This parameter can be one of the following values: - * @arg WRPSector: A value between OB_WRP_SECTOR_0 and OB_WRP_SECTOR_23 - * @arg OB_WRP_SECTOR_All - * @note BANK2 starts from OB_WRP_SECTOR_12 - * - * @param Banks Enable write protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * @arg FLASH_BANK_2: WRP on all sectors of bank2 - * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 - * - * @retval HAL FLASH State - */ -static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_WRP_SECTOR(WRPSector)); - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - if (((WRPSector == OB_WRP_SECTOR_All) && ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH))) || - (WRPSector < OB_WRP_SECTOR_12)) - { - if (WRPSector == OB_WRP_SECTOR_All) - { - /*Write protection on all sector of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~(WRPSector >> 12)); - } - else - { - /*Write protection done on sectors of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~WRPSector); - } - } - else - { - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~(WRPSector >> 12)); - } - - /*Write protection on all sector of BANK2*/ - if ((WRPSector == OB_WRP_SECTOR_All) && (Banks == FLASH_BANK_BOTH)) - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~(WRPSector >> 12)); - } - } - - } - return status; -} - -/** - * @brief Disable the write protection of the desired bank1 or bank 2 sectors - * - * @note When the memory read protection level is selected (RDP level = 1), - * it is not possible to program or erase the flash sector i if CortexM4 - * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 - * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). - * - * @param WRPSector specifies the sector(s) to be write protected. - * This parameter can be one of the following values: - * @arg WRPSector: A value between OB_WRP_SECTOR_0 and OB_WRP_SECTOR_23 - * @arg OB_WRP_Sector_All - * @note BANK2 starts from OB_WRP_SECTOR_12 - * - * @param Banks Disable write protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: Bank1 to be erased - * @arg FLASH_BANK_2: Bank2 to be erased - * @arg FLASH_BANK_BOTH: Bank1 and Bank2 to be erased - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_WRP_SECTOR(WRPSector)); - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - if (((WRPSector == OB_WRP_SECTOR_All) && ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH))) || - (WRPSector < OB_WRP_SECTOR_12)) - { - if (WRPSector == OB_WRP_SECTOR_All) - { - /*Write protection on all sector of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); - } - else - { - /*Write protection done on sectors of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)WRPSector; - } - } - else - { - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); - } - - /*Write protection on all sector of BANK2*/ - if ((WRPSector == OB_WRP_SECTOR_All) && (Banks == FLASH_BANK_BOTH)) - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)(WRPSector >> 12); - } - } - - } - - return status; -} - -/** - * @brief Configure the Dual Bank Boot. - * - * @note This function can be used only for STM32F42xxx/43xxx devices. - * - * @param BootConfig specifies the Dual Bank Boot Option byte. - * This parameter can be one of the following values: - * @arg OB_Dual_BootEnabled: Dual Bank Boot Enable - * @arg OB_Dual_BootDisabled: Dual Bank Boot Disabled - * @retval None - */ -static HAL_StatusTypeDef FLASH_OB_BootConfig(uint8_t BootConfig) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_BOOT(BootConfig)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /* Set Dual Bank Boot */ - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BFB2); - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= BootConfig; - } - - return status; -} - -/** - * @brief Enable the read/write protection (PCROP) of the desired - * sectors of Bank 1 and/or Bank 2. - * @note This function can be used only for STM32F42xxx/43xxx devices. - * @param SectorBank1 Specifies the sector(s) to be read/write protected or unprotected for bank1. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_SECTOR_0 and OB_PCROP_SECTOR_11 - * @arg OB_PCROP_SECTOR__All - * @param SectorBank2 Specifies the sector(s) to be read/write protected or unprotected for bank2. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_SECTOR_12 and OB_PCROP_SECTOR_23 - * @arg OB_PCROP_SECTOR__All - * @param Banks Enable PCROP protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * @arg FLASH_BANK_2: WRP on all sectors of bank2 - * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - if ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH)) - { - assert_param(IS_OB_PCROP(SectorBank1)); - /*Write protection done on sectors of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)SectorBank1; - } - else - { - assert_param(IS_OB_PCROP(SectorBank2)); - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)SectorBank2; - } - - /*Write protection on all sector of BANK2*/ - if (Banks == FLASH_BANK_BOTH) - { - assert_param(IS_OB_PCROP(SectorBank2)); - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS |= (uint16_t)SectorBank2; - } - } - - } - - return status; -} - - -/** - * @brief Disable the read/write protection (PCROP) of the desired - * sectors of Bank 1 and/or Bank 2. - * @note This function can be used only for STM32F42xxx/43xxx devices. - * @param SectorBank1 specifies the sector(s) to be read/write protected or unprotected for bank1. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_SECTOR_0 and OB_PCROP_SECTOR_11 - * @arg OB_PCROP_SECTOR__All - * @param SectorBank2 Specifies the sector(s) to be read/write protected or unprotected for bank2. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_SECTOR_12 and OB_PCROP_SECTOR_23 - * @arg OB_PCROP_SECTOR__All - * @param Banks Disable PCROP protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * @arg FLASH_BANK_2: WRP on all sectors of bank2 - * @arg FLASH_BANK_BOTH: WRP on all sectors of bank1 & bank2 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t SectorBank1, uint32_t SectorBank2, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_FLASH_BANK(Banks)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - if ((Banks == FLASH_BANK_1) || (Banks == FLASH_BANK_BOTH)) - { - assert_param(IS_OB_PCROP(SectorBank1)); - /*Write protection done on sectors of BANK1*/ - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~SectorBank1); - } - else - { - /*Write protection done on sectors of BANK2*/ - assert_param(IS_OB_PCROP(SectorBank2)); - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~SectorBank2); - } - - /*Write protection on all sector of BANK2*/ - if (Banks == FLASH_BANK_BOTH) - { - assert_param(IS_OB_PCROP(SectorBank2)); - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /*Write protection done on sectors of BANK2*/ - *(__IO uint16_t *)OPTCR1_BYTE2_ADDRESS &= (~SectorBank2); - } - } - - } - - return status; - -} - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -/** - * @brief Mass erase of FLASH memory - * @param VoltageRange The device voltage range which defines the erase parallelism. - * This parameter can be one of the following values: - * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, - * the operation will be done by byte (8-bit) - * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, - * the operation will be done by half word (16-bit) - * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, - * the operation will be done by word (32-bit) - * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, - * the operation will be done by double word (64-bit) - * - * @param Banks Banks to be erased - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: Bank1 to be erased - * - * @retval None - */ -static void FLASH_MassErase(uint8_t VoltageRange, uint32_t Banks) -{ - /* Check the parameters */ - assert_param(IS_VOLTAGERANGE(VoltageRange)); - assert_param(IS_FLASH_BANK(Banks)); - UNUSED(Banks); - - /* If the previous operation is completed, proceed to erase all sectors */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= FLASH_CR_MER; - FLASH->CR |= FLASH_CR_STRT | ((uint32_t)VoltageRange << 8U); -} - -/** - * @brief Erase the specified FLASH memory sector - * @param Sector FLASH sector to erase - * The value of this parameter depend on device used within the same series - * @param VoltageRange The device voltage range which defines the erase parallelism. - * This parameter can be one of the following values: - * @arg FLASH_VOLTAGE_RANGE_1: when the device voltage range is 1.8V to 2.1V, - * the operation will be done by byte (8-bit) - * @arg FLASH_VOLTAGE_RANGE_2: when the device voltage range is 2.1V to 2.7V, - * the operation will be done by half word (16-bit) - * @arg FLASH_VOLTAGE_RANGE_3: when the device voltage range is 2.7V to 3.6V, - * the operation will be done by word (32-bit) - * @arg FLASH_VOLTAGE_RANGE_4: when the device voltage range is 2.7V to 3.6V + External Vpp, - * the operation will be done by double word (64-bit) - * - * @retval None - */ -void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange) -{ - uint32_t tmp_psize = 0U; - - /* Check the parameters */ - assert_param(IS_FLASH_SECTOR(Sector)); - assert_param(IS_VOLTAGERANGE(VoltageRange)); - - if (VoltageRange == FLASH_VOLTAGE_RANGE_1) - { - tmp_psize = FLASH_PSIZE_BYTE; - } - else if (VoltageRange == FLASH_VOLTAGE_RANGE_2) - { - tmp_psize = FLASH_PSIZE_HALF_WORD; - } - else if (VoltageRange == FLASH_VOLTAGE_RANGE_3) - { - tmp_psize = FLASH_PSIZE_WORD; - } - else - { - tmp_psize = FLASH_PSIZE_DOUBLE_WORD; - } - - /* If the previous operation is completed, proceed to erase the sector */ - CLEAR_BIT(FLASH->CR, FLASH_CR_PSIZE); - FLASH->CR |= tmp_psize; - CLEAR_BIT(FLASH->CR, FLASH_CR_SNB); - FLASH->CR |= FLASH_CR_SER | (Sector << FLASH_CR_SNB_Pos); - FLASH->CR |= FLASH_CR_STRT; -} - -/** - * @brief Enable the write protection of the desired bank 1 sectors - * - * @note When the memory read protection level is selected (RDP level = 1), - * it is not possible to program or erase the flash sector i if CortexM4 - * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 - * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). - * - * @param WRPSector specifies the sector(s) to be write protected. - * The value of this parameter depend on device used within the same series - * - * @param Banks Enable write protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_EnableWRP(uint32_t WRPSector, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_WRP_SECTOR(WRPSector)); - assert_param(IS_FLASH_BANK(Banks)); - UNUSED(Banks); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~WRPSector); - } - - return status; -} - -/** - * @brief Disable the write protection of the desired bank 1 sectors - * - * @note When the memory read protection level is selected (RDP level = 1), - * it is not possible to program or erase the flash sector i if CortexM4 - * debug features are connected or boot code is executed in RAM, even if nWRPi = 1 - * @note Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1). - * - * @param WRPSector specifies the sector(s) to be write protected. - * The value of this parameter depend on device used within the same series - * - * @param Banks Enable write protection on all the sectors for the specific bank - * This parameter can be one of the following values: - * @arg FLASH_BANK_1: WRP on all sectors of bank1 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_DisableWRP(uint32_t WRPSector, uint32_t Banks) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_WRP_SECTOR(WRPSector)); - assert_param(IS_FLASH_BANK(Banks)); - UNUSED(Banks); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)WRPSector; - } - - return status; -} -#endif /* STM32F40xxx || STM32F41xxx || STM32F401xx || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx - STM32F413xx || STM32F423xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Enable the read/write protection (PCROP) of the desired sectors. - * @note This function can be used only for STM32F401xx devices. - * @param Sector specifies the sector(s) to be read/write protected or unprotected. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector5 - * @arg OB_PCROP_Sector_All - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_EnablePCROP(uint32_t Sector) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_PCROP(Sector)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS |= (uint16_t)Sector; - } - - return status; -} - - -/** - * @brief Disable the read/write protection (PCROP) of the desired sectors. - * @note This function can be used only for STM32F401xx devices. - * @param Sector specifies the sector(s) to be read/write protected or unprotected. - * This parameter can be one of the following values: - * @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector5 - * @arg OB_PCROP_Sector_All - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_DisablePCROP(uint32_t Sector) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_PCROP(Sector)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint16_t *)OPTCR_BYTE2_ADDRESS &= (~Sector); - } - - return status; - -} -#endif /* STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx - STM32F413xx || STM32F423xx */ - -/** - * @brief Set the read protection level. - * @param Level specifies the read protection level. - * This parameter can be one of the following values: - * @arg OB_RDP_LEVEL_0: No protection - * @arg OB_RDP_LEVEL_1: Read protection of the memory - * @arg OB_RDP_LEVEL_2: Full chip protection - * - * @note WARNING: When enabling OB_RDP level 2 it's no more possible to go back to level 1 or 0 - * - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_RDP_LevelConfig(uint8_t Level) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_RDP_LEVEL(Level)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - *(__IO uint8_t *)OPTCR_BYTE1_ADDRESS = Level; - } - - return status; -} - -/** - * @brief Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. - * @param Iwdg Selects the IWDG mode - * This parameter can be one of the following values: - * @arg OB_IWDG_SW: Software IWDG selected - * @arg OB_IWDG_HW: Hardware IWDG selected - * @param Stop Reset event when entering STOP mode. - * This parameter can be one of the following values: - * @arg OB_STOP_NO_RST: No reset generated when entering in STOP - * @arg OB_STOP_RST: Reset generated when entering in STOP - * @param Stdby Reset event when entering Standby mode. - * This parameter can be one of the following values: - * @arg OB_STDBY_NO_RST: No reset generated when entering in STANDBY - * @arg OB_STDBY_RST: Reset generated when entering in STANDBY - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_UserConfig(uint8_t Iwdg, uint8_t Stop, uint8_t Stdby) -{ - uint8_t optiontmp = 0xFF; - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_OB_IWDG_SOURCE(Iwdg)); - assert_param(IS_OB_STOP_SOURCE(Stop)); - assert_param(IS_OB_STDBY_SOURCE(Stdby)); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation((uint32_t)FLASH_TIMEOUT_VALUE); - - if (status == HAL_OK) - { - /* Mask OPTLOCK, OPTSTRT, BOR_LEV and BFB2 bits */ - optiontmp = (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x1F); - - /* Update User Option Byte */ - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS = Iwdg | (uint8_t)(Stdby | (uint8_t)(Stop | ((uint8_t)optiontmp))); - } - - return status; -} - -/** - * @brief Set the BOR Level. - * @param Level specifies the Option Bytes BOR Reset Level. - * This parameter can be one of the following values: - * @arg OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V - * @arg OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V - * @arg OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V - * @arg OB_BOR_OFF: Supply voltage ranges from 1.62 to 2.1 V - * @retval HAL Status - */ -static HAL_StatusTypeDef FLASH_OB_BOR_LevelConfig(uint8_t Level) -{ - /* Check the parameters */ - assert_param(IS_OB_BOR_LEVEL(Level)); - - /* Set the BOR Level */ - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BOR_LEV); - *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= Level; - - return HAL_OK; - -} - -/** - * @brief Return the FLASH User Option Byte value. - * @retval uint8_t FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1) - * and RST_STDBY(Bit2). - */ -static uint8_t FLASH_OB_GetUser(void) -{ - /* Return the User Option Byte */ - return ((uint8_t)(FLASH->OPTCR & 0xE0)); -} - -/** - * @brief Return the FLASH Write Protection Option Bytes value. - * @retval uint16_t FLASH Write Protection Option Bytes value - */ -static uint16_t FLASH_OB_GetWRP(void) -{ - /* Return the FLASH write protection Register value */ - return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS)); -} - -/** - * @brief Returns the FLASH Read Protection level. - * @retval FLASH ReadOut Protection Status: - * This parameter can be one of the following values: - * @arg OB_RDP_LEVEL_0: No protection - * @arg OB_RDP_LEVEL_1: Read protection of the memory - * @arg OB_RDP_LEVEL_2: Full chip protection - */ -static uint8_t FLASH_OB_GetRDP(void) -{ - uint8_t readstatus = OB_RDP_LEVEL_0; - - if (*(__IO uint8_t *)(OPTCR_BYTE1_ADDRESS) == (uint8_t)OB_RDP_LEVEL_2) - { - readstatus = OB_RDP_LEVEL_2; - } - else if (*(__IO uint8_t *)(OPTCR_BYTE1_ADDRESS) == (uint8_t)OB_RDP_LEVEL_0) - { - readstatus = OB_RDP_LEVEL_0; - } - else - { - readstatus = OB_RDP_LEVEL_1; - } - - return readstatus; -} - -/** - * @brief Returns the FLASH BOR level. - * @retval uint8_t The FLASH BOR level: - * - OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V - * - OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V - * - OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V - * - OB_BOR_OFF : Supply voltage ranges from 1.62 to 2.1 V - */ -static uint8_t FLASH_OB_GetBOR(void) -{ - /* Return the FLASH BOR level */ - return (uint8_t)(*(__IO uint8_t *)(OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0C); -} - -/** - * @brief Flush the instruction and data caches - * @retval None - */ -void FLASH_FlushCaches(void) -{ - /* Flush instruction cache */ - if (READ_BIT(FLASH->ACR, FLASH_ACR_ICEN) != RESET) - { - /* Disable instruction cache */ - __HAL_FLASH_INSTRUCTION_CACHE_DISABLE(); - /* Reset instruction cache */ - __HAL_FLASH_INSTRUCTION_CACHE_RESET(); - /* Enable instruction cache */ - __HAL_FLASH_INSTRUCTION_CACHE_ENABLE(); - } - - /* Flush data cache */ - if (READ_BIT(FLASH->ACR, FLASH_ACR_DCEN) != RESET) - { - /* Disable data cache */ - __HAL_FLASH_DATA_CACHE_DISABLE(); - /* Reset data cache */ - __HAL_FLASH_DATA_CACHE_RESET(); - /* Enable data cache */ - __HAL_FLASH_DATA_CACHE_ENABLE(); - } -} - -/** - * @} - */ - -#endif /* HAL_FLASH_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c deleted file mode 100644 index 12db458b5766cc0..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c +++ /dev/null @@ -1,175 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ramfunc.c - * @author MCD Application Team - * @brief FLASH RAMFUNC module driver. - * This file provides a FLASH firmware functions which should be - * executed from internal SRAM - * + Stop/Start the flash interface while System Run - * + Enable/Disable the flash sleep while System Run - @verbatim - ============================================================================== - ##### APIs executed from Internal RAM ##### - ============================================================================== - [..] - *** ARM Compiler *** - -------------------- - [..] RAM functions are defined using the toolchain options. - Functions that are be executed in RAM should reside in a separate - source module. Using the 'Options for File' dialog you can simply change - the 'Code / Const' area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the - Options for Target' dialog. - - *** ICCARM Compiler *** - ----------------------- - [..] RAM functions are defined using a specific toolchain keyword "__ramfunc". - - *** GNU Compiler *** - -------------------- - [..] RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FLASH_RAMFUNC FLASH RAMFUNC - * @brief FLASH functions executed from RAM - * @{ - */ -#ifdef HAL_FLASH_MODULE_ENABLED -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup FLASH_RAMFUNC_Exported_Functions FLASH RAMFUNC Exported Functions - * @{ - */ - -/** @defgroup FLASH_RAMFUNC_Exported_Functions_Group1 Peripheral features functions executed from internal RAM - * @brief Peripheral Extended features functions - * -@verbatim - - =============================================================================== - ##### ramfunc functions ##### - =============================================================================== - [..] - This subsection provides a set of functions that should be executed from RAM - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Stop the flash interface while System Run - * @note This mode is only available for STM32F41xxx/STM32F446xx devices. - * @note This mode couldn't be set while executing with the flash itself. - * It should be done with specific routine executed from RAM. - * @retval HAL status - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void) -{ - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Stop the flash interface while System Run */ - SET_BIT(PWR->CR, PWR_CR_FISSR); - - return HAL_OK; -} - -/** - * @brief Start the flash interface while System Run - * @note This mode is only available for STM32F411xx/STM32F446xx devices. - * @note This mode couldn't be set while executing with the flash itself. - * It should be done with specific routine executed from RAM. - * @retval HAL status - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void) -{ - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Start the flash interface while System Run */ - CLEAR_BIT(PWR->CR, PWR_CR_FISSR); - - return HAL_OK; -} - -/** - * @brief Enable the flash sleep while System Run - * @note This mode is only available for STM32F41xxx/STM32F446xx devices. - * @note This mode could n't be set while executing with the flash itself. - * It should be done with specific routine executed from RAM. - * @retval HAL status - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void) -{ - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Enable the flash sleep while System Run */ - SET_BIT(PWR->CR, PWR_CR_FMSSR); - - return HAL_OK; -} - -/** - * @brief Disable the flash sleep while System Run - * @note This mode is only available for STM32F41xxx/STM32F446xx devices. - * @note This mode couldn't be set while executing with the flash itself. - * It should be done with specific routine executed from RAM. - * @retval HAL status - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void) -{ - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Disable the flash sleep while System Run */ - CLEAR_BIT(PWR->CR, PWR_CR_FMSSR); - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -#endif /* HAL_FLASH_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c.c deleted file mode 100644 index 306475925d481fb..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c.c +++ /dev/null @@ -1,6813 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpi2c.c - * @author MCD Application Team - * @brief FMPI2C HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Inter Integrated Circuit (FMPI2C) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral State and Errors functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The FMPI2C HAL driver can be used as follows: - - (#) Declare a FMPI2C_HandleTypeDef handle structure, for example: - FMPI2C_HandleTypeDef hfmpi2c; - - (#)Initialize the FMPI2C low level resources by implementing the HAL_FMPI2C_MspInit() API: - (##) Enable the FMPI2Cx interface clock - (##) FMPI2C pins configuration - (+++) Enable the clock for the FMPI2C GPIOs - (+++) Configure FMPI2C pins as alternate function open-drain - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the FMPI2Cx interrupt priority - (+++) Enable the NVIC FMPI2C IRQ Channel - (##) DMA Configuration if you need to use DMA process - (+++) Declare a DMA_HandleTypeDef handle structure for - the transmit or receive stream - (+++) Enable the DMAx interface clock using - (+++) Configure the DMA handle parameters - (+++) Configure the DMA Tx or Rx stream - (+++) Associate the initialized DMA handle to the hfmpi2c DMA Tx or Rx handle - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on - the DMA Tx or Rx stream - - (#) Configure the Communication Clock Timing, Own Address1, Master Addressing mode, Dual Addressing mode, - Own Address2, Own Address2 Mask, General call and Nostretch mode in the hfmpi2c Init structure. - - (#) Initialize the FMPI2C registers by calling the HAL_FMPI2C_Init(), configures also the low level Hardware - (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_FMPI2C_MspInit(&hfmpi2c) API. - - (#) To check if target device is ready for communication, use the function HAL_FMPI2C_IsDeviceReady() - - (#) For FMPI2C IO and IO MEM operations, three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Transmit in master mode an amount of data in blocking mode using HAL_FMPI2C_Master_Transmit() - (+) Receive in master mode an amount of data in blocking mode using HAL_FMPI2C_Master_Receive() - (+) Transmit in slave mode an amount of data in blocking mode using HAL_FMPI2C_Slave_Transmit() - (+) Receive in slave mode an amount of data in blocking mode using HAL_FMPI2C_Slave_Receive() - - *** Polling mode IO MEM operation *** - ===================================== - [..] - (+) Write an amount of data in blocking mode to a specific memory address using HAL_FMPI2C_Mem_Write() - (+) Read an amount of data in blocking mode from a specific memory address using HAL_FMPI2C_Mem_Read() - - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Transmit in master mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Transmit_IT() - (+) At transmission end of transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback() - (+) Receive in master mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Receive_IT() - (+) At reception end of transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback() - (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Transmit_IT() - (+) At transmission end of transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback() - (+) Receive in slave mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Receive_IT() - (+) At reception end of transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback() - (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() - (+) Abort a master FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT() - (+) End of abort process, HAL_FMPI2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_AbortCpltCallback() - (+) Discard a slave FMPI2C process communication using __HAL_FMPI2C_GENERATE_NACK() macro. - This action will inform Master to generate a Stop condition to discard the communication. - - - *** Interrupt mode or DMA mode IO sequential operation *** - ========================================================== - [..] - (@) These interfaces allow to manage a sequential transfer with a repeated start condition - when a direction change during transfer - [..] - (+) A specific option field manage the different steps of a sequential transfer - (+) Option field values are defined through FMPI2C_XFEROPTIONS and are listed below: - (++) FMPI2C_FIRST_AND_LAST_FRAME: No sequential usage, functional is same as associated interfaces in no sequential mode - (++) FMPI2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address - and data to transfer without a final stop condition - (++) FMPI2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with start condition, address - and data to transfer without a final stop condition, an then permit a call the same master sequential interface - several times (like HAL_FMPI2C_Master_Seq_Transmit_IT() then HAL_FMPI2C_Master_Seq_Transmit_IT() - or HAL_FMPI2C_Master_Seq_Transmit_DMA() then HAL_FMPI2C_Master_Seq_Transmit_DMA()) - (++) FMPI2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address - and with new data to transfer if the direction change or manage only the new data to - transfer - if no direction change and without a final stop condition in both cases - (++) FMPI2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address - and with new data to transfer if the direction change or manage only the new data to - transfer - if no direction change and with a final stop condition in both cases - (++) FMPI2C_LAST_FRAME_NO_STOP: Sequential usage (Master only), this option allow to manage a restart condition - after several call of the same master sequential interface several times - (link with option FMPI2C_FIRST_AND_NEXT_FRAME). - Usage can, transfer several bytes one by one using - HAL_FMPI2C_Master_Seq_Transmit_IT - or HAL_FMPI2C_Master_Seq_Receive_IT - or HAL_FMPI2C_Master_Seq_Transmit_DMA - or HAL_FMPI2C_Master_Seq_Receive_DMA - with option FMPI2C_FIRST_AND_NEXT_FRAME then FMPI2C_NEXT_FRAME. - Then usage of this option FMPI2C_LAST_FRAME_NO_STOP at the last Transmit or - Receive sequence permit to call the opposite interface Receive or Transmit - without stopping the communication and so generate a restart condition. - (++) FMPI2C_OTHER_FRAME: Sequential usage (Master only), this option allow to manage a restart condition after - each call of the same master sequential - interface. - Usage can, transfer several bytes one by one with a restart with slave address between - each bytes using - HAL_FMPI2C_Master_Seq_Transmit_IT - or HAL_FMPI2C_Master_Seq_Receive_IT - or HAL_FMPI2C_Master_Seq_Transmit_DMA - or HAL_FMPI2C_Master_Seq_Receive_DMA - with option FMPI2C_FIRST_FRAME then FMPI2C_OTHER_FRAME. - Then usage of this option FMPI2C_OTHER_AND_LAST_FRAME at the last frame to help automatic - generation of STOP condition. - - (+) Different sequential FMPI2C interfaces are listed below: - (++) Sequential transmit in master FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Seq_Transmit_IT() - or using HAL_FMPI2C_Master_Seq_Transmit_DMA() - (+++) At transmission end of current frame transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback() - (++) Sequential receive in master FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Master_Seq_Receive_IT() - or using HAL_FMPI2C_Master_Seq_Receive_DMA() - (+++) At reception end of current frame transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback() - (++) Abort a master IT or DMA FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT() - (+++) End of abort process, HAL_FMPI2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_AbortCpltCallback() - (++) Enable/disable the Address listen mode in slave FMPI2C mode using HAL_FMPI2C_EnableListen_IT() HAL_FMPI2C_DisableListen_IT() - (+++) When address slave FMPI2C match, HAL_FMPI2C_AddrCallback() is executed and user can - add his own code to check the Address Match Code and the transmission direction request by master (Write/Read). - (+++) At Listen mode end HAL_FMPI2C_ListenCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_ListenCpltCallback() - (++) Sequential transmit in slave FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Seq_Transmit_IT() - or using HAL_FMPI2C_Slave_Seq_Transmit_DMA() - (+++) At transmission end of current frame transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback() - (++) Sequential receive in slave FMPI2C mode an amount of data in non-blocking mode using HAL_FMPI2C_Slave_Seq_Receive_IT() - or using HAL_FMPI2C_Slave_Seq_Receive_DMA() - (+++) At reception end of current frame transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback() - (++) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() - (++) Discard a slave FMPI2C process communication using __HAL_FMPI2C_GENERATE_NACK() macro. - This action will inform Master to generate a Stop condition to discard the communication. - - *** Interrupt mode IO MEM operation *** - ======================================= - [..] - (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using - HAL_FMPI2C_Mem_Write_IT() - (+) At Memory end of write transfer, HAL_FMPI2C_MemTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MemTxCpltCallback() - (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using - HAL_FMPI2C_Mem_Read_IT() - (+) At Memory end of read transfer, HAL_FMPI2C_MemRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MemRxCpltCallback() - (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() - - *** DMA mode IO operation *** - ============================== - [..] - (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using - HAL_FMPI2C_Master_Transmit_DMA() - (+) At transmission end of transfer, HAL_FMPI2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MasterTxCpltCallback() - (+) Receive in master mode an amount of data in non-blocking mode (DMA) using - HAL_FMPI2C_Master_Receive_DMA() - (+) At reception end of transfer, HAL_FMPI2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MasterRxCpltCallback() - (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using - HAL_FMPI2C_Slave_Transmit_DMA() - (+) At transmission end of transfer, HAL_FMPI2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_SlaveTxCpltCallback() - (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using - HAL_FMPI2C_Slave_Receive_DMA() - (+) At reception end of transfer, HAL_FMPI2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_SlaveRxCpltCallback() - (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() - (+) Abort a master FMPI2C process communication with Interrupt using HAL_FMPI2C_Master_Abort_IT() - (+) End of abort process, HAL_FMPI2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_AbortCpltCallback() - (+) Discard a slave FMPI2C process communication using __HAL_FMPI2C_GENERATE_NACK() macro. - This action will inform Master to generate a Stop condition to discard the communication. - - *** DMA mode IO MEM operation *** - ================================= - [..] - (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using - HAL_FMPI2C_Mem_Write_DMA() - (+) At Memory end of write transfer, HAL_FMPI2C_MemTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MemTxCpltCallback() - (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using - HAL_FMPI2C_Mem_Read_DMA() - (+) At Memory end of read transfer, HAL_FMPI2C_MemRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_MemRxCpltCallback() - (+) In case of transfer Error, HAL_FMPI2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_FMPI2C_ErrorCallback() - - - *** FMPI2C HAL driver macros list *** - ================================== - [..] - Below the list of most used macros in FMPI2C HAL driver. - - (+) __HAL_FMPI2C_ENABLE: Enable the FMPI2C peripheral - (+) __HAL_FMPI2C_DISABLE: Disable the FMPI2C peripheral - (+) __HAL_FMPI2C_GENERATE_NACK: Generate a Non-Acknowledge FMPI2C peripheral in Slave mode - (+) __HAL_FMPI2C_GET_FLAG: Check whether the specified FMPI2C flag is set or not - (+) __HAL_FMPI2C_CLEAR_FLAG: Clear the specified FMPI2C pending flag - (+) __HAL_FMPI2C_ENABLE_IT: Enable the specified FMPI2C interrupt - (+) __HAL_FMPI2C_DISABLE_IT: Disable the specified FMPI2C interrupt - - *** Callback registration *** - ============================================= - [..] - The compilation flag USE_HAL_FMPI2C_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_FMPI2C_RegisterCallback() or HAL_FMPI2C_RegisterAddrCallback() - to register an interrupt callback. - [..] - Function HAL_FMPI2C_RegisterCallback() allows to register following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) MemTxCpltCallback : callback for Memory transmission end of transfer. - (+) MemRxCpltCallback : callback for Memory reception end of transfer. - (+) ErrorCallback : callback for error detection. - (+) AbortCpltCallback : callback for abort completion process. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - [..] - For specific callback AddrCallback use dedicated register callbacks : HAL_FMPI2C_RegisterAddrCallback(). - [..] - Use function HAL_FMPI2C_UnRegisterCallback to reset a callback to the default - weak function. - HAL_FMPI2C_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) MemTxCpltCallback : callback for Memory transmission end of transfer. - (+) MemRxCpltCallback : callback for Memory reception end of transfer. - (+) ErrorCallback : callback for error detection. - (+) AbortCpltCallback : callback for abort completion process. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - [..] - For callback AddrCallback use dedicated register callbacks : HAL_FMPI2C_UnRegisterAddrCallback(). - [..] - By default, after the HAL_FMPI2C_Init() and when the state is HAL_FMPI2C_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_FMPI2C_MasterTxCpltCallback(), HAL_FMPI2C_MasterRxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_FMPI2C_Init()/ HAL_FMPI2C_DeInit() only when - these callbacks are null (not registered beforehand). - If MspInit or MspDeInit are not null, the HAL_FMPI2C_Init()/ HAL_FMPI2C_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - [..] - Callbacks can be registered/unregistered in HAL_FMPI2C_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_FMPI2C_STATE_READY or HAL_FMPI2C_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_FMPI2C_RegisterCallback() before calling HAL_FMPI2C_DeInit() - or HAL_FMPI2C_Init() function. - [..] - When the compilation flag USE_HAL_FMPI2C_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - [..] - (@) You can refer to the FMPI2C HAL driver header file for more useful macros - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FMPI2C FMPI2C - * @brief FMPI2C HAL module driver - * @{ - */ - -#ifdef HAL_FMPI2C_MODULE_ENABLED -#if defined(FMPI2C_CR1_PE) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ - -/** @defgroup FMPI2C_Private_Define FMPI2C Private Define - * @{ - */ -#define TIMING_CLEAR_MASK (0xF0FFFFFFU) /*!< FMPI2C TIMING clear register Mask */ -#define FMPI2C_TIMEOUT_ADDR (10000U) /*!< 10 s */ -#define FMPI2C_TIMEOUT_BUSY (25U) /*!< 25 ms */ -#define FMPI2C_TIMEOUT_DIR (25U) /*!< 25 ms */ -#define FMPI2C_TIMEOUT_RXNE (25U) /*!< 25 ms */ -#define FMPI2C_TIMEOUT_STOPF (25U) /*!< 25 ms */ -#define FMPI2C_TIMEOUT_TC (25U) /*!< 25 ms */ -#define FMPI2C_TIMEOUT_TCR (25U) /*!< 25 ms */ -#define FMPI2C_TIMEOUT_TXIS (25U) /*!< 25 ms */ -#define FMPI2C_TIMEOUT_FLAG (25U) /*!< 25 ms */ - -#define MAX_NBYTE_SIZE 255U -#define SLAVE_ADDR_SHIFT 7U -#define SLAVE_ADDR_MSK 0x06U - -/* Private define for @ref PreviousState usage */ -#define FMPI2C_STATE_MSK ((uint32_t)((uint32_t)((uint32_t)HAL_FMPI2C_STATE_BUSY_TX | \ - (uint32_t)HAL_FMPI2C_STATE_BUSY_RX) & \ - (uint32_t)(~((uint32_t)HAL_FMPI2C_STATE_READY)))) -/*!< Mask State define, keep only RX and TX bits */ -#define FMPI2C_STATE_NONE ((uint32_t)(HAL_FMPI2C_MODE_NONE)) -/*!< Default Value */ -#define FMPI2C_STATE_MASTER_BUSY_TX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | \ - (uint32_t)HAL_FMPI2C_MODE_MASTER)) -/*!< Master Busy TX, combinaison of State LSB and Mode enum */ -#define FMPI2C_STATE_MASTER_BUSY_RX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | \ - (uint32_t)HAL_FMPI2C_MODE_MASTER)) -/*!< Master Busy RX, combinaison of State LSB and Mode enum */ -#define FMPI2C_STATE_SLAVE_BUSY_TX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | \ - (uint32_t)HAL_FMPI2C_MODE_SLAVE)) -/*!< Slave Busy TX, combinaison of State LSB and Mode enum */ -#define FMPI2C_STATE_SLAVE_BUSY_RX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | \ - (uint32_t)HAL_FMPI2C_MODE_SLAVE)) -/*!< Slave Busy RX, combinaison of State LSB and Mode enum */ -#define FMPI2C_STATE_MEM_BUSY_TX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_TX & FMPI2C_STATE_MSK) | \ - (uint32_t)HAL_FMPI2C_MODE_MEM)) -/*!< Memory Busy TX, combinaison of State LSB and Mode enum */ -#define FMPI2C_STATE_MEM_BUSY_RX ((uint32_t)(((uint32_t)HAL_FMPI2C_STATE_BUSY_RX & FMPI2C_STATE_MSK) | \ - (uint32_t)HAL_FMPI2C_MODE_MEM)) -/*!< Memory Busy RX, combinaison of State LSB and Mode enum */ - - -/* Private define to centralize the enable/disable of Interrupts */ -#define FMPI2C_XFER_TX_IT (uint16_t)(0x0001U) /*!< Bit field can be combinated with - @ref FMPI2C_XFER_LISTEN_IT */ -#define FMPI2C_XFER_RX_IT (uint16_t)(0x0002U) /*!< Bit field can be combinated with - @ref FMPI2C_XFER_LISTEN_IT */ -#define FMPI2C_XFER_LISTEN_IT (uint16_t)(0x8000U) /*!< Bit field can be combinated with @ref FMPI2C_XFER_TX_IT - and @ref FMPI2C_XFER_RX_IT */ - -#define FMPI2C_XFER_ERROR_IT (uint16_t)(0x0010U) /*!< Bit definition to manage addition of global Error - and NACK treatment */ -#define FMPI2C_XFER_CPLT_IT (uint16_t)(0x0020U) /*!< Bit definition to manage only STOP evenement */ -#define FMPI2C_XFER_RELOAD_IT (uint16_t)(0x0040U) /*!< Bit definition to manage only Reload of NBYTE */ - -/* Private define Sequential Transfer Options default/reset value */ -#define FMPI2C_NO_OPTION_FRAME (0xFFFF0000U) -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - -/** @defgroup FMPI2C_Private_Functions FMPI2C Private Functions - * @{ - */ -/* Private functions to handle DMA transfer */ -static void FMPI2C_DMAMasterTransmitCplt(DMA_HandleTypeDef *hdma); -static void FMPI2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma); -static void FMPI2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma); -static void FMPI2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma); -static void FMPI2C_DMAError(DMA_HandleTypeDef *hdma); -static void FMPI2C_DMAAbort(DMA_HandleTypeDef *hdma); - -/* Private functions to handle IT transfer */ -static void FMPI2C_ITAddrCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags); -static void FMPI2C_ITMasterSeqCplt(FMPI2C_HandleTypeDef *hfmpi2c); -static void FMPI2C_ITSlaveSeqCplt(FMPI2C_HandleTypeDef *hfmpi2c); -static void FMPI2C_ITMasterCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags); -static void FMPI2C_ITSlaveCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags); -static void FMPI2C_ITListenCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags); -static void FMPI2C_ITError(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ErrorCode); - -/* Private functions to handle IT transfer */ -static HAL_StatusTypeDef FMPI2C_RequestMemoryWrite(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, - uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, - uint32_t Tickstart); -static HAL_StatusTypeDef FMPI2C_RequestMemoryRead(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, - uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, - uint32_t Tickstart); - -/* Private functions for FMPI2C transfer IRQ handler */ -static HAL_StatusTypeDef FMPI2C_Master_ISR_IT(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, - uint32_t ITSources); -static HAL_StatusTypeDef FMPI2C_Slave_ISR_IT(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, - uint32_t ITSources); -static HAL_StatusTypeDef FMPI2C_Master_ISR_DMA(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, - uint32_t ITSources); -static HAL_StatusTypeDef FMPI2C_Slave_ISR_DMA(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, - uint32_t ITSources); - -/* Private functions to handle flags during polling transfer */ -static HAL_StatusTypeDef FMPI2C_WaitOnFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Flag, FlagStatus Status, - uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef FMPI2C_WaitOnTXISFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, - uint32_t Tickstart); -static HAL_StatusTypeDef FMPI2C_WaitOnRXNEFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, - uint32_t Tickstart); -static HAL_StatusTypeDef FMPI2C_WaitOnSTOPFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, - uint32_t Tickstart); -static HAL_StatusTypeDef FMPI2C_IsAcknowledgeFailed(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, - uint32_t Tickstart); - -/* Private functions to centralize the enable/disable of Interrupts */ -static void FMPI2C_Enable_IRQ(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t InterruptRequest); -static void FMPI2C_Disable_IRQ(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t InterruptRequest); - -/* Private function to treat different error callback */ -static void FMPI2C_TreatErrorCallback(FMPI2C_HandleTypeDef *hfmpi2c); - -/* Private function to flush TXDR register */ -static void FMPI2C_Flush_TXDR(FMPI2C_HandleTypeDef *hfmpi2c); - -/* Private function to handle start, restart or stop a transfer */ -static void FMPI2C_TransferConfig(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t Size, uint32_t Mode, - uint32_t Request); - -/* Private function to Convert Specific options */ -static void FMPI2C_ConvertOtherXferOptions(FMPI2C_HandleTypeDef *hfmpi2c); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup FMPI2C_Exported_Functions FMPI2C Exported Functions - * @{ - */ - -/** @defgroup FMPI2C_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - deinitialize the FMPI2Cx peripheral: - - (+) User must Implement HAL_FMPI2C_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). - - (+) Call the function HAL_FMPI2C_Init() to configure the selected device with - the selected configuration: - (++) Clock Timing - (++) Own Address 1 - (++) Addressing mode (Master, Slave) - (++) Dual Addressing mode - (++) Own Address 2 - (++) Own Address 2 Mask - (++) General call mode - (++) Nostretch mode - - (+) Call the function HAL_FMPI2C_DeInit() to restore the default configuration - of the selected FMPI2Cx peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the FMPI2C according to the specified parameters - * in the FMPI2C_InitTypeDef and initialize the associated handle. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Init(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Check the FMPI2C handle allocation */ - if (hfmpi2c == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); - assert_param(IS_FMPI2C_OWN_ADDRESS1(hfmpi2c->Init.OwnAddress1)); - assert_param(IS_FMPI2C_ADDRESSING_MODE(hfmpi2c->Init.AddressingMode)); - assert_param(IS_FMPI2C_DUAL_ADDRESS(hfmpi2c->Init.DualAddressMode)); - assert_param(IS_FMPI2C_OWN_ADDRESS2(hfmpi2c->Init.OwnAddress2)); - assert_param(IS_FMPI2C_OWN_ADDRESS2_MASK(hfmpi2c->Init.OwnAddress2Masks)); - assert_param(IS_FMPI2C_GENERAL_CALL(hfmpi2c->Init.GeneralCallMode)); - assert_param(IS_FMPI2C_NO_STRETCH(hfmpi2c->Init.NoStretchMode)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hfmpi2c->Lock = HAL_UNLOCKED; - -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - /* Init the FMPI2C Callback settings */ - hfmpi2c->MasterTxCpltCallback = HAL_FMPI2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - hfmpi2c->MasterRxCpltCallback = HAL_FMPI2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - hfmpi2c->SlaveTxCpltCallback = HAL_FMPI2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - hfmpi2c->SlaveRxCpltCallback = HAL_FMPI2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - hfmpi2c->ListenCpltCallback = HAL_FMPI2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - hfmpi2c->MemTxCpltCallback = HAL_FMPI2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ - hfmpi2c->MemRxCpltCallback = HAL_FMPI2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ - hfmpi2c->ErrorCallback = HAL_FMPI2C_ErrorCallback; /* Legacy weak ErrorCallback */ - hfmpi2c->AbortCpltCallback = HAL_FMPI2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - hfmpi2c->AddrCallback = HAL_FMPI2C_AddrCallback; /* Legacy weak AddrCallback */ - - if (hfmpi2c->MspInitCallback == NULL) - { - hfmpi2c->MspInitCallback = HAL_FMPI2C_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ - hfmpi2c->MspInitCallback(hfmpi2c); -#else - /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ - HAL_FMPI2C_MspInit(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; - - /* Disable the selected FMPI2C peripheral */ - __HAL_FMPI2C_DISABLE(hfmpi2c); - - /*---------------------------- FMPI2Cx TIMINGR Configuration ------------------*/ - /* Configure FMPI2Cx: Frequency range */ - hfmpi2c->Instance->TIMINGR = hfmpi2c->Init.Timing & TIMING_CLEAR_MASK; - - /*---------------------------- FMPI2Cx OAR1 Configuration ---------------------*/ - /* Disable Own Address1 before set the Own Address1 configuration */ - hfmpi2c->Instance->OAR1 &= ~FMPI2C_OAR1_OA1EN; - - /* Configure FMPI2Cx: Own Address1 and ack own address1 mode */ - if (hfmpi2c->Init.AddressingMode == FMPI2C_ADDRESSINGMODE_7BIT) - { - hfmpi2c->Instance->OAR1 = (FMPI2C_OAR1_OA1EN | hfmpi2c->Init.OwnAddress1); - } - else /* FMPI2C_ADDRESSINGMODE_10BIT */ - { - hfmpi2c->Instance->OAR1 = (FMPI2C_OAR1_OA1EN | FMPI2C_OAR1_OA1MODE | hfmpi2c->Init.OwnAddress1); - } - - /*---------------------------- FMPI2Cx CR2 Configuration ----------------------*/ - /* Configure FMPI2Cx: Addressing Master mode */ - if (hfmpi2c->Init.AddressingMode == FMPI2C_ADDRESSINGMODE_10BIT) - { - hfmpi2c->Instance->CR2 = (FMPI2C_CR2_ADD10); - } - /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process */ - hfmpi2c->Instance->CR2 |= (FMPI2C_CR2_AUTOEND | FMPI2C_CR2_NACK); - - /*---------------------------- FMPI2Cx OAR2 Configuration ---------------------*/ - /* Disable Own Address2 before set the Own Address2 configuration */ - hfmpi2c->Instance->OAR2 &= ~FMPI2C_DUALADDRESS_ENABLE; - - /* Configure FMPI2Cx: Dual mode and Own Address2 */ - hfmpi2c->Instance->OAR2 = (hfmpi2c->Init.DualAddressMode | hfmpi2c->Init.OwnAddress2 | \ - (hfmpi2c->Init.OwnAddress2Masks << 8)); - - /*---------------------------- FMPI2Cx CR1 Configuration ----------------------*/ - /* Configure FMPI2Cx: Generalcall and NoStretch mode */ - hfmpi2c->Instance->CR1 = (hfmpi2c->Init.GeneralCallMode | hfmpi2c->Init.NoStretchMode); - - /* Enable the selected FMPI2C peripheral */ - __HAL_FMPI2C_ENABLE(hfmpi2c); - - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - return HAL_OK; -} - -/** - * @brief DeInitialize the FMPI2C peripheral. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_DeInit(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Check the FMPI2C handle allocation */ - if (hfmpi2c == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; - - /* Disable the FMPI2C Peripheral Clock */ - __HAL_FMPI2C_DISABLE(hfmpi2c); - -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - if (hfmpi2c->MspDeInitCallback == NULL) - { - hfmpi2c->MspDeInitCallback = HAL_FMPI2C_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - hfmpi2c->MspDeInitCallback(hfmpi2c); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_FMPI2C_MspDeInit(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - hfmpi2c->State = HAL_FMPI2C_STATE_RESET; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Release Lock */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; -} - -/** - * @brief Initialize the FMPI2C MSP. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_MspInit(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize the FMPI2C MSP. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_MspDeInit(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User FMPI2C Callback - * To be used instead of the weak predefined callback - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID - * @arg @ref HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_ERROR_CB_ID Error callback ID - * @arg @ref HAL_FMPI2C_ABORT_CB_ID Abort callback ID - * @arg @ref HAL_FMPI2C_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_FMPI2C_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_RegisterCallback(FMPI2C_HandleTypeDef *hfmpi2c, HAL_FMPI2C_CallbackIDTypeDef CallbackID, - pFMPI2C_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hfmpi2c); - - if (HAL_FMPI2C_STATE_READY == hfmpi2c->State) - { - switch (CallbackID) - { - case HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID : - hfmpi2c->MasterTxCpltCallback = pCallback; - break; - - case HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID : - hfmpi2c->MasterRxCpltCallback = pCallback; - break; - - case HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID : - hfmpi2c->SlaveTxCpltCallback = pCallback; - break; - - case HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID : - hfmpi2c->SlaveRxCpltCallback = pCallback; - break; - - case HAL_FMPI2C_LISTEN_COMPLETE_CB_ID : - hfmpi2c->ListenCpltCallback = pCallback; - break; - - case HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID : - hfmpi2c->MemTxCpltCallback = pCallback; - break; - - case HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID : - hfmpi2c->MemRxCpltCallback = pCallback; - break; - - case HAL_FMPI2C_ERROR_CB_ID : - hfmpi2c->ErrorCallback = pCallback; - break; - - case HAL_FMPI2C_ABORT_CB_ID : - hfmpi2c->AbortCpltCallback = pCallback; - break; - - case HAL_FMPI2C_MSPINIT_CB_ID : - hfmpi2c->MspInitCallback = pCallback; - break; - - case HAL_FMPI2C_MSPDEINIT_CB_ID : - hfmpi2c->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_FMPI2C_STATE_RESET == hfmpi2c->State) - { - switch (CallbackID) - { - case HAL_FMPI2C_MSPINIT_CB_ID : - hfmpi2c->MspInitCallback = pCallback; - break; - - case HAL_FMPI2C_MSPDEINIT_CB_ID : - hfmpi2c->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hfmpi2c); - return status; -} - -/** - * @brief Unregister an FMPI2C Callback - * FMPI2C callback is redirected to the weak predefined callback - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * This parameter can be one of the following values: - * @arg @ref HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID - * @arg @ref HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID - * @arg @ref HAL_FMPI2C_ERROR_CB_ID Error callback ID - * @arg @ref HAL_FMPI2C_ABORT_CB_ID Abort callback ID - * @arg @ref HAL_FMPI2C_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_FMPI2C_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_UnRegisterCallback(FMPI2C_HandleTypeDef *hfmpi2c, HAL_FMPI2C_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hfmpi2c); - - if (HAL_FMPI2C_STATE_READY == hfmpi2c->State) - { - switch (CallbackID) - { - case HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID : - hfmpi2c->MasterTxCpltCallback = HAL_FMPI2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - break; - - case HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID : - hfmpi2c->MasterRxCpltCallback = HAL_FMPI2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - break; - - case HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID : - hfmpi2c->SlaveTxCpltCallback = HAL_FMPI2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - break; - - case HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID : - hfmpi2c->SlaveRxCpltCallback = HAL_FMPI2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - break; - - case HAL_FMPI2C_LISTEN_COMPLETE_CB_ID : - hfmpi2c->ListenCpltCallback = HAL_FMPI2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - break; - - case HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID : - hfmpi2c->MemTxCpltCallback = HAL_FMPI2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ - break; - - case HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID : - hfmpi2c->MemRxCpltCallback = HAL_FMPI2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ - break; - - case HAL_FMPI2C_ERROR_CB_ID : - hfmpi2c->ErrorCallback = HAL_FMPI2C_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_FMPI2C_ABORT_CB_ID : - hfmpi2c->AbortCpltCallback = HAL_FMPI2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_FMPI2C_MSPINIT_CB_ID : - hfmpi2c->MspInitCallback = HAL_FMPI2C_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_FMPI2C_MSPDEINIT_CB_ID : - hfmpi2c->MspDeInitCallback = HAL_FMPI2C_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_FMPI2C_STATE_RESET == hfmpi2c->State) - { - switch (CallbackID) - { - case HAL_FMPI2C_MSPINIT_CB_ID : - hfmpi2c->MspInitCallback = HAL_FMPI2C_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_FMPI2C_MSPDEINIT_CB_ID : - hfmpi2c->MspDeInitCallback = HAL_FMPI2C_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hfmpi2c); - return status; -} - -/** - * @brief Register the Slave Address Match FMPI2C Callback - * To be used instead of the weak HAL_FMPI2C_AddrCallback() predefined callback - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pCallback pointer to the Address Match Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_RegisterAddrCallback(FMPI2C_HandleTypeDef *hfmpi2c, pFMPI2C_AddrCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hfmpi2c); - - if (HAL_FMPI2C_STATE_READY == hfmpi2c->State) - { - hfmpi2c->AddrCallback = pCallback; - } - else - { - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hfmpi2c); - return status; -} - -/** - * @brief UnRegister the Slave Address Match FMPI2C Callback - * Info Ready FMPI2C Callback is redirected to the weak HAL_FMPI2C_AddrCallback() predefined callback - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_UnRegisterAddrCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hfmpi2c); - - if (HAL_FMPI2C_STATE_READY == hfmpi2c->State) - { - hfmpi2c->AddrCallback = HAL_FMPI2C_AddrCallback; /* Legacy weak AddrCallback */ - } - else - { - /* Update the error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hfmpi2c); - return status; -} - -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup FMPI2C_Exported_Functions_Group2 Input and Output operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the FMPI2C data - transfers. - - (#) There are two modes of transfer: - (++) Blocking mode : The communication is performed in the polling mode. - The status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode : The communication is performed using Interrupts - or DMA. These functions return the status of the transfer startup. - The end of the data processing will be indicated through the - dedicated FMPI2C IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - - (#) Blocking mode functions are : - (++) HAL_FMPI2C_Master_Transmit() - (++) HAL_FMPI2C_Master_Receive() - (++) HAL_FMPI2C_Slave_Transmit() - (++) HAL_FMPI2C_Slave_Receive() - (++) HAL_FMPI2C_Mem_Write() - (++) HAL_FMPI2C_Mem_Read() - (++) HAL_FMPI2C_IsDeviceReady() - - (#) No-Blocking mode functions with Interrupt are : - (++) HAL_FMPI2C_Master_Transmit_IT() - (++) HAL_FMPI2C_Master_Receive_IT() - (++) HAL_FMPI2C_Slave_Transmit_IT() - (++) HAL_FMPI2C_Slave_Receive_IT() - (++) HAL_FMPI2C_Mem_Write_IT() - (++) HAL_FMPI2C_Mem_Read_IT() - (++) HAL_FMPI2C_Master_Seq_Transmit_IT() - (++) HAL_FMPI2C_Master_Seq_Receive_IT() - (++) HAL_FMPI2C_Slave_Seq_Transmit_IT() - (++) HAL_FMPI2C_Slave_Seq_Receive_IT() - (++) HAL_FMPI2C_EnableListen_IT() - (++) HAL_FMPI2C_DisableListen_IT() - (++) HAL_FMPI2C_Master_Abort_IT() - - (#) No-Blocking mode functions with DMA are : - (++) HAL_FMPI2C_Master_Transmit_DMA() - (++) HAL_FMPI2C_Master_Receive_DMA() - (++) HAL_FMPI2C_Slave_Transmit_DMA() - (++) HAL_FMPI2C_Slave_Receive_DMA() - (++) HAL_FMPI2C_Mem_Write_DMA() - (++) HAL_FMPI2C_Mem_Read_DMA() - (++) HAL_FMPI2C_Master_Seq_Transmit_DMA() - (++) HAL_FMPI2C_Master_Seq_Receive_DMA() - (++) HAL_FMPI2C_Slave_Seq_Transmit_DMA() - (++) HAL_FMPI2C_Slave_Seq_Receive_DMA() - - (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: - (++) HAL_FMPI2C_MasterTxCpltCallback() - (++) HAL_FMPI2C_MasterRxCpltCallback() - (++) HAL_FMPI2C_SlaveTxCpltCallback() - (++) HAL_FMPI2C_SlaveRxCpltCallback() - (++) HAL_FMPI2C_MemTxCpltCallback() - (++) HAL_FMPI2C_MemRxCpltCallback() - (++) HAL_FMPI2C_AddrCallback() - (++) HAL_FMPI2C_ListenCpltCallback() - (++) HAL_FMPI2C_ErrorCallback() - (++) HAL_FMPI2C_AbortCpltCallback() - -@endverbatim - * @{ - */ - -/** - * @brief Transmits in master mode an amount of data in blocking mode. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, FMPI2C_TIMEOUT_BUSY, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferISR = NULL; - - /* Send Slave Address */ - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, - FMPI2C_GENERATE_START_WRITE); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_GENERATE_START_WRITE); - } - - while (hfmpi2c->XferCount > 0U) - { - /* Wait until TXIS flag is set */ - if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - /* Write data to TXDR */ - hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferCount--; - hfmpi2c->XferSize--; - - if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) - { - /* Wait until TCR flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, - FMPI2C_NO_STARTSTOP); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_NO_STARTSTOP); - } - } - } - - /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ - /* Wait until STOPF flag is set */ - if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Clear Configuration Register 2 */ - FMPI2C_RESET_CR2(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives in master mode an amount of data in blocking mode. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, FMPI2C_TIMEOUT_BUSY, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferISR = NULL; - - /* Send Slave Address */ - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, - FMPI2C_GENERATE_START_READ); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_GENERATE_START_READ); - } - - while (hfmpi2c->XferCount > 0U) - { - /* Wait until RXNE flag is set */ - if (FMPI2C_WaitOnRXNEFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from RXDR */ - *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferSize--; - hfmpi2c->XferCount--; - - if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) - { - /* Wait until TCR flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, - FMPI2C_NO_STARTSTOP); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_NO_STARTSTOP); - } - } - } - - /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ - /* Wait until STOPF flag is set */ - if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Clear Configuration Register 2 */ - FMPI2C_RESET_CR2(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmits in slave mode an amount of data in blocking mode. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t Timeout) -{ - uint32_t tickstart; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferISR = NULL; - - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Wait until ADDR flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - - /* If 10bit addressing mode is selected */ - if (hfmpi2c->Init.AddressingMode == FMPI2C_ADDRESSINGMODE_10BIT) - { - /* Wait until ADDR flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - } - - /* Wait until DIR flag is set Transmitter mode */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_DIR, RESET, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - while (hfmpi2c->XferCount > 0U) - { - /* Wait until TXIS flag is set */ - if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - /* Write data to TXDR */ - hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferCount--; - } - - /* Wait until STOP flag is set */ - if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - - if (hfmpi2c->ErrorCode == HAL_FMPI2C_ERROR_AF) - { - /* Normal use case for Transmitter mode */ - /* A NACK is generated to confirm the end of transfer */ - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - } - else - { - return HAL_ERROR; - } - } - - /* Clear STOP flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Wait until BUSY flag is reset */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in blocking mode - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t Timeout) -{ - uint32_t tickstart; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferISR = NULL; - - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Wait until ADDR flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - - /* Wait until DIR flag is reset Receiver mode */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_DIR, SET, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - while (hfmpi2c->XferCount > 0U) - { - /* Wait until RXNE flag is set */ - if (FMPI2C_WaitOnRXNEFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - - /* Store Last receive data if any */ - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_RXNE) == SET) - { - /* Read data from RXDR */ - *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferCount--; - } - - return HAL_ERROR; - } - - /* Read data from RXDR */ - *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferCount--; - } - - /* Wait until STOP flag is set */ - if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - /* Clear STOP flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Wait until BUSY flag is reset */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - return HAL_ERROR; - } - - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size) -{ - uint32_t xfermode; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = FMPI2C_AUTOEND_MODE; - } - - /* Send Slave Address */ - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_WRITE); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - - /* Enable ERR, TC, STOP, NACK, TXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size) -{ - uint32_t xfermode; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = FMPI2C_AUTOEND_MODE; - } - - /* Send Slave Address */ - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_READ); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - - /* Enable ERR, TC, STOP, NACK, RXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size) -{ - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferSize = hfmpi2c->XferCount; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - - /* Enable ERR, TC, STOP, NACK, TXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT | FMPI2C_XFER_LISTEN_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size) -{ - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferSize = hfmpi2c->XferCount; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - - /* Enable ERR, TC, STOP, NACK, RXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT | FMPI2C_XFER_LISTEN_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in master mode an amount of data in non-blocking mode with DMA - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size) -{ - uint32_t xfermode; - HAL_StatusTypeDef dmaxferstatus; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = FMPI2C_AUTOEND_MODE; - } - - if (hfmpi2c->XferSize > 0U) - { - if (hfmpi2c->hdmatx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMAMasterTransmitCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address */ - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_WRITE); - - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR and NACK interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - else - { - /* Update Transfer ISR function pointer */ - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - /* Send Slave Address */ - /* Set NBYTES to write and generate START condition */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_GENERATE_START_WRITE); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR, TC, STOP, NACK, TXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in master mode an amount of data in non-blocking mode with DMA - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size) -{ - uint32_t xfermode; - HAL_StatusTypeDef dmaxferstatus; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = FMPI2C_AUTOEND_MODE; - } - - if (hfmpi2c->XferSize > 0U) - { - if (hfmpi2c->hdmarx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMAMasterReceiveCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)pData, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address */ - /* Set NBYTES to read and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_READ); - - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR and NACK interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - else - { - /* Update Transfer ISR function pointer */ - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - /* Send Slave Address */ - /* Set NBYTES to read and generate START condition */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_GENERATE_START_READ); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR, TC, STOP, NACK, TXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef dmaxferstatus; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferSize = hfmpi2c->XferCount; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_DMA; - - if (hfmpi2c->hdmatx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMASlaveTransmitCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR, STOP, NACK, ADDR interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in non-blocking mode with DMA - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef dmaxferstatus; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferSize = hfmpi2c->XferCount; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_DMA; - - if (hfmpi2c->hdmarx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMASlaveReceiveCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)pData, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR, STOP, NACK, ADDR interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} -/** - * @brief Write an amount of data in blocking mode to a specific memory address - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart; - - /* Check the parameters */ - assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, FMPI2C_TIMEOUT_BUSY, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferISR = NULL; - - /* Send Slave Address and Memory Address */ - if (FMPI2C_RequestMemoryWrite(hfmpi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - return HAL_ERROR; - } - - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, FMPI2C_NO_STARTSTOP); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, FMPI2C_NO_STARTSTOP); - } - - do - { - /* Wait until TXIS flag is set */ - if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Write data to TXDR */ - hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferCount--; - hfmpi2c->XferSize--; - - if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) - { - /* Wait until TCR flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, - FMPI2C_NO_STARTSTOP); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_NO_STARTSTOP); - } - } - - } while (hfmpi2c->XferCount > 0U); - - /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ - /* Wait until STOPF flag is reset */ - if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Clear Configuration Register 2 */ - FMPI2C_RESET_CR2(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Read an amount of data in blocking mode from a specific memory address - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart; - - /* Check the parameters */ - assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_BUSY, SET, FMPI2C_TIMEOUT_BUSY, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferISR = NULL; - - /* Send Slave Address and Memory Address */ - if (FMPI2C_RequestMemoryRead(hfmpi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - return HAL_ERROR; - } - - /* Send Slave Address */ - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, - FMPI2C_GENERATE_START_READ); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_GENERATE_START_READ); - } - - do - { - /* Wait until RXNE flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_RXNE, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from RXDR */ - *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferSize--; - hfmpi2c->XferCount--; - - if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) - { - /* Wait until TCR flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t) hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, - FMPI2C_NO_STARTSTOP); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_NO_STARTSTOP); - } - } - } while (hfmpi2c->XferCount > 0U); - - /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ - /* Wait until STOPF flag is reset */ - if (FMPI2C_WaitOnSTOPFlagUntilTimeout(hfmpi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Clear Configuration Register 2 */ - FMPI2C_RESET_CR2(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} -/** - * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - uint32_t tickstart; - uint32_t xfermode; - - /* Check the parameters */ - assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = FMPI2C_AUTOEND_MODE; - } - - /* Send Slave Address and Memory Address */ - if (FMPI2C_RequestMemoryWrite(hfmpi2c, DevAddress, MemAddress, MemAddSize, FMPI2C_TIMEOUT_FLAG, tickstart) - != HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - return HAL_ERROR; - } - - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_NO_STARTSTOP); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - - /* Enable ERR, TC, STOP, NACK, TXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - uint32_t tickstart; - uint32_t xfermode; - - /* Check the parameters */ - assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = FMPI2C_AUTOEND_MODE; - } - - /* Send Slave Address and Memory Address */ - if (FMPI2C_RequestMemoryRead(hfmpi2c, DevAddress, MemAddress, MemAddSize, FMPI2C_TIMEOUT_FLAG, tickstart) != HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - return HAL_ERROR; - } - - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_READ); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - - /* Enable ERR, TC, STOP, NACK, RXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} -/** - * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - uint32_t tickstart; - uint32_t xfermode; - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = FMPI2C_AUTOEND_MODE; - } - - /* Send Slave Address and Memory Address */ - if (FMPI2C_RequestMemoryWrite(hfmpi2c, DevAddress, MemAddress, MemAddSize, FMPI2C_TIMEOUT_FLAG, tickstart) - != HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - return HAL_ERROR; - } - - - if (hfmpi2c->hdmatx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMAMasterTransmitCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address */ - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_NO_STARTSTOP); - - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR and NACK interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be read - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - uint32_t tickstart; - uint32_t xfermode; - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_FMPI2C_MEMADD_SIZE(MemAddSize)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MEM; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = FMPI2C_AUTOEND_MODE; - } - - /* Send Slave Address and Memory Address */ - if (FMPI2C_RequestMemoryRead(hfmpi2c, DevAddress, MemAddress, MemAddSize, FMPI2C_TIMEOUT_FLAG, tickstart) != HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - return HAL_ERROR; - } - - if (hfmpi2c->hdmarx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMAMasterReceiveCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)pData, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Set NBYTES to write and reload if hfmpi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_GENERATE_START_READ); - - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR and NACK interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Checks if target device is ready for communication. - * @note This function is used with Memory devices - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Trials Number of trials - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_IsDeviceReady(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint32_t Trials, - uint32_t Timeout) -{ - uint32_t tickstart; - - __IO uint32_t FMPI2C_Trials = 0UL; - - FlagStatus tmp1; - FlagStatus tmp2; - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_BUSY) == SET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - do - { - /* Generate Start */ - hfmpi2c->Instance->CR2 = FMPI2C_GENERATE_START(hfmpi2c->Init.AddressingMode, DevAddress); - - /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ - /* Wait until STOPF flag is set or a NACK flag is set*/ - tickstart = HAL_GetTick(); - - tmp1 = __HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - tmp2 = __HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - while ((tmp1 == RESET) && (tmp2 == RESET)) - { - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - - tmp1 = __HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - tmp2 = __HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - } - - /* Check if the NACKF flag has not been set */ - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_AF) == RESET) - { - /* Wait until STOPF flag is reset */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Device is ready */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - /* Wait until STOPF flag is reset */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Clear STOP Flag, auto generated with autoend*/ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - } - - /* Check if the maximum allowed number of trials has been reached */ - if (FMPI2C_Trials == Trials) - { - /* Generate Stop */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_STOP; - - /* Wait until STOPF flag is reset */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - } - - /* Increment Trials */ - FMPI2C_Trials++; - } while (FMPI2C_Trials < Trials); - - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in master FMPI2C mode an amount of data in non-blocking mode with Interrupt. - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions) -{ - uint32_t xfermode; - uint32_t xferrequest = FMPI2C_GENERATE_START_WRITE; - - /* Check the parameters */ - assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = XferOptions; - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = hfmpi2c->XferOptions; - } - - /* If transfer direction not change and there is no request to start another frame, - do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((hfmpi2c->PreviousState == FMPI2C_STATE_MASTER_BUSY_TX) && \ - (IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0)) - { - xferrequest = FMPI2C_NO_STARTSTOP; - } - else - { - /* Convert OTHER_xxx XferOptions if any */ - FMPI2C_ConvertOtherXferOptions(hfmpi2c); - - /* Update xfermode accordingly if no reload is necessary */ - if (hfmpi2c->XferCount <= MAX_NBYTE_SIZE) - { - xfermode = hfmpi2c->XferOptions; - } - } - - /* Send Slave Address and set NBYTES to write */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, xferrequest); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in master FMPI2C mode an amount of data in non-blocking mode with DMA. - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions) -{ - uint32_t xfermode; - uint32_t xferrequest = FMPI2C_GENERATE_START_WRITE; - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = XferOptions; - hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; - - /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = hfmpi2c->XferOptions; - } - - /* If transfer direction not change and there is no request to start another frame, - do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((hfmpi2c->PreviousState == FMPI2C_STATE_MASTER_BUSY_TX) && \ - (IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0)) - { - xferrequest = FMPI2C_NO_STARTSTOP; - } - else - { - /* Convert OTHER_xxx XferOptions if any */ - FMPI2C_ConvertOtherXferOptions(hfmpi2c); - - /* Update xfermode accordingly if no reload is necessary */ - if (hfmpi2c->XferCount <= MAX_NBYTE_SIZE) - { - xfermode = hfmpi2c->XferOptions; - } - } - - if (hfmpi2c->XferSize > 0U) - { - if (hfmpi2c->hdmatx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMAMasterTransmitCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address and set NBYTES to write */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, xferrequest); - - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR and NACK interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - else - { - /* Update Transfer ISR function pointer */ - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - /* Send Slave Address */ - /* Set NBYTES to write and generate START condition */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_GENERATE_START_WRITE); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR, TC, STOP, NACK, TXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in master FMPI2C mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions) -{ - uint32_t xfermode; - uint32_t xferrequest = FMPI2C_GENERATE_START_READ; - - /* Check the parameters */ - assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = XferOptions; - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = hfmpi2c->XferOptions; - } - - /* If transfer direction not change and there is no request to start another frame, - do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((hfmpi2c->PreviousState == FMPI2C_STATE_MASTER_BUSY_RX) && \ - (IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0)) - { - xferrequest = FMPI2C_NO_STARTSTOP; - } - else - { - /* Convert OTHER_xxx XferOptions if any */ - FMPI2C_ConvertOtherXferOptions(hfmpi2c); - - /* Update xfermode accordingly if no reload is necessary */ - if (hfmpi2c->XferCount <= MAX_NBYTE_SIZE) - { - xfermode = hfmpi2c->XferOptions; - } - } - - /* Send Slave Address and set NBYTES to read */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, xferrequest); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in master FMPI2C mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions) -{ - uint32_t xfermode; - uint32_t xferrequest = FMPI2C_GENERATE_START_READ; - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX; - hfmpi2c->Mode = HAL_FMPI2C_MODE_MASTER; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferOptions = XferOptions; - hfmpi2c->XferISR = FMPI2C_Master_ISR_DMA; - - /* If hfmpi2c->XferCount > MAX_NBYTE_SIZE, use reload mode */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - xfermode = hfmpi2c->XferOptions; - } - - /* If transfer direction not change and there is no request to start another frame, - do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((hfmpi2c->PreviousState == FMPI2C_STATE_MASTER_BUSY_RX) && \ - (IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 0)) - { - xferrequest = FMPI2C_NO_STARTSTOP; - } - else - { - /* Convert OTHER_xxx XferOptions if any */ - FMPI2C_ConvertOtherXferOptions(hfmpi2c); - - /* Update xfermode accordingly if no reload is necessary */ - if (hfmpi2c->XferCount <= MAX_NBYTE_SIZE) - { - xfermode = hfmpi2c->XferOptions; - } - } - - if (hfmpi2c->XferSize > 0U) - { - if (hfmpi2c->hdmarx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMAMasterReceiveCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)pData, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address and set NBYTES to read */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, xfermode, xferrequest); - - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR and NACK interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_ERROR_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - else - { - /* Update Transfer ISR function pointer */ - hfmpi2c->XferISR = FMPI2C_Master_ISR_IT; - - /* Send Slave Address */ - /* Set NBYTES to read and generate START condition */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_AUTOEND_MODE, - FMPI2C_GENERATE_START_READ); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR, TC, STOP, NACK, TXI interrupt */ - /* possible to enable all of these */ - /* FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | - FMPI2C_IT_ADDRI | FMPI2C_IT_RXI | FMPI2C_IT_TXI */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in slave/device FMPI2C mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_TX_IT); - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */ - /* and then toggle the HAL slave RX state to TX state */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX_LISTEN) - { - /* Disable associated Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - - /* Abort DMA Xfer if any */ - if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_RXDMAEN) == FMPI2C_CR1_RXDMAEN) - { - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; - - if (hfmpi2c->hdmarx != NULL) - { - /* Set the FMPI2C DMA Abort callback : - will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ - hfmpi2c->hdmarx->XferAbortCallback = FMPI2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hfmpi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hfmpi2c->hdmarx->XferAbortCallback(hfmpi2c->hdmarx); - } - } - } - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferSize = hfmpi2c->XferCount; - hfmpi2c->XferOptions = XferOptions; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; - - if (FMPI2C_GET_DIR(hfmpi2c) == FMPI2C_DIRECTION_RECEIVE) - { - /* Clear ADDR flag after prepare the transfer parameters */ - /* This action will generate an acknowledge to the Master */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* REnable ADDR interrupt */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT | FMPI2C_XFER_LISTEN_IT); - - return HAL_OK; - } - else - { - return HAL_ERROR; - } -} - -/** - * @brief Sequential transmit in slave/device FMPI2C mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions) -{ - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_TX_IT); - - /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */ - /* and then toggle the HAL slave RX state to TX state */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX_LISTEN) - { - /* Disable associated Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - - if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_RXDMAEN) == FMPI2C_CR1_RXDMAEN) - { - /* Abort DMA Xfer if any */ - if (hfmpi2c->hdmarx != NULL) - { - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; - - /* Set the FMPI2C DMA Abort callback : - will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ - hfmpi2c->hdmarx->XferAbortCallback = FMPI2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hfmpi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hfmpi2c->hdmarx->XferAbortCallback(hfmpi2c->hdmarx); - } - } - } - } - else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) - { - if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_TXDMAEN) == FMPI2C_CR1_TXDMAEN) - { - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; - - /* Abort DMA Xfer if any */ - if (hfmpi2c->hdmatx != NULL) - { - /* Set the FMPI2C DMA Abort callback : - will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ - hfmpi2c->hdmatx->XferAbortCallback = FMPI2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hfmpi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hfmpi2c->hdmatx->XferAbortCallback(hfmpi2c->hdmatx); - } - } - } - } - else - { - /* Nothing to do */ - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_TX_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferSize = hfmpi2c->XferCount; - hfmpi2c->XferOptions = XferOptions; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_DMA; - - if (hfmpi2c->hdmatx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmatx->XferCpltCallback = FMPI2C_DMASlaveTransmitCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmatx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmatx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)pData, (uint32_t)&hfmpi2c->Instance->TXDR, - hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Reset XferSize */ - hfmpi2c->XferSize = 0; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (FMPI2C_GET_DIR(hfmpi2c) == FMPI2C_DIRECTION_RECEIVE) - { - /* Clear ADDR flag after prepare the transfer parameters */ - /* This action will generate an acknowledge to the Master */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* Enable ERR, STOP, NACK, ADDR interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; - - return HAL_OK; - } - else - { - return HAL_ERROR; - } -} - -/** - * @brief Sequential receive in slave/device FMPI2C mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT); - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */ - /* and then toggle the HAL slave TX state to RX state */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) - { - /* Disable associated Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - - if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_TXDMAEN) == FMPI2C_CR1_TXDMAEN) - { - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; - - /* Abort DMA Xfer if any */ - if (hfmpi2c->hdmatx != NULL) - { - /* Set the FMPI2C DMA Abort callback : - will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ - hfmpi2c->hdmatx->XferAbortCallback = FMPI2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hfmpi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hfmpi2c->hdmatx->XferAbortCallback(hfmpi2c->hdmatx); - } - } - } - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferSize = hfmpi2c->XferCount; - hfmpi2c->XferOptions = XferOptions; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; - - if (FMPI2C_GET_DIR(hfmpi2c) == FMPI2C_DIRECTION_TRANSMIT) - { - /* Clear ADDR flag after prepare the transfer parameters */ - /* This action will generate an acknowledge to the Master */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* REnable ADDR interrupt */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT | FMPI2C_XFER_LISTEN_IT); - - return HAL_OK; - } - else - { - return HAL_ERROR; - } -} - -/** - * @brief Sequential receive in slave/device FMPI2C mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPI2C_XFEROPTIONS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions) -{ - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT); - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* FMPI2C cannot manage full duplex exchange so disable previous IT enabled if any */ - /* and then toggle the HAL slave TX state to RX state */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) - { - /* Disable associated Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - - if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_TXDMAEN) == FMPI2C_CR1_TXDMAEN) - { - /* Abort DMA Xfer if any */ - if (hfmpi2c->hdmatx != NULL) - { - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; - - /* Set the FMPI2C DMA Abort callback : - will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ - hfmpi2c->hdmatx->XferAbortCallback = FMPI2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hfmpi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hfmpi2c->hdmatx->XferAbortCallback(hfmpi2c->hdmatx); - } - } - } - } - else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX_LISTEN) - { - if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_RXDMAEN) == FMPI2C_CR1_RXDMAEN) - { - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; - - /* Abort DMA Xfer if any */ - if (hfmpi2c->hdmarx != NULL) - { - /* Set the FMPI2C DMA Abort callback : - will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ - hfmpi2c->hdmarx->XferAbortCallback = FMPI2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hfmpi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hfmpi2c->hdmarx->XferAbortCallback(hfmpi2c->hdmarx); - } - } - } - } - else - { - /* Nothing to do */ - } - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY_RX_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_SLAVE; - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - - /* Enable Address Acknowledge */ - hfmpi2c->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Prepare transfer parameters */ - hfmpi2c->pBuffPtr = pData; - hfmpi2c->XferCount = Size; - hfmpi2c->XferSize = hfmpi2c->XferCount; - hfmpi2c->XferOptions = XferOptions; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_DMA; - - if (hfmpi2c->hdmarx != NULL) - { - /* Set the FMPI2C DMA transfer complete callback */ - hfmpi2c->hdmarx->XferCpltCallback = FMPI2C_DMASlaveReceiveCplt; - - /* Set the DMA error callback */ - hfmpi2c->hdmarx->XferErrorCallback = FMPI2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hfmpi2c->hdmarx->XferHalfCpltCallback = NULL; - hfmpi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, - (uint32_t)pData, hfmpi2c->XferSize); - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Reset XferSize */ - hfmpi2c->XferSize = 0; - } - else - { - /* Update FMPI2C state */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Update FMPI2C error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - - if (FMPI2C_GET_DIR(hfmpi2c) == FMPI2C_DIRECTION_TRANSMIT) - { - /* Clear ADDR flag after prepare the transfer parameters */ - /* This action will generate an acknowledge to the Master */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - /* REnable ADDR interrupt */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT | FMPI2C_XFER_LISTEN_IT); - - /* Enable DMA Request */ - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; - - return HAL_OK; - } - else - { - return HAL_ERROR; - } -} - -/** - * @brief Enable the Address listen mode with Interrupt. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_EnableListen_IT(FMPI2C_HandleTypeDef *hfmpi2c) -{ - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; - - /* Enable the Address Match interrupt */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Disable the Address listen mode with Interrupt. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_DisableListen_IT(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Declaration of tmp to prevent undefined behavior of volatile usage */ - uint32_t tmp; - - /* Disable Address listen mode only if a transfer is not ongoing */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_LISTEN) - { - tmp = (uint32_t)(hfmpi2c->State) & FMPI2C_STATE_MSK; - hfmpi2c->PreviousState = tmp | (uint32_t)(hfmpi2c->Mode); - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - hfmpi2c->XferISR = NULL; - - /* Disable the Address Match interrupt */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Abort a master FMPI2C IT or DMA process communication with Interrupt. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Abort_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress) -{ - if (hfmpi2c->Mode == HAL_FMPI2C_MODE_MASTER) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - /* Disable Interrupts and Store Previous state */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX) - { - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_TX; - } - else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) - { - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_RX; - } - else - { - /* Do nothing */ - } - - /* Set State at HAL_FMPI2C_STATE_ABORT */ - hfmpi2c->State = HAL_FMPI2C_STATE_ABORT; - - /* Set NBYTES to 1 to generate a dummy read on FMPI2C peripheral */ - /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, 1, FMPI2C_AUTOEND_MODE, FMPI2C_GENERATE_STOP); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Note : The FMPI2C interrupts must be enabled after unlocking current process - to avoid the risk of FMPI2C interrupt handle execution before current - process unlock */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_CPLT_IT); - - return HAL_OK; - } - else - { - /* Wrong usage of abort function */ - /* This function should be used only in case of abort monitored by master device */ - return HAL_ERROR; - } -} - -/** - * @} - */ - -/** @defgroup FMPI2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ - -/** - * @brief This function handles FMPI2C event interrupt request. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -void HAL_FMPI2C_EV_IRQHandler(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Get current IT Flags and IT sources value */ - uint32_t itflags = READ_REG(hfmpi2c->Instance->ISR); - uint32_t itsources = READ_REG(hfmpi2c->Instance->CR1); - - /* FMPI2C events treatment -------------------------------------*/ - if (hfmpi2c->XferISR != NULL) - { - hfmpi2c->XferISR(hfmpi2c, itflags, itsources); - } -} - -/** - * @brief This function handles FMPI2C error interrupt request. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -void HAL_FMPI2C_ER_IRQHandler(FMPI2C_HandleTypeDef *hfmpi2c) -{ - uint32_t itflags = READ_REG(hfmpi2c->Instance->ISR); - uint32_t itsources = READ_REG(hfmpi2c->Instance->CR1); - uint32_t tmperror; - - /* FMPI2C Bus error interrupt occurred ------------------------------------*/ - if ((FMPI2C_CHECK_FLAG(itflags, FMPI2C_FLAG_BERR) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(itsources, FMPI2C_IT_ERRI) != RESET)) - { - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_BERR; - - /* Clear BERR flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_BERR); - } - - /* FMPI2C Over-Run/Under-Run interrupt occurred ----------------------------------------*/ - if ((FMPI2C_CHECK_FLAG(itflags, FMPI2C_FLAG_OVR) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(itsources, FMPI2C_IT_ERRI) != RESET)) - { - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_OVR; - - /* Clear OVR flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_OVR); - } - - /* FMPI2C Arbitration Loss error interrupt occurred -------------------------------------*/ - if ((FMPI2C_CHECK_FLAG(itflags, FMPI2C_FLAG_ARLO) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(itsources, FMPI2C_IT_ERRI) != RESET)) - { - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_ARLO; - - /* Clear ARLO flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ARLO); - } - - /* Store current volatile hfmpi2c->ErrorCode, misra rule */ - tmperror = hfmpi2c->ErrorCode; - - /* Call the Error Callback in case of Error detected */ - if ((tmperror & (HAL_FMPI2C_ERROR_BERR | HAL_FMPI2C_ERROR_OVR | HAL_FMPI2C_ERROR_ARLO)) != HAL_FMPI2C_ERROR_NONE) - { - FMPI2C_ITError(hfmpi2c, tmperror); - } -} - -/** - * @brief Master Tx Transfer completed callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_MasterTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_MasterTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Master Rx Transfer completed callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_MasterRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_MasterRxCpltCallback could be implemented in the user file - */ -} - -/** @brief Slave Tx Transfer completed callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_SlaveTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_SlaveTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Slave Rx Transfer completed callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_SlaveRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_SlaveRxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Slave Address Match callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref FMPI2C_XFERDIRECTION - * @param AddrMatchCode Address Match Code - * @retval None - */ -__weak void HAL_FMPI2C_AddrCallback(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t TransferDirection, uint16_t AddrMatchCode) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - UNUSED(TransferDirection); - UNUSED(AddrMatchCode); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_AddrCallback() could be implemented in the user file - */ -} - -/** - * @brief Listen Complete callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_ListenCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_ListenCpltCallback() could be implemented in the user file - */ -} - -/** - * @brief Memory Tx Transfer completed callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_MemTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_MemTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Memory Rx Transfer completed callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_MemRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_MemRxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief FMPI2C error callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_ErrorCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief FMPI2C abort callback. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval None - */ -__weak void HAL_FMPI2C_AbortCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPI2C_AbortCpltCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup FMPI2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @brief Peripheral State, Mode and Error functions - * -@verbatim - =============================================================================== - ##### Peripheral State, Mode and Error functions ##### - =============================================================================== - [..] - This subsection permit to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the FMPI2C handle state. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval HAL state - */ -HAL_FMPI2C_StateTypeDef HAL_FMPI2C_GetState(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Return FMPI2C handle state */ - return hfmpi2c->State; -} - -/** - * @brief Returns the FMPI2C Master, Slave, Memory or no mode. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for FMPI2C module - * @retval HAL mode - */ -HAL_FMPI2C_ModeTypeDef HAL_FMPI2C_GetMode(FMPI2C_HandleTypeDef *hfmpi2c) -{ - return hfmpi2c->Mode; -} - -/** - * @brief Return the FMPI2C error code. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @retval FMPI2C Error Code - */ -uint32_t HAL_FMPI2C_GetError(FMPI2C_HandleTypeDef *hfmpi2c) -{ - return hfmpi2c->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup FMPI2C_Private_Functions - * @{ - */ - -/** - * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with Interrupt. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param ITFlags Interrupt flags to handle. - * @param ITSources Interrupt sources enabled. - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_Master_ISR_IT(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, - uint32_t ITSources) -{ - uint16_t devaddress; - uint32_t tmpITFlags = ITFlags; - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_AF) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_NACKI) != RESET)) - { - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Set corresponding Error Code */ - /* No need to generate STOP, it is automatically done */ - /* Error callback will be send during stop flag treatment */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; - - /* Flush TX register */ - FMPI2C_Flush_TXDR(hfmpi2c); - } - else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_RXNE) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_RXI) != RESET)) - { - /* Remove RXNE flag on temporary variable as read done */ - tmpITFlags &= ~FMPI2C_FLAG_RXNE; - - /* Read data from RXDR */ - *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferSize--; - hfmpi2c->XferCount--; - } - else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_TXIS) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TXI) != RESET)) - { - /* Write data to TXDR */ - hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferSize--; - hfmpi2c->XferCount--; - } - else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_TCR) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TCI) != RESET)) - { - if ((hfmpi2c->XferCount != 0U) && (hfmpi2c->XferSize == 0U)) - { - devaddress = (uint16_t)(hfmpi2c->Instance->CR2 & FMPI2C_CR2_SADD); - - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - FMPI2C_TransferConfig(hfmpi2c, devaddress, (uint8_t)hfmpi2c->XferSize, FMPI2C_RELOAD_MODE, FMPI2C_NO_STARTSTOP); - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - if (hfmpi2c->XferOptions != FMPI2C_NO_OPTION_FRAME) - { - FMPI2C_TransferConfig(hfmpi2c, devaddress, (uint8_t)hfmpi2c->XferSize, - hfmpi2c->XferOptions, FMPI2C_NO_STARTSTOP); - } - else - { - FMPI2C_TransferConfig(hfmpi2c, devaddress, (uint8_t)hfmpi2c->XferSize, - FMPI2C_AUTOEND_MODE, FMPI2C_NO_STARTSTOP); - } - } - } - else - { - /* Call TxCpltCallback() if no stop mode is set */ - if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) - { - /* Call FMPI2C Master Sequential complete process */ - FMPI2C_ITMasterSeqCplt(hfmpi2c); - } - else - { - /* Wrong size Status regarding TCR flag event */ - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_SIZE); - } - } - } - else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_TC) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TCI) != RESET)) - { - if (hfmpi2c->XferCount == 0U) - { - if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) - { - /* Generate a stop condition in case of no transfer option */ - if (hfmpi2c->XferOptions == FMPI2C_NO_OPTION_FRAME) - { - /* Generate Stop */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_STOP; - } - else - { - /* Call FMPI2C Master Sequential complete process */ - FMPI2C_ITMasterSeqCplt(hfmpi2c); - } - } - } - else - { - /* Wrong size Status regarding TC flag event */ - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_SIZE); - } - } - else - { - /* Nothing to do */ - } - - if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_STOPF) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_STOPI) != RESET)) - { - /* Call FMPI2C Master complete process */ - FMPI2C_ITMasterCplt(hfmpi2c, tmpITFlags); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; -} - -/** - * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with Interrupt. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param ITFlags Interrupt flags to handle. - * @param ITSources Interrupt sources enabled. - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_Slave_ISR_IT(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, - uint32_t ITSources) -{ - uint32_t tmpoptions = hfmpi2c->XferOptions; - uint32_t tmpITFlags = ITFlags; - - /* Process locked */ - __HAL_LOCK(hfmpi2c); - - /* Check if STOPF is set */ - if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_STOPF) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_STOPI) != RESET)) - { - /* Call FMPI2C Slave complete process */ - FMPI2C_ITSlaveCplt(hfmpi2c, tmpITFlags); - } - - if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_AF) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_NACKI) != RESET)) - { - /* Check that FMPI2C transfer finished */ - /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */ - /* Mean XferCount == 0*/ - /* So clear Flag NACKF only */ - if (hfmpi2c->XferCount == 0U) - { - if ((hfmpi2c->State == HAL_FMPI2C_STATE_LISTEN) && (tmpoptions == FMPI2C_FIRST_AND_LAST_FRAME)) - /* Same action must be done for (tmpoptions == FMPI2C_LAST_FRAME) which removed for - Warning[Pa134]: left and right operands are identical */ - { - /* Call FMPI2C Listen complete process */ - FMPI2C_ITListenCplt(hfmpi2c, tmpITFlags); - } - else if ((hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) && (tmpoptions != FMPI2C_NO_OPTION_FRAME)) - { - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Flush TX register */ - FMPI2C_Flush_TXDR(hfmpi2c); - - /* Last Byte is Transmitted */ - /* Call FMPI2C Slave Sequential complete process */ - FMPI2C_ITSlaveSeqCplt(hfmpi2c); - } - else - { - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - } - } - else - { - /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/ - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; - - if ((tmpoptions == FMPI2C_FIRST_FRAME) || (tmpoptions == FMPI2C_NEXT_FRAME)) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, hfmpi2c->ErrorCode); - } - } - } - else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_RXNE) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_RXI) != RESET)) - { - if (hfmpi2c->XferCount > 0U) - { - /* Read data from RXDR */ - *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferSize--; - hfmpi2c->XferCount--; - } - - if ((hfmpi2c->XferCount == 0U) && \ - (tmpoptions != FMPI2C_NO_OPTION_FRAME)) - { - /* Call FMPI2C Slave Sequential complete process */ - FMPI2C_ITSlaveSeqCplt(hfmpi2c); - } - } - else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_ADDR) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_ADDRI) != RESET)) - { - FMPI2C_ITAddrCplt(hfmpi2c, tmpITFlags); - } - else if ((FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_TXIS) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TXI) != RESET)) - { - /* Write data to TXDR only if XferCount not reach "0" */ - /* A TXIS flag can be set, during STOP treatment */ - /* Check if all Data have already been sent */ - /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */ - if (hfmpi2c->XferCount > 0U) - { - /* Write data to TXDR */ - hfmpi2c->Instance->TXDR = *hfmpi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - hfmpi2c->XferCount--; - hfmpi2c->XferSize--; - } - else - { - if ((tmpoptions == FMPI2C_NEXT_FRAME) || (tmpoptions == FMPI2C_FIRST_FRAME)) - { - /* Last Byte is Transmitted */ - /* Call FMPI2C Slave Sequential complete process */ - FMPI2C_ITSlaveSeqCplt(hfmpi2c); - } - } - } - else - { - /* Nothing to do */ - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; -} - -/** - * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode with DMA. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param ITFlags Interrupt flags to handle. - * @param ITSources Interrupt sources enabled. - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_Master_ISR_DMA(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, - uint32_t ITSources) -{ - uint16_t devaddress; - uint32_t xfermode; - - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_AF) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_NACKI) != RESET)) - { - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Set corresponding Error Code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; - - /* No need to generate STOP, it is automatically done */ - /* But enable STOP interrupt, to treat it */ - /* Error callback will be send during stop flag treatment */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_CPLT_IT); - - /* Flush TX register */ - FMPI2C_Flush_TXDR(hfmpi2c); - } - else if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_TCR) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TCI) != RESET)) - { - /* Disable TC interrupt */ - __HAL_FMPI2C_DISABLE_IT(hfmpi2c, FMPI2C_IT_TCI); - - if (hfmpi2c->XferCount != 0U) - { - /* Recover Slave address */ - devaddress = (uint16_t)(hfmpi2c->Instance->CR2 & FMPI2C_CR2_SADD); - - /* Prepare the new XferSize to transfer */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - xfermode = FMPI2C_RELOAD_MODE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - if (hfmpi2c->XferOptions != FMPI2C_NO_OPTION_FRAME) - { - xfermode = hfmpi2c->XferOptions; - } - else - { - xfermode = FMPI2C_AUTOEND_MODE; - } - } - - /* Set the new XferSize in Nbytes register */ - FMPI2C_TransferConfig(hfmpi2c, devaddress, (uint8_t)hfmpi2c->XferSize, xfermode, FMPI2C_NO_STARTSTOP); - - /* Update XferCount value */ - hfmpi2c->XferCount -= hfmpi2c->XferSize; - - /* Enable DMA Request */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) - { - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_RXDMAEN; - } - else - { - hfmpi2c->Instance->CR1 |= FMPI2C_CR1_TXDMAEN; - } - } - else - { - /* Call TxCpltCallback() if no stop mode is set */ - if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) - { - /* Call FMPI2C Master Sequential complete process */ - FMPI2C_ITMasterSeqCplt(hfmpi2c); - } - else - { - /* Wrong size Status regarding TCR flag event */ - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_SIZE); - } - } - } - else if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_TC) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_TCI) != RESET)) - { - if (hfmpi2c->XferCount == 0U) - { - if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) - { - /* Generate a stop condition in case of no transfer option */ - if (hfmpi2c->XferOptions == FMPI2C_NO_OPTION_FRAME) - { - /* Generate Stop */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_STOP; - } - else - { - /* Call FMPI2C Master Sequential complete process */ - FMPI2C_ITMasterSeqCplt(hfmpi2c); - } - } - } - else - { - /* Wrong size Status regarding TC flag event */ - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_SIZE); - } - } - else if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_STOPF) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_STOPI) != RESET)) - { - /* Call FMPI2C Master complete process */ - FMPI2C_ITMasterCplt(hfmpi2c, ITFlags); - } - else - { - /* Nothing to do */ - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; -} - -/** - * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode with DMA. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param ITFlags Interrupt flags to handle. - * @param ITSources Interrupt sources enabled. - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_Slave_ISR_DMA(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, - uint32_t ITSources) -{ - uint32_t tmpoptions = hfmpi2c->XferOptions; - uint32_t treatdmanack = 0U; - HAL_FMPI2C_StateTypeDef tmpstate; - - /* Process locked */ - __HAL_LOCK(hfmpi2c); - - /* Check if STOPF is set */ - if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_STOPF) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_STOPI) != RESET)) - { - /* Call FMPI2C Slave complete process */ - FMPI2C_ITSlaveCplt(hfmpi2c, ITFlags); - } - - if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_AF) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_NACKI) != RESET)) - { - /* Check that FMPI2C transfer finished */ - /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */ - /* Mean XferCount == 0 */ - /* So clear Flag NACKF only */ - if ((FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_CR1_TXDMAEN) != RESET) || - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_CR1_RXDMAEN) != RESET)) - { - /* Split check of hdmarx, for MISRA compliance */ - if (hfmpi2c->hdmarx != NULL) - { - if (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_CR1_RXDMAEN) != RESET) - { - if (__HAL_DMA_GET_COUNTER(hfmpi2c->hdmarx) == 0U) - { - treatdmanack = 1U; - } - } - } - - /* Split check of hdmatx, for MISRA compliance */ - if (hfmpi2c->hdmatx != NULL) - { - if (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_CR1_TXDMAEN) != RESET) - { - if (__HAL_DMA_GET_COUNTER(hfmpi2c->hdmatx) == 0U) - { - treatdmanack = 1U; - } - } - } - - if (treatdmanack == 1U) - { - if ((hfmpi2c->State == HAL_FMPI2C_STATE_LISTEN) && (tmpoptions == FMPI2C_FIRST_AND_LAST_FRAME)) - /* Same action must be done for (tmpoptions == FMPI2C_LAST_FRAME) which removed for - Warning[Pa134]: left and right operands are identical */ - { - /* Call FMPI2C Listen complete process */ - FMPI2C_ITListenCplt(hfmpi2c, ITFlags); - } - else if ((hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) && (tmpoptions != FMPI2C_NO_OPTION_FRAME)) - { - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Flush TX register */ - FMPI2C_Flush_TXDR(hfmpi2c); - - /* Last Byte is Transmitted */ - /* Call FMPI2C Slave Sequential complete process */ - FMPI2C_ITSlaveSeqCplt(hfmpi2c); - } - else - { - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - } - } - else - { - /* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/ - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; - - /* Store current hfmpi2c->State, solve MISRA2012-Rule-13.5 */ - tmpstate = hfmpi2c->State; - - if ((tmpoptions == FMPI2C_FIRST_FRAME) || (tmpoptions == FMPI2C_NEXT_FRAME)) - { - if ((tmpstate == HAL_FMPI2C_STATE_BUSY_TX) || (tmpstate == HAL_FMPI2C_STATE_BUSY_TX_LISTEN)) - { - hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_TX; - } - else if ((tmpstate == HAL_FMPI2C_STATE_BUSY_RX) || (tmpstate == HAL_FMPI2C_STATE_BUSY_RX_LISTEN)) - { - hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_RX; - } - else - { - /* Do nothing */ - } - - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, hfmpi2c->ErrorCode); - } - } - } - else - { - /* Only Clear NACK Flag, no DMA treatment is pending */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - } - } - else if ((FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_ADDR) != RESET) && \ - (FMPI2C_CHECK_IT_SOURCE(ITSources, FMPI2C_IT_ADDRI) != RESET)) - { - FMPI2C_ITAddrCplt(hfmpi2c, ITFlags); - } - else - { - /* Nothing to do */ - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; -} - -/** - * @brief Master sends target device address followed by internal memory address for write request. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_RequestMemoryWrite(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, - uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, - uint32_t Tickstart) -{ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)MemAddSize, FMPI2C_RELOAD_MODE, FMPI2C_GENERATE_START_WRITE); - - /* Wait until TXIS flag is set */ - if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* If Memory address size is 8Bit */ - if (MemAddSize == FMPI2C_MEMADD_SIZE_8BIT) - { - /* Send Memory Address */ - hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_LSB(MemAddress); - } - /* If Memory address size is 16Bit */ - else - { - /* Send MSB of Memory Address */ - hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_MSB(MemAddress); - - /* Wait until TXIS flag is set */ - if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Send LSB of Memory Address */ - hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_LSB(MemAddress); - } - - /* Wait until TCR flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TCR, RESET, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Master sends target device address followed by internal memory address for read request. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_RequestMemoryRead(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, - uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, - uint32_t Tickstart) -{ - FMPI2C_TransferConfig(hfmpi2c, DevAddress, (uint8_t)MemAddSize, FMPI2C_SOFTEND_MODE, FMPI2C_GENERATE_START_WRITE); - - /* Wait until TXIS flag is set */ - if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* If Memory address size is 8Bit */ - if (MemAddSize == FMPI2C_MEMADD_SIZE_8BIT) - { - /* Send Memory Address */ - hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_LSB(MemAddress); - } - /* If Memory address size is 16Bit */ - else - { - /* Send MSB of Memory Address */ - hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_MSB(MemAddress); - - /* Wait until TXIS flag is set */ - if (FMPI2C_WaitOnTXISFlagUntilTimeout(hfmpi2c, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Send LSB of Memory Address */ - hfmpi2c->Instance->TXDR = FMPI2C_MEM_ADD_LSB(MemAddress); - } - - /* Wait until TC flag is set */ - if (FMPI2C_WaitOnFlagUntilTimeout(hfmpi2c, FMPI2C_FLAG_TC, RESET, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief FMPI2C Address complete process callback. - * @param hfmpi2c FMPI2C handle. - * @param ITFlags Interrupt flags to handle. - * @retval None - */ -static void FMPI2C_ITAddrCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags) -{ - uint8_t transferdirection; - uint16_t slaveaddrcode; - uint16_t ownadd1code; - uint16_t ownadd2code; - - /* Prevent unused argument(s) compilation warning */ - UNUSED(ITFlags); - - /* In case of Listen state, need to inform upper layer of address match code event */ - if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) == (uint32_t)HAL_FMPI2C_STATE_LISTEN) - { - transferdirection = FMPI2C_GET_DIR(hfmpi2c); - slaveaddrcode = FMPI2C_GET_ADDR_MATCH(hfmpi2c); - ownadd1code = FMPI2C_GET_OWN_ADDRESS1(hfmpi2c); - ownadd2code = FMPI2C_GET_OWN_ADDRESS2(hfmpi2c); - - /* If 10bits addressing mode is selected */ - if (hfmpi2c->Init.AddressingMode == FMPI2C_ADDRESSINGMODE_10BIT) - { - if ((slaveaddrcode & SLAVE_ADDR_MSK) == ((ownadd1code >> SLAVE_ADDR_SHIFT) & SLAVE_ADDR_MSK)) - { - slaveaddrcode = ownadd1code; - hfmpi2c->AddrEventCount++; - if (hfmpi2c->AddrEventCount == 2U) - { - /* Reset Address Event counter */ - hfmpi2c->AddrEventCount = 0U; - - /* Clear ADDR flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call Slave Addr callback */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); -#else - HAL_FMPI2C_AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - } - else - { - slaveaddrcode = ownadd2code; - - /* Disable ADDR Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call Slave Addr callback */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); -#else - HAL_FMPI2C_AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - } - /* else 7 bits addressing mode is selected */ - else - { - /* Disable ADDR Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call Slave Addr callback */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); -#else - HAL_FMPI2C_AddrCallback(hfmpi2c, transferdirection, slaveaddrcode); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - } - /* Else clear address flag only */ - else - { - /* Clear ADDR flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_ADDR); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - } -} - -/** - * @brief FMPI2C Master sequential complete process. - * @param hfmpi2c FMPI2C handle. - * @retval None - */ -static void FMPI2C_ITMasterSeqCplt(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* Reset FMPI2C handle mode */ - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* No Generate Stop, to permit restart mode */ - /* The stop will be done at the end of transfer, when FMPI2C_AUTOEND_MODE enable */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX) - { - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_TX; - hfmpi2c->XferISR = NULL; - - /* Disable Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->MasterTxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_MasterTxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX */ - else - { - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_RX; - hfmpi2c->XferISR = NULL; - - /* Disable Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->MasterRxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_MasterRxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } -} - -/** - * @brief FMPI2C Slave sequential complete process. - * @param hfmpi2c FMPI2C handle. - * @retval None - */ -static void FMPI2C_ITSlaveSeqCplt(FMPI2C_HandleTypeDef *hfmpi2c) -{ - uint32_t tmpcr1value = READ_REG(hfmpi2c->Instance->CR1); - - /* Reset FMPI2C handle mode */ - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* If a DMA is ongoing, Update handle size context */ - if (FMPI2C_CHECK_IT_SOURCE(tmpcr1value, FMPI2C_CR1_TXDMAEN) != RESET) - { - /* Disable DMA Request */ - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; - } - else if (FMPI2C_CHECK_IT_SOURCE(tmpcr1value, FMPI2C_CR1_RXDMAEN) != RESET) - { - /* Disable DMA Request */ - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; - } - else - { - /* Do nothing */ - } - - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) - { - /* Remove HAL_FMPI2C_STATE_SLAVE_BUSY_TX, keep only HAL_FMPI2C_STATE_LISTEN */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_TX; - - /* Disable Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->SlaveTxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_SlaveTxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - - else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX_LISTEN) - { - /* Remove HAL_FMPI2C_STATE_SLAVE_BUSY_RX, keep only HAL_FMPI2C_STATE_LISTEN */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_RX; - - /* Disable Interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->SlaveRxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_SlaveRxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - else - { - /* Nothing to do */ - } -} - -/** - * @brief FMPI2C Master complete process. - * @param hfmpi2c FMPI2C handle. - * @param ITFlags Interrupt flags to handle. - * @retval None - */ -static void FMPI2C_ITMasterCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags) -{ - uint32_t tmperror; - uint32_t tmpITFlags = ITFlags; - __IO uint32_t tmpreg; - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Disable Interrupts and Store Previous state */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX) - { - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_TX_IT); - hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_TX; - } - else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) - { - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT); - hfmpi2c->PreviousState = FMPI2C_STATE_MASTER_BUSY_RX; - } - else - { - /* Do nothing */ - } - - /* Clear Configuration Register 2 */ - FMPI2C_RESET_CR2(hfmpi2c); - - /* Reset handle parameters */ - hfmpi2c->XferISR = NULL; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - - if (FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_AF) != RESET) - { - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Set acknowledge error code */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; - } - - /* Fetch Last receive data if any */ - if ((hfmpi2c->State == HAL_FMPI2C_STATE_ABORT) && (FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_RXNE) != RESET)) - { - /* Read data from RXDR */ - tmpreg = (uint8_t)hfmpi2c->Instance->RXDR; - UNUSED(tmpreg); - } - - /* Flush TX register */ - FMPI2C_Flush_TXDR(hfmpi2c); - - /* Store current volatile hfmpi2c->ErrorCode, misra rule */ - tmperror = hfmpi2c->ErrorCode; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ - if ((hfmpi2c->State == HAL_FMPI2C_STATE_ABORT) || (tmperror != HAL_FMPI2C_ERROR_NONE)) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, hfmpi2c->ErrorCode); - } - /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX */ - else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_TX) - { - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - - if (hfmpi2c->Mode == HAL_FMPI2C_MODE_MEM) - { - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->MemTxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_MemTxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - else - { - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->MasterTxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_MasterTxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - } - /* hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX */ - else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) - { - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - - if (hfmpi2c->Mode == HAL_FMPI2C_MODE_MEM) - { - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->MemRxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_MemRxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - else - { - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->MasterRxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_MasterRxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - } - else - { - /* Nothing to do */ - } -} - -/** - * @brief FMPI2C Slave complete process. - * @param hfmpi2c FMPI2C handle. - * @param ITFlags Interrupt flags to handle. - * @retval None - */ -static void FMPI2C_ITSlaveCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags) -{ - uint32_t tmpcr1value = READ_REG(hfmpi2c->Instance->CR1); - uint32_t tmpITFlags = ITFlags; - HAL_FMPI2C_StateTypeDef tmpstate = hfmpi2c->State; - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Disable Interrupts and Store Previous state */ - if ((tmpstate == HAL_FMPI2C_STATE_BUSY_TX) || (tmpstate == HAL_FMPI2C_STATE_BUSY_TX_LISTEN)) - { - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_TX_IT); - hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_TX; - } - else if ((tmpstate == HAL_FMPI2C_STATE_BUSY_RX) || (tmpstate == HAL_FMPI2C_STATE_BUSY_RX_LISTEN)) - { - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT); - hfmpi2c->PreviousState = FMPI2C_STATE_SLAVE_BUSY_RX; - } - else - { - /* Do nothing */ - } - - /* Disable Address Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - - /* Clear Configuration Register 2 */ - FMPI2C_RESET_CR2(hfmpi2c); - - /* Flush TX register */ - FMPI2C_Flush_TXDR(hfmpi2c); - - /* If a DMA is ongoing, Update handle size context */ - if (FMPI2C_CHECK_IT_SOURCE(tmpcr1value, FMPI2C_CR1_TXDMAEN) != RESET) - { - /* Disable DMA Request */ - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; - - if (hfmpi2c->hdmatx != NULL) - { - hfmpi2c->XferCount = (uint16_t)__HAL_DMA_GET_COUNTER(hfmpi2c->hdmatx); - } - } - else if (FMPI2C_CHECK_IT_SOURCE(tmpcr1value, FMPI2C_CR1_RXDMAEN) != RESET) - { - /* Disable DMA Request */ - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; - - if (hfmpi2c->hdmarx != NULL) - { - hfmpi2c->XferCount = (uint16_t)__HAL_DMA_GET_COUNTER(hfmpi2c->hdmarx); - } - } - else - { - /* Do nothing */ - } - - /* Store Last receive data if any */ - if (FMPI2C_CHECK_FLAG(tmpITFlags, FMPI2C_FLAG_RXNE) != RESET) - { - /* Remove RXNE flag on temporary variable as read done */ - tmpITFlags &= ~FMPI2C_FLAG_RXNE; - - /* Read data from RXDR */ - *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - if ((hfmpi2c->XferSize > 0U)) - { - hfmpi2c->XferSize--; - hfmpi2c->XferCount--; - } - } - - /* All data are not transferred, so set error code accordingly */ - if (hfmpi2c->XferCount != 0U) - { - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; - } - - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - hfmpi2c->XferISR = NULL; - - if (hfmpi2c->ErrorCode != HAL_FMPI2C_ERROR_NONE) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, hfmpi2c->ErrorCode); - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ - if (hfmpi2c->State == HAL_FMPI2C_STATE_LISTEN) - { - /* Call FMPI2C Listen complete process */ - FMPI2C_ITListenCplt(hfmpi2c, tmpITFlags); - } - } - else if (hfmpi2c->XferOptions != FMPI2C_NO_OPTION_FRAME) - { - /* Call the Sequential Complete callback, to inform upper layer of the end of Transfer */ - FMPI2C_ITSlaveSeqCplt(hfmpi2c); - - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->ListenCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_ListenCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - /* Call the corresponding callback to inform upper layer of End of Transfer */ - else if (hfmpi2c->State == HAL_FMPI2C_STATE_BUSY_RX) - { - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->SlaveRxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_SlaveRxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - else - { - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->SlaveTxCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_SlaveTxCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } -} - -/** - * @brief FMPI2C Listen complete process. - * @param hfmpi2c FMPI2C handle. - * @param ITFlags Interrupt flags to handle. - * @retval None - */ -static void FMPI2C_ITListenCplt(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags) -{ - /* Reset handle parameters */ - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - hfmpi2c->XferISR = NULL; - - /* Store Last receive data if any */ - if (FMPI2C_CHECK_FLAG(ITFlags, FMPI2C_FLAG_RXNE) != RESET) - { - /* Read data from RXDR */ - *hfmpi2c->pBuffPtr = (uint8_t)hfmpi2c->Instance->RXDR; - - /* Increment Buffer pointer */ - hfmpi2c->pBuffPtr++; - - if ((hfmpi2c->XferSize > 0U)) - { - hfmpi2c->XferSize--; - hfmpi2c->XferCount--; - - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; - } - } - - /* Disable all Interrupts*/ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT | FMPI2C_XFER_TX_IT); - - /* Clear NACK Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->ListenCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_ListenCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -} - -/** - * @brief FMPI2C interrupts error process. - * @param hfmpi2c FMPI2C handle. - * @param ErrorCode Error code to handle. - * @retval None - */ -static void FMPI2C_ITError(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ErrorCode) -{ - HAL_FMPI2C_StateTypeDef tmpstate = hfmpi2c->State; - uint32_t tmppreviousstate; - - /* Reset handle parameters */ - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - hfmpi2c->XferOptions = FMPI2C_NO_OPTION_FRAME; - hfmpi2c->XferCount = 0U; - - /* Set new error code */ - hfmpi2c->ErrorCode |= ErrorCode; - - /* Disable Interrupts */ - if ((tmpstate == HAL_FMPI2C_STATE_LISTEN) || - (tmpstate == HAL_FMPI2C_STATE_BUSY_TX_LISTEN) || - (tmpstate == HAL_FMPI2C_STATE_BUSY_RX_LISTEN)) - { - /* Disable all interrupts, except interrupts related to LISTEN state */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_RX_IT | FMPI2C_XFER_TX_IT); - - /* keep HAL_FMPI2C_STATE_LISTEN if set */ - hfmpi2c->State = HAL_FMPI2C_STATE_LISTEN; - hfmpi2c->XferISR = FMPI2C_Slave_ISR_IT; - } - else - { - /* Disable all interrupts */ - FMPI2C_Disable_IRQ(hfmpi2c, FMPI2C_XFER_LISTEN_IT | FMPI2C_XFER_RX_IT | FMPI2C_XFER_TX_IT); - - /* If state is an abort treatment on going, don't change state */ - /* This change will be do later */ - if (hfmpi2c->State != HAL_FMPI2C_STATE_ABORT) - { - /* Set HAL_FMPI2C_STATE_READY */ - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - } - hfmpi2c->XferISR = NULL; - } - - /* Abort DMA TX transfer if any */ - tmppreviousstate = hfmpi2c->PreviousState; - if ((hfmpi2c->hdmatx != NULL) && ((tmppreviousstate == FMPI2C_STATE_MASTER_BUSY_TX) || \ - (tmppreviousstate == FMPI2C_STATE_SLAVE_BUSY_TX))) - { - if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_TXDMAEN) == FMPI2C_CR1_TXDMAEN) - { - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; - } - - if (HAL_DMA_GetState(hfmpi2c->hdmatx) != HAL_DMA_STATE_READY) - { - /* Set the FMPI2C DMA Abort callback : - will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ - hfmpi2c->hdmatx->XferAbortCallback = FMPI2C_DMAAbort; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hfmpi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hfmpi2c->hdmatx->XferAbortCallback(hfmpi2c->hdmatx); - } - } - else - { - FMPI2C_TreatErrorCallback(hfmpi2c); - } - } - /* Abort DMA RX transfer if any */ - else if ((hfmpi2c->hdmarx != NULL) && ((tmppreviousstate == FMPI2C_STATE_MASTER_BUSY_RX) || \ - (tmppreviousstate == FMPI2C_STATE_SLAVE_BUSY_RX))) - { - if ((hfmpi2c->Instance->CR1 & FMPI2C_CR1_RXDMAEN) == FMPI2C_CR1_RXDMAEN) - { - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; - } - - if (HAL_DMA_GetState(hfmpi2c->hdmarx) != HAL_DMA_STATE_READY) - { - /* Set the FMPI2C DMA Abort callback : - will lead to call HAL_FMPI2C_ErrorCallback() at end of DMA abort procedure */ - hfmpi2c->hdmarx->XferAbortCallback = FMPI2C_DMAAbort; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hfmpi2c->hdmarx) != HAL_OK) - { - /* Call Directly hfmpi2c->hdmarx->XferAbortCallback function in case of error */ - hfmpi2c->hdmarx->XferAbortCallback(hfmpi2c->hdmarx); - } - } - else - { - FMPI2C_TreatErrorCallback(hfmpi2c); - } - } - else - { - FMPI2C_TreatErrorCallback(hfmpi2c); - } -} - -/** - * @brief FMPI2C Error callback treatment. - * @param hfmpi2c FMPI2C handle. - * @retval None - */ -static void FMPI2C_TreatErrorCallback(FMPI2C_HandleTypeDef *hfmpi2c) -{ - if (hfmpi2c->State == HAL_FMPI2C_STATE_ABORT) - { - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->AbortCpltCallback(hfmpi2c); -#else - HAL_FMPI2C_AbortCpltCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } - else - { - hfmpi2c->PreviousState = FMPI2C_STATE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - hfmpi2c->ErrorCallback(hfmpi2c); -#else - HAL_FMPI2C_ErrorCallback(hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - } -} - -/** - * @brief FMPI2C Tx data register flush process. - * @param hfmpi2c FMPI2C handle. - * @retval None - */ -static void FMPI2C_Flush_TXDR(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* If a pending TXIS flag is set */ - /* Write a dummy data in TXDR to clear it */ - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_TXIS) != RESET) - { - hfmpi2c->Instance->TXDR = 0x00U; - } - - /* Flush TX register if not empty */ - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_TXE) == RESET) - { - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_TXE); - } -} - -/** - * @brief DMA FMPI2C master transmit process complete callback. - * @param hdma DMA handle - * @retval None - */ -static void FMPI2C_DMAMasterTransmitCplt(DMA_HandleTypeDef *hdma) -{ - /* Derogation MISRAC2012-Rule-11.5 */ - FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); - - /* Disable DMA Request */ - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; - - /* If last transfer, enable STOP interrupt */ - if (hfmpi2c->XferCount == 0U) - { - /* Enable STOP interrupt */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_CPLT_IT); - } - /* else prepare a new DMA transfer and enable TCReload interrupt */ - else - { - /* Update Buffer pointer */ - hfmpi2c->pBuffPtr += hfmpi2c->XferSize; - - /* Set the XferSize to transfer */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - } - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(hfmpi2c->hdmatx, (uint32_t)hfmpi2c->pBuffPtr, (uint32_t)&hfmpi2c->Instance->TXDR, - hfmpi2c->XferSize) != HAL_OK) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_DMA); - } - else - { - /* Enable TC interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RELOAD_IT); - } - } -} - -/** - * @brief DMA FMPI2C slave transmit process complete callback. - * @param hdma DMA handle - * @retval None - */ -static void FMPI2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma) -{ - /* Derogation MISRAC2012-Rule-11.5 */ - FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); - uint32_t tmpoptions = hfmpi2c->XferOptions; - - if ((tmpoptions == FMPI2C_NEXT_FRAME) || (tmpoptions == FMPI2C_FIRST_FRAME)) - { - /* Disable DMA Request */ - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_TXDMAEN; - - /* Last Byte is Transmitted */ - /* Call FMPI2C Slave Sequential complete process */ - FMPI2C_ITSlaveSeqCplt(hfmpi2c); - } - else - { - /* No specific action, Master fully manage the generation of STOP condition */ - /* Mean that this generation can arrive at any time, at the end or during DMA process */ - /* So STOP condition should be manage through Interrupt treatment */ - } -} - -/** - * @brief DMA FMPI2C master receive process complete callback. - * @param hdma DMA handle - * @retval None - */ -static void FMPI2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma) -{ - /* Derogation MISRAC2012-Rule-11.5 */ - FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); - - /* Disable DMA Request */ - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; - - /* If last transfer, enable STOP interrupt */ - if (hfmpi2c->XferCount == 0U) - { - /* Enable STOP interrupt */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_CPLT_IT); - } - /* else prepare a new DMA transfer and enable TCReload interrupt */ - else - { - /* Update Buffer pointer */ - hfmpi2c->pBuffPtr += hfmpi2c->XferSize; - - /* Set the XferSize to transfer */ - if (hfmpi2c->XferCount > MAX_NBYTE_SIZE) - { - hfmpi2c->XferSize = MAX_NBYTE_SIZE; - } - else - { - hfmpi2c->XferSize = hfmpi2c->XferCount; - } - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(hfmpi2c->hdmarx, (uint32_t)&hfmpi2c->Instance->RXDR, (uint32_t)hfmpi2c->pBuffPtr, - hfmpi2c->XferSize) != HAL_OK) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_DMA); - } - else - { - /* Enable TC interrupts */ - FMPI2C_Enable_IRQ(hfmpi2c, FMPI2C_XFER_RELOAD_IT); - } - } -} - -/** - * @brief DMA FMPI2C slave receive process complete callback. - * @param hdma DMA handle - * @retval None - */ -static void FMPI2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma) -{ - /* Derogation MISRAC2012-Rule-11.5 */ - FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); - uint32_t tmpoptions = hfmpi2c->XferOptions; - - if ((__HAL_DMA_GET_COUNTER(hfmpi2c->hdmarx) == 0U) && \ - (tmpoptions != FMPI2C_NO_OPTION_FRAME)) - { - /* Disable DMA Request */ - hfmpi2c->Instance->CR1 &= ~FMPI2C_CR1_RXDMAEN; - - /* Call FMPI2C Slave Sequential complete process */ - FMPI2C_ITSlaveSeqCplt(hfmpi2c); - } - else - { - /* No specific action, Master fully manage the generation of STOP condition */ - /* Mean that this generation can arrive at any time, at the end or during DMA process */ - /* So STOP condition should be manage through Interrupt treatment */ - } -} - -/** - * @brief DMA FMPI2C communication error callback. - * @param hdma DMA handle - * @retval None - */ -static void FMPI2C_DMAError(DMA_HandleTypeDef *hdma) -{ - uint32_t treatdmaerror = 0U; - /* Derogation MISRAC2012-Rule-11.5 */ - FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); - - if (hfmpi2c->hdmatx != NULL) - { - if (__HAL_DMA_GET_COUNTER(hfmpi2c->hdmatx) == 0U) - { - treatdmaerror = 1U; - } - } - - if (hfmpi2c->hdmarx != NULL) - { - if (__HAL_DMA_GET_COUNTER(hfmpi2c->hdmarx) == 0U) - { - treatdmaerror = 1U; - } - } - - /* Check if a FIFO error is detected, if true normal use case, so no specific action to perform */ - if (!((HAL_DMA_GetError(hdma) == HAL_DMA_ERROR_FE)) && (treatdmaerror != 0U)) - { - /* Disable Acknowledge */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_NACK; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ - FMPI2C_ITError(hfmpi2c, HAL_FMPI2C_ERROR_DMA); - } -} - -/** - * @brief DMA FMPI2C communication abort callback - * (To be called at end of DMA Abort procedure). - * @param hdma DMA handle. - * @retval None - */ -static void FMPI2C_DMAAbort(DMA_HandleTypeDef *hdma) -{ - /* Derogation MISRAC2012-Rule-11.5 */ - FMPI2C_HandleTypeDef *hfmpi2c = (FMPI2C_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); - - /* Reset AbortCpltCallback */ - if (hfmpi2c->hdmatx != NULL) - { - hfmpi2c->hdmatx->XferAbortCallback = NULL; - } - if (hfmpi2c->hdmarx != NULL) - { - hfmpi2c->hdmarx->XferAbortCallback = NULL; - } - - FMPI2C_TreatErrorCallback(hfmpi2c); -} - -/** - * @brief This function handles FMPI2C Communication Timeout. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param Flag Specifies the FMPI2C flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_WaitOnFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Flag, FlagStatus Status, - uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, Flag) == Status) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles FMPI2C Communication Timeout for specific usage of TXIS flag. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_WaitOnTXISFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, - uint32_t Tickstart) -{ - while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_TXIS) == RESET) - { - /* Check if a NACK is detected */ - if (FMPI2C_IsAcknowledgeFailed(hfmpi2c, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles FMPI2C Communication Timeout for specific usage of STOP flag. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_WaitOnSTOPFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, - uint32_t Tickstart) -{ - while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF) == RESET) - { - /* Check if a NACK is detected */ - if (FMPI2C_IsAcknowledgeFailed(hfmpi2c, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - return HAL_OK; -} - -/** - * @brief This function handles FMPI2C Communication Timeout for specific usage of RXNE flag. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_WaitOnRXNEFlagUntilTimeout(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, - uint32_t Tickstart) -{ - while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_RXNE) == RESET) - { - /* Check if a NACK is detected */ - if (FMPI2C_IsAcknowledgeFailed(hfmpi2c, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check if a STOPF is detected */ - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF) == SET) - { - /* Check if an RXNE is pending */ - /* Store Last receive data if any */ - if ((__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_RXNE) == SET) && (hfmpi2c->XferSize > 0U)) - { - /* Return HAL_OK */ - /* The Reading of data from RXDR will be done in caller function */ - return HAL_OK; - } - else - { - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Clear Configuration Register 2 */ - FMPI2C_RESET_CR2(hfmpi2c); - - hfmpi2c->ErrorCode = HAL_FMPI2C_ERROR_NONE; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - - /* Check for the Timeout */ - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - return HAL_OK; -} - -/** - * @brief This function handles Acknowledge failed detection during an FMPI2C Communication. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef FMPI2C_IsAcknowledgeFailed(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t Timeout, uint32_t Tickstart) -{ - if (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_AF) == SET) - { - /* In case of Soft End condition, generate the STOP condition */ - if (FMPI2C_GET_STOP_MODE(hfmpi2c) != FMPI2C_AUTOEND_MODE) - { - /* Generate Stop */ - hfmpi2c->Instance->CR2 |= FMPI2C_CR2_STOP; - } - /* Wait until STOP Flag is reset */ - /* AutoEnd should be initiate after AF */ - while (__HAL_FMPI2C_GET_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF) == RESET) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_TIMEOUT; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - } - } - - /* Clear NACKF Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_AF); - - /* Clear STOP Flag */ - __HAL_FMPI2C_CLEAR_FLAG(hfmpi2c, FMPI2C_FLAG_STOPF); - - /* Flush TX register */ - FMPI2C_Flush_TXDR(hfmpi2c); - - /* Clear Configuration Register 2 */ - FMPI2C_RESET_CR2(hfmpi2c); - - hfmpi2c->ErrorCode |= HAL_FMPI2C_ERROR_AF; - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - hfmpi2c->Mode = HAL_FMPI2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_ERROR; - } - return HAL_OK; -} - -/** - * @brief Handles FMPI2Cx communication when starting transfer or during transfer (TC or TCR flag are set). - * @param hfmpi2c FMPI2C handle. - * @param DevAddress Specifies the slave address to be programmed. - * @param Size Specifies the number of bytes to be programmed. - * This parameter must be a value between 0 and 255. - * @param Mode New state of the FMPI2C START condition generation. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_RELOAD_MODE Enable Reload mode . - * @arg @ref FMPI2C_AUTOEND_MODE Enable Automatic end mode. - * @arg @ref FMPI2C_SOFTEND_MODE Enable Software end mode. - * @param Request New state of the FMPI2C START condition generation. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_NO_STARTSTOP Don't Generate stop and start condition. - * @arg @ref FMPI2C_GENERATE_STOP Generate stop condition (Size should be set to 0). - * @arg @ref FMPI2C_GENERATE_START_READ Generate Restart for read request. - * @arg @ref FMPI2C_GENERATE_START_WRITE Generate Restart for write request. - * @retval None - */ -static void FMPI2C_TransferConfig(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t Size, uint32_t Mode, - uint32_t Request) -{ - /* Check the parameters */ - assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); - assert_param(IS_TRANSFER_MODE(Mode)); - assert_param(IS_TRANSFER_REQUEST(Request)); - - /* update CR2 register */ - MODIFY_REG(hfmpi2c->Instance->CR2, - ((FMPI2C_CR2_SADD | FMPI2C_CR2_NBYTES | FMPI2C_CR2_RELOAD | FMPI2C_CR2_AUTOEND | \ - (FMPI2C_CR2_RD_WRN & (uint32_t)(Request >> (31U - FMPI2C_CR2_RD_WRN_Pos))) | \ - FMPI2C_CR2_START | FMPI2C_CR2_STOP)), \ - (uint32_t)(((uint32_t)DevAddress & FMPI2C_CR2_SADD) | \ - (((uint32_t)Size << FMPI2C_CR2_NBYTES_Pos) & FMPI2C_CR2_NBYTES) | \ - (uint32_t)Mode | (uint32_t)Request)); -} - -/** - * @brief Manage the enabling of Interrupts. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param InterruptRequest Value of @ref FMPI2C_Interrupt_configuration_definition. - * @retval None - */ -static void FMPI2C_Enable_IRQ(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t InterruptRequest) -{ - uint32_t tmpisr = 0U; - - if ((hfmpi2c->XferISR == FMPI2C_Master_ISR_DMA) || \ - (hfmpi2c->XferISR == FMPI2C_Slave_ISR_DMA)) - { - if ((InterruptRequest & FMPI2C_XFER_LISTEN_IT) == FMPI2C_XFER_LISTEN_IT) - { - /* Enable ERR, STOP, NACK and ADDR interrupts */ - tmpisr |= FMPI2C_IT_ADDRI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; - } - - if (InterruptRequest == FMPI2C_XFER_ERROR_IT) - { - /* Enable ERR and NACK interrupts */ - tmpisr |= FMPI2C_IT_ERRI | FMPI2C_IT_NACKI; - } - - if (InterruptRequest == FMPI2C_XFER_CPLT_IT) - { - /* Enable STOP interrupts */ - tmpisr |= (FMPI2C_IT_STOPI | FMPI2C_IT_TCI); - } - - if (InterruptRequest == FMPI2C_XFER_RELOAD_IT) - { - /* Enable TC interrupts */ - tmpisr |= FMPI2C_IT_TCI; - } - } - else - { - if ((InterruptRequest & FMPI2C_XFER_LISTEN_IT) == FMPI2C_XFER_LISTEN_IT) - { - /* Enable ERR, STOP, NACK, and ADDR interrupts */ - tmpisr |= FMPI2C_IT_ADDRI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; - } - - if ((InterruptRequest & FMPI2C_XFER_TX_IT) == FMPI2C_XFER_TX_IT) - { - /* Enable ERR, TC, STOP, NACK and RXI interrupts */ - tmpisr |= FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_TXI; - } - - if ((InterruptRequest & FMPI2C_XFER_RX_IT) == FMPI2C_XFER_RX_IT) - { - /* Enable ERR, TC, STOP, NACK and TXI interrupts */ - tmpisr |= FMPI2C_IT_ERRI | FMPI2C_IT_TCI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_RXI; - } - - if (InterruptRequest == FMPI2C_XFER_CPLT_IT) - { - /* Enable STOP interrupts */ - tmpisr |= FMPI2C_IT_STOPI; - } - } - - /* Enable interrupts only at the end */ - /* to avoid the risk of FMPI2C interrupt handle execution before */ - /* all interrupts requested done */ - __HAL_FMPI2C_ENABLE_IT(hfmpi2c, tmpisr); -} - -/** - * @brief Manage the disabling of Interrupts. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2C. - * @param InterruptRequest Value of @ref FMPI2C_Interrupt_configuration_definition. - * @retval None - */ -static void FMPI2C_Disable_IRQ(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t InterruptRequest) -{ - uint32_t tmpisr = 0U; - - if ((InterruptRequest & FMPI2C_XFER_TX_IT) == FMPI2C_XFER_TX_IT) - { - /* Disable TC and TXI interrupts */ - tmpisr |= FMPI2C_IT_TCI | FMPI2C_IT_TXI; - - if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) != (uint32_t)HAL_FMPI2C_STATE_LISTEN) - { - /* Disable NACK and STOP interrupts */ - tmpisr |= FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; - } - } - - if ((InterruptRequest & FMPI2C_XFER_RX_IT) == FMPI2C_XFER_RX_IT) - { - /* Disable TC and RXI interrupts */ - tmpisr |= FMPI2C_IT_TCI | FMPI2C_IT_RXI; - - if (((uint32_t)hfmpi2c->State & (uint32_t)HAL_FMPI2C_STATE_LISTEN) != (uint32_t)HAL_FMPI2C_STATE_LISTEN) - { - /* Disable NACK and STOP interrupts */ - tmpisr |= FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; - } - } - - if ((InterruptRequest & FMPI2C_XFER_LISTEN_IT) == FMPI2C_XFER_LISTEN_IT) - { - /* Disable ADDR, NACK and STOP interrupts */ - tmpisr |= FMPI2C_IT_ADDRI | FMPI2C_IT_STOPI | FMPI2C_IT_NACKI | FMPI2C_IT_ERRI; - } - - if (InterruptRequest == FMPI2C_XFER_ERROR_IT) - { - /* Enable ERR and NACK interrupts */ - tmpisr |= FMPI2C_IT_ERRI | FMPI2C_IT_NACKI; - } - - if (InterruptRequest == FMPI2C_XFER_CPLT_IT) - { - /* Enable STOP interrupts */ - tmpisr |= FMPI2C_IT_STOPI; - } - - if (InterruptRequest == FMPI2C_XFER_RELOAD_IT) - { - /* Enable TC interrupts */ - tmpisr |= FMPI2C_IT_TCI; - } - - /* Disable interrupts only at the end */ - /* to avoid a breaking situation like at "t" time */ - /* all disable interrupts request are not done */ - __HAL_FMPI2C_DISABLE_IT(hfmpi2c, tmpisr); -} - -/** - * @brief Convert FMPI2Cx OTHER_xxx XferOptions to functional XferOptions. - * @param hfmpi2c FMPI2C handle. - * @retval None - */ -static void FMPI2C_ConvertOtherXferOptions(FMPI2C_HandleTypeDef *hfmpi2c) -{ - /* if user set XferOptions to FMPI2C_OTHER_FRAME */ - /* it request implicitly to generate a restart condition */ - /* set XferOptions to FMPI2C_FIRST_FRAME */ - if (hfmpi2c->XferOptions == FMPI2C_OTHER_FRAME) - { - hfmpi2c->XferOptions = FMPI2C_FIRST_FRAME; - } - /* else if user set XferOptions to FMPI2C_OTHER_AND_LAST_FRAME */ - /* it request implicitly to generate a restart condition */ - /* then generate a stop condition at the end of transfer */ - /* set XferOptions to FMPI2C_FIRST_AND_LAST_FRAME */ - else if (hfmpi2c->XferOptions == FMPI2C_OTHER_AND_LAST_FRAME) - { - hfmpi2c->XferOptions = FMPI2C_FIRST_AND_LAST_FRAME; - } - else - { - /* Nothing to do */ - } -} - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#endif /* HAL_FMPI2C_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c_ex.c deleted file mode 100644 index 0a8f72ccf788893..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpi2c_ex.c +++ /dev/null @@ -1,261 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpi2c_ex.c - * @author MCD Application Team - * @brief FMPI2C Extended HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of FMPI2C Extended peripheral: - * + Filter Mode Functions - * + FastModePlus Functions - * - @verbatim - ============================================================================== - ##### FMPI2C peripheral Extended features ##### - ============================================================================== - - [..] Comparing to other previous devices, the FMPI2C interface for STM32F4xx - devices contains the following additional features - - (+) Possibility to disable or enable Analog Noise Filter - (+) Use of a configured Digital Noise Filter - (+) Disable or enable Fast Mode Plus - - ##### How to use this driver ##### - ============================================================================== - [..] This driver provides functions to: - (#) Configure FMPI2C Analog noise filter using the function HAL_FMPI2CEx_ConfigAnalogFilter() - (#) Configure FMPI2C Digital noise filter using the function HAL_FMPI2CEx_ConfigDigitalFilter() - (#) Configure the enable or disable of fast mode plus driving capability using the functions : - (++) HAL_FMPI2CEx_EnableFastModePlus() - (++) HAL_FMPI2CEx_DisableFastModePlus() - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FMPI2CEx FMPI2CEx - * @brief FMPI2C Extended HAL module driver - * @{ - */ - -#ifdef HAL_FMPI2C_MODULE_ENABLED -#if defined(FMPI2C_CR1_PE) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup FMPI2CEx_Exported_Functions FMPI2C Extended Exported Functions - * @{ - */ - -/** @defgroup FMPI2CEx_Exported_Functions_Group1 Filter Mode Functions - * @brief Filter Mode Functions - * -@verbatim - =============================================================================== - ##### Filter Mode Functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure Noise Filters - -@endverbatim - * @{ - */ - -/** - * @brief Configure FMPI2C Analog noise filter. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2Cx peripheral. - * @param AnalogFilter New state of the Analog filter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2CEx_ConfigAnalogFilter(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t AnalogFilter) -{ - /* Check the parameters */ - assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); - assert_param(IS_FMPI2C_ANALOG_FILTER(AnalogFilter)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; - - /* Disable the selected FMPI2C peripheral */ - __HAL_FMPI2C_DISABLE(hfmpi2c); - - /* Reset FMPI2Cx ANOFF bit */ - hfmpi2c->Instance->CR1 &= ~(FMPI2C_CR1_ANFOFF); - - /* Set analog filter bit*/ - hfmpi2c->Instance->CR1 |= AnalogFilter; - - __HAL_FMPI2C_ENABLE(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configure FMPI2C Digital noise filter. - * @param hfmpi2c Pointer to a FMPI2C_HandleTypeDef structure that contains - * the configuration information for the specified FMPI2Cx peripheral. - * @param DigitalFilter Coefficient of digital noise filter between Min_Data=0x00 and Max_Data=0x0F. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPI2CEx_ConfigDigitalFilter(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t DigitalFilter) -{ - uint32_t tmpreg; - - /* Check the parameters */ - assert_param(IS_FMPI2C_ALL_INSTANCE(hfmpi2c->Instance)); - assert_param(IS_FMPI2C_DIGITAL_FILTER(DigitalFilter)); - - if (hfmpi2c->State == HAL_FMPI2C_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_BUSY; - - /* Disable the selected FMPI2C peripheral */ - __HAL_FMPI2C_DISABLE(hfmpi2c); - - /* Get the old register value */ - tmpreg = hfmpi2c->Instance->CR1; - - /* Reset FMPI2Cx DNF bits [11:8] */ - tmpreg &= ~(FMPI2C_CR1_DNF); - - /* Set FMPI2Cx DNF coefficient */ - tmpreg |= DigitalFilter << 8U; - - /* Store the new register value */ - hfmpi2c->Instance->CR1 = tmpreg; - - __HAL_FMPI2C_ENABLE(hfmpi2c); - - hfmpi2c->State = HAL_FMPI2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} -/** - * @} - */ - -/** @defgroup FMPI2CEx_Exported_Functions_Group3 Fast Mode Plus Functions - * @brief Fast Mode Plus Functions - * -@verbatim - =============================================================================== - ##### Fast Mode Plus Functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure Fast Mode Plus - -@endverbatim - * @{ - */ - -/** - * @brief Enable the FMPI2C fast mode plus driving capability. - * @param ConfigFastModePlus Selects the pin. - * This parameter can be one of the @ref FMPI2CEx_FastModePlus values - * @note For FMPI2C1, fast mode plus driving capability can be enabled on all selected - * FMPI2C1 pins using FMPI2C_FASTMODEPLUS_FMPI2C1 parameter or independently - * on each one of the following pins PB6, PB7, PB8 and PB9. - * @note For remaining FMPI2C1 pins (PA14, PA15...) fast mode plus driving capability - * can be enabled only by using FMPI2C_FASTMODEPLUS_FMPI2C1 parameter. - * @retval None - */ -void HAL_FMPI2CEx_EnableFastModePlus(uint32_t ConfigFastModePlus) -{ - /* Check the parameter */ - assert_param(IS_FMPI2C_FASTMODEPLUS(ConfigFastModePlus)); - - /* Enable SYSCFG clock */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - - /* Enable fast mode plus driving capability for selected pin */ - SET_BIT(SYSCFG->CFGR, (uint32_t)ConfigFastModePlus); -} - -/** - * @brief Disable the FMPI2C fast mode plus driving capability. - * @param ConfigFastModePlus Selects the pin. - * This parameter can be one of the @ref FMPI2CEx_FastModePlus values - * @note For FMPI2C1, fast mode plus driving capability can be disabled on all selected - * FMPI2C1 pins using FMPI2C_FASTMODEPLUS_FMPI2C1 parameter or independently - * on each one of the following pins PB6, PB7, PB8 and PB9. - * @note For remaining FMPI2C1 pins (PA14, PA15...) fast mode plus driving capability - * can be disabled only by using FMPI2C_FASTMODEPLUS_FMPI2C1 parameter. - * @retval None - */ -void HAL_FMPI2CEx_DisableFastModePlus(uint32_t ConfigFastModePlus) -{ - /* Check the parameter */ - assert_param(IS_FMPI2C_FASTMODEPLUS(ConfigFastModePlus)); - - /* Enable SYSCFG clock */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - - /* Disable fast mode plus driving capability for selected pin */ - CLEAR_BIT(SYSCFG->CFGR, (uint32_t)ConfigFastModePlus); -} -/** - * @} - */ -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#endif /* HAL_FMPI2C_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus.c deleted file mode 100644 index 578ecc5bfc281ac..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus.c +++ /dev/null @@ -1,2746 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpsmbus.c - * @author MCD Application Team - * @brief FMPSMBUS HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the System Management Bus (SMBus) peripheral, - * based on I2C principles of operation : - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral State and Errors functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The FMPSMBUS HAL driver can be used as follows: - - (#) Declare a FMPSMBUS_HandleTypeDef handle structure, for example: - FMPSMBUS_HandleTypeDef hfmpsmbus; - - (#)Initialize the FMPSMBUS low level resources by implementing the HAL_FMPSMBUS_MspInit() API: - (##) Enable the FMPSMBUSx interface clock - (##) FMPSMBUS pins configuration - (+++) Enable the clock for the FMPSMBUS GPIOs - (+++) Configure FMPSMBUS pins as alternate function open-drain - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the FMPSMBUSx interrupt priority - (+++) Enable the NVIC FMPSMBUS IRQ Channel - - (#) Configure the Communication Clock Timing, Bus Timeout, Own Address1, Master Addressing mode, - Dual Addressing mode, Own Address2, Own Address2 Mask, General call, Nostretch mode, - Peripheral mode and Packet Error Check mode in the hfmpsmbus Init structure. - - (#) Initialize the FMPSMBUS registers by calling the HAL_FMPSMBUS_Init() API: - (++) These API's configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) - by calling the customized HAL_FMPSMBUS_MspInit(&hfmpsmbus) API. - - (#) To check if target device is ready for communication, use the function HAL_FMPSMBUS_IsDeviceReady() - - (#) For FMPSMBUS IO operations, only one mode of operations is available within this driver - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Transmit in master/host FMPSMBUS mode an amount of data in non-blocking mode using HAL_FMPSMBUS_Master_Transmit_IT() - (++) At transmission end of transfer HAL_FMPSMBUS_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPSMBUS_MasterTxCpltCallback() - (+) Receive in master/host FMPSMBUS mode an amount of data in non-blocking mode using HAL_FMPSMBUS_Master_Receive_IT() - (++) At reception end of transfer HAL_FMPSMBUS_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPSMBUS_MasterRxCpltCallback() - (+) Abort a master/host FMPSMBUS process communication with Interrupt using HAL_FMPSMBUS_Master_Abort_IT() - (++) The associated previous transfer callback is called at the end of abort process - (++) mean HAL_FMPSMBUS_MasterTxCpltCallback() in case of previous state was master transmit - (++) mean HAL_FMPSMBUS_MasterRxCpltCallback() in case of previous state was master receive - (+) Enable/disable the Address listen mode in slave/device or host/slave FMPSMBUS mode - using HAL_FMPSMBUS_EnableListen_IT() HAL_FMPSMBUS_DisableListen_IT() - (++) When address slave/device FMPSMBUS match, HAL_FMPSMBUS_AddrCallback() is executed and user can - add his own code to check the Address Match Code and the transmission direction request by master/host (Write/Read). - (++) At Listen mode end HAL_FMPSMBUS_ListenCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPSMBUS_ListenCpltCallback() - (+) Transmit in slave/device FMPSMBUS mode an amount of data in non-blocking mode using HAL_FMPSMBUS_Slave_Transmit_IT() - (++) At transmission end of transfer HAL_FMPSMBUS_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPSMBUS_SlaveTxCpltCallback() - (+) Receive in slave/device FMPSMBUS mode an amount of data in non-blocking mode using HAL_FMPSMBUS_Slave_Receive_IT() - (++) At reception end of transfer HAL_FMPSMBUS_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPSMBUS_SlaveRxCpltCallback() - (+) Enable/Disable the FMPSMBUS alert mode using HAL_FMPSMBUS_EnableAlert_IT() HAL_FMPSMBUS_DisableAlert_IT() - (++) When FMPSMBUS Alert is generated HAL_FMPSMBUS_ErrorCallback() is executed and user can - add his own code by customization of function pointer HAL_FMPSMBUS_ErrorCallback() - to check the Alert Error Code using function HAL_FMPSMBUS_GetError() - (+) Get HAL state machine or error values using HAL_FMPSMBUS_GetState() or HAL_FMPSMBUS_GetError() - (+) In case of transfer Error, HAL_FMPSMBUS_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_FMPSMBUS_ErrorCallback() - to check the Error Code using function HAL_FMPSMBUS_GetError() - - *** FMPSMBUS HAL driver macros list *** - ================================== - [..] - Below the list of most used macros in FMPSMBUS HAL driver. - - (+) __HAL_FMPSMBUS_ENABLE: Enable the FMPSMBUS peripheral - (+) __HAL_FMPSMBUS_DISABLE: Disable the FMPSMBUS peripheral - (+) __HAL_FMPSMBUS_GET_FLAG: Check whether the specified FMPSMBUS flag is set or not - (+) __HAL_FMPSMBUS_CLEAR_FLAG: Clear the specified FMPSMBUS pending flag - (+) __HAL_FMPSMBUS_ENABLE_IT: Enable the specified FMPSMBUS interrupt - (+) __HAL_FMPSMBUS_DISABLE_IT: Disable the specified FMPSMBUS interrupt - - *** Callback registration *** - ============================================= - [..] - The compilation flag USE_HAL_FMPSMBUS_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_FMPSMBUS_RegisterCallback() or HAL_FMPSMBUS_RegisterAddrCallback() - to register an interrupt callback. - [..] - Function HAL_FMPSMBUS_RegisterCallback() allows to register following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) ErrorCallback : callback for error detection. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - [..] - For specific callback AddrCallback use dedicated register callbacks : HAL_FMPSMBUS_RegisterAddrCallback. - [..] - Use function HAL_FMPSMBUS_UnRegisterCallback to reset a callback to the default - weak function. - HAL_FMPSMBUS_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) ErrorCallback : callback for error detection. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - [..] - For callback AddrCallback use dedicated register callbacks : HAL_FMPSMBUS_UnRegisterAddrCallback. - [..] - By default, after the HAL_FMPSMBUS_Init() and when the state is HAL_FMPI2C_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_FMPSMBUS_MasterTxCpltCallback(), HAL_FMPSMBUS_MasterRxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_FMPSMBUS_Init()/ HAL_FMPSMBUS_DeInit() only when - these callbacks are null (not registered beforehand). - If MspInit or MspDeInit are not null, the HAL_FMPSMBUS_Init()/ HAL_FMPSMBUS_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - [..] - Callbacks can be registered/unregistered in HAL_FMPI2C_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_FMPI2C_STATE_READY or HAL_FMPI2C_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_FMPSMBUS_RegisterCallback() before calling HAL_FMPSMBUS_DeInit() - or HAL_FMPSMBUS_Init() function. - [..] - When the compilation flag USE_HAL_FMPSMBUS_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - [..] - (@) You can refer to the FMPSMBUS HAL driver header file for more useful macros - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FMPSMBUS FMPSMBUS - * @brief FMPSMBUS HAL module driver - * @{ - */ - -#ifdef HAL_FMPSMBUS_MODULE_ENABLED - -#if defined(FMPI2C_CR1_PE) -/* Private typedef -----------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Private_Define FMPSMBUS Private Constants - * @{ - */ -#define TIMING_CLEAR_MASK (0xF0FFFFFFUL) /*!< FMPSMBUS TIMING clear register Mask */ -#define HAL_TIMEOUT_ADDR (10000U) /*!< 10 s */ -#define HAL_TIMEOUT_BUSY (25U) /*!< 25 ms */ -#define HAL_TIMEOUT_DIR (25U) /*!< 25 ms */ -#define HAL_TIMEOUT_RXNE (25U) /*!< 25 ms */ -#define HAL_TIMEOUT_STOPF (25U) /*!< 25 ms */ -#define HAL_TIMEOUT_TC (25U) /*!< 25 ms */ -#define HAL_TIMEOUT_TCR (25U) /*!< 25 ms */ -#define HAL_TIMEOUT_TXIS (25U) /*!< 25 ms */ -#define MAX_NBYTE_SIZE 255U -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup FMPSMBUS_Private_Functions FMPSMBUS Private Functions - * @{ - */ -static HAL_StatusTypeDef FMPSMBUS_WaitOnFlagUntilTimeout(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t Flag, - FlagStatus Status, uint32_t Timeout); - -static void FMPSMBUS_Enable_IRQ(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t InterruptRequest); -static void FMPSMBUS_Disable_IRQ(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t InterruptRequest); -static HAL_StatusTypeDef FMPSMBUS_Master_ISR(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t StatusFlags); -static HAL_StatusTypeDef FMPSMBUS_Slave_ISR(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t StatusFlags); - -static void FMPSMBUS_ConvertOtherXferOptions(FMPSMBUS_HandleTypeDef *hfmpsmbus); - -static void FMPSMBUS_ITErrorHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus); - -static void FMPSMBUS_TransferConfig(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint8_t Size, - uint32_t Mode, uint32_t Request); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup FMPSMBUS_Exported_Functions FMPSMBUS Exported Functions - * @{ - */ - -/** @defgroup FMPSMBUS_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - deinitialize the FMPSMBUSx peripheral: - - (+) User must Implement HAL_FMPSMBUS_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, IT and NVIC ). - - (+) Call the function HAL_FMPSMBUS_Init() to configure the selected device with - the selected configuration: - (++) Clock Timing - (++) Bus Timeout - (++) Analog Filer mode - (++) Own Address 1 - (++) Addressing mode (Master, Slave) - (++) Dual Addressing mode - (++) Own Address 2 - (++) Own Address 2 Mask - (++) General call mode - (++) Nostretch mode - (++) Packet Error Check mode - (++) Peripheral mode - - - (+) Call the function HAL_FMPSMBUS_DeInit() to restore the default configuration - of the selected FMPSMBUSx peripheral. - - (+) Enable/Disable Analog/Digital filters with HAL_FMPSMBUS_ConfigAnalogFilter() and - HAL_FMPSMBUS_ConfigDigitalFilter(). - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the FMPSMBUS according to the specified parameters - * in the FMPSMBUS_InitTypeDef and initialize the associated handle. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_Init(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Check the FMPSMBUS handle allocation */ - if (hfmpsmbus == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); - assert_param(IS_FMPSMBUS_ANALOG_FILTER(hfmpsmbus->Init.AnalogFilter)); - assert_param(IS_FMPSMBUS_OWN_ADDRESS1(hfmpsmbus->Init.OwnAddress1)); - assert_param(IS_FMPSMBUS_ADDRESSING_MODE(hfmpsmbus->Init.AddressingMode)); - assert_param(IS_FMPSMBUS_DUAL_ADDRESS(hfmpsmbus->Init.DualAddressMode)); - assert_param(IS_FMPSMBUS_OWN_ADDRESS2(hfmpsmbus->Init.OwnAddress2)); - assert_param(IS_FMPSMBUS_OWN_ADDRESS2_MASK(hfmpsmbus->Init.OwnAddress2Masks)); - assert_param(IS_FMPSMBUS_GENERAL_CALL(hfmpsmbus->Init.GeneralCallMode)); - assert_param(IS_FMPSMBUS_NO_STRETCH(hfmpsmbus->Init.NoStretchMode)); - assert_param(IS_FMPSMBUS_PEC(hfmpsmbus->Init.PacketErrorCheckMode)); - assert_param(IS_FMPSMBUS_PERIPHERAL_MODE(hfmpsmbus->Init.PeripheralMode)); - - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hfmpsmbus->Lock = HAL_UNLOCKED; - -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->MasterTxCpltCallback = HAL_FMPSMBUS_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - hfmpsmbus->MasterRxCpltCallback = HAL_FMPSMBUS_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - hfmpsmbus->SlaveTxCpltCallback = HAL_FMPSMBUS_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - hfmpsmbus->SlaveRxCpltCallback = HAL_FMPSMBUS_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - hfmpsmbus->ListenCpltCallback = HAL_FMPSMBUS_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - hfmpsmbus->ErrorCallback = HAL_FMPSMBUS_ErrorCallback; /* Legacy weak ErrorCallback */ - hfmpsmbus->AddrCallback = HAL_FMPSMBUS_AddrCallback; /* Legacy weak AddrCallback */ - - if (hfmpsmbus->MspInitCallback == NULL) - { - hfmpsmbus->MspInitCallback = HAL_FMPSMBUS_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ - hfmpsmbus->MspInitCallback(hfmpsmbus); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - HAL_FMPSMBUS_MspInit(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; - - /* Disable the selected FMPSMBUS peripheral */ - __HAL_FMPSMBUS_DISABLE(hfmpsmbus); - - /*---------------------------- FMPSMBUSx TIMINGR Configuration ------------------------*/ - /* Configure FMPSMBUSx: Frequency range */ - hfmpsmbus->Instance->TIMINGR = hfmpsmbus->Init.Timing & TIMING_CLEAR_MASK; - - /*---------------------------- FMPSMBUSx TIMEOUTR Configuration ------------------------*/ - /* Configure FMPSMBUSx: Bus Timeout */ - hfmpsmbus->Instance->TIMEOUTR &= ~FMPI2C_TIMEOUTR_TIMOUTEN; - hfmpsmbus->Instance->TIMEOUTR &= ~FMPI2C_TIMEOUTR_TEXTEN; - hfmpsmbus->Instance->TIMEOUTR = hfmpsmbus->Init.SMBusTimeout; - - /*---------------------------- FMPSMBUSx OAR1 Configuration -----------------------*/ - /* Configure FMPSMBUSx: Own Address1 and ack own address1 mode */ - hfmpsmbus->Instance->OAR1 &= ~FMPI2C_OAR1_OA1EN; - - if (hfmpsmbus->Init.OwnAddress1 != 0UL) - { - if (hfmpsmbus->Init.AddressingMode == FMPSMBUS_ADDRESSINGMODE_7BIT) - { - hfmpsmbus->Instance->OAR1 = (FMPI2C_OAR1_OA1EN | hfmpsmbus->Init.OwnAddress1); - } - else /* FMPSMBUS_ADDRESSINGMODE_10BIT */ - { - hfmpsmbus->Instance->OAR1 = (FMPI2C_OAR1_OA1EN | FMPI2C_OAR1_OA1MODE | hfmpsmbus->Init.OwnAddress1); - } - } - - /*---------------------------- FMPSMBUSx CR2 Configuration ------------------------*/ - /* Configure FMPSMBUSx: Addressing Master mode */ - if (hfmpsmbus->Init.AddressingMode == FMPSMBUS_ADDRESSINGMODE_10BIT) - { - hfmpsmbus->Instance->CR2 = (FMPI2C_CR2_ADD10); - } - /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process) */ - /* AUTOEND and NACK bit will be manage during Transfer process */ - hfmpsmbus->Instance->CR2 |= (FMPI2C_CR2_AUTOEND | FMPI2C_CR2_NACK); - - /*---------------------------- FMPSMBUSx OAR2 Configuration -----------------------*/ - /* Configure FMPSMBUSx: Dual mode and Own Address2 */ - hfmpsmbus->Instance->OAR2 = (hfmpsmbus->Init.DualAddressMode | hfmpsmbus->Init.OwnAddress2 | \ - (hfmpsmbus->Init.OwnAddress2Masks << 8U)); - - /*---------------------------- FMPSMBUSx CR1 Configuration ------------------------*/ - /* Configure FMPSMBUSx: Generalcall and NoStretch mode */ - hfmpsmbus->Instance->CR1 = (hfmpsmbus->Init.GeneralCallMode | hfmpsmbus->Init.NoStretchMode | \ - hfmpsmbus->Init.PacketErrorCheckMode | hfmpsmbus->Init.PeripheralMode | \ - hfmpsmbus->Init.AnalogFilter); - - /* Enable Slave Byte Control only in case of Packet Error Check is enabled - and FMPSMBUS Peripheral is set in Slave mode */ - if ((hfmpsmbus->Init.PacketErrorCheckMode == FMPSMBUS_PEC_ENABLE) && \ - ((hfmpsmbus->Init.PeripheralMode == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE) || \ - (hfmpsmbus->Init.PeripheralMode == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE_ARP))) - { - hfmpsmbus->Instance->CR1 |= FMPI2C_CR1_SBC; - } - - /* Enable the selected FMPSMBUS peripheral */ - __HAL_FMPSMBUS_ENABLE(hfmpsmbus); - - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; - hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_READY; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitialize the FMPSMBUS peripheral. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_DeInit(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Check the FMPSMBUS handle allocation */ - if (hfmpsmbus == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; - - /* Disable the FMPSMBUS Peripheral Clock */ - __HAL_FMPSMBUS_DISABLE(hfmpsmbus); - -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - if (hfmpsmbus->MspDeInitCallback == NULL) - { - hfmpsmbus->MspDeInitCallback = HAL_FMPSMBUS_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - hfmpsmbus->MspDeInitCallback(hfmpsmbus); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_FMPSMBUS_MspDeInit(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; - hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_RESET; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hfmpsmbus); - - return HAL_OK; -} - -/** - * @brief Initialize the FMPSMBUS MSP. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -__weak void HAL_FMPSMBUS_MspInit(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize the FMPSMBUS MSP. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -__weak void HAL_FMPSMBUS_MspDeInit(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Configure Analog noise filter. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param AnalogFilter This parameter can be one of the following values: - * @arg @ref FMPSMBUS_ANALOGFILTER_ENABLE - * @arg @ref FMPSMBUS_ANALOGFILTER_DISABLE - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_ConfigAnalogFilter(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t AnalogFilter) -{ - /* Check the parameters */ - assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); - assert_param(IS_FMPSMBUS_ANALOG_FILTER(AnalogFilter)); - - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; - - /* Disable the selected FMPSMBUS peripheral */ - __HAL_FMPSMBUS_DISABLE(hfmpsmbus); - - /* Reset ANOFF bit */ - hfmpsmbus->Instance->CR1 &= ~(FMPI2C_CR1_ANFOFF); - - /* Set analog filter bit*/ - hfmpsmbus->Instance->CR1 |= AnalogFilter; - - __HAL_FMPSMBUS_ENABLE(hfmpsmbus); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configure Digital noise filter. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param DigitalFilter Coefficient of digital noise filter between Min_Data=0x00 and Max_Data=0x0F. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_ConfigDigitalFilter(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t DigitalFilter) -{ - uint32_t tmpreg; - - /* Check the parameters */ - assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); - assert_param(IS_FMPSMBUS_DIGITAL_FILTER(DigitalFilter)); - - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; - - /* Disable the selected FMPSMBUS peripheral */ - __HAL_FMPSMBUS_DISABLE(hfmpsmbus); - - /* Get the old register value */ - tmpreg = hfmpsmbus->Instance->CR1; - - /* Reset FMPI2C DNF bits [11:8] */ - tmpreg &= ~(FMPI2C_CR1_DNF); - - /* Set FMPI2Cx DNF coefficient */ - tmpreg |= DigitalFilter << FMPI2C_CR1_DNF_Pos; - - /* Store the new register value */ - hfmpsmbus->Instance->CR1 = tmpreg; - - __HAL_FMPSMBUS_ENABLE(hfmpsmbus); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User FMPSMBUS Callback - * To be used instead of the weak predefined callback - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_FMPSMBUS_ERROR_CB_ID Error callback ID - * @arg @ref HAL_FMPSMBUS_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_FMPSMBUS_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_RegisterCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - HAL_FMPSMBUS_CallbackIDTypeDef CallbackID, - pFMPSMBUS_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hfmpsmbus); - - if (HAL_FMPSMBUS_STATE_READY == hfmpsmbus->State) - { - switch (CallbackID) - { - case HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID : - hfmpsmbus->MasterTxCpltCallback = pCallback; - break; - - case HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID : - hfmpsmbus->MasterRxCpltCallback = pCallback; - break; - - case HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID : - hfmpsmbus->SlaveTxCpltCallback = pCallback; - break; - - case HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID : - hfmpsmbus->SlaveRxCpltCallback = pCallback; - break; - - case HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID : - hfmpsmbus->ListenCpltCallback = pCallback; - break; - - case HAL_FMPSMBUS_ERROR_CB_ID : - hfmpsmbus->ErrorCallback = pCallback; - break; - - case HAL_FMPSMBUS_MSPINIT_CB_ID : - hfmpsmbus->MspInitCallback = pCallback; - break; - - case HAL_FMPSMBUS_MSPDEINIT_CB_ID : - hfmpsmbus->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_FMPSMBUS_STATE_RESET == hfmpsmbus->State) - { - switch (CallbackID) - { - case HAL_FMPSMBUS_MSPINIT_CB_ID : - hfmpsmbus->MspInitCallback = pCallback; - break; - - case HAL_FMPSMBUS_MSPDEINIT_CB_ID : - hfmpsmbus->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hfmpsmbus); - return status; -} - -/** - * @brief Unregister an FMPSMBUS Callback - * FMPSMBUS callback is redirected to the weak predefined callback - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * This parameter can be one of the following values: - * @arg @ref HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_FMPSMBUS_ERROR_CB_ID Error callback ID - * @arg @ref HAL_FMPSMBUS_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_FMPSMBUS_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_UnRegisterCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - HAL_FMPSMBUS_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hfmpsmbus); - - if (HAL_FMPSMBUS_STATE_READY == hfmpsmbus->State) - { - switch (CallbackID) - { - case HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID : - hfmpsmbus->MasterTxCpltCallback = HAL_FMPSMBUS_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - break; - - case HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID : - hfmpsmbus->MasterRxCpltCallback = HAL_FMPSMBUS_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - break; - - case HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID : - hfmpsmbus->SlaveTxCpltCallback = HAL_FMPSMBUS_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - break; - - case HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID : - hfmpsmbus->SlaveRxCpltCallback = HAL_FMPSMBUS_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - break; - - case HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID : - hfmpsmbus->ListenCpltCallback = HAL_FMPSMBUS_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - break; - - case HAL_FMPSMBUS_ERROR_CB_ID : - hfmpsmbus->ErrorCallback = HAL_FMPSMBUS_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_FMPSMBUS_MSPINIT_CB_ID : - hfmpsmbus->MspInitCallback = HAL_FMPSMBUS_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_FMPSMBUS_MSPDEINIT_CB_ID : - hfmpsmbus->MspDeInitCallback = HAL_FMPSMBUS_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_FMPSMBUS_STATE_RESET == hfmpsmbus->State) - { - switch (CallbackID) - { - case HAL_FMPSMBUS_MSPINIT_CB_ID : - hfmpsmbus->MspInitCallback = HAL_FMPSMBUS_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_FMPSMBUS_MSPDEINIT_CB_ID : - hfmpsmbus->MspDeInitCallback = HAL_FMPSMBUS_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hfmpsmbus); - return status; -} - -/** - * @brief Register the Slave Address Match FMPSMBUS Callback - * To be used instead of the weak HAL_FMPSMBUS_AddrCallback() predefined callback - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param pCallback pointer to the Address Match Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_RegisterAddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - pFMPSMBUS_AddrCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hfmpsmbus); - - if (HAL_FMPSMBUS_STATE_READY == hfmpsmbus->State) - { - hfmpsmbus->AddrCallback = pCallback; - } - else - { - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hfmpsmbus); - return status; -} - -/** - * @brief UnRegister the Slave Address Match FMPSMBUS Callback - * Info Ready FMPSMBUS Callback is redirected to the weak HAL_FMPSMBUS_AddrCallback() predefined callback - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_UnRegisterAddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hfmpsmbus); - - if (HAL_FMPSMBUS_STATE_READY == hfmpsmbus->State) - { - hfmpsmbus->AddrCallback = HAL_FMPSMBUS_AddrCallback; /* Legacy weak AddrCallback */ - } - else - { - /* Update the error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hfmpsmbus); - return status; -} - -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup FMPSMBUS_Exported_Functions_Group2 Input and Output operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the FMPSMBUS data - transfers. - - (#) Blocking mode function to check if device is ready for usage is : - (++) HAL_FMPSMBUS_IsDeviceReady() - - (#) There is only one mode of transfer: - (++) Non-Blocking mode : The communication is performed using Interrupts. - These functions return the status of the transfer startup. - The end of the data processing will be indicated through the - dedicated FMPSMBUS IRQ when using Interrupt mode. - - (#) Non-Blocking mode functions with Interrupt are : - (++) HAL_FMPSMBUS_Master_Transmit_IT() - (++) HAL_FMPSMBUS_Master_Receive_IT() - (++) HAL_FMPSMBUS_Slave_Transmit_IT() - (++) HAL_FMPSMBUS_Slave_Receive_IT() - (++) HAL_FMPSMBUS_EnableListen_IT() or alias HAL_FMPSMBUS_EnableListen_IT() - (++) HAL_FMPSMBUS_DisableListen_IT() - (++) HAL_FMPSMBUS_EnableAlert_IT() - (++) HAL_FMPSMBUS_DisableAlert_IT() - - (#) A set of Transfer Complete Callbacks are provided in non-Blocking mode: - (++) HAL_FMPSMBUS_MasterTxCpltCallback() - (++) HAL_FMPSMBUS_MasterRxCpltCallback() - (++) HAL_FMPSMBUS_SlaveTxCpltCallback() - (++) HAL_FMPSMBUS_SlaveRxCpltCallback() - (++) HAL_FMPSMBUS_AddrCallback() - (++) HAL_FMPSMBUS_ListenCpltCallback() - (++) HAL_FMPSMBUS_ErrorCallback() - -@endverbatim - * @{ - */ - -/** - * @brief Transmit in master/host FMPSMBUS mode an amount of data in non-blocking mode with Interrupt. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPSMBUS_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Transmit_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, - uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - uint32_t tmp; - - /* Check the parameters */ - assert_param(IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_MASTER_BUSY_TX; - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; - /* Prepare transfer parameters */ - hfmpsmbus->pBuffPtr = pData; - hfmpsmbus->XferCount = Size; - hfmpsmbus->XferOptions = XferOptions; - - /* In case of Quick command, remove autoend mode */ - /* Manage the stop generation by software */ - if (hfmpsmbus->pBuffPtr == NULL) - { - hfmpsmbus->XferOptions &= ~FMPSMBUS_AUTOEND_MODE; - } - - if (Size > MAX_NBYTE_SIZE) - { - hfmpsmbus->XferSize = MAX_NBYTE_SIZE; - } - else - { - hfmpsmbus->XferSize = Size; - } - - /* Send Slave Address */ - /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */ - if ((hfmpsmbus->XferSize < hfmpsmbus->XferCount) && (hfmpsmbus->XferSize == MAX_NBYTE_SIZE)) - { - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, - FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE), - FMPSMBUS_GENERATE_START_WRITE); - } - else - { - /* If transfer direction not change, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - - /* Store current volatile XferOptions, misra rule */ - tmp = hfmpsmbus->XferOptions; - - if ((hfmpsmbus->PreviousState == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) && \ - (IS_FMPSMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(tmp) == 0)) - { - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, - FMPSMBUS_NO_STARTSTOP); - } - /* Else transfer direction change, so generate Restart with new transfer direction */ - else - { - /* Convert OTHER_xxx XferOptions if any */ - FMPSMBUS_ConvertOtherXferOptions(hfmpsmbus); - - /* Handle Transfer */ - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, - hfmpsmbus->XferOptions, - FMPSMBUS_GENERATE_START_WRITE); - } - - /* If PEC mode is enable, size to transmit manage by SW part should be Size-1 byte, corresponding to PEC byte */ - /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */ - if (FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) - { - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - } - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process - to avoid the risk of FMPSMBUS interrupt handle execution before current - process unlock */ - FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in master/host FMPSMBUS mode an amount of data in non-blocking mode with Interrupt. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPSMBUS_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Receive_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions) -{ - uint32_t tmp; - - /* Check the parameters */ - assert_param(IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_MASTER_BUSY_RX; - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; - - /* Prepare transfer parameters */ - hfmpsmbus->pBuffPtr = pData; - hfmpsmbus->XferCount = Size; - hfmpsmbus->XferOptions = XferOptions; - - /* In case of Quick command, remove autoend mode */ - /* Manage the stop generation by software */ - if (hfmpsmbus->pBuffPtr == NULL) - { - hfmpsmbus->XferOptions &= ~FMPSMBUS_AUTOEND_MODE; - } - - if (Size > MAX_NBYTE_SIZE) - { - hfmpsmbus->XferSize = MAX_NBYTE_SIZE; - } - else - { - hfmpsmbus->XferSize = Size; - } - - /* Send Slave Address */ - /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */ - if ((hfmpsmbus->XferSize < hfmpsmbus->XferCount) && (hfmpsmbus->XferSize == MAX_NBYTE_SIZE)) - { - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, - FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE), - FMPSMBUS_GENERATE_START_READ); - } - else - { - /* If transfer direction not change, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - - /* Store current volatile XferOptions, Misra rule */ - tmp = hfmpsmbus->XferOptions; - - if ((hfmpsmbus->PreviousState == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) && \ - (IS_FMPSMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(tmp) == 0)) - { - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, - FMPSMBUS_NO_STARTSTOP); - } - /* Else transfer direction change, so generate Restart with new transfer direction */ - else - { - /* Convert OTHER_xxx XferOptions if any */ - FMPSMBUS_ConvertOtherXferOptions(hfmpsmbus); - - /* Handle Transfer */ - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, - hfmpsmbus->XferOptions, - FMPSMBUS_GENERATE_START_READ); - } - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process - to avoid the risk of FMPSMBUS interrupt handle execution before current - process unlock */ - FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Abort a master/host FMPSMBUS process communication with Interrupt. - * @note This abort can be called only if state is ready - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Abort_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress) -{ - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - /* Keep the same state as previous */ - /* to perform as well the call of the corresponding end of transfer callback */ - if (hfmpsmbus->PreviousState == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) - { - hfmpsmbus->State = HAL_FMPSMBUS_STATE_MASTER_BUSY_TX; - } - else if (hfmpsmbus->PreviousState == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) - { - hfmpsmbus->State = HAL_FMPSMBUS_STATE_MASTER_BUSY_RX; - } - else - { - /* Wrong usage of abort function */ - /* This function should be used only in case of abort monitored by master device */ - return HAL_ERROR; - } - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; - - /* Set NBYTES to 1 to generate a dummy read on FMPSMBUS peripheral */ - /* Set AUTOEND mode, this will generate a NACK then STOP condition to abort the current transfer */ - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, 1, FMPSMBUS_AUTOEND_MODE, FMPSMBUS_NO_STARTSTOP); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process - to avoid the risk of FMPSMBUS interrupt handle execution before current - process unlock */ - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) - { - FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); - } - else if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) - { - FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); - } - else - { - /* Nothing to do */ - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in slave/device FMPSMBUS mode an amount of data in non-blocking mode with Interrupt. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPSMBUS_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_Slave_Transmit_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t *pData, uint16_t Size, - uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_LISTEN) == HAL_FMPSMBUS_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0UL)) - { - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR | FMPSMBUS_IT_TX); - - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - hfmpsmbus->State = (HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX | HAL_FMPSMBUS_STATE_LISTEN); - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; - - /* Set SBC bit to manage Acknowledge at each bit */ - hfmpsmbus->Instance->CR1 |= FMPI2C_CR1_SBC; - - /* Enable Address Acknowledge */ - hfmpsmbus->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Prepare transfer parameters */ - hfmpsmbus->pBuffPtr = pData; - hfmpsmbus->XferCount = Size; - hfmpsmbus->XferOptions = XferOptions; - - /* Convert OTHER_xxx XferOptions if any */ - FMPSMBUS_ConvertOtherXferOptions(hfmpsmbus); - - if (Size > MAX_NBYTE_SIZE) - { - hfmpsmbus->XferSize = MAX_NBYTE_SIZE; - } - else - { - hfmpsmbus->XferSize = Size; - } - - /* Set NBYTES to write and reload if size > MAX_NBYTE_SIZE and generate RESTART */ - if ((hfmpsmbus->XferSize < hfmpsmbus->XferCount) && (hfmpsmbus->XferSize == MAX_NBYTE_SIZE)) - { - FMPSMBUS_TransferConfig(hfmpsmbus, 0, (uint8_t)hfmpsmbus->XferSize, - FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE), - FMPSMBUS_NO_STARTSTOP); - } - else - { - /* Set NBYTE to transmit */ - FMPSMBUS_TransferConfig(hfmpsmbus, 0, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, - FMPSMBUS_NO_STARTSTOP); - - /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */ - /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */ - if (FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) - { - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - } - } - - /* Clear ADDR flag after prepare the transfer parameters */ - /* This action will generate an acknowledge to the HOST */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ADDR); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process - to avoid the risk of FMPSMBUS interrupt handle execution before current - process unlock */ - /* REnable ADDR interrupt */ - FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX | FMPSMBUS_IT_ADDR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave/device FMPSMBUS mode an amount of data in non-blocking mode with Interrupt. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref FMPSMBUS_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_Slave_Receive_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t *pData, uint16_t Size, - uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_LISTEN) == HAL_FMPSMBUS_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0UL)) - { - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_INVALID_PARAM; - return HAL_ERROR; - } - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR | FMPSMBUS_IT_RX); - - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - hfmpsmbus->State = (HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX | HAL_FMPSMBUS_STATE_LISTEN); - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; - - /* Set SBC bit to manage Acknowledge at each bit */ - hfmpsmbus->Instance->CR1 |= FMPI2C_CR1_SBC; - - /* Enable Address Acknowledge */ - hfmpsmbus->Instance->CR2 &= ~FMPI2C_CR2_NACK; - - /* Prepare transfer parameters */ - hfmpsmbus->pBuffPtr = pData; - hfmpsmbus->XferSize = Size; - hfmpsmbus->XferCount = Size; - hfmpsmbus->XferOptions = XferOptions; - - /* Convert OTHER_xxx XferOptions if any */ - FMPSMBUS_ConvertOtherXferOptions(hfmpsmbus); - - /* Set NBYTE to receive */ - /* If XferSize equal "1", or XferSize equal "2" with PEC requested (mean 1 data byte + 1 PEC byte */ - /* no need to set RELOAD bit mode, a ACK will be automatically generated in that case */ - /* else need to set RELOAD bit mode to generate an automatic ACK at each byte Received */ - /* This RELOAD bit will be reset for last BYTE to be receive in FMPSMBUS_Slave_ISR */ - if (((FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) && (hfmpsmbus->XferSize == 2U)) || (hfmpsmbus->XferSize == 1U)) - { - FMPSMBUS_TransferConfig(hfmpsmbus, 0, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, - FMPSMBUS_NO_STARTSTOP); - } - else - { - FMPSMBUS_TransferConfig(hfmpsmbus, 0, 1, hfmpsmbus->XferOptions | FMPSMBUS_RELOAD_MODE, FMPSMBUS_NO_STARTSTOP); - } - - /* Clear ADDR flag after prepare the transfer parameters */ - /* This action will generate an acknowledge to the HOST */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ADDR); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Note : The FMPSMBUS interrupts must be enabled after unlocking current process - to avoid the risk of FMPSMBUS interrupt handle execution before current - process unlock */ - /* REnable ADDR interrupt */ - FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX | FMPSMBUS_IT_ADDR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Enable the Address listen mode with Interrupt. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_EnableListen_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - hfmpsmbus->State = HAL_FMPSMBUS_STATE_LISTEN; - - /* Enable the Address Match interrupt */ - FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR); - - return HAL_OK; -} - -/** - * @brief Disable the Address listen mode with Interrupt. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_DisableListen_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Disable Address listen mode only if a transfer is not ongoing */ - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_LISTEN) - { - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Disable the Address Match interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Enable the FMPSMBUS alert mode with Interrupt. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUSx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_EnableAlert_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Enable SMBus alert */ - hfmpsmbus->Instance->CR1 |= FMPI2C_CR1_ALERTEN; - - /* Clear ALERT flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ALERT); - - /* Enable Alert Interrupt */ - FMPSMBUS_Enable_IRQ(hfmpsmbus, FMPSMBUS_IT_ALERT); - - return HAL_OK; -} -/** - * @brief Disable the FMPSMBUS alert mode with Interrupt. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUSx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_DisableAlert_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Enable SMBus alert */ - hfmpsmbus->Instance->CR1 &= ~FMPI2C_CR1_ALERTEN; - - /* Disable Alert Interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ALERT); - - return HAL_OK; -} - -/** - * @brief Check if target device is ready for communication. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Trials Number of trials - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_FMPSMBUS_IsDeviceReady(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint32_t Trials, - uint32_t Timeout) -{ - uint32_t tickstart; - - __IO uint32_t FMPSMBUS_Trials = 0UL; - - FlagStatus tmp1; - FlagStatus tmp2; - - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_READY) - { - if (__HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_BUSY) != RESET) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_BUSY; - hfmpsmbus->ErrorCode = HAL_FMPSMBUS_ERROR_NONE; - - do - { - /* Generate Start */ - hfmpsmbus->Instance->CR2 = FMPSMBUS_GENERATE_START(hfmpsmbus->Init.AddressingMode, DevAddress); - - /* No need to Check TC flag, with AUTOEND mode the stop is automatically generated */ - /* Wait until STOPF flag is set or a NACK flag is set*/ - tickstart = HAL_GetTick(); - - tmp1 = __HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); - tmp2 = __HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); - - while ((tmp1 == RESET) && (tmp2 == RESET)) - { - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0UL)) - { - /* Device is ready */ - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Update FMPSMBUS error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_HALTIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - return HAL_ERROR; - } - } - - tmp1 = __HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); - tmp2 = __HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); - } - - /* Check if the NACKF flag has not been set */ - if (__HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF) == RESET) - { - /* Wait until STOPF flag is reset */ - if (FMPSMBUS_WaitOnFlagUntilTimeout(hfmpsmbus, FMPSMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear STOP Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); - - /* Device is ready */ - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - return HAL_OK; - } - else - { - /* Wait until STOPF flag is reset */ - if (FMPSMBUS_WaitOnFlagUntilTimeout(hfmpsmbus, FMPSMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear NACK Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); - - /* Clear STOP Flag, auto generated with autoend*/ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); - } - - /* Check if the maximum allowed number of trials has been reached */ - if (FMPSMBUS_Trials == Trials) - { - /* Generate Stop */ - hfmpsmbus->Instance->CR2 |= FMPI2C_CR2_STOP; - - /* Wait until STOPF flag is reset */ - if (FMPSMBUS_WaitOnFlagUntilTimeout(hfmpsmbus, FMPSMBUS_FLAG_STOPF, RESET, Timeout) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear STOP Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); - } - - /* Increment Trials */ - FMPSMBUS_Trials++; - } while (FMPSMBUS_Trials < Trials); - - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Update FMPSMBUS error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_HALTIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - return HAL_ERROR; - } - else - { - return HAL_BUSY; - } -} -/** - * @} - */ - -/** @defgroup FMPSMBUS_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ - -/** - * @brief Handle FMPSMBUS event interrupt request. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -void HAL_FMPSMBUS_EV_IRQHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Use a local variable to store the current ISR flags */ - /* This action will avoid a wrong treatment due to ISR flags change during interrupt handler */ - uint32_t tmpisrvalue = READ_REG(hfmpsmbus->Instance->ISR); - uint32_t tmpcr1value = READ_REG(hfmpsmbus->Instance->CR1); - - /* FMPSMBUS in mode Transmitter ---------------------------------------------------*/ - if ((FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, (FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | - FMPSMBUS_IT_NACKI | FMPSMBUS_IT_TXI)) != RESET) && - ((FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TXIS) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TCR) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TC) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_STOPF) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_AF) != RESET))) - { - /* Slave mode selected */ - if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) - { - (void)FMPSMBUS_Slave_ISR(hfmpsmbus, tmpisrvalue); - } - /* Master mode selected */ - else if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) - { - (void)FMPSMBUS_Master_ISR(hfmpsmbus, tmpisrvalue); - } - else - { - /* Nothing to do */ - } - } - - /* FMPSMBUS in mode Receiver ----------------------------------------------------*/ - if ((FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, (FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | - FMPSMBUS_IT_NACKI | FMPSMBUS_IT_RXI)) != RESET) && - ((FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_RXNE) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TCR) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_TC) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_STOPF) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_AF) != RESET))) - { - /* Slave mode selected */ - if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) - { - (void)FMPSMBUS_Slave_ISR(hfmpsmbus, tmpisrvalue); - } - /* Master mode selected */ - else if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) - { - (void)FMPSMBUS_Master_ISR(hfmpsmbus, tmpisrvalue); - } - else - { - /* Nothing to do */ - } - } - - /* FMPSMBUS in mode Listener Only --------------------------------------------------*/ - if (((FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, FMPSMBUS_IT_ADDRI) != RESET) || - (FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, FMPSMBUS_IT_STOPI) != RESET) || - (FMPSMBUS_CHECK_IT_SOURCE(tmpcr1value, FMPSMBUS_IT_NACKI) != RESET)) && - ((FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_ADDR) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_STOPF) != RESET) || - (FMPSMBUS_CHECK_FLAG(tmpisrvalue, FMPSMBUS_FLAG_AF) != RESET))) - { - if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_LISTEN) == HAL_FMPSMBUS_STATE_LISTEN) - { - (void)FMPSMBUS_Slave_ISR(hfmpsmbus, tmpisrvalue); - } - } -} - -/** - * @brief Handle FMPSMBUS error interrupt request. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -void HAL_FMPSMBUS_ER_IRQHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - FMPSMBUS_ITErrorHandler(hfmpsmbus); -} - -/** - * @brief Master Tx Transfer completed callback. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -__weak void HAL_FMPSMBUS_MasterTxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_MasterTxCpltCallback() could be implemented in the user file - */ -} - -/** - * @brief Master Rx Transfer completed callback. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -__weak void HAL_FMPSMBUS_MasterRxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_MasterRxCpltCallback() could be implemented in the user file - */ -} - -/** @brief Slave Tx Transfer completed callback. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -__weak void HAL_FMPSMBUS_SlaveTxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_SlaveTxCpltCallback() could be implemented in the user file - */ -} - -/** - * @brief Slave Rx Transfer completed callback. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -__weak void HAL_FMPSMBUS_SlaveRxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_SlaveRxCpltCallback() could be implemented in the user file - */ -} - -/** - * @brief Slave Address Match callback. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param TransferDirection Master request Transfer Direction (Write/Read) - * @param AddrMatchCode Address Match Code - * @retval None - */ -__weak void HAL_FMPSMBUS_AddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t TransferDirection, - uint16_t AddrMatchCode) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - UNUSED(TransferDirection); - UNUSED(AddrMatchCode); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_AddrCallback() could be implemented in the user file - */ -} - -/** - * @brief Listen Complete callback. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -__weak void HAL_FMPSMBUS_ListenCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_ListenCpltCallback() could be implemented in the user file - */ -} - -/** - * @brief FMPSMBUS error callback. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval None - */ -__weak void HAL_FMPSMBUS_ErrorCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hfmpsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_FMPSMBUS_ErrorCallback() could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup FMPSMBUS_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief Peripheral State and Errors functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the FMPSMBUS handle state. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval HAL state - */ -uint32_t HAL_FMPSMBUS_GetState(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* Return FMPSMBUS handle state */ - return hfmpsmbus->State; -} - -/** - * @brief Return the FMPSMBUS error code. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @retval FMPSMBUS Error Code - */ -uint32_t HAL_FMPSMBUS_GetError(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - return hfmpsmbus->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup FMPSMBUS_Private_Functions FMPSMBUS Private Functions - * @brief Data transfers Private functions - * @{ - */ - -/** - * @brief Interrupt Sub-Routine which handle the Interrupt Flags Master Mode. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param StatusFlags Value of Interrupt Flags. - * @retval HAL status - */ -static HAL_StatusTypeDef FMPSMBUS_Master_ISR(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t StatusFlags) -{ - uint16_t DevAddress; - - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_AF) != RESET) - { - /* Clear NACK Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); - - /* Set corresponding Error Code */ - /* No need to generate STOP, it is automatically done */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_ACKF; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the Error callback to inform upper layer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->ErrorCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_ErrorCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_STOPF) != RESET) - { - /* Check and treat errors if errors occurs during STOP process */ - FMPSMBUS_ITErrorHandler(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) - { - /* Disable Interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); - - /* Clear STOP Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); - - /* Clear Configuration Register 2 */ - FMPSMBUS_RESET_CR2(hfmpsmbus); - - /* Flush remaining data in Fifo register in case of error occurs before TXEmpty */ - /* Disable the selected FMPSMBUS peripheral */ - __HAL_FMPSMBUS_DISABLE(hfmpsmbus); - - hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_READY; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Re-enable the selected FMPSMBUS peripheral */ - __HAL_FMPSMBUS_ENABLE(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->MasterTxCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_MasterTxCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) - { - /* Store Last receive data if any */ - if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_RXNE) != RESET) - { - /* Read data from RXDR */ - *hfmpsmbus->pBuffPtr = (uint8_t)(hfmpsmbus->Instance->RXDR); - - /* Increment Buffer pointer */ - hfmpsmbus->pBuffPtr++; - - if ((hfmpsmbus->XferSize > 0U)) - { - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - } - } - - /* Disable Interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); - - /* Clear STOP Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); - - /* Clear Configuration Register 2 */ - FMPSMBUS_RESET_CR2(hfmpsmbus); - - hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_READY; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->MasterRxCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_MasterRxCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else - { - /* Nothing to do */ - } - } - else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_RXNE) != RESET) - { - /* Read data from RXDR */ - *hfmpsmbus->pBuffPtr = (uint8_t)(hfmpsmbus->Instance->RXDR); - - /* Increment Buffer pointer */ - hfmpsmbus->pBuffPtr++; - - /* Increment Size counter */ - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - } - else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TXIS) != RESET) - { - /* Write data to TXDR */ - hfmpsmbus->Instance->TXDR = *hfmpsmbus->pBuffPtr; - - /* Increment Buffer pointer */ - hfmpsmbus->pBuffPtr++; - - /* Increment Size counter */ - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - } - else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TCR) != RESET) - { - if ((hfmpsmbus->XferCount != 0U) && (hfmpsmbus->XferSize == 0U)) - { - DevAddress = (uint16_t)(hfmpsmbus->Instance->CR2 & FMPI2C_CR2_SADD); - - if (hfmpsmbus->XferCount > MAX_NBYTE_SIZE) - { - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, MAX_NBYTE_SIZE, - (FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE)), - FMPSMBUS_NO_STARTSTOP); - hfmpsmbus->XferSize = MAX_NBYTE_SIZE; - } - else - { - hfmpsmbus->XferSize = hfmpsmbus->XferCount; - FMPSMBUS_TransferConfig(hfmpsmbus, DevAddress, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, - FMPSMBUS_NO_STARTSTOP); - /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */ - /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */ - if (FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) - { - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - } - } - } - else if ((hfmpsmbus->XferCount == 0U) && (hfmpsmbus->XferSize == 0U)) - { - /* Call TxCpltCallback() if no stop mode is set */ - if (FMPSMBUS_GET_STOP_MODE(hfmpsmbus) != FMPSMBUS_AUTOEND_MODE) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) - { - /* Disable Interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->MasterTxCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_MasterTxCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) - { - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->MasterRxCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_MasterRxCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else - { - /* Nothing to do */ - } - } - } - else - { - /* Nothing to do */ - } - } - else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TC) != RESET) - { - if (hfmpsmbus->XferCount == 0U) - { - /* Specific use case for Quick command */ - if (hfmpsmbus->pBuffPtr == NULL) - { - /* Generate a Stop command */ - hfmpsmbus->Instance->CR2 |= FMPI2C_CR2_STOP; - } - /* Call TxCpltCallback() if no stop mode is set */ - else if (FMPSMBUS_GET_STOP_MODE(hfmpsmbus) != FMPSMBUS_AUTOEND_MODE) - { - /* No Generate Stop, to permit restart mode */ - /* The stop will be done at the end of transfer, when FMPSMBUS_AUTOEND_MODE enable */ - - /* Call the corresponding callback to inform upper layer of End of Transfer */ - if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_TX) - { - /* Disable Interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->MasterTxCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_MasterTxCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else if (hfmpsmbus->State == HAL_FMPSMBUS_STATE_MASTER_BUSY_RX) - { - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->MasterRxCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_MasterRxCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else - { - /* Nothing to do */ - } - } - else - { - /* Nothing to do */ - } - } - } - else - { - /* Nothing to do */ - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - return HAL_OK; -} -/** - * @brief Interrupt Sub-Routine which handle the Interrupt Flags Slave Mode. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param StatusFlags Value of Interrupt Flags. - * @retval HAL status - */ -static HAL_StatusTypeDef FMPSMBUS_Slave_ISR(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t StatusFlags) -{ - uint8_t TransferDirection; - uint16_t SlaveAddrCode; - - /* Process Locked */ - __HAL_LOCK(hfmpsmbus); - - if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_AF) != RESET) - { - /* Check that FMPSMBUS transfer finished */ - /* if yes, normal usecase, a NACK is sent by the HOST when Transfer is finished */ - /* Mean XferCount == 0*/ - /* So clear Flag NACKF only */ - if (hfmpsmbus->XferCount == 0U) - { - /* Clear NACK Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - } - else - { - /* if no, error usecase, a Non-Acknowledge of last Data is generated by the HOST*/ - /* Clear NACK Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_AF); - - /* Set HAL State to "Idle" State, mean to LISTEN state */ - /* So reset Slave Busy state */ - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State &= ~((uint32_t)HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX); - hfmpsmbus->State &= ~((uint32_t)HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX); - - /* Disable RX/TX Interrupts, keep only ADDR Interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX | FMPSMBUS_IT_TX); - - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_ACKF; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the Error callback to inform upper layer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->ErrorCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_ErrorCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - } - else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_ADDR) != RESET) - { - TransferDirection = (uint8_t)(FMPSMBUS_GET_DIR(hfmpsmbus)); - SlaveAddrCode = (uint16_t)(FMPSMBUS_GET_ADDR_MATCH(hfmpsmbus)); - - /* Disable ADDR interrupt to prevent multiple ADDRInterrupt*/ - /* Other ADDRInterrupt will be treat in next Listen usecase */ - __HAL_FMPSMBUS_DISABLE_IT(hfmpsmbus, FMPSMBUS_IT_ADDRI); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call Slave Addr callback */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->AddrCallback(hfmpsmbus, TransferDirection, SlaveAddrCode); -#else - HAL_FMPSMBUS_AddrCallback(hfmpsmbus, TransferDirection, SlaveAddrCode); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else if ((FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_RXNE) != RESET) || - (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TCR) != RESET)) - { - if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) - { - /* Read data from RXDR */ - *hfmpsmbus->pBuffPtr = (uint8_t)(hfmpsmbus->Instance->RXDR); - - /* Increment Buffer pointer */ - hfmpsmbus->pBuffPtr++; - - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - - if (hfmpsmbus->XferCount == 1U) - { - /* Receive last Byte, can be PEC byte in case of PEC BYTE enabled */ - /* or only the last Byte of Transfer */ - /* So reset the RELOAD bit mode */ - hfmpsmbus->XferOptions &= ~FMPSMBUS_RELOAD_MODE; - FMPSMBUS_TransferConfig(hfmpsmbus, 0, 1, hfmpsmbus->XferOptions, FMPSMBUS_NO_STARTSTOP); - } - else if (hfmpsmbus->XferCount == 0U) - { - /* Last Byte is received, disable Interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX); - - /* Remove HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX, keep only HAL_FMPSMBUS_STATE_LISTEN */ - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State &= ~((uint32_t)HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->SlaveRxCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_SlaveRxCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - else - { - /* Set Reload for next Bytes */ - FMPSMBUS_TransferConfig(hfmpsmbus, 0, 1, - FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE), - FMPSMBUS_NO_STARTSTOP); - - /* Ack last Byte Read */ - hfmpsmbus->Instance->CR2 &= ~FMPI2C_CR2_NACK; - } - } - else if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) - { - if ((hfmpsmbus->XferCount != 0U) && (hfmpsmbus->XferSize == 0U)) - { - if (hfmpsmbus->XferCount > MAX_NBYTE_SIZE) - { - FMPSMBUS_TransferConfig(hfmpsmbus, 0, MAX_NBYTE_SIZE, - (FMPSMBUS_RELOAD_MODE | (hfmpsmbus->XferOptions & FMPSMBUS_SENDPEC_MODE)), - FMPSMBUS_NO_STARTSTOP); - hfmpsmbus->XferSize = MAX_NBYTE_SIZE; - } - else - { - hfmpsmbus->XferSize = hfmpsmbus->XferCount; - FMPSMBUS_TransferConfig(hfmpsmbus, 0, (uint8_t)hfmpsmbus->XferSize, hfmpsmbus->XferOptions, - FMPSMBUS_NO_STARTSTOP); - /* If PEC mode is enable, size to transmit should be Size-1 byte, corresponding to PEC byte */ - /* PEC byte is automatically sent by HW block, no need to manage it in Transmit process */ - if (FMPSMBUS_GET_PEC_MODE(hfmpsmbus) != 0UL) - { - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - } - } - } - } - else - { - /* Nothing to do */ - } - } - else if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_TXIS) != RESET) - { - /* Write data to TXDR only if XferCount not reach "0" */ - /* A TXIS flag can be set, during STOP treatment */ - /* Check if all Data have already been sent */ - /* If it is the case, this last write in TXDR is not sent, correspond to a dummy TXIS event */ - if (hfmpsmbus->XferCount > 0U) - { - /* Write data to TXDR */ - hfmpsmbus->Instance->TXDR = *hfmpsmbus->pBuffPtr; - - /* Increment Buffer pointer */ - hfmpsmbus->pBuffPtr++; - - hfmpsmbus->XferCount--; - hfmpsmbus->XferSize--; - } - - if (hfmpsmbus->XferCount == 0U) - { - /* Last Byte is Transmitted */ - /* Remove HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX, keep only HAL_FMPSMBUS_STATE_LISTEN */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_TX); - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State &= ~((uint32_t)HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX); - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->SlaveTxCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_SlaveTxCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - } - else - { - /* Nothing to do */ - } - - /* Check if STOPF is set */ - if (FMPSMBUS_CHECK_FLAG(StatusFlags, FMPSMBUS_FLAG_STOPF) != RESET) - { - if ((hfmpsmbus->State & HAL_FMPSMBUS_STATE_LISTEN) == HAL_FMPSMBUS_STATE_LISTEN) - { - /* Store Last receive data if any */ - if (__HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, FMPSMBUS_FLAG_RXNE) != RESET) - { - /* Read data from RXDR */ - *hfmpsmbus->pBuffPtr = (uint8_t)(hfmpsmbus->Instance->RXDR); - - /* Increment Buffer pointer */ - hfmpsmbus->pBuffPtr++; - - if ((hfmpsmbus->XferSize > 0U)) - { - hfmpsmbus->XferSize--; - hfmpsmbus->XferCount--; - } - } - - /* Disable RX and TX Interrupts */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_RX | FMPSMBUS_IT_TX); - - /* Disable ADDR Interrupt */ - FMPSMBUS_Disable_IRQ(hfmpsmbus, FMPSMBUS_IT_ADDR); - - /* Disable Address Acknowledge */ - hfmpsmbus->Instance->CR2 |= FMPI2C_CR2_NACK; - - /* Clear Configuration Register 2 */ - FMPSMBUS_RESET_CR2(hfmpsmbus); - - /* Clear STOP Flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_STOPF); - - /* Clear ADDR flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ADDR); - - hfmpsmbus->XferOptions = 0; - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->ListenCpltCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_ListenCpltCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } - } - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - return HAL_OK; -} -/** - * @brief Manage the enabling of Interrupts. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param InterruptRequest Value of @ref FMPSMBUS_Interrupt_configuration_definition. - * @retval HAL status - */ -static void FMPSMBUS_Enable_IRQ(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t InterruptRequest) -{ - uint32_t tmpisr = 0UL; - - if ((InterruptRequest & FMPSMBUS_IT_ALERT) == FMPSMBUS_IT_ALERT) - { - /* Enable ERR interrupt */ - tmpisr |= FMPSMBUS_IT_ERRI; - } - - if ((InterruptRequest & FMPSMBUS_IT_ADDR) == FMPSMBUS_IT_ADDR) - { - /* Enable ADDR, STOP interrupt */ - tmpisr |= FMPSMBUS_IT_ADDRI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI | FMPSMBUS_IT_ERRI; - } - - if ((InterruptRequest & FMPSMBUS_IT_TX) == FMPSMBUS_IT_TX) - { - /* Enable ERR, TC, STOP, NACK, RXI interrupt */ - tmpisr |= FMPSMBUS_IT_ERRI | FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI | FMPSMBUS_IT_TXI; - } - - if ((InterruptRequest & FMPSMBUS_IT_RX) == FMPSMBUS_IT_RX) - { - /* Enable ERR, TC, STOP, NACK, TXI interrupt */ - tmpisr |= FMPSMBUS_IT_ERRI | FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI | FMPSMBUS_IT_RXI; - } - - /* Enable interrupts only at the end */ - /* to avoid the risk of FMPSMBUS interrupt handle execution before */ - /* all interrupts requested done */ - __HAL_FMPSMBUS_ENABLE_IT(hfmpsmbus, tmpisr); -} -/** - * @brief Manage the disabling of Interrupts. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param InterruptRequest Value of @ref FMPSMBUS_Interrupt_configuration_definition. - * @retval HAL status - */ -static void FMPSMBUS_Disable_IRQ(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t InterruptRequest) -{ - uint32_t tmpisr = 0UL; - uint32_t tmpstate = hfmpsmbus->State; - - if ((tmpstate == HAL_FMPSMBUS_STATE_READY) && ((InterruptRequest & FMPSMBUS_IT_ALERT) == FMPSMBUS_IT_ALERT)) - { - /* Disable ERR interrupt */ - tmpisr |= FMPSMBUS_IT_ERRI; - } - - if ((InterruptRequest & FMPSMBUS_IT_TX) == FMPSMBUS_IT_TX) - { - /* Disable TC, STOP, NACK and TXI interrupt */ - tmpisr |= FMPSMBUS_IT_TCI | FMPSMBUS_IT_TXI; - - if ((FMPSMBUS_GET_ALERT_ENABLED(hfmpsmbus) == 0UL) - && ((tmpstate & HAL_FMPSMBUS_STATE_LISTEN) != HAL_FMPSMBUS_STATE_LISTEN)) - { - /* Disable ERR interrupt */ - tmpisr |= FMPSMBUS_IT_ERRI; - } - - if ((tmpstate & HAL_FMPSMBUS_STATE_LISTEN) != HAL_FMPSMBUS_STATE_LISTEN) - { - /* Disable STOP and NACK interrupt */ - tmpisr |= FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI; - } - } - - if ((InterruptRequest & FMPSMBUS_IT_RX) == FMPSMBUS_IT_RX) - { - /* Disable TC, STOP, NACK and RXI interrupt */ - tmpisr |= FMPSMBUS_IT_TCI | FMPSMBUS_IT_RXI; - - if ((FMPSMBUS_GET_ALERT_ENABLED(hfmpsmbus) == 0UL) - && ((tmpstate & HAL_FMPSMBUS_STATE_LISTEN) != HAL_FMPSMBUS_STATE_LISTEN)) - { - /* Disable ERR interrupt */ - tmpisr |= FMPSMBUS_IT_ERRI; - } - - if ((tmpstate & HAL_FMPSMBUS_STATE_LISTEN) != HAL_FMPSMBUS_STATE_LISTEN) - { - /* Disable STOP and NACK interrupt */ - tmpisr |= FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI; - } - } - - if ((InterruptRequest & FMPSMBUS_IT_ADDR) == FMPSMBUS_IT_ADDR) - { - /* Disable ADDR, STOP and NACK interrupt */ - tmpisr |= FMPSMBUS_IT_ADDRI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI; - - if (FMPSMBUS_GET_ALERT_ENABLED(hfmpsmbus) == 0UL) - { - /* Disable ERR interrupt */ - tmpisr |= FMPSMBUS_IT_ERRI; - } - } - - /* Disable interrupts only at the end */ - /* to avoid a breaking situation like at "t" time */ - /* all disable interrupts request are not done */ - __HAL_FMPSMBUS_DISABLE_IT(hfmpsmbus, tmpisr); -} - -/** - * @brief FMPSMBUS interrupts error handler. - * @param hfmpsmbus FMPSMBUS handle. - * @retval None - */ -static void FMPSMBUS_ITErrorHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - uint32_t itflags = READ_REG(hfmpsmbus->Instance->ISR); - uint32_t itsources = READ_REG(hfmpsmbus->Instance->CR1); - uint32_t tmpstate; - uint32_t tmperror; - - /* FMPSMBUS Bus error interrupt occurred ------------------------------------*/ - if (((itflags & FMPSMBUS_FLAG_BERR) == FMPSMBUS_FLAG_BERR) && \ - ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) - { - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_BERR; - - /* Clear BERR flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_BERR); - } - - /* FMPSMBUS Over-Run/Under-Run interrupt occurred ----------------------------------------*/ - if (((itflags & FMPSMBUS_FLAG_OVR) == FMPSMBUS_FLAG_OVR) && \ - ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) - { - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_OVR; - - /* Clear OVR flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_OVR); - } - - /* FMPSMBUS Arbitration Loss error interrupt occurred ------------------------------------*/ - if (((itflags & FMPSMBUS_FLAG_ARLO) == FMPSMBUS_FLAG_ARLO) && \ - ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) - { - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_ARLO; - - /* Clear ARLO flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ARLO); - } - - /* FMPSMBUS Timeout error interrupt occurred ---------------------------------------------*/ - if (((itflags & FMPSMBUS_FLAG_TIMEOUT) == FMPSMBUS_FLAG_TIMEOUT) && \ - ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) - { - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_BUSTIMEOUT; - - /* Clear TIMEOUT flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_TIMEOUT); - } - - /* FMPSMBUS Alert error interrupt occurred -----------------------------------------------*/ - if (((itflags & FMPSMBUS_FLAG_ALERT) == FMPSMBUS_FLAG_ALERT) && \ - ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) - { - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_ALERT; - - /* Clear ALERT flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_ALERT); - } - - /* FMPSMBUS Packet Error Check error interrupt occurred ----------------------------------*/ - if (((itflags & FMPSMBUS_FLAG_PECERR) == FMPSMBUS_FLAG_PECERR) && \ - ((itsources & FMPSMBUS_IT_ERRI) == FMPSMBUS_IT_ERRI)) - { - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_PECERR; - - /* Clear PEC error flag */ - __HAL_FMPSMBUS_CLEAR_FLAG(hfmpsmbus, FMPSMBUS_FLAG_PECERR); - } - - /* Store current volatile hfmpsmbus->State, misra rule */ - tmperror = hfmpsmbus->ErrorCode; - - /* Call the Error Callback in case of Error detected */ - if ((tmperror != HAL_FMPSMBUS_ERROR_NONE) && (tmperror != HAL_FMPSMBUS_ERROR_ACKF)) - { - /* Do not Reset the HAL state in case of ALERT error */ - if ((tmperror & HAL_FMPSMBUS_ERROR_ALERT) != HAL_FMPSMBUS_ERROR_ALERT) - { - /* Store current volatile hfmpsmbus->State, misra rule */ - tmpstate = hfmpsmbus->State; - - if (((tmpstate & HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX) - || ((tmpstate & HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX) == HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX)) - { - /* Reset only HAL_FMPSMBUS_STATE_SLAVE_BUSY_XX */ - /* keep HAL_FMPSMBUS_STATE_LISTEN if set */ - hfmpsmbus->PreviousState = HAL_FMPSMBUS_STATE_READY; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_LISTEN; - } - } - - /* Call the Error callback to inform upper layer */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - hfmpsmbus->ErrorCallback(hfmpsmbus); -#else - HAL_FMPSMBUS_ErrorCallback(hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Handle FMPSMBUS Communication Timeout. - * @param hfmpsmbus Pointer to a FMPSMBUS_HandleTypeDef structure that contains - * the configuration information for the specified FMPSMBUS. - * @param Flag Specifies the FMPSMBUS flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Timeout Timeout duration - * @retval HAL status - */ -static HAL_StatusTypeDef FMPSMBUS_WaitOnFlagUntilTimeout(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t Flag, - FlagStatus Status, uint32_t Timeout) -{ - uint32_t tickstart = HAL_GetTick(); - - /* Wait until flag is set */ - while ((FlagStatus)(__HAL_FMPSMBUS_GET_FLAG(hfmpsmbus, Flag)) == Status) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0UL)) - { - hfmpsmbus->PreviousState = hfmpsmbus->State; - hfmpsmbus->State = HAL_FMPSMBUS_STATE_READY; - - /* Update FMPSMBUS error code */ - hfmpsmbus->ErrorCode |= HAL_FMPSMBUS_ERROR_HALTIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hfmpsmbus); - - return HAL_ERROR; - } - } - } - - return HAL_OK; -} - -/** - * @brief Handle FMPSMBUSx communication when starting transfer or during transfer (TC or TCR flag are set). - * @param hfmpsmbus FMPSMBUS handle. - * @param DevAddress specifies the slave address to be programmed. - * @param Size specifies the number of bytes to be programmed. - * This parameter must be a value between 0 and 255. - * @param Mode New state of the FMPSMBUS START condition generation. - * This parameter can be one or a combination of the following values: - * @arg @ref FMPSMBUS_RELOAD_MODE Enable Reload mode. - * @arg @ref FMPSMBUS_AUTOEND_MODE Enable Automatic end mode. - * @arg @ref FMPSMBUS_SOFTEND_MODE Enable Software end mode and Reload mode. - * @arg @ref FMPSMBUS_SENDPEC_MODE Enable Packet Error Calculation mode. - * @param Request New state of the FMPSMBUS START condition generation. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_NO_STARTSTOP Don't Generate stop and start condition. - * @arg @ref FMPSMBUS_GENERATE_STOP Generate stop condition (Size should be set to 0). - * @arg @ref FMPSMBUS_GENERATE_START_READ Generate Restart for read request. - * @arg @ref FMPSMBUS_GENERATE_START_WRITE Generate Restart for write request. - * @retval None - */ -static void FMPSMBUS_TransferConfig(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint8_t Size, - uint32_t Mode, uint32_t Request) -{ - /* Check the parameters */ - assert_param(IS_FMPSMBUS_ALL_INSTANCE(hfmpsmbus->Instance)); - assert_param(IS_FMPSMBUS_TRANSFER_MODE(Mode)); - assert_param(IS_FMPSMBUS_TRANSFER_REQUEST(Request)); - - /* update CR2 register */ - MODIFY_REG(hfmpsmbus->Instance->CR2, - ((FMPI2C_CR2_SADD | FMPI2C_CR2_NBYTES | FMPI2C_CR2_RELOAD | FMPI2C_CR2_AUTOEND | \ - (FMPI2C_CR2_RD_WRN & (uint32_t)(Request >> (31UL - FMPI2C_CR2_RD_WRN_Pos))) | \ - FMPI2C_CR2_START | FMPI2C_CR2_STOP | FMPI2C_CR2_PECBYTE)), \ - (uint32_t)(((uint32_t)DevAddress & FMPI2C_CR2_SADD) | \ - (((uint32_t)Size << FMPI2C_CR2_NBYTES_Pos) & FMPI2C_CR2_NBYTES) | \ - (uint32_t)Mode | (uint32_t)Request)); -} - -/** - * @brief Convert FMPSMBUSx OTHER_xxx XferOptions to functional XferOptions. - * @param hfmpsmbus FMPSMBUS handle. - * @retval None - */ -static void FMPSMBUS_ConvertOtherXferOptions(FMPSMBUS_HandleTypeDef *hfmpsmbus) -{ - /* if user set XferOptions to FMPSMBUS_OTHER_FRAME_NO_PEC */ - /* it request implicitly to generate a restart condition */ - /* set XferOptions to FMPSMBUS_FIRST_FRAME */ - if (hfmpsmbus->XferOptions == FMPSMBUS_OTHER_FRAME_NO_PEC) - { - hfmpsmbus->XferOptions = FMPSMBUS_FIRST_FRAME; - } - /* else if user set XferOptions to FMPSMBUS_OTHER_FRAME_WITH_PEC */ - /* it request implicitly to generate a restart condition */ - /* set XferOptions to FMPSMBUS_FIRST_FRAME | FMPSMBUS_SENDPEC_MODE */ - else if (hfmpsmbus->XferOptions == FMPSMBUS_OTHER_FRAME_WITH_PEC) - { - hfmpsmbus->XferOptions = FMPSMBUS_FIRST_FRAME | FMPSMBUS_SENDPEC_MODE; - } - /* else if user set XferOptions to FMPSMBUS_OTHER_AND_LAST_FRAME_NO_PEC */ - /* it request implicitly to generate a restart condition */ - /* then generate a stop condition at the end of transfer */ - /* set XferOptions to FMPSMBUS_FIRST_AND_LAST_FRAME_NO_PEC */ - else if (hfmpsmbus->XferOptions == FMPSMBUS_OTHER_AND_LAST_FRAME_NO_PEC) - { - hfmpsmbus->XferOptions = FMPSMBUS_FIRST_AND_LAST_FRAME_NO_PEC; - } - /* else if user set XferOptions to FMPSMBUS_OTHER_AND_LAST_FRAME_WITH_PEC */ - /* it request implicitly to generate a restart condition */ - /* then generate a stop condition at the end of transfer */ - /* set XferOptions to FMPSMBUS_FIRST_AND_LAST_FRAME_WITH_PEC */ - else if (hfmpsmbus->XferOptions == FMPSMBUS_OTHER_AND_LAST_FRAME_WITH_PEC) - { - hfmpsmbus->XferOptions = FMPSMBUS_FIRST_AND_LAST_FRAME_WITH_PEC; - } - else - { - /* Nothing to do */ - } -} -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#endif /* HAL_FMPSMBUS_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus_ex.c deleted file mode 100644 index e5147ca66aaae80..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_fmpsmbus_ex.c +++ /dev/null @@ -1,148 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpsmbus_ex.c - * @author MCD Application Team - * @brief FMPSMBUS Extended HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of FMPSMBUS Extended peripheral: - * + Extended features functions - * - @verbatim - ============================================================================== - ##### FMPSMBUS peripheral Extended features ##### - ============================================================================== - - [..] Comparing to other previous devices, the FMPSMBUS interface for STM32F4xx - devices contains the following additional features - - (+) Disable or enable Fast Mode Plus - - ##### How to use this driver ##### - ============================================================================== - (#) Configure the enable or disable of fast mode plus driving capability using the functions : - (++) HAL_FMPSMBUSEx_EnableFastModePlus() - (++) HAL_FMPSMBUSEx_DisableFastModePlus() - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FMPSMBUSEx FMPSMBUSEx - * @brief FMPSMBUS Extended HAL module driver - * @{ - */ - -#ifdef HAL_FMPSMBUS_MODULE_ENABLED -#if defined(FMPI2C_CR1_PE) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup FMPSMBUSEx_Exported_Functions FMPSMBUS Extended Exported Functions - * @{ - */ - -/** @defgroup FMPSMBUSEx_Exported_Functions_Group3 Fast Mode Plus Functions - * @brief Fast Mode Plus Functions - * -@verbatim - =============================================================================== - ##### Fast Mode Plus Functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure Fast Mode Plus - -@endverbatim - * @{ - */ - -/** - * @brief Enable the FMPSMBUS fast mode plus driving capability. - * @param ConfigFastModePlus Selects the pin. - * This parameter can be one of the @ref FMPSMBUSEx_FastModePlus values - * @note For FMPI2C1, fast mode plus driving capability can be enabled on all selected - * FMPI2C1 pins using FMPSMBUS_FASTMODEPLUS_FMPI2C1 parameter or independently - * on each one of the following pins PB6, PB7, PB8 and PB9. - * @note For remaining FMPI2C1 pins (PA14, PA15...) fast mode plus driving capability - * can be enabled only by using FMPSMBUS_FASTMODEPLUS_FMPI2C1 parameter. - * @retval None - */ -void HAL_FMPSMBUSEx_EnableFastModePlus(uint32_t ConfigFastModePlus) -{ - /* Check the parameter */ - assert_param(IS_FMPSMBUS_FASTMODEPLUS(ConfigFastModePlus)); - - /* Enable SYSCFG clock */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - - /* Enable fast mode plus driving capability for selected pin */ - SET_BIT(SYSCFG->CFGR, (uint32_t)ConfigFastModePlus); -} - -/** - * @brief Disable the FMPSMBUS fast mode plus driving capability. - * @param ConfigFastModePlus Selects the pin. - * This parameter can be one of the @ref FMPSMBUSEx_FastModePlus values - * @note For FMPI2C1, fast mode plus driving capability can be disabled on all selected - * FMPI2C1 pins using FMPSMBUS_FASTMODEPLUS_FMPI2C1 parameter or independently - * on each one of the following pins PB6, PB7, PB8 and PB9. - * @note For remaining FMPI2C1 pins (PA14, PA15...) fast mode plus driving capability - * can be disabled only by using FMPSMBUS_FASTMODEPLUS_FMPI2C1 parameter. - * @retval None - */ -void HAL_FMPSMBUSEx_DisableFastModePlus(uint32_t ConfigFastModePlus) -{ - /* Check the parameter */ - assert_param(IS_FMPSMBUS_FASTMODEPLUS(ConfigFastModePlus)); - - /* Enable SYSCFG clock */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - - /* Disable fast mode plus driving capability for selected pin */ - CLEAR_BIT(SYSCFG->CFGR, (uint32_t)ConfigFastModePlus); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#endif /* HAL_FMPSMBUS_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c deleted file mode 100644 index 47203391fcfff18..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c +++ /dev/null @@ -1,534 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio.c - * @author MCD Application Team - * @brief GPIO HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the General Purpose Input/Output (GPIO) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * - @verbatim - ============================================================================== - ##### GPIO Peripheral features ##### - ============================================================================== - [..] - Subject to the specific hardware characteristics of each I/O port listed in the datasheet, each - port bit of the General Purpose IO (GPIO) Ports, can be individually configured by software - in several modes: - (+) Input mode - (+) Analog mode - (+) Output mode - (+) Alternate function mode - (+) External interrupt/event lines - - [..] - During and just after reset, the alternate functions and external interrupt - lines are not active and the I/O ports are configured in input floating mode. - - [..] - All GPIO pins have weak internal pull-up and pull-down resistors, which can be - activated or not. - - [..] - In Output or Alternate mode, each IO can be configured on open-drain or push-pull - type and the IO speed can be selected depending on the VDD value. - - [..] - All ports have external interrupt/event capability. To use external interrupt - lines, the port must be configured in input mode. All available GPIO pins are - connected to the 16 external interrupt/event lines from EXTI0 to EXTI15. - - [..] - The external interrupt/event controller consists of up to 23 edge detectors - (16 lines are connected to GPIO) for generating event/interrupt requests (each - input line can be independently configured to select the type (interrupt or event) - and the corresponding trigger event (rising or falling or both). Each line can - also be masked independently. - - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Enable the GPIO AHB clock using the following function: __HAL_RCC_GPIOx_CLK_ENABLE(). - - (#) Configure the GPIO pin(s) using HAL_GPIO_Init(). - (++) Configure the IO mode using "Mode" member from GPIO_InitTypeDef structure - (++) Activate Pull-up, Pull-down resistor using "Pull" member from GPIO_InitTypeDef - structure. - (++) In case of Output or alternate function mode selection: the speed is - configured through "Speed" member from GPIO_InitTypeDef structure. - (++) In alternate mode is selection, the alternate function connected to the IO - is configured through "Alternate" member from GPIO_InitTypeDef structure. - (++) Analog mode is required when a pin is to be used as ADC channel - or DAC output. - (++) In case of external interrupt/event selection the "Mode" member from - GPIO_InitTypeDef structure select the type (interrupt or event) and - the corresponding trigger event (rising or falling or both). - - (#) In case of external interrupt/event mode selection, configure NVIC IRQ priority - mapped to the EXTI line using HAL_NVIC_SetPriority() and enable it using - HAL_NVIC_EnableIRQ(). - - (#) To get the level of a pin configured in input mode use HAL_GPIO_ReadPin(). - - (#) To set/reset the level of a pin configured in output mode use - HAL_GPIO_WritePin()/HAL_GPIO_TogglePin(). - - (#) To lock pin configuration until next reset use HAL_GPIO_LockPin(). - - - (#) During and just after reset, the alternate functions are not - active and the GPIO pins are configured in input floating mode (except JTAG - pins). - - (#) The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as general purpose - (PC14 and PC15, respectively) when the LSE oscillator is off. The LSE has - priority over the GPIO function. - - (#) The HSE oscillator pins OSC_IN/OSC_OUT can be used as - general purpose PH0 and PH1, respectively, when the HSE oscillator is off. - The HSE has priority over the GPIO function. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIO GPIO - * @brief GPIO HAL module driver - * @{ - */ - -#ifdef HAL_GPIO_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup GPIO_Private_Constants GPIO Private Constants - * @{ - */ - -#define GPIO_NUMBER 16U -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIO_Exported_Functions GPIO Exported Functions - * @{ - */ - -/** @defgroup GPIO_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] - This section provides functions allowing to initialize and de-initialize the GPIOs - to be ready for use. - -@endverbatim - * @{ - */ - - -/** - * @brief Initializes the GPIOx peripheral according to the specified parameters in the GPIO_Init. - * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Init pointer to a GPIO_InitTypeDef structure that contains - * the configuration information for the specified GPIO peripheral. - * @retval None - */ -void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init) -{ - uint32_t position; - uint32_t ioposition = 0x00U; - uint32_t iocurrent = 0x00U; - uint32_t temp = 0x00U; - - /* Check the parameters */ - assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); - assert_param(IS_GPIO_PIN(GPIO_Init->Pin)); - assert_param(IS_GPIO_MODE(GPIO_Init->Mode)); - - /* Configure the port pins */ - for(position = 0U; position < GPIO_NUMBER; position++) - { - /* Get the IO position */ - ioposition = 0x01U << position; - /* Get the current IO position */ - iocurrent = (uint32_t)(GPIO_Init->Pin) & ioposition; - - if(iocurrent == ioposition) - { - /*--------------------- GPIO Mode Configuration ------------------------*/ - /* In case of Output or Alternate function mode selection */ - if(((GPIO_Init->Mode & GPIO_MODE) == MODE_OUTPUT) || \ - (GPIO_Init->Mode & GPIO_MODE) == MODE_AF) - { - /* Check the Speed parameter */ - assert_param(IS_GPIO_SPEED(GPIO_Init->Speed)); - /* Configure the IO Speed */ - temp = GPIOx->OSPEEDR; - temp &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2U)); - temp |= (GPIO_Init->Speed << (position * 2U)); - GPIOx->OSPEEDR = temp; - - /* Configure the IO Output Type */ - temp = GPIOx->OTYPER; - temp &= ~(GPIO_OTYPER_OT_0 << position) ; - temp |= (((GPIO_Init->Mode & OUTPUT_TYPE) >> OUTPUT_TYPE_Pos) << position); - GPIOx->OTYPER = temp; - } - - if((GPIO_Init->Mode & GPIO_MODE) != MODE_ANALOG) - { - /* Check the parameters */ - assert_param(IS_GPIO_PULL(GPIO_Init->Pull)); - - /* Activate the Pull-up or Pull down resistor for the current IO */ - temp = GPIOx->PUPDR; - temp &= ~(GPIO_PUPDR_PUPDR0 << (position * 2U)); - temp |= ((GPIO_Init->Pull) << (position * 2U)); - GPIOx->PUPDR = temp; - } - - /* In case of Alternate function mode selection */ - if((GPIO_Init->Mode & GPIO_MODE) == MODE_AF) - { - /* Check the Alternate function parameter */ - assert_param(IS_GPIO_AF(GPIO_Init->Alternate)); - /* Configure Alternate function mapped with the current IO */ - temp = GPIOx->AFR[position >> 3U]; - temp &= ~(0xFU << ((uint32_t)(position & 0x07U) * 4U)) ; - temp |= ((uint32_t)(GPIO_Init->Alternate) << (((uint32_t)position & 0x07U) * 4U)); - GPIOx->AFR[position >> 3U] = temp; - } - - /* Configure IO Direction mode (Input, Output, Alternate or Analog) */ - temp = GPIOx->MODER; - temp &= ~(GPIO_MODER_MODER0 << (position * 2U)); - temp |= ((GPIO_Init->Mode & GPIO_MODE) << (position * 2U)); - GPIOx->MODER = temp; - - /*--------------------- EXTI Mode Configuration ------------------------*/ - /* Configure the External Interrupt or event for the current IO */ - if((GPIO_Init->Mode & EXTI_MODE) != 0x00U) - { - /* Enable SYSCFG Clock */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - - temp = SYSCFG->EXTICR[position >> 2U]; - temp &= ~(0x0FU << (4U * (position & 0x03U))); - temp |= ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4U * (position & 0x03U))); - SYSCFG->EXTICR[position >> 2U] = temp; - - /* Clear EXTI line configuration */ - temp = EXTI->IMR; - temp &= ~((uint32_t)iocurrent); - if((GPIO_Init->Mode & EXTI_IT) != 0x00U) - { - temp |= iocurrent; - } - EXTI->IMR = temp; - - temp = EXTI->EMR; - temp &= ~((uint32_t)iocurrent); - if((GPIO_Init->Mode & EXTI_EVT) != 0x00U) - { - temp |= iocurrent; - } - EXTI->EMR = temp; - - /* Clear Rising Falling edge configuration */ - temp = EXTI->RTSR; - temp &= ~((uint32_t)iocurrent); - if((GPIO_Init->Mode & TRIGGER_RISING) != 0x00U) - { - temp |= iocurrent; - } - EXTI->RTSR = temp; - - temp = EXTI->FTSR; - temp &= ~((uint32_t)iocurrent); - if((GPIO_Init->Mode & TRIGGER_FALLING) != 0x00U) - { - temp |= iocurrent; - } - EXTI->FTSR = temp; - } - } - } -} - -/** - * @brief De-initializes the GPIOx peripheral registers to their default reset values. - * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Pin specifies the port bit to be written. - * This parameter can be one of GPIO_PIN_x where x can be (0..15). - * @retval None - */ -void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin) -{ - uint32_t position; - uint32_t ioposition = 0x00U; - uint32_t iocurrent = 0x00U; - uint32_t tmp = 0x00U; - - /* Check the parameters */ - assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); - - /* Configure the port pins */ - for(position = 0U; position < GPIO_NUMBER; position++) - { - /* Get the IO position */ - ioposition = 0x01U << position; - /* Get the current IO position */ - iocurrent = (GPIO_Pin) & ioposition; - - if(iocurrent == ioposition) - { - /*------------------------- EXTI Mode Configuration --------------------*/ - tmp = SYSCFG->EXTICR[position >> 2U]; - tmp &= (0x0FU << (4U * (position & 0x03U))); - if(tmp == ((uint32_t)(GPIO_GET_INDEX(GPIOx)) << (4U * (position & 0x03U)))) - { - /* Clear EXTI line configuration */ - EXTI->IMR &= ~((uint32_t)iocurrent); - EXTI->EMR &= ~((uint32_t)iocurrent); - - /* Clear Rising Falling edge configuration */ - EXTI->RTSR &= ~((uint32_t)iocurrent); - EXTI->FTSR &= ~((uint32_t)iocurrent); - - /* Configure the External Interrupt or event for the current IO */ - tmp = 0x0FU << (4U * (position & 0x03U)); - SYSCFG->EXTICR[position >> 2U] &= ~tmp; - } - - /*------------------------- GPIO Mode Configuration --------------------*/ - /* Configure IO Direction in Input Floating Mode */ - GPIOx->MODER &= ~(GPIO_MODER_MODER0 << (position * 2U)); - - /* Configure the default Alternate Function in current IO */ - GPIOx->AFR[position >> 3U] &= ~(0xFU << ((uint32_t)(position & 0x07U) * 4U)) ; - - /* Deactivate the Pull-up and Pull-down resistor for the current IO */ - GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << (position * 2U)); - - /* Configure the default value IO Output Type */ - GPIOx->OTYPER &= ~(GPIO_OTYPER_OT_0 << position) ; - - /* Configure the default value for IO Speed */ - GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (position * 2U)); - } - } -} - -/** - * @} - */ - -/** @defgroup GPIO_Exported_Functions_Group2 IO operation functions - * @brief GPIO Read and Write - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - -@endverbatim - * @{ - */ - -/** - * @brief Reads the specified input port pin. - * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Pin specifies the port bit to read. - * This parameter can be GPIO_PIN_x where x can be (0..15). - * @retval The input port pin value. - */ -GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - GPIO_PinState bitstatus; - - /* Check the parameters */ - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - if((GPIOx->IDR & GPIO_Pin) != (uint32_t)GPIO_PIN_RESET) - { - bitstatus = GPIO_PIN_SET; - } - else - { - bitstatus = GPIO_PIN_RESET; - } - return bitstatus; -} - -/** - * @brief Sets or clears the selected data port bit. - * - * @note This function uses GPIOx_BSRR register to allow atomic read/modify - * accesses. In this way, there is no risk of an IRQ occurring between - * the read and the modify access. - * - * @param GPIOx where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Pin specifies the port bit to be written. - * This parameter can be one of GPIO_PIN_x where x can be (0..15). - * @param PinState specifies the value to be written to the selected bit. - * This parameter can be one of the GPIO_PinState enum values: - * @arg GPIO_PIN_RESET: to clear the port pin - * @arg GPIO_PIN_SET: to set the port pin - * @retval None - */ -void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState) -{ - /* Check the parameters */ - assert_param(IS_GPIO_PIN(GPIO_Pin)); - assert_param(IS_GPIO_PIN_ACTION(PinState)); - - if(PinState != GPIO_PIN_RESET) - { - GPIOx->BSRR = GPIO_Pin; - } - else - { - GPIOx->BSRR = (uint32_t)GPIO_Pin << 16U; - } -} - -/** - * @brief Toggles the specified GPIO pins. - * @param GPIOx Where x can be (A..K) to select the GPIO peripheral for STM32F429X device or - * x can be (A..I) to select the GPIO peripheral for STM32F40XX and STM32F427X devices. - * @param GPIO_Pin Specifies the pins to be toggled. - * @retval None - */ -void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - uint32_t odr; - - /* Check the parameters */ - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - /* get current Ouput Data Register value */ - odr = GPIOx->ODR; - - /* Set selected pins that were at low level, and reset ones that were high */ - GPIOx->BSRR = ((odr & GPIO_Pin) << GPIO_NUMBER) | (~odr & GPIO_Pin); -} - -/** - * @brief Locks GPIO Pins configuration registers. - * @note The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR, - * GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH. - * @note The configuration of the locked GPIO pins can no longer be modified - * until the next reset. - * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F4 family - * @param GPIO_Pin specifies the port bit to be locked. - * This parameter can be any combination of GPIO_PIN_x where x can be (0..15). - * @retval None - */ -HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - __IO uint32_t tmp = GPIO_LCKR_LCKK; - - /* Check the parameters */ - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - /* Apply lock key write sequence */ - tmp |= GPIO_Pin; - /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */ - GPIOx->LCKR = tmp; - /* Reset LCKx bit(s): LCKK='0' + LCK[15-0] */ - GPIOx->LCKR = GPIO_Pin; - /* Set LCKx bit(s): LCKK='1' + LCK[15-0] */ - GPIOx->LCKR = tmp; - /* Read LCKR register. This read is mandatory to complete key lock sequence */ - tmp = GPIOx->LCKR; - - /* Read again in order to confirm lock is active */ - if((GPIOx->LCKR & GPIO_LCKR_LCKK) != RESET) - { - return HAL_OK; - } - else - { - return HAL_ERROR; - } -} - -/** - * @brief This function handles EXTI interrupt request. - * @param GPIO_Pin Specifies the pins connected EXTI line - * @retval None - */ -void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin) -{ - /* EXTI line interrupt detected */ - if(__HAL_GPIO_EXTI_GET_IT(GPIO_Pin) != RESET) - { - __HAL_GPIO_EXTI_CLEAR_IT(GPIO_Pin); - HAL_GPIO_EXTI_Callback(GPIO_Pin); - } -} - -/** - * @brief EXTI line detection callbacks. - * @param GPIO_Pin Specifies the pins connected EXTI line - * @retval None - */ -__weak void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(GPIO_Pin); - /* NOTE: This function Should not be modified, when the callback is needed, - the HAL_GPIO_EXTI_Callback could be implemented in the user file - */ -} - -/** - * @} - */ - - -/** - * @} - */ - -#endif /* HAL_GPIO_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash.c deleted file mode 100644 index c901e19d61f4490..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash.c +++ /dev/null @@ -1,3518 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hash.c - * @author MCD Application Team - * @brief HASH HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the HASH peripheral: - * + Initialization and de-initialization methods - * + HASH or HMAC processing in polling mode - * + HASH or HMAC processing in interrupt mode - * + HASH or HMAC processing in DMA mode - * + Peripheral State methods - * + HASH or HMAC processing suspension/resumption - * - @verbatim - =============================================================================== - ##### How to use this driver ##### - =============================================================================== - [..] - The HASH HAL driver can be used as follows: - - (#)Initialize the HASH low level resources by implementing the HAL_HASH_MspInit(): - (##) Enable the HASH interface clock using __HASH_CLK_ENABLE() - (##) When resorting to interrupt-based APIs (e.g. HAL_HASH_xxx_Start_IT()) - (+++) Configure the HASH interrupt priority using HAL_NVIC_SetPriority() - (+++) Enable the HASH IRQ handler using HAL_NVIC_EnableIRQ() - (+++) In HASH IRQ handler, call HAL_HASH_IRQHandler() API - (##) When resorting to DMA-based APIs (e.g. HAL_HASH_xxx_Start_DMA()) - (+++) Enable the DMAx interface clock using - __DMAx_CLK_ENABLE() - (+++) Configure and enable one DMA stream to manage data transfer from - memory to peripheral (input stream). Managing data transfer from - peripheral to memory can be performed only using CPU. - (+++) Associate the initialized DMA handle to the HASH DMA handle - using __HAL_LINKDMA() - (+++) Configure the priority and enable the NVIC for the transfer complete - interrupt on the DMA stream: use - HAL_NVIC_SetPriority() and - HAL_NVIC_EnableIRQ() - - (#)Initialize the HASH HAL using HAL_HASH_Init(). This function: - (##) resorts to HAL_HASH_MspInit() for low-level initialization, - (##) configures the data type: 1-bit, 8-bit, 16-bit or 32-bit. - - (#)Three processing schemes are available: - (##) Polling mode: processing APIs are blocking functions - i.e. they process the data and wait till the digest computation is finished, - e.g. HAL_HASH_xxx_Start() for HASH or HAL_HMAC_xxx_Start() for HMAC - (##) Interrupt mode: processing APIs are not blocking functions - i.e. they process the data under interrupt, - e.g. HAL_HASH_xxx_Start_IT() for HASH or HAL_HMAC_xxx_Start_IT() for HMAC - (##) DMA mode: processing APIs are not blocking functions and the CPU is - not used for data transfer i.e. the data transfer is ensured by DMA, - e.g. HAL_HASH_xxx_Start_DMA() for HASH or HAL_HMAC_xxx_Start_DMA() - for HMAC. Note that in DMA mode, a call to HAL_HASH_xxx_Finish() - is then required to retrieve the digest. - - (#)When the processing function is called after HAL_HASH_Init(), the HASH peripheral is - initialized and processes the buffer fed in input. When the input data have all been - fed to the Peripheral, the digest computation can start. - - (#)Multi-buffer processing is possible in polling, interrupt and DMA modes. - (##) In polling mode, only multi-buffer HASH processing is possible. - API HAL_HASH_xxx_Accumulate() must be called for each input buffer, except for the last one. - User must resort to HAL_HASH_xxx_Accumulate_End() to enter the last one and retrieve as - well the computed digest. - - (##) In interrupt mode, API HAL_HASH_xxx_Accumulate_IT() must be called for each input buffer, - except for the last one. - User must resort to HAL_HASH_xxx_Accumulate_End_IT() to enter the last one and retrieve as - well the computed digest. - - (##) In DMA mode, multi-buffer HASH and HMAC processing are possible. - (+++) HASH processing: once initialization is done, MDMAT bit must be set - through __HAL_HASH_SET_MDMAT() macro. - From that point, each buffer can be fed to the Peripheral through HAL_HASH_xxx_Start_DMA() API. - Before entering the last buffer, reset the MDMAT bit with __HAL_HASH_RESET_MDMAT() - macro then wrap-up the HASH processing in feeding the last input buffer through the - same API HAL_HASH_xxx_Start_DMA(). The digest can then be retrieved with a call to - API HAL_HASH_xxx_Finish(). - (+++) HMAC processing (requires to resort to extended functions): - after initialization, the key and the first input buffer are entered - in the Peripheral with the API HAL_HMACEx_xxx_Step1_2_DMA(). This carries out HMAC step 1 and - starts step 2. - The following buffers are next entered with the API HAL_HMACEx_xxx_Step2_DMA(). At this - point, the HMAC processing is still carrying out step 2. - Then, step 2 for the last input buffer and step 3 are carried out by a single call - to HAL_HMACEx_xxx_Step2_3_DMA(). - - The digest can finally be retrieved with a call to API HAL_HASH_xxx_Finish(). - - - (#)Context swapping. - (##) Two APIs are available to suspend HASH or HMAC processing: - (+++) HAL_HASH_SwFeed_ProcessSuspend() when data are entered by software (polling or IT mode), - (+++) HAL_HASH_DMAFeed_ProcessSuspend() when data are entered by DMA. - - (##) When HASH or HMAC processing is suspended, HAL_HASH_ContextSaving() allows - to save in memory the Peripheral context. This context can be restored afterwards - to resume the HASH processing thanks to HAL_HASH_ContextRestoring(). - - (##) Once the HASH Peripheral has been restored to the same configuration as that at suspension - time, processing can be restarted with the same API call (same API, same handle, - same parameters) as done before the suspension. Relevant parameters to restart at - the proper location are internally saved in the HASH handle. - - (#)Call HAL_HASH_DeInit() to deinitialize the HASH peripheral. - - *** Remarks on message length *** - =================================== - [..] - (#) HAL in interruption mode (interruptions driven) - - (##)Due to HASH peripheral hardware design, the peripheral interruption is triggered every 64 bytes. - This is why, for driver implementation simplicity’s sake, user is requested to enter a message the - length of which is a multiple of 4 bytes. - - (##) When the message length (in bytes) is not a multiple of words, a specific field exists in HASH_STR - to specify which bits to discard at the end of the complete message to process only the message bits - and not extra bits. - - (##) If user needs to perform a hash computation of a large input buffer that is spread around various places - in memory and where each piece of this input buffer is not necessarily a multiple of 4 bytes in size, it becomes - necessary to use a temporary buffer to format the data accordingly before feeding them to the Peripheral. - It is advised to the user to - (+++) achieve the first formatting operation by software then enter the data - (+++) while the Peripheral is processing the first input set, carry out the second formatting - operation by software, to be ready when DINIS occurs. - (+++) repeat step 2 until the whole message is processed. - - [..] - (#) HAL in DMA mode - - (##) Again, due to hardware design, the DMA transfer to feed the data can only be done on a word-basis. - The same field described above in HASH_STR is used to specify which bits to discard at the end of the - DMA transfer to process only the message bits and not extra bits. Due to hardware implementation, - this is possible only at the end of the complete message. When several DMA transfers are needed to - enter the message, this is not applicable at the end of the intermediary transfers. - - (##) Similarly to the interruption-driven mode, it is suggested to the user to format the consecutive - chunks of data by software while the DMA transfer and processing is on-going for the first parts of - the message. Due to the 32-bit alignment required for the DMA transfer, it is underlined that the - software formatting operation is more complex than in the IT mode. - - *** Callback registration *** - =================================== - [..] - (#) The compilation define USE_HAL_HASH_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use function @ref HAL_HASH_RegisterCallback() to register a user callback. - - (#) Function @ref HAL_HASH_RegisterCallback() allows to register following callbacks: - (+) InCpltCallback : callback for input completion. - (+) DgstCpltCallback : callback for digest computation completion. - (+) ErrorCallback : callback for error. - (+) MspInitCallback : HASH MspInit. - (+) MspDeInitCallback : HASH MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - (#) Use function @ref HAL_HASH_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - @ref HAL_HASH_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) InCpltCallback : callback for input completion. - (+) DgstCpltCallback : callback for digest computation completion. - (+) ErrorCallback : callback for error. - (+) MspInitCallback : HASH MspInit. - (+) MspDeInitCallback : HASH MspDeInit. - - (#) By default, after the @ref HAL_HASH_Init and if the state is HAL_HASH_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions: - examples @ref HAL_HASH_InCpltCallback(), @ref HAL_HASH_DgstCpltCallback() - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the @ref HAL_HASH_Init - and @ref HAL_HASH_DeInit only when these callbacks are null (not registered beforehand) - If not, MspInit or MspDeInit are not null, the @ref HAL_HASH_Init and @ref HAL_HASH_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_HASH_RegisterCallback before calling @ref HAL_HASH_DeInit - or @ref HAL_HASH_Init function. - - When The compilation define USE_HAL_HASH_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (HASH) - -/** @defgroup HASH HASH - * @brief HASH HAL module driver. - * @{ - */ - -#ifdef HAL_HASH_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup HASH_Private_Constants HASH Private Constants - * @{ - */ - -/** @defgroup HASH_Digest_Calculation_Status HASH Digest Calculation Status - * @{ - */ -#define HASH_DIGEST_CALCULATION_NOT_STARTED ((uint32_t)0x00000000U) /*!< DCAL not set after input data written in DIN register */ -#define HASH_DIGEST_CALCULATION_STARTED ((uint32_t)0x00000001U) /*!< DCAL set after input data written in DIN register */ -/** - * @} - */ - -/** @defgroup HASH_Number_Of_CSR_Registers HASH Number of Context Swap Registers - * @{ - */ -#define HASH_NUMBER_OF_CSR_REGISTERS 54U /*!< Number of Context Swap Registers */ -/** - * @} - */ - -/** @defgroup HASH_TimeOut_Value HASH TimeOut Value - * @{ - */ -#define HASH_TIMEOUTVALUE 1000U /*!< Time-out value */ -/** - * @} - */ - -/** @defgroup HASH_DMA_Suspension_Words_Limit HASH DMA suspension words limit - * @{ - */ -#define HASH_DMA_SUSPENSION_WORDS_LIMIT 20U /*!< Number of words below which DMA suspension is aborted */ -/** - * @} - */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup HASH_Private_Functions HASH Private Functions - * @{ - */ -static void HASH_DMAXferCplt(DMA_HandleTypeDef *hdma); -static void HASH_DMAError(DMA_HandleTypeDef *hdma); -static void HASH_GetDigest(uint8_t *pMsgDigest, uint8_t Size); -static HAL_StatusTypeDef HASH_WaitOnFlagUntilTimeout(HASH_HandleTypeDef *hhash, uint32_t Flag, FlagStatus Status, - uint32_t Timeout); -static HAL_StatusTypeDef HASH_WriteData(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -static HAL_StatusTypeDef HASH_IT(HASH_HandleTypeDef *hhash); -static uint32_t HASH_Write_Block_Data(HASH_HandleTypeDef *hhash); -static HAL_StatusTypeDef HMAC_Processing(HASH_HandleTypeDef *hhash, uint32_t Timeout); -/** - * @} - */ - -/** @defgroup HASH_Exported_Functions HASH Exported Functions - * @{ - */ - -/** @defgroup HASH_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization, configuration and call-back functions. - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize the HASH according to the specified parameters - in the HASH_InitTypeDef and create the associated handle - (+) DeInitialize the HASH peripheral - (+) Initialize the HASH MCU Specific Package (MSP) - (+) DeInitialize the HASH MSP - - [..] This section provides as well call back functions definitions for user - code to manage: - (+) Input data transfer to Peripheral completion - (+) Calculated digest retrieval completion - (+) Error management - - - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the HASH according to the specified parameters in the - HASH_HandleTypeDef and create the associated handle. - * @note Only MDMAT and DATATYPE bits of HASH Peripheral are set by HAL_HASH_Init(), - * other configuration bits are set by HASH or HMAC processing APIs. - * @note MDMAT bit is systematically reset by HAL_HASH_Init(). To set it for - * multi-buffer HASH processing, user needs to resort to - * __HAL_HASH_SET_MDMAT() macro. For HMAC multi-buffer processing, the - * relevant APIs manage themselves the MDMAT bit. - * @param hhash HASH handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_Init(HASH_HandleTypeDef *hhash) -{ - /* Check the hash handle allocation */ - if (hhash == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_HASH_DATATYPE(hhash->Init.DataType)); - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - if (hhash->State == HAL_HASH_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hhash->Lock = HAL_UNLOCKED; - - /* Reset Callback pointers in HAL_HASH_STATE_RESET only */ - hhash->InCpltCallback = HAL_HASH_InCpltCallback; /* Legacy weak (surcharged) input completion callback */ - hhash->DgstCpltCallback = HAL_HASH_DgstCpltCallback; /* Legacy weak (surcharged) digest computation - completion callback */ - hhash->ErrorCallback = HAL_HASH_ErrorCallback; /* Legacy weak (surcharged) error callback */ - if (hhash->MspInitCallback == NULL) - { - hhash->MspInitCallback = HAL_HASH_MspInit; - } - - /* Init the low level hardware */ - hhash->MspInitCallback(hhash); - } -#else - if (hhash->State == HAL_HASH_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hhash->Lock = HAL_UNLOCKED; - - /* Init the low level hardware */ - HAL_HASH_MspInit(hhash); - } -#endif /* (USE_HAL_HASH_REGISTER_CALLBACKS) */ - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Reset HashInCount, HashITCounter, HashBuffSize and NbWordsAlreadyPushed */ - hhash->HashInCount = 0; - hhash->HashBuffSize = 0; - hhash->HashITCounter = 0; - hhash->NbWordsAlreadyPushed = 0; - /* Reset digest calculation bridle (MDMAT bit control) */ - hhash->DigestCalculationDisable = RESET; - /* Set phase to READY */ - hhash->Phase = HAL_HASH_PHASE_READY; - /* Reset suspension request flag */ - hhash->SuspendRequest = HAL_HASH_SUSPEND_NONE; - - /* Set the data type bit */ - MODIFY_REG(HASH->CR, HASH_CR_DATATYPE, hhash->Init.DataType); -#if defined(HASH_CR_MDMAT) - /* Reset MDMAT bit */ - __HAL_HASH_RESET_MDMAT(); -#endif /* HASH_CR_MDMAT */ - /* Reset HASH handle status */ - hhash->Status = HAL_OK; - - /* Set the HASH state to Ready */ - hhash->State = HAL_HASH_STATE_READY; - - /* Initialise the error code */ - hhash->ErrorCode = HAL_HASH_ERROR_NONE; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief DeInitialize the HASH peripheral. - * @param hhash HASH handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_DeInit(HASH_HandleTypeDef *hhash) -{ - /* Check the HASH handle allocation */ - if (hhash == NULL) - { - return HAL_ERROR; - } - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Set the default HASH phase */ - hhash->Phase = HAL_HASH_PHASE_READY; - - /* Reset HashInCount, HashITCounter and HashBuffSize */ - hhash->HashInCount = 0; - hhash->HashBuffSize = 0; - hhash->HashITCounter = 0; - /* Reset digest calculation bridle (MDMAT bit control) */ - hhash->DigestCalculationDisable = RESET; - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - if (hhash->MspDeInitCallback == NULL) - { - hhash->MspDeInitCallback = HAL_HASH_MspDeInit; - } - - /* DeInit the low level hardware */ - hhash->MspDeInitCallback(hhash); -#else - /* DeInit the low level hardware: CLOCK, NVIC */ - HAL_HASH_MspDeInit(hhash); -#endif /* (USE_HAL_HASH_REGISTER_CALLBACKS) */ - - - /* Reset HASH handle status */ - hhash->Status = HAL_OK; - - /* Set the HASH state to Ready */ - hhash->State = HAL_HASH_STATE_RESET; - - /* Initialise the error code */ - hhash->ErrorCode = HAL_HASH_ERROR_NONE; - - /* Reset multi buffers accumulation flag */ - hhash->Accumulation = 0U; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initialize the HASH MSP. - * @param hhash HASH handle. - * @retval None - */ -__weak void HAL_HASH_MspInit(HASH_HandleTypeDef *hhash) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhash); - - /* NOTE : This function should not be modified; when the callback is needed, - HAL_HASH_MspInit() can be implemented in the user file. - */ -} - -/** - * @brief DeInitialize the HASH MSP. - * @param hhash HASH handle. - * @retval None - */ -__weak void HAL_HASH_MspDeInit(HASH_HandleTypeDef *hhash) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhash); - - /* NOTE : This function should not be modified; when the callback is needed, - HAL_HASH_MspDeInit() can be implemented in the user file. - */ -} - -/** - * @brief Input data transfer complete call back. - * @note HAL_HASH_InCpltCallback() is called when the complete input message - * has been fed to the Peripheral. This API is invoked only when input data are - * entered under interruption or through DMA. - * @note In case of HASH or HMAC multi-buffer DMA feeding case (MDMAT bit set), - * HAL_HASH_InCpltCallback() is called at the end of each buffer feeding - * to the Peripheral. - * @param hhash HASH handle. - * @retval None - */ -__weak void HAL_HASH_InCpltCallback(HASH_HandleTypeDef *hhash) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhash); - - /* NOTE : This function should not be modified; when the callback is needed, - HAL_HASH_InCpltCallback() can be implemented in the user file. - */ -} - -/** - * @brief Digest computation complete call back. - * @note HAL_HASH_DgstCpltCallback() is used under interruption, is not - * relevant with DMA. - * @param hhash HASH handle. - * @retval None - */ -__weak void HAL_HASH_DgstCpltCallback(HASH_HandleTypeDef *hhash) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhash); - - /* NOTE : This function should not be modified; when the callback is needed, - HAL_HASH_DgstCpltCallback() can be implemented in the user file. - */ -} - -/** - * @brief Error callback. - * @note Code user can resort to hhash->Status (HAL_ERROR, HAL_TIMEOUT,...) - * to retrieve the error type. - * @param hhash HASH handle. - * @retval None - */ -__weak void HAL_HASH_ErrorCallback(HASH_HandleTypeDef *hhash) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhash); - - /* NOTE : This function should not be modified; when the callback is needed, - HAL_HASH_ErrorCallback() can be implemented in the user file. - */ -} - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User HASH Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hhash HASH handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_HASH_INPUTCPLT_CB_ID HASH input completion Callback ID - * @arg @ref HAL_HASH_DGSTCPLT_CB_ID HASH digest computation completion Callback ID - * @arg @ref HAL_HASH_ERROR_CB_ID HASH error Callback ID - * @arg @ref HAL_HASH_MSPINIT_CB_ID HASH MspInit callback ID - * @arg @ref HAL_HASH_MSPDEINIT_CB_ID HASH MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_HASH_RegisterCallback(HASH_HandleTypeDef *hhash, HAL_HASH_CallbackIDTypeDef CallbackID, - pHASH_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hhash); - - if (HAL_HASH_STATE_READY == hhash->State) - { - switch (CallbackID) - { - case HAL_HASH_INPUTCPLT_CB_ID : - hhash->InCpltCallback = pCallback; - break; - - case HAL_HASH_DGSTCPLT_CB_ID : - hhash->DgstCpltCallback = pCallback; - break; - - case HAL_HASH_ERROR_CB_ID : - hhash->ErrorCallback = pCallback; - break; - - case HAL_HASH_MSPINIT_CB_ID : - hhash->MspInitCallback = pCallback; - break; - - case HAL_HASH_MSPDEINIT_CB_ID : - hhash->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_HASH_STATE_RESET == hhash->State) - { - switch (CallbackID) - { - case HAL_HASH_MSPINIT_CB_ID : - hhash->MspInitCallback = pCallback; - break; - - case HAL_HASH_MSPDEINIT_CB_ID : - hhash->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hhash); - return status; -} - -/** - * @brief Unregister a HASH Callback - * HASH Callback is redirected to the weak (surcharged) predefined callback - * @param hhash HASH handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_HASH_INPUTCPLT_CB_ID HASH input completion Callback ID - * @arg @ref HAL_HASH_DGSTCPLT_CB_ID HASH digest computation completion Callback ID - * @arg @ref HAL_HASH_ERROR_CB_ID HASH error Callback ID - * @arg @ref HAL_HASH_MSPINIT_CB_ID HASH MspInit callback ID - * @arg @ref HAL_HASH_MSPDEINIT_CB_ID HASH MspDeInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_HASH_UnRegisterCallback(HASH_HandleTypeDef *hhash, HAL_HASH_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hhash); - - if (HAL_HASH_STATE_READY == hhash->State) - { - switch (CallbackID) - { - case HAL_HASH_INPUTCPLT_CB_ID : - hhash->InCpltCallback = HAL_HASH_InCpltCallback; /* Legacy weak (surcharged) input completion callback */ - break; - - case HAL_HASH_DGSTCPLT_CB_ID : - hhash->DgstCpltCallback = HAL_HASH_DgstCpltCallback; /* Legacy weak (surcharged) digest computation - completion callback */ - break; - - case HAL_HASH_ERROR_CB_ID : - hhash->ErrorCallback = HAL_HASH_ErrorCallback; /* Legacy weak (surcharged) error callback */ - break; - - case HAL_HASH_MSPINIT_CB_ID : - hhash->MspInitCallback = HAL_HASH_MspInit; /* Legacy weak (surcharged) Msp Init */ - break; - - case HAL_HASH_MSPDEINIT_CB_ID : - hhash->MspDeInitCallback = HAL_HASH_MspDeInit; /* Legacy weak (surcharged) Msp DeInit */ - break; - - default : - /* Update the error code */ - hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_HASH_STATE_RESET == hhash->State) - { - switch (CallbackID) - { - case HAL_HASH_MSPINIT_CB_ID : - hhash->MspInitCallback = HAL_HASH_MspInit; /* Legacy weak (surcharged) Msp Init */ - break; - - case HAL_HASH_MSPDEINIT_CB_ID : - hhash->MspDeInitCallback = HAL_HASH_MspDeInit; /* Legacy weak (surcharged) Msp DeInit */ - break; - - default : - /* Update the error code */ - hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hhash->ErrorCode |= HAL_HASH_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hhash); - return status; -} -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup HASH_Exported_Functions_Group2 HASH processing functions in polling mode - * @brief HASH processing functions using polling mode. - * -@verbatim - =============================================================================== - ##### Polling mode HASH processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in polling mode - the hash value using one of the following algorithms: - (+) MD5 - (++) HAL_HASH_MD5_Start() - (++) HAL_HASH_MD5_Accmlt() - (++) HAL_HASH_MD5_Accmlt_End() - (+) SHA1 - (++) HAL_HASH_SHA1_Start() - (++) HAL_HASH_SHA1_Accmlt() - (++) HAL_HASH_SHA1_Accmlt_End() - - [..] For a single buffer to be hashed, user can resort to HAL_HASH_xxx_Start(). - - [..] In case of multi-buffer HASH processing (a single digest is computed while - several buffers are fed to the Peripheral), the user can resort to successive calls - to HAL_HASH_xxx_Accumulate() and wrap-up the digest computation by a call - to HAL_HASH_xxx_Accumulate_End(). - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the HASH peripheral in MD5 mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. - * @param Timeout Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_MD5_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout) -{ - return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief If not already done, initialize the HASH peripheral in MD5 mode then - * processes pInBuffer. - * @note Consecutive calls to HAL_HASH_MD5_Accmlt() can be used to feed - * several input buffers back-to-back to the Peripheral that will yield a single - * HASH signature once all buffers have been entered. Wrap-up of input - * buffers feeding and retrieval of digest is done by a call to - * HAL_HASH_MD5_Accmlt_End(). - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note Digest is not retrieved by this API, user must resort to HAL_HASH_MD5_Accmlt_End() - * to read it, feeding at the same time the last input buffer to the Peripheral. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. Only HAL_HASH_MD5_Accmlt_End() is able - * to manage the ending buffer with a length in bytes not a multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Accumulate(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief End computation of a single HASH signature after several calls to HAL_HASH_MD5_Accmlt() API. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. - * @param Timeout Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief Initialize the HASH peripheral in SHA1 mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. - * @param Timeout Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_SHA1_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout) -{ - return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA1); -} - -/** - * @brief If not already done, initialize the HASH peripheral in SHA1 mode then - * processes pInBuffer. - * @note Consecutive calls to HAL_HASH_SHA1_Accmlt() can be used to feed - * several input buffers back-to-back to the Peripheral that will yield a single - * HASH signature once all buffers have been entered. Wrap-up of input - * buffers feeding and retrieval of digest is done by a call to - * HAL_HASH_SHA1_Accmlt_End(). - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note Digest is not retrieved by this API, user must resort to HAL_HASH_SHA1_Accmlt_End() - * to read it, feeding at the same time the last input buffer to the Peripheral. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. Only HAL_HASH_SHA1_Accmlt_End() is able - * to manage the ending buffer with a length in bytes not a multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Accumulate(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); -} - -/** - * @brief End computation of a single HASH signature after several calls to HAL_HASH_SHA1_Accmlt() API. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. - * @param Timeout Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA1); -} - -/** - * @} - */ - -/** @defgroup HASH_Exported_Functions_Group3 HASH processing functions in interrupt mode - * @brief HASH processing functions using interrupt mode. - * -@verbatim - =============================================================================== - ##### Interruption mode HASH processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in interrupt mode - the hash value using one of the following algorithms: - (+) MD5 - (++) HAL_HASH_MD5_Start_IT() - (++) HAL_HASH_MD5_Accmlt_IT() - (++) HAL_HASH_MD5_Accmlt_End_IT() - (+) SHA1 - (++) HAL_HASH_SHA1_Start_IT() - (++) HAL_HASH_SHA1_Accmlt_IT() - (++) HAL_HASH_SHA1_Accmlt_End_IT() - - [..] API HAL_HASH_IRQHandler() manages each HASH interruption. - - [..] Note that HAL_HASH_IRQHandler() manages as well HASH Peripheral interruptions when in - HMAC processing mode. - - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the HASH peripheral in MD5 mode, next process pInBuffer then - * read the computed digest in interruption mode. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_MD5_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief If not already done, initialize the HASH peripheral in MD5 mode then - * processes pInBuffer in interruption mode. - * @note Consecutive calls to HAL_HASH_MD5_Accmlt_IT() can be used to feed - * several input buffers back-to-back to the Peripheral that will yield a single - * HASH signature once all buffers have been entered. Wrap-up of input - * buffers feeding and retrieval of digest is done by a call to - * HAL_HASH_MD5_Accmlt_End_IT(). - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. Only HAL_HASH_MD5_Accmlt_End_IT() is able - * to manage the ending buffer with a length in bytes not a multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Accumulate_IT(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief End computation of a single HASH signature after several calls to HAL_HASH_MD5_Accmlt_IT() API. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief Initialize the HASH peripheral in SHA1 mode, next process pInBuffer then - * read the computed digest in interruption mode. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_SHA1_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA1); -} - - -/** - * @brief If not already done, initialize the HASH peripheral in SHA1 mode then - * processes pInBuffer in interruption mode. - * @note Consecutive calls to HAL_HASH_SHA1_Accmlt_IT() can be used to feed - * several input buffers back-to-back to the Peripheral that will yield a single - * HASH signature once all buffers have been entered. Wrap-up of input - * buffers feeding and retrieval of digest is done by a call to - * HAL_HASH_SHA1_Accmlt_End_IT(). - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. Only HAL_HASH_SHA1_Accmlt_End_IT() is able - * to manage the ending buffer with a length in bytes not a multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Accumulate_IT(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); -} - -/** - * @brief End computation of a single HASH signature after several calls to HAL_HASH_SHA1_Accmlt_IT() API. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA1); -} - -/** - * @brief Handle HASH interrupt request. - * @param hhash HASH handle. - * @note HAL_HASH_IRQHandler() handles interrupts in HMAC processing as well. - * @note In case of error reported during the HASH interruption processing, - * HAL_HASH_ErrorCallback() API is called so that user code can - * manage the error. The error type is available in hhash->Status field. - * @retval None - */ -void HAL_HASH_IRQHandler(HASH_HandleTypeDef *hhash) -{ - hhash->Status = HASH_IT(hhash); - if (hhash->Status != HAL_OK) - { - hhash->ErrorCode |= HAL_HASH_ERROR_IT; -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - hhash->ErrorCallback(hhash); -#else - HAL_HASH_ErrorCallback(hhash); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - /* After error handling by code user, reset HASH handle HAL status */ - hhash->Status = HAL_OK; - } -} - -/** - * @} - */ - -/** @defgroup HASH_Exported_Functions_Group4 HASH processing functions in DMA mode - * @brief HASH processing functions using DMA mode. - * -@verbatim - =============================================================================== - ##### DMA mode HASH processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in DMA mode - the hash value using one of the following algorithms: - (+) MD5 - (++) HAL_HASH_MD5_Start_DMA() - (++) HAL_HASH_MD5_Finish() - (+) SHA1 - (++) HAL_HASH_SHA1_Start_DMA() - (++) HAL_HASH_SHA1_Finish() - - [..] When resorting to DMA mode to enter the data in the Peripheral, user must resort - to HAL_HASH_xxx_Start_DMA() then read the resulting digest with - HAL_HASH_xxx_Finish(). - [..] In case of multi-buffer HASH processing, MDMAT bit must first be set before - the successive calls to HAL_HASH_xxx_Start_DMA(). Then, MDMAT bit needs to be - reset before the last call to HAL_HASH_xxx_Start_DMA(). Digest is finally - retrieved thanks to HAL_HASH_xxx_Finish(). - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the HASH peripheral in MD5 mode then initiate a DMA transfer - * to feed the input buffer to the Peripheral. - * @note Once the DMA transfer is finished, HAL_HASH_MD5_Finish() API must - * be called to retrieve the computed digest. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_MD5_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief Return the computed digest in MD5 mode. - * @note The API waits for DCIS to be set then reads the computed digest. - * @note HAL_HASH_MD5_Finish() can be used as well to retrieve the digest in - * HMAC MD5 mode. - * @param hhash HASH handle. - * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_MD5_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Finish(hhash, pOutBuffer, Timeout); -} - -/** - * @brief Initialize the HASH peripheral in SHA1 mode then initiate a DMA transfer - * to feed the input buffer to the Peripheral. - * @note Once the DMA transfer is finished, HAL_HASH_SHA1_Finish() API must - * be called to retrieve the computed digest. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_SHA1_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); -} - - -/** - * @brief Return the computed digest in SHA1 mode. - * @note The API waits for DCIS to be set then reads the computed digest. - * @note HAL_HASH_SHA1_Finish() can be used as well to retrieve the digest in - * HMAC SHA1 mode. - * @param hhash HASH handle. - * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_SHA1_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Finish(hhash, pOutBuffer, Timeout); -} - -/** - * @} - */ - -/** @defgroup HASH_Exported_Functions_Group5 HMAC processing functions in polling mode - * @brief HMAC processing functions using polling mode. - * -@verbatim - =============================================================================== - ##### Polling mode HMAC processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in polling mode - the HMAC value using one of the following algorithms: - (+) MD5 - (++) HAL_HMAC_MD5_Start() - (+) SHA1 - (++) HAL_HMAC_SHA1_Start() - - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the HASH peripheral in HMAC MD5 mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMAC_MD5_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout) -{ - return HMAC_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief Initialize the HASH peripheral in HMAC SHA1 mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMAC_SHA1_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout) -{ - return HMAC_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA1); -} - -/** - * @} - */ - - -/** @defgroup HASH_Exported_Functions_Group6 HMAC processing functions in interrupt mode - * @brief HMAC processing functions using interrupt mode. - * -@verbatim - =============================================================================== - ##### Interrupt mode HMAC processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in interrupt mode - the HMAC value using one of the following algorithms: - (+) MD5 - (++) HAL_HMAC_MD5_Start_IT() - (+) SHA1 - (++) HAL_HMAC_SHA1_Start_IT() - -@endverbatim - * @{ - */ - - -/** - * @brief Initialize the HASH peripheral in HMAC MD5 mode, next process pInBuffer then - * read the computed digest in interrupt mode. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 16 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMAC_MD5_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HMAC_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief Initialize the HASH peripheral in HMAC SHA1 mode, next process pInBuffer then - * read the computed digest in interrupt mode. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 20 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMAC_SHA1_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HMAC_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA1); -} - -/** - * @} - */ - - - -/** @defgroup HASH_Exported_Functions_Group7 HMAC processing functions in DMA mode - * @brief HMAC processing functions using DMA modes. - * -@verbatim - =============================================================================== - ##### DMA mode HMAC processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in DMA mode - the HMAC value using one of the following algorithms: - (+) MD5 - (++) HAL_HMAC_MD5_Start_DMA() - (+) SHA1 - (++) HAL_HMAC_SHA1_Start_DMA() - - [..] When resorting to DMA mode to enter the data in the Peripheral for HMAC processing, - user must resort to HAL_HMAC_xxx_Start_DMA() then read the resulting digest - with HAL_HASH_xxx_Finish(). - -@endverbatim - * @{ - */ - - -/** - * @brief Initialize the HASH peripheral in HMAC MD5 mode then initiate the required - * DMA transfers to feed the key and the input buffer to the Peripheral. - * @note Once the DMA transfers are finished (indicated by hhash->State set back - * to HAL_HASH_STATE_READY), HAL_HASH_MD5_Finish() API must be called to retrieve - * the computed digest. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note If MDMAT bit is set before calling this function (multi-buffer - * HASH processing case), the input buffer size (in bytes) must be - * a multiple of 4 otherwise, the HASH digest computation is corrupted. - * For the processing of the last buffer of the thread, MDMAT bit must - * be reset and the buffer length (in bytes) doesn't have to be a - * multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMAC_MD5_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); -} - - -/** - * @brief Initialize the HASH peripheral in HMAC SHA1 mode then initiate the required - * DMA transfers to feed the key and the input buffer to the Peripheral. - * @note Once the DMA transfers are finished (indicated by hhash->State set back - * to HAL_HASH_STATE_READY), HAL_HASH_SHA1_Finish() API must be called to retrieve - * the computed digest. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note If MDMAT bit is set before calling this function (multi-buffer - * HASH processing case), the input buffer size (in bytes) must be - * a multiple of 4 otherwise, the HASH digest computation is corrupted. - * For the processing of the last buffer of the thread, MDMAT bit must - * be reset and the buffer length (in bytes) doesn't have to be a - * multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMAC_SHA1_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); -} - -/** - * @} - */ - -/** @defgroup HASH_Exported_Functions_Group8 Peripheral states functions - * @brief Peripheral State functions. - * -@verbatim - =============================================================================== - ##### Peripheral State methods ##### - =============================================================================== - [..] - This section permits to get in run-time the state and the peripheral handle - status of the peripheral: - (+) HAL_HASH_GetState() - (+) HAL_HASH_GetStatus() - - [..] - Additionally, this subsection provides functions allowing to save and restore - the HASH or HMAC processing context in case of calculation suspension: - (+) HAL_HASH_ContextSaving() - (+) HAL_HASH_ContextRestoring() - - [..] - This subsection provides functions allowing to suspend the HASH processing - (+) when input are fed to the Peripheral by software - (++) HAL_HASH_SwFeed_ProcessSuspend() - (+) when input are fed to the Peripheral by DMA - (++) HAL_HASH_DMAFeed_ProcessSuspend() - - - -@endverbatim - * @{ - */ - -/** - * @brief Return the HASH handle state. - * @note The API yields the current state of the handle (BUSY, READY,...). - * @param hhash HASH handle. - * @retval HAL HASH state - */ -HAL_HASH_StateTypeDef HAL_HASH_GetState(HASH_HandleTypeDef *hhash) -{ - return hhash->State; -} - - -/** - * @brief Return the HASH HAL status. - * @note The API yields the HAL status of the handle: it is the result of the - * latest HASH processing and allows to report any issue (e.g. HAL_TIMEOUT). - * @param hhash HASH handle. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_GetStatus(HASH_HandleTypeDef *hhash) -{ - return hhash->Status; -} - -/** - * @brief Save the HASH context in case of processing suspension. - * @param hhash HASH handle. - * @param pMemBuffer pointer to the memory buffer where the HASH context - * is saved. - * @note The IMR, STR, CR then all the CSR registers are saved - * in that order. Only the r/w bits are read to be restored later on. - * @note By default, all the context swap registers (there are - * HASH_NUMBER_OF_CSR_REGISTERS of those) are saved. - * @note pMemBuffer points to a buffer allocated by the user. The buffer size - * must be at least (HASH_NUMBER_OF_CSR_REGISTERS + 3) * 4 uint8 long. - * @retval None - */ -void HAL_HASH_ContextSaving(HASH_HandleTypeDef *hhash, uint8_t *pMemBuffer) -{ - uint32_t mem_ptr = (uint32_t)pMemBuffer; - uint32_t csr_ptr = (uint32_t)HASH->CSR; - uint32_t i; - - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhash); - - /* Save IMR register content */ - *(uint32_t *)(mem_ptr) = READ_BIT(HASH->IMR, HASH_IT_DINI | HASH_IT_DCI); - mem_ptr += 4U; - /* Save STR register content */ - *(uint32_t *)(mem_ptr) = READ_BIT(HASH->STR, HASH_STR_NBLW); - mem_ptr += 4U; - /* Save CR register content */ -#if defined(HASH_CR_MDMAT) - *(uint32_t *)(mem_ptr) = READ_BIT(HASH->CR, HASH_CR_DMAE | HASH_CR_DATATYPE | HASH_CR_MODE | HASH_CR_ALGO | - HASH_CR_LKEY | HASH_CR_MDMAT); -#else - *(uint32_t *)(mem_ptr) = READ_BIT(HASH->CR, HASH_CR_DMAE | HASH_CR_DATATYPE | HASH_CR_MODE | HASH_CR_ALGO | - HASH_CR_LKEY); -#endif /* HASH_CR_MDMAT*/ - mem_ptr += 4U; - /* By default, save all CSRs registers */ - for (i = HASH_NUMBER_OF_CSR_REGISTERS; i > 0U; i--) - { - *(uint32_t *)(mem_ptr) = *(uint32_t *)(csr_ptr); - mem_ptr += 4U; - csr_ptr += 4U; - } -} - - -/** - * @brief Restore the HASH context in case of processing resumption. - * @param hhash HASH handle. - * @param pMemBuffer pointer to the memory buffer where the HASH context - * is stored. - * @note The IMR, STR, CR then all the CSR registers are restored - * in that order. Only the r/w bits are restored. - * @note By default, all the context swap registers (HASH_NUMBER_OF_CSR_REGISTERS - * of those) are restored (all of them have been saved by default - * beforehand). - * @retval None - */ -void HAL_HASH_ContextRestoring(HASH_HandleTypeDef *hhash, uint8_t *pMemBuffer) -{ - uint32_t mem_ptr = (uint32_t)pMemBuffer; - uint32_t csr_ptr = (uint32_t)HASH->CSR; - uint32_t i; - - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhash); - - /* Restore IMR register content */ - WRITE_REG(HASH->IMR, (*(uint32_t *)(mem_ptr))); - mem_ptr += 4U; - /* Restore STR register content */ - WRITE_REG(HASH->STR, (*(uint32_t *)(mem_ptr))); - mem_ptr += 4U; - /* Restore CR register content */ - WRITE_REG(HASH->CR, (*(uint32_t *)(mem_ptr))); - mem_ptr += 4U; - - /* Reset the HASH processor before restoring the Context - Swap Registers (CSR) */ - __HAL_HASH_INIT(); - - /* By default, restore all CSR registers */ - for (i = HASH_NUMBER_OF_CSR_REGISTERS; i > 0U; i--) - { - WRITE_REG((*(uint32_t *)(csr_ptr)), (*(uint32_t *)(mem_ptr))); - mem_ptr += 4U; - csr_ptr += 4U; - } -} - - -/** - * @brief Initiate HASH processing suspension when in polling or interruption mode. - * @param hhash HASH handle. - * @note Set the handle field SuspendRequest to the appropriate value so that - * the on-going HASH processing is suspended as soon as the required - * conditions are met. Note that the actual suspension is carried out - * by the functions HASH_WriteData() in polling mode and HASH_IT() in - * interruption mode. - * @retval None - */ -void HAL_HASH_SwFeed_ProcessSuspend(HASH_HandleTypeDef *hhash) -{ - /* Set Handle Suspend Request field */ - hhash->SuspendRequest = HAL_HASH_SUSPEND; -} - -/** - * @brief Suspend the HASH processing when in DMA mode. - * @param hhash HASH handle. - * @note When suspension attempt occurs at the very end of a DMA transfer and - * all the data have already been entered in the Peripheral, hhash->State is - * set to HAL_HASH_STATE_READY and the API returns HAL_ERROR. It is - * recommended to wrap-up the processing in reading the digest as usual. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASH_DMAFeed_ProcessSuspend(HASH_HandleTypeDef *hhash) -{ - uint32_t tmp_remaining_DMATransferSize_inWords; - uint32_t tmp_initial_DMATransferSize_inWords; - uint32_t tmp_words_already_pushed; - - if (hhash->State == HAL_HASH_STATE_READY) - { - return HAL_ERROR; - } - else - { - - /* Make sure there is enough time to suspend the processing */ - tmp_remaining_DMATransferSize_inWords = ((DMA_Stream_TypeDef *)hhash->hdmain->Instance)->NDTR; - - if (tmp_remaining_DMATransferSize_inWords <= HASH_DMA_SUSPENSION_WORDS_LIMIT) - { - /* No suspension attempted since almost to the end of the transferred data. */ - /* Best option for user code is to wrap up low priority message hashing */ - return HAL_ERROR; - } - - /* Wait for BUSY flag to be reset */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, HASH_TIMEOUTVALUE) != HAL_OK) - { - return HAL_TIMEOUT; - } - - if (__HAL_HASH_GET_FLAG(HASH_FLAG_DCIS) != RESET) - { - return HAL_ERROR; - } - - /* Wait for BUSY flag to be set */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, RESET, HASH_TIMEOUTVALUE) != HAL_OK) - { - return HAL_TIMEOUT; - } - /* Disable DMA channel */ - /* Note that the Abort function will - - Clear the transfer error flags - - Unlock - - Set the State - */ - if (HAL_DMA_Abort(hhash->hdmain) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear DMAE bit */ - CLEAR_BIT(HASH->CR, HASH_CR_DMAE); - - /* Wait for BUSY flag to be reset */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, HASH_TIMEOUTVALUE) != HAL_OK) - { - return HAL_TIMEOUT; - } - - if (__HAL_HASH_GET_FLAG(HASH_FLAG_DCIS) != RESET) - { - return HAL_ERROR; - } - - /* At this point, DMA interface is disabled and no transfer is on-going */ - /* Retrieve from the DMA handle how many words remain to be written */ - tmp_remaining_DMATransferSize_inWords = ((DMA_Stream_TypeDef *)hhash->hdmain->Instance)->NDTR; - - if (tmp_remaining_DMATransferSize_inWords == 0U) - { - /* All the DMA transfer is actually done. Suspension occurred at the very end - of the transfer. Either the digest computation is about to start (HASH case) - or processing is about to move from one step to another (HMAC case). - In both cases, the processing can't be suspended at this point. It is - safer to - - retrieve the low priority block digest before starting the high - priority block processing (HASH case) - - re-attempt a new suspension (HMAC case) - */ - return HAL_ERROR; - } - else - { - - /* Compute how many words were supposed to be transferred by DMA */ - tmp_initial_DMATransferSize_inWords = (((hhash->HashInCount % 4U) != 0U) ? \ - ((hhash->HashInCount + 3U) / 4U) : (hhash->HashInCount / 4U)); - - /* If discrepancy between the number of words reported by DMA Peripheral and - the numbers of words entered as reported by HASH Peripheral, correct it */ - /* tmp_words_already_pushed reflects the number of words that were already pushed before - the start of DMA transfer (multi-buffer processing case) */ - tmp_words_already_pushed = hhash->NbWordsAlreadyPushed; - if (((tmp_words_already_pushed + tmp_initial_DMATransferSize_inWords - \ - tmp_remaining_DMATransferSize_inWords) % 16U) != HASH_NBW_PUSHED()) - { - tmp_remaining_DMATransferSize_inWords--; /* one less word to be transferred again */ - } - - /* Accordingly, update the input pointer that points at the next word to be - transferred to the Peripheral by DMA */ - hhash->pHashInBuffPtr += 4U * (tmp_initial_DMATransferSize_inWords - tmp_remaining_DMATransferSize_inWords) ; - - /* And store in HashInCount the remaining size to transfer (in bytes) */ - hhash->HashInCount = 4U * tmp_remaining_DMATransferSize_inWords; - - } - - /* Set State as suspended */ - hhash->State = HAL_HASH_STATE_SUSPENDED; - - return HAL_OK; - - } -} - -/** - * @brief Return the HASH handle error code. - * @param hhash pointer to a HASH_HandleTypeDef structure. - * @retval HASH Error Code - */ -uint32_t HAL_HASH_GetError(HASH_HandleTypeDef *hhash) -{ - /* Return HASH Error Code */ - return hhash->ErrorCode; -} -/** - * @} - */ - - -/** - * @} - */ - -/** @defgroup HASH_Private_Functions HASH Private Functions - * @{ - */ - -/** - * @brief DMA HASH Input Data transfer completion callback. - * @param hdma DMA handle. - * @note In case of HMAC processing, HASH_DMAXferCplt() initiates - * the next DMA transfer for the following HMAC step. - * @retval None - */ -static void HASH_DMAXferCplt(DMA_HandleTypeDef *hdma) -{ - HASH_HandleTypeDef *hhash = (HASH_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - uint32_t inputaddr; - uint32_t buffersize; - HAL_StatusTypeDef status = HAL_OK; - - if (hhash->State != HAL_HASH_STATE_SUSPENDED) - { - - /* Disable the DMA transfer */ - CLEAR_BIT(HASH->CR, HASH_CR_DMAE); - - if (READ_BIT(HASH->CR, HASH_CR_MODE) == 0U) - { - /* If no HMAC processing, input data transfer is now over */ - - /* Change the HASH state to ready */ - hhash->State = HAL_HASH_STATE_READY; - - /* Call Input data transfer complete call back */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - hhash->InCpltCallback(hhash); -#else - HAL_HASH_InCpltCallback(hhash); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - } - else - { - /* HMAC processing: depending on the current HMAC step and whether or - not multi-buffer processing is on-going, the next step is initiated - and MDMAT bit is set. */ - - - if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_3) - { - /* This is the end of HMAC processing */ - - /* Change the HASH state to ready */ - hhash->State = HAL_HASH_STATE_READY; - - /* Call Input data transfer complete call back - (note that the last DMA transfer was that of the key - for the outer HASH operation). */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - hhash->InCpltCallback(hhash); -#else - HAL_HASH_InCpltCallback(hhash); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - return; - } - else if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) - { - inputaddr = (uint32_t)hhash->pHashMsgBuffPtr; /* DMA transfer start address */ - buffersize = hhash->HashBuffSize; /* DMA transfer size (in bytes) */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_2; /* Move phase from Step 1 to Step 2 */ - - /* In case of suspension request, save the new starting parameters */ - hhash->HashInCount = hhash->HashBuffSize; /* Initial DMA transfer size (in bytes) */ - hhash->pHashInBuffPtr = hhash->pHashMsgBuffPtr ; /* DMA transfer start address */ - - hhash->NbWordsAlreadyPushed = 0U; /* Reset number of words already pushed */ -#if defined(HASH_CR_MDMAT) - /* Check whether or not digest calculation must be disabled (in case of multi-buffer HMAC processing) */ - if (hhash->DigestCalculationDisable != RESET) - { - /* Digest calculation is disabled: Step 2 must start with MDMAT bit set, - no digest calculation will be triggered at the end of the input buffer feeding to the Peripheral */ - __HAL_HASH_SET_MDMAT(); - } -#endif /* HASH_CR_MDMAT*/ - } - else /*case (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2)*/ - { - if (hhash->DigestCalculationDisable != RESET) - { - /* No automatic move to Step 3 as a new message buffer will be fed to the Peripheral - (case of multi-buffer HMAC processing): - DCAL must not be set. - Phase remains in Step 2, MDMAT remains set at this point. - Change the HASH state to ready and call Input data transfer complete call back. */ - hhash->State = HAL_HASH_STATE_READY; -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - hhash->InCpltCallback(hhash); -#else - HAL_HASH_InCpltCallback(hhash); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - return ; - } - else - { - /* Digest calculation is not disabled (case of single buffer input or last buffer - of multi-buffer HMAC processing) */ - inputaddr = (uint32_t)hhash->Init.pKey; /* DMA transfer start address */ - buffersize = hhash->Init.KeySize; /* DMA transfer size (in bytes) */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_3; /* Move phase from Step 2 to Step 3 */ - /* In case of suspension request, save the new starting parameters */ - hhash->HashInCount = hhash->Init.KeySize; /* Initial size for second DMA transfer (input data) */ - hhash->pHashInBuffPtr = hhash->Init.pKey ; /* address passed to DMA, now entering data message */ - - hhash->NbWordsAlreadyPushed = 0U; /* Reset number of words already pushed */ - } - } - - /* Configure the Number of valid bits in last word of the message */ - __HAL_HASH_SET_NBVALIDBITS(buffersize); - - /* Set the HASH DMA transfer completion call back */ - hhash->hdmain->XferCpltCallback = HASH_DMAXferCplt; - - /* Enable the DMA In DMA stream */ - status = HAL_DMA_Start_IT(hhash->hdmain, inputaddr, (uint32_t)&HASH->DIN, \ - (((buffersize % 4U) != 0U) ? ((buffersize + (4U - (buffersize % 4U))) / 4U) : \ - (buffersize / 4U))); - - - - /* Enable DMA requests */ - SET_BIT(HASH->CR, HASH_CR_DMAE); - - /* Return function status */ - if (status != HAL_OK) - { - /* Update HASH state machine to error */ - hhash->State = HAL_HASH_STATE_ERROR; - } - else - { - /* Change HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - } - } - } - - return; -} - -/** - * @brief DMA HASH communication error callback. - * @param hdma DMA handle. - * @note HASH_DMAError() callback invokes HAL_HASH_ErrorCallback() that - * can contain user code to manage the error. - * @retval None - */ -static void HASH_DMAError(DMA_HandleTypeDef *hdma) -{ - HASH_HandleTypeDef *hhash = (HASH_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hhash->State != HAL_HASH_STATE_SUSPENDED) - { - hhash->ErrorCode |= HAL_HASH_ERROR_DMA; - /* Set HASH state to ready to prevent any blocking issue in user code - present in HAL_HASH_ErrorCallback() */ - hhash->State = HAL_HASH_STATE_READY; - /* Set HASH handle status to error */ - hhash->Status = HAL_ERROR; -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - hhash->ErrorCallback(hhash); -#else - HAL_HASH_ErrorCallback(hhash); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - /* After error handling by code user, reset HASH handle HAL status */ - hhash->Status = HAL_OK; - - } -} - -/** - * @brief Feed the input buffer to the HASH Peripheral. - * @param hhash HASH handle. - * @param pInBuffer pointer to input buffer. - * @param Size the size of input buffer in bytes. - * @note HASH_WriteData() regularly reads hhash->SuspendRequest to check whether - * or not the HASH processing must be suspended. If this is the case, the - * processing is suspended when possible and the Peripheral feeding point reached at - * suspension time is stored in the handle for resumption later on. - * @retval HAL status - */ -static HAL_StatusTypeDef HASH_WriteData(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - uint32_t buffercounter; - __IO uint32_t inputaddr = (uint32_t) pInBuffer; - - for (buffercounter = 0U; buffercounter < Size; buffercounter += 4U) - { - /* Write input data 4 bytes at a time */ - HASH->DIN = *(uint32_t *)inputaddr; - inputaddr += 4U; - - /* If the suspension flag has been raised and if the processing is not about - to end, suspend processing */ - if ((hhash->SuspendRequest == HAL_HASH_SUSPEND) && ((buffercounter + 4U) < Size)) - { - /* Wait for DINIS = 1, which occurs when 16 32-bit locations are free - in the input buffer */ - if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS)) - { - /* Reset SuspendRequest */ - hhash->SuspendRequest = HAL_HASH_SUSPEND_NONE; - - /* Depending whether the key or the input data were fed to the Peripheral, the feeding point - reached at suspension time is not saved in the same handle fields */ - if ((hhash->Phase == HAL_HASH_PHASE_PROCESS) || (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2)) - { - /* Save current reading and writing locations of Input and Output buffers */ - hhash->pHashInBuffPtr = (uint8_t *)inputaddr; - /* Save the number of bytes that remain to be processed at this point */ - hhash->HashInCount = Size - (buffercounter + 4U); - } - else if ((hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) || (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_3)) - { - /* Save current reading and writing locations of Input and Output buffers */ - hhash->pHashKeyBuffPtr = (uint8_t *)inputaddr; - /* Save the number of bytes that remain to be processed at this point */ - hhash->HashKeyCount = Size - (buffercounter + 4U); - } - else - { - /* Unexpected phase: unlock process and report error */ - hhash->State = HAL_HASH_STATE_READY; - __HAL_UNLOCK(hhash); - return HAL_ERROR; - } - - /* Set the HASH state to Suspended and exit to stop entering data */ - hhash->State = HAL_HASH_STATE_SUSPENDED; - - return HAL_OK; - } /* if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS)) */ - } /* if ((hhash->SuspendRequest == HAL_HASH_SUSPEND) && ((buffercounter+4) < Size)) */ - } /* for(buffercounter = 0; buffercounter < Size; buffercounter+=4) */ - - /* At this point, all the data have been entered to the Peripheral: exit */ - return HAL_OK; -} - -/** - * @brief Retrieve the message digest. - * @param pMsgDigest pointer to the computed digest. - * @param Size message digest size in bytes. - * @retval None - */ -static void HASH_GetDigest(uint8_t *pMsgDigest, uint8_t Size) -{ - uint32_t msgdigest = (uint32_t)pMsgDigest; - - switch (Size) - { - /* Read the message digest */ - case 16: /* MD5 */ - *(uint32_t *)(msgdigest) = __REV(HASH->HR[0]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[1]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[2]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[3]); - break; - case 20: /* SHA1 */ - *(uint32_t *)(msgdigest) = __REV(HASH->HR[0]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[1]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[2]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[3]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[4]); - break; - case 28: /* SHA224 */ - *(uint32_t *)(msgdigest) = __REV(HASH->HR[0]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[1]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[2]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[3]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[4]); -#if defined(HASH_CR_MDMAT) - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[5]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[6]); -#endif /* HASH_CR_MDMAT*/ - break; - case 32: /* SHA256 */ - *(uint32_t *)(msgdigest) = __REV(HASH->HR[0]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[1]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[2]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[3]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH->HR[4]); -#if defined(HASH_CR_MDMAT) - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[5]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[6]); - msgdigest += 4U; - *(uint32_t *)(msgdigest) = __REV(HASH_DIGEST->HR[7]); -#endif /* HASH_CR_MDMAT*/ - break; - default: - break; - } -} - - - -/** - * @brief Handle HASH processing Timeout. - * @param hhash HASH handle. - * @param Flag specifies the HASH flag to check. - * @param Status the Flag status (SET or RESET). - * @param Timeout Timeout duration. - * @retval HAL status - */ -static HAL_StatusTypeDef HASH_WaitOnFlagUntilTimeout(HASH_HandleTypeDef *hhash, uint32_t Flag, FlagStatus Status, - uint32_t Timeout) -{ - uint32_t tickstart = HAL_GetTick(); - - /* Wait until flag is set */ - if (Status == RESET) - { - while (__HAL_HASH_GET_FLAG(Flag) == RESET) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Set State to Ready to be able to restart later on */ - hhash->State = HAL_HASH_STATE_READY; - /* Store time out issue in handle status */ - hhash->Status = HAL_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - return HAL_TIMEOUT; - } - } - } - } - else - { - while (__HAL_HASH_GET_FLAG(Flag) != RESET) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - /* Set State to Ready to be able to restart later on */ - hhash->State = HAL_HASH_STATE_READY; - /* Store time out issue in handle status */ - hhash->Status = HAL_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - return HAL_TIMEOUT; - } - } - } - } - return HAL_OK; -} - - -/** - * @brief HASH processing in interruption mode. - * @param hhash HASH handle. - * @note HASH_IT() regularly reads hhash->SuspendRequest to check whether - * or not the HASH processing must be suspended. If this is the case, the - * processing is suspended when possible and the Peripheral feeding point reached at - * suspension time is stored in the handle for resumption later on. - * @retval HAL status - */ -static HAL_StatusTypeDef HASH_IT(HASH_HandleTypeDef *hhash) -{ - if (hhash->State == HAL_HASH_STATE_BUSY) - { - /* ITCounter must not be equal to 0 at this point. Report an error if this is the case. */ - if (hhash->HashITCounter == 0U) - { - /* Disable Interrupts */ - __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); - /* HASH state set back to Ready to prevent any issue in user code - present in HAL_HASH_ErrorCallback() */ - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - else if (hhash->HashITCounter == 1U) - { - /* This is the first call to HASH_IT, the first input data are about to be - entered in the Peripheral. A specific processing is carried out at this point to - start-up the processing. */ - hhash->HashITCounter = 2U; - } - else - { - /* Cruise speed reached, HashITCounter remains equal to 3 until the end of - the HASH processing or the end of the current step for HMAC processing. */ - hhash->HashITCounter = 3U; - } - - /* If digest is ready */ - if (__HAL_HASH_GET_FLAG(HASH_FLAG_DCIS)) - { - /* Read the digest */ - HASH_GetDigest(hhash->pHashOutBuffPtr, HASH_DIGEST_LENGTH()); - - /* Disable Interrupts */ - __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_READY; - /* Reset HASH state machine */ - hhash->Phase = HAL_HASH_PHASE_READY; - /* Call digest computation complete call back */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - hhash->DgstCpltCallback(hhash); -#else - HAL_HASH_DgstCpltCallback(hhash); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - return HAL_OK; - } - - /* If Peripheral ready to accept new data */ - if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS)) - { - - /* If the suspension flag has been raised and if the processing is not about - to end, suspend processing */ - if ((hhash->HashInCount != 0U) && (hhash->SuspendRequest == HAL_HASH_SUSPEND)) - { - /* Disable Interrupts */ - __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); - - /* Reset SuspendRequest */ - hhash->SuspendRequest = HAL_HASH_SUSPEND_NONE; - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_SUSPENDED; - - return HAL_OK; - } - - /* Enter input data in the Peripheral through HASH_Write_Block_Data() call and - check whether the digest calculation has been triggered */ - if (HASH_Write_Block_Data(hhash) == HASH_DIGEST_CALCULATION_STARTED) - { - /* Call Input data transfer complete call back - (called at the end of each step for HMAC) */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - hhash->InCpltCallback(hhash); -#else - HAL_HASH_InCpltCallback(hhash); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) - { - /* Wait until Peripheral is not busy anymore */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, HASH_TIMEOUTVALUE) != HAL_OK) - { - /* Disable Interrupts */ - __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); - return HAL_TIMEOUT; - } - /* Initialization start for HMAC STEP 2 */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_2; /* Move phase from Step 1 to Step 2 */ - __HAL_HASH_SET_NBVALIDBITS(hhash->HashBuffSize); /* Set NBLW for the input message */ - hhash->HashInCount = hhash->HashBuffSize; /* Set the input data size (in bytes) */ - hhash->pHashInBuffPtr = hhash->pHashMsgBuffPtr; /* Set the input data address */ - hhash->HashITCounter = 1; /* Set ITCounter to 1 to indicate the start - of a new phase */ - __HAL_HASH_ENABLE_IT(HASH_IT_DINI); /* Enable IT (was disabled in HASH_Write_Block_Data) */ - } - else if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2) - { - /* Wait until Peripheral is not busy anymore */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, HASH_TIMEOUTVALUE) != HAL_OK) - { - /* Disable Interrupts */ - __HAL_HASH_DISABLE_IT(HASH_IT_DINI | HASH_IT_DCI); - return HAL_TIMEOUT; - } - /* Initialization start for HMAC STEP 3 */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_3; /* Move phase from Step 2 to Step 3 */ - __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); /* Set NBLW for the key */ - hhash->HashInCount = hhash->Init.KeySize; /* Set the key size (in bytes) */ - hhash->pHashInBuffPtr = hhash->Init.pKey; /* Set the key address */ - hhash->HashITCounter = 1; /* Set ITCounter to 1 to indicate the start - of a new phase */ - __HAL_HASH_ENABLE_IT(HASH_IT_DINI); /* Enable IT (was disabled in HASH_Write_Block_Data) */ - } - else - { - /* Nothing to do */ - } - } /* if (HASH_Write_Block_Data(hhash) == HASH_DIGEST_CALCULATION_STARTED) */ - } /* if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS))*/ - - /* Return function status */ - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - - -/** - * @brief Write a block of data in HASH Peripheral in interruption mode. - * @param hhash HASH handle. - * @note HASH_Write_Block_Data() is called under interruption by HASH_IT(). - * @retval HAL status - */ -static uint32_t HASH_Write_Block_Data(HASH_HandleTypeDef *hhash) -{ - uint32_t inputaddr; - uint32_t buffercounter; - uint32_t inputcounter; - uint32_t ret = HASH_DIGEST_CALCULATION_NOT_STARTED; - - /* If there are more than 64 bytes remaining to be entered */ - if (hhash->HashInCount > 64U) - { - inputaddr = (uint32_t)hhash->pHashInBuffPtr; - /* Write the Input block in the Data IN register - (16 32-bit words, or 64 bytes are entered) */ - for (buffercounter = 0U; buffercounter < 64U; buffercounter += 4U) - { - HASH->DIN = *(uint32_t *)inputaddr; - inputaddr += 4U; - } - /* If this is the start of input data entering, an additional word - must be entered to start up the HASH processing */ - if (hhash->HashITCounter == 2U) - { - HASH->DIN = *(uint32_t *)inputaddr; - if (hhash->HashInCount >= 68U) - { - /* There are still data waiting to be entered in the Peripheral. - Decrement buffer counter and set pointer to the proper - memory location for the next data entering round. */ - hhash->HashInCount -= 68U; - hhash->pHashInBuffPtr += 68U; - } - else - { - /* All the input buffer has been fed to the HW. */ - hhash->HashInCount = 0U; - } - } - else - { - /* 64 bytes have been entered and there are still some remaining: - Decrement buffer counter and set pointer to the proper - memory location for the next data entering round.*/ - hhash->HashInCount -= 64U; - hhash->pHashInBuffPtr += 64U; - } - } - else - { - /* 64 or less bytes remain to be entered. This is the last - data entering round. */ - - /* Get the buffer address */ - inputaddr = (uint32_t)hhash->pHashInBuffPtr; - /* Get the buffer counter */ - inputcounter = hhash->HashInCount; - /* Disable Interrupts */ - __HAL_HASH_DISABLE_IT(HASH_IT_DINI); - - /* Write the Input block in the Data IN register */ - for (buffercounter = 0U; buffercounter < ((inputcounter + 3U) / 4U); buffercounter++) - { - HASH->DIN = *(uint32_t *)inputaddr; - inputaddr += 4U; - } - - if (hhash->Accumulation == 1U) - { - /* Field accumulation is set, API only feeds data to the Peripheral and under interruption. - The digest computation will be started when the last buffer data are entered. */ - - /* Reset multi buffers accumulation flag */ - hhash->Accumulation = 0U; - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_READY; - /* Call Input data transfer complete call back */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - hhash->InCpltCallback(hhash); -#else - HAL_HASH_InCpltCallback(hhash); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - } - else - { - /* Start the Digest calculation */ - __HAL_HASH_START_DIGEST(); - /* Return indication that digest calculation has started: - this return value triggers the call to Input data transfer - complete call back as well as the proper transition from - one step to another in HMAC mode. */ - ret = HASH_DIGEST_CALCULATION_STARTED; - } - /* Reset buffer counter */ - hhash->HashInCount = 0; - } - - /* Return whether or digest calculation has started */ - return ret; -} - -/** - * @brief HMAC processing in polling mode. - * @param hhash HASH handle. - * @param Timeout Timeout value. - * @retval HAL status - */ -static HAL_StatusTypeDef HMAC_Processing(HASH_HandleTypeDef *hhash, uint32_t Timeout) -{ - /* Ensure first that Phase is correct */ - if ((hhash->Phase != HAL_HASH_PHASE_HMAC_STEP_1) && (hhash->Phase != HAL_HASH_PHASE_HMAC_STEP_2) - && (hhash->Phase != HAL_HASH_PHASE_HMAC_STEP_3)) - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_READY; - - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - return HAL_ERROR; - } - - /* HMAC Step 1 processing */ - if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) - { - /************************** STEP 1 ******************************************/ - /* Configure the Number of valid bits in last word of the message */ - __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); - - /* Write input buffer in Data register */ - hhash->Status = HASH_WriteData(hhash, hhash->pHashKeyBuffPtr, hhash->HashKeyCount); - if (hhash->Status != HAL_OK) - { - return hhash->Status; - } - - /* Check whether or not key entering process has been suspended */ - if (hhash->State == HAL_HASH_STATE_SUSPENDED) - { - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - /* Stop right there and return function status */ - return HAL_OK; - } - - /* No processing suspension at this point: set DCAL bit. */ - __HAL_HASH_START_DIGEST(); - - /* Wait for BUSY flag to be cleared */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* Move from Step 1 to Step 2 */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_2; - - } - - /* HMAC Step 2 processing. - After phase check, HMAC_Processing() may - - directly start up from this point in resumption case - if the same Step 2 processing was suspended previously - - or fall through from the Step 1 processing carried out hereabove */ - if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2) - { - /************************** STEP 2 ******************************************/ - /* Configure the Number of valid bits in last word of the message */ - __HAL_HASH_SET_NBVALIDBITS(hhash->HashBuffSize); - - /* Write input buffer in Data register */ - hhash->Status = HASH_WriteData(hhash, hhash->pHashInBuffPtr, hhash->HashInCount); - if (hhash->Status != HAL_OK) - { - return hhash->Status; - } - - /* Check whether or not data entering process has been suspended */ - if (hhash->State == HAL_HASH_STATE_SUSPENDED) - { - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - /* Stop right there and return function status */ - return HAL_OK; - } - - /* No processing suspension at this point: set DCAL bit. */ - __HAL_HASH_START_DIGEST(); - - /* Wait for BUSY flag to be cleared */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_BUSY, SET, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* Move from Step 2 to Step 3 */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_3; - /* In case Step 1 phase was suspended then resumed, - set again Key input buffers and size before moving to - next step */ - hhash->pHashKeyBuffPtr = hhash->Init.pKey; - hhash->HashKeyCount = hhash->Init.KeySize; - } - - - /* HMAC Step 3 processing. - After phase check, HMAC_Processing() may - - directly start up from this point in resumption case - if the same Step 3 processing was suspended previously - - or fall through from the Step 2 processing carried out hereabove */ - if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_3) - { - /************************** STEP 3 ******************************************/ - /* Configure the Number of valid bits in last word of the message */ - __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); - - /* Write input buffer in Data register */ - hhash->Status = HASH_WriteData(hhash, hhash->pHashKeyBuffPtr, hhash->HashKeyCount); - if (hhash->Status != HAL_OK) - { - return hhash->Status; - } - - /* Check whether or not key entering process has been suspended */ - if (hhash->State == HAL_HASH_STATE_SUSPENDED) - { - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - /* Stop right there and return function status */ - return HAL_OK; - } - - /* No processing suspension at this point: start the Digest calculation. */ - __HAL_HASH_START_DIGEST(); - - /* Wait for DCIS flag to be set */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_DCIS, RESET, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* Read the message digest */ - HASH_GetDigest(hhash->pHashOutBuffPtr, HASH_DIGEST_LENGTH()); - - /* Reset HASH state machine */ - hhash->Phase = HAL_HASH_PHASE_READY; - } - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_READY; - - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - return HAL_OK; -} - - -/** - * @brief Initialize the HASH peripheral, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. - * @param Timeout Timeout value. - * @param Algorithm HASH algorithm. - * @retval HAL status - */ -HAL_StatusTypeDef HASH_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout, uint32_t Algorithm) -{ - uint8_t *pInBuffer_tmp; /* input data address, input parameter of HASH_WriteData() */ - uint32_t Size_tmp; /* input data size (in bytes), input parameter of HASH_WriteData() */ - HAL_HASH_StateTypeDef State_tmp = hhash->State; - - - /* Initiate HASH processing in case of start or resumption */ - if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) - { - /* Check input parameters */ - if ((pInBuffer == NULL) || (pOutBuffer == NULL)) - { - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* Check if initialization phase has not been already performed */ - if (hhash->Phase == HAL_HASH_PHASE_READY) - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); - - /* Configure the number of valid bits in last word of the message */ - __HAL_HASH_SET_NBVALIDBITS(Size); - - /* pInBuffer_tmp and Size_tmp are initialized to be used afterwards as - input parameters of HASH_WriteData() */ - pInBuffer_tmp = pInBuffer; /* pInBuffer_tmp is set to the input data address */ - Size_tmp = Size; /* Size_tmp contains the input data size in bytes */ - - /* Set the phase */ - hhash->Phase = HAL_HASH_PHASE_PROCESS; - } - else if (hhash->Phase == HAL_HASH_PHASE_PROCESS) - { - /* if the Peripheral has already been initialized, two cases are possible */ - - /* Process resumption time ... */ - if (hhash->State == HAL_HASH_STATE_SUSPENDED) - { - /* Since this is resumption, pInBuffer_tmp and Size_tmp are not set - to the API input parameters but to those saved beforehand by HASH_WriteData() - when the processing was suspended */ - pInBuffer_tmp = hhash->pHashInBuffPtr; - Size_tmp = hhash->HashInCount; - } - /* ... or multi-buffer HASH processing end */ - else - { - /* pInBuffer_tmp and Size_tmp are initialized to be used afterwards as - input parameters of HASH_WriteData() */ - pInBuffer_tmp = pInBuffer; - Size_tmp = Size; - /* Configure the number of valid bits in last word of the message */ - __HAL_HASH_SET_NBVALIDBITS(Size); - } - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - } - else - { - /* Phase error */ - hhash->State = HAL_HASH_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - return HAL_ERROR; - } - - - /* Write input buffer in Data register */ - hhash->Status = HASH_WriteData(hhash, pInBuffer_tmp, Size_tmp); - if (hhash->Status != HAL_OK) - { - return hhash->Status; - } - - /* If the process has not been suspended, carry on to digest calculation */ - if (hhash->State != HAL_HASH_STATE_SUSPENDED) - { - /* Start the Digest calculation */ - __HAL_HASH_START_DIGEST(); - - /* Wait for DCIS flag to be set */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_DCIS, RESET, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* Read the message digest */ - HASH_GetDigest(pOutBuffer, HASH_DIGEST_LENGTH()); - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_READY; - - /* Reset HASH state machine */ - hhash->Phase = HAL_HASH_PHASE_READY; - - } - - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - return HAL_OK; - - } - else - { - return HAL_BUSY; - } -} - - -/** - * @brief If not already done, initialize the HASH peripheral then - * processes pInBuffer. - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @param Algorithm HASH algorithm. - * @retval HAL status - */ -HAL_StatusTypeDef HASH_Accumulate(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm) -{ - uint8_t *pInBuffer_tmp; /* input data address, input parameter of HASH_WriteData() */ - uint32_t Size_tmp; /* input data size (in bytes), input parameter of HASH_WriteData() */ - HAL_HASH_StateTypeDef State_tmp = hhash->State; - - /* Make sure the input buffer size (in bytes) is a multiple of 4 */ - if ((Size % 4U) != 0U) - { - return HAL_ERROR; - } - - /* Initiate HASH processing in case of start or resumption */ - if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) - { - /* Check input parameters */ - if ((pInBuffer == NULL) || (Size == 0U)) - { - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* If resuming the HASH processing */ - if (hhash->State == HAL_HASH_STATE_SUSPENDED) - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Since this is resumption, pInBuffer_tmp and Size_tmp are not set - to the API input parameters but to those saved beforehand by HASH_WriteData() - when the processing was suspended */ - pInBuffer_tmp = hhash->pHashInBuffPtr; /* pInBuffer_tmp is set to the input data address */ - Size_tmp = hhash->HashInCount; /* Size_tmp contains the input data size in bytes */ - - } - else - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* pInBuffer_tmp and Size_tmp are initialized to be used afterwards as - input parameters of HASH_WriteData() */ - pInBuffer_tmp = pInBuffer; /* pInBuffer_tmp is set to the input data address */ - Size_tmp = Size; /* Size_tmp contains the input data size in bytes */ - - /* Check if initialization phase has already be performed */ - if (hhash->Phase == HAL_HASH_PHASE_READY) - { - /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); - } - - /* Set the phase */ - hhash->Phase = HAL_HASH_PHASE_PROCESS; - - } - - /* Write input buffer in Data register */ - hhash->Status = HASH_WriteData(hhash, pInBuffer_tmp, Size_tmp); - if (hhash->Status != HAL_OK) - { - return hhash->Status; - } - - /* If the process has not been suspended, move the state to Ready */ - if (hhash->State != HAL_HASH_STATE_SUSPENDED) - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_READY; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - return HAL_OK; - - } - else - { - return HAL_BUSY; - } - - -} - - -/** - * @brief If not already done, initialize the HASH peripheral then - * processes pInBuffer in interruption mode. - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @param Algorithm HASH algorithm. - * @retval HAL status - */ -HAL_StatusTypeDef HASH_Accumulate_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm) -{ - HAL_HASH_StateTypeDef State_tmp = hhash->State; - __IO uint32_t inputaddr = (uint32_t) pInBuffer; - uint32_t SizeVar = Size; - - /* Make sure the input buffer size (in bytes) is a multiple of 4 */ - if ((Size % 4U) != 0U) - { - return HAL_ERROR; - } - - /* Initiate HASH processing in case of start or resumption */ - if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) - { - /* Check input parameters */ - if ((pInBuffer == NULL) || (Size == 0U)) - { - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* If resuming the HASH processing */ - if (hhash->State == HAL_HASH_STATE_SUSPENDED) - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - } - else - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Check if initialization phase has already be performed */ - if (hhash->Phase == HAL_HASH_PHASE_READY) - { - /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); - hhash->HashITCounter = 1; - } - else - { - hhash->HashITCounter = 3; /* 'cruise-speed' reached during a previous buffer processing */ - } - - /* Set the phase */ - hhash->Phase = HAL_HASH_PHASE_PROCESS; - - /* If DINIS is equal to 0 (for example if an incomplete block has been previously - fed to the Peripheral), the DINIE interruption won't be triggered when DINIE is set. - Therefore, first words are manually entered until DINIS raises, or until there - is not more data to enter. */ - while ((!(__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS))) && (SizeVar > 0U)) - { - - /* Write input data 4 bytes at a time */ - HASH->DIN = *(uint32_t *)inputaddr; - inputaddr += 4U; - SizeVar -= 4U; - } - - /* If DINIS is still not set or if all the data have been fed, stop here */ - if ((!(__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS))) || (SizeVar == 0U)) - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_READY; - - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - return HAL_OK; - } - - /* otherwise, carry on in interrupt-mode */ - hhash->HashInCount = SizeVar; /* Counter used to keep track of number of data - to be fed to the Peripheral */ - hhash->pHashInBuffPtr = (uint8_t *)inputaddr; /* Points at data which will be fed to the Peripheral at - the next interruption */ - /* In case of suspension, hhash->HashInCount and hhash->pHashInBuffPtr contain - the information describing where the HASH process is stopped. - These variables are used later on to resume the HASH processing at the - correct location. */ - - } - - /* Set multi buffers accumulation flag */ - hhash->Accumulation = 1U; - - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Enable Data Input interrupt */ - __HAL_HASH_ENABLE_IT(HASH_IT_DINI); - - /* Return function status */ - return HAL_OK; - - } - else - { - return HAL_BUSY; - } - -} - - - -/** - * @brief Initialize the HASH peripheral, next process pInBuffer then - * read the computed digest in interruption mode. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. - * @param Algorithm HASH algorithm. - * @retval HAL status - */ -HAL_StatusTypeDef HASH_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Algorithm) -{ - HAL_HASH_StateTypeDef State_tmp = hhash->State; - __IO uint32_t inputaddr = (uint32_t) pInBuffer; - uint32_t polling_step = 0U; - uint32_t initialization_skipped = 0U; - uint32_t SizeVar = Size; - - /* If State is ready or suspended, start or resume IT-based HASH processing */ - if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) - { - /* Check input parameters */ - if ((pInBuffer == NULL) || (Size == 0U) || (pOutBuffer == NULL)) - { - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Initialize IT counter */ - hhash->HashITCounter = 1; - - /* Check if initialization phase has already be performed */ - if (hhash->Phase == HAL_HASH_PHASE_READY) - { - /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); - - /* Configure the number of valid bits in last word of the message */ - __HAL_HASH_SET_NBVALIDBITS(SizeVar); - - - hhash->HashInCount = SizeVar; /* Counter used to keep track of number of data - to be fed to the Peripheral */ - hhash->pHashInBuffPtr = pInBuffer; /* Points at data which will be fed to the Peripheral at - the next interruption */ - /* In case of suspension, hhash->HashInCount and hhash->pHashInBuffPtr contain - the information describing where the HASH process is stopped. - These variables are used later on to resume the HASH processing at the - correct location. */ - - hhash->pHashOutBuffPtr = pOutBuffer; /* Points at the computed digest */ - } - else - { - initialization_skipped = 1; /* info user later on in case of multi-buffer */ - } - - /* Set the phase */ - hhash->Phase = HAL_HASH_PHASE_PROCESS; - - /* If DINIS is equal to 0 (for example if an incomplete block has been previously - fed to the Peripheral), the DINIE interruption won't be triggered when DINIE is set. - Therefore, first words are manually entered until DINIS raises. */ - while ((!(__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS))) && (SizeVar > 3U)) - { - polling_step = 1U; /* note that some words are entered before enabling the interrupt */ - - /* Write input data 4 bytes at a time */ - HASH->DIN = *(uint32_t *)inputaddr; - inputaddr += 4U; - SizeVar -= 4U; - } - - if (polling_step == 1U) - { - if (SizeVar == 0U) - { - /* If all the data have been entered at this point, it only remains to - read the digest */ - hhash->pHashOutBuffPtr = pOutBuffer; /* Points at the computed digest */ - - /* Start the Digest calculation */ - __HAL_HASH_START_DIGEST(); - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Enable Interrupts */ - __HAL_HASH_ENABLE_IT(HASH_IT_DCI); - - /* Return function status */ - return HAL_OK; - } - else if (__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS)) - { - /* It remains data to enter and the Peripheral is ready to trigger DINIE, - carry on as usual. - Update HashInCount and pHashInBuffPtr accordingly. */ - hhash->HashInCount = SizeVar; - hhash->pHashInBuffPtr = (uint8_t *)inputaddr; - __HAL_HASH_SET_NBVALIDBITS( - SizeVar); /* Update the configuration of the number of valid bits in last word of the message */ - hhash->pHashOutBuffPtr = pOutBuffer; /* Points at the computed digest */ - if (initialization_skipped == 1U) - { - hhash->HashITCounter = 3; /* 'cruise-speed' reached during a previous buffer processing */ - } - } - else - { - /* DINIS is not set but it remains a few data to enter (not enough for a full word). - Manually enter the last bytes before enabling DCIE. */ - __HAL_HASH_SET_NBVALIDBITS(SizeVar); - HASH->DIN = *(uint32_t *)inputaddr; - - /* Start the Digest calculation */ - hhash->pHashOutBuffPtr = pOutBuffer; /* Points at the computed digest */ - __HAL_HASH_START_DIGEST(); - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Enable Interrupts */ - __HAL_HASH_ENABLE_IT(HASH_IT_DCI); - - /* Return function status */ - return HAL_OK; - } - } /* if (polling_step == 1) */ - - - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Enable Interrupts */ - __HAL_HASH_ENABLE_IT(HASH_IT_DINI | HASH_IT_DCI); - - /* Return function status */ - return HAL_OK; - } - else - { - return HAL_BUSY; - } - -} - - -/** - * @brief Initialize the HASH peripheral then initiate a DMA transfer - * to feed the input buffer to the Peripheral. - * @note If MDMAT bit is set before calling this function (multi-buffer - * HASH processing case), the input buffer size (in bytes) must be - * a multiple of 4 otherwise, the HASH digest computation is corrupted. - * For the processing of the last buffer of the thread, MDMAT bit must - * be reset and the buffer length (in bytes) doesn't have to be a - * multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param Algorithm HASH algorithm. - * @retval HAL status - */ -HAL_StatusTypeDef HASH_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm) -{ - uint32_t inputaddr; - uint32_t inputSize; - HAL_StatusTypeDef status ; - HAL_HASH_StateTypeDef State_tmp = hhash->State; - - #if defined (HASH_CR_MDMAT) - /* Make sure the input buffer size (in bytes) is a multiple of 4 when MDMAT bit is set - (case of multi-buffer HASH processing) */ - assert_param(IS_HASH_DMA_MULTIBUFFER_SIZE(Size)); - #endif /* MDMA defined*/ - /* If State is ready or suspended, start or resume polling-based HASH processing */ - if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) - { - /* Check input parameters */ - if ((pInBuffer == NULL) || (Size == 0U) || - /* Check phase coherency. Phase must be - either READY (fresh start) - or PROCESS (multi-buffer HASH management) */ - ((hhash->Phase != HAL_HASH_PHASE_READY) && (!(IS_HASH_PROCESSING(hhash))))) - { - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* If not a resumption case */ - if (hhash->State == HAL_HASH_STATE_READY) - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Check if initialization phase has already been performed. - If Phase is already set to HAL_HASH_PHASE_PROCESS, this means the - API is processing a new input data message in case of multi-buffer HASH - computation. */ - if (hhash->Phase == HAL_HASH_PHASE_READY) - { - /* Select the HASH algorithm, clear HMAC mode and long key selection bit, reset the HASH processor core */ - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, Algorithm | HASH_CR_INIT); - - /* Set the phase */ - hhash->Phase = HAL_HASH_PHASE_PROCESS; - } - - /* Configure the Number of valid bits in last word of the message */ - __HAL_HASH_SET_NBVALIDBITS(Size); - - inputaddr = (uint32_t)pInBuffer; /* DMA transfer start address */ - inputSize = Size; /* DMA transfer size (in bytes) */ - - /* In case of suspension request, save the starting parameters */ - hhash->pHashInBuffPtr = pInBuffer; /* DMA transfer start address */ - hhash->HashInCount = Size; /* DMA transfer size (in bytes) */ - - } - /* If resumption case */ - else - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Resumption case, inputaddr and inputSize are not set to the API input parameters - but to those saved beforehand by HAL_HASH_DMAFeed_ProcessSuspend() when the - processing was suspended */ - inputaddr = (uint32_t)hhash->pHashInBuffPtr; /* DMA transfer start address */ - inputSize = hhash->HashInCount; /* DMA transfer size (in bytes) */ - - } - - /* Set the HASH DMA transfer complete callback */ - hhash->hdmain->XferCpltCallback = HASH_DMAXferCplt; - /* Set the DMA error callback */ - hhash->hdmain->XferErrorCallback = HASH_DMAError; - - /* Store number of words already pushed to manage proper DMA processing suspension */ - hhash->NbWordsAlreadyPushed = HASH_NBW_PUSHED(); - - /* Enable the DMA In DMA stream */ - status = HAL_DMA_Start_IT(hhash->hdmain, inputaddr, (uint32_t)&HASH->DIN, \ - (((inputSize % 4U) != 0U) ? ((inputSize + (4U - (inputSize % 4U))) / 4U) : \ - (inputSize / 4U))); - - /* Enable DMA requests */ - SET_BIT(HASH->CR, HASH_CR_DMAE); - - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - if (status != HAL_OK) - { - /* Update HASH state machine to error */ - hhash->State = HAL_HASH_STATE_ERROR; - } - - return status; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Return the computed digest. - * @note The API waits for DCIS to be set then reads the computed digest. - * @param hhash HASH handle. - * @param pOutBuffer pointer to the computed digest. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HASH_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) -{ - - if (hhash->State == HAL_HASH_STATE_READY) - { - /* Check parameter */ - if (pOutBuffer == NULL) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* Change the HASH state to busy */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Wait for DCIS flag to be set */ - if (HASH_WaitOnFlagUntilTimeout(hhash, HASH_FLAG_DCIS, RESET, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* Read the message digest */ - HASH_GetDigest(pOutBuffer, HASH_DIGEST_LENGTH()); - - /* Change the HASH state to ready */ - hhash->State = HAL_HASH_STATE_READY; - - /* Reset HASH state machine */ - hhash->Phase = HAL_HASH_PHASE_READY; - - /* Process UnLock */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - return HAL_OK; - - } - else - { - return HAL_BUSY; - } - -} - - -/** - * @brief Initialize the HASH peripheral in HMAC mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. - * @param Timeout Timeout value. - * @param Algorithm HASH algorithm. - * @retval HAL status - */ -HAL_StatusTypeDef HMAC_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout, uint32_t Algorithm) -{ - HAL_HASH_StateTypeDef State_tmp = hhash->State; - - /* If State is ready or suspended, start or resume polling-based HASH processing */ - if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) - { - /* Check input parameters */ - if ((pInBuffer == NULL) || (Size == 0U) || (hhash->Init.pKey == NULL) || (hhash->Init.KeySize == 0U) - || (pOutBuffer == NULL)) - { - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Check if initialization phase has already be performed */ - if (hhash->Phase == HAL_HASH_PHASE_READY) - { - /* Check if key size is larger than 64 bytes, accordingly set LKEY and the other setting bits */ - if (hhash->Init.KeySize > 64U) - { - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, - Algorithm | HASH_ALGOMODE_HMAC | HASH_HMAC_KEYTYPE_LONGKEY | HASH_CR_INIT); - } - else - { - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, - Algorithm | HASH_ALGOMODE_HMAC | HASH_CR_INIT); - } - /* Set the phase to Step 1 */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_1; - /* Resort to hhash internal fields to feed the Peripheral. - Parameters will be updated in case of suspension to contain the proper - information at resumption time. */ - hhash->pHashOutBuffPtr = pOutBuffer; /* Output digest address */ - hhash->pHashInBuffPtr = pInBuffer; /* Input data address, HMAC_Processing input - parameter for Step 2 */ - hhash->HashInCount = Size; /* Input data size, HMAC_Processing input - parameter for Step 2 */ - hhash->HashBuffSize = Size; /* Store the input buffer size for the whole HMAC process*/ - hhash->pHashKeyBuffPtr = hhash->Init.pKey; /* Key address, HMAC_Processing input parameter for Step - 1 and Step 3 */ - hhash->HashKeyCount = hhash->Init.KeySize; /* Key size, HMAC_Processing input parameter for Step 1 - and Step 3 */ - } - - /* Carry out HMAC processing */ - return HMAC_Processing(hhash, Timeout); - - } - else - { - return HAL_BUSY; - } -} - - - -/** - * @brief Initialize the HASH peripheral in HMAC mode, next process pInBuffer then - * read the computed digest in interruption mode. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. - * @param Algorithm HASH algorithm. - * @retval HAL status - */ -HAL_StatusTypeDef HMAC_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Algorithm) -{ - HAL_HASH_StateTypeDef State_tmp = hhash->State; - - /* If State is ready or suspended, start or resume IT-based HASH processing */ - if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) - { - /* Check input parameters */ - if ((pInBuffer == NULL) || (Size == 0U) || (hhash->Init.pKey == NULL) || (hhash->Init.KeySize == 0U) - || (pOutBuffer == NULL)) - { - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Initialize IT counter */ - hhash->HashITCounter = 1; - - /* Check if initialization phase has already be performed */ - if (hhash->Phase == HAL_HASH_PHASE_READY) - { - /* Check if key size is larger than 64 bytes, accordingly set LKEY and the other setting bits */ - if (hhash->Init.KeySize > 64U) - { - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, - Algorithm | HASH_ALGOMODE_HMAC | HASH_HMAC_KEYTYPE_LONGKEY | HASH_CR_INIT); - } - else - { - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, - Algorithm | HASH_ALGOMODE_HMAC | HASH_CR_INIT); - } - - /* Resort to hhash internal fields hhash->pHashInBuffPtr and hhash->HashInCount - to feed the Peripheral whatever the HMAC step. - Lines below are set to start HMAC Step 1 processing where key is entered first. */ - hhash->HashInCount = hhash->Init.KeySize; /* Key size */ - hhash->pHashInBuffPtr = hhash->Init.pKey ; /* Key address */ - - /* Store input and output parameters in handle fields to manage steps transition - or possible HMAC suspension/resumption */ - hhash->pHashKeyBuffPtr = hhash->Init.pKey; /* Key address */ - hhash->pHashMsgBuffPtr = pInBuffer; /* Input message address */ - hhash->HashBuffSize = Size; /* Input message size (in bytes) */ - hhash->pHashOutBuffPtr = pOutBuffer; /* Output digest address */ - - /* Configure the number of valid bits in last word of the key */ - __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); - - /* Set the phase to Step 1 */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_1; - } - else if ((hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_1) || (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_3)) - { - /* Restart IT-based HASH processing after Step 1 or Step 3 suspension */ - - } - else if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2) - { - /* Restart IT-based HASH processing after Step 2 suspension */ - - } - else - { - /* Error report as phase incorrect */ - /* Process Unlock */ - __HAL_UNLOCK(hhash); - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - /* Process Unlock */ - __HAL_UNLOCK(hhash); - - /* Enable Interrupts */ - __HAL_HASH_ENABLE_IT(HASH_IT_DINI | HASH_IT_DCI); - - /* Return function status */ - return HAL_OK; - } - else - { - return HAL_BUSY; - } - -} - - - -/** - * @brief Initialize the HASH peripheral in HMAC mode then initiate the required - * DMA transfers to feed the key and the input buffer to the Peripheral. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note In case of multi-buffer HMAC processing, the input buffer size (in bytes) must - * be a multiple of 4 otherwise, the HASH digest computation is corrupted. - * Only the length of the last buffer of the thread doesn't have to be a - * multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param Algorithm HASH algorithm. - * @retval HAL status - */ -HAL_StatusTypeDef HMAC_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm) -{ - uint32_t inputaddr; - uint32_t inputSize; - HAL_StatusTypeDef status ; - HAL_HASH_StateTypeDef State_tmp = hhash->State; - /* Make sure the input buffer size (in bytes) is a multiple of 4 when digest calculation - is disabled (multi-buffer HMAC processing, MDMAT bit to be set) */ - assert_param(IS_HMAC_DMA_MULTIBUFFER_SIZE(hhash, Size)); - /* If State is ready or suspended, start or resume DMA-based HASH processing */ - if ((State_tmp == HAL_HASH_STATE_READY) || (State_tmp == HAL_HASH_STATE_SUSPENDED)) - { - /* Check input parameters */ - if ((pInBuffer == NULL) || (Size == 0U) || (hhash->Init.pKey == NULL) || (hhash->Init.KeySize == 0U) || - /* Check phase coherency. Phase must be - either READY (fresh start) - or one of HMAC PROCESS steps (multi-buffer HASH management) */ - ((hhash->Phase != HAL_HASH_PHASE_READY) && (!(IS_HMAC_PROCESSING(hhash))))) - { - hhash->State = HAL_HASH_STATE_READY; - return HAL_ERROR; - } - - - /* Process Locked */ - __HAL_LOCK(hhash); - - /* If not a case of resumption after suspension */ - if (hhash->State == HAL_HASH_STATE_READY) - { - /* Check whether or not initialization phase has already be performed */ - if (hhash->Phase == HAL_HASH_PHASE_READY) - { - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; -#if defined(HASH_CR_MDMAT) - /* Check if key size is larger than 64 bytes, accordingly set LKEY and the other setting bits. - At the same time, ensure MDMAT bit is cleared. */ - if (hhash->Init.KeySize > 64U) - { - MODIFY_REG(HASH->CR, HASH_CR_MDMAT | HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, - Algorithm | HASH_ALGOMODE_HMAC | HASH_HMAC_KEYTYPE_LONGKEY | HASH_CR_INIT); - } - else - { - MODIFY_REG(HASH->CR, HASH_CR_MDMAT | HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, - Algorithm | HASH_ALGOMODE_HMAC | HASH_CR_INIT); - } -#else - /* Check if key size is larger than 64 bytes, accordingly set LKEY and the other setting bits */ - if (hhash->Init.KeySize > 64U) - { - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, - Algorithm | HASH_ALGOMODE_HMAC | HASH_HMAC_KEYTYPE_LONGKEY | HASH_CR_INIT); - } - else - { - MODIFY_REG(HASH->CR, HASH_CR_LKEY | HASH_CR_ALGO | HASH_CR_MODE | HASH_CR_INIT, - Algorithm | HASH_ALGOMODE_HMAC | HASH_CR_INIT); - } -#endif /* HASH_CR_MDMAT*/ - /* Store input aparameters in handle fields to manage steps transition - or possible HMAC suspension/resumption */ - hhash->HashInCount = hhash->Init.KeySize; /* Initial size for first DMA transfer (key size) */ - hhash->pHashKeyBuffPtr = hhash->Init.pKey; /* Key address */ - hhash->pHashInBuffPtr = hhash->Init.pKey ; /* First address passed to DMA (key address at Step 1) */ - hhash->pHashMsgBuffPtr = pInBuffer; /* Input data address */ - hhash->HashBuffSize = Size; /* input data size (in bytes) */ - - /* Set DMA input parameters */ - inputaddr = (uint32_t)(hhash->Init.pKey); /* Address passed to DMA (start by entering Key message) */ - inputSize = hhash->Init.KeySize; /* Size for first DMA transfer (in bytes) */ - - /* Configure the number of valid bits in last word of the key */ - __HAL_HASH_SET_NBVALIDBITS(hhash->Init.KeySize); - - /* Set the phase to Step 1 */ - hhash->Phase = HAL_HASH_PHASE_HMAC_STEP_1; - - } - else if (hhash->Phase == HAL_HASH_PHASE_HMAC_STEP_2) - { - /* Process a new input data message in case of multi-buffer HMAC processing - (this is not a resumption case) */ - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Save input parameters to be able to manage possible suspension/resumption */ - hhash->HashInCount = Size; /* Input message address */ - hhash->pHashInBuffPtr = pInBuffer; /* Input message size in bytes */ - - /* Set DMA input parameters */ - inputaddr = (uint32_t)pInBuffer; /* Input message address */ - inputSize = Size; /* Input message size in bytes */ - - if (hhash->DigestCalculationDisable == RESET) - { - /* This means this is the last buffer of the multi-buffer sequence: DCAL needs to be set. */ -#if defined(HASH_CR_MDMAT) - __HAL_HASH_RESET_MDMAT(); -#endif /* HASH_CR_MDMAT*/ - __HAL_HASH_SET_NBVALIDBITS(inputSize); - } - } - else - { - /* Phase not aligned with handle READY state */ - __HAL_UNLOCK(hhash); - /* Return function status */ - return HAL_ERROR; - } - } - else - { - /* Resumption case (phase may be Step 1, 2 or 3) */ - - /* Change the HASH state */ - hhash->State = HAL_HASH_STATE_BUSY; - - /* Set DMA input parameters at resumption location; - inputaddr and inputSize are not set to the API input parameters - but to those saved beforehand by HAL_HASH_DMAFeed_ProcessSuspend() when the - processing was suspended. */ - inputaddr = (uint32_t)(hhash->pHashInBuffPtr); /* Input message address */ - inputSize = hhash->HashInCount; /* Input message size in bytes */ - } - - - /* Set the HASH DMA transfer complete callback */ - hhash->hdmain->XferCpltCallback = HASH_DMAXferCplt; - /* Set the DMA error callback */ - hhash->hdmain->XferErrorCallback = HASH_DMAError; - - /* Store number of words already pushed to manage proper DMA processing suspension */ - hhash->NbWordsAlreadyPushed = HASH_NBW_PUSHED(); - - /* Enable the DMA In DMA stream */ - status = HAL_DMA_Start_IT(hhash->hdmain, inputaddr, (uint32_t)&HASH->DIN, \ - (((inputSize % 4U) != 0U) ? ((inputSize + (4U - (inputSize % 4U))) / 4U) \ - : (inputSize / 4U))); - /* Enable DMA requests */ - SET_BIT(HASH->CR, HASH_CR_DMAE); - - /* Process Unlocked */ - __HAL_UNLOCK(hhash); - - /* Return function status */ - if (status != HAL_OK) - { - /* Update HASH state machine to error */ - hhash->State = HAL_HASH_STATE_ERROR; - } - - /* Return function status */ - return status; - } - else - { - return HAL_BUSY; - } -} -/** - * @} - */ - -#endif /* HAL_HASH_MODULE_ENABLED */ - -/** - * @} - */ -#endif /* HASH*/ -/** - * @} - */ - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash_ex.c deleted file mode 100644 index e733f5ad7704a99..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hash_ex.c +++ /dev/null @@ -1,1043 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hash_ex.c - * @author MCD Application Team - * @brief Extended HASH HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the HASH peripheral for SHA-224 and SHA-256 - * algorithms: - * + HASH or HMAC processing in polling mode - * + HASH or HMAC processing in interrupt mode - * + HASH or HMAC processing in DMA mode - * Additionally, this file provides functions to manage HMAC - * multi-buffer DMA-based processing for MD-5, SHA-1, SHA-224 - * and SHA-256. - * - * - @verbatim - =============================================================================== - ##### HASH peripheral extended features ##### - =============================================================================== - [..] - The SHA-224 and SHA-256 HASH and HMAC processing can be carried out exactly - the same way as for SHA-1 or MD-5 algorithms. - (#) Three modes are available. - (##) Polling mode: processing APIs are blocking functions - i.e. they process the data and wait till the digest computation is finished, - e.g. HAL_HASHEx_xxx_Start() - (##) Interrupt mode: processing APIs are not blocking functions - i.e. they process the data under interrupt, - e.g. HAL_HASHEx_xxx_Start_IT() - (##) DMA mode: processing APIs are not blocking functions and the CPU is - not used for data transfer i.e. the data transfer is ensured by DMA, - e.g. HAL_HASHEx_xxx_Start_DMA(). Note that in DMA mode, a call to - HAL_HASHEx_xxx_Finish() is then required to retrieve the digest. - - (#)Multi-buffer processing is possible in polling, interrupt and DMA modes. - (##) In polling mode, only multi-buffer HASH processing is possible. - API HAL_HASHEx_xxx_Accumulate() must be called for each input buffer, except for the last one. - User must resort to HAL_HASHEx_xxx_Accumulate_End() to enter the last one and retrieve as - well the computed digest. - - (##) In interrupt mode, API HAL_HASHEx_xxx_Accumulate_IT() must be called for each input buffer, - except for the last one. - User must resort to HAL_HASHEx_xxx_Accumulate_End_IT() to enter the last one and retrieve as - well the computed digest. - - (##) In DMA mode, multi-buffer HASH and HMAC processing are possible. - - (+++) HASH processing: once initialization is done, MDMAT bit must be set through - __HAL_HASH_SET_MDMAT() macro. - From that point, each buffer can be fed to the Peripheral through HAL_HASHEx_xxx_Start_DMA() API. - Before entering the last buffer, reset the MDMAT bit with __HAL_HASH_RESET_MDMAT() - macro then wrap-up the HASH processing in feeding the last input buffer through the - same API HAL_HASHEx_xxx_Start_DMA(). The digest can then be retrieved with a call to - API HAL_HASHEx_xxx_Finish(). - - (+++) HMAC processing (MD-5, SHA-1, SHA-224 and SHA-256 must all resort to - extended functions): after initialization, the key and the first input buffer are entered - in the Peripheral with the API HAL_HMACEx_xxx_Step1_2_DMA(). This carries out HMAC step 1 and - starts step 2. - The following buffers are next entered with the API HAL_HMACEx_xxx_Step2_DMA(). At this - point, the HMAC processing is still carrying out step 2. - Then, step 2 for the last input buffer and step 3 are carried out by a single call - to HAL_HMACEx_xxx_Step2_3_DMA(). - - The digest can finally be retrieved with a call to API HAL_HASH_xxx_Finish() for - MD-5 and SHA-1, to HAL_HASHEx_xxx_Finish() for SHA-224 and SHA-256. - - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - - - - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (HASH) - -/** @defgroup HASHEx HASHEx - * @brief HASH HAL extended module driver. - * @{ - */ -#ifdef HAL_HASH_MODULE_ENABLED -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -#if defined (HASH_CR_MDMAT) - -/** @defgroup HASHEx_Exported_Functions HASH Extended Exported Functions - * @{ - */ - -/** @defgroup HASHEx_Exported_Functions_Group1 HASH extended processing functions in polling mode - * @brief HASH extended processing functions using polling mode. - * -@verbatim - =============================================================================== - ##### Polling mode HASH extended processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in polling mode - the hash value using one of the following algorithms: - (+) SHA224 - (++) HAL_HASHEx_SHA224_Start() - (++) HAL_HASHEx_SHA224_Accmlt() - (++) HAL_HASHEx_SHA224_Accmlt_End() - (+) SHA256 - (++) HAL_HASHEx_SHA256_Start() - (++) HAL_HASHEx_SHA256_Accmlt() - (++) HAL_HASHEx_SHA256_Accmlt_End() - - [..] For a single buffer to be hashed, user can resort to HAL_HASH_xxx_Start(). - - [..] In case of multi-buffer HASH processing (a single digest is computed while - several buffers are fed to the Peripheral), the user can resort to successive calls - to HAL_HASHEx_xxx_Accumulate() and wrap-up the digest computation by a call - to HAL_HASHEx_xxx_Accumulate_End(). - -@endverbatim - * @{ - */ - - -/** - * @brief Initialize the HASH peripheral in SHA224 mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. - * @param Timeout Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief If not already done, initialize the HASH peripheral in SHA224 mode then - * processes pInBuffer. - * @note Consecutive calls to HAL_HASHEx_SHA224_Accmlt() can be used to feed - * several input buffers back-to-back to the Peripheral that will yield a single - * HASH signature once all buffers have been entered. Wrap-up of input - * buffers feeding and retrieval of digest is done by a call to - * HAL_HASHEx_SHA224_Accmlt_End(). - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note Digest is not retrieved by this API, user must resort to HAL_HASHEx_SHA224_Accmlt_End() - * to read it, feeding at the same time the last input buffer to the Peripheral. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. Only HAL_HASHEx_SHA224_Accmlt_End() is able - * to manage the ending buffer with a length in bytes not a multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Accumulate(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief End computation of a single HASH signature after several calls to HAL_HASHEx_SHA224_Accmlt() API. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. - * @param Timeout Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief Initialize the HASH peripheral in SHA256 mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. - * @param Timeout Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA256); -} - -/** - * @brief If not already done, initialize the HASH peripheral in SHA256 mode then - * processes pInBuffer. - * @note Consecutive calls to HAL_HASHEx_SHA256_Accmlt() can be used to feed - * several input buffers back-to-back to the Peripheral that will yield a single - * HASH signature once all buffers have been entered. Wrap-up of input - * buffers feeding and retrieval of digest is done by a call to - * HAL_HASHEx_SHA256_Accmlt_End(). - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note Digest is not retrieved by this API, user must resort to HAL_HASHEx_SHA256_Accmlt_End() - * to read it, feeding at the same time the last input buffer to the Peripheral. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. Only HAL_HASHEx_SHA256_Accmlt_End() is able - * to manage the ending buffer with a length in bytes not a multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Accumulate(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); -} - -/** - * @brief End computation of a single HASH signature after several calls to HAL_HASHEx_SHA256_Accmlt() API. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. - * @param Timeout Timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA256); -} - -/** - * @} - */ - -/** @defgroup HASHEx_Exported_Functions_Group2 HASH extended processing functions in interrupt mode - * @brief HASH extended processing functions using interrupt mode. - * -@verbatim - =============================================================================== - ##### Interruption mode HASH extended processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in interrupt mode - the hash value using one of the following algorithms: - (+) SHA224 - (++) HAL_HASHEx_SHA224_Start_IT() - (++) HAL_HASHEx_SHA224_Accmlt_IT() - (++) HAL_HASHEx_SHA224_Accmlt_End_IT() - (+) SHA256 - (++) HAL_HASHEx_SHA256_Start_IT() - (++) HAL_HASHEx_SHA256_Accmlt_IT() - (++) HAL_HASHEx_SHA256_Accmlt_End_IT() - -@endverbatim - * @{ - */ - - -/** - * @brief Initialize the HASH peripheral in SHA224 mode, next process pInBuffer then - * read the computed digest in interruption mode. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief If not already done, initialize the HASH peripheral in SHA224 mode then - * processes pInBuffer in interruption mode. - * @note Consecutive calls to HAL_HASHEx_SHA224_Accmlt_IT() can be used to feed - * several input buffers back-to-back to the Peripheral that will yield a single - * HASH signature once all buffers have been entered. Wrap-up of input - * buffers feeding and retrieval of digest is done by a call to - * HAL_HASHEx_SHA224_Accmlt_End_IT(). - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. Only HAL_HASHEx_SHA224_Accmlt_End_IT() is able - * to manage the ending buffer with a length in bytes not a multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Accumulate_IT(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief End computation of a single HASH signature after several calls to HAL_HASHEx_SHA224_Accmlt_IT() API. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief Initialize the HASH peripheral in SHA256 mode, next process pInBuffer then - * read the computed digest in interruption mode. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA256); -} - -/** - * @brief If not already done, initialize the HASH peripheral in SHA256 mode then - * processes pInBuffer in interruption mode. - * @note Consecutive calls to HAL_HASHEx_SHA256_Accmlt_IT() can be used to feed - * several input buffers back-to-back to the Peripheral that will yield a single - * HASH signature once all buffers have been entered. Wrap-up of input - * buffers feeding and retrieval of digest is done by a call to - * HAL_HASHEx_SHA256_Accmlt_End_IT(). - * @note Field hhash->Phase of HASH handle is tested to check whether or not - * the Peripheral has already been initialized. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. Only HAL_HASHEx_SHA256_Accmlt_End_IT() is able - * to manage the ending buffer with a length in bytes not a multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes, must be a multiple of 4. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Accumulate_IT(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); -} - -/** - * @brief End computation of a single HASH signature after several calls to HAL_HASHEx_SHA256_Accmlt_IT() API. - * @note Digest is available in pOutBuffer. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HASH_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA256); -} - -/** - * @} - */ - -/** @defgroup HASHEx_Exported_Functions_Group3 HASH extended processing functions in DMA mode - * @brief HASH extended processing functions using DMA mode. - * -@verbatim - =============================================================================== - ##### DMA mode HASH extended processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in DMA mode - the hash value using one of the following algorithms: - (+) SHA224 - (++) HAL_HASHEx_SHA224_Start_DMA() - (++) HAL_HASHEx_SHA224_Finish() - (+) SHA256 - (++) HAL_HASHEx_SHA256_Start_DMA() - (++) HAL_HASHEx_SHA256_Finish() - - [..] When resorting to DMA mode to enter the data in the Peripheral, user must resort - to HAL_HASHEx_xxx_Start_DMA() then read the resulting digest with - HAL_HASHEx_xxx_Finish(). - - [..] In case of multi-buffer HASH processing, MDMAT bit must first be set before - the successive calls to HAL_HASHEx_xxx_Start_DMA(). Then, MDMAT bit needs to be - reset before the last call to HAL_HASHEx_xxx_Start_DMA(). Digest is finally - retrieved thanks to HAL_HASHEx_xxx_Finish(). - -@endverbatim - * @{ - */ - - - - -/** - * @brief Initialize the HASH peripheral in SHA224 mode then initiate a DMA transfer - * to feed the input buffer to the Peripheral. - * @note Once the DMA transfer is finished, HAL_HASHEx_SHA224_Finish() API must - * be called to retrieve the computed digest. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief Return the computed digest in SHA224 mode. - * @note The API waits for DCIS to be set then reads the computed digest. - * @note HAL_HASHEx_SHA224_Finish() can be used as well to retrieve the digest in - * HMAC SHA224 mode. - * @param hhash HASH handle. - * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Finish(hhash, pOutBuffer, Timeout); -} - -/** - * @brief Initialize the HASH peripheral in SHA256 mode then initiate a DMA transfer - * to feed the input buffer to the Peripheral. - * @note Once the DMA transfer is finished, HAL_HASHEx_SHA256_Finish() API must - * be called to retrieve the computed digest. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HASH_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); -} - -/** - * @brief Return the computed digest in SHA256 mode. - * @note The API waits for DCIS to be set then reads the computed digest. - * @note HAL_HASHEx_SHA256_Finish() can be used as well to retrieve the digest in - * HMAC SHA256 mode. - * @param hhash HASH handle. - * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HASHEx_SHA256_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HASH_Finish(hhash, pOutBuffer, Timeout); -} - -/** - * @} - */ - -/** @defgroup HASHEx_Exported_Functions_Group4 HMAC extended processing functions in polling mode - * @brief HMAC extended processing functions using polling mode. - * -@verbatim - =============================================================================== - ##### Polling mode HMAC extended processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in polling mode - the HMAC value using one of the following algorithms: - (+) SHA224 - (++) HAL_HMACEx_SHA224_Start() - (+) SHA256 - (++) HAL_HMACEx_SHA256_Start() - -@endverbatim - * @{ - */ - - - -/** - * @brief Initialize the HASH peripheral in HMAC SHA224 mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HMAC_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief Initialize the HASH peripheral in HMAC SHA256 mode, next process pInBuffer then - * read the computed digest. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. - * @param Timeout Timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout) -{ - return HMAC_Start(hhash, pInBuffer, Size, pOutBuffer, Timeout, HASH_ALGOSELECTION_SHA256); -} - -/** - * @} - */ - - -/** @defgroup HASHEx_Exported_Functions_Group5 HMAC extended processing functions in interrupt mode - * @brief HMAC extended processing functions using interruption mode. - * -@verbatim - =============================================================================== - ##### Interrupt mode HMAC extended processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in interrupt mode - the HMAC value using one of the following algorithms: - (+) SHA224 - (++) HAL_HMACEx_SHA224_Start_IT() - (+) SHA256 - (++) HAL_HMACEx_SHA256_Start_IT() - -@endverbatim - * @{ - */ - - - -/** - * @brief Initialize the HASH peripheral in HMAC SHA224 mode, next process pInBuffer then - * read the computed digest in interrupt mode. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 28 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HMAC_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief Initialize the HASH peripheral in HMAC SHA256 mode, next process pInBuffer then - * read the computed digest in interrupt mode. - * @note Digest is available in pOutBuffer. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @param pOutBuffer pointer to the computed digest. Digest size is 32 bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer) -{ - return HMAC_Start_IT(hhash, pInBuffer, Size, pOutBuffer, HASH_ALGOSELECTION_SHA256); -} - - - - -/** - * @} - */ - - -/** @defgroup HASHEx_Exported_Functions_Group6 HMAC extended processing functions in DMA mode - * @brief HMAC extended processing functions using DMA mode. - * -@verbatim - =============================================================================== - ##### DMA mode HMAC extended processing functions ##### - =============================================================================== - [..] This section provides functions allowing to calculate in DMA mode - the HMAC value using one of the following algorithms: - (+) SHA224 - (++) HAL_HMACEx_SHA224_Start_DMA() - (+) SHA256 - (++) HAL_HMACEx_SHA256_Start_DMA() - - [..] When resorting to DMA mode to enter the data in the Peripheral for HMAC processing, - user must resort to HAL_HMACEx_xxx_Start_DMA() then read the resulting digest - with HAL_HASHEx_xxx_Finish(). - - -@endverbatim - * @{ - */ - - - -/** - * @brief Initialize the HASH peripheral in HMAC SHA224 mode then initiate the required - * DMA transfers to feed the key and the input buffer to the Peripheral. - * @note Once the DMA transfers are finished (indicated by hhash->State set back - * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA224_Finish() API must be called to retrieve - * the computed digest. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note If MDMAT bit is set before calling this function (multi-buffer - * HASH processing case), the input buffer size (in bytes) must be - * a multiple of 4 otherwise, the HASH digest computation is corrupted. - * For the processing of the last buffer of the thread, MDMAT bit must - * be reset and the buffer length (in bytes) doesn't have to be a - * multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief Initialize the HASH peripheral in HMAC SHA224 mode then initiate the required - * DMA transfers to feed the key and the input buffer to the Peripheral. - * @note Once the DMA transfers are finished (indicated by hhash->State set back - * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve - * the computed digest. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note If MDMAT bit is set before calling this function (multi-buffer - * HASH processing case), the input buffer size (in bytes) must be - * a multiple of 4 otherwise, the HASH digest computation is corrupted. - * For the processing of the last buffer of the thread, MDMAT bit must - * be reset and the buffer length (in bytes) doesn't have to be a - * multiple of 4. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (buffer to be hashed). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); -} - - -/** - * @} - */ - -/** @defgroup HASHEx_Exported_Functions_Group7 Multi-buffer HMAC extended processing functions in DMA mode - * @brief HMAC extended processing functions in multi-buffer DMA mode. - * -@verbatim - =============================================================================== - ##### Multi-buffer DMA mode HMAC extended processing functions ##### - =============================================================================== - [..] This section provides functions to manage HMAC multi-buffer - DMA-based processing for MD5, SHA1, SHA224 and SHA256 algorithms. - (+) MD5 - (++) HAL_HMACEx_MD5_Step1_2_DMA() - (++) HAL_HMACEx_MD5_Step2_DMA() - (++) HAL_HMACEx_MD5_Step2_3_DMA() - (+) SHA1 - (++) HAL_HMACEx_SHA1_Step1_2_DMA() - (++) HAL_HMACEx_SHA1_Step2_DMA() - (++) HAL_HMACEx_SHA1_Step2_3_DMA() - - (+) SHA256 - (++) HAL_HMACEx_SHA224_Step1_2_DMA() - (++) HAL_HMACEx_SHA224_Step2_DMA() - (++) HAL_HMACEx_SHA224_Step2_3_DMA() - (+) SHA256 - (++) HAL_HMACEx_SHA256_Step1_2_DMA() - (++) HAL_HMACEx_SHA256_Step2_DMA() - (++) HAL_HMACEx_SHA256_Step2_3_DMA() - - [..] User must first start-up the multi-buffer DMA-based HMAC computation in - calling HAL_HMACEx_xxx_Step1_2_DMA(). This carries out HMAC step 1 and - intiates step 2 with the first input buffer. - - [..] The following buffers are next fed to the Peripheral with a call to the API - HAL_HMACEx_xxx_Step2_DMA(). There may be several consecutive calls - to this API. - - [..] Multi-buffer DMA-based HMAC computation is wrapped up by a call to - HAL_HMACEx_xxx_Step2_3_DMA(). This finishes step 2 in feeding the last input - buffer to the Peripheral then carries out step 3. - - [..] Digest is retrieved by a call to HAL_HASH_xxx_Finish() for MD-5 or - SHA-1, to HAL_HASHEx_xxx_Finish() for SHA-224 or SHA-256. - - [..] If only two buffers need to be consecutively processed, a call to - HAL_HMACEx_xxx_Step1_2_DMA() followed by a call to HAL_HMACEx_xxx_Step2_3_DMA() - is sufficient. - -@endverbatim - * @{ - */ - -/** - * @brief MD5 HMAC step 1 completion and step 2 start in multi-buffer DMA mode. - * @note Step 1 consists in writing the inner hash function key in the Peripheral, - * step 2 consists in writing the message text. - * @note The API carries out the HMAC step 1 then starts step 2 with - * the first buffer entered to the Peripheral. DCAL bit is not automatically set after - * the message buffer feeding, allowing other messages DMA transfers to occur. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_MD5_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - hhash->DigestCalculationDisable = SET; - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief MD5 HMAC step 2 in multi-buffer DMA mode. - * @note Step 2 consists in writing the message text in the Peripheral. - * @note The API carries on the HMAC step 2, applied to the buffer entered as input - * parameter. DCAL bit is not automatically set after the message buffer feeding, - * allowing other messages DMA transfers to occur. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_MD5_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - if (hhash->DigestCalculationDisable != SET) - { - return HAL_ERROR; - } - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); -} - -/** - * @brief MD5 HMAC step 2 wrap-up and step 3 completion in multi-buffer DMA mode. - * @note Step 2 consists in writing the message text in the Peripheral, - * step 3 consists in writing the outer hash function key. - * @note The API wraps up the HMAC step 2 in processing the buffer entered as input - * parameter (the input buffer must be the last one of the multi-buffer thread) - * then carries out HMAC step 3. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note Once the DMA transfers are finished (indicated by hhash->State set back - * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve - * the computed digest. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_MD5_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - hhash->DigestCalculationDisable = RESET; - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_MD5); -} - - -/** - * @brief SHA1 HMAC step 1 completion and step 2 start in multi-buffer DMA mode. - * @note Step 1 consists in writing the inner hash function key in the Peripheral, - * step 2 consists in writing the message text. - * @note The API carries out the HMAC step 1 then starts step 2 with - * the first buffer entered to the Peripheral. DCAL bit is not automatically set after - * the message buffer feeding, allowing other messages DMA transfers to occur. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - hhash->DigestCalculationDisable = SET; - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); -} - -/** - * @brief SHA1 HMAC step 2 in multi-buffer DMA mode. - * @note Step 2 consists in writing the message text in the Peripheral. - * @note The API carries on the HMAC step 2, applied to the buffer entered as input - * parameter. DCAL bit is not automatically set after the message buffer feeding, - * allowing other messages DMA transfers to occur. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - if (hhash->DigestCalculationDisable != SET) - { - return HAL_ERROR; - } - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); -} - -/** - * @brief SHA1 HMAC step 2 wrap-up and step 3 completion in multi-buffer DMA mode. - * @note Step 2 consists in writing the message text in the Peripheral, - * step 3 consists in writing the outer hash function key. - * @note The API wraps up the HMAC step 2 in processing the buffer entered as input - * parameter (the input buffer must be the last one of the multi-buffer thread) - * then carries out HMAC step 3. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note Once the DMA transfers are finished (indicated by hhash->State set back - * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve - * the computed digest. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - hhash->DigestCalculationDisable = RESET; - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA1); -} - -/** - * @brief SHA224 HMAC step 1 completion and step 2 start in multi-buffer DMA mode. - * @note Step 1 consists in writing the inner hash function key in the Peripheral, - * step 2 consists in writing the message text. - * @note The API carries out the HMAC step 1 then starts step 2 with - * the first buffer entered to the Peripheral. DCAL bit is not automatically set after - * the message buffer feeding, allowing other messages DMA transfers to occur. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - hhash->DigestCalculationDisable = SET; - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief SHA224 HMAC step 2 in multi-buffer DMA mode. - * @note Step 2 consists in writing the message text in the Peripheral. - * @note The API carries on the HMAC step 2, applied to the buffer entered as input - * parameter. DCAL bit is not automatically set after the message buffer feeding, - * allowing other messages DMA transfers to occur. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - if (hhash->DigestCalculationDisable != SET) - { - return HAL_ERROR; - } - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief SHA224 HMAC step 2 wrap-up and step 3 completion in multi-buffer DMA mode. - * @note Step 2 consists in writing the message text in the Peripheral, - * step 3 consists in writing the outer hash function key. - * @note The API wraps up the HMAC step 2 in processing the buffer entered as input - * parameter (the input buffer must be the last one of the multi-buffer thread) - * then carries out HMAC step 3. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note Once the DMA transfers are finished (indicated by hhash->State set back - * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve - * the computed digest. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - hhash->DigestCalculationDisable = RESET; - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA224); -} - -/** - * @brief SHA256 HMAC step 1 completion and step 2 start in multi-buffer DMA mode. - * @note Step 1 consists in writing the inner hash function key in the Peripheral, - * step 2 consists in writing the message text. - * @note The API carries out the HMAC step 1 then starts step 2 with - * the first buffer entered to the Peripheral. DCAL bit is not automatically set after - * the message buffer feeding, allowing other messages DMA transfers to occur. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - hhash->DigestCalculationDisable = SET; - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); -} - -/** - * @brief SHA256 HMAC step 2 in multi-buffer DMA mode. - * @note Step 2 consists in writing the message text in the Peripheral. - * @note The API carries on the HMAC step 2, applied to the buffer entered as input - * parameter. DCAL bit is not automatically set after the message buffer feeding, - * allowing other messages DMA transfers to occur. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note The input buffer size (in bytes) must be a multiple of 4 otherwise, the - * HASH digest computation is corrupted. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - if (hhash->DigestCalculationDisable != SET) - { - return HAL_ERROR; - } - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); -} - -/** - * @brief SHA256 HMAC step 2 wrap-up and step 3 completion in multi-buffer DMA mode. - * @note Step 2 consists in writing the message text in the Peripheral, - * step 3 consists in writing the outer hash function key. - * @note The API wraps up the HMAC step 2 in processing the buffer entered as input - * parameter (the input buffer must be the last one of the multi-buffer thread) - * then carries out HMAC step 3. - * @note Same key is used for the inner and the outer hash functions; pointer to key and - * key size are respectively stored in hhash->Init.pKey and hhash->Init.KeySize. - * @note Once the DMA transfers are finished (indicated by hhash->State set back - * to HAL_HASH_STATE_READY), HAL_HASHEx_SHA256_Finish() API must be called to retrieve - * the computed digest. - * @param hhash HASH handle. - * @param pInBuffer pointer to the input buffer (message buffer). - * @param Size length of the input buffer in bytes. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size) -{ - hhash->DigestCalculationDisable = RESET; - return HMAC_Start_DMA(hhash, pInBuffer, Size, HASH_ALGOSELECTION_SHA256); -} - -/** - * @} - */ - -#endif /* MDMA defined*/ -/** - * @} - */ -#endif /* HAL_HASH_MODULE_ENABLED */ - -/** - * @} - */ -#endif /* HASH*/ -/** - * @} - */ - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c deleted file mode 100644 index 6ab4a3d37b9d016..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_hcd.c +++ /dev/null @@ -1,1747 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hcd.c - * @author MCD Application Team - * @brief HCD HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the USB Peripheral Controller: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#)Declare a HCD_HandleTypeDef handle structure, for example: - HCD_HandleTypeDef hhcd; - - (#)Fill parameters of Init structure in HCD handle - - (#)Call HAL_HCD_Init() API to initialize the HCD peripheral (Core, Host core, ...) - - (#)Initialize the HCD low level resources through the HAL_HCD_MspInit() API: - (##) Enable the HCD/USB Low Level interface clock using the following macros - (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - (+++) __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); (For High Speed Mode) - (+++) __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); (For High Speed Mode) - - (##) Initialize the related GPIO clocks - (##) Configure HCD pin-out - (##) Configure HCD NVIC interrupt - - (#)Associate the Upper USB Host stack to the HAL HCD Driver: - (##) hhcd.pData = phost; - - (#)Enable HCD transmission and reception: - (##) HAL_HCD_Start(); - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_HCD_MODULE_ENABLED -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -/** @defgroup HCD HCD - * @brief HCD HAL module driver - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup HCD_Private_Functions HCD Private Functions - * @{ - */ -static void HCD_HC_IN_IRQHandler(HCD_HandleTypeDef *hhcd, uint8_t chnum); -static void HCD_HC_OUT_IRQHandler(HCD_HandleTypeDef *hhcd, uint8_t chnum); -static void HCD_RXQLVL_IRQHandler(HCD_HandleTypeDef *hhcd); -static void HCD_Port_IRQHandler(HCD_HandleTypeDef *hhcd); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup HCD_Exported_Functions HCD Exported Functions - * @{ - */ - -/** @defgroup HCD_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to: - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the host driver. - * @param hhcd HCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_Init(HCD_HandleTypeDef *hhcd) -{ - USB_OTG_GlobalTypeDef *USBx; - - /* Check the HCD handle allocation */ - if (hhcd == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_HCD_ALL_INSTANCE(hhcd->Instance)); - - USBx = hhcd->Instance; - - if (hhcd->State == HAL_HCD_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hhcd->Lock = HAL_UNLOCKED; - -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - hhcd->SOFCallback = HAL_HCD_SOF_Callback; - hhcd->ConnectCallback = HAL_HCD_Connect_Callback; - hhcd->DisconnectCallback = HAL_HCD_Disconnect_Callback; - hhcd->PortEnabledCallback = HAL_HCD_PortEnabled_Callback; - hhcd->PortDisabledCallback = HAL_HCD_PortDisabled_Callback; - hhcd->HC_NotifyURBChangeCallback = HAL_HCD_HC_NotifyURBChange_Callback; - - if (hhcd->MspInitCallback == NULL) - { - hhcd->MspInitCallback = HAL_HCD_MspInit; - } - - /* Init the low level hardware */ - hhcd->MspInitCallback(hhcd); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC... */ - HAL_HCD_MspInit(hhcd); -#endif /* (USE_HAL_HCD_REGISTER_CALLBACKS) */ - } - - hhcd->State = HAL_HCD_STATE_BUSY; - - /* Disable DMA mode for FS instance */ - if ((USBx->CID & (0x1U << 8)) == 0U) - { - hhcd->Init.dma_enable = 0U; - } - - /* Disable the Interrupts */ - __HAL_HCD_DISABLE(hhcd); - - /* Init the Core (common init.) */ - (void)USB_CoreInit(hhcd->Instance, hhcd->Init); - - /* Force Host Mode*/ - (void)USB_SetCurrentMode(hhcd->Instance, USB_HOST_MODE); - - /* Init Host */ - (void)USB_HostInit(hhcd->Instance, hhcd->Init); - - hhcd->State = HAL_HCD_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initialize a host channel. - * @param hhcd HCD handle - * @param ch_num Channel number. - * This parameter can be a value from 1 to 15 - * @param epnum Endpoint number. - * This parameter can be a value from 1 to 15 - * @param dev_address Current device address - * This parameter can be a value from 0 to 255 - * @param speed Current device speed. - * This parameter can be one of these values: - * HCD_DEVICE_SPEED_HIGH: High speed mode, - * HCD_DEVICE_SPEED_FULL: Full speed mode, - * HCD_DEVICE_SPEED_LOW: Low speed mode - * @param ep_type Endpoint Type. - * This parameter can be one of these values: - * EP_TYPE_CTRL: Control type, - * EP_TYPE_ISOC: Isochronous type, - * EP_TYPE_BULK: Bulk type, - * EP_TYPE_INTR: Interrupt type - * @param mps Max Packet Size. - * This parameter can be a value from 0 to32K - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_HC_Init(HCD_HandleTypeDef *hhcd, - uint8_t ch_num, - uint8_t epnum, - uint8_t dev_address, - uint8_t speed, - uint8_t ep_type, - uint16_t mps) -{ - HAL_StatusTypeDef status; - - __HAL_LOCK(hhcd); - hhcd->hc[ch_num].do_ping = 0U; - hhcd->hc[ch_num].dev_addr = dev_address; - hhcd->hc[ch_num].max_packet = mps; - hhcd->hc[ch_num].ch_num = ch_num; - hhcd->hc[ch_num].ep_type = ep_type; - hhcd->hc[ch_num].ep_num = epnum & 0x7FU; - - if ((epnum & 0x80U) == 0x80U) - { - hhcd->hc[ch_num].ep_is_in = 1U; - } - else - { - hhcd->hc[ch_num].ep_is_in = 0U; - } - - hhcd->hc[ch_num].speed = speed; - - status = USB_HC_Init(hhcd->Instance, - ch_num, - epnum, - dev_address, - speed, - ep_type, - mps); - __HAL_UNLOCK(hhcd); - - return status; -} - -/** - * @brief Halt a host channel. - * @param hhcd HCD handle - * @param ch_num Channel number. - * This parameter can be a value from 1 to 15 - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_HC_Halt(HCD_HandleTypeDef *hhcd, uint8_t ch_num) -{ - HAL_StatusTypeDef status = HAL_OK; - - __HAL_LOCK(hhcd); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_UNLOCK(hhcd); - - return status; -} - -/** - * @brief DeInitialize the host driver. - * @param hhcd HCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_DeInit(HCD_HandleTypeDef *hhcd) -{ - /* Check the HCD handle allocation */ - if (hhcd == NULL) - { - return HAL_ERROR; - } - - hhcd->State = HAL_HCD_STATE_BUSY; - -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - if (hhcd->MspDeInitCallback == NULL) - { - hhcd->MspDeInitCallback = HAL_HCD_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware */ - hhcd->MspDeInitCallback(hhcd); -#else - /* DeInit the low level hardware: CLOCK, NVIC.*/ - HAL_HCD_MspDeInit(hhcd); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - - __HAL_HCD_DISABLE(hhcd); - - hhcd->State = HAL_HCD_STATE_RESET; - - return HAL_OK; -} - -/** - * @brief Initialize the HCD MSP. - * @param hhcd HCD handle - * @retval None - */ -__weak void HAL_HCD_MspInit(HCD_HandleTypeDef *hhcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_HCD_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize the HCD MSP. - * @param hhcd HCD handle - * @retval None - */ -__weak void HAL_HCD_MspDeInit(HCD_HandleTypeDef *hhcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_HCD_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup HCD_Exported_Functions_Group2 Input and Output operation functions - * @brief HCD IO operation functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to manage the USB Host Data - Transfer - -@endverbatim - * @{ - */ - -/** - * @brief Submit a new URB for processing. - * @param hhcd HCD handle - * @param ch_num Channel number. - * This parameter can be a value from 1 to 15 - * @param direction Channel number. - * This parameter can be one of these values: - * 0 : Output / 1 : Input - * @param ep_type Endpoint Type. - * This parameter can be one of these values: - * EP_TYPE_CTRL: Control type/ - * EP_TYPE_ISOC: Isochronous type/ - * EP_TYPE_BULK: Bulk type/ - * EP_TYPE_INTR: Interrupt type/ - * @param token Endpoint Type. - * This parameter can be one of these values: - * 0: HC_PID_SETUP / 1: HC_PID_DATA1 - * @param pbuff pointer to URB data - * @param length Length of URB data - * @param do_ping activate do ping protocol (for high speed only). - * This parameter can be one of these values: - * 0 : do ping inactive / 1 : do ping active - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_HC_SubmitRequest(HCD_HandleTypeDef *hhcd, - uint8_t ch_num, - uint8_t direction, - uint8_t ep_type, - uint8_t token, - uint8_t *pbuff, - uint16_t length, - uint8_t do_ping) -{ - hhcd->hc[ch_num].ep_is_in = direction; - hhcd->hc[ch_num].ep_type = ep_type; - - if (token == 0U) - { - hhcd->hc[ch_num].data_pid = HC_PID_SETUP; - hhcd->hc[ch_num].do_ping = do_ping; - } - else - { - hhcd->hc[ch_num].data_pid = HC_PID_DATA1; - } - - /* Manage Data Toggle */ - switch (ep_type) - { - case EP_TYPE_CTRL: - if ((token == 1U) && (direction == 0U)) /*send data */ - { - if (length == 0U) - { - /* For Status OUT stage, Length==0, Status Out PID = 1 */ - hhcd->hc[ch_num].toggle_out = 1U; - } - - /* Set the Data Toggle bit as per the Flag */ - if (hhcd->hc[ch_num].toggle_out == 0U) - { - /* Put the PID 0 */ - hhcd->hc[ch_num].data_pid = HC_PID_DATA0; - } - else - { - /* Put the PID 1 */ - hhcd->hc[ch_num].data_pid = HC_PID_DATA1; - } - } - break; - - case EP_TYPE_BULK: - if (direction == 0U) - { - /* Set the Data Toggle bit as per the Flag */ - if (hhcd->hc[ch_num].toggle_out == 0U) - { - /* Put the PID 0 */ - hhcd->hc[ch_num].data_pid = HC_PID_DATA0; - } - else - { - /* Put the PID 1 */ - hhcd->hc[ch_num].data_pid = HC_PID_DATA1; - } - } - else - { - if (hhcd->hc[ch_num].toggle_in == 0U) - { - hhcd->hc[ch_num].data_pid = HC_PID_DATA0; - } - else - { - hhcd->hc[ch_num].data_pid = HC_PID_DATA1; - } - } - - break; - case EP_TYPE_INTR: - if (direction == 0U) - { - /* Set the Data Toggle bit as per the Flag */ - if (hhcd->hc[ch_num].toggle_out == 0U) - { - /* Put the PID 0 */ - hhcd->hc[ch_num].data_pid = HC_PID_DATA0; - } - else - { - /* Put the PID 1 */ - hhcd->hc[ch_num].data_pid = HC_PID_DATA1; - } - } - else - { - if (hhcd->hc[ch_num].toggle_in == 0U) - { - hhcd->hc[ch_num].data_pid = HC_PID_DATA0; - } - else - { - hhcd->hc[ch_num].data_pid = HC_PID_DATA1; - } - } - break; - - case EP_TYPE_ISOC: - hhcd->hc[ch_num].data_pid = HC_PID_DATA0; - break; - - default: - break; - } - - hhcd->hc[ch_num].xfer_buff = pbuff; - hhcd->hc[ch_num].xfer_len = length; - hhcd->hc[ch_num].urb_state = URB_IDLE; - hhcd->hc[ch_num].xfer_count = 0U; - hhcd->hc[ch_num].ch_num = ch_num; - hhcd->hc[ch_num].state = HC_IDLE; - - return USB_HC_StartXfer(hhcd->Instance, &hhcd->hc[ch_num], (uint8_t)hhcd->Init.dma_enable); -} - -/** - * @brief Handle HCD interrupt request. - * @param hhcd HCD handle - * @retval None - */ -void HAL_HCD_IRQHandler(HCD_HandleTypeDef *hhcd) -{ - USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t i; - uint32_t interrupt; - - /* Ensure that we are in device mode */ - if (USB_GetMode(hhcd->Instance) == USB_OTG_MODE_HOST) - { - /* Avoid spurious interrupt */ - if (__HAL_HCD_IS_INVALID_INTERRUPT(hhcd)) - { - return; - } - - if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT)) - { - /* Incorrect mode, acknowledge the interrupt */ - __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT); - } - - if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_IISOIXFR)) - { - /* Incorrect mode, acknowledge the interrupt */ - __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_IISOIXFR); - } - - if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_PTXFE)) - { - /* Incorrect mode, acknowledge the interrupt */ - __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_PTXFE); - } - - if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_MMIS)) - { - /* Incorrect mode, acknowledge the interrupt */ - __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_MMIS); - } - - /* Handle Host Disconnect Interrupts */ - if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_DISCINT)) - { - __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_DISCINT); - - if ((USBx_HPRT0 & USB_OTG_HPRT_PCSTS) == 0U) - { - /* Flush USB Fifo */ - (void)USB_FlushTxFifo(USBx, 0x10U); - (void)USB_FlushRxFifo(USBx); - - /* Restore FS Clock */ - (void)USB_InitFSLSPClkSel(hhcd->Instance, HCFG_48_MHZ); - - /* Handle Host Port Disconnect Interrupt */ -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - hhcd->DisconnectCallback(hhcd); -#else - HAL_HCD_Disconnect_Callback(hhcd); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - } - } - - /* Handle Host Port Interrupts */ - if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_HPRTINT)) - { - HCD_Port_IRQHandler(hhcd); - } - - /* Handle Host SOF Interrupt */ - if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_SOF)) - { -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - hhcd->SOFCallback(hhcd); -#else - HAL_HCD_SOF_Callback(hhcd); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - - __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_SOF); - } - - /* Handle Rx Queue Level Interrupts */ - if ((__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_RXFLVL)) != 0U) - { - USB_MASK_INTERRUPT(hhcd->Instance, USB_OTG_GINTSTS_RXFLVL); - - HCD_RXQLVL_IRQHandler(hhcd); - - USB_UNMASK_INTERRUPT(hhcd->Instance, USB_OTG_GINTSTS_RXFLVL); - } - - /* Handle Host channel Interrupt */ - if (__HAL_HCD_GET_FLAG(hhcd, USB_OTG_GINTSTS_HCINT)) - { - interrupt = USB_HC_ReadInterrupt(hhcd->Instance); - for (i = 0U; i < hhcd->Init.Host_channels; i++) - { - if ((interrupt & (1UL << (i & 0xFU))) != 0U) - { - if ((USBx_HC(i)->HCCHAR & USB_OTG_HCCHAR_EPDIR) == USB_OTG_HCCHAR_EPDIR) - { - HCD_HC_IN_IRQHandler(hhcd, (uint8_t)i); - } - else - { - HCD_HC_OUT_IRQHandler(hhcd, (uint8_t)i); - } - } - } - __HAL_HCD_CLEAR_FLAG(hhcd, USB_OTG_GINTSTS_HCINT); - } - } -} - - -/** - * @brief Handles HCD Wakeup interrupt request. - * @param hhcd HCD handle - * @retval HAL status - */ -void HAL_HCD_WKUP_IRQHandler(HCD_HandleTypeDef *hhcd) -{ - UNUSED(hhcd); -} - - -/** - * @brief SOF callback. - * @param hhcd HCD handle - * @retval None - */ -__weak void HAL_HCD_SOF_Callback(HCD_HandleTypeDef *hhcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_HCD_SOF_Callback could be implemented in the user file - */ -} - -/** - * @brief Connection Event callback. - * @param hhcd HCD handle - * @retval None - */ -__weak void HAL_HCD_Connect_Callback(HCD_HandleTypeDef *hhcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_HCD_Connect_Callback could be implemented in the user file - */ -} - -/** - * @brief Disconnection Event callback. - * @param hhcd HCD handle - * @retval None - */ -__weak void HAL_HCD_Disconnect_Callback(HCD_HandleTypeDef *hhcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_HCD_Disconnect_Callback could be implemented in the user file - */ -} - -/** - * @brief Port Enabled Event callback. - * @param hhcd HCD handle - * @retval None - */ -__weak void HAL_HCD_PortEnabled_Callback(HCD_HandleTypeDef *hhcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_HCD_Disconnect_Callback could be implemented in the user file - */ -} - -/** - * @brief Port Disabled Event callback. - * @param hhcd HCD handle - * @retval None - */ -__weak void HAL_HCD_PortDisabled_Callback(HCD_HandleTypeDef *hhcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_HCD_Disconnect_Callback could be implemented in the user file - */ -} - -/** - * @brief Notify URB state change callback. - * @param hhcd HCD handle - * @param chnum Channel number. - * This parameter can be a value from 1 to 15 - * @param urb_state: - * This parameter can be one of these values: - * URB_IDLE/ - * URB_DONE/ - * URB_NOTREADY/ - * URB_NYET/ - * URB_ERROR/ - * URB_STALL/ - * @retval None - */ -__weak void HAL_HCD_HC_NotifyURBChange_Callback(HCD_HandleTypeDef *hhcd, uint8_t chnum, HCD_URBStateTypeDef urb_state) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hhcd); - UNUSED(chnum); - UNUSED(urb_state); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_HCD_HC_NotifyURBChange_Callback could be implemented in the user file - */ -} - -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) -/** - * @brief Register a User USB HCD Callback - * To be used instead of the weak predefined callback - * @param hhcd USB HCD handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_HCD_SOF_CB_ID USB HCD SOF callback ID - * @arg @ref HAL_HCD_CONNECT_CB_ID USB HCD Connect callback ID - * @arg @ref HAL_HCD_DISCONNECT_CB_ID OTG HCD Disconnect callback ID - * @arg @ref HAL_HCD_PORT_ENABLED_CB_ID USB HCD Port Enable callback ID - * @arg @ref HAL_HCD_PORT_DISABLED_CB_ID USB HCD Port Disable callback ID - * @arg @ref HAL_HCD_MSPINIT_CB_ID MspDeInit callback ID - * @arg @ref HAL_HCD_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_RegisterCallback(HCD_HandleTypeDef *hhcd, - HAL_HCD_CallbackIDTypeDef CallbackID, - pHCD_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hhcd); - - if (hhcd->State == HAL_HCD_STATE_READY) - { - switch (CallbackID) - { - case HAL_HCD_SOF_CB_ID : - hhcd->SOFCallback = pCallback; - break; - - case HAL_HCD_CONNECT_CB_ID : - hhcd->ConnectCallback = pCallback; - break; - - case HAL_HCD_DISCONNECT_CB_ID : - hhcd->DisconnectCallback = pCallback; - break; - - case HAL_HCD_PORT_ENABLED_CB_ID : - hhcd->PortEnabledCallback = pCallback; - break; - - case HAL_HCD_PORT_DISABLED_CB_ID : - hhcd->PortDisabledCallback = pCallback; - break; - - case HAL_HCD_MSPINIT_CB_ID : - hhcd->MspInitCallback = pCallback; - break; - - case HAL_HCD_MSPDEINIT_CB_ID : - hhcd->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hhcd->State == HAL_HCD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_HCD_MSPINIT_CB_ID : - hhcd->MspInitCallback = pCallback; - break; - - case HAL_HCD_MSPDEINIT_CB_ID : - hhcd->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hhcd); - return status; -} - -/** - * @brief Unregister an USB HCD Callback - * USB HCD callback is redirected to the weak predefined callback - * @param hhcd USB HCD handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_HCD_SOF_CB_ID USB HCD SOF callback ID - * @arg @ref HAL_HCD_CONNECT_CB_ID USB HCD Connect callback ID - * @arg @ref HAL_HCD_DISCONNECT_CB_ID OTG HCD Disconnect callback ID - * @arg @ref HAL_HCD_PORT_ENABLED_CB_ID USB HCD Port Enabled callback ID - * @arg @ref HAL_HCD_PORT_DISABLED_CB_ID USB HCD Port Disabled callback ID - * @arg @ref HAL_HCD_MSPINIT_CB_ID MspDeInit callback ID - * @arg @ref HAL_HCD_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_UnRegisterCallback(HCD_HandleTypeDef *hhcd, HAL_HCD_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hhcd); - - /* Setup Legacy weak Callbacks */ - if (hhcd->State == HAL_HCD_STATE_READY) - { - switch (CallbackID) - { - case HAL_HCD_SOF_CB_ID : - hhcd->SOFCallback = HAL_HCD_SOF_Callback; - break; - - case HAL_HCD_CONNECT_CB_ID : - hhcd->ConnectCallback = HAL_HCD_Connect_Callback; - break; - - case HAL_HCD_DISCONNECT_CB_ID : - hhcd->DisconnectCallback = HAL_HCD_Disconnect_Callback; - break; - - case HAL_HCD_PORT_ENABLED_CB_ID : - hhcd->PortEnabledCallback = HAL_HCD_PortEnabled_Callback; - break; - - case HAL_HCD_PORT_DISABLED_CB_ID : - hhcd->PortDisabledCallback = HAL_HCD_PortDisabled_Callback; - break; - - case HAL_HCD_MSPINIT_CB_ID : - hhcd->MspInitCallback = HAL_HCD_MspInit; - break; - - case HAL_HCD_MSPDEINIT_CB_ID : - hhcd->MspDeInitCallback = HAL_HCD_MspDeInit; - break; - - default : - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hhcd->State == HAL_HCD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_HCD_MSPINIT_CB_ID : - hhcd->MspInitCallback = HAL_HCD_MspInit; - break; - - case HAL_HCD_MSPDEINIT_CB_ID : - hhcd->MspDeInitCallback = HAL_HCD_MspDeInit; - break; - - default : - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hhcd); - return status; -} - -/** - * @brief Register USB HCD Host Channel Notify URB Change Callback - * To be used instead of the weak HAL_HCD_HC_NotifyURBChange_Callback() predefined callback - * @param hhcd HCD handle - * @param pCallback pointer to the USB HCD Host Channel Notify URB Change Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_RegisterHC_NotifyURBChangeCallback(HCD_HandleTypeDef *hhcd, - pHCD_HC_NotifyURBChangeCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hhcd); - - if (hhcd->State == HAL_HCD_STATE_READY) - { - hhcd->HC_NotifyURBChangeCallback = pCallback; - } - else - { - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hhcd); - - return status; -} - -/** - * @brief Unregister the USB HCD Host Channel Notify URB Change Callback - * USB HCD Host Channel Notify URB Change Callback is redirected - * to the weak HAL_HCD_HC_NotifyURBChange_Callback() predefined callback - * @param hhcd HCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_UnRegisterHC_NotifyURBChangeCallback(HCD_HandleTypeDef *hhcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hhcd); - - if (hhcd->State == HAL_HCD_STATE_READY) - { - hhcd->HC_NotifyURBChangeCallback = HAL_HCD_HC_NotifyURBChange_Callback; /* Legacy weak DataOutStageCallback */ - } - else - { - /* Update the error code */ - hhcd->ErrorCode |= HAL_HCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hhcd); - - return status; -} -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup HCD_Exported_Functions_Group3 Peripheral Control functions - * @brief Management functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the HCD data - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Start the host driver. - * @param hhcd HCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_Start(HCD_HandleTypeDef *hhcd) -{ - __HAL_LOCK(hhcd); - /* Enable port power */ - (void)USB_DriveVbus(hhcd->Instance, 1U); - - /* Enable global interrupt */ - __HAL_HCD_ENABLE(hhcd); - __HAL_UNLOCK(hhcd); - - return HAL_OK; -} - -/** - * @brief Stop the host driver. - * @param hhcd HCD handle - * @retval HAL status - */ - -HAL_StatusTypeDef HAL_HCD_Stop(HCD_HandleTypeDef *hhcd) -{ - __HAL_LOCK(hhcd); - (void)USB_StopHost(hhcd->Instance); - __HAL_UNLOCK(hhcd); - - return HAL_OK; -} - -/** - * @brief Reset the host port. - * @param hhcd HCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HCD_ResetPort(HCD_HandleTypeDef *hhcd) -{ - return (USB_ResetPort(hhcd->Instance)); -} - -/** - * @} - */ - -/** @defgroup HCD_Exported_Functions_Group4 Peripheral State functions - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the HCD handle state. - * @param hhcd HCD handle - * @retval HAL state - */ -HCD_StateTypeDef HAL_HCD_GetState(HCD_HandleTypeDef *hhcd) -{ - return hhcd->State; -} - -/** - * @brief Return URB state for a channel. - * @param hhcd HCD handle - * @param chnum Channel number. - * This parameter can be a value from 1 to 15 - * @retval URB state. - * This parameter can be one of these values: - * URB_IDLE/ - * URB_DONE/ - * URB_NOTREADY/ - * URB_NYET/ - * URB_ERROR/ - * URB_STALL - */ -HCD_URBStateTypeDef HAL_HCD_HC_GetURBState(HCD_HandleTypeDef *hhcd, uint8_t chnum) -{ - return hhcd->hc[chnum].urb_state; -} - - -/** - * @brief Return the last host transfer size. - * @param hhcd HCD handle - * @param chnum Channel number. - * This parameter can be a value from 1 to 15 - * @retval last transfer size in byte - */ -uint32_t HAL_HCD_HC_GetXferCount(HCD_HandleTypeDef *hhcd, uint8_t chnum) -{ - return hhcd->hc[chnum].xfer_count; -} - -/** - * @brief Return the Host Channel state. - * @param hhcd HCD handle - * @param chnum Channel number. - * This parameter can be a value from 1 to 15 - * @retval Host channel state - * This parameter can be one of these values: - * HC_IDLE/ - * HC_XFRC/ - * HC_HALTED/ - * HC_NYET/ - * HC_NAK/ - * HC_STALL/ - * HC_XACTERR/ - * HC_BBLERR/ - * HC_DATATGLERR - */ -HCD_HCStateTypeDef HAL_HCD_HC_GetState(HCD_HandleTypeDef *hhcd, uint8_t chnum) -{ - return hhcd->hc[chnum].state; -} - -/** - * @brief Return the current Host frame number. - * @param hhcd HCD handle - * @retval Current Host frame number - */ -uint32_t HAL_HCD_GetCurrentFrame(HCD_HandleTypeDef *hhcd) -{ - return (USB_GetCurrentFrame(hhcd->Instance)); -} - -/** - * @brief Return the Host enumeration speed. - * @param hhcd HCD handle - * @retval Enumeration speed - */ -uint32_t HAL_HCD_GetCurrentSpeed(HCD_HandleTypeDef *hhcd) -{ - return (USB_GetHostSpeed(hhcd->Instance)); -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup HCD_Private_Functions - * @{ - */ -/** - * @brief Handle Host Channel IN interrupt requests. - * @param hhcd HCD handle - * @param chnum Channel number. - * This parameter can be a value from 1 to 15 - * @retval none - */ -static void HCD_HC_IN_IRQHandler(HCD_HandleTypeDef *hhcd, uint8_t chnum) -{ - USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t ch_num = (uint32_t)chnum; - - uint32_t tmpreg; - - if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_AHBERR) == USB_OTG_HCINT_AHBERR) - { - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_AHBERR); - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_BBERR) == USB_OTG_HCINT_BBERR) - { - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_BBERR); - hhcd->hc[ch_num].state = HC_BBLERR; - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_ACK) == USB_OTG_HCINT_ACK) - { - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_ACK); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_STALL) == USB_OTG_HCINT_STALL) - { - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - hhcd->hc[ch_num].state = HC_STALL; - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_STALL); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_DTERR) == USB_OTG_HCINT_DTERR) - { - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - hhcd->hc[ch_num].state = HC_DATATGLERR; - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_DTERR); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_TXERR) == USB_OTG_HCINT_TXERR) - { - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - hhcd->hc[ch_num].state = HC_XACTERR; - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_TXERR); - } - else - { - /* ... */ - } - - if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_FRMOR) == USB_OTG_HCINT_FRMOR) - { - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_FRMOR); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_XFRC) == USB_OTG_HCINT_XFRC) - { - if (hhcd->Init.dma_enable != 0U) - { - hhcd->hc[ch_num].xfer_count = hhcd->hc[ch_num].XferSize - \ - (USBx_HC(ch_num)->HCTSIZ & USB_OTG_HCTSIZ_XFRSIZ); - } - - hhcd->hc[ch_num].state = HC_XFRC; - hhcd->hc[ch_num].ErrCnt = 0U; - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_XFRC); - - if ((hhcd->hc[ch_num].ep_type == EP_TYPE_CTRL) || - (hhcd->hc[ch_num].ep_type == EP_TYPE_BULK)) - { - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); - } - else if (hhcd->hc[ch_num].ep_type == EP_TYPE_INTR) - { - USBx_HC(ch_num)->HCCHAR |= USB_OTG_HCCHAR_ODDFRM; - hhcd->hc[ch_num].urb_state = URB_DONE; - -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - hhcd->HC_NotifyURBChangeCallback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); -#else - HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - } - else if (hhcd->hc[ch_num].ep_type == EP_TYPE_ISOC) - { - hhcd->hc[ch_num].urb_state = URB_DONE; - hhcd->hc[ch_num].toggle_in ^= 1U; - -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - hhcd->HC_NotifyURBChangeCallback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); -#else - HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - } - else - { - /* ... */ - } - - if (hhcd->Init.dma_enable == 1U) - { - if (((hhcd->hc[ch_num].XferSize / hhcd->hc[ch_num].max_packet) & 1U) != 0U) - { - hhcd->hc[ch_num].toggle_in ^= 1U; - } - } - else - { - hhcd->hc[ch_num].toggle_in ^= 1U; - } - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_CHH) == USB_OTG_HCINT_CHH) - { - __HAL_HCD_MASK_HALT_HC_INT(ch_num); - - if (hhcd->hc[ch_num].state == HC_XFRC) - { - hhcd->hc[ch_num].urb_state = URB_DONE; - } - else if (hhcd->hc[ch_num].state == HC_STALL) - { - hhcd->hc[ch_num].urb_state = URB_STALL; - } - else if ((hhcd->hc[ch_num].state == HC_XACTERR) || - (hhcd->hc[ch_num].state == HC_DATATGLERR)) - { - hhcd->hc[ch_num].ErrCnt++; - if (hhcd->hc[ch_num].ErrCnt > 2U) - { - hhcd->hc[ch_num].ErrCnt = 0U; - hhcd->hc[ch_num].urb_state = URB_ERROR; - } - else - { - hhcd->hc[ch_num].urb_state = URB_NOTREADY; - - /* re-activate the channel */ - tmpreg = USBx_HC(ch_num)->HCCHAR; - tmpreg &= ~USB_OTG_HCCHAR_CHDIS; - tmpreg |= USB_OTG_HCCHAR_CHENA; - USBx_HC(ch_num)->HCCHAR = tmpreg; - } - } - else if (hhcd->hc[ch_num].state == HC_NAK) - { - hhcd->hc[ch_num].urb_state = URB_NOTREADY; - - /* re-activate the channel */ - tmpreg = USBx_HC(ch_num)->HCCHAR; - tmpreg &= ~USB_OTG_HCCHAR_CHDIS; - tmpreg |= USB_OTG_HCCHAR_CHENA; - USBx_HC(ch_num)->HCCHAR = tmpreg; - } - else if (hhcd->hc[ch_num].state == HC_BBLERR) - { - hhcd->hc[ch_num].ErrCnt++; - hhcd->hc[ch_num].urb_state = URB_ERROR; - } - else - { - /* ... */ - } - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_CHH); - HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_NAK) == USB_OTG_HCINT_NAK) - { - if (hhcd->hc[ch_num].ep_type == EP_TYPE_INTR) - { - hhcd->hc[ch_num].ErrCnt = 0U; - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - } - else if ((hhcd->hc[ch_num].ep_type == EP_TYPE_CTRL) || - (hhcd->hc[ch_num].ep_type == EP_TYPE_BULK)) - { - hhcd->hc[ch_num].ErrCnt = 0U; - - if (hhcd->Init.dma_enable == 0U) - { - hhcd->hc[ch_num].state = HC_NAK; - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - } - } - else - { - /* ... */ - } - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); - } - else - { - /* ... */ - } -} - -/** - * @brief Handle Host Channel OUT interrupt requests. - * @param hhcd HCD handle - * @param chnum Channel number. - * This parameter can be a value from 1 to 15 - * @retval none - */ -static void HCD_HC_OUT_IRQHandler(HCD_HandleTypeDef *hhcd, uint8_t chnum) -{ - USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t ch_num = (uint32_t)chnum; - uint32_t tmpreg; - uint32_t num_packets; - - if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_AHBERR) == USB_OTG_HCINT_AHBERR) - { - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_AHBERR); - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_ACK) == USB_OTG_HCINT_ACK) - { - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_ACK); - - if (hhcd->hc[ch_num].do_ping == 1U) - { - hhcd->hc[ch_num].do_ping = 0U; - hhcd->hc[ch_num].urb_state = URB_NOTREADY; - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - } - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_FRMOR) == USB_OTG_HCINT_FRMOR) - { - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_FRMOR); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_XFRC) == USB_OTG_HCINT_XFRC) - { - hhcd->hc[ch_num].ErrCnt = 0U; - - /* transaction completed with NYET state, update do ping state */ - if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_NYET) == USB_OTG_HCINT_NYET) - { - hhcd->hc[ch_num].do_ping = 1U; - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NYET); - } - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_XFRC); - hhcd->hc[ch_num].state = HC_XFRC; - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_NYET) == USB_OTG_HCINT_NYET) - { - hhcd->hc[ch_num].state = HC_NYET; - hhcd->hc[ch_num].do_ping = 1U; - hhcd->hc[ch_num].ErrCnt = 0U; - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NYET); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_STALL) == USB_OTG_HCINT_STALL) - { - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_STALL); - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - hhcd->hc[ch_num].state = HC_STALL; - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_NAK) == USB_OTG_HCINT_NAK) - { - hhcd->hc[ch_num].ErrCnt = 0U; - hhcd->hc[ch_num].state = HC_NAK; - - if (hhcd->hc[ch_num].do_ping == 0U) - { - if (hhcd->hc[ch_num].speed == HCD_DEVICE_SPEED_HIGH) - { - hhcd->hc[ch_num].do_ping = 1U; - } - } - - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_TXERR) == USB_OTG_HCINT_TXERR) - { - if (hhcd->Init.dma_enable == 0U) - { - hhcd->hc[ch_num].state = HC_XACTERR; - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - } - else - { - hhcd->hc[ch_num].ErrCnt++; - if (hhcd->hc[ch_num].ErrCnt > 2U) - { - hhcd->hc[ch_num].ErrCnt = 0U; - hhcd->hc[ch_num].urb_state = URB_ERROR; - HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, - hhcd->hc[ch_num].urb_state); - } - else - { - hhcd->hc[ch_num].urb_state = URB_NOTREADY; - } - } - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_TXERR); - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_DTERR) == USB_OTG_HCINT_DTERR) - { - __HAL_HCD_UNMASK_HALT_HC_INT(ch_num); - (void)USB_HC_Halt(hhcd->Instance, (uint8_t)ch_num); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_NAK); - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_DTERR); - hhcd->hc[ch_num].state = HC_DATATGLERR; - } - else if ((USBx_HC(ch_num)->HCINT & USB_OTG_HCINT_CHH) == USB_OTG_HCINT_CHH) - { - __HAL_HCD_MASK_HALT_HC_INT(ch_num); - - if (hhcd->hc[ch_num].state == HC_XFRC) - { - hhcd->hc[ch_num].urb_state = URB_DONE; - if ((hhcd->hc[ch_num].ep_type == EP_TYPE_BULK) || - (hhcd->hc[ch_num].ep_type == EP_TYPE_INTR)) - { - if (hhcd->Init.dma_enable == 0U) - { - hhcd->hc[ch_num].toggle_out ^= 1U; - } - - if ((hhcd->Init.dma_enable == 1U) && (hhcd->hc[ch_num].xfer_len > 0U)) - { - num_packets = (hhcd->hc[ch_num].xfer_len + hhcd->hc[ch_num].max_packet - 1U) / hhcd->hc[ch_num].max_packet; - - if ((num_packets & 1U) != 0U) - { - hhcd->hc[ch_num].toggle_out ^= 1U; - } - } - } - } - else if (hhcd->hc[ch_num].state == HC_NAK) - { - hhcd->hc[ch_num].urb_state = URB_NOTREADY; - } - else if (hhcd->hc[ch_num].state == HC_NYET) - { - hhcd->hc[ch_num].urb_state = URB_NOTREADY; - } - else if (hhcd->hc[ch_num].state == HC_STALL) - { - hhcd->hc[ch_num].urb_state = URB_STALL; - } - else if ((hhcd->hc[ch_num].state == HC_XACTERR) || - (hhcd->hc[ch_num].state == HC_DATATGLERR)) - { - hhcd->hc[ch_num].ErrCnt++; - if (hhcd->hc[ch_num].ErrCnt > 2U) - { - hhcd->hc[ch_num].ErrCnt = 0U; - hhcd->hc[ch_num].urb_state = URB_ERROR; - } - else - { - hhcd->hc[ch_num].urb_state = URB_NOTREADY; - - /* re-activate the channel */ - tmpreg = USBx_HC(ch_num)->HCCHAR; - tmpreg &= ~USB_OTG_HCCHAR_CHDIS; - tmpreg |= USB_OTG_HCCHAR_CHENA; - USBx_HC(ch_num)->HCCHAR = tmpreg; - } - } - else - { - /* ... */ - } - - __HAL_HCD_CLEAR_HC_INT(ch_num, USB_OTG_HCINT_CHH); - HAL_HCD_HC_NotifyURBChange_Callback(hhcd, (uint8_t)ch_num, hhcd->hc[ch_num].urb_state); - } - else - { - /* ... */ - } -} - -/** - * @brief Handle Rx Queue Level interrupt requests. - * @param hhcd HCD handle - * @retval none - */ -static void HCD_RXQLVL_IRQHandler(HCD_HandleTypeDef *hhcd) -{ - USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t pktsts; - uint32_t pktcnt; - uint32_t GrxstspReg; - uint32_t xferSizePktCnt; - uint32_t tmpreg; - uint32_t ch_num; - - GrxstspReg = hhcd->Instance->GRXSTSP; - ch_num = GrxstspReg & USB_OTG_GRXSTSP_EPNUM; - pktsts = (GrxstspReg & USB_OTG_GRXSTSP_PKTSTS) >> 17; - pktcnt = (GrxstspReg & USB_OTG_GRXSTSP_BCNT) >> 4; - - switch (pktsts) - { - case GRXSTS_PKTSTS_IN: - /* Read the data into the host buffer. */ - if ((pktcnt > 0U) && (hhcd->hc[ch_num].xfer_buff != (void *)0)) - { - if ((hhcd->hc[ch_num].xfer_count + pktcnt) <= hhcd->hc[ch_num].xfer_len) - { - (void)USB_ReadPacket(hhcd->Instance, - hhcd->hc[ch_num].xfer_buff, (uint16_t)pktcnt); - - /* manage multiple Xfer */ - hhcd->hc[ch_num].xfer_buff += pktcnt; - hhcd->hc[ch_num].xfer_count += pktcnt; - - /* get transfer size packet count */ - xferSizePktCnt = (USBx_HC(ch_num)->HCTSIZ & USB_OTG_HCTSIZ_PKTCNT) >> 19; - - if ((hhcd->hc[ch_num].max_packet == pktcnt) && (xferSizePktCnt > 0U)) - { - /* re-activate the channel when more packets are expected */ - tmpreg = USBx_HC(ch_num)->HCCHAR; - tmpreg &= ~USB_OTG_HCCHAR_CHDIS; - tmpreg |= USB_OTG_HCCHAR_CHENA; - USBx_HC(ch_num)->HCCHAR = tmpreg; - hhcd->hc[ch_num].toggle_in ^= 1U; - } - } - else - { - hhcd->hc[ch_num].urb_state = URB_ERROR; - } - } - break; - - case GRXSTS_PKTSTS_DATA_TOGGLE_ERR: - break; - - case GRXSTS_PKTSTS_IN_XFER_COMP: - case GRXSTS_PKTSTS_CH_HALTED: - default: - break; - } -} - -/** - * @brief Handle Host Port interrupt requests. - * @param hhcd HCD handle - * @retval None - */ -static void HCD_Port_IRQHandler(HCD_HandleTypeDef *hhcd) -{ - USB_OTG_GlobalTypeDef *USBx = hhcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - __IO uint32_t hprt0; - __IO uint32_t hprt0_dup; - - /* Handle Host Port Interrupts */ - hprt0 = USBx_HPRT0; - hprt0_dup = USBx_HPRT0; - - hprt0_dup &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | \ - USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); - - /* Check whether Port Connect detected */ - if ((hprt0 & USB_OTG_HPRT_PCDET) == USB_OTG_HPRT_PCDET) - { - if ((hprt0 & USB_OTG_HPRT_PCSTS) == USB_OTG_HPRT_PCSTS) - { -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - hhcd->ConnectCallback(hhcd); -#else - HAL_HCD_Connect_Callback(hhcd); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - } - hprt0_dup |= USB_OTG_HPRT_PCDET; - } - - /* Check whether Port Enable Changed */ - if ((hprt0 & USB_OTG_HPRT_PENCHNG) == USB_OTG_HPRT_PENCHNG) - { - hprt0_dup |= USB_OTG_HPRT_PENCHNG; - - if ((hprt0 & USB_OTG_HPRT_PENA) == USB_OTG_HPRT_PENA) - { - if (hhcd->Init.phy_itface == USB_OTG_EMBEDDED_PHY) - { - if ((hprt0 & USB_OTG_HPRT_PSPD) == (HPRT0_PRTSPD_LOW_SPEED << 17)) - { - (void)USB_InitFSLSPClkSel(hhcd->Instance, HCFG_6_MHZ); - } - else - { - (void)USB_InitFSLSPClkSel(hhcd->Instance, HCFG_48_MHZ); - } - } - else - { - if (hhcd->Init.speed == HCD_SPEED_FULL) - { - USBx_HOST->HFIR = 60000U; - } - } -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - hhcd->PortEnabledCallback(hhcd); -#else - HAL_HCD_PortEnabled_Callback(hhcd); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - - } - else - { -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - hhcd->PortDisabledCallback(hhcd); -#else - HAL_HCD_PortDisabled_Callback(hhcd); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - } - } - - /* Check for an overcurrent */ - if ((hprt0 & USB_OTG_HPRT_POCCHNG) == USB_OTG_HPRT_POCCHNG) - { - hprt0_dup |= USB_OTG_HPRT_POCCHNG; - } - - /* Clear Port Interrupts */ - USBx_HPRT0 = hprt0_dup; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -#endif /* HAL_HCD_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c deleted file mode 100644 index dfe5e623703dd6a..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c +++ /dev/null @@ -1,7524 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c.c - * @author MCD Application Team - * @brief I2C HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Inter Integrated Circuit (I2C) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral State, Mode and Error functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The I2C HAL driver can be used as follows: - - (#) Declare a I2C_HandleTypeDef handle structure, for example: - I2C_HandleTypeDef hi2c; - - (#)Initialize the I2C low level resources by implementing the HAL_I2C_MspInit() API: - (##) Enable the I2Cx interface clock - (##) I2C pins configuration - (+++) Enable the clock for the I2C GPIOs - (+++) Configure I2C pins as alternate function open-drain - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the I2Cx interrupt priority - (+++) Enable the NVIC I2C IRQ Channel - (##) DMA Configuration if you need to use DMA process - (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive stream - (+++) Enable the DMAx interface clock using - (+++) Configure the DMA handle parameters - (+++) Configure the DMA Tx or Rx stream - (+++) Associate the initialized DMA handle to the hi2c DMA Tx or Rx handle - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on - the DMA Tx or Rx stream - - (#) Configure the Communication Speed, Duty cycle, Addressing mode, Own Address1, - Dual Addressing mode, Own Address2, General call and Nostretch mode in the hi2c Init structure. - - (#) Initialize the I2C registers by calling the HAL_I2C_Init(), configures also the low level Hardware - (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_I2C_MspInit() API. - - (#) To check if target device is ready for communication, use the function HAL_I2C_IsDeviceReady() - - (#) For I2C IO and IO MEM operations, three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Transmit in master mode an amount of data in blocking mode using HAL_I2C_Master_Transmit() - (+) Receive in master mode an amount of data in blocking mode using HAL_I2C_Master_Receive() - (+) Transmit in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Transmit() - (+) Receive in slave mode an amount of data in blocking mode using HAL_I2C_Slave_Receive() - - *** Polling mode IO MEM operation *** - ===================================== - [..] - (+) Write an amount of data in blocking mode to a specific memory address using HAL_I2C_Mem_Write() - (+) Read an amount of data in blocking mode from a specific memory address using HAL_I2C_Mem_Read() - - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Transmit in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Transmit_IT() - (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() - (+) Receive in master mode an amount of data in non-blocking mode using HAL_I2C_Master_Receive_IT() - (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() - (+) Transmit in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Transmit_IT() - (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() - (+) Receive in slave mode an amount of data in non-blocking mode using HAL_I2C_Slave_Receive_IT() - (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() - (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() - (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() - - *** Interrupt mode or DMA mode IO sequential operation *** - ========================================================== - [..] - (@) These interfaces allow to manage a sequential transfer with a repeated start condition - when a direction change during transfer - [..] - (+) A specific option field manage the different steps of a sequential transfer - (+) Option field values are defined through I2C_XferOptions_definition and are listed below: - (++) I2C_FIRST_AND_LAST_FRAME: No sequential usage, functional is same as associated interfaces in no sequential mode - (++) I2C_FIRST_FRAME: Sequential usage, this option allow to manage a sequence with start condition, address - and data to transfer without a final stop condition - (++) I2C_FIRST_AND_NEXT_FRAME: Sequential usage (Master only), this option allow to manage a sequence with start condition, address - and data to transfer without a final stop condition, an then permit a call the same master sequential interface - several times (like HAL_I2C_Master_Seq_Transmit_IT() then HAL_I2C_Master_Seq_Transmit_IT() - or HAL_I2C_Master_Seq_Transmit_DMA() then HAL_I2C_Master_Seq_Transmit_DMA()) - (++) I2C_NEXT_FRAME: Sequential usage, this option allow to manage a sequence with a restart condition, address - and with new data to transfer if the direction change or manage only the new data to transfer - if no direction change and without a final stop condition in both cases - (++) I2C_LAST_FRAME: Sequential usage, this option allow to manage a sequance with a restart condition, address - and with new data to transfer if the direction change or manage only the new data to transfer - if no direction change and with a final stop condition in both cases - (++) I2C_LAST_FRAME_NO_STOP: Sequential usage (Master only), this option allow to manage a restart condition after several call of the same master sequential - interface several times (link with option I2C_FIRST_AND_NEXT_FRAME). - Usage can, transfer several bytes one by one using HAL_I2C_Master_Seq_Transmit_IT(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) - or HAL_I2C_Master_Seq_Receive_IT(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) - or HAL_I2C_Master_Seq_Transmit_DMA(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME) - or HAL_I2C_Master_Seq_Receive_DMA(option I2C_FIRST_AND_NEXT_FRAME then I2C_NEXT_FRAME). - Then usage of this option I2C_LAST_FRAME_NO_STOP at the last Transmit or Receive sequence permit to call the opposite interface Receive or Transmit - without stopping the communication and so generate a restart condition. - (++) I2C_OTHER_FRAME: Sequential usage (Master only), this option allow to manage a restart condition after each call of the same master sequential - interface. - Usage can, transfer several bytes one by one with a restart with slave address between each bytes using HAL_I2C_Master_Seq_Transmit_IT(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) - or HAL_I2C_Master_Seq_Receive_IT(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) - or HAL_I2C_Master_Seq_Transmit_DMA(option I2C_FIRST_FRAME then I2C_OTHER_FRAME) - or HAL_I2C_Master_Seq_Receive_DMA(option I2C_FIRST_FRAME then I2C_OTHER_FRAME). - Then usage of this option I2C_OTHER_AND_LAST_FRAME at the last frame to help automatic generation of STOP condition. - - (+) Different sequential I2C interfaces are listed below: - (++) Sequential transmit in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Seq_Transmit_IT() - or using HAL_I2C_Master_Seq_Transmit_DMA() - (+++) At transmission end of current frame transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() - (++) Sequential receive in master I2C mode an amount of data in non-blocking mode using HAL_I2C_Master_Seq_Receive_IT() - or using HAL_I2C_Master_Seq_Receive_DMA() - (+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() - (++) Abort a master IT or DMA I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() - (+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() - (++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT() HAL_I2C_DisableListen_IT() - (+++) When address slave I2C match, HAL_I2C_AddrCallback() is executed and user can - add his own code to check the Address Match Code and the transmission direction request by master (Write/Read). - (+++) At Listen mode end HAL_I2C_ListenCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_ListenCpltCallback() - (++) Sequential transmit in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Seq_Transmit_IT() - or using HAL_I2C_Slave_Seq_Transmit_DMA() - (+++) At transmission end of current frame transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() - (++) Sequential receive in slave I2C mode an amount of data in non-blocking mode using HAL_I2C_Slave_Seq_Receive_IT() - or using HAL_I2C_Slave_Seq_Receive_DMA() - (+++) At reception end of current frame transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() - (++) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - - *** Interrupt mode IO MEM operation *** - ======================================= - [..] - (+) Write an amount of data in non-blocking mode with Interrupt to a specific memory address using - HAL_I2C_Mem_Write_IT() - (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback() - (+) Read an amount of data in non-blocking mode with Interrupt from a specific memory address using - HAL_I2C_Mem_Read_IT() - (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback() - (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - - *** DMA mode IO operation *** - ============================== - [..] - (+) Transmit in master mode an amount of data in non-blocking mode (DMA) using - HAL_I2C_Master_Transmit_DMA() - (+) At transmission end of transfer, HAL_I2C_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterTxCpltCallback() - (+) Receive in master mode an amount of data in non-blocking mode (DMA) using - HAL_I2C_Master_Receive_DMA() - (+) At reception end of transfer, HAL_I2C_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() - (+) Transmit in slave mode an amount of data in non-blocking mode (DMA) using - HAL_I2C_Slave_Transmit_DMA() - (+) At transmission end of transfer, HAL_I2C_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveTxCpltCallback() - (+) Receive in slave mode an amount of data in non-blocking mode (DMA) using - HAL_I2C_Slave_Receive_DMA() - (+) At reception end of transfer, HAL_I2C_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() - (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - (+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() - (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_AbortCpltCallback() - - *** DMA mode IO MEM operation *** - ================================= - [..] - (+) Write an amount of data in non-blocking mode with DMA to a specific memory address using - HAL_I2C_Mem_Write_DMA() - (+) At Memory end of write transfer, HAL_I2C_MemTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MemTxCpltCallback() - (+) Read an amount of data in non-blocking mode with DMA from a specific memory address using - HAL_I2C_Mem_Read_DMA() - (+) At Memory end of read transfer, HAL_I2C_MemRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_I2C_MemRxCpltCallback() - (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2C_ErrorCallback() - - - *** I2C HAL driver macros list *** - ================================== - [..] - Below the list of most used macros in I2C HAL driver. - - (+) __HAL_I2C_ENABLE: Enable the I2C peripheral - (+) __HAL_I2C_DISABLE: Disable the I2C peripheral - (+) __HAL_I2C_GET_FLAG: Checks whether the specified I2C flag is set or not - (+) __HAL_I2C_CLEAR_FLAG: Clear the specified I2C pending flag - (+) __HAL_I2C_ENABLE_IT: Enable the specified I2C interrupt - (+) __HAL_I2C_DISABLE_IT: Disable the specified I2C interrupt - - *** Callback registration *** - ============================================= - [..] - The compilation flag USE_HAL_I2C_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_I2C_RegisterCallback() or HAL_I2C_RegisterAddrCallback() - to register an interrupt callback. - [..] - Function HAL_I2C_RegisterCallback() allows to register following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) MemTxCpltCallback : callback for Memory transmission end of transfer. - (+) MemRxCpltCallback : callback for Memory reception end of transfer. - (+) ErrorCallback : callback for error detection. - (+) AbortCpltCallback : callback for abort completion process. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - [..] - For specific callback AddrCallback use dedicated register callbacks : HAL_I2C_RegisterAddrCallback(). - [..] - Use function HAL_I2C_UnRegisterCallback to reset a callback to the default - weak function. - HAL_I2C_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) MemTxCpltCallback : callback for Memory transmission end of transfer. - (+) MemRxCpltCallback : callback for Memory reception end of transfer. - (+) ErrorCallback : callback for error detection. - (+) AbortCpltCallback : callback for abort completion process. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - [..] - For callback AddrCallback use dedicated register callbacks : HAL_I2C_UnRegisterAddrCallback(). - [..] - By default, after the HAL_I2C_Init() and when the state is HAL_I2C_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_I2C_MasterTxCpltCallback(), HAL_I2C_MasterRxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_I2C_Init()/ HAL_I2C_DeInit() only when - these callbacks are null (not registered beforehand). - If MspInit or MspDeInit are not null, the HAL_I2C_Init()/ HAL_I2C_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - [..] - Callbacks can be registered/unregistered in HAL_I2C_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_I2C_STATE_READY or HAL_I2C_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_I2C_RegisterCallback() before calling HAL_I2C_DeInit() - or HAL_I2C_Init() function. - [..] - When the compilation flag USE_HAL_I2C_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - - - [..] - (@) You can refer to the I2C HAL driver header file for more useful macros - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup I2C I2C - * @brief I2C HAL module driver - * @{ - */ - -#ifdef HAL_I2C_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup I2C_Private_Define - * @{ - */ -#define I2C_TIMEOUT_FLAG 35U /*!< Timeout 35 ms */ -#define I2C_TIMEOUT_BUSY_FLAG 25U /*!< Timeout 25 ms */ -#define I2C_TIMEOUT_STOP_FLAG 5U /*!< Timeout 5 ms */ -#define I2C_NO_OPTION_FRAME 0xFFFF0000U /*!< XferOptions default value */ - -/* Private define for @ref PreviousState usage */ -#define I2C_STATE_MSK ((uint32_t)((uint32_t)((uint32_t)HAL_I2C_STATE_BUSY_TX | (uint32_t)HAL_I2C_STATE_BUSY_RX) & (uint32_t)(~((uint32_t)HAL_I2C_STATE_READY)))) /*!< Mask State define, keep only RX and TX bits */ -#define I2C_STATE_NONE ((uint32_t)(HAL_I2C_MODE_NONE)) /*!< Default Value */ -#define I2C_STATE_MASTER_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_MASTER)) /*!< Master Busy TX, combinaison of State LSB and Mode enum */ -#define I2C_STATE_MASTER_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_MASTER)) /*!< Master Busy RX, combinaison of State LSB and Mode enum */ -#define I2C_STATE_SLAVE_BUSY_TX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_TX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_SLAVE)) /*!< Slave Busy TX, combinaison of State LSB and Mode enum */ -#define I2C_STATE_SLAVE_BUSY_RX ((uint32_t)(((uint32_t)HAL_I2C_STATE_BUSY_RX & I2C_STATE_MSK) | (uint32_t)HAL_I2C_MODE_SLAVE)) /*!< Slave Busy RX, combinaison of State LSB and Mode enum */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - -/** @defgroup I2C_Private_Functions I2C Private Functions - * @{ - */ -/* Private functions to handle DMA transfer */ -static void I2C_DMAXferCplt(DMA_HandleTypeDef *hdma); -static void I2C_DMAError(DMA_HandleTypeDef *hdma); -static void I2C_DMAAbort(DMA_HandleTypeDef *hdma); - -static void I2C_ITError(I2C_HandleTypeDef *hi2c); - -static HAL_StatusTypeDef I2C_MasterRequestWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_MasterRequestRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart); - -/* Private functions to handle flags during polling transfer */ -static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnMasterAddressFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnTXEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnBTFFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef I2C_WaitOnSTOPRequestThroughIT(I2C_HandleTypeDef *hi2c); -static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c); - -/* Private functions for I2C transfer IRQ handler */ -static void I2C_MasterTransmit_TXE(I2C_HandleTypeDef *hi2c); -static void I2C_MasterTransmit_BTF(I2C_HandleTypeDef *hi2c); -static void I2C_MasterReceive_RXNE(I2C_HandleTypeDef *hi2c); -static void I2C_MasterReceive_BTF(I2C_HandleTypeDef *hi2c); -static void I2C_Master_SB(I2C_HandleTypeDef *hi2c); -static void I2C_Master_ADD10(I2C_HandleTypeDef *hi2c); -static void I2C_Master_ADDR(I2C_HandleTypeDef *hi2c); - -static void I2C_SlaveTransmit_TXE(I2C_HandleTypeDef *hi2c); -static void I2C_SlaveTransmit_BTF(I2C_HandleTypeDef *hi2c); -static void I2C_SlaveReceive_RXNE(I2C_HandleTypeDef *hi2c); -static void I2C_SlaveReceive_BTF(I2C_HandleTypeDef *hi2c); -static void I2C_Slave_ADDR(I2C_HandleTypeDef *hi2c, uint32_t IT2Flags); -static void I2C_Slave_STOPF(I2C_HandleTypeDef *hi2c); -static void I2C_Slave_AF(I2C_HandleTypeDef *hi2c); - -static void I2C_MemoryTransmit_TXE_BTF(I2C_HandleTypeDef *hi2c); - -/* Private function to Convert Specific options */ -static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup I2C_Exported_Functions I2C Exported Functions - * @{ - */ - -/** @defgroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - deinitialize the I2Cx peripheral: - - (+) User must Implement HAL_I2C_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC). - - (+) Call the function HAL_I2C_Init() to configure the selected device with - the selected configuration: - (++) Communication Speed - (++) Duty cycle - (++) Addressing mode - (++) Own Address 1 - (++) Dual Addressing mode - (++) Own Address 2 - (++) General call mode - (++) Nostretch mode - - (+) Call the function HAL_I2C_DeInit() to restore the default configuration - of the selected I2Cx peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the I2C according to the specified parameters - * in the I2C_InitTypeDef and initialize the associated handle. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c) -{ - uint32_t freqrange; - uint32_t pclk1; - - /* Check the I2C handle allocation */ - if (hi2c == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); - assert_param(IS_I2C_CLOCK_SPEED(hi2c->Init.ClockSpeed)); - assert_param(IS_I2C_DUTY_CYCLE(hi2c->Init.DutyCycle)); - assert_param(IS_I2C_OWN_ADDRESS1(hi2c->Init.OwnAddress1)); - assert_param(IS_I2C_ADDRESSING_MODE(hi2c->Init.AddressingMode)); - assert_param(IS_I2C_DUAL_ADDRESS(hi2c->Init.DualAddressMode)); - assert_param(IS_I2C_OWN_ADDRESS2(hi2c->Init.OwnAddress2)); - assert_param(IS_I2C_GENERAL_CALL(hi2c->Init.GeneralCallMode)); - assert_param(IS_I2C_NO_STRETCH(hi2c->Init.NoStretchMode)); - - if (hi2c->State == HAL_I2C_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hi2c->Lock = HAL_UNLOCKED; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - /* Init the I2C Callback settings */ - hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ - hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ - hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */ - hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */ - - if (hi2c->MspInitCallback == NULL) - { - hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - hi2c->MspInitCallback(hi2c); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - HAL_I2C_MspInit(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - - hi2c->State = HAL_I2C_STATE_BUSY; - - /* Disable the selected I2C peripheral */ - __HAL_I2C_DISABLE(hi2c); - - /*Reset I2C*/ - hi2c->Instance->CR1 |= I2C_CR1_SWRST; - hi2c->Instance->CR1 &= ~I2C_CR1_SWRST; - - /* Get PCLK1 frequency */ - pclk1 = HAL_RCC_GetPCLK1Freq(); - - /* Check the minimum allowed PCLK1 frequency */ - if (I2C_MIN_PCLK_FREQ(pclk1, hi2c->Init.ClockSpeed) == 1U) - { - return HAL_ERROR; - } - - /* Calculate frequency range */ - freqrange = I2C_FREQRANGE(pclk1); - - /*---------------------------- I2Cx CR2 Configuration ----------------------*/ - /* Configure I2Cx: Frequency range */ - MODIFY_REG(hi2c->Instance->CR2, I2C_CR2_FREQ, freqrange); - - /*---------------------------- I2Cx TRISE Configuration --------------------*/ - /* Configure I2Cx: Rise Time */ - MODIFY_REG(hi2c->Instance->TRISE, I2C_TRISE_TRISE, I2C_RISE_TIME(freqrange, hi2c->Init.ClockSpeed)); - - /*---------------------------- I2Cx CCR Configuration ----------------------*/ - /* Configure I2Cx: Speed */ - MODIFY_REG(hi2c->Instance->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), I2C_SPEED(pclk1, hi2c->Init.ClockSpeed, hi2c->Init.DutyCycle)); - - /*---------------------------- I2Cx CR1 Configuration ----------------------*/ - /* Configure I2Cx: Generalcall and NoStretch mode */ - MODIFY_REG(hi2c->Instance->CR1, (I2C_CR1_ENGC | I2C_CR1_NOSTRETCH), (hi2c->Init.GeneralCallMode | hi2c->Init.NoStretchMode)); - - /*---------------------------- I2Cx OAR1 Configuration ---------------------*/ - /* Configure I2Cx: Own Address1 and addressing mode */ - MODIFY_REG(hi2c->Instance->OAR1, (I2C_OAR1_ADDMODE | I2C_OAR1_ADD8_9 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD0), (hi2c->Init.AddressingMode | hi2c->Init.OwnAddress1)); - - /*---------------------------- I2Cx OAR2 Configuration ---------------------*/ - /* Configure I2Cx: Dual mode and Own Address2 */ - MODIFY_REG(hi2c->Instance->OAR2, (I2C_OAR2_ENDUAL | I2C_OAR2_ADD2), (hi2c->Init.DualAddressMode | hi2c->Init.OwnAddress2)); - - /* Enable the selected I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->Mode = HAL_I2C_MODE_NONE; - - return HAL_OK; -} - -/** - * @brief DeInitialize the I2C peripheral. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c) -{ - /* Check the I2C handle allocation */ - if (hi2c == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); - - hi2c->State = HAL_I2C_STATE_BUSY; - - /* Disable the I2C Peripheral Clock */ - __HAL_I2C_DISABLE(hi2c); - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - if (hi2c->MspDeInitCallback == NULL) - { - hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - hi2c->MspDeInitCallback(hi2c); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_I2C_MspDeInit(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - hi2c->State = HAL_I2C_STATE_RESET; - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; -} - -/** - * @brief Initialize the I2C MSP. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize the I2C MSP. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User I2C Callback - * To be used instead of the weak predefined callback - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID - * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID - * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID - * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID - * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID, pI2C_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hi2c); - - if (HAL_I2C_STATE_READY == hi2c->State) - { - switch (CallbackID) - { - case HAL_I2C_MASTER_TX_COMPLETE_CB_ID : - hi2c->MasterTxCpltCallback = pCallback; - break; - - case HAL_I2C_MASTER_RX_COMPLETE_CB_ID : - hi2c->MasterRxCpltCallback = pCallback; - break; - - case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID : - hi2c->SlaveTxCpltCallback = pCallback; - break; - - case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID : - hi2c->SlaveRxCpltCallback = pCallback; - break; - - case HAL_I2C_LISTEN_COMPLETE_CB_ID : - hi2c->ListenCpltCallback = pCallback; - break; - - case HAL_I2C_MEM_TX_COMPLETE_CB_ID : - hi2c->MemTxCpltCallback = pCallback; - break; - - case HAL_I2C_MEM_RX_COMPLETE_CB_ID : - hi2c->MemRxCpltCallback = pCallback; - break; - - case HAL_I2C_ERROR_CB_ID : - hi2c->ErrorCallback = pCallback; - break; - - case HAL_I2C_ABORT_CB_ID : - hi2c->AbortCpltCallback = pCallback; - break; - - case HAL_I2C_MSPINIT_CB_ID : - hi2c->MspInitCallback = pCallback; - break; - - case HAL_I2C_MSPDEINIT_CB_ID : - hi2c->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_I2C_STATE_RESET == hi2c->State) - { - switch (CallbackID) - { - case HAL_I2C_MSPINIT_CB_ID : - hi2c->MspInitCallback = pCallback; - break; - - case HAL_I2C_MSPDEINIT_CB_ID : - hi2c->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - return status; -} - -/** - * @brief Unregister an I2C Callback - * I2C callback is redirected to the weak predefined callback - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * This parameter can be one of the following values: - * @arg @ref HAL_I2C_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_I2C_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_I2C_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_I2C_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_I2C_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_I2C_MEM_TX_COMPLETE_CB_ID Memory Tx Transfer callback ID - * @arg @ref HAL_I2C_MEM_RX_COMPLETE_CB_ID Memory Rx Transfer completed callback ID - * @arg @ref HAL_I2C_ERROR_CB_ID Error callback ID - * @arg @ref HAL_I2C_ABORT_CB_ID Abort callback ID - * @arg @ref HAL_I2C_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_I2C_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hi2c); - - if (HAL_I2C_STATE_READY == hi2c->State) - { - switch (CallbackID) - { - case HAL_I2C_MASTER_TX_COMPLETE_CB_ID : - hi2c->MasterTxCpltCallback = HAL_I2C_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - break; - - case HAL_I2C_MASTER_RX_COMPLETE_CB_ID : - hi2c->MasterRxCpltCallback = HAL_I2C_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - break; - - case HAL_I2C_SLAVE_TX_COMPLETE_CB_ID : - hi2c->SlaveTxCpltCallback = HAL_I2C_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - break; - - case HAL_I2C_SLAVE_RX_COMPLETE_CB_ID : - hi2c->SlaveRxCpltCallback = HAL_I2C_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - break; - - case HAL_I2C_LISTEN_COMPLETE_CB_ID : - hi2c->ListenCpltCallback = HAL_I2C_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - break; - - case HAL_I2C_MEM_TX_COMPLETE_CB_ID : - hi2c->MemTxCpltCallback = HAL_I2C_MemTxCpltCallback; /* Legacy weak MemTxCpltCallback */ - break; - - case HAL_I2C_MEM_RX_COMPLETE_CB_ID : - hi2c->MemRxCpltCallback = HAL_I2C_MemRxCpltCallback; /* Legacy weak MemRxCpltCallback */ - break; - - case HAL_I2C_ERROR_CB_ID : - hi2c->ErrorCallback = HAL_I2C_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_I2C_ABORT_CB_ID : - hi2c->AbortCpltCallback = HAL_I2C_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_I2C_MSPINIT_CB_ID : - hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_I2C_MSPDEINIT_CB_ID : - hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_I2C_STATE_RESET == hi2c->State) - { - switch (CallbackID) - { - case HAL_I2C_MSPINIT_CB_ID : - hi2c->MspInitCallback = HAL_I2C_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_I2C_MSPDEINIT_CB_ID : - hi2c->MspDeInitCallback = HAL_I2C_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - return status; -} - -/** - * @brief Register the Slave Address Match I2C Callback - * To be used instead of the weak HAL_I2C_AddrCallback() predefined callback - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pCallback pointer to the Address Match Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hi2c); - - if (HAL_I2C_STATE_READY == hi2c->State) - { - hi2c->AddrCallback = pCallback; - } - else - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - return status; -} - -/** - * @brief UnRegister the Slave Address Match I2C Callback - * Info Ready I2C Callback is redirected to the weak HAL_I2C_AddrCallback() predefined callback - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hi2c); - - if (HAL_I2C_STATE_READY == hi2c->State) - { - hi2c->AddrCallback = HAL_I2C_AddrCallback; /* Legacy weak AddrCallback */ - } - else - { - /* Update the error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2c); - return status; -} - -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup I2C_Exported_Functions_Group2 Input and Output operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the I2C data - transfers. - - (#) There are two modes of transfer: - (++) Blocking mode : The communication is performed in the polling mode. - The status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode : The communication is performed using Interrupts - or DMA. These functions return the status of the transfer startup. - The end of the data processing will be indicated through the - dedicated I2C IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - - (#) Blocking mode functions are : - (++) HAL_I2C_Master_Transmit() - (++) HAL_I2C_Master_Receive() - (++) HAL_I2C_Slave_Transmit() - (++) HAL_I2C_Slave_Receive() - (++) HAL_I2C_Mem_Write() - (++) HAL_I2C_Mem_Read() - (++) HAL_I2C_IsDeviceReady() - - (#) No-Blocking mode functions with Interrupt are : - (++) HAL_I2C_Master_Transmit_IT() - (++) HAL_I2C_Master_Receive_IT() - (++) HAL_I2C_Slave_Transmit_IT() - (++) HAL_I2C_Slave_Receive_IT() - (++) HAL_I2C_Mem_Write_IT() - (++) HAL_I2C_Mem_Read_IT() - (++) HAL_I2C_Master_Seq_Transmit_IT() - (++) HAL_I2C_Master_Seq_Receive_IT() - (++) HAL_I2C_Slave_Seq_Transmit_IT() - (++) HAL_I2C_Slave_Seq_Receive_IT() - (++) HAL_I2C_EnableListen_IT() - (++) HAL_I2C_DisableListen_IT() - (++) HAL_I2C_Master_Abort_IT() - - (#) No-Blocking mode functions with DMA are : - (++) HAL_I2C_Master_Transmit_DMA() - (++) HAL_I2C_Master_Receive_DMA() - (++) HAL_I2C_Slave_Transmit_DMA() - (++) HAL_I2C_Slave_Receive_DMA() - (++) HAL_I2C_Mem_Write_DMA() - (++) HAL_I2C_Mem_Read_DMA() - (++) HAL_I2C_Master_Seq_Transmit_DMA() - (++) HAL_I2C_Master_Seq_Receive_DMA() - (++) HAL_I2C_Slave_Seq_Transmit_DMA() - (++) HAL_I2C_Slave_Seq_Receive_DMA() - - (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: - (++) HAL_I2C_MasterTxCpltCallback() - (++) HAL_I2C_MasterRxCpltCallback() - (++) HAL_I2C_SlaveTxCpltCallback() - (++) HAL_I2C_SlaveRxCpltCallback() - (++) HAL_I2C_MemTxCpltCallback() - (++) HAL_I2C_MemRxCpltCallback() - (++) HAL_I2C_AddrCallback() - (++) HAL_I2C_ListenCpltCallback() - (++) HAL_I2C_ErrorCallback() - (++) HAL_I2C_AbortCpltCallback() - -@endverbatim - * @{ - */ - -/** - * @brief Transmits in master mode an amount of data in blocking mode. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Send Slave Address */ - if (I2C_MasterRequestWrite(hi2c, DevAddress, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - while (hi2c->XferSize > 0U) - { - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - hi2c->XferSize--; - - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - hi2c->XferSize--; - } - - /* Wait until BTF flag is set */ - if (I2C_WaitOnBTFFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives in master mode an amount of data in blocking mode. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Send Slave Address */ - if (I2C_MasterRequestRead(hi2c, DevAddress, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - if (hi2c->XferSize == 0U) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferSize == 1U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferSize == 2U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - - while (hi2c->XferSize > 0U) - { - if (hi2c->XferSize <= 3U) - { - /* One byte */ - if (hi2c->XferSize == 1U) - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - /* Two bytes */ - else if (hi2c->XferSize == 2U) - { - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - /* 3 Last bytes */ - else - { - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - else - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - } - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmits in slave mode an amount of data in blocking mode. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* If 10bit addressing mode is selected */ - if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT) - { - /* Wait until ADDR flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - - while (hi2c->XferSize > 0U) - { - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - return HAL_ERROR; - } - - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - hi2c->XferSize--; - - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - hi2c->XferSize--; - } - } - - /* Wait until AF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_AF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear AF flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in blocking mode - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == (uint16_t)0)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - while (hi2c->XferSize > 0U) - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - - /* Wait until STOP flag is set */ - if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - return HAL_ERROR; - } - - /* Clear STOP flag */ - __HAL_I2C_CLEAR_STOPFLAG(hi2c); - - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in master mode an amount of data in non-blocking mode with Interrupt - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in master mode an amount of data in non-blocking mode with Interrupt - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in slave mode an amount of data in non-blocking mode with Interrupt - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) -{ - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in non-blocking mode with Interrupt - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) -{ - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in master mode an amount of data in non-blocking mode with DMA - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - HAL_StatusTypeDef dmaxferstatus; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferM1CpltCallback = NULL; - hi2c->hdmatx->XferM1HalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in master mode an amount of data in non-blocking mode with DMA - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - HAL_StatusTypeDef dmaxferstatus; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferM1CpltCallback = NULL; - hi2c->hdmarx->XferM1HalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit in slave mode an amount of data in non-blocking mode with DMA - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef dmaxferstatus; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferM1CpltCallback = NULL; - hi2c->hdmatx->XferM1HalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_LISTEN; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - hi2c->Instance->CR2 |= I2C_CR2_DMAEN; - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive in slave mode an amount of data in non-blocking mode with DMA - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef dmaxferstatus; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferM1CpltCallback = NULL; - hi2c->hdmarx->XferM1HalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_LISTEN; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Write an amount of data in blocking mode to a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - while (hi2c->XferSize > 0U) - { - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) && (hi2c->XferSize != 0U)) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - - /* Wait until BTF flag is set */ - if (I2C_WaitOnBTFFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Read an amount of data in blocking mode from a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - if (hi2c->XferSize == 0U) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferSize == 1U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferSize == 2U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - - while (hi2c->XferSize > 0U) - { - if (hi2c->XferSize <= 3U) - { - /* One byte */ - if (hi2c->XferSize == 1U) - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - /* Two bytes */ - else if (hi2c->XferSize == 2U) - { - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - /* 3 Last bytes */ - else - { - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Wait until BTF flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BTF, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - else - { - /* Wait until RXNE flag is set */ - if (I2C_WaitOnRXNEFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferSize--; - hi2c->XferCount--; - } - } - } - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Write an amount of data in non-blocking mode with Interrupt to a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - hi2c->Memaddress = MemAddress; - hi2c->MemaddSize = MemAddSize; - hi2c->EventCount = 0U; - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Read an amount of data in non-blocking mode with Interrupt from a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - hi2c->Memaddress = MemAddress; - hi2c->MemaddSize = MemAddSize; - hi2c->EventCount = 0U; - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - if (hi2c->XferSize > 0U) - { - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Write an amount of data in non-blocking mode with DMA to a specific memory address - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - __IO uint32_t count = 0U; - HAL_StatusTypeDef dmaxferstatus; - - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - hi2c->Memaddress = MemAddress; - hi2c->MemaddSize = MemAddSize; - hi2c->EventCount = 0U; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferM1CpltCallback = NULL; - hi2c->hdmatx->XferM1HalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryWrite(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) - { - /* Abort the ongoing DMA */ - dmaxferstatus = HAL_DMA_Abort_IT(hi2c->hdmatx); - - /* Prevent unused argument(s) compilation and MISRA warning */ - UNUSED(dmaxferstatus); - - /* Set the unused I2C DMA transfer complete callback to NULL */ - hi2c->hdmatx->XferCpltCallback = NULL; - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->XferSize = 0U; - hi2c->XferCount = 0U; - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_ERR); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_SIZE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Reads an amount of data in non-blocking mode with DMA from a specific memory address. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param pData Pointer to data buffer - * @param Size Amount of data to be read - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size) -{ - /* Init tickstart for timeout management*/ - uint32_t tickstart = HAL_GetTick(); - __IO uint32_t count = 0U; - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_MEMADD_SIZE(MemAddSize)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MEM; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->Devaddress = DevAddress; - hi2c->Memaddress = MemAddress; - hi2c->MemaddSize = MemAddSize; - hi2c->EventCount = 0U; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferM1CpltCallback = NULL; - hi2c->hdmarx->XferM1HalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) - { - /* Abort the ongoing DMA */ - dmaxferstatus = HAL_DMA_Abort_IT(hi2c->hdmarx); - - /* Prevent unused argument(s) compilation and MISRA warning */ - UNUSED(dmaxferstatus); - - /* Set the unused I2C DMA transfer complete callback to NULL */ - hi2c->hdmarx->XferCpltCallback = NULL; - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->XferSize = 0U; - hi2c->XferCount = 0U; - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - return HAL_ERROR; - } - - if (hi2c->XferSize == 1U) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - else - { - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_ERR); - - /* Enable DMA Request */ - hi2c->Instance->CR2 |= I2C_CR2_DMAEN; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Send Slave Address and Memory Address */ - if (I2C_RequestMemoryRead(hi2c, DevAddress, MemAddress, MemAddSize, I2C_TIMEOUT_FLAG, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->State = HAL_I2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Checks if target device is ready for communication. - * @note This function is used with Memory devices - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Trials Number of trials - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout) -{ - /* Get tick */ - uint32_t tickstart = HAL_GetTick(); - uint32_t I2C_Trials = 1U; - FlagStatus tmp1; - FlagStatus tmp2; - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - do - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); - - /* Wait until ADDR or AF flag are set */ - /* Get tick */ - tickstart = HAL_GetTick(); - - tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR); - tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF); - while ((hi2c->State != HAL_I2C_STATE_TIMEOUT) && (tmp1 == RESET) && (tmp2 == RESET)) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->State = HAL_I2C_STATE_TIMEOUT; - } - tmp1 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR); - tmp2 = __HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF); - } - - hi2c->State = HAL_I2C_STATE_READY; - - /* Check if the ADDR flag has been set */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_ADDR) == SET) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Clear ADDR Flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - hi2c->State = HAL_I2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_OK; - } - else - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Clear AF Flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - /* Wait until BUSY flag is reset */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, I2C_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_ERROR; - } - } - - /* Increment Trials */ - I2C_Trials++; - } - while (I2C_Trials < Trials); - - hi2c->State = HAL_I2C_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with Interrupt. - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t Prev_State = 0x00U; - __IO uint32_t count = 0x00U; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - hi2c->Devaddress = DevAddress; - - Prev_State = hi2c->PreviousState; - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in master I2C mode an amount of data in non-blocking mode with DMA. - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t Prev_State = 0x00U; - __IO uint32_t count = 0x00U; - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - hi2c->Devaddress = DevAddress; - - Prev_State = hi2c->PreviousState; - - if (hi2c->XferSize > 0U) - { - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* If XferOptions is not associated to a new frame, mean no start bit is request, enable directly the DMA request */ - /* In other cases, DMA request is enabled after Slave address treatment in IRQHandler */ - if ((XferOptions == I2C_NEXT_FRAME) || (XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) - { - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_TX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in master I2C mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t Prev_State = 0x00U; - __IO uint32_t count = 0U; - uint32_t enableIT = (I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - hi2c->Devaddress = DevAddress; - - Prev_State = hi2c->PreviousState; - - if ((hi2c->XferCount == 2U) && ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP))) - { - if (Prev_State == I2C_STATE_MASTER_BUSY_RX) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Remove Enabling of IT_BUF, mean RXNE treatment, treat the 2 bytes through BTF */ - enableIT &= ~I2C_IT_BUF; - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable interrupts */ - __HAL_I2C_ENABLE_IT(hi2c, enableIT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in master mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t Prev_State = 0x00U; - __IO uint32_t count = 0U; - uint32_t enableIT = (I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP) || (XferOptions == I2C_FIRST_AND_LAST_FRAME) || (XferOptions == I2C_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = I2C_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Clear Last DMA bit */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - - hi2c->State = HAL_I2C_STATE_BUSY_RX; - hi2c->Mode = HAL_I2C_MODE_MASTER; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - hi2c->Devaddress = DevAddress; - - Prev_State = hi2c->PreviousState; - - if (hi2c->XferSize > 0U) - { - if ((hi2c->XferCount == 2U) && ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP))) - { - if (Prev_State == I2C_STATE_MASTER_BUSY_RX) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - if ((XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_OTHER_AND_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) - { - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - } - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - if (dmaxferstatus == HAL_OK) - { - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Update interrupt for only EVT and ERR */ - enableIT = (I2C_IT_EVT | I2C_IT_ERR); - } - else - { - /* Update interrupt for only ERR */ - enableIT = I2C_IT_ERR; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* If XferOptions is not associated to a new frame, mean no start bit is request, enable directly the DMA request */ - /* In other cases, DMA request is enabled after Slave address treatment in IRQHandler */ - if ((XferOptions == I2C_NEXT_FRAME) || (XferOptions == I2C_LAST_FRAME) || (XferOptions == I2C_LAST_FRAME_NO_STOP)) - { - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, enableIT); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* If transfer direction not change and there is no request to start another frame, do not generate Restart Condition */ - /* Mean Previous state is same as current state */ - if ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(XferOptions) == 1)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable interrupts */ - __HAL_I2C_ENABLE_IT(hi2c, enableIT); - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in slave mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential transmit in slave mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */ - /* and then toggle the HAL slave RX state to TX state */ - if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN) - { - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - /* Abort DMA Xfer if any */ - if (hi2c->hdmarx != NULL) - { - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); - } - } - } - } - else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) - { - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Abort DMA Xfer if any */ - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); - } - } - } - } - else - { - /* Nothing to do */ - } - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_TX_LISTEN; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmatx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmatx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmatx->XferHalfCpltCallback = NULL; - hi2c->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr, (uint32_t)&hi2c->Instance->DR, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_LISTEN; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Enable DMA Request */ - hi2c->Instance->CR2 |= I2C_CR2_DMAEN; - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in slave mode an amount of data in non-blocking mode with Interrupt - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sequential receive in slave mode an amount of data in non-blocking mode with DMA - * @note This interface allow to manage repeated start condition when a direction change during transfer - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref I2C_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - HAL_StatusTypeDef dmaxferstatus; - - /* Check the parameters */ - assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2c); - - /* Disable Interrupts, to prevent preemption during treatment in case of multicall */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* I2C cannot manage full duplex exchange so disable previous IT enabled if any */ - /* and then toggle the HAL slave RX state to TX state */ - if (hi2c->State == HAL_I2C_STATE_BUSY_RX_LISTEN) - { - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - /* Abort DMA Xfer if any */ - if (hi2c->hdmarx != NULL) - { - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); - } - } - } - } - else if (hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) - { - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Abort DMA Xfer if any */ - if (hi2c->hdmatx != NULL) - { - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); - } - } - } - } - else - { - /* Nothing to do */ - } - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Disable Pos */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - - hi2c->State = HAL_I2C_STATE_BUSY_RX_LISTEN; - hi2c->Mode = HAL_I2C_MODE_SLAVE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Prepare transfer parameters */ - hi2c->pBuffPtr = pData; - hi2c->XferCount = Size; - hi2c->XferSize = hi2c->XferCount; - hi2c->XferOptions = XferOptions; - - if (hi2c->hdmarx != NULL) - { - /* Set the I2C DMA transfer complete callback */ - hi2c->hdmarx->XferCpltCallback = I2C_DMAXferCplt; - - /* Set the DMA error callback */ - hi2c->hdmarx->XferErrorCallback = I2C_DMAError; - - /* Set the unused DMA callbacks to NULL */ - hi2c->hdmarx->XferHalfCpltCallback = NULL; - hi2c->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmarx, (uint32_t)&hi2c->Instance->DR, (uint32_t)hi2c->pBuffPtr, hi2c->XferSize); - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_LISTEN; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA_PARAM; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - if (dmaxferstatus == HAL_OK) - { - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Note : The I2C interrupts must be enabled after unlocking current process - to avoid the risk of I2C interrupt handle execution before current - process unlock */ - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - return HAL_OK; - } - else - { - /* Update I2C state */ - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Update I2C error code */ - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Enable the Address listen mode with Interrupt. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->State == HAL_I2C_STATE_READY) - { - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Check if the I2C is already enabled */ - if ((hi2c->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - } - - /* Enable Address Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable EVT and ERR interrupt */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Disable the Address listen mode with Interrupt. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of tmp to prevent undefined behavior of volatile usage */ - uint32_t tmp; - - /* Disable Address listen mode only if a transfer is not ongoing */ - if (hi2c->State == HAL_I2C_STATE_LISTEN) - { - tmp = (uint32_t)(hi2c->State) & I2C_STATE_MSK; - hi2c->PreviousState = tmp | (uint32_t)(hi2c->Mode); - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Disable Address Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Disable EVT and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Abort a master I2C IT or DMA process communication with Interrupt. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - - /* Prevent unused argument(s) compilation warning */ - UNUSED(DevAddress); - - /* Abort Master transfer during Receive or Transmit process */ - if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BUSY) != RESET) && (CurrentMode == HAL_I2C_MODE_MASTER)) - { - /* Process Locked */ - __HAL_LOCK(hi2c); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_ABORT; - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->XferCount = 0U; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ - I2C_ITError(hi2c); - - return HAL_OK; - } - else - { - /* Wrong usage of abort function */ - /* This function should be used only in case of abort monitored by master device */ - /* Or periphal is not in busy state, mean there is no active sequence to be abort */ - return HAL_ERROR; - } -} - -/** - * @} - */ - -/** @defgroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ - -/** - * @brief This function handles I2C event interrupt request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c) -{ - uint32_t sr1itflags; - uint32_t sr2itflags = 0U; - uint32_t itsources = READ_REG(hi2c->Instance->CR2); - uint32_t CurrentXferOptions = hi2c->XferOptions; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - /* Master or Memory mode selected */ - if ((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) - { - sr2itflags = READ_REG(hi2c->Instance->SR2); - sr1itflags = READ_REG(hi2c->Instance->SR1); - - /* Exit IRQ event until Start Bit detected in case of Other frame requested */ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_SB) == RESET) && (IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(CurrentXferOptions) == 1U)) - { - return; - } - - /* SB Set ----------------------------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_SB) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - /* Convert OTHER_xxx XferOptions if any */ - I2C_ConvertOtherXferOptions(hi2c); - - I2C_Master_SB(hi2c); - } - /* ADD10 Set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADD10) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_Master_ADD10(hi2c); - } - /* ADDR Set --------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADDR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_Master_ADDR(hi2c); - } - /* I2C in mode Transmitter -----------------------------------------------*/ - else if (I2C_CHECK_FLAG(sr2itflags, I2C_FLAG_TRA) != RESET) - { - /* Do not check buffer and BTF flag if a Xfer DMA is on going */ - if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) - { - /* TXE set and BTF reset -----------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_TXE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) - { - I2C_MasterTransmit_TXE(hi2c); - } - /* BTF set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - if (CurrentState == HAL_I2C_STATE_BUSY_TX) - { - I2C_MasterTransmit_BTF(hi2c); - } - else /* HAL_I2C_MODE_MEM */ - { - if (CurrentMode == HAL_I2C_MODE_MEM) - { - I2C_MemoryTransmit_TXE_BTF(hi2c); - } - } - } - else - { - /* Do nothing */ - } - } - } - /* I2C in mode Receiver --------------------------------------------------*/ - else - { - /* Do not check buffer and BTF flag if a Xfer DMA is on going */ - if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) - { - /* RXNE set and BTF reset -----------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_RXNE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) - { - I2C_MasterReceive_RXNE(hi2c); - } - /* BTF set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_MasterReceive_BTF(hi2c); - } - else - { - /* Do nothing */ - } - } - } - } - /* Slave mode selected */ - else - { - /* If an error is detected, read only SR1 register to prevent */ - /* a clear of ADDR flags by reading SR2 after reading SR1 in Error treatment */ - if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) - { - sr1itflags = READ_REG(hi2c->Instance->SR1); - } - else - { - sr2itflags = READ_REG(hi2c->Instance->SR2); - sr1itflags = READ_REG(hi2c->Instance->SR1); - } - - /* ADDR set --------------------------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ADDR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - /* Now time to read SR2, this will clear ADDR flag automatically */ - if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) - { - sr2itflags = READ_REG(hi2c->Instance->SR2); - } - I2C_Slave_ADDR(hi2c, sr2itflags); - } - /* STOPF set --------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_STOPF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_Slave_STOPF(hi2c); - } - /* I2C in mode Transmitter -----------------------------------------------*/ - else if ((CurrentState == HAL_I2C_STATE_BUSY_TX) || (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN)) - { - /* TXE set and BTF reset -----------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_TXE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) - { - I2C_SlaveTransmit_TXE(hi2c); - } - /* BTF set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_SlaveTransmit_BTF(hi2c); - } - else - { - /* Do nothing */ - } - } - /* I2C in mode Receiver --------------------------------------------------*/ - else - { - /* RXNE set and BTF reset ----------------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_RXNE) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_BUF) != RESET) && (I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) == RESET)) - { - I2C_SlaveReceive_RXNE(hi2c); - } - /* BTF set -------------------------------------------------------------*/ - else if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BTF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_EVT) != RESET)) - { - I2C_SlaveReceive_BTF(hi2c); - } - else - { - /* Do nothing */ - } - } - } -} - -/** - * @brief This function handles I2C error interrupt request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c) -{ - HAL_I2C_ModeTypeDef tmp1; - uint32_t tmp2; - HAL_I2C_StateTypeDef tmp3; - uint32_t tmp4; - uint32_t sr1itflags = READ_REG(hi2c->Instance->SR1); - uint32_t itsources = READ_REG(hi2c->Instance->CR2); - uint32_t error = HAL_I2C_ERROR_NONE; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - - /* I2C Bus error interrupt occurred ----------------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_BERR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) - { - error |= HAL_I2C_ERROR_BERR; - - /* Clear BERR flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_BERR); - } - - /* I2C Arbitration Lost error interrupt occurred ---------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_ARLO) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) - { - error |= HAL_I2C_ERROR_ARLO; - - /* Clear ARLO flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ARLO); - } - - /* I2C Acknowledge failure error interrupt occurred ------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_AF) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) - { - tmp1 = CurrentMode; - tmp2 = hi2c->XferCount; - tmp3 = hi2c->State; - tmp4 = hi2c->PreviousState; - if ((tmp1 == HAL_I2C_MODE_SLAVE) && (tmp2 == 0U) && \ - ((tmp3 == HAL_I2C_STATE_BUSY_TX) || (tmp3 == HAL_I2C_STATE_BUSY_TX_LISTEN) || \ - ((tmp3 == HAL_I2C_STATE_LISTEN) && (tmp4 == I2C_STATE_SLAVE_BUSY_TX)))) - { - I2C_Slave_AF(hi2c); - } - else - { - /* Clear AF flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - error |= HAL_I2C_ERROR_AF; - - /* Do not generate a STOP in case of Slave receive non acknowledge during transfer (mean not at the end of transfer) */ - if ((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - } - } - - /* I2C Over-Run/Under-Run interrupt occurred -------------------------------*/ - if ((I2C_CHECK_FLAG(sr1itflags, I2C_FLAG_OVR) != RESET) && (I2C_CHECK_IT_SOURCE(itsources, I2C_IT_ERR) != RESET)) - { - error |= HAL_I2C_ERROR_OVR; - /* Clear OVR flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_OVR); - } - - /* Call the Error Callback in case of Error detected -----------------------*/ - if (error != HAL_I2C_ERROR_NONE) - { - hi2c->ErrorCode |= error; - I2C_ITError(hi2c); - } -} - -/** - * @brief Master Tx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MasterTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Master Rx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MasterRxCpltCallback could be implemented in the user file - */ -} - -/** @brief Slave Tx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_SlaveTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Slave Rx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_SlaveRxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Slave Address Match callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref I2C_XferDirection_definition - * @param AddrMatchCode Address Match Code - * @retval None - */ -__weak void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - UNUSED(TransferDirection); - UNUSED(AddrMatchCode); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_AddrCallback() could be implemented in the user file - */ -} - -/** - * @brief Listen Complete callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_ListenCpltCallback() could be implemented in the user file - */ -} - -/** - * @brief Memory Tx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MemTxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Memory Rx Transfer completed callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_MemRxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief I2C error callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief I2C abort callback. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval None - */ -__weak void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2c); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2C_AbortCpltCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @brief Peripheral State, Mode and Error functions - * -@verbatim - =============================================================================== - ##### Peripheral State, Mode and Error functions ##### - =============================================================================== - [..] - This subsection permit to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the I2C handle state. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL state - */ -HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c) -{ - /* Return I2C handle state */ - return hi2c->State; -} - -/** - * @brief Returns the I2C Master, Slave, Memory or no mode. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval HAL mode - */ -HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c) -{ - return hi2c->Mode; -} - -/** - * @brief Return the I2C error code. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval I2C Error Code - */ -uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c) -{ - return hi2c->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup I2C_Private_Functions - * @{ - */ - -/** - * @brief Handle TXE flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MasterTransmit_TXE(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - uint32_t CurrentXferOptions = hi2c->XferOptions; - - if ((hi2c->XferSize == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) - { - /* Call TxCpltCallback() directly if no stop mode is set */ - if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) && (CurrentXferOptions != I2C_NO_OPTION_FRAME)) - { - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterTxCpltCallback(hi2c); -#else - HAL_I2C_MasterTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else /* Generate Stop condition then Call TxCpltCallback() */ - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemTxCpltCallback(hi2c); -#else - HAL_I2C_MemTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterTxCpltCallback(hi2c); -#else - HAL_I2C_MasterTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - } - else if ((CurrentState == HAL_I2C_STATE_BUSY_TX) || \ - ((CurrentMode == HAL_I2C_MODE_MEM) && (CurrentState == HAL_I2C_STATE_BUSY_RX))) - { - if (hi2c->XferCount == 0U) - { - /* Disable BUF interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - } - else - { - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - I2C_MemoryTransmit_TXE_BTF(hi2c); - } - else - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - } - } - else - { - /* Do nothing */ - } -} - -/** - * @brief Handle BTF flag for Master transmitter - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MasterTransmit_BTF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hi2c->XferOptions; - - if (hi2c->State == HAL_I2C_STATE_BUSY_TX) - { - if (hi2c->XferCount != 0U) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - else - { - /* Call TxCpltCallback() directly if no stop mode is set */ - if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) && (CurrentXferOptions != I2C_NO_OPTION_FRAME)) - { - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_TX; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterTxCpltCallback(hi2c); -#else - HAL_I2C_MasterTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else /* Generate Stop condition then Call TxCpltCallback() */ - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemTxCpltCallback(hi2c); -#else - HAL_I2C_MemTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterTxCpltCallback(hi2c); -#else - HAL_I2C_MasterTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - } - } - else - { - /* Do nothing */ - } -} - -/** - * @brief Handle TXE and BTF flag for Memory transmitter - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MemoryTransmit_TXE_BTF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - if (hi2c->EventCount == 0U) - { - /* If Memory address size is 8Bit */ - if (hi2c->MemaddSize == I2C_MEMADD_SIZE_8BIT) - { - /* Send Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(hi2c->Memaddress); - - hi2c->EventCount += 2U; - } - /* If Memory address size is 16Bit */ - else - { - /* Send MSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_MSB(hi2c->Memaddress); - - hi2c->EventCount++; - } - } - else if (hi2c->EventCount == 1U) - { - /* Send LSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(hi2c->Memaddress); - - hi2c->EventCount++; - } - else if (hi2c->EventCount == 2U) - { - if (CurrentState == HAL_I2C_STATE_BUSY_RX) - { - /* Generate Restart */ - hi2c->Instance->CR1 |= I2C_CR1_START; - - hi2c->EventCount++; - } - else if ((hi2c->XferCount > 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - else if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX)) - { - /* Generate Stop condition then Call TxCpltCallback() */ - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemTxCpltCallback(hi2c); -#else - HAL_I2C_MemTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Do nothing */ - } - } - else - { - /* Do nothing */ - } -} - -/** - * @brief Handle RXNE flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MasterReceive_RXNE(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->State == HAL_I2C_STATE_BUSY_RX) - { - uint32_t tmp; - - tmp = hi2c->XferCount; - if (tmp > 3U) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - if (hi2c->XferCount == (uint16_t)3) - { - /* Disable BUF interrupt, this help to treat correctly the last 4 bytes - on BTF subroutine */ - /* Disable BUF interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - } - } - else if ((hi2c->XferOptions != I2C_FIRST_AND_NEXT_FRAME) && ((tmp == 1U) || (tmp == 0U))) - { - if (I2C_WaitOnSTOPRequestThroughIT(hi2c) == HAL_OK) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - hi2c->State = HAL_I2C_STATE_READY; - - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_NONE; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemRxCpltCallback(hi2c); -#else - HAL_I2C_MemRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterRxCpltCallback(hi2c); -#else - HAL_I2C_MasterRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - else - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Call user error callback */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - else - { - /* Do nothing */ - } - } -} - -/** - * @brief Handle BTF flag for Master receiver - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_MasterReceive_BTF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hi2c->XferOptions; - - if (hi2c->XferCount == 4U) - { - /* Disable BUF interrupt, this help to treat correctly the last 2 bytes - on BTF subroutine if there is a reception delay between N-1 and N byte */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - else if (hi2c->XferCount == 3U) - { - /* Disable BUF interrupt, this help to treat correctly the last 2 bytes - on BTF subroutine if there is a reception delay between N-1 and N byte */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - - if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - else if (hi2c->XferCount == 2U) - { - /* Prepare next transfer or stop current transfer */ - if ((CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - else if ((CurrentXferOptions == I2C_NEXT_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_NEXT_FRAME)) - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - else if (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else - { - /* Do nothing */ - } - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - /* Disable EVT and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - hi2c->State = HAL_I2C_STATE_READY; - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_NONE; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemRxCpltCallback(hi2c); -#else - HAL_I2C_MemRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterRxCpltCallback(hi2c); -#else - HAL_I2C_MasterRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - else - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } -} - -/** - * @brief Handle SB flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Master_SB(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - if (hi2c->EventCount == 0U) - { - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(hi2c->Devaddress); - } - else - { - hi2c->Instance->DR = I2C_7BIT_ADD_READ(hi2c->Devaddress); - } - } - else - { - if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) - { - /* Send slave 7 Bits address */ - if (hi2c->State == HAL_I2C_STATE_BUSY_TX) - { - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(hi2c->Devaddress); - } - else - { - hi2c->Instance->DR = I2C_7BIT_ADD_READ(hi2c->Devaddress); - } - - if (((hi2c->hdmatx != NULL) && (hi2c->hdmatx->XferCpltCallback != NULL)) - || ((hi2c->hdmarx != NULL) && (hi2c->hdmarx->XferCpltCallback != NULL))) - { - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } - } - else - { - if (hi2c->EventCount == 0U) - { - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(hi2c->Devaddress); - } - else if (hi2c->EventCount == 1U) - { - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_READ(hi2c->Devaddress); - } - else - { - /* Do nothing */ - } - } - } -} - -/** - * @brief Handle ADD10 flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Master_ADD10(I2C_HandleTypeDef *hi2c) -{ - /* Send slave address */ - hi2c->Instance->DR = I2C_10BIT_ADDRESS(hi2c->Devaddress); - - if (((hi2c->hdmatx != NULL) && (hi2c->hdmatx->XferCpltCallback != NULL)) - || ((hi2c->hdmarx != NULL) && (hi2c->hdmarx->XferCpltCallback != NULL))) - { - /* Enable DMA Request */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - } -} - -/** - * @brief Handle ADDR flag for Master - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Master_ADDR(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - uint32_t CurrentXferOptions = hi2c->XferOptions; - uint32_t Prev_State = hi2c->PreviousState; - - if (hi2c->State == HAL_I2C_STATE_BUSY_RX) - { - if ((hi2c->EventCount == 0U) && (CurrentMode == HAL_I2C_MODE_MEM)) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else if ((hi2c->EventCount == 0U) && (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Restart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - hi2c->EventCount++; - } - else - { - if (hi2c->XferCount == 0U) - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - else if (hi2c->XferCount == 1U) - { - if (CurrentXferOptions == I2C_NO_OPTION_FRAME) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - } - /* Prepare next transfer or stop current transfer */ - else if ((CurrentXferOptions != I2C_FIRST_AND_LAST_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME) \ - && ((Prev_State != I2C_STATE_MASTER_BUSY_RX) || (CurrentXferOptions == I2C_FIRST_FRAME))) - { - if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - } - else if (hi2c->XferCount == 2U) - { - if ((CurrentXferOptions != I2C_NEXT_FRAME) && (CurrentXferOptions != I2C_FIRST_AND_NEXT_FRAME) && (CurrentXferOptions != I2C_LAST_FRAME_NO_STOP)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_POS); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - if (((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) && ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP) || (CurrentXferOptions == I2C_LAST_FRAME))) - { - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - if (((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) && ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME_NO_STOP) || (CurrentXferOptions == I2C_LAST_FRAME))) - { - /* Enable Last DMA bit */ - SET_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } - - /* Reset Event counter */ - hi2c->EventCount = 0U; - } - } - else - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - } -} - -/** - * @brief Handle TXE flag for Slave - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_SlaveTransmit_TXE(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - if (hi2c->XferCount != 0U) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN)) - { - /* Last Byte is received, disable Interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveTxCpltCallback(hi2c); -#else - HAL_I2C_SlaveTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief Handle BTF flag for Slave transmitter - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_SlaveTransmit_BTF(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->XferCount != 0U) - { - /* Write data to DR */ - hi2c->Instance->DR = *hi2c->pBuffPtr; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } -} - -/** - * @brief Handle RXNE flag for Slave - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_SlaveReceive_RXNE(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - if (hi2c->XferCount != 0U) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - - if ((hi2c->XferCount == 0U) && (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN)) - { - /* Last Byte is received, disable Interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_BUF); - - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveRxCpltCallback(hi2c); -#else - HAL_I2C_SlaveRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief Handle BTF flag for Slave receiver - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_SlaveReceive_BTF(I2C_HandleTypeDef *hi2c) -{ - if (hi2c->XferCount != 0U) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } -} - -/** - * @brief Handle ADD flag for Slave - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param IT2Flags Interrupt2 flags to handle. - * @retval None - */ -static void I2C_Slave_ADDR(I2C_HandleTypeDef *hi2c, uint32_t IT2Flags) -{ - uint8_t TransferDirection = I2C_DIRECTION_RECEIVE; - uint16_t SlaveAddrCode; - - if (((uint32_t)hi2c->State & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - /* Disable BUF interrupt, BUF enabling is manage through slave specific interface */ - __HAL_I2C_DISABLE_IT(hi2c, (I2C_IT_BUF)); - - /* Transfer Direction requested by Master */ - if (I2C_CHECK_FLAG(IT2Flags, I2C_FLAG_TRA) == RESET) - { - TransferDirection = I2C_DIRECTION_TRANSMIT; - } - - if (I2C_CHECK_FLAG(IT2Flags, I2C_FLAG_DUALF) == RESET) - { - SlaveAddrCode = (uint16_t)hi2c->Init.OwnAddress1; - } - else - { - SlaveAddrCode = (uint16_t)hi2c->Init.OwnAddress2; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - /* Call Slave Addr callback */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->AddrCallback(hi2c, TransferDirection, SlaveAddrCode); -#else - HAL_I2C_AddrCallback(hi2c, TransferDirection, SlaveAddrCode); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - } -} - -/** - * @brief Handle STOPF flag for Slave - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Slave_STOPF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Clear STOPF flag */ - __HAL_I2C_CLEAR_STOPFLAG(hi2c); - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* If a DMA is ongoing, Update handle size context */ - if ((hi2c->Instance->CR2 & I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - if ((CurrentState == HAL_I2C_STATE_BUSY_RX) || (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN)) - { - hi2c->XferCount = (uint16_t)(__HAL_DMA_GET_COUNTER(hi2c->hdmarx)); - - if (hi2c->XferCount != 0U) - { - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - } - - /* Disable, stop the current DMA */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Abort DMA Xfer if any */ - if (HAL_DMA_GetState(hi2c->hdmarx) != HAL_DMA_STATE_READY) - { - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); - } - } - } - else - { - hi2c->XferCount = (uint16_t)(__HAL_DMA_GET_COUNTER(hi2c->hdmatx)); - - if (hi2c->XferCount != 0U) - { - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - } - - /* Disable, stop the current DMA */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - /* Abort DMA Xfer if any */ - if (HAL_DMA_GetState(hi2c->hdmatx) != HAL_DMA_STATE_READY) - { - /* Set the I2C DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); - } - } - } - } - - /* All data are not transferred, so set error code accordingly */ - if (hi2c->XferCount != 0U) - { - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - - /* Update counter */ - hi2c->XferCount--; - } - - if (hi2c->XferCount != 0U) - { - /* Set ErrorCode corresponding to a Non-Acknowledge */ - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - } - } - - if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - I2C_ITError(hi2c); - } - else - { - if (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN) - { - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveRxCpltCallback(hi2c); -#else - HAL_I2C_SlaveRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - - if (hi2c->State == HAL_I2C_STATE_LISTEN) - { - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ListenCpltCallback(hi2c); -#else - HAL_I2C_ListenCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - if ((hi2c->PreviousState == I2C_STATE_SLAVE_BUSY_RX) || (CurrentState == HAL_I2C_STATE_BUSY_RX)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveRxCpltCallback(hi2c); -#else - HAL_I2C_SlaveRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - } -} - -/** - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @retval None - */ -static void I2C_Slave_AF(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - uint32_t CurrentXferOptions = hi2c->XferOptions; - - if (((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME)) && \ - (CurrentState == HAL_I2C_STATE_LISTEN)) - { - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Clear AF flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ListenCpltCallback(hi2c); -#else - HAL_I2C_ListenCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else if (CurrentState == HAL_I2C_STATE_BUSY_TX) - { - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - - /* Clear AF flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveTxCpltCallback(hi2c); -#else - HAL_I2C_SlaveTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Clear AF flag only */ - /* State Listen, but XferOptions == FIRST or NEXT */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - } -} - -/** - * @brief I2C interrupts error process - * @param hi2c I2C handle. - * @retval None - */ -static void I2C_ITError(I2C_HandleTypeDef *hi2c) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - uint32_t CurrentError; - - if (((CurrentMode == HAL_I2C_MODE_MASTER) || (CurrentMode == HAL_I2C_MODE_MEM)) && (CurrentState == HAL_I2C_STATE_BUSY_RX)) - { - /* Disable Pos bit in I2C CR1 when error occurred in Master/Mem Receive IT Process */ - hi2c->Instance->CR1 &= ~I2C_CR1_POS; - } - - if (((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - /* keep HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_LISTEN; - } - else - { - /* If state is an abort treatment on going, don't change state */ - /* This change will be do later */ - if ((READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) != I2C_CR2_DMAEN) && (CurrentState != HAL_I2C_STATE_ABORT)) - { - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - } - hi2c->PreviousState = I2C_STATE_NONE; - } - - /* Abort DMA transfer */ - if (READ_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN) == I2C_CR2_DMAEN) - { - hi2c->Instance->CR2 &= ~I2C_CR2_DMAEN; - - if (hi2c->hdmatx->State != HAL_DMA_STATE_READY) - { - /* Set the DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmatx->XferAbortCallback = I2C_DMAAbort; - - if (HAL_DMA_Abort_IT(hi2c->hdmatx) != HAL_OK) - { - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - hi2c->State = HAL_I2C_STATE_READY; - - /* Call Directly XferAbortCallback function in case of error */ - hi2c->hdmatx->XferAbortCallback(hi2c->hdmatx); - } - } - else - { - /* Set the DMA Abort callback : - will lead to call HAL_I2C_ErrorCallback() at end of DMA abort procedure */ - hi2c->hdmarx->XferAbortCallback = I2C_DMAAbort; - - if (HAL_DMA_Abort_IT(hi2c->hdmarx) != HAL_OK) - { - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - } - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - hi2c->State = HAL_I2C_STATE_READY; - - /* Call Directly hi2c->hdmarx->XferAbortCallback function in case of error */ - hi2c->hdmarx->XferAbortCallback(hi2c->hdmarx); - } - } - } - else if (hi2c->State == HAL_I2C_STATE_ABORT) - { - hi2c->State = HAL_I2C_STATE_READY; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - } - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->AbortCpltCallback(hi2c); -#else - HAL_I2C_AbortCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Store Last receive data if any */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == SET) - { - /* Read data from DR */ - *hi2c->pBuffPtr = (uint8_t)hi2c->Instance->DR; - - /* Increment Buffer pointer */ - hi2c->pBuffPtr++; - } - - /* Call user error callback */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - - /* STOP Flag is not set after a NACK reception, BusError, ArbitrationLost, OverRun */ - CurrentError = hi2c->ErrorCode; - - if (((CurrentError & HAL_I2C_ERROR_BERR) == HAL_I2C_ERROR_BERR) || \ - ((CurrentError & HAL_I2C_ERROR_ARLO) == HAL_I2C_ERROR_ARLO) || \ - ((CurrentError & HAL_I2C_ERROR_AF) == HAL_I2C_ERROR_AF) || \ - ((CurrentError & HAL_I2C_ERROR_OVR) == HAL_I2C_ERROR_OVR)) - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR); - } - - /* So may inform upper layer that listen phase is stopped */ - /* during NACK error treatment */ - CurrentState = hi2c->State; - if (((hi2c->ErrorCode & HAL_I2C_ERROR_AF) == HAL_I2C_ERROR_AF) && (CurrentState == HAL_I2C_STATE_LISTEN)) - { - hi2c->XferOptions = I2C_NO_OPTION_FRAME; - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ListenCpltCallback(hi2c); -#else - HAL_I2C_ListenCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } -} - -/** - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_MasterRequestWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hi2c->XferOptions; - - /* Generate Start condition if first transfer */ - if ((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_NO_OPTION_FRAME)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_RX) - { - /* Generate ReStart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else - { - /* Do nothing */ - } - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) - { - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); - } - else - { - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(DevAddress); - - /* Wait until ADD10 flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADD10, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_10BIT_ADDRESS(DevAddress); - } - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Master sends target device address for read request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_MasterRequestRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Timeout, uint32_t Tickstart) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hi2c->XferOptions; - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start condition if first transfer */ - if ((CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_FIRST_FRAME) || (CurrentXferOptions == I2C_NO_OPTION_FRAME)) - { - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else if (hi2c->PreviousState == I2C_STATE_MASTER_BUSY_TX) - { - /* Generate ReStart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - } - else - { - /* Do nothing */ - } - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_7BIT) - { - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_READ(DevAddress); - } - else - { - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_WRITE(DevAddress); - - /* Wait until ADD10 flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADD10, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_10BIT_ADDRESS(DevAddress); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Generate Restart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send header of slave address */ - hi2c->Instance->DR = I2C_10BIT_HEADER_READ(DevAddress); - } - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Master sends target device address followed by internal memory address for write request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_RequestMemoryWrite(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart) -{ - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* If Memory address size is 8Bit */ - if (MemAddSize == I2C_MEMADD_SIZE_8BIT) - { - /* Send Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); - } - /* If Memory address size is 16Bit */ - else - { - /* Send MSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_MSB(MemAddress); - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Send LSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); - } - - return HAL_OK; -} - -/** - * @brief Master sends target device address followed by internal memory address for read request. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param DevAddress Target device address: The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param MemAddress Internal memory address - * @param MemAddSize Size of internal memory address - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint32_t Timeout, uint32_t Tickstart) -{ - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_WRITE(DevAddress); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - /* Clear ADDR flag */ - __HAL_I2C_CLEAR_ADDRFLAG(hi2c); - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* If Memory address size is 8Bit */ - if (MemAddSize == I2C_MEMADD_SIZE_8BIT) - { - /* Send Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); - } - /* If Memory address size is 16Bit */ - else - { - /* Send MSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_MSB(MemAddress); - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Send LSB of Memory Address */ - hi2c->Instance->DR = I2C_MEM_ADD_LSB(MemAddress); - } - - /* Wait until TXE flag is set */ - if (I2C_WaitOnTXEFlagUntilTimeout(hi2c, Timeout, Tickstart) != HAL_OK) - { - if (hi2c->ErrorCode == HAL_I2C_ERROR_AF) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - return HAL_ERROR; - } - - /* Generate Restart */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_SB, RESET, Timeout, Tickstart) != HAL_OK) - { - if (READ_BIT(hi2c->Instance->CR1, I2C_CR1_START) == I2C_CR1_START) - { - hi2c->ErrorCode = HAL_I2C_WRONG_START; - } - return HAL_TIMEOUT; - } - - /* Send slave address */ - hi2c->Instance->DR = I2C_7BIT_ADD_READ(DevAddress); - - /* Wait until ADDR flag is set */ - if (I2C_WaitOnMasterAddressFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, Timeout, Tickstart) != HAL_OK) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief DMA I2C process complete callback. - * @param hdma DMA handle - * @retval None - */ -static void I2C_DMAXferCplt(DMA_HandleTypeDef *hdma) -{ - I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - HAL_I2C_ModeTypeDef CurrentMode = hi2c->Mode; - uint32_t CurrentXferOptions = hi2c->XferOptions; - - /* Disable EVT and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Clear Complete callback */ - if (hi2c->hdmatx != NULL) - { - hi2c->hdmatx->XferCpltCallback = NULL; - } - if (hi2c->hdmarx != NULL) - { - hi2c->hdmarx->XferCpltCallback = NULL; - } - - if ((((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_BUSY_TX) == (uint32_t)HAL_I2C_STATE_BUSY_TX) || ((((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_BUSY_RX) == (uint32_t)HAL_I2C_STATE_BUSY_RX) && (CurrentMode == HAL_I2C_MODE_SLAVE))) - { - /* Disable DMA Request */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - hi2c->XferCount = 0U; - - if (CurrentState == HAL_I2C_STATE_BUSY_TX_LISTEN) - { - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_TX; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveTxCpltCallback(hi2c); -#else - HAL_I2C_SlaveTxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else if (CurrentState == HAL_I2C_STATE_BUSY_RX_LISTEN) - { - /* Set state at HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; - hi2c->State = HAL_I2C_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->SlaveRxCpltCallback(hi2c); -#else - HAL_I2C_SlaveRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - /* Do nothing */ - } - - /* Enable EVT and ERR interrupt to treat end of transfer in IRQ handler */ - __HAL_I2C_ENABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - } - /* Check current Mode, in case of treatment DMA handler have been preempted by a prior interrupt */ - else if (hi2c->Mode != HAL_I2C_MODE_NONE) - { - if (hi2c->XferCount == (uint16_t)1) - { - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - } - - /* Disable EVT and ERR interrupt */ - __HAL_I2C_DISABLE_IT(hi2c, I2C_IT_EVT | I2C_IT_ERR); - - /* Prepare next transfer or stop current transfer */ - if ((CurrentXferOptions == I2C_NO_OPTION_FRAME) || (CurrentXferOptions == I2C_FIRST_AND_LAST_FRAME) || (CurrentXferOptions == I2C_OTHER_AND_LAST_FRAME) || (CurrentXferOptions == I2C_LAST_FRAME)) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - } - - /* Disable Last DMA */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_LAST); - - /* Disable DMA Request */ - CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_DMAEN); - - hi2c->XferCount = 0U; - - /* Check if Errors has been detected during transfer */ - if (hi2c->ErrorCode != HAL_I2C_ERROR_NONE) - { -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->State = HAL_I2C_STATE_READY; - - if (hi2c->Mode == HAL_I2C_MODE_MEM) - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_NONE; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MemRxCpltCallback(hi2c); -#else - HAL_I2C_MemRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->PreviousState = I2C_STATE_MASTER_BUSY_RX; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->MasterRxCpltCallback(hi2c); -#else - HAL_I2C_MasterRxCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - } - } - else - { - /* Do nothing */ - } -} - -/** - * @brief DMA I2C communication error callback. - * @param hdma DMA handle - * @retval None - */ -static void I2C_DMAError(DMA_HandleTypeDef *hdma) -{ - I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Clear Complete callback */ - if (hi2c->hdmatx != NULL) - { - hi2c->hdmatx->XferCpltCallback = NULL; - } - if (hi2c->hdmarx != NULL) - { - hi2c->hdmarx->XferCpltCallback = NULL; - } - - /* Ignore DMA FIFO error */ - if (HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) - { - /* Disable Acknowledge */ - hi2c->Instance->CR1 &= ~I2C_CR1_ACK; - - hi2c->XferCount = 0U; - - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - - hi2c->ErrorCode |= HAL_I2C_ERROR_DMA; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA I2C communication abort callback - * (To be called at end of DMA Abort procedure). - * @param hdma DMA handle. - * @retval None - */ -static void I2C_DMAAbort(DMA_HandleTypeDef *hdma) -{ - __IO uint32_t count = 0U; - I2C_HandleTypeDef *hi2c = (I2C_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - HAL_I2C_StateTypeDef CurrentState = hi2c->State; - - /* During abort treatment, check that there is no pending STOP request */ - /* Wait until STOP flag is reset */ - count = I2C_TIMEOUT_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - if (count == 0U) - { - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - break; - } - count--; - } - while (READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP); - - /* Clear Complete callback */ - if (hi2c->hdmatx != NULL) - { - hi2c->hdmatx->XferCpltCallback = NULL; - } - if (hi2c->hdmarx != NULL) - { - hi2c->hdmarx->XferCpltCallback = NULL; - } - - /* Disable Acknowledge */ - CLEAR_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - hi2c->XferCount = 0U; - - /* Reset XferAbortCallback */ - if (hi2c->hdmatx != NULL) - { - hi2c->hdmatx->XferAbortCallback = NULL; - } - if (hi2c->hdmarx != NULL) - { - hi2c->hdmarx->XferAbortCallback = NULL; - } - - /* Disable I2C peripheral to prevent dummy data in buffer */ - __HAL_I2C_DISABLE(hi2c); - - /* Check if come from abort from user */ - if (hi2c->State == HAL_I2C_STATE_ABORT) - { - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode = HAL_I2C_ERROR_NONE; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->AbortCpltCallback(hi2c); -#else - HAL_I2C_AbortCpltCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } - else - { - if (((uint32_t)CurrentState & (uint32_t)HAL_I2C_STATE_LISTEN) == (uint32_t)HAL_I2C_STATE_LISTEN) - { - /* Renable I2C peripheral */ - __HAL_I2C_ENABLE(hi2c); - - /* Enable Acknowledge */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_ACK); - - /* keep HAL_I2C_STATE_LISTEN */ - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_LISTEN; - } - else - { - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - } - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - hi2c->ErrorCallback(hi2c); -#else - HAL_I2C_ErrorCallback(hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ - } -} - -/** - * @brief This function handles I2C Communication Timeout. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param Flag specifies the I2C flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart) -{ - /* Wait until flag is set */ - while (__HAL_I2C_GET_FLAG(hi2c, Flag) == Status) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for Master addressing phase. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for I2C module - * @param Flag specifies the I2C flag to check. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnMasterAddressFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Flag, uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_I2C_GET_FLAG(hi2c, Flag) == RESET) - { - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) - { - /* Generate Stop */ - SET_BIT(hi2c->Instance->CR1, I2C_CR1_STOP); - - /* Clear AF Flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of TXE flag. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnTXEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_TXE) == RESET) - { - /* Check if a NACK is detected */ - if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of BTF flag. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnBTFFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_BTF) == RESET) - { - /* Check if a NACK is detected */ - if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of STOP flag. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) -{ - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == RESET) - { - /* Check if a NACK is detected */ - if (I2C_IsAcknowledgeFailed(hi2c) != HAL_OK) - { - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of STOP request through Interrupt. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnSTOPRequestThroughIT(I2C_HandleTypeDef *hi2c) -{ - __IO uint32_t count = 0U; - - /* Wait until STOP flag is reset */ - count = I2C_TIMEOUT_STOP_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - count--; - if (count == 0U) - { - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - return HAL_ERROR; - } - } - while (READ_BIT(hi2c->Instance->CR1, I2C_CR1_STOP) == I2C_CR1_STOP); - - return HAL_OK; -} - -/** - * @brief This function handles I2C Communication Timeout for specific usage of RXNE flag. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, uint32_t Tickstart) -{ - - while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET) - { - /* Check if a STOPF is detected */ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == SET) - { - /* Clear STOP Flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - - /* Check for the Timeout */ - if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - } - return HAL_OK; -} - -/** - * @brief This function handles Acknowledge failed detection during an I2C Communication. - * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2C. - * @retval HAL status - */ -static HAL_StatusTypeDef I2C_IsAcknowledgeFailed(I2C_HandleTypeDef *hi2c) -{ - if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) - { - /* Clear NACKF Flag */ - __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF); - - hi2c->PreviousState = I2C_STATE_NONE; - hi2c->State = HAL_I2C_STATE_READY; - hi2c->Mode = HAL_I2C_MODE_NONE; - hi2c->ErrorCode |= HAL_I2C_ERROR_AF; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2c); - - return HAL_ERROR; - } - return HAL_OK; -} - -/** - * @brief Convert I2Cx OTHER_xxx XferOptions to functional XferOptions. - * @param hi2c I2C handle. - * @retval None - */ -static void I2C_ConvertOtherXferOptions(I2C_HandleTypeDef *hi2c) -{ - /* if user set XferOptions to I2C_OTHER_FRAME */ - /* it request implicitly to generate a restart condition */ - /* set XferOptions to I2C_FIRST_FRAME */ - if (hi2c->XferOptions == I2C_OTHER_FRAME) - { - hi2c->XferOptions = I2C_FIRST_FRAME; - } - /* else if user set XferOptions to I2C_OTHER_AND_LAST_FRAME */ - /* it request implicitly to generate a restart condition */ - /* then generate a stop condition at the end of transfer */ - /* set XferOptions to I2C_FIRST_AND_LAST_FRAME */ - else if (hi2c->XferOptions == I2C_OTHER_AND_LAST_FRAME) - { - hi2c->XferOptions = I2C_FIRST_AND_LAST_FRAME; - } - else - { - /* Nothing to do */ - } -} - -/** - * @} - */ - -#endif /* HAL_I2C_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c deleted file mode 100644 index ed50332005cc93c..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c +++ /dev/null @@ -1,184 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c_ex.c - * @author MCD Application Team - * @brief I2C Extension HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of I2C extension peripheral: - * + Extension features functions - * - @verbatim - ============================================================================== - ##### I2C peripheral extension features ##### - ============================================================================== - - [..] Comparing to other previous devices, the I2C interface for STM32F427xx/437xx/ - 429xx/439xx devices contains the following additional features : - - (+) Possibility to disable or enable Analog Noise Filter - (+) Use of a configured Digital Noise Filter - - ##### How to use this driver ##### - ============================================================================== - [..] This driver provides functions to configure Noise Filter - (#) Configure I2C Analog noise filter using the function HAL_I2C_AnalogFilter_Config() - (#) Configure I2C Digital noise filter using the function HAL_I2C_DigitalFilter_Config() - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup I2CEx I2CEx - * @brief I2C HAL module driver - * @{ - */ - -#ifdef HAL_I2C_MODULE_ENABLED - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup I2CEx_Exported_Functions I2C Exported Functions - * @{ - */ - - -/** @defgroup I2CEx_Exported_Functions_Group1 Extension features functions - * @brief Extension features functions - * -@verbatim - =============================================================================== - ##### Extension features functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure Noise Filters - -@endverbatim - * @{ - */ - -/** - * @brief Configures I2C Analog noise filter. - * @param hi2c pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2Cx peripheral. - * @param AnalogFilter new state of the Analog filter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); - assert_param(IS_I2C_ANALOG_FILTER(AnalogFilter)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - hi2c->State = HAL_I2C_STATE_BUSY; - - /* Disable the selected I2C peripheral */ - __HAL_I2C_DISABLE(hi2c); - - /* Reset I2Cx ANOFF bit */ - hi2c->Instance->FLTR &= ~(I2C_FLTR_ANOFF); - - /* Disable the analog filter */ - hi2c->Instance->FLTR |= AnalogFilter; - - __HAL_I2C_ENABLE(hi2c); - - hi2c->State = HAL_I2C_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configures I2C Digital noise filter. - * @param hi2c pointer to a I2C_HandleTypeDef structure that contains - * the configuration information for the specified I2Cx peripheral. - * @param DigitalFilter Coefficient of digital noise filter between 0x00 and 0x0F. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter) -{ - uint16_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_I2C_ALL_INSTANCE(hi2c->Instance)); - assert_param(IS_I2C_DIGITAL_FILTER(DigitalFilter)); - - if (hi2c->State == HAL_I2C_STATE_READY) - { - hi2c->State = HAL_I2C_STATE_BUSY; - - /* Disable the selected I2C peripheral */ - __HAL_I2C_DISABLE(hi2c); - - /* Get the old register value */ - tmpreg = hi2c->Instance->FLTR; - - /* Reset I2Cx DNF bit [3:0] */ - tmpreg &= ~(I2C_FLTR_DNF); - - /* Set I2Cx DNF coefficient */ - tmpreg |= DigitalFilter; - - /* Store the new register value */ - hi2c->Instance->FLTR = tmpreg; - - __HAL_I2C_ENABLE(hi2c); - - hi2c->State = HAL_I2C_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @} - */ - -/** - * @} - */ -#endif - -#endif /* HAL_I2C_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s.c deleted file mode 100644 index 332b6c2cae516fd..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s.c +++ /dev/null @@ -1,2095 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2s.c - * @author MCD Application Team - * @brief I2S HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Integrated Interchip Sound (I2S) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral State and Errors functions - @verbatim - =============================================================================== - ##### How to use this driver ##### - =============================================================================== - [..] - The I2S HAL driver can be used as follow: - - (#) Declare a I2S_HandleTypeDef handle structure. - (#) Initialize the I2S low level resources by implement the HAL_I2S_MspInit() API: - (##) Enable the SPIx interface clock. - (##) I2S pins configuration: - (+++) Enable the clock for the I2S GPIOs. - (+++) Configure these I2S pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_I2S_Transmit_IT() - and HAL_I2S_Receive_IT() APIs). - (+++) Configure the I2Sx interrupt priority. - (+++) Enable the NVIC I2S IRQ handle. - (##) DMA Configuration if you need to use DMA process (HAL_I2S_Transmit_DMA() - and HAL_I2S_Receive_DMA() APIs: - (+++) Declare a DMA handle structure for the Tx/Rx Stream/Channel. - (+++) Enable the DMAx interface clock. - (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. - (+++) Configure the DMA Tx/Rx Stream/Channel. - (+++) Associate the initialized DMA handle to the I2S DMA Tx/Rx handle. - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the - DMA Tx/Rx Stream/Channel. - - (#) Program the Mode, Standard, Data Format, MCLK Output, Audio frequency and Polarity - using HAL_I2S_Init() function. - - -@- The specific I2S interrupts (Transmission complete interrupt, - RXNE interrupt and Error Interrupts) will be managed using the macros - __HAL_I2S_ENABLE_IT() and __HAL_I2S_DISABLE_IT() inside the transmit and receive process. - -@- Make sure that either: - (+@) I2S PLL clock is configured or - (+@) External clock source is configured after setting correctly - the define constant EXTERNAL_CLOCK_VALUE in the stm32f4xx_hal_conf.h file. - - (#) Three mode of operations are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Send an amount of data in blocking mode using HAL_I2S_Transmit() - (+) Receive an amount of data in blocking mode using HAL_I2S_Receive() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Send an amount of data in non blocking mode using HAL_I2S_Transmit_IT() - (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback - (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_TxCpltCallback - (+) Receive an amount of data in non blocking mode using HAL_I2S_Receive_IT() - (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback - (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_RxCpltCallback - (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2S_ErrorCallback - - *** DMA mode IO operation *** - ============================== - [..] - (+) Send an amount of data in non blocking mode (DMA) using HAL_I2S_Transmit_DMA() - (+) At transmission end of half transfer HAL_I2S_TxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_TxHalfCpltCallback - (+) At transmission end of transfer HAL_I2S_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_TxCpltCallback - (+) Receive an amount of data in non blocking mode (DMA) using HAL_I2S_Receive_DMA() - (+) At reception end of half transfer HAL_I2S_RxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_RxHalfCpltCallback - (+) At reception end of transfer HAL_I2S_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_RxCpltCallback - (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2S_ErrorCallback - (+) Pause the DMA Transfer using HAL_I2S_DMAPause() - (+) Resume the DMA Transfer using HAL_I2S_DMAResume() - (+) Stop the DMA Transfer using HAL_I2S_DMAStop() - In Slave mode, if HAL_I2S_DMAStop is used to stop the communication, an error - HAL_I2S_ERROR_BUSY_LINE_RX is raised as the master continue to transmit data. - In this case __HAL_I2S_FLUSH_RX_DR macro must be used to flush the remaining data - inside DR register and avoid using DeInit/Init process for the next transfer. - - *** I2S HAL driver macros list *** - =================================== - [..] - Below the list of most used macros in I2S HAL driver. - - (+) __HAL_I2S_ENABLE: Enable the specified SPI peripheral (in I2S mode) - (+) __HAL_I2S_DISABLE: Disable the specified SPI peripheral (in I2S mode) - (+) __HAL_I2S_ENABLE_IT : Enable the specified I2S interrupts - (+) __HAL_I2S_DISABLE_IT : Disable the specified I2S interrupts - (+) __HAL_I2S_GET_FLAG: Check whether the specified I2S flag is set or not - (+) __HAL_I2S_FLUSH_RX_DR: Read DR Register to Flush RX Data - - [..] - (@) You can refer to the I2S HAL driver header file for more useful macros - - *** I2S HAL driver macros list *** - =================================== - [..] - Callback registration: - - (#) The compilation flag USE_HAL_I2S_REGISTER_CALLBACKS when set to 1U - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_I2S_RegisterCallback() to register an interrupt callback. - - Function HAL_I2S_RegisterCallback() allows to register following callbacks: - (++) TxCpltCallback : I2S Tx Completed callback - (++) RxCpltCallback : I2S Rx Completed callback - (++) TxRxCpltCallback : I2S TxRx Completed callback - (++) TxHalfCpltCallback : I2S Tx Half Completed callback - (++) RxHalfCpltCallback : I2S Rx Half Completed callback - (++) ErrorCallback : I2S Error callback - (++) MspInitCallback : I2S Msp Init callback - (++) MspDeInitCallback : I2S Msp DeInit callback - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - - (#) Use function HAL_I2S_UnRegisterCallback to reset a callback to the default - weak function. - HAL_I2S_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (++) TxCpltCallback : I2S Tx Completed callback - (++) RxCpltCallback : I2S Rx Completed callback - (++) TxRxCpltCallback : I2S TxRx Completed callback - (++) TxHalfCpltCallback : I2S Tx Half Completed callback - (++) RxHalfCpltCallback : I2S Rx Half Completed callback - (++) ErrorCallback : I2S Error callback - (++) MspInitCallback : I2S Msp Init callback - (++) MspDeInitCallback : I2S Msp DeInit callback - - [..] - By default, after the HAL_I2S_Init() and when the state is HAL_I2S_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_I2S_MasterTxCpltCallback(), HAL_I2S_MasterRxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_I2S_Init()/ HAL_I2S_DeInit() only when - these callbacks are null (not registered beforehand). - If MspInit or MspDeInit are not null, the HAL_I2S_Init()/ HAL_I2S_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - - [..] - Callbacks can be registered/unregistered in HAL_I2S_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_I2S_STATE_READY or HAL_I2S_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_I2S_RegisterCallback() before calling HAL_I2S_DeInit() - or HAL_I2S_Init() function. - - [..] - When the compilation define USE_HAL_I2S_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -#ifdef HAL_I2S_MODULE_ENABLED - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup I2S I2S - * @brief I2S HAL module driver - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -#define I2S_TIMEOUT_FLAG 100U /*!< Timeout 100 ms */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup I2S_Private_Functions I2S Private Functions - * @{ - */ -static void I2S_DMATxCplt(DMA_HandleTypeDef *hdma); -static void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma); -static void I2S_DMARxCplt(DMA_HandleTypeDef *hdma); -static void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma); -static void I2S_DMAError(DMA_HandleTypeDef *hdma); -static void I2S_Transmit_IT(I2S_HandleTypeDef *hi2s); -static void I2S_Receive_IT(I2S_HandleTypeDef *hi2s); -static void I2S_IRQHandler(I2S_HandleTypeDef *hi2s); -static HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag, FlagStatus State, - uint32_t Timeout); -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ - -/** @defgroup I2S_Exported_Functions I2S Exported Functions - * @{ - */ - -/** @defgroup I2S_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - de-initialize the I2Sx peripheral in simplex mode: - - (+) User must Implement HAL_I2S_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). - - (+) Call the function HAL_I2S_Init() to configure the selected device with - the selected configuration: - (++) Mode - (++) Standard - (++) Data Format - (++) MCLK Output - (++) Audio frequency - (++) Polarity - (++) Full duplex mode - - (+) Call the function HAL_I2S_DeInit() to restore the default configuration - of the selected I2Sx peripheral. - @endverbatim - * @{ - */ - -/** - * @brief Initializes the I2S according to the specified parameters - * in the I2S_InitTypeDef and create the associated handle. - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_Init(I2S_HandleTypeDef *hi2s) -{ - uint32_t i2sdiv; - uint32_t i2sodd; - uint32_t packetlength; - uint32_t tmp; - uint32_t i2sclk; -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - uint16_t tmpreg; -#endif - - /* Check the I2S handle allocation */ - if (hi2s == NULL) - { - return HAL_ERROR; - } - - /* Check the I2S parameters */ - assert_param(IS_I2S_ALL_INSTANCE(hi2s->Instance)); - assert_param(IS_I2S_MODE(hi2s->Init.Mode)); - assert_param(IS_I2S_STANDARD(hi2s->Init.Standard)); - assert_param(IS_I2S_DATA_FORMAT(hi2s->Init.DataFormat)); - assert_param(IS_I2S_MCLK_OUTPUT(hi2s->Init.MCLKOutput)); - assert_param(IS_I2S_AUDIO_FREQ(hi2s->Init.AudioFreq)); - assert_param(IS_I2S_CPOL(hi2s->Init.CPOL)); - assert_param(IS_I2S_CLOCKSOURCE(hi2s->Init.ClockSource)); - - if (hi2s->State == HAL_I2S_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hi2s->Lock = HAL_UNLOCKED; - - /* Initialize Default I2S IrqHandler ISR */ - hi2s->IrqHandlerISR = I2S_IRQHandler; - -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - /* Init the I2S Callback settings */ - hi2s->TxCpltCallback = HAL_I2S_TxCpltCallback; /* Legacy weak TxCpltCallback */ - hi2s->RxCpltCallback = HAL_I2S_RxCpltCallback; /* Legacy weak RxCpltCallback */ -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - hi2s->TxRxCpltCallback = HAL_I2SEx_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - hi2s->TxHalfCpltCallback = HAL_I2S_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - hi2s->RxHalfCpltCallback = HAL_I2S_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - hi2s->TxRxHalfCpltCallback = HAL_I2SEx_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - hi2s->ErrorCallback = HAL_I2S_ErrorCallback; /* Legacy weak ErrorCallback */ - - if (hi2s->MspInitCallback == NULL) - { - hi2s->MspInitCallback = HAL_I2S_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware : GPIO, CLOCK, NVIC... */ - hi2s->MspInitCallback(hi2s); -#else - /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ - HAL_I2S_MspInit(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - - hi2s->State = HAL_I2S_STATE_BUSY; - - /*----------------------- SPIx I2SCFGR & I2SPR Configuration ----------------*/ - /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ - CLEAR_BIT(hi2s->Instance->I2SCFGR, (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CKPOL | \ - SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC | SPI_I2SCFGR_I2SCFG | \ - SPI_I2SCFGR_I2SE | SPI_I2SCFGR_I2SMOD)); - hi2s->Instance->I2SPR = 0x0002U; - - /*----------------------- I2SPR: I2SDIV and ODD Calculation -----------------*/ - /* If the requested audio frequency is not the default, compute the prescaler */ - if (hi2s->Init.AudioFreq != I2S_AUDIOFREQ_DEFAULT) - { - /* Check the frame length (For the Prescaler computing) ********************/ - if (hi2s->Init.DataFormat == I2S_DATAFORMAT_16B) - { - /* Packet length is 16 bits */ - packetlength = 16U; - } - else - { - /* Packet length is 32 bits */ - packetlength = 32U; - } - - /* I2S standard */ - if (hi2s->Init.Standard <= I2S_STANDARD_LSB) - { - /* In I2S standard packet length is multiplied by 2 */ - packetlength = packetlength * 2U; - } - - /* Get the source clock value **********************************************/ -#if defined(I2S_APB1_APB2_FEATURE) - if (IS_I2S_APB1_INSTANCE(hi2s->Instance)) - { - i2sclk = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_I2S_APB1); - } - else - { - i2sclk = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_I2S_APB2); - } -#else - i2sclk = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_I2S); -#endif /* I2S_APB1_APB2_FEATURE */ - - /* Compute the Real divider depending on the MCLK output state, with a floating point */ - if (hi2s->Init.MCLKOutput == I2S_MCLKOUTPUT_ENABLE) - { - /* MCLK output is enabled */ - if (hi2s->Init.DataFormat != I2S_DATAFORMAT_16B) - { - tmp = (uint32_t)(((((i2sclk / (packetlength * 4U)) * 10U) / hi2s->Init.AudioFreq)) + 5U); - } - else - { - tmp = (uint32_t)(((((i2sclk / (packetlength * 8U)) * 10U) / hi2s->Init.AudioFreq)) + 5U); - } - } - else - { - /* MCLK output is disabled */ - tmp = (uint32_t)(((((i2sclk / packetlength) * 10U) / hi2s->Init.AudioFreq)) + 5U); - } - - /* Remove the flatting point */ - tmp = tmp / 10U; - - /* Check the parity of the divider */ - i2sodd = (uint32_t)(tmp & (uint32_t)1U); - - /* Compute the i2sdiv prescaler */ - i2sdiv = (uint32_t)((tmp - i2sodd) / 2U); - - /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ - i2sodd = (uint32_t)(i2sodd << 8U); - } - else - { - /* Set the default values */ - i2sdiv = 2U; - i2sodd = 0U; - } - - /* Test if the divider is 1 or 0 or greater than 0xFF */ - if ((i2sdiv < 2U) || (i2sdiv > 0xFFU)) - { - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_PRESCALER); - return HAL_ERROR; - } - - /*----------------------- SPIx I2SCFGR & I2SPR Configuration ----------------*/ - - /* Write to SPIx I2SPR register the computed value */ - hi2s->Instance->I2SPR = (uint32_t)((uint32_t)i2sdiv | (uint32_t)(i2sodd | (uint32_t)hi2s->Init.MCLKOutput)); - - /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ - /* And configure the I2S with the I2S_InitStruct values */ - MODIFY_REG(hi2s->Instance->I2SCFGR, (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | \ - SPI_I2SCFGR_CKPOL | SPI_I2SCFGR_I2SSTD | \ - SPI_I2SCFGR_PCMSYNC | SPI_I2SCFGR_I2SCFG | \ - SPI_I2SCFGR_I2SE | SPI_I2SCFGR_I2SMOD), \ - (SPI_I2SCFGR_I2SMOD | hi2s->Init.Mode | \ - hi2s->Init.Standard | hi2s->Init.DataFormat | \ - hi2s->Init.CPOL)); - -#if defined(SPI_I2SCFGR_ASTRTEN) - if ((hi2s->Init.Standard == I2S_STANDARD_PCM_SHORT) || ((hi2s->Init.Standard == I2S_STANDARD_PCM_LONG))) - { - /* Write to SPIx I2SCFGR */ - SET_BIT(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_ASTRTEN); - } -#endif /* SPI_I2SCFGR_ASTRTEN */ - -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - - /* Configure the I2S extended if the full duplex mode is enabled */ - assert_param(IS_I2S_FULLDUPLEX_MODE(hi2s->Init.FullDuplexMode)); - - if (hi2s->Init.FullDuplexMode == I2S_FULLDUPLEXMODE_ENABLE) - { - /* Set FullDuplex I2S IrqHandler ISR if FULLDUPLEXMODE is enabled */ - hi2s->IrqHandlerISR = HAL_I2SEx_FullDuplex_IRQHandler; - - /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ - CLEAR_BIT(I2SxEXT(hi2s->Instance)->I2SCFGR, (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CKPOL | \ - SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC | SPI_I2SCFGR_I2SCFG | \ - SPI_I2SCFGR_I2SE | SPI_I2SCFGR_I2SMOD)); - I2SxEXT(hi2s->Instance)->I2SPR = 2U; - - /* Get the I2SCFGR register value */ - tmpreg = I2SxEXT(hi2s->Instance)->I2SCFGR; - - /* Get the mode to be configured for the extended I2S */ - if ((hi2s->Init.Mode == I2S_MODE_MASTER_TX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_TX)) - { - tmp = I2S_MODE_SLAVE_RX; - } - else /* I2S_MODE_MASTER_RX || I2S_MODE_SLAVE_RX */ - { - tmp = I2S_MODE_SLAVE_TX; - } - - /* Configure the I2S Slave with the I2S Master parameter values */ - tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | \ - (uint16_t)tmp | \ - (uint16_t)hi2s->Init.Standard | \ - (uint16_t)hi2s->Init.DataFormat | \ - (uint16_t)hi2s->Init.CPOL); - - /* Write to SPIx I2SCFGR */ - WRITE_REG(I2SxEXT(hi2s->Instance)->I2SCFGR, tmpreg); - } -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->State = HAL_I2S_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the I2S peripheral - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_DeInit(I2S_HandleTypeDef *hi2s) -{ - /* Check the I2S handle allocation */ - if (hi2s == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_I2S_ALL_INSTANCE(hi2s->Instance)); - - hi2s->State = HAL_I2S_STATE_BUSY; - - /* Disable the I2S Peripheral Clock */ - __HAL_I2S_DISABLE(hi2s); - -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - if (hi2s->MspDeInitCallback == NULL) - { - hi2s->MspDeInitCallback = HAL_I2S_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ - hi2s->MspDeInitCallback(hi2s); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ - HAL_I2S_MspDeInit(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->State = HAL_I2S_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hi2s); - - return HAL_OK; -} - -/** - * @brief I2S MSP Init - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -__weak void HAL_I2S_MspInit(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_I2S_MspInit could be implemented in the user file - */ -} - -/** - * @brief I2S MSP DeInit - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -__weak void HAL_I2S_MspDeInit(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_I2S_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -/** - * @brief Register a User I2S Callback - * To be used instead of the weak predefined callback - * @param hi2s Pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for the specified I2S. - * @param CallbackID ID of the callback to be registered - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_RegisterCallback(I2S_HandleTypeDef *hi2s, HAL_I2S_CallbackIDTypeDef CallbackID, - pI2S_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hi2s->ErrorCode |= HAL_I2S_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hi2s); - - if (HAL_I2S_STATE_READY == hi2s->State) - { - switch (CallbackID) - { - case HAL_I2S_TX_COMPLETE_CB_ID : - hi2s->TxCpltCallback = pCallback; - break; - - case HAL_I2S_RX_COMPLETE_CB_ID : - hi2s->RxCpltCallback = pCallback; - break; - -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - case HAL_I2S_TX_RX_COMPLETE_CB_ID : - hi2s->TxRxCpltCallback = pCallback; - break; -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - - case HAL_I2S_TX_HALF_COMPLETE_CB_ID : - hi2s->TxHalfCpltCallback = pCallback; - break; - - case HAL_I2S_RX_HALF_COMPLETE_CB_ID : - hi2s->RxHalfCpltCallback = pCallback; - break; - -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - case HAL_I2S_TX_RX_HALF_COMPLETE_CB_ID : - hi2s->TxRxHalfCpltCallback = pCallback; - break; -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - - case HAL_I2S_ERROR_CB_ID : - hi2s->ErrorCallback = pCallback; - break; - - case HAL_I2S_MSPINIT_CB_ID : - hi2s->MspInitCallback = pCallback; - break; - - case HAL_I2S_MSPDEINIT_CB_ID : - hi2s->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_I2S_STATE_RESET == hi2s->State) - { - switch (CallbackID) - { - case HAL_I2S_MSPINIT_CB_ID : - hi2s->MspInitCallback = pCallback; - break; - - case HAL_I2S_MSPDEINIT_CB_ID : - hi2s->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2s); - return status; -} - -/** - * @brief Unregister an I2S Callback - * I2S callback is redirected to the weak predefined callback - * @param hi2s Pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for the specified I2S. - * @param CallbackID ID of the callback to be unregistered - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_UnRegisterCallback(I2S_HandleTypeDef *hi2s, HAL_I2S_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hi2s); - - if (HAL_I2S_STATE_READY == hi2s->State) - { - switch (CallbackID) - { - case HAL_I2S_TX_COMPLETE_CB_ID : - hi2s->TxCpltCallback = HAL_I2S_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_I2S_RX_COMPLETE_CB_ID : - hi2s->RxCpltCallback = HAL_I2S_RxCpltCallback; /* Legacy weak RxCpltCallback */ - break; - -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - case HAL_I2S_TX_RX_COMPLETE_CB_ID : - hi2s->TxRxCpltCallback = HAL_I2SEx_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ - break; -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - - case HAL_I2S_TX_HALF_COMPLETE_CB_ID : - hi2s->TxHalfCpltCallback = HAL_I2S_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - break; - - case HAL_I2S_RX_HALF_COMPLETE_CB_ID : - hi2s->RxHalfCpltCallback = HAL_I2S_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - break; - -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - case HAL_I2S_TX_RX_HALF_COMPLETE_CB_ID : - hi2s->TxRxHalfCpltCallback = HAL_I2SEx_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ - break; -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - - case HAL_I2S_ERROR_CB_ID : - hi2s->ErrorCallback = HAL_I2S_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_I2S_MSPINIT_CB_ID : - hi2s->MspInitCallback = HAL_I2S_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_I2S_MSPDEINIT_CB_ID : - hi2s->MspDeInitCallback = HAL_I2S_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_I2S_STATE_RESET == hi2s->State) - { - switch (CallbackID) - { - case HAL_I2S_MSPINIT_CB_ID : - hi2s->MspInitCallback = HAL_I2S_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_I2S_MSPDEINIT_CB_ID : - hi2s->MspDeInitCallback = HAL_I2S_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hi2s); - return status; -} -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup I2S_Exported_Functions_Group2 IO operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the I2S data - transfers. - - (#) There are two modes of transfer: - (++) Blocking mode : The communication is performed in the polling mode. - The status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode : The communication is performed using Interrupts - or DMA. These functions return the status of the transfer startup. - The end of the data processing will be indicated through the - dedicated I2S IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - - (#) Blocking mode functions are : - (++) HAL_I2S_Transmit() - (++) HAL_I2S_Receive() - - (#) No-Blocking mode functions with Interrupt are : - (++) HAL_I2S_Transmit_IT() - (++) HAL_I2S_Receive_IT() - - (#) No-Blocking mode functions with DMA are : - (++) HAL_I2S_Transmit_DMA() - (++) HAL_I2S_Receive_DMA() - - (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: - (++) HAL_I2S_TxCpltCallback() - (++) HAL_I2S_RxCpltCallback() - (++) HAL_I2S_ErrorCallback() - -@endverbatim - * @{ - */ - -/** - * @brief Transmit an amount of data in blocking mode - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pData a 16-bit pointer to data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 24-bit or 32-bit data length. - * @param Timeout Timeout duration - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_Transmit(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tmpreg_cfgr; - - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - if (hi2s->State != HAL_I2S_STATE_READY) - { - __HAL_UNLOCK(hi2s); - return HAL_BUSY; - } - - /* Set state and reset error code */ - hi2s->State = HAL_I2S_STATE_BUSY_TX; - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->pTxBuffPtr = pData; - - tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - - if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) - { - hi2s->TxXferSize = (Size << 1U); - hi2s->TxXferCount = (Size << 1U); - } - else - { - hi2s->TxXferSize = Size; - hi2s->TxXferCount = Size; - } - - tmpreg_cfgr = hi2s->Instance->I2SCFGR; - - /* Check if the I2S is already enabled */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) - { - /* Enable I2S peripheral */ - __HAL_I2S_ENABLE(hi2s); - } - - /* Wait until TXE flag is set */ - if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - hi2s->State = HAL_I2S_STATE_READY; - __HAL_UNLOCK(hi2s); - return HAL_ERROR; - } - - while (hi2s->TxXferCount > 0U) - { - hi2s->Instance->DR = (*hi2s->pTxBuffPtr); - hi2s->pTxBuffPtr++; - hi2s->TxXferCount--; - - /* Wait until TXE flag is set */ - if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - hi2s->State = HAL_I2S_STATE_READY; - __HAL_UNLOCK(hi2s); - return HAL_ERROR; - } - - /* Check if an underrun occurs */ - if (__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_UDR) == SET) - { - /* Clear underrun flag */ - __HAL_I2S_CLEAR_UDRFLAG(hi2s); - - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); - } - } - - /* Check if Slave mode is selected */ - if (((tmpreg_cfgr & SPI_I2SCFGR_I2SCFG) == I2S_MODE_SLAVE_TX) - || ((tmpreg_cfgr & SPI_I2SCFGR_I2SCFG) == I2S_MODE_SLAVE_RX)) - { - /* Wait until Busy flag is reset */ - if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_BSY, RESET, Timeout) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - hi2s->State = HAL_I2S_STATE_READY; - __HAL_UNLOCK(hi2s); - return HAL_ERROR; - } - } - - hi2s->State = HAL_I2S_STATE_READY; - __HAL_UNLOCK(hi2s); - return HAL_OK; -} - -/** - * @brief Receive an amount of data in blocking mode - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pData a 16-bit pointer to data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 24-bit or 32-bit data length. - * @param Timeout Timeout duration - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @note In I2S Master Receiver mode, just after enabling the peripheral the clock will be generate - * in continuous way and as the I2S is not disabled at the end of the I2S transaction. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_Receive(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tmpreg_cfgr; - - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - if (hi2s->State != HAL_I2S_STATE_READY) - { - __HAL_UNLOCK(hi2s); - return HAL_BUSY; - } - - /* Set state and reset error code */ - hi2s->State = HAL_I2S_STATE_BUSY_RX; - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->pRxBuffPtr = pData; - - tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - - if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) - { - hi2s->RxXferSize = (Size << 1U); - hi2s->RxXferCount = (Size << 1U); - } - else - { - hi2s->RxXferSize = Size; - hi2s->RxXferCount = Size; - } - - /* Check if the I2S is already enabled */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) - { - /* Enable I2S peripheral */ - __HAL_I2S_ENABLE(hi2s); - } - - /* Check if Master Receiver mode is selected */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX) - { - /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read - access to the SPI_SR register. */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - } - - /* Receive data */ - while (hi2s->RxXferCount > 0U) - { - /* Wait until RXNE flag is set */ - if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_RXNE, SET, Timeout) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - hi2s->State = HAL_I2S_STATE_READY; - __HAL_UNLOCK(hi2s); - return HAL_ERROR; - } - - (*hi2s->pRxBuffPtr) = (uint16_t)hi2s->Instance->DR; - hi2s->pRxBuffPtr++; - hi2s->RxXferCount--; - - /* Check if an overrun occurs */ - if (__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_OVR) == SET) - { - /* Clear overrun flag */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); - } - } - - hi2s->State = HAL_I2S_STATE_READY; - __HAL_UNLOCK(hi2s); - return HAL_OK; -} - -/** - * @brief Transmit an amount of data in non-blocking mode with Interrupt - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pData a 16-bit pointer to data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 24-bit or 32-bit data length. - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_Transmit_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size) -{ - uint32_t tmpreg_cfgr; - - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - if (hi2s->State != HAL_I2S_STATE_READY) - { - __HAL_UNLOCK(hi2s); - return HAL_BUSY; - } - - /* Set state and reset error code */ - hi2s->State = HAL_I2S_STATE_BUSY_TX; - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->pTxBuffPtr = pData; - - tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - - if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) - { - hi2s->TxXferSize = (Size << 1U); - hi2s->TxXferCount = (Size << 1U); - } - else - { - hi2s->TxXferSize = Size; - hi2s->TxXferCount = Size; - } - - /* Enable TXE and ERR interrupt */ - __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - /* Check if the I2S is already enabled */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) - { - /* Enable I2S peripheral */ - __HAL_I2S_ENABLE(hi2s); - } - - __HAL_UNLOCK(hi2s); - return HAL_OK; -} - -/** - * @brief Receive an amount of data in non-blocking mode with Interrupt - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pData a 16-bit pointer to the Receive data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 24-bit or 32-bit data length. - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @note It is recommended to use DMA for the I2S receiver to avoid de-synchronization - * between Master and Slave otherwise the I2S interrupt should be optimized. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_Receive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size) -{ - uint32_t tmpreg_cfgr; - - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - if (hi2s->State != HAL_I2S_STATE_READY) - { - __HAL_UNLOCK(hi2s); - return HAL_BUSY; - } - - /* Set state and reset error code */ - hi2s->State = HAL_I2S_STATE_BUSY_RX; - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->pRxBuffPtr = pData; - - tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - - if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) - { - hi2s->RxXferSize = (Size << 1U); - hi2s->RxXferCount = (Size << 1U); - } - else - { - hi2s->RxXferSize = Size; - hi2s->RxXferCount = Size; - } - - /* Enable RXNE and ERR interrupt */ - __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - /* Check if the I2S is already enabled */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) - { - /* Enable I2S peripheral */ - __HAL_I2S_ENABLE(hi2s); - } - - __HAL_UNLOCK(hi2s); - return HAL_OK; -} - -/** - * @brief Transmit an amount of data in non-blocking mode with DMA - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pData a 16-bit pointer to the Transmit data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 24-bit or 32-bit data length. - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_Transmit_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size) -{ - uint32_t tmpreg_cfgr; - - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - if (hi2s->State != HAL_I2S_STATE_READY) - { - __HAL_UNLOCK(hi2s); - return HAL_BUSY; - } - - /* Set state and reset error code */ - hi2s->State = HAL_I2S_STATE_BUSY_TX; - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->pTxBuffPtr = pData; - - tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - - if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) - { - hi2s->TxXferSize = (Size << 1U); - hi2s->TxXferCount = (Size << 1U); - } - else - { - hi2s->TxXferSize = Size; - hi2s->TxXferCount = Size; - } - - /* Set the I2S Tx DMA Half transfer complete callback */ - hi2s->hdmatx->XferHalfCpltCallback = I2S_DMATxHalfCplt; - - /* Set the I2S Tx DMA transfer complete callback */ - hi2s->hdmatx->XferCpltCallback = I2S_DMATxCplt; - - /* Set the DMA error callback */ - hi2s->hdmatx->XferErrorCallback = I2S_DMAError; - - /* Enable the Tx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hi2s->hdmatx, - (uint32_t)hi2s->pTxBuffPtr, - (uint32_t)&hi2s->Instance->DR, - hi2s->TxXferSize)) - { - /* Update SPI error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); - hi2s->State = HAL_I2S_STATE_READY; - - __HAL_UNLOCK(hi2s); - return HAL_ERROR; - } - - /* Check if the I2S is already enabled */ - if (HAL_IS_BIT_CLR(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) - { - /* Enable I2S peripheral */ - __HAL_I2S_ENABLE(hi2s); - } - - /* Check if the I2S Tx request is already enabled */ - if (HAL_IS_BIT_CLR(hi2s->Instance->CR2, SPI_CR2_TXDMAEN)) - { - /* Enable Tx DMA Request */ - SET_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); - } - - __HAL_UNLOCK(hi2s); - return HAL_OK; -} - -/** - * @brief Receive an amount of data in non-blocking mode with DMA - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pData a 16-bit pointer to the Receive data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 24-bit or 32-bit data length. - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_Receive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size) -{ - uint32_t tmpreg_cfgr; - - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - if (hi2s->State != HAL_I2S_STATE_READY) - { - __HAL_UNLOCK(hi2s); - return HAL_BUSY; - } - - /* Set state and reset error code */ - hi2s->State = HAL_I2S_STATE_BUSY_RX; - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->pRxBuffPtr = pData; - - tmpreg_cfgr = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - - if ((tmpreg_cfgr == I2S_DATAFORMAT_24B) || (tmpreg_cfgr == I2S_DATAFORMAT_32B)) - { - hi2s->RxXferSize = (Size << 1U); - hi2s->RxXferCount = (Size << 1U); - } - else - { - hi2s->RxXferSize = Size; - hi2s->RxXferCount = Size; - } - - /* Set the I2S Rx DMA Half transfer complete callback */ - hi2s->hdmarx->XferHalfCpltCallback = I2S_DMARxHalfCplt; - - /* Set the I2S Rx DMA transfer complete callback */ - hi2s->hdmarx->XferCpltCallback = I2S_DMARxCplt; - - /* Set the DMA error callback */ - hi2s->hdmarx->XferErrorCallback = I2S_DMAError; - - /* Check if Master Receiver mode is selected */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX) - { - /* Clear the Overrun Flag by a read operation to the SPI_DR register followed by a read - access to the SPI_SR register. */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - } - - /* Enable the Rx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hi2s->hdmarx, (uint32_t)&hi2s->Instance->DR, (uint32_t)hi2s->pRxBuffPtr, - hi2s->RxXferSize)) - { - /* Update SPI error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); - hi2s->State = HAL_I2S_STATE_READY; - - __HAL_UNLOCK(hi2s); - return HAL_ERROR; - } - - /* Check if the I2S is already enabled */ - if (HAL_IS_BIT_CLR(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) - { - /* Enable I2S peripheral */ - __HAL_I2S_ENABLE(hi2s); - } - - /* Check if the I2S Rx request is already enabled */ - if (HAL_IS_BIT_CLR(hi2s->Instance->CR2, SPI_CR2_RXDMAEN)) - { - /* Enable Rx DMA Request */ - SET_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); - } - - __HAL_UNLOCK(hi2s); - return HAL_OK; -} - -/** - * @brief Pauses the audio DMA Stream/Channel playing from the Media. - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_DMAPause(I2S_HandleTypeDef *hi2s) -{ - /* Process Locked */ - __HAL_LOCK(hi2s); - - if (hi2s->State == HAL_I2S_STATE_BUSY_TX) - { - /* Disable the I2S DMA Tx request */ - CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); - } - else if (hi2s->State == HAL_I2S_STATE_BUSY_RX) - { - /* Disable the I2S DMA Rx request */ - CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); - } -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - else if (hi2s->State == HAL_I2S_STATE_BUSY_TX_RX) - { - /* Pause the audio file playing by disabling the I2S DMA request */ - CLEAR_BIT(hi2s->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN)); - CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN)); - } -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - else - { - /* nothing to do */ - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2s); - - return HAL_OK; -} - -/** - * @brief Resumes the audio DMA Stream/Channel playing from the Media. - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_DMAResume(I2S_HandleTypeDef *hi2s) -{ - /* Process Locked */ - __HAL_LOCK(hi2s); - - if (hi2s->State == HAL_I2S_STATE_BUSY_TX) - { - /* Enable the I2S DMA Tx request */ - SET_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); - } - else if (hi2s->State == HAL_I2S_STATE_BUSY_RX) - { - /* Enable the I2S DMA Rx request */ - SET_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); - } -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - else if (hi2s->State == HAL_I2S_STATE_BUSY_TX_RX) - { - /* Pause the audio file playing by disabling the I2S DMA request */ - SET_BIT(hi2s->Instance->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); - SET_BIT(I2SxEXT(hi2s->Instance)->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); - - /* If the I2Sext peripheral is still not enabled, enable it */ - if ((I2SxEXT(hi2s->Instance)->I2SCFGR & SPI_I2SCFGR_I2SE) == 0U) - { - /* Enable I2Sext peripheral */ - __HAL_I2SEXT_ENABLE(hi2s); - } - } -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - else - { - /* nothing to do */ - } - - /* If the I2S peripheral is still not enabled, enable it */ - if (HAL_IS_BIT_CLR(hi2s->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) - { - /* Enable I2S peripheral */ - __HAL_I2S_ENABLE(hi2s); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hi2s); - - return HAL_OK; -} - -/** - * @brief Stops the audio DMA Stream/Channel playing from the Media. - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2S_DMAStop(I2S_HandleTypeDef *hi2s) -{ -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - uint32_t tickstart; -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - HAL_StatusTypeDef errorcode = HAL_OK; - /* The Lock is not implemented on this API to allow the user application - to call the HAL SPI API under callbacks HAL_I2S_TxCpltCallback() or HAL_I2S_RxCpltCallback() - when calling HAL_DMA_Abort() API the DMA TX or RX Transfer complete interrupt is generated - and the correspond call back is executed HAL_I2S_TxCpltCallback() or HAL_I2S_RxCpltCallback() - */ - - if ((hi2s->Init.Mode == I2S_MODE_MASTER_TX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_TX)) - { - /* Abort the I2S DMA tx Stream/Channel */ - if (hi2s->hdmatx != NULL) - { - /* Disable the I2S DMA tx Stream/Channel */ - if (HAL_OK != HAL_DMA_Abort(hi2s->hdmatx)) - { - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); - errorcode = HAL_ERROR; - } - } - - /* Wait until TXE flag is set */ - if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, I2S_TIMEOUT_FLAG) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - hi2s->State = HAL_I2S_STATE_READY; - errorcode = HAL_ERROR; - } - - /* Wait until BSY flag is Reset */ - if (I2S_WaitFlagStateUntilTimeout(hi2s, I2S_FLAG_BSY, RESET, I2S_TIMEOUT_FLAG) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - hi2s->State = HAL_I2S_STATE_READY; - errorcode = HAL_ERROR; - } - - /* Disable I2S peripheral */ - __HAL_I2S_DISABLE(hi2s); - - /* Clear UDR flag */ - __HAL_I2S_CLEAR_UDRFLAG(hi2s); - - /* Disable the I2S Tx DMA requests */ - CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); - -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - - if (hi2s->State == HAL_I2S_STATE_BUSY_TX_RX) - { - /* Abort the I2S DMA rx Stream/Channel */ - if (hi2s->hdmarx != NULL) - { - /* Disable the I2S DMA rx Stream/Channel */ - if (HAL_OK != HAL_DMA_Abort(hi2s->hdmarx)) - { - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); - errorcode = HAL_ERROR; - } - } - - /* Disable I2Sext peripheral */ - __HAL_I2SEXT_DISABLE(hi2s); - - /* Clear OVR flag */ - __HAL_I2SEXT_CLEAR_OVRFLAG(hi2s); - - /* Disable the I2SxEXT DMA request */ - CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_RXDMAEN); - - if (hi2s->Init.Mode == I2S_MODE_SLAVE_TX) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_BUSY_LINE_RX); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - errorcode = HAL_ERROR; - } - else - { - /* Read DR to Flush RX Data */ - READ_REG(I2SxEXT(hi2s->Instance)->DR); - } - } -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - } - - else if ((hi2s->Init.Mode == I2S_MODE_MASTER_RX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_RX)) - { - /* Abort the I2S DMA rx Stream/Channel */ - if (hi2s->hdmarx != NULL) - { - /* Disable the I2S DMA rx Stream/Channel */ - if (HAL_OK != HAL_DMA_Abort(hi2s->hdmarx)) - { - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); - errorcode = HAL_ERROR; - } - } -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - - if (hi2s->State == HAL_I2S_STATE_BUSY_TX_RX) - { - /* Abort the I2S DMA tx Stream/Channel */ - if (hi2s->hdmatx != NULL) - { - /* Disable the I2S DMA tx Stream/Channel */ - if (HAL_OK != HAL_DMA_Abort(hi2s->hdmatx)) - { - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); - errorcode = HAL_ERROR; - } - } - - tickstart = HAL_GetTick(); - - /* Wait until TXE flag is set */ - while (__HAL_I2SEXT_GET_FLAG(hi2s, I2S_FLAG_TXE) != SET) - { - if (((HAL_GetTick() - tickstart) > I2S_TIMEOUT_FLAG)) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - errorcode = HAL_ERROR; - } - } - - /* Wait until BSY flag is Reset */ - while (__HAL_I2SEXT_GET_FLAG(hi2s, I2S_FLAG_BSY) != RESET) - { - if (((HAL_GetTick() - tickstart) > I2S_TIMEOUT_FLAG)) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - errorcode = HAL_ERROR; - } - } - - /* Disable I2Sext peripheral */ - __HAL_I2SEXT_DISABLE(hi2s); - - /* Clear UDR flag */ - __HAL_I2SEXT_CLEAR_UDRFLAG(hi2s); - - /* Disable the I2SxEXT DMA request */ - CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_TXDMAEN); - } -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - - /* Disable I2S peripheral */ - __HAL_I2S_DISABLE(hi2s); - - /* Clear OVR flag */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - - /* Disable the I2S Rx DMA request */ - CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); - - if (hi2s->Init.Mode == I2S_MODE_SLAVE_RX) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_BUSY_LINE_RX); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - errorcode = HAL_ERROR; - } - else - { - /* Read DR to Flush RX Data */ - READ_REG((hi2s->Instance)->DR); - } - } - - hi2s->State = HAL_I2S_STATE_READY; - - return errorcode; -} - -/** - * @brief This function handles I2S interrupt request. - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -void HAL_I2S_IRQHandler(I2S_HandleTypeDef *hi2s) -{ - /* Call the IrqHandler ISR set during HAL_I2S_INIT */ - hi2s->IrqHandlerISR(hi2s); -} - -/** - * @brief Tx Transfer Half completed callbacks - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -__weak void HAL_I2S_TxHalfCpltCallback(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_I2S_TxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx Transfer completed callbacks - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -__weak void HAL_I2S_TxCpltCallback(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_I2S_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer half completed callbacks - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -__weak void HAL_I2S_RxHalfCpltCallback(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_I2S_RxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callbacks - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -__weak void HAL_I2S_RxCpltCallback(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_I2S_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief I2S error callbacks - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -__weak void HAL_I2S_ErrorCallback(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_I2S_ErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup I2S_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the I2S state - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval HAL state - */ -HAL_I2S_StateTypeDef HAL_I2S_GetState(I2S_HandleTypeDef *hi2s) -{ - return hi2s->State; -} - -/** - * @brief Return the I2S error code - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval I2S Error Code - */ -uint32_t HAL_I2S_GetError(I2S_HandleTypeDef *hi2s) -{ - return hi2s->ErrorCode; -} -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup I2S_Private_Functions I2S Private Functions - * @{ - */ -/** - * @brief DMA I2S transmit process complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void I2S_DMATxCplt(DMA_HandleTypeDef *hdma) -{ - I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* if DMA is configured in DMA_NORMAL Mode */ - if (hdma->Init.Mode == DMA_NORMAL) - { - /* Disable Tx DMA Request */ - CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); - - hi2s->TxXferCount = 0U; - hi2s->State = HAL_I2S_STATE_READY; - } - /* Call user Tx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxCpltCallback(hi2s); -#else - HAL_I2S_TxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA I2S transmit process half complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void I2S_DMATxHalfCplt(DMA_HandleTypeDef *hdma) -{ - I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Call user Tx half complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxHalfCpltCallback(hi2s); -#else - HAL_I2S_TxHalfCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA I2S receive process complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void I2S_DMARxCplt(DMA_HandleTypeDef *hdma) -{ - I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* if DMA is configured in DMA_NORMAL Mode */ - if (hdma->Init.Mode == DMA_NORMAL) - { - /* Disable Rx DMA Request */ - CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); - hi2s->RxXferCount = 0U; - hi2s->State = HAL_I2S_STATE_READY; - } - /* Call user Rx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->RxCpltCallback(hi2s); -#else - HAL_I2S_RxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA I2S receive process half complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void I2S_DMARxHalfCplt(DMA_HandleTypeDef *hdma) -{ - I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Call user Rx half complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->RxHalfCpltCallback(hi2s); -#else - HAL_I2S_RxHalfCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA I2S communication error callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void I2S_DMAError(DMA_HandleTypeDef *hdma) -{ - I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; /* Derogation MISRAC2012-Rule-11.5 */ - - /* Disable Rx and Tx DMA Request */ - CLEAR_BIT(hi2s->Instance->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); - hi2s->TxXferCount = 0U; - hi2s->RxXferCount = 0U; - - hi2s->State = HAL_I2S_STATE_READY; - - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); - /* Call user error callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->ErrorCallback(hi2s); -#else - HAL_I2S_ErrorCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} - -/** - * @brief Transmit an amount of data in non-blocking mode with Interrupt - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -static void I2S_Transmit_IT(I2S_HandleTypeDef *hi2s) -{ - /* Transmit data */ - hi2s->Instance->DR = (*hi2s->pTxBuffPtr); - hi2s->pTxBuffPtr++; - hi2s->TxXferCount--; - - if (hi2s->TxXferCount == 0U) - { - /* Disable TXE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - hi2s->State = HAL_I2S_STATE_READY; - /* Call user Tx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxCpltCallback(hi2s); -#else - HAL_I2S_TxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Receive an amount of data in non-blocking mode with Interrupt - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -static void I2S_Receive_IT(I2S_HandleTypeDef *hi2s) -{ - /* Receive data */ - (*hi2s->pRxBuffPtr) = (uint16_t)hi2s->Instance->DR; - hi2s->pRxBuffPtr++; - hi2s->RxXferCount--; - - if (hi2s->RxXferCount == 0U) - { - /* Disable RXNE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - hi2s->State = HAL_I2S_STATE_READY; - /* Call user Rx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->RxCpltCallback(hi2s); -#else - HAL_I2S_RxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } -} - -/** - * @brief This function handles I2S interrupt request. - * @param hi2s: pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @retval None - */ -static void I2S_IRQHandler(I2S_HandleTypeDef *hi2s) -{ - __IO uint32_t i2ssr = hi2s->Instance->SR; - - if (hi2s->State == HAL_I2S_STATE_BUSY_RX) - { - /* I2S in mode Receiver ------------------------------------------------*/ - if (((i2ssr & I2S_FLAG_RXNE) == I2S_FLAG_RXNE) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_RXNE) != RESET)) - { - I2S_Receive_IT(hi2s); - } - - /* I2S Overrun error interrupt occurred -------------------------------------*/ - if (((i2ssr & I2S_FLAG_OVR) == I2S_FLAG_OVR) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_ERR) != RESET)) - { - /* Disable RXNE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - /* Clear Overrun flag */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); - /* Call user error callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->ErrorCallback(hi2s); -#else - HAL_I2S_ErrorCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - } - - if (hi2s->State == HAL_I2S_STATE_BUSY_TX) - { - /* I2S in mode Transmitter -----------------------------------------------*/ - if (((i2ssr & I2S_FLAG_TXE) == I2S_FLAG_TXE) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_TXE) != RESET)) - { - I2S_Transmit_IT(hi2s); - } - - /* I2S Underrun error interrupt occurred --------------------------------*/ - if (((i2ssr & I2S_FLAG_UDR) == I2S_FLAG_UDR) && (__HAL_I2S_GET_IT_SOURCE(hi2s, I2S_IT_ERR) != RESET)) - { - /* Disable TXE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - /* Clear Underrun flag */ - __HAL_I2S_CLEAR_UDRFLAG(hi2s); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); - /* Call user error callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->ErrorCallback(hi2s); -#else - HAL_I2S_ErrorCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief This function handles I2S Communication Timeout. - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param Flag Flag checked - * @param State Value of the flag expected - * @param Timeout Duration of the timeout - * @retval HAL status - */ -static HAL_StatusTypeDef I2S_WaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, uint32_t Flag, FlagStatus State, - uint32_t Timeout) -{ - uint32_t tickstart; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until flag is set to status*/ - while (((__HAL_I2S_GET_FLAG(hi2s, Flag)) ? SET : RESET) != State) - { - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) >= Timeout) || (Timeout == 0U)) - { - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2s); - - return HAL_TIMEOUT; - } - } - } - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_I2S_MODULE_ENABLED */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s_ex.c deleted file mode 100644 index cd0db5e90ae2c2e..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2s_ex.c +++ /dev/null @@ -1,1138 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2s_ex.c - * @author MCD Application Team - * @brief I2S HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of I2S extension peripheral: - * + Extension features Functions - * - @verbatim - ============================================================================== - ##### I2S Extension features ##### - ============================================================================== - [..] - (#) In I2S full duplex mode, each SPI peripheral is able to manage sending and receiving - data simultaneously using two data lines. Each SPI peripheral has an extended block - called I2Sxext (i.e I2S2ext for SPI2 and I2S3ext for SPI3). - (#) The extension block is not a full SPI IP, it is used only as I2S slave to - implement full duplex mode. The extension block uses the same clock sources - as its master. - - (#) Both I2Sx and I2Sx_ext can be configured as transmitters or receivers. - - [..] - (@) Only I2Sx can deliver SCK and WS to I2Sx_ext in full duplex mode, where - I2Sx can be I2S2 or I2S3. - - ##### How to use this driver ##### - =============================================================================== - [..] - Three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Send and receive in the same time an amount of data in blocking mode using HAL_I2SEx_TransmitReceive() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Send and receive in the same time an amount of data in non blocking mode using HAL_I2SEx_TransmitReceive_IT() - (+) At transmission/reception end of transfer HAL_I2SEx_TxRxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2SEx_TxRxCpltCallback - (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2S_ErrorCallback - - *** DMA mode IO operation *** - ============================== - [..] - (+) Send and receive an amount of data in non blocking mode (DMA) using HAL_I2SEx_TransmitReceive_DMA() - (+) At transmission/reception end of transfer HAL_I2SEx_TxRxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_I2S_TxRxCpltCallback - (+) In case of transfer Error, HAL_I2S_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_I2S_ErrorCallback - (+) __HAL_I2SEXT_FLUSH_RX_DR: In Full-Duplex Slave mode, if HAL_I2S_DMAStop is used to stop the - communication, an error HAL_I2S_ERROR_BUSY_LINE_RX is raised as the master continue to transmit data. - In this case __HAL_I2SEXT_FLUSH_RX_DR macro must be used to flush the remaining data - inside I2Sx and I2Sx_ext DR registers and avoid using DeInit/Init process for the next transfer. - @endverbatim - - Additional Figure: The Extended block uses the same clock sources as its master. - - +-----------------------+ - I2Sx_SCK | | - ----------+-->| I2Sx |------------------->I2Sx_SD(in/out) - +--|-->| | - | | +-----------------------+ - | | - I2S_WS | | - ------>| | - | | +-----------------------+ - | +-->| | - | | I2Sx_ext |------------------->I2Sx_extSD(in/out) - +----->| | - +-----------------------+ - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_I2S_MODULE_ENABLED - -/** @defgroup I2SEx I2SEx - * @brief I2S Extended HAL module driver - * @{ - */ - -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) - -/* Private typedef -----------------------------------------------------------*/ -/** @defgroup I2SEx_Private_Typedef I2S Extended Private Typedef - * @{ - */ -typedef enum -{ - I2S_USE_I2S = 0x00U, /*!< I2Sx should be used */ - I2S_USE_I2SEXT = 0x01U, /*!< I2Sx_ext should be used */ -} I2S_UseTypeDef; -/** - * @} - */ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup I2SEx_Private_Functions I2S Extended Private Functions - * @{ - */ -static void I2SEx_TxRxDMAHalfCplt(DMA_HandleTypeDef *hdma); -static void I2SEx_TxRxDMACplt(DMA_HandleTypeDef *hdma); -static void I2SEx_TxRxDMAError(DMA_HandleTypeDef *hdma); -static void I2SEx_RxISR_I2S(I2S_HandleTypeDef *hi2s); -static void I2SEx_RxISR_I2SExt(I2S_HandleTypeDef *hi2s); -static void I2SEx_TxISR_I2S(I2S_HandleTypeDef *hi2s); -static void I2SEx_TxISR_I2SExt(I2S_HandleTypeDef *hi2s); -static HAL_StatusTypeDef I2SEx_FullDuplexWaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, - uint32_t Flag, - uint32_t State, - uint32_t Timeout, - I2S_UseTypeDef i2sUsed); -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup I2SEx I2SEx - * @{ - */ - -/** @addtogroup I2SEx_Exported_Functions I2S Extended Exported Functions - * @{ - */ - -/** @defgroup I2SEx_Exported_Functions_Group1 I2S Extended IO operation functions - * @brief I2SEx IO operation functions - * -@verbatim - =============================================================================== - ##### IO operation functions##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the I2S data - transfers. - - (#) There are two modes of transfer: - (++) Blocking mode : The communication is performed in the polling mode. - The status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode : The communication is performed using Interrupts - or DMA. These functions return the status of the transfer startup. - The end of the data processing will be indicated through the - dedicated I2S IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - - (#) Blocking mode functions are : - (++) HAL_I2SEx_TransmitReceive() - - (#) No-Blocking mode functions with Interrupt are : - (++) HAL_I2SEx_TransmitReceive_IT() - (++) HAL_I2SEx_FullDuplex_IRQHandler() - - (#) No-Blocking mode functions with DMA are : - (++) HAL_I2SEx_TransmitReceive_DMA() - - (#) A set of Transfer Complete Callback are provided in non Blocking mode: - (++) HAL_I2SEx_TxRxCpltCallback() -@endverbatim - * @{ - */ -/** - * @brief Full-Duplex Transmit/Receive data in blocking mode. - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pTxData a 16-bit pointer to the Transmit data buffer. - * @param pRxData a 16-bit pointer to the Receive data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 16-bit data length. - * @param Timeout Timeout duration - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive(I2S_HandleTypeDef *hi2s, - uint16_t *pTxData, - uint16_t *pRxData, - uint16_t Size, - uint32_t Timeout) -{ - uint32_t tmp1 = 0U; - HAL_StatusTypeDef errorcode = HAL_OK; - - if (hi2s->State != HAL_I2S_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - tmp1 = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - /* Check the Data format: When a 16-bit data frame or a 16-bit data frame extended - is selected during the I2S configuration phase, the Size parameter means the number - of 16-bit data length in the transaction and when a 24-bit data frame or a 32-bit data - frame is selected the Size parameter means the number of 16-bit data length. */ - if ((tmp1 == I2S_DATAFORMAT_24B) || (tmp1 == I2S_DATAFORMAT_32B)) - { - hi2s->TxXferSize = (Size << 1U); - hi2s->TxXferCount = (Size << 1U); - hi2s->RxXferSize = (Size << 1U); - hi2s->RxXferCount = (Size << 1U); - } - else - { - hi2s->TxXferSize = Size; - hi2s->TxXferCount = Size; - hi2s->RxXferSize = Size; - hi2s->RxXferCount = Size; - } - - /* Set state and reset error code */ - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->State = HAL_I2S_STATE_BUSY_TX_RX; - - tmp1 = hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG; - /* Check if the I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX Mode is selected */ - if ((tmp1 == I2S_MODE_MASTER_TX) || (tmp1 == I2S_MODE_SLAVE_TX)) - { - /* Prepare the First Data before enabling the I2S */ - hi2s->Instance->DR = (*pTxData++); - hi2s->TxXferCount--; - - /* Enable I2Sext(receiver) before enabling I2Sx peripheral */ - __HAL_I2SEXT_ENABLE(hi2s); - - /* Enable I2Sx peripheral */ - __HAL_I2S_ENABLE(hi2s); - - /* Check if Master Receiver mode is selected */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_TX) - { - /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read - access to the SPI_SR register. */ - __HAL_I2SEXT_CLEAR_OVRFLAG(hi2s); - } - - while ((hi2s->RxXferCount > 0U) || (hi2s->TxXferCount > 0U)) - { - if (hi2s->TxXferCount > 0U) - { - /* Wait until TXE flag is set */ - if (I2SEx_FullDuplexWaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout, I2S_USE_I2S) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - errorcode = HAL_ERROR; - goto error; - } - /* Write Data on DR register */ - hi2s->Instance->DR = (*pTxData++); - hi2s->TxXferCount--; - - /* Check if an underrun occurs */ - if ((__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_UDR) == SET) && (tmp1 == I2S_MODE_SLAVE_TX)) - { - /* Clear Underrun flag */ - __HAL_I2S_CLEAR_UDRFLAG(hi2s); - - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); - } - } - if (hi2s->RxXferCount > 0U) - { - /* Wait until RXNE flag is set */ - if (I2SEx_FullDuplexWaitFlagStateUntilTimeout(hi2s, I2S_FLAG_RXNE, SET, Timeout, I2S_USE_I2SEXT) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - errorcode = HAL_ERROR; - goto error; - } - /* Read Data from DR register */ - (*pRxData++) = I2SxEXT(hi2s->Instance)->DR; - hi2s->RxXferCount--; - - /* Check if an overrun occurs */ - if (__HAL_I2SEXT_GET_FLAG(hi2s, I2S_FLAG_OVR) == SET) - { - /* Clear Overrun flag */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); - } - } - } - } - /* The I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX Mode is selected */ - else - { - /* Prepare the First Data before enabling the I2S */ - I2SxEXT(hi2s->Instance)->DR = (*pTxData++); - hi2s->TxXferCount--; - - /* Enable I2Sext(transmitter) after enabling I2Sx peripheral */ - __HAL_I2SEXT_ENABLE(hi2s); - - /* Enable I2S peripheral before the I2Sext*/ - __HAL_I2S_ENABLE(hi2s); - - /* Check if Master Receiver mode is selected */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX) - { - /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read - access to the SPI_SR register. */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - } - - while ((hi2s->RxXferCount > 0U) || (hi2s->TxXferCount > 0U)) - { - if (hi2s->TxXferCount > 0U) - { - /* Wait until TXE flag is set */ - if (I2SEx_FullDuplexWaitFlagStateUntilTimeout(hi2s, I2S_FLAG_TXE, SET, Timeout, I2S_USE_I2SEXT) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - errorcode = HAL_ERROR; - goto error; - } - /* Write Data on DR register */ - I2SxEXT(hi2s->Instance)->DR = (*pTxData++); - hi2s->TxXferCount--; - - /* Check if an underrun occurs */ - if ((__HAL_I2SEXT_GET_FLAG(hi2s, I2S_FLAG_UDR) == SET) && (tmp1 == I2S_MODE_SLAVE_RX)) - { - /* Clear Underrun flag */ - __HAL_I2S_CLEAR_UDRFLAG(hi2s); - - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); - } - } - if (hi2s->RxXferCount > 0U) - { - /* Wait until RXNE flag is set */ - if (I2SEx_FullDuplexWaitFlagStateUntilTimeout(hi2s, I2S_FLAG_RXNE, SET, Timeout, I2S_USE_I2S) != HAL_OK) - { - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_TIMEOUT); - errorcode = HAL_ERROR; - goto error; - } - /* Read Data from DR register */ - (*pRxData++) = hi2s->Instance->DR; - hi2s->RxXferCount--; - - /* Check if an overrun occurs */ - if (__HAL_I2S_GET_FLAG(hi2s, I2S_FLAG_OVR) == SET) - { - /* Clear Overrun flag */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - - /* Set the error code */ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); - } - } - } - } - - if (hi2s->ErrorCode != HAL_I2S_ERROR_NONE) - { - errorcode = HAL_ERROR; - } - -error : - hi2s->State = HAL_I2S_STATE_READY; - __HAL_UNLOCK(hi2s); - return errorcode; -} - -/** - * @brief Full-Duplex Transmit/Receive data in non-blocking mode using Interrupt - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pTxData a 16-bit pointer to the Transmit data buffer. - * @param pRxData a 16-bit pointer to the Receive data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 16-bit data length. - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive_IT(I2S_HandleTypeDef *hi2s, - uint16_t *pTxData, - uint16_t *pRxData, - uint16_t Size) -{ - uint32_t tmp1 = 0U; - HAL_StatusTypeDef errorcode = HAL_OK; - - if (hi2s->State != HAL_I2S_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - hi2s->pTxBuffPtr = pTxData; - hi2s->pRxBuffPtr = pRxData; - - tmp1 = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - /* Check the Data format: When a 16-bit data frame or a 16-bit data frame extended - is selected during the I2S configuration phase, the Size parameter means the number - of 16-bit data length in the transaction and when a 24-bit data frame or a 32-bit data - frame is selected the Size parameter means the number of 16-bit data length. */ - if ((tmp1 == I2S_DATAFORMAT_24B) || (tmp1 == I2S_DATAFORMAT_32B)) - { - hi2s->TxXferSize = (Size << 1U); - hi2s->TxXferCount = (Size << 1U); - hi2s->RxXferSize = (Size << 1U); - hi2s->RxXferCount = (Size << 1U); - } - else - { - hi2s->TxXferSize = Size; - hi2s->TxXferCount = Size; - hi2s->RxXferSize = Size; - hi2s->RxXferCount = Size; - } - - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->State = HAL_I2S_STATE_BUSY_TX_RX; - - /* Set the function for IT treatment */ - if ((hi2s->Init.Mode == I2S_MODE_MASTER_TX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_TX)) - { - /* Enable I2Sext RXNE and ERR interrupts */ - __HAL_I2SEXT_ENABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - /* Enable I2Sx TXE and ERR interrupts */ - __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - /* Transmit First data */ - hi2s->Instance->DR = (*hi2s->pTxBuffPtr++); - hi2s->TxXferCount--; - - if (hi2s->TxXferCount == 0U) - { - /* Disable TXE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - } - } - else /* The I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX Mode is selected */ - { - /* Enable I2Sext TXE and ERR interrupts */ - __HAL_I2SEXT_ENABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - /* Enable I2Sext RXNE and ERR interrupts */ - __HAL_I2S_ENABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - /* Transmit First data */ - I2SxEXT(hi2s->Instance)->DR = (*hi2s->pTxBuffPtr++); - hi2s->TxXferCount--; - - if (hi2s->TxXferCount == 0U) - { - /* Disable I2Sext TXE and ERR interrupt */ - __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - } - } - - /* Enable I2Sext peripheral */ - __HAL_I2SEXT_ENABLE(hi2s); - - /* Enable I2S peripheral */ - __HAL_I2S_ENABLE(hi2s); - -error : - __HAL_UNLOCK(hi2s); - return errorcode; -} - -/** - * @brief Full-Duplex Transmit/Receive data in non-blocking mode using DMA - * @param hi2s pointer to a I2S_HandleTypeDef structure that contains - * the configuration information for I2S module - * @param pTxData a 16-bit pointer to the Transmit data buffer. - * @param pRxData a 16-bit pointer to the Receive data buffer. - * @param Size number of data sample to be sent: - * @note When a 16-bit data frame or a 16-bit data frame extended is selected during the I2S - * configuration phase, the Size parameter means the number of 16-bit data length - * in the transaction and when a 24-bit data frame or a 32-bit data frame is selected - * the Size parameter means the number of 16-bit data length. - * @note The I2S is kept enabled at the end of transaction to avoid the clock de-synchronization - * between Master and Slave(example: audio streaming). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive_DMA(I2S_HandleTypeDef *hi2s, - uint16_t *pTxData, - uint16_t *pRxData, - uint16_t Size) -{ - uint32_t *tmp = NULL; - uint32_t tmp1 = 0U; - HAL_StatusTypeDef errorcode = HAL_OK; - - if (hi2s->State != HAL_I2S_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hi2s); - - hi2s->pTxBuffPtr = pTxData; - hi2s->pRxBuffPtr = pRxData; - - tmp1 = hi2s->Instance->I2SCFGR & (SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN); - /* Check the Data format: When a 16-bit data frame or a 16-bit data frame extended - is selected during the I2S configuration phase, the Size parameter means the number - of 16-bit data length in the transaction and when a 24-bit data frame or a 32-bit data - frame is selected the Size parameter means the number of 16-bit data length. */ - if ((tmp1 == I2S_DATAFORMAT_24B) || (tmp1 == I2S_DATAFORMAT_32B)) - { - hi2s->TxXferSize = (Size << 1U); - hi2s->TxXferCount = (Size << 1U); - hi2s->RxXferSize = (Size << 1U); - hi2s->RxXferCount = (Size << 1U); - } - else - { - hi2s->TxXferSize = Size; - hi2s->TxXferCount = Size; - hi2s->RxXferSize = Size; - hi2s->RxXferCount = Size; - } - - hi2s->ErrorCode = HAL_I2S_ERROR_NONE; - hi2s->State = HAL_I2S_STATE_BUSY_TX_RX; - - /* Set the I2S Rx DMA Half transfer complete callback */ - hi2s->hdmarx->XferHalfCpltCallback = I2SEx_TxRxDMAHalfCplt; - - /* Set the I2S Rx DMA transfer complete callback */ - hi2s->hdmarx->XferCpltCallback = I2SEx_TxRxDMACplt; - - /* Set the I2S Rx DMA error callback */ - hi2s->hdmarx->XferErrorCallback = I2SEx_TxRxDMAError; - - /* Set the I2S Tx DMA Half transfer complete callback as NULL */ - hi2s->hdmatx->XferHalfCpltCallback = NULL; - - /* Set the I2S Tx DMA transfer complete callback as NULL */ - hi2s->hdmatx->XferCpltCallback = NULL; - - /* Set the I2S Tx DMA error callback */ - hi2s->hdmatx->XferErrorCallback = I2SEx_TxRxDMAError; - - tmp1 = hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG; - /* Check if the I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX Mode is selected */ - if ((tmp1 == I2S_MODE_MASTER_TX) || (tmp1 == I2S_MODE_SLAVE_TX)) - { - /* Enable the Rx DMA Stream */ - tmp = (uint32_t *)&pRxData; - HAL_DMA_Start_IT(hi2s->hdmarx, (uint32_t)&I2SxEXT(hi2s->Instance)->DR, *(uint32_t *)tmp, hi2s->RxXferSize); - - /* Enable Rx DMA Request */ - SET_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_RXDMAEN); - - /* Enable the Tx DMA Stream */ - tmp = (uint32_t *)&pTxData; - HAL_DMA_Start_IT(hi2s->hdmatx, *(uint32_t *)tmp, (uint32_t)&hi2s->Instance->DR, hi2s->TxXferSize); - - /* Enable Tx DMA Request */ - SET_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); - - /* Check if the I2S is already enabled */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) - { - /* Enable I2Sext(receiver) before enabling I2Sx peripheral */ - __HAL_I2SEXT_ENABLE(hi2s); - - /* Enable I2S peripheral after the I2Sext */ - __HAL_I2S_ENABLE(hi2s); - } - } - else - { - /* Check if Master Receiver mode is selected */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_RX) - { - /* Clear the Overrun Flag by a read operation on the SPI_DR register followed by a read - access to the SPI_SR register. */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - } - /* Enable the Tx DMA Stream */ - tmp = (uint32_t *)&pTxData; - HAL_DMA_Start_IT(hi2s->hdmatx, *(uint32_t *)tmp, (uint32_t)&I2SxEXT(hi2s->Instance)->DR, hi2s->TxXferSize); - - /* Enable Tx DMA Request */ - SET_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_TXDMAEN); - - /* Enable the Rx DMA Stream */ - tmp = (uint32_t *)&pRxData; - HAL_DMA_Start_IT(hi2s->hdmarx, (uint32_t)&hi2s->Instance->DR, *(uint32_t *)tmp, hi2s->RxXferSize); - - /* Enable Rx DMA Request */ - SET_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); - - /* Check if the I2S is already enabled */ - if ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SE) != SPI_I2SCFGR_I2SE) - { - /* Enable I2Sext(transmitter) before enabling I2Sx peripheral */ - __HAL_I2SEXT_ENABLE(hi2s); - /* Enable I2S peripheral before the I2Sext */ - __HAL_I2S_ENABLE(hi2s); - } - } - -error : - __HAL_UNLOCK(hi2s); - return errorcode; -} - -/** - * @brief This function handles I2S/I2Sext interrupt requests in full-duplex mode. - * @param hi2s I2S handle - * @retval HAL status - */ -void HAL_I2SEx_FullDuplex_IRQHandler(I2S_HandleTypeDef *hi2s) -{ - __IO uint32_t i2ssr = hi2s->Instance->SR; - __IO uint32_t i2sextsr = I2SxEXT(hi2s->Instance)->SR; - __IO uint32_t i2scr2 = hi2s->Instance->CR2; - __IO uint32_t i2sextcr2 = I2SxEXT(hi2s->Instance)->CR2; - - /* Check if the I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX Mode is selected */ - if ((hi2s->Init.Mode == I2S_MODE_MASTER_TX) || (hi2s->Init.Mode == I2S_MODE_SLAVE_TX)) - { - /* I2S in mode Transmitter -------------------------------------------------*/ - if (((i2ssr & I2S_FLAG_TXE) == I2S_FLAG_TXE) && ((i2scr2 & I2S_IT_TXE) != RESET)) - { - /* When the I2S mode is configured as I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX, - the I2S TXE interrupt will be generated to manage the full-duplex transmit phase. */ - I2SEx_TxISR_I2S(hi2s); - } - - /* I2Sext in mode Receiver -----------------------------------------------*/ - if (((i2sextsr & I2S_FLAG_RXNE) == I2S_FLAG_RXNE) && ((i2sextcr2 & I2S_IT_RXNE) != RESET)) - { - /* When the I2S mode is configured as I2S_MODE_MASTER_TX or I2S_MODE_SLAVE_TX, - the I2Sext RXNE interrupt will be generated to manage the full-duplex receive phase. */ - I2SEx_RxISR_I2SExt(hi2s); - } - - /* I2Sext Overrun error interrupt occurred --------------------------------*/ - if (((i2sextsr & I2S_FLAG_OVR) == I2S_FLAG_OVR) && ((i2sextcr2 & I2S_IT_ERR) != RESET)) - { - /* Disable RXNE and ERR interrupt */ - __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - /* Disable TXE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - /* Clear Overrun flag */ - __HAL_I2S_CLEAR_OVRFLAG(hi2s); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); - /* Call user error callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->ErrorCallback(hi2s); -#else - HAL_I2S_ErrorCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - - /* I2S Underrun error interrupt occurred ----------------------------------*/ - if (((i2ssr & I2S_FLAG_UDR) == I2S_FLAG_UDR) && ((i2scr2 & I2S_IT_ERR) != RESET)) - { - /* Disable TXE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - /* Disable RXNE and ERR interrupt */ - __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - /* Clear underrun flag */ - __HAL_I2S_CLEAR_UDRFLAG(hi2s); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); - /* Call user error callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->ErrorCallback(hi2s); -#else - HAL_I2S_ErrorCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - } - /* The I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX Mode is selected */ - else - { - /* I2Sext in mode Transmitter ----------------------------------------------*/ - if (((i2sextsr & I2S_FLAG_TXE) == I2S_FLAG_TXE) && ((i2sextcr2 & I2S_IT_TXE) != RESET)) - { - /* When the I2S mode is configured as I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX, - the I2Sext TXE interrupt will be generated to manage the full-duplex transmit phase. */ - I2SEx_TxISR_I2SExt(hi2s); - } - - /* I2S in mode Receiver --------------------------------------------------*/ - if (((i2ssr & I2S_FLAG_RXNE) == I2S_FLAG_RXNE) && ((i2scr2 & I2S_IT_RXNE) != RESET)) - { - /* When the I2S mode is configured as I2S_MODE_MASTER_RX or I2S_MODE_SLAVE_RX, - the I2S RXNE interrupt will be generated to manage the full-duplex receive phase. */ - I2SEx_RxISR_I2S(hi2s); - } - - /* I2S Overrun error interrupt occurred -------------------------------------*/ - if (((i2ssr & I2S_FLAG_OVR) == I2S_FLAG_OVR) && ((i2scr2 & I2S_IT_ERR) != RESET)) - { - /* Disable RXNE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - /* Disable TXE and ERR interrupt */ - __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_OVR); - /* Call user error callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->ErrorCallback(hi2s); -#else - HAL_I2S_ErrorCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - - /* I2Sext Underrun error interrupt occurred -------------------------------*/ - if (((i2sextsr & I2S_FLAG_UDR) == I2S_FLAG_UDR) && ((i2sextcr2 & I2S_IT_ERR) != RESET)) - { - /* Disable TXE and ERR interrupt */ - __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - /* Disable RXNE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_UDR); - /* Call user error callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->ErrorCallback(hi2s); -#else - HAL_I2S_ErrorCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief Tx and Rx Transfer half completed callback - * @param hi2s I2S handle - * @retval None - */ -__weak void HAL_I2SEx_TxRxHalfCpltCallback(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_I2SEx_TxRxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx and Rx Transfer completed callback - * @param hi2s I2S handle - * @retval None - */ -__weak void HAL_I2SEx_TxRxCpltCallback(I2S_HandleTypeDef *hi2s) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hi2s); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_I2SEx_TxRxCpltCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup I2SEx_Private_Functions I2S Extended Private Functions - * @{ - */ - -/** - * @brief DMA I2S transmit receive process half complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void I2SEx_TxRxDMAHalfCplt(DMA_HandleTypeDef *hdma) -{ - I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Call user TxRx Half complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxRxHalfCpltCallback(hi2s); -#else - HAL_I2SEx_TxRxHalfCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA I2S transmit receive process complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void I2SEx_TxRxDMACplt(DMA_HandleTypeDef *hdma) -{ - I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* If DMA is configured in DMA_NORMAL mode */ - if (hdma->Init.Mode == DMA_NORMAL) - { - if (((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_MASTER_TX) || \ - ((hi2s->Instance->I2SCFGR & SPI_I2SCFGR_I2SCFG) == I2S_MODE_SLAVE_TX)) - /* Disable Tx & Rx DMA Requests */ - { - CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_RXDMAEN); - CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_TXDMAEN); - } - else - { - CLEAR_BIT(hi2s->Instance->CR2, SPI_CR2_RXDMAEN); - CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, SPI_CR2_TXDMAEN); - } - - hi2s->RxXferCount = 0U; - hi2s->TxXferCount = 0U; - - hi2s->State = HAL_I2S_STATE_READY; - } - - /* Call user TxRx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxRxCpltCallback(hi2s); -#else - HAL_I2SEx_TxRxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA I2S communication error callback - * @param hdma DMA handle - * @retval None - */ -static void I2SEx_TxRxDMAError(DMA_HandleTypeDef *hdma) -{ - I2S_HandleTypeDef *hi2s = (I2S_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Disable Rx and Tx DMA Request */ - CLEAR_BIT(hi2s->Instance->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); - CLEAR_BIT(I2SxEXT(hi2s->Instance)->CR2, (SPI_CR2_RXDMAEN | SPI_CR2_TXDMAEN)); - - hi2s->TxXferCount = 0U; - hi2s->RxXferCount = 0U; - - hi2s->State = HAL_I2S_STATE_READY; - - /* Set the error code and execute error callback*/ - SET_BIT(hi2s->ErrorCode, HAL_I2S_ERROR_DMA); - /* Call user error callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->ErrorCallback(hi2s); -#else - HAL_I2S_ErrorCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} - -/** - * @brief I2S Full-Duplex IT handler transmit function - * @param hi2s I2S handle - * @retval None - */ -static void I2SEx_TxISR_I2S(I2S_HandleTypeDef *hi2s) -{ - /* Write Data on DR register */ - hi2s->Instance->DR = (*hi2s->pTxBuffPtr++); - hi2s->TxXferCount--; - - if (hi2s->TxXferCount == 0U) - { - /* Disable TXE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - if (hi2s->RxXferCount == 0U) - { - hi2s->State = HAL_I2S_STATE_READY; - /* Call user TxRx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxRxCpltCallback(hi2s); -#else - HAL_I2SEx_TxRxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief I2SExt Full-Duplex IT handler transmit function - * @param hi2s I2S handle - * @retval None - */ -static void I2SEx_TxISR_I2SExt(I2S_HandleTypeDef *hi2s) -{ - /* Write Data on DR register */ - I2SxEXT(hi2s->Instance)->DR = (*hi2s->pTxBuffPtr++); - hi2s->TxXferCount--; - - if (hi2s->TxXferCount == 0U) - { - /* Disable I2Sext TXE and ERR interrupt */ - __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_TXE | I2S_IT_ERR)); - - if (hi2s->RxXferCount == 0U) - { - hi2s->State = HAL_I2S_STATE_READY; - /* Call user TxRx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxRxCpltCallback(hi2s); -#else - HAL_I2SEx_TxRxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief I2S Full-Duplex IT handler receive function - * @param hi2s I2S handle - * @retval None - */ -static void I2SEx_RxISR_I2S(I2S_HandleTypeDef *hi2s) -{ - /* Read Data from DR register */ - (*hi2s->pRxBuffPtr++) = hi2s->Instance->DR; - hi2s->RxXferCount--; - - if (hi2s->RxXferCount == 0U) - { - /* Disable RXNE and ERR interrupt */ - __HAL_I2S_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - if (hi2s->TxXferCount == 0U) - { - hi2s->State = HAL_I2S_STATE_READY; - /* Call user TxRx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxRxCpltCallback(hi2s); -#else - HAL_I2SEx_TxRxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief I2SExt Full-Duplex IT handler receive function - * @param hi2s I2S handle - * @retval None - */ -static void I2SEx_RxISR_I2SExt(I2S_HandleTypeDef *hi2s) -{ - /* Read Data from DR register */ - (*hi2s->pRxBuffPtr++) = I2SxEXT(hi2s->Instance)->DR; - hi2s->RxXferCount--; - - if (hi2s->RxXferCount == 0U) - { - /* Disable I2Sext RXNE and ERR interrupt */ - __HAL_I2SEXT_DISABLE_IT(hi2s, (I2S_IT_RXNE | I2S_IT_ERR)); - - if (hi2s->TxXferCount == 0U) - { - hi2s->State = HAL_I2S_STATE_READY; - /* Call user TxRx complete callback */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - hi2s->TxRxCpltCallback(hi2s); -#else - HAL_I2SEx_TxRxCpltCallback(hi2s); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief This function handles I2S Communication Timeout. - * @param hi2s I2S handle - * @param Flag Flag checked - * @param State Value of the flag expected - * @param Timeout Duration of the timeout - * @param i2sUsed I2S instance reference - * @retval HAL status - */ -static HAL_StatusTypeDef I2SEx_FullDuplexWaitFlagStateUntilTimeout(I2S_HandleTypeDef *hi2s, - uint32_t Flag, - uint32_t State, - uint32_t Timeout, - I2S_UseTypeDef i2sUsed) -{ - uint32_t tickstart = HAL_GetTick(); - - if (i2sUsed == I2S_USE_I2S) - { - /* Wait until flag is reset */ - while (((__HAL_I2S_GET_FLAG(hi2s, Flag)) ? SET : RESET) != State) - { - if (Timeout != HAL_MAX_DELAY) - { - if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout)) - { - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2s); - - return HAL_TIMEOUT; - } - } - } - } - else /* i2sUsed == I2S_USE_I2SEXT */ - { - /* Wait until flag is reset */ - while (((__HAL_I2SEXT_GET_FLAG(hi2s, Flag)) ? SET : RESET) != State) - { - if (Timeout != HAL_MAX_DELAY) - { - if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout)) - { - /* Set the I2S State ready */ - hi2s->State = HAL_I2S_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hi2s); - - return HAL_TIMEOUT; - } - } - } - } - return HAL_OK; -} - -/** - * @} - */ -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - -/** - * @} - */ -#endif /* HAL_I2S_MODULE_ENABLED */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_irda.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_irda.c deleted file mode 100644 index 29974d61b353936..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_irda.c +++ /dev/null @@ -1,2672 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_irda.c - * @author MCD Application Team - * @brief IRDA HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the IrDA SIR ENDEC block (IrDA): - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Errors functions - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The IRDA HAL driver can be used as follows: - - (#) Declare a IRDA_HandleTypeDef handle structure (eg. IRDA_HandleTypeDef hirda). - (#) Initialize the IRDA low level resources by implementing the HAL_IRDA_MspInit() API: - (##) Enable the USARTx interface clock. - (##) IRDA pins configuration: - (+++) Enable the clock for the IRDA GPIOs. - (+++) Configure IRDA pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_IRDA_Transmit_IT() - and HAL_IRDA_Receive_IT() APIs): - (+++) Configure the USARTx interrupt priority. - (+++) Enable the NVIC USART IRQ handle. - (##) DMA Configuration if you need to use DMA process (HAL_IRDA_Transmit_DMA() - and HAL_IRDA_Receive_DMA() APIs): - (+++) Declare a DMA handle structure for the Tx/Rx stream. - (+++) Enable the DMAx interface clock. - (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. - (+++) Configure the DMA Tx/Rx stream. - (+++) Associate the initialized DMA handle to the IRDA DMA Tx/Rx handle. - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx stream. - (+++) Configure the IRDAx interrupt priority and enable the NVIC USART IRQ handle - (used for last byte sending completion detection in DMA non circular mode) - - (#) Program the Baud Rate, Word Length, Parity, IrDA Mode, Prescaler - and Mode(Receiver/Transmitter) in the hirda Init structure. - - (#) Initialize the IRDA registers by calling the HAL_IRDA_Init() API: - (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) - by calling the customized HAL_IRDA_MspInit() API. - - -@@- The specific IRDA interrupts (Transmission complete interrupt, - RXNE interrupt and Error Interrupts) will be managed using the macros - __HAL_IRDA_ENABLE_IT() and __HAL_IRDA_DISABLE_IT() inside the transmit and receive process. - - (#) Three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Send an amount of data in blocking mode using HAL_IRDA_Transmit() - (+) Receive an amount of data in blocking mode using HAL_IRDA_Receive() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Send an amount of data in non blocking mode using HAL_IRDA_Transmit_IT() - (+) At transmission end of transfer HAL_IRDA_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_IRDA_TxCpltCallback - (+) Receive an amount of data in non blocking mode using HAL_IRDA_Receive_IT() - (+) At reception end of transfer HAL_IRDA_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_IRDA_RxCpltCallback - (+) In case of transfer Error, HAL_IRDA_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_IRDA_ErrorCallback - - *** DMA mode IO operation *** - ============================= - [..] - (+) Send an amount of data in non blocking mode (DMA) using HAL_IRDA_Transmit_DMA() - (+) At transmission end of half transfer HAL_IRDA_TxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_IRDA_TxHalfCpltCallback - (+) At transmission end of transfer HAL_IRDA_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_IRDA_TxCpltCallback - (+) Receive an amount of data in non blocking mode (DMA) using HAL_IRDA_Receive_DMA() - (+) At reception end of half transfer HAL_IRDA_RxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_IRDA_RxHalfCpltCallback - (+) At reception end of transfer HAL_IRDA_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_IRDA_RxCpltCallback - (+) In case of transfer Error, HAL_IRDA_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_IRDA_ErrorCallback - (+) Pause the DMA Transfer using HAL_IRDA_DMAPause() - (+) Resume the DMA Transfer using HAL_IRDA_DMAResume() - (+) Stop the DMA Transfer using HAL_IRDA_DMAStop() - - *** IRDA HAL driver macros list *** - =================================== - [..] - Below the list of most used macros in IRDA HAL driver. - - (+) __HAL_IRDA_ENABLE: Enable the IRDA peripheral - (+) __HAL_IRDA_DISABLE: Disable the IRDA peripheral - (+) __HAL_IRDA_GET_FLAG : Check whether the specified IRDA flag is set or not - (+) __HAL_IRDA_CLEAR_FLAG : Clear the specified IRDA pending flag - (+) __HAL_IRDA_ENABLE_IT: Enable the specified IRDA interrupt - (+) __HAL_IRDA_DISABLE_IT: Disable the specified IRDA interrupt - (+) __HAL_IRDA_GET_IT_SOURCE: Check whether the specified IRDA interrupt has occurred or not - - [..] - (@) You can refer to the IRDA HAL driver header file for more useful macros - - ##### Callback registration ##### - ================================== - - [..] - The compilation define USE_HAL_IRDA_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - [..] - Use Function HAL_IRDA_RegisterCallback() to register a user callback. - Function HAL_IRDA_RegisterCallback() allows to register following callbacks: - (+) TxHalfCpltCallback : Tx Half Complete Callback. - (+) TxCpltCallback : Tx Complete Callback. - (+) RxHalfCpltCallback : Rx Half Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. - (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. - (+) MspInitCallback : IRDA MspInit. - (+) MspDeInitCallback : IRDA MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_IRDA_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - HAL_IRDA_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxHalfCpltCallback : Tx Half Complete Callback. - (+) TxCpltCallback : Tx Complete Callback. - (+) RxHalfCpltCallback : Rx Half Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. - (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. - (+) MspInitCallback : IRDA MspInit. - (+) MspDeInitCallback : IRDA MspDeInit. - - [..] - By default, after the HAL_IRDA_Init() and when the state is HAL_IRDA_STATE_RESET - all callbacks are set to the corresponding weak (surcharged) functions: - examples HAL_IRDA_TxCpltCallback(), HAL_IRDA_RxHalfCpltCallback(). - Exception done for MspInit and MspDeInit functions that are respectively - reset to the legacy weak (surcharged) functions in the HAL_IRDA_Init() - and HAL_IRDA_DeInit() only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_IRDA_Init() and HAL_IRDA_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in HAL_IRDA_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_IRDA_STATE_READY or HAL_IRDA_STATE_RESET state, thus registered (user) - MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_IRDA_RegisterCallback() before calling HAL_IRDA_DeInit() - or HAL_IRDA_Init() function. - - [..] - When The compilation define USE_HAL_IRDA_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - [..] - (@) Additional remark: If the parity is enabled, then the MSB bit of the data written - in the data register is transmitted but is changed by the parity bit. - Depending on the frame length defined by the M bit (8-bits or 9-bits), - the possible IRDA frame formats are as listed in the following table: - +-------------------------------------------------------------+ - | M bit | PCE bit | IRDA frame | - |---------------------|---------------------------------------| - | 0 | 0 | | SB | 8 bit data | 1 STB | | - |---------|-----------|---------------------------------------| - | 0 | 1 | | SB | 7 bit data | PB | 1 STB | | - |---------|-----------|---------------------------------------| - | 1 | 0 | | SB | 9 bit data | 1 STB | | - |---------|-----------|---------------------------------------| - | 1 | 1 | | SB | 8 bit data | PB | 1 STB | | - +-------------------------------------------------------------+ - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup IRDA IRDA - * @brief HAL IRDA module driver - * @{ - */ - -#ifdef HAL_IRDA_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup IRDA_Private_Functions - * @{ - */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -void IRDA_InitCallbacksToDefault(IRDA_HandleTypeDef *hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ -static void IRDA_SetConfig(IRDA_HandleTypeDef *hirda); -static HAL_StatusTypeDef IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda); -static HAL_StatusTypeDef IRDA_EndTransmit_IT(IRDA_HandleTypeDef *hirda); -static HAL_StatusTypeDef IRDA_Receive_IT(IRDA_HandleTypeDef *hirda); -static void IRDA_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void IRDA_DMATransmitHalfCplt(DMA_HandleTypeDef *hdma); -static void IRDA_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void IRDA_DMAReceiveHalfCplt(DMA_HandleTypeDef *hdma); -static void IRDA_DMAError(DMA_HandleTypeDef *hdma); -static void IRDA_DMAAbortOnError(DMA_HandleTypeDef *hdma); -static void IRDA_DMATxAbortCallback(DMA_HandleTypeDef *hdma); -static void IRDA_DMARxAbortCallback(DMA_HandleTypeDef *hdma); -static void IRDA_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma); -static void IRDA_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef IRDA_WaitOnFlagUntilTimeout(IRDA_HandleTypeDef *hirda, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout); -static void IRDA_EndTxTransfer(IRDA_HandleTypeDef *hirda); -static void IRDA_EndRxTransfer(IRDA_HandleTypeDef *hirda); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup IRDA_Exported_Functions IrDA Exported Functions - * @{ - */ - -/** @defgroup IRDA_Exported_Functions_Group1 IrDA Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - - ============================================================================== - ##### Initialization and Configuration functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to initialize the USARTx or the UARTy - in asynchronous IrDA mode. - (+) For the asynchronous mode only these parameters can be configured: - (++) BaudRate - (++) WordLength - (++) Parity: If the parity is enabled, then the MSB bit of the data written - in the data register is transmitted but is changed by the parity bit. - Depending on the frame length defined by the M bit (8-bits or 9-bits), - please refer to Reference manual for possible IRDA frame formats. - (++) Prescaler: A pulse of width less than two and greater than one PSC period(s) may or may - not be rejected. The receiver set up time should be managed by software. The IrDA physical layer - specification specifies a minimum of 10 ms delay between transmission and - reception (IrDA is a half duplex protocol). - (++) Mode: Receiver/transmitter modes - (++) IrDAMode: the IrDA can operate in the Normal mode or in the Low power mode. - [..] - The HAL_IRDA_Init() API follows IRDA configuration procedures (details for the procedures - are available in reference manual). - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the IRDA mode according to the specified - * parameters in the IRDA_InitTypeDef and create the associated handle. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_Init(IRDA_HandleTypeDef *hirda) -{ - /* Check the IRDA handle allocation */ - if (hirda == NULL) - { - return HAL_ERROR; - } - - /* Check the IRDA instance parameters */ - assert_param(IS_IRDA_INSTANCE(hirda->Instance)); - /* Check the IRDA mode parameter in the IRDA handle */ - assert_param(IS_IRDA_POWERMODE(hirda->Init.IrDAMode)); - - if (hirda->gState == HAL_IRDA_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hirda->Lock = HAL_UNLOCKED; - -#if USE_HAL_IRDA_REGISTER_CALLBACKS == 1 - IRDA_InitCallbacksToDefault(hirda); - - if (hirda->MspInitCallback == NULL) - { - hirda->MspInitCallback = HAL_IRDA_MspInit; - } - - /* Init the low level hardware */ - hirda->MspInitCallback(hirda); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_IRDA_MspInit(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - } - - hirda->gState = HAL_IRDA_STATE_BUSY; - - /* Disable the IRDA peripheral */ - __HAL_IRDA_DISABLE(hirda); - - /* Set the IRDA communication parameters */ - IRDA_SetConfig(hirda); - - /* In IrDA mode, the following bits must be kept cleared: - - LINEN, STOP and CLKEN bits in the USART_CR2 register, - - SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(hirda->Instance->CR2, (USART_CR2_LINEN | USART_CR2_STOP | USART_CR2_CLKEN)); - CLEAR_BIT(hirda->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL)); - - /* Enable the IRDA peripheral */ - __HAL_IRDA_ENABLE(hirda); - - /* Set the prescaler */ - MODIFY_REG(hirda->Instance->GTPR, USART_GTPR_PSC, hirda->Init.Prescaler); - - /* Configure the IrDA mode */ - MODIFY_REG(hirda->Instance->CR3, USART_CR3_IRLP, hirda->Init.IrDAMode); - - /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ - SET_BIT(hirda->Instance->CR3, USART_CR3_IREN); - - /* Initialize the IRDA state*/ - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - hirda->gState = HAL_IRDA_STATE_READY; - hirda->RxState = HAL_IRDA_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the IRDA peripheral - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_DeInit(IRDA_HandleTypeDef *hirda) -{ - /* Check the IRDA handle allocation */ - if (hirda == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_IRDA_INSTANCE(hirda->Instance)); - - hirda->gState = HAL_IRDA_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_IRDA_DISABLE(hirda); - - /* DeInit the low level hardware */ -#if USE_HAL_IRDA_REGISTER_CALLBACKS == 1 - if (hirda->MspDeInitCallback == NULL) - { - hirda->MspDeInitCallback = HAL_IRDA_MspDeInit; - } - /* DeInit the low level hardware */ - hirda->MspDeInitCallback(hirda); -#else - HAL_IRDA_MspDeInit(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - - hirda->gState = HAL_IRDA_STATE_RESET; - hirda->RxState = HAL_IRDA_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hirda); - - return HAL_OK; -} - -/** - * @brief IRDA MSP Init. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_MspInit(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_IRDA_MspInit can be implemented in the user file - */ -} - -/** - * @brief IRDA MSP DeInit. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_MspDeInit(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_IRDA_MspDeInit can be implemented in the user file - */ -} - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User IRDA Callback - * To be used instead of the weak predefined callback - * @param hirda irda handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_IRDA_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID - * @arg @ref HAL_IRDA_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_IRDA_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID - * @arg @ref HAL_IRDA_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_IRDA_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_IRDA_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID - * @arg @ref HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID - * @arg @ref HAL_IRDA_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_IRDA_MSPDEINIT_CB_ID MspDeInit Callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_RegisterCallback(IRDA_HandleTypeDef *hirda, HAL_IRDA_CallbackIDTypeDef CallbackID, pIRDA_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hirda); - - if (hirda->gState == HAL_IRDA_STATE_READY) - { - switch (CallbackID) - { - case HAL_IRDA_TX_HALFCOMPLETE_CB_ID : - hirda->TxHalfCpltCallback = pCallback; - break; - - case HAL_IRDA_TX_COMPLETE_CB_ID : - hirda->TxCpltCallback = pCallback; - break; - - case HAL_IRDA_RX_HALFCOMPLETE_CB_ID : - hirda->RxHalfCpltCallback = pCallback; - break; - - case HAL_IRDA_RX_COMPLETE_CB_ID : - hirda->RxCpltCallback = pCallback; - break; - - case HAL_IRDA_ERROR_CB_ID : - hirda->ErrorCallback = pCallback; - break; - - case HAL_IRDA_ABORT_COMPLETE_CB_ID : - hirda->AbortCpltCallback = pCallback; - break; - - case HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID : - hirda->AbortTransmitCpltCallback = pCallback; - break; - - case HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID : - hirda->AbortReceiveCpltCallback = pCallback; - break; - - case HAL_IRDA_MSPINIT_CB_ID : - hirda->MspInitCallback = pCallback; - break; - - case HAL_IRDA_MSPDEINIT_CB_ID : - hirda->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hirda->gState == HAL_IRDA_STATE_RESET) - { - switch (CallbackID) - { - case HAL_IRDA_MSPINIT_CB_ID : - hirda->MspInitCallback = pCallback; - break; - - case HAL_IRDA_MSPDEINIT_CB_ID : - hirda->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hirda); - - return status; -} - -/** - * @brief Unregister an IRDA callback - * IRDA callback is redirected to the weak predefined callback - * @param hirda irda handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_IRDA_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID - * @arg @ref HAL_IRDA_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_IRDA_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID - * @arg @ref HAL_IRDA_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_IRDA_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_IRDA_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID - * @arg @ref HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID - * @arg @ref HAL_IRDA_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_IRDA_MSPDEINIT_CB_ID MspDeInit Callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_UnRegisterCallback(IRDA_HandleTypeDef *hirda, HAL_IRDA_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hirda); - - if (HAL_IRDA_STATE_READY == hirda->gState) - { - switch (CallbackID) - { - case HAL_IRDA_TX_HALFCOMPLETE_CB_ID : - hirda->TxHalfCpltCallback = HAL_IRDA_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - break; - - case HAL_IRDA_TX_COMPLETE_CB_ID : - hirda->TxCpltCallback = HAL_IRDA_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_IRDA_RX_HALFCOMPLETE_CB_ID : - hirda->RxHalfCpltCallback = HAL_IRDA_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - break; - - case HAL_IRDA_RX_COMPLETE_CB_ID : - hirda->RxCpltCallback = HAL_IRDA_RxCpltCallback; /* Legacy weak RxCpltCallback */ - break; - - case HAL_IRDA_ERROR_CB_ID : - hirda->ErrorCallback = HAL_IRDA_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_IRDA_ABORT_COMPLETE_CB_ID : - hirda->AbortCpltCallback = HAL_IRDA_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID : - hirda->AbortTransmitCpltCallback = HAL_IRDA_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ - break; - - case HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID : - hirda->AbortReceiveCpltCallback = HAL_IRDA_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ - break; - - case HAL_IRDA_MSPINIT_CB_ID : - hirda->MspInitCallback = HAL_IRDA_MspInit; /* Legacy weak MspInitCallback */ - break; - - case HAL_IRDA_MSPDEINIT_CB_ID : - hirda->MspDeInitCallback = HAL_IRDA_MspDeInit; /* Legacy weak MspDeInitCallback */ - break; - - default : - /* Update the error code */ - hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_IRDA_STATE_RESET == hirda->gState) - { - switch (CallbackID) - { - case HAL_IRDA_MSPINIT_CB_ID : - hirda->MspInitCallback = HAL_IRDA_MspInit; - break; - - case HAL_IRDA_MSPDEINIT_CB_ID : - hirda->MspDeInitCallback = HAL_IRDA_MspDeInit; - break; - - default : - /* Update the error code */ - hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hirda->ErrorCode |= HAL_IRDA_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hirda); - - return status; -} -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup IRDA_Exported_Functions_Group2 IO operation functions - * @brief IRDA Transmit and Receive functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to manage the IRDA data transfers. - IrDA is a half duplex communication protocol. If the Transmitter is busy, any data - on the IrDA receive line will be ignored by the IrDA decoder and if the Receiver - is busy, data on the TX from the USART to IrDA will not be encoded by IrDA. - While receiving data, transmission should be avoided as the data to be transmitted - could be corrupted. - - (#) There are two modes of transfer: - (++) Blocking mode: The communication is performed in polling mode. - The HAL status of all data processing is returned by the same function - after finishing transfer. - (++) Non-Blocking mode: The communication is performed using Interrupts - or DMA, these API's return the HAL status. - The end of the data processing will be indicated through the - dedicated IRDA IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - The HAL_IRDA_TxCpltCallback(), HAL_IRDA_RxCpltCallback() user callbacks - will be executed respectively at the end of the Transmit or Receive process - The HAL_IRDA_ErrorCallback() user callback will be executed when a communication error is detected - - (#) Blocking mode APIs are : - (++) HAL_IRDA_Transmit() - (++) HAL_IRDA_Receive() - - (#) Non Blocking mode APIs with Interrupt are : - (++) HAL_IRDA_Transmit_IT() - (++) HAL_IRDA_Receive_IT() - (++) HAL_IRDA_IRQHandler() - - (#) Non Blocking mode functions with DMA are : - (++) HAL_IRDA_Transmit_DMA() - (++) HAL_IRDA_Receive_DMA() - (++) HAL_IRDA_DMAPause() - (++) HAL_IRDA_DMAResume() - (++) HAL_IRDA_DMAStop() - - (#) A set of Transfer Complete Callbacks are provided in Non Blocking mode: - (++) HAL_IRDA_TxHalfCpltCallback() - (++) HAL_IRDA_TxCpltCallback() - (++) HAL_IRDA_RxHalfCpltCallback() - (++) HAL_IRDA_RxCpltCallback() - (++) HAL_IRDA_ErrorCallback() - - (#) Non-Blocking mode transfers could be aborted using Abort API's : - (+) HAL_IRDA_Abort() - (+) HAL_IRDA_AbortTransmit() - (+) HAL_IRDA_AbortReceive() - (+) HAL_IRDA_Abort_IT() - (+) HAL_IRDA_AbortTransmit_IT() - (+) HAL_IRDA_AbortReceive_IT() - - (#) For Abort services based on interrupts (HAL_IRDA_Abortxxx_IT), a set of Abort Complete Callbacks are provided: - (+) HAL_IRDA_AbortCpltCallback() - (+) HAL_IRDA_AbortTransmitCpltCallback() - (+) HAL_IRDA_AbortReceiveCpltCallback() - - (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. - Errors are handled as follows : - (+) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is - to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . - Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, - and HAL_IRDA_ErrorCallback() user callback is executed. Transfer is kept ongoing on IRDA side. - If user wants to abort it, Abort services should be called by user. - (+) Error is considered as Blocking : Transfer could not be completed properly and is aborted. - This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode. - Error code is set to allow user to identify error type, and HAL_IRDA_ErrorCallback() user callback is executed. - -@endverbatim - * @{ - */ - -/** - * @brief Sends an amount of data in blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must reflect the number - * of u16 available through pData. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent. - * @param Timeout Specify timeout value. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_Transmit(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint16_t *tmp; - uint32_t tickstart = 0U; - - /* Check that a Tx process is not already ongoing */ - if (hirda->gState == HAL_IRDA_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hirda); - - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - hirda->gState = HAL_IRDA_STATE_BUSY_TX; - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - hirda->TxXferSize = Size; - hirda->TxXferCount = Size; - while (hirda->TxXferCount > 0U) - { - hirda->TxXferCount--; - if (hirda->Init.WordLength == IRDA_WORDLENGTH_9B) - { - if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - tmp = (uint16_t *) pData; - hirda->Instance->DR = (*tmp & (uint16_t)0x01FF); - if (hirda->Init.Parity == IRDA_PARITY_NONE) - { - pData += 2U; - } - else - { - pData += 1U; - } - } - else - { - if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - hirda->Instance->DR = (*pData++ & (uint8_t)0xFF); - } - } - - if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* At end of Tx process, restore hirda->gState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must reflect the number - * of u16 available through pData. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @param Timeout Specify timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_Receive(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint16_t *tmp; - uint32_t tickstart = 0U; - - /* Check that a Rx process is not already ongoing */ - if (hirda->RxState == HAL_IRDA_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hirda); - - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - hirda->RxState = HAL_IRDA_STATE_BUSY_RX; - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - hirda->RxXferSize = Size; - hirda->RxXferCount = Size; - - /* Check the remain data to be received */ - while (hirda->RxXferCount > 0U) - { - hirda->RxXferCount--; - - if (hirda->Init.WordLength == IRDA_WORDLENGTH_9B) - { - if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - tmp = (uint16_t *) pData ; - if (hirda->Init.Parity == IRDA_PARITY_NONE) - { - *tmp = (uint16_t)(hirda->Instance->DR & (uint16_t)0x01FF); - pData += 2U; - } - else - { - *tmp = (uint16_t)(hirda->Instance->DR & (uint16_t)0x00FF); - pData += 1U; - } - } - else - { - if (IRDA_WaitOnFlagUntilTimeout(hirda, IRDA_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - if (hirda->Init.Parity == IRDA_PARITY_NONE) - { - *pData++ = (uint8_t)(hirda->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pData++ = (uint8_t)(hirda->Instance->DR & (uint8_t)0x007F); - } - } - } - - /* At end of Rx process, restore hirda->RxState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Send an amount of data in non blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must reflect the number - * of u16 available through pData. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size) -{ - /* Check that a Tx process is not already ongoing */ - if (hirda->gState == HAL_IRDA_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hirda); - - hirda->pTxBuffPtr = pData; - hirda->TxXferSize = Size; - hirda->TxXferCount = Size; - - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - hirda->gState = HAL_IRDA_STATE_BUSY_TX; - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - /* Enable the IRDA Transmit Data Register Empty Interrupt */ - SET_BIT(hirda->Instance->CR1, USART_CR1_TXEIE); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in non blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must reflect the number - * of u16 available through pData. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_Receive_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size) -{ - /* Check that a Rx process is not already ongoing */ - if (hirda->RxState == HAL_IRDA_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hirda); - - hirda->pRxBuffPtr = pData; - hirda->RxXferSize = Size; - hirda->RxXferCount = Size; - - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - hirda->RxState = HAL_IRDA_STATE_BUSY_RX; - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - /* Enable the IRDA Parity Error and Data Register Not Empty Interrupts */ - SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE); - - /* Enable the IRDA Error Interrupt: (Frame error, Noise error, Overrun error) */ - SET_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Send an amount of data in DMA mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must reflect the number - * of u16 available through pData. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_Transmit_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size) -{ - uint32_t *tmp; - - /* Check that a Tx process is not already ongoing */ - if (hirda->gState == HAL_IRDA_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hirda); - - hirda->pTxBuffPtr = pData; - hirda->TxXferSize = Size; - hirda->TxXferCount = Size; - - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - hirda->gState = HAL_IRDA_STATE_BUSY_TX; - - /* Set the IRDA DMA transfer complete callback */ - hirda->hdmatx->XferCpltCallback = IRDA_DMATransmitCplt; - - /* Set the IRDA DMA half transfer complete callback */ - hirda->hdmatx->XferHalfCpltCallback = IRDA_DMATransmitHalfCplt; - - /* Set the DMA error callback */ - hirda->hdmatx->XferErrorCallback = IRDA_DMAError; - - /* Set the DMA abort callback */ - hirda->hdmatx->XferAbortCallback = NULL; - - /* Enable the IRDA transmit DMA stream */ - tmp = (uint32_t *)&pData; - HAL_DMA_Start_IT(hirda->hdmatx, *(uint32_t *)tmp, (uint32_t)&hirda->Instance->DR, Size); - - /* Clear the TC flag in the SR register by writing 0 to it */ - __HAL_IRDA_CLEAR_FLAG(hirda, IRDA_FLAG_TC); - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - /* Enable the DMA transfer for transmit request by setting the DMAT bit - in the USART CR3 register */ - SET_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives an amount of data in DMA mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must reflect the number - * of u16 available through pData. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @note When the IRDA parity is enabled (PCE = 1) the data received contain the parity bit. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_Receive_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size) -{ - uint32_t *tmp; - - /* Check that a Rx process is not already ongoing */ - if (hirda->RxState == HAL_IRDA_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hirda); - - hirda->pRxBuffPtr = pData; - hirda->RxXferSize = Size; - - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - hirda->RxState = HAL_IRDA_STATE_BUSY_RX; - - /* Set the IRDA DMA transfer complete callback */ - hirda->hdmarx->XferCpltCallback = IRDA_DMAReceiveCplt; - - /* Set the IRDA DMA half transfer complete callback */ - hirda->hdmarx->XferHalfCpltCallback = IRDA_DMAReceiveHalfCplt; - - /* Set the DMA error callback */ - hirda->hdmarx->XferErrorCallback = IRDA_DMAError; - - /* Set the DMA abort callback */ - hirda->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - tmp = (uint32_t *)&pData; - HAL_DMA_Start_IT(hirda->hdmarx, (uint32_t)&hirda->Instance->DR, *(uint32_t *)tmp, Size); - - /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */ - __HAL_IRDA_CLEAR_OREFLAG(hirda); - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - /* Enable the IRDA Parity Error Interrupt */ - SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE); - - /* Enable the IRDA Error Interrupt: (Frame error, Noise error, Overrun error) */ - SET_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Enable the DMA transfer for the receiver request by setting the DMAR bit - in the USART CR3 register */ - SET_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Pauses the DMA Transfer. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_DMAPause(IRDA_HandleTypeDef *hirda) -{ - uint32_t dmarequest = 0x00U; - - /* Process Locked */ - __HAL_LOCK(hirda); - - dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT); - if ((hirda->gState == HAL_IRDA_STATE_BUSY_TX) && dmarequest) - { - /* Disable the IRDA DMA Tx request */ - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - } - - dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR); - if ((hirda->RxState == HAL_IRDA_STATE_BUSY_RX) && dmarequest) - { - /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hirda->Instance->CR1, USART_CR1_PEIE); - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Disable the IRDA DMA Rx request */ - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - return HAL_OK; -} - -/** - * @brief Resumes the DMA Transfer. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_DMAResume(IRDA_HandleTypeDef *hirda) -{ - /* Process Locked */ - __HAL_LOCK(hirda); - - if (hirda->gState == HAL_IRDA_STATE_BUSY_TX) - { - /* Enable the IRDA DMA Tx request */ - SET_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - } - - if (hirda->RxState == HAL_IRDA_STATE_BUSY_RX) - { - /* Clear the Overrun flag before resuming the Rx transfer */ - __HAL_IRDA_CLEAR_OREFLAG(hirda); - - /* Re-enable PE and ERR (Frame error, noise error, overrun error) interrupts */ - SET_BIT(hirda->Instance->CR1, USART_CR1_PEIE); - SET_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Enable the IRDA DMA Rx request */ - SET_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - return HAL_OK; -} - -/** - * @brief Stops the DMA Transfer. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IRDA_DMAStop(IRDA_HandleTypeDef *hirda) -{ - uint32_t dmarequest = 0x00U; - /* The Lock is not implemented on this API to allow the user application - to call the HAL IRDA API under callbacks HAL_IRDA_TxCpltCallback() / HAL_IRDA_RxCpltCallback(): - when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated - and the correspond call back is executed HAL_IRDA_TxCpltCallback() / HAL_IRDA_RxCpltCallback() - */ - - /* Stop IRDA DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT); - if ((hirda->gState == HAL_IRDA_STATE_BUSY_TX) && dmarequest) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - - /* Abort the IRDA DMA Tx channel */ - if (hirda->hdmatx != NULL) - { - HAL_DMA_Abort(hirda->hdmatx); - } - IRDA_EndTxTransfer(hirda); - } - - /* Stop IRDA DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR); - if ((hirda->RxState == HAL_IRDA_STATE_BUSY_RX) && dmarequest) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - - /* Abort the IRDA DMA Rx channel */ - if (hirda->hdmarx != NULL) - { - HAL_DMA_Abort(hirda->hdmarx); - } - IRDA_EndRxTransfer(hirda); - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing transfers (blocking mode). - * @param hirda IRDA handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_IRDA_Abort(IRDA_HandleTypeDef *hirda) -{ - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Disable the IRDA DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - - /* Abort the IRDA DMA Tx channel : use blocking DMA Abort API (no callback) */ - if (hirda->hdmatx != NULL) - { - /* Set the IRDA DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - hirda->hdmatx->XferAbortCallback = NULL; - - HAL_DMA_Abort(hirda->hdmatx); - } - } - - /* Disable the IRDA DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - - /* Abort the IRDA DMA Rx channel : use blocking DMA Abort API (no callback) */ - if (hirda->hdmarx != NULL) - { - /* Set the IRDA DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - hirda->hdmarx->XferAbortCallback = NULL; - - HAL_DMA_Abort(hirda->hdmarx); - } - } - - /* Reset Tx and Rx transfer counters */ - hirda->TxXferCount = 0x00U; - hirda->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - - /* Restore hirda->RxState and hirda->gState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; - hirda->gState = HAL_IRDA_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Abort ongoing Transmit transfer (blocking mode). - * @param hirda IRDA handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_IRDA_AbortTransmit(IRDA_HandleTypeDef *hirda) -{ - /* Disable TXEIE and TCIE interrupts */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* Disable the IRDA DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - - /* Abort the IRDA DMA Tx channel : use blocking DMA Abort API (no callback) */ - if (hirda->hdmatx != NULL) - { - /* Set the IRDA DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - hirda->hdmatx->XferAbortCallback = NULL; - - HAL_DMA_Abort(hirda->hdmatx); - } - } - - /* Reset Tx transfer counter */ - hirda->TxXferCount = 0x00U; - - /* Restore hirda->gState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Abort ongoing Receive transfer (blocking mode). - * @param hirda IRDA handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_IRDA_AbortReceive(IRDA_HandleTypeDef *hirda) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Disable the IRDA DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - - /* Abort the IRDA DMA Rx channel : use blocking DMA Abort API (no callback) */ - if (hirda->hdmarx != NULL) - { - /* Set the IRDA DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - hirda->hdmarx->XferAbortCallback = NULL; - - HAL_DMA_Abort(hirda->hdmarx); - } - } - - /* Reset Rx transfer counter */ - hirda->RxXferCount = 0x00U; - - /* Restore hirda->RxState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Abort ongoing transfers (Interrupt mode). - * @param hirda IRDA handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_IRDA_Abort_IT(IRDA_HandleTypeDef *hirda) -{ - uint32_t AbortCplt = 0x01U; - - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* If DMA Tx and/or DMA Rx Handles are associated to IRDA Handle, DMA Abort complete callbacks should be initialised - before any call to DMA Abort functions */ - /* DMA Tx Handle is valid */ - if (hirda->hdmatx != NULL) - { - /* Set DMA Abort Complete callback if IRDA DMA Tx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) - { - hirda->hdmatx->XferAbortCallback = IRDA_DMATxAbortCallback; - } - else - { - hirda->hdmatx->XferAbortCallback = NULL; - } - } - /* DMA Rx Handle is valid */ - if (hirda->hdmarx != NULL) - { - /* Set DMA Abort Complete callback if IRDA DMA Rx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) - { - hirda->hdmarx->XferAbortCallback = IRDA_DMARxAbortCallback; - } - else - { - hirda->hdmarx->XferAbortCallback = NULL; - } - } - - /* Disable the IRDA DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) - { - /* Disable DMA Tx at IRDA level */ - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - - /* Abort the IRDA DMA Tx channel : use non blocking DMA Abort API (callback) */ - if (hirda->hdmatx != NULL) - { - /* IRDA Tx DMA Abort callback has already been initialised : - will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hirda->hdmatx) != HAL_OK) - { - hirda->hdmatx->XferAbortCallback = NULL; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* Disable the IRDA DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - - /* Abort the IRDA DMA Rx channel : use non blocking DMA Abort API (callback) */ - if (hirda->hdmarx != NULL) - { - /* IRDA Rx DMA Abort callback has already been initialised : - will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK) - { - hirda->hdmarx->XferAbortCallback = NULL; - AbortCplt = 0x01U; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ - if (AbortCplt == 0x01U) - { - /* Reset Tx and Rx transfer counters */ - hirda->TxXferCount = 0x00U; - hirda->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - - /* Restore hirda->gState and hirda->RxState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - hirda->RxState = HAL_IRDA_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - hirda->AbortCpltCallback(hirda); -#else - /* Call legacy weak Abort complete callback */ - HAL_IRDA_AbortCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing Transmit transfer (Interrupt mode). - * @param hirda IRDA handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable IRDA Interrupts (Tx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_IRDA_AbortTransmit_IT(IRDA_HandleTypeDef *hirda) -{ - /* Disable TXEIE and TCIE interrupts */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* Disable the IRDA DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT)) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - - /* Abort the IRDA DMA Tx channel : use non blocking DMA Abort API (callback) */ - if (hirda->hdmatx != NULL) - { - /* Set the IRDA DMA Abort callback : - will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */ - hirda->hdmatx->XferAbortCallback = IRDA_DMATxOnlyAbortCallback; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(hirda->hdmatx) != HAL_OK) - { - /* Call Directly hirda->hdmatx->XferAbortCallback function in case of error */ - hirda->hdmatx->XferAbortCallback(hirda->hdmatx); - } - } - else - { - /* Reset Tx transfer counter */ - hirda->TxXferCount = 0x00U; - - /* Restore hirda->gState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - hirda->AbortTransmitCpltCallback(hirda); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_IRDA_AbortTransmitCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - } - } - else - { - /* Reset Tx transfer counter */ - hirda->TxXferCount = 0x00U; - - /* Restore hirda->gState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - hirda->AbortTransmitCpltCallback(hirda); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_IRDA_AbortTransmitCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing Receive transfer (Interrupt mode). - * @param hirda IRDA handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_IRDA_AbortReceive_IT(IRDA_HandleTypeDef *hirda) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Disable the IRDA DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - - /* Abort the IRDA DMA Rx channel : use non blocking DMA Abort API (callback) */ - if (hirda->hdmarx != NULL) - { - /* Set the IRDA DMA Abort callback : - will lead to call HAL_IRDA_AbortCpltCallback() at end of DMA abort procedure */ - hirda->hdmarx->XferAbortCallback = IRDA_DMARxOnlyAbortCallback; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK) - { - /* Call Directly hirda->hdmarx->XferAbortCallback function in case of error */ - hirda->hdmarx->XferAbortCallback(hirda->hdmarx); - } - } - else - { - /* Reset Rx transfer counter */ - hirda->RxXferCount = 0x00U; - - /* Restore hirda->RxState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - hirda->AbortReceiveCpltCallback(hirda); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_IRDA_AbortReceiveCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - } - } - else - { - /* Reset Rx transfer counter */ - hirda->RxXferCount = 0x00U; - - /* Restore hirda->RxState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - hirda->AbortReceiveCpltCallback(hirda); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_IRDA_AbortReceiveCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - } - - return HAL_OK; -} - -/** - * @brief This function handles IRDA interrupt request. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -void HAL_IRDA_IRQHandler(IRDA_HandleTypeDef *hirda) -{ - uint32_t isrflags = READ_REG(hirda->Instance->SR); - uint32_t cr1its = READ_REG(hirda->Instance->CR1); - uint32_t cr3its = READ_REG(hirda->Instance->CR3); - uint32_t errorflags = 0x00U; - uint32_t dmarequest = 0x00U; - - /* If no error occurs */ - errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); - if (errorflags == RESET) - { - /* IRDA in mode Receiver -----------------------------------------------*/ - if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - IRDA_Receive_IT(hirda); - return; - } - } - - /* If some errors occur */ - if ((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) - { - /* IRDA parity error interrupt occurred -------------------------------*/ - if (((isrflags & USART_SR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) - { - hirda->ErrorCode |= HAL_IRDA_ERROR_PE; - } - - /* IRDA noise error interrupt occurred --------------------------------*/ - if (((isrflags & USART_SR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - hirda->ErrorCode |= HAL_IRDA_ERROR_NE; - } - - /* IRDA frame error interrupt occurred --------------------------------*/ - if (((isrflags & USART_SR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - hirda->ErrorCode |= HAL_IRDA_ERROR_FE; - } - - /* IRDA Over-Run interrupt occurred -----------------------------------*/ - if (((isrflags & USART_SR_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET))) - { - hirda->ErrorCode |= HAL_IRDA_ERROR_ORE; - } - /* Call IRDA Error Call back function if need be -----------------------*/ - if (hirda->ErrorCode != HAL_IRDA_ERROR_NONE) - { - /* IRDA in mode Receiver ---------------------------------------------*/ - if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - IRDA_Receive_IT(hirda); - } - - /* If Overrun error occurs, or if any error occurs in DMA mode reception, - consider error as blocking */ - dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR); - if (((hirda->ErrorCode & HAL_IRDA_ERROR_ORE) != RESET) || dmarequest) - { - /* Blocking error : transfer is aborted - Set the IRDA state ready to be able to start again the process, - Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ - IRDA_EndRxTransfer(hirda); - - /* Disable the IRDA DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - - /* Abort the IRDA DMA Rx channel */ - if (hirda->hdmarx != NULL) - { - /* Set the IRDA DMA Abort callback : - will lead to call HAL_IRDA_ErrorCallback() at end of DMA abort procedure */ - hirda->hdmarx->XferAbortCallback = IRDA_DMAAbortOnError; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(hirda->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hirda->hdmarx->XferAbortCallback(hirda->hdmarx); - } - } - else - { -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hirda->ErrorCallback(hirda); -#else - /* Call legacy weak user error callback */ - HAL_IRDA_ErrorCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - } - } - else - { -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hirda->ErrorCallback(hirda); -#else - /* Call legacy weak user error callback */ - HAL_IRDA_ErrorCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - } - } - else - { - /* Non Blocking error : transfer could go on. - Error is notified to user through user error callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hirda->ErrorCallback(hirda); -#else - /* Call legacy weak user error callback */ - HAL_IRDA_ErrorCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - } - } - return; - } /* End if some error occurs */ - - /* IRDA in mode Transmitter ------------------------------------------------*/ - if (((isrflags & USART_SR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) - { - IRDA_Transmit_IT(hirda); - return; - } - - /* IRDA in mode Transmitter end --------------------------------------------*/ - if (((isrflags & USART_SR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) - { - IRDA_EndTransmit_IT(hirda); - return; - } -} - -/** - * @brief Tx Transfer complete callback. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_TxCpltCallback(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_IRDA_TxCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief Tx Half Transfer completed callback. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_IRDA_TxHalfCpltCallback(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_IRDA_TxHalfCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief Rx Transfer complete callback. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_RxCpltCallback(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_IRDA_RxCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief Rx Half Transfer complete callback. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_RxHalfCpltCallback(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_IRDA_RxHalfCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief IRDA error callback. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_ErrorCallback(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_IRDA_ErrorCallback can be implemented in the user file. - */ -} - -/** - * @brief IRDA Abort Complete callback. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_AbortCpltCallback(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_IRDA_AbortCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief IRDA Abort Transmit Complete callback. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_AbortTransmitCpltCallback(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_IRDA_AbortTransmitCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief IRDA Abort Receive Complete callback. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -__weak void HAL_IRDA_AbortReceiveCpltCallback(IRDA_HandleTypeDef *hirda) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hirda); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_IRDA_AbortReceiveCpltCallback can be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup IRDA_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief IRDA State and Errors functions - * -@verbatim - ============================================================================== - ##### Peripheral State and Errors functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to return the State of IrDA - communication process and also return Peripheral Errors occurred during communication process - (+) HAL_IRDA_GetState() API can be helpful to check in run-time the state of the IrDA peripheral. - (+) HAL_IRDA_GetError() check in run-time errors that could be occurred during communication. - -@endverbatim - * @{ - */ - -/** - * @brief Return the IRDA state. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA. - * @retval HAL state - */ -HAL_IRDA_StateTypeDef HAL_IRDA_GetState(IRDA_HandleTypeDef *hirda) -{ - uint32_t temp1 = 0x00U, temp2 = 0x00U; - temp1 = hirda->gState; - temp2 = hirda->RxState; - - return (HAL_IRDA_StateTypeDef)(temp1 | temp2); -} - -/** - * @brief Return the IRDA error code - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA. - * @retval IRDA Error Code - */ -uint32_t HAL_IRDA_GetError(IRDA_HandleTypeDef *hirda) -{ - return hirda->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup IRDA_Private_Functions IRDA Private Functions - * @{ - */ - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -/** - * @brief Initialize the callbacks to their default values. - * @param hirda IRDA handle. - * @retval none - */ -void IRDA_InitCallbacksToDefault(IRDA_HandleTypeDef *hirda) -{ - /* Init the IRDA Callback settings */ - hirda->TxHalfCpltCallback = HAL_IRDA_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - hirda->TxCpltCallback = HAL_IRDA_TxCpltCallback; /* Legacy weak TxCpltCallback */ - hirda->RxHalfCpltCallback = HAL_IRDA_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - hirda->RxCpltCallback = HAL_IRDA_RxCpltCallback; /* Legacy weak RxCpltCallback */ - hirda->ErrorCallback = HAL_IRDA_ErrorCallback; /* Legacy weak ErrorCallback */ - hirda->AbortCpltCallback = HAL_IRDA_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - hirda->AbortTransmitCpltCallback = HAL_IRDA_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ - hirda->AbortReceiveCpltCallback = HAL_IRDA_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ - -} -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - -/** - * @brief DMA IRDA transmit process complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA. - * @retval None - */ -static void IRDA_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* DMA Normal mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) - { - hirda->TxXferCount = 0U; - - /* Disable the DMA transfer for transmit request by resetting the DMAT bit - in the IRDA CR3 register */ - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAT); - - /* Enable the IRDA Transmit Complete Interrupt */ - SET_BIT(hirda->Instance->CR1, USART_CR1_TCIE); - } - /* DMA Circular mode */ - else - { -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Tx complete callback */ - hirda->TxCpltCallback(hirda); -#else - /* Call legacy weak Tx complete callback */ - HAL_IRDA_TxCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - } -} - -/** - * @brief DMA IRDA receive process half complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA. - * @retval None - */ -static void IRDA_DMATransmitHalfCplt(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Tx Half complete callback */ - hirda->TxHalfCpltCallback(hirda); -#else - /* Call legacy weak Tx complete callback */ - HAL_IRDA_TxHalfCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ -} - -/** - * @brief DMA IRDA receive process complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA. - * @retval None - */ -static void IRDA_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* DMA Normal mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) - { - hirda->RxXferCount = 0U; - - /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hirda->Instance->CR1, USART_CR1_PEIE); - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Disable the DMA transfer for the receiver request by resetting the DMAR bit - in the IRDA CR3 register */ - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_DMAR); - - /* At end of Rx process, restore hirda->RxState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; - } - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Rx complete callback */ - hirda->RxCpltCallback(hirda); -#else - /* Call legacy weak Rx complete callback */ - HAL_IRDA_RxCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA IRDA receive process half complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA. - * @retval None - */ -static void IRDA_DMAReceiveHalfCplt(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /*Call registered Rx Half complete callback*/ - hirda->RxHalfCpltCallback(hirda); -#else - /* Call legacy weak Rx Half complete callback */ - HAL_IRDA_RxHalfCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ -} - -/** - * @brief DMA IRDA communication error callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA. - * @retval None - */ -static void IRDA_DMAError(DMA_HandleTypeDef *hdma) -{ - uint32_t dmarequest = 0x00U; - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Stop IRDA DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAT); - if ((hirda->gState == HAL_IRDA_STATE_BUSY_TX) && dmarequest) - { - hirda->TxXferCount = 0U; - IRDA_EndTxTransfer(hirda); - } - - /* Stop IRDA DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(hirda->Instance->CR3, USART_CR3_DMAR); - if ((hirda->RxState == HAL_IRDA_STATE_BUSY_RX) && dmarequest) - { - hirda->RxXferCount = 0U; - IRDA_EndRxTransfer(hirda); - } - - hirda->ErrorCode |= HAL_IRDA_ERROR_DMA; - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hirda->ErrorCallback(hirda); -#else - /* Call legacy weak user error callback */ - HAL_IRDA_ErrorCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ -} - -/** - * @brief This function handles IRDA Communication Timeout. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA. - * @param Flag specifies the IRDA flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Tickstart Tick start value - * @param Timeout Timeout duration - * @retval HAL status - */ -static HAL_StatusTypeDef IRDA_WaitOnFlagUntilTimeout(IRDA_HandleTypeDef *hirda, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout) -{ - /* Wait until flag is set */ - while ((__HAL_IRDA_GET_FLAG(hirda, Flag) ? SET : RESET) == Status) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) - { - /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE)); - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - hirda->gState = HAL_IRDA_STATE_READY; - hirda->RxState = HAL_IRDA_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hirda); - - return HAL_TIMEOUT; - } - } - } - return HAL_OK; -} - -/** - * @brief End ongoing Tx transfer on IRDA peripheral (following error detection or Transmit completion). - * @param hirda IRDA handle. - * @retval None - */ -static void IRDA_EndTxTransfer(IRDA_HandleTypeDef *hirda) -{ - /* Disable TXEIE and TCIE interrupts */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* At end of Tx process, restore hirda->gState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; -} - -/** - * @brief End ongoing Rx transfer on IRDA peripheral (following error detection or Reception completion). - * @param hirda IRDA handle. - * @retval None - */ -static void IRDA_EndRxTransfer(IRDA_HandleTypeDef *hirda) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* At end of Rx process, restore hirda->RxState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; -} - -/** - * @brief DMA IRDA communication abort callback, when initiated by HAL services on Error - * (To be called at end of DMA Abort procedure following error occurrence). - * @param hdma DMA handle. - * @retval None - */ -static void IRDA_DMAAbortOnError(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - hirda->RxXferCount = 0x00U; - hirda->TxXferCount = 0x00U; - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hirda->ErrorCallback(hirda); -#else - /* Call legacy weak user error callback */ - HAL_IRDA_ErrorCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ -} - -/** - * @brief DMA IRDA Tx communication abort callback, when initiated by user - * (To be called at end of DMA Tx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Rx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void IRDA_DMATxAbortCallback(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - hirda->hdmatx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if (hirda->hdmarx != NULL) - { - if (hirda->hdmarx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - hirda->TxXferCount = 0x00U; - hirda->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - - /* Restore hirda->gState and hirda->RxState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - hirda->RxState = HAL_IRDA_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - hirda->AbortCpltCallback(hirda); -#else - /* Call legacy weak Abort complete callback */ - HAL_IRDA_AbortCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ -} - -/** - * @brief DMA IRDA Rx communication abort callback, when initiated by user - * (To be called at end of DMA Rx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Tx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void IRDA_DMARxAbortCallback(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - hirda->hdmarx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if (hirda->hdmatx != NULL) - { - if (hirda->hdmatx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - hirda->TxXferCount = 0x00U; - hirda->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - hirda->ErrorCode = HAL_IRDA_ERROR_NONE; - - /* Restore hirda->gState and hirda->RxState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - hirda->RxState = HAL_IRDA_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - hirda->AbortCpltCallback(hirda); -#else - /* Call legacy weak Abort complete callback */ - HAL_IRDA_AbortCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ -} - -/** - * @brief DMA IRDA Tx communication abort callback, when initiated by user by a call to - * HAL_IRDA_AbortTransmit_IT API (Abort only Tx transfer) - * (This callback is executed at end of DMA Tx Abort procedure following user abort request, - * and leads to user Tx Abort Complete callback execution). - * @param hdma DMA handle. - * @retval None - */ -static void IRDA_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - hirda->TxXferCount = 0x00U; - - /* Restore hirda->gState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - hirda->AbortTransmitCpltCallback(hirda); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_IRDA_AbortTransmitCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ -} - -/** - * @brief DMA IRDA Rx communication abort callback, when initiated by user by a call to - * HAL_IRDA_AbortReceive_IT API (Abort only Rx transfer) - * (This callback is executed at end of DMA Rx Abort procedure following user abort request, - * and leads to user Rx Abort Complete callback execution). - * @param hdma DMA handle. - * @retval None - */ -static void IRDA_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma) -{ - IRDA_HandleTypeDef *hirda = (IRDA_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - hirda->RxXferCount = 0x00U; - - /* Restore hirda->RxState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - hirda->AbortReceiveCpltCallback(hirda); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_IRDA_AbortReceiveCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ -} - -/** - * @brief Send an amount of data in non blocking mode. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval HAL status - */ -static HAL_StatusTypeDef IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda) -{ - uint16_t *tmp; - - /* Check that a Tx process is ongoing */ - if (hirda->gState == HAL_IRDA_STATE_BUSY_TX) - { - if (hirda->Init.WordLength == IRDA_WORDLENGTH_9B) - { - tmp = (uint16_t *) hirda->pTxBuffPtr; - hirda->Instance->DR = (uint16_t)(*tmp & (uint16_t)0x01FF); - if (hirda->Init.Parity == IRDA_PARITY_NONE) - { - hirda->pTxBuffPtr += 2U; - } - else - { - hirda->pTxBuffPtr += 1U; - } - } - else - { - hirda->Instance->DR = (uint8_t)(*hirda->pTxBuffPtr++ & (uint8_t)0x00FF); - } - - if (--hirda->TxXferCount == 0U) - { - /* Disable the IRDA Transmit Data Register Empty Interrupt */ - CLEAR_BIT(hirda->Instance->CR1, USART_CR1_TXEIE); - - /* Enable the IRDA Transmit Complete Interrupt */ - SET_BIT(hirda->Instance->CR1, USART_CR1_TCIE); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Wraps up transmission in non blocking mode. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval HAL status - */ -static HAL_StatusTypeDef IRDA_EndTransmit_IT(IRDA_HandleTypeDef *hirda) -{ - /* Disable the IRDA Transmit Complete Interrupt */ - CLEAR_BIT(hirda->Instance->CR1, USART_CR1_TCIE); - - /* Disable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Tx process is ended, restore hirda->gState to Ready */ - hirda->gState = HAL_IRDA_STATE_READY; - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Tx complete callback */ - hirda->TxCpltCallback(hirda); -#else - /* Call legacy weak Tx complete callback */ - HAL_IRDA_TxCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACK */ - - return HAL_OK; -} - -/** - * @brief Receives an amount of data in non blocking mode. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval HAL status - */ -static HAL_StatusTypeDef IRDA_Receive_IT(IRDA_HandleTypeDef *hirda) -{ - uint16_t *tmp; - uint16_t uhdata; - - /* Check that a Rx process is ongoing */ - if (hirda->RxState == HAL_IRDA_STATE_BUSY_RX) - { - uhdata = (uint16_t) READ_REG(hirda->Instance->DR); - if (hirda->Init.WordLength == IRDA_WORDLENGTH_9B) - { - tmp = (uint16_t *) hirda->pRxBuffPtr; - if (hirda->Init.Parity == IRDA_PARITY_NONE) - { - *tmp = (uint16_t)(uhdata & (uint16_t)0x01FF); - hirda->pRxBuffPtr += 2U; - } - else - { - *tmp = (uint16_t)(uhdata & (uint16_t)0x00FF); - hirda->pRxBuffPtr += 1U; - } - } - else - { - if (hirda->Init.Parity == IRDA_PARITY_NONE) - { - *hirda->pRxBuffPtr++ = (uint8_t)(uhdata & (uint8_t)0x00FF); - } - else - { - *hirda->pRxBuffPtr++ = (uint8_t)(uhdata & (uint8_t)0x007F); - } - } - - if (--hirda->RxXferCount == 0U) - { - /* Disable the IRDA Data Register not empty Interrupt */ - CLEAR_BIT(hirda->Instance->CR1, USART_CR1_RXNEIE); - - /* Disable the IRDA Parity Error Interrupt */ - CLEAR_BIT(hirda->Instance->CR1, USART_CR1_PEIE); - - /* Disable the IRDA Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(hirda->Instance->CR3, USART_CR3_EIE); - - /* Rx process is completed, restore hirda->RxState to Ready */ - hirda->RxState = HAL_IRDA_STATE_READY; - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - /* Call registered Rx complete callback */ - hirda->RxCpltCallback(hirda); -#else - /* Call legacy weak Rx complete callback */ - HAL_IRDA_RxCpltCallback(hirda); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - - return HAL_OK; - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configures the IRDA peripheral. - * @param hirda Pointer to a IRDA_HandleTypeDef structure that contains - * the configuration information for the specified IRDA module. - * @retval None - */ -static void IRDA_SetConfig(IRDA_HandleTypeDef *hirda) -{ - uint32_t pclk; - - /* Check the parameters */ - assert_param(IS_IRDA_INSTANCE(hirda->Instance)); - assert_param(IS_IRDA_BAUDRATE(hirda->Init.BaudRate)); - assert_param(IS_IRDA_WORD_LENGTH(hirda->Init.WordLength)); - assert_param(IS_IRDA_PARITY(hirda->Init.Parity)); - assert_param(IS_IRDA_MODE(hirda->Init.Mode)); - assert_param(IS_IRDA_POWERMODE(hirda->Init.IrDAMode)); - - /*-------------------------- USART CR2 Configuration ------------------------*/ - /* Clear STOP[13:12] bits */ - CLEAR_BIT(hirda->Instance->CR2, USART_CR2_STOP); - - /*-------------------------- USART CR1 Configuration -----------------------*/ - /* Clear M, PCE, PS, TE and RE bits */ - CLEAR_BIT(hirda->Instance->CR1, (USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | USART_CR1_RE)); - - /* Configure the USART Word Length, Parity and mode: - Set the M bits according to hirda->Init.WordLength value - Set PCE and PS bits according to hirda->Init.Parity value - Set TE and RE bits according to hirda->Init.Mode value */ - /* Write to USART CR1 */ - SET_BIT(hirda->Instance->CR1, (hirda->Init.WordLength | hirda->Init.Parity | hirda->Init.Mode)); - - /*-------------------------- USART CR3 Configuration -----------------------*/ - /* Clear CTSE and RTSE bits */ - CLEAR_BIT(hirda->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE)); - - /*-------------------------- USART BRR Configuration -----------------------*/ -#if defined(USART6) && defined(UART9) && defined(UART10) - if ((hirda->Instance == USART1) || (hirda->Instance == USART6) || (hirda->Instance == UART9) || (hirda->Instance == UART10)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - SET_BIT(hirda->Instance->BRR, IRDA_BRR(pclk, hirda->Init.BaudRate)); - } -#elif defined(USART6) - if((hirda->Instance == USART1) || (hirda->Instance == USART6)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - SET_BIT(hirda->Instance->BRR, IRDA_BRR(pclk, hirda->Init.BaudRate)); - } -#else - if(hirda->Instance == USART1) - { - pclk = HAL_RCC_GetPCLK2Freq(); - SET_BIT(hirda->Instance->BRR, IRDA_BRR(pclk, hirda->Init.BaudRate)); - } -#endif /* USART6 */ - else - { - pclk = HAL_RCC_GetPCLK1Freq(); - SET_BIT(hirda->Instance->BRR, IRDA_BRR(pclk, hirda->Init.BaudRate)); - } -} - -/** - * @} - */ - -#endif /* HAL_IRDA_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c deleted file mode 100644 index 5f376dac6cdf52c..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_iwdg.c +++ /dev/null @@ -1,265 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_iwdg.c - * @author MCD Application Team - * @brief IWDG HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Independent Watchdog (IWDG) peripheral: - * + Initialization and Start functions - * + IO operation functions - * - @verbatim - ============================================================================== - ##### IWDG Generic features ##### - ============================================================================== - [..] - (+) The IWDG can be started by either software or hardware (configurable - through option byte). - - (+) The IWDG is clocked by the Low-Speed Internal clock (LSI) and thus stays - active even if the main clock fails. - - (+) Once the IWDG is started, the LSI is forced ON and both cannot be - disabled. The counter starts counting down from the reset value (0xFFF). - When it reaches the end of count value (0x000) a reset signal is - generated (IWDG reset). - - (+) Whenever the key value 0x0000 AAAA is written in the IWDG_KR register, - the IWDG_RLR value is reloaded into the counter and the watchdog reset - is prevented. - - (+) The IWDG is implemented in the VDD voltage domain that is still functional - in STOP and STANDBY mode (IWDG reset can wake up the CPU from STANDBY). - IWDGRST flag in RCC_CSR register can be used to inform when an IWDG - reset occurs. - - (+) Debug mode: When the microcontroller enters debug mode (core halted), - the IWDG counter either continues to work normally or stops, depending - on DBG_IWDG_STOP configuration bit in DBG module, accessible through - __HAL_DBGMCU_FREEZE_IWDG() and __HAL_DBGMCU_UNFREEZE_IWDG() macros. - - [..] Min-max timeout value @32KHz (LSI): ~125us / ~32.7s - The IWDG timeout may vary due to LSI clock frequency dispersion. - STM32F4xx devices provide the capability to measure the LSI clock - frequency (LSI clock is internally connected to TIM5 CH4 input capture). - The measured value can be used to have an IWDG timeout with an - acceptable accuracy. - - [..] Default timeout value (necessary for IWDG_SR status register update): - Constant LSI_VALUE is defined based on the nominal LSI clock frequency. - This frequency being subject to variations as mentioned above, the - default timeout value (defined through constant HAL_IWDG_DEFAULT_TIMEOUT - below) may become too short or too long. - In such cases, this default timeout value can be tuned by redefining - the constant LSI_VALUE at user-application level (based, for instance, - on the measured LSI clock frequency as explained above). - - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Use IWDG using HAL_IWDG_Init() function to : - (++) Enable instance by writing Start keyword in IWDG_KEY register. LSI - clock is forced ON and IWDG counter starts counting down. - (++) Enable write access to configuration registers: - IWDG_PR and IWDG_RLR. - (++) Configure the IWDG prescaler and counter reload value. This reload - value will be loaded in the IWDG counter each time the watchdog is - reloaded, then the IWDG will start counting down from this value. - (++) Wait for status flags to be reset. - - (#) Then the application program must refresh the IWDG counter at regular - intervals during normal operation to prevent an MCU reset, using - HAL_IWDG_Refresh() function. - - *** IWDG HAL driver macros list *** - ==================================== - [..] - Below the list of most used macros in IWDG HAL driver: - (+) __HAL_IWDG_START: Enable the IWDG peripheral - (+) __HAL_IWDG_RELOAD_COUNTER: Reloads IWDG counter with value defined in - the reload register - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_IWDG_MODULE_ENABLED -/** @addtogroup IWDG - * @brief IWDG HAL module driver. - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup IWDG_Private_Defines IWDG Private Defines - * @{ - */ -/* Status register needs up to 5 LSI clock periods divided by the clock - prescaler to be updated. The number of LSI clock periods is upper-rounded to - 6 for the timeout value calculation. - The timeout value is calculated using the highest prescaler (256) and - the LSI_VALUE constant. The value of this constant can be changed by the user - to take into account possible LSI clock period variations. - The timeout value is multiplied by 1000 to be converted in milliseconds. - LSI startup time is also considered here by adding LSI_STARTUP_TIMEOUT - converted in milliseconds. */ -#define HAL_IWDG_DEFAULT_TIMEOUT (((6UL * 256UL * 1000UL) / LSI_VALUE) + ((LSI_STARTUP_TIME / 1000UL) + 1UL)) -#define IWDG_KERNEL_UPDATE_FLAGS (IWDG_SR_RVU | IWDG_SR_PVU) -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup IWDG_Exported_Functions - * @{ - */ - -/** @addtogroup IWDG_Exported_Functions_Group1 - * @brief Initialization and Start functions. - * -@verbatim - =============================================================================== - ##### Initialization and Start functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize the IWDG according to the specified parameters in the - IWDG_InitTypeDef of associated handle. - (+) Once initialization is performed in HAL_IWDG_Init function, Watchdog - is reloaded in order to exit function with correct time base. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the IWDG according to the specified parameters in the - * IWDG_InitTypeDef and start watchdog. Before exiting function, - * watchdog is refreshed in order to have correct time base. - * @param hiwdg pointer to a IWDG_HandleTypeDef structure that contains - * the configuration information for the specified IWDG module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IWDG_Init(IWDG_HandleTypeDef *hiwdg) -{ - uint32_t tickstart; - - /* Check the IWDG handle allocation */ - if (hiwdg == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_IWDG_ALL_INSTANCE(hiwdg->Instance)); - assert_param(IS_IWDG_PRESCALER(hiwdg->Init.Prescaler)); - assert_param(IS_IWDG_RELOAD(hiwdg->Init.Reload)); - - /* Enable IWDG. LSI is turned on automatically */ - __HAL_IWDG_START(hiwdg); - - /* Enable write access to IWDG_PR and IWDG_RLR registers by writing - 0x5555 in KR */ - IWDG_ENABLE_WRITE_ACCESS(hiwdg); - - /* Write to IWDG registers the Prescaler & Reload values to work with */ - hiwdg->Instance->PR = hiwdg->Init.Prescaler; - hiwdg->Instance->RLR = hiwdg->Init.Reload; - - /* Check pending flag, if previous update not done, return timeout */ - tickstart = HAL_GetTick(); - - /* Wait for register to be updated */ - while ((hiwdg->Instance->SR & IWDG_KERNEL_UPDATE_FLAGS) != 0x00u) - { - if ((HAL_GetTick() - tickstart) > HAL_IWDG_DEFAULT_TIMEOUT) - { - if ((hiwdg->Instance->SR & IWDG_KERNEL_UPDATE_FLAGS) != 0x00u) - { - return HAL_TIMEOUT; - } - } - } - - /* Reload IWDG counter with value defined in the reload register */ - __HAL_IWDG_RELOAD_COUNTER(hiwdg); - - /* Return function status */ - return HAL_OK; -} - - -/** - * @} - */ - - -/** @addtogroup IWDG_Exported_Functions_Group2 - * @brief IO operation functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Refresh the IWDG. - -@endverbatim - * @{ - */ - -/** - * @brief Refresh the IWDG. - * @param hiwdg pointer to a IWDG_HandleTypeDef structure that contains - * the configuration information for the specified IWDG module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_IWDG_Refresh(IWDG_HandleTypeDef *hiwdg) -{ - /* Reload IWDG counter with value defined in the reload register */ - __HAL_IWDG_RELOAD_COUNTER(hiwdg); - - /* Return function status */ - return HAL_OK; -} - - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_IWDG_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_lptim.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_lptim.c deleted file mode 100644 index 0ed761721e888bc..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_lptim.c +++ /dev/null @@ -1,2479 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_lptim.c - * @author MCD Application Team - * @brief LPTIM HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Low Power Timer (LPTIM) peripheral: - * + Initialization and de-initialization functions. - * + Start/Stop operation functions in polling mode. - * + Start/Stop operation functions in interrupt mode. - * + Reading operation functions. - * + Peripheral State functions. - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LPTIM HAL driver can be used as follows: - - (#)Initialize the LPTIM low level resources by implementing the - HAL_LPTIM_MspInit(): - (++) Enable the LPTIM interface clock using __HAL_RCC_LPTIMx_CLK_ENABLE(). - (++) In case of using interrupts (e.g. HAL_LPTIM_PWM_Start_IT()): - (+++) Configure the LPTIM interrupt priority using HAL_NVIC_SetPriority(). - (+++) Enable the LPTIM IRQ handler using HAL_NVIC_EnableIRQ(). - (+++) In LPTIM IRQ handler, call HAL_LPTIM_IRQHandler(). - - (#)Initialize the LPTIM HAL using HAL_LPTIM_Init(). This function - configures mainly: - (++) The instance: LPTIM1. - (++) Clock: the counter clock. - (+++) Source : it can be either the ULPTIM input (IN1) or one of - the internal clock; (APB, LSE or LSI). - (+++) Prescaler: select the clock divider. - (++) UltraLowPowerClock : To be used only if the ULPTIM is selected - as counter clock source. - (+++) Polarity: polarity of the active edge for the counter unit - if the ULPTIM input is selected. - (+++) SampleTime: clock sampling time to configure the clock glitch - filter. - (++) Trigger: How the counter start. - (+++) Source: trigger can be software or one of the hardware triggers. - (+++) ActiveEdge : only for hardware trigger. - (+++) SampleTime : trigger sampling time to configure the trigger - glitch filter. - (++) OutputPolarity : 2 opposite polarities are possible. - (++) UpdateMode: specifies whether the update of the autoreload and - the compare values is done immediately or after the end of current - period. - - (#)Six modes are available: - - (++) PWM Mode: To generate a PWM signal with specified period and pulse, - call HAL_LPTIM_PWM_Start() or HAL_LPTIM_PWM_Start_IT() for interruption - mode. - - (++) One Pulse Mode: To generate pulse with specified width in response - to a stimulus, call HAL_LPTIM_OnePulse_Start() or - HAL_LPTIM_OnePulse_Start_IT() for interruption mode. - - (++) Set once Mode: In this mode, the output changes the level (from - low level to high level if the output polarity is configured high, else - the opposite) when a compare match occurs. To start this mode, call - HAL_LPTIM_SetOnce_Start() or HAL_LPTIM_SetOnce_Start_IT() for - interruption mode. - - (++) Encoder Mode: To use the encoder interface call - HAL_LPTIM_Encoder_Start() or HAL_LPTIM_Encoder_Start_IT() for - interruption mode. Only available for LPTIM1 instance. - - (++) Time out Mode: an active edge on one selected trigger input rests - the counter. The first trigger event will start the timer, any - successive trigger event will reset the counter and the timer will - restart. To start this mode call HAL_LPTIM_TimeOut_Start_IT() or - HAL_LPTIM_TimeOut_Start_IT() for interruption mode. - - (++) Counter Mode: counter can be used to count external events on - the LPTIM Input1 or it can be used to count internal clock cycles. - To start this mode, call HAL_LPTIM_Counter_Start() or - HAL_LPTIM_Counter_Start_IT() for interruption mode. - - - (#) User can stop any process by calling the corresponding API: - HAL_LPTIM_Xxx_Stop() or HAL_LPTIM_Xxx_Stop_IT() if the process is - already started in interruption mode. - - (#) De-initialize the LPTIM peripheral using HAL_LPTIM_DeInit(). - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_LPTIM_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - [..] - Use Function HAL_LPTIM_RegisterCallback() to register a callback. - HAL_LPTIM_RegisterCallback() takes as parameters the HAL peripheral handle, - the Callback ID and a pointer to the user callback function. - [..] - Use function HAL_LPTIM_UnRegisterCallback() to reset a callback to the - default weak function. - HAL_LPTIM_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - [..] - These functions allow to register/unregister following callbacks: - - (+) MspInitCallback : LPTIM Base Msp Init Callback. - (+) MspDeInitCallback : LPTIM Base Msp DeInit Callback. - (+) CompareMatchCallback : Compare match Callback. - (+) AutoReloadMatchCallback : Auto-reload match Callback. - (+) TriggerCallback : External trigger event detection Callback. - (+) CompareWriteCallback : Compare register write complete Callback. - (+) AutoReloadWriteCallback : Auto-reload register write complete Callback. - (+) DirectionUpCallback : Up-counting direction change Callback. - (+) DirectionDownCallback : Down-counting direction change Callback. - - [..] - By default, after the Init and when the state is HAL_LPTIM_STATE_RESET - all interrupt callbacks are set to the corresponding weak functions: - examples HAL_LPTIM_TriggerCallback(), HAL_LPTIM_CompareMatchCallback(). - - [..] - Exception done for MspInit and MspDeInit functions that are reset to the legacy weak - functionalities in the Init/DeInit only when these callbacks are null - (not registered beforehand). If not, MspInit or MspDeInit are not null, the Init/DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - [..] - Callbacks can be registered/unregistered in HAL_LPTIM_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_LPTIM_STATE_READY or HAL_LPTIM_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_LPTIM_RegisterCallback() before calling DeInit or Init function. - - [..] - When The compilation define USE_HAL_LPTIM_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup LPTIM LPTIM - * @brief LPTIM HAL module driver. - * @{ - */ - -#ifdef HAL_LPTIM_MODULE_ENABLED - -#if defined (LPTIM1) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup LPTIM_Private_Constants - * @{ - */ -#define TIMEOUT 1000UL /* Timeout is 1s */ -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -static void LPTIM_ResetCallback(LPTIM_HandleTypeDef *lptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -static HAL_StatusTypeDef LPTIM_WaitForFlag(LPTIM_HandleTypeDef *hlptim, uint32_t flag); - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup LPTIM_Exported_Functions LPTIM Exported Functions - * @{ - */ - -/** @defgroup LPTIM_Exported_Functions_Group1 Initialization/de-initialization functions - * @brief Initialization and Configuration functions. - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Initialize the LPTIM according to the specified parameters in the - LPTIM_InitTypeDef and initialize the associated handle. - (+) DeInitialize the LPTIM peripheral. - (+) Initialize the LPTIM MSP. - (+) DeInitialize the LPTIM MSP. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the LPTIM according to the specified parameters in the - * LPTIM_InitTypeDef and initialize the associated handle. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Init(LPTIM_HandleTypeDef *hlptim) -{ - uint32_t tmpcfgr; - - /* Check the LPTIM handle allocation */ - if (hlptim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - assert_param(IS_LPTIM_CLOCK_SOURCE(hlptim->Init.Clock.Source)); - assert_param(IS_LPTIM_CLOCK_PRESCALER(hlptim->Init.Clock.Prescaler)); - if ((hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_ULPTIM) - || (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) - { - assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim->Init.UltraLowPowerClock.Polarity)); - assert_param(IS_LPTIM_CLOCK_SAMPLE_TIME(hlptim->Init.UltraLowPowerClock.SampleTime)); - } - assert_param(IS_LPTIM_TRG_SOURCE(hlptim->Init.Trigger.Source)); - if (hlptim->Init.Trigger.Source != LPTIM_TRIGSOURCE_SOFTWARE) - { - assert_param(IS_LPTIM_EXT_TRG_POLARITY(hlptim->Init.Trigger.ActiveEdge)); - assert_param(IS_LPTIM_TRIG_SAMPLE_TIME(hlptim->Init.Trigger.SampleTime)); - } - assert_param(IS_LPTIM_OUTPUT_POLARITY(hlptim->Init.OutputPolarity)); - assert_param(IS_LPTIM_UPDATE_MODE(hlptim->Init.UpdateMode)); - assert_param(IS_LPTIM_COUNTER_SOURCE(hlptim->Init.CounterSource)); - - if (hlptim->State == HAL_LPTIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hlptim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - LPTIM_ResetCallback(hlptim); - - if (hlptim->MspInitCallback == NULL) - { - hlptim->MspInitCallback = HAL_LPTIM_MspInit; - } - - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - hlptim->MspInitCallback(hlptim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - HAL_LPTIM_MspInit(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - } - - /* Change the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Get the LPTIMx CFGR value */ - tmpcfgr = hlptim->Instance->CFGR; - - if ((hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_ULPTIM) - || (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) - { - tmpcfgr &= (uint32_t)(~(LPTIM_CFGR_CKPOL | LPTIM_CFGR_CKFLT)); - } - if (hlptim->Init.Trigger.Source != LPTIM_TRIGSOURCE_SOFTWARE) - { - tmpcfgr &= (uint32_t)(~(LPTIM_CFGR_TRGFLT | LPTIM_CFGR_TRIGSEL)); - } - - /* Clear CKSEL, PRESC, TRIGEN, TRGFLT, WAVPOL, PRELOAD & COUNTMODE bits */ - tmpcfgr &= (uint32_t)(~(LPTIM_CFGR_CKSEL | LPTIM_CFGR_TRIGEN | LPTIM_CFGR_PRELOAD | - LPTIM_CFGR_WAVPOL | LPTIM_CFGR_PRESC | LPTIM_CFGR_COUNTMODE)); - - /* Set initialization parameters */ - tmpcfgr |= (hlptim->Init.Clock.Source | - hlptim->Init.Clock.Prescaler | - hlptim->Init.OutputPolarity | - hlptim->Init.UpdateMode | - hlptim->Init.CounterSource); - - /* Glitch filters for internal triggers and external inputs are configured - * only if an internal clock source is provided to the LPTIM - */ - if (hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC) - { - tmpcfgr |= (hlptim->Init.Trigger.SampleTime | - hlptim->Init.UltraLowPowerClock.SampleTime); - } - - /* Configure LPTIM external clock polarity and digital filter */ - if ((hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_ULPTIM) - || (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) - { - tmpcfgr |= (hlptim->Init.UltraLowPowerClock.Polarity | - hlptim->Init.UltraLowPowerClock.SampleTime); - } - - /* Configure LPTIM external trigger */ - if (hlptim->Init.Trigger.Source != LPTIM_TRIGSOURCE_SOFTWARE) - { - /* Enable External trigger and set the trigger source */ - tmpcfgr |= (hlptim->Init.Trigger.Source | - hlptim->Init.Trigger.ActiveEdge | - hlptim->Init.Trigger.SampleTime); - } - - /* Write to LPTIMx CFGR */ - hlptim->Instance->CFGR = tmpcfgr; - - /* Change the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief DeInitialize the LPTIM peripheral. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_DeInit(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the LPTIM handle allocation */ - if (hlptim == NULL) - { - return HAL_ERROR; - } - - /* Change the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the LPTIM Peripheral Clock */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - if (hlptim->MspDeInitCallback == NULL) - { - hlptim->MspDeInitCallback = HAL_LPTIM_MspDeInit; - } - - /* DeInit the low level hardware: CLOCK, NVIC.*/ - hlptim->MspDeInitCallback(hlptim); -#else - /* DeInit the low level hardware: CLOCK, NVIC.*/ - HAL_LPTIM_MspDeInit(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - - /* Change the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hlptim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Initialize the LPTIM MSP. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_MspInit(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize LPTIM MSP. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_MspDeInit(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup LPTIM_Exported_Functions_Group2 LPTIM Start-Stop operation functions - * @brief Start-Stop operation functions. - * -@verbatim - ============================================================================== - ##### LPTIM Start Stop operation functions ##### - ============================================================================== - [..] This section provides functions allowing to: - (+) Start the PWM mode. - (+) Stop the PWM mode. - (+) Start the One pulse mode. - (+) Stop the One pulse mode. - (+) Start the Set once mode. - (+) Stop the Set once mode. - (+) Start the Encoder mode. - (+) Stop the Encoder mode. - (+) Start the Timeout mode. - (+) Stop the Timeout mode. - (+) Start the Counter mode. - (+) Stop the Counter mode. - - -@endverbatim - * @{ - */ - -/** - * @brief Start the LPTIM PWM generation. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @param Pulse Specifies the compare value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_PWM_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(IS_LPTIM_PULSE(Pulse)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Reset WAVE bit to set PWM mode */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Load the pulse value in the compare register */ - __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Start timer in continuous mode */ - __HAL_LPTIM_START_CONTINUOUS(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the LPTIM PWM generation. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_PWM_Stop(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Change the LPTIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the LPTIM PWM generation in interrupt mode. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF - * @param Pulse Specifies the compare value. - * This parameter must be a value between 0x0000 and 0xFFFF - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_PWM_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(IS_LPTIM_PULSE(Pulse)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Reset WAVE bit to set PWM mode */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Load the pulse value in the compare register */ - __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Enable Autoreload write complete interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK); - - /* Enable Compare write complete interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK); - - /* Enable Autoreload match interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM); - - /* Enable Compare match interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM); - - /* If external trigger source is used, then enable external trigger interrupt */ - if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) - { - /* Enable external trigger interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG); - } - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Start timer in continuous mode */ - __HAL_LPTIM_START_CONTINUOUS(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the LPTIM PWM generation in interrupt mode. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_PWM_Stop_IT(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable Autoreload write complete interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK); - - /* Disable Compare write complete interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK); - - /* Disable Autoreload match interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM); - - /* Disable Compare match interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM); - - /* If external trigger source is used, then disable external trigger interrupt */ - if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) - { - /* Disable external trigger interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG); - } - - /* Change the LPTIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the LPTIM One pulse generation. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @param Pulse Specifies the compare value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(IS_LPTIM_PULSE(Pulse)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Reset WAVE bit to set one pulse mode */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Load the pulse value in the compare register */ - __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Start timer in single (one shot) mode */ - __HAL_LPTIM_START_SINGLE(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the LPTIM One pulse generation. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Change the LPTIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the LPTIM One pulse generation in interrupt mode. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @param Pulse Specifies the compare value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(IS_LPTIM_PULSE(Pulse)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Reset WAVE bit to set one pulse mode */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Load the pulse value in the compare register */ - __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Enable Autoreload write complete interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK); - - /* Enable Compare write complete interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK); - - /* Enable Autoreload match interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM); - - /* Enable Compare match interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM); - - /* If external trigger source is used, then enable external trigger interrupt */ - if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) - { - /* Enable external trigger interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG); - } - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Start timer in single (one shot) mode */ - __HAL_LPTIM_START_SINGLE(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the LPTIM One pulse generation in interrupt mode. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop_IT(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable Autoreload write complete interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK); - - /* Disable Compare write complete interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK); - - /* Disable Autoreload match interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM); - - /* Disable Compare match interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM); - - /* If external trigger source is used, then disable external trigger interrupt */ - if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) - { - /* Disable external trigger interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG); - } - - /* Change the LPTIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the LPTIM in Set once mode. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @param Pulse Specifies the compare value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(IS_LPTIM_PULSE(Pulse)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Set WAVE bit to enable the set once mode */ - hlptim->Instance->CFGR |= LPTIM_CFGR_WAVE; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Load the pulse value in the compare register */ - __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Start timer in single (one shot) mode */ - __HAL_LPTIM_START_SINGLE(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the LPTIM Set once mode. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Change the LPTIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the LPTIM Set once mode in interrupt mode. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @param Pulse Specifies the compare value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(IS_LPTIM_PULSE(Pulse)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Set WAVE bit to enable the set once mode */ - hlptim->Instance->CFGR |= LPTIM_CFGR_WAVE; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Load the pulse value in the compare register */ - __HAL_LPTIM_COMPARE_SET(hlptim, Pulse); - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Enable Autoreload write complete interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK); - - /* Enable Compare write complete interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK); - - /* Enable Autoreload match interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM); - - /* Enable Compare match interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM); - - /* If external trigger source is used, then enable external trigger interrupt */ - if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) - { - /* Enable external trigger interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG); - } - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Start timer in single (one shot) mode */ - __HAL_LPTIM_START_SINGLE(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the LPTIM Set once mode in interrupt mode. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop_IT(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable Autoreload write complete interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK); - - /* Disable Compare write complete interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK); - - /* Disable Autoreload match interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM); - - /* Disable Compare match interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM); - - /* If external trigger source is used, then disable external trigger interrupt */ - if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE) - { - /* Disable external trigger interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG); - } - - /* Change the LPTIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the Encoder interface. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Encoder_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period) -{ - uint32_t tmpcfgr; - - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC); - assert_param(hlptim->Init.Clock.Prescaler == LPTIM_PRESCALER_DIV1); - assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim->Init.UltraLowPowerClock.Polarity)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Get the LPTIMx CFGR value */ - tmpcfgr = hlptim->Instance->CFGR; - - /* Clear CKPOL bits */ - tmpcfgr &= (uint32_t)(~LPTIM_CFGR_CKPOL); - - /* Set Input polarity */ - tmpcfgr |= hlptim->Init.UltraLowPowerClock.Polarity; - - /* Write to LPTIMx CFGR */ - hlptim->Instance->CFGR = tmpcfgr; - - /* Set ENC bit to enable the encoder interface */ - hlptim->Instance->CFGR |= LPTIM_CFGR_ENC; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Start timer in continuous mode */ - __HAL_LPTIM_START_CONTINUOUS(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the Encoder interface. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Reset ENC bit to disable the encoder interface */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_ENC; - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the Encoder interface in interrupt mode. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Encoder_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period) -{ - uint32_t tmpcfgr; - - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC); - assert_param(hlptim->Init.Clock.Prescaler == LPTIM_PRESCALER_DIV1); - assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim->Init.UltraLowPowerClock.Polarity)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Configure edge sensitivity for encoder mode */ - /* Get the LPTIMx CFGR value */ - tmpcfgr = hlptim->Instance->CFGR; - - /* Clear CKPOL bits */ - tmpcfgr &= (uint32_t)(~LPTIM_CFGR_CKPOL); - - /* Set Input polarity */ - tmpcfgr |= hlptim->Init.UltraLowPowerClock.Polarity; - - /* Write to LPTIMx CFGR */ - hlptim->Instance->CFGR = tmpcfgr; - - /* Set ENC bit to enable the encoder interface */ - hlptim->Instance->CFGR |= LPTIM_CFGR_ENC; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Enable "switch to down direction" interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_DOWN); - - /* Enable "switch to up direction" interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_UP); - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Start timer in continuous mode */ - __HAL_LPTIM_START_CONTINUOUS(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the Encoder interface in interrupt mode. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop_IT(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Reset ENC bit to disable the encoder interface */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_ENC; - - /* Disable "switch to down direction" interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_DOWN); - - /* Disable "switch to up direction" interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_UP); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the Timeout function. - * @note The first trigger event will start the timer, any successive - * trigger event will reset the counter and the timer restarts. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @param Timeout Specifies the TimeOut value to reset the counter. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(IS_LPTIM_PULSE(Timeout)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Set TIMOUT bit to enable the timeout function */ - hlptim->Instance->CFGR |= LPTIM_CFGR_TIMOUT; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Load the Timeout value in the compare register */ - __HAL_LPTIM_COMPARE_SET(hlptim, Timeout); - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Start timer in continuous mode */ - __HAL_LPTIM_START_CONTINUOUS(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the Timeout function. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Reset TIMOUT bit to enable the timeout function */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_TIMOUT; - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the Timeout function in interrupt mode. - * @note The first trigger event will start the timer, any successive - * trigger event will reset the counter and the timer restarts. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @param Timeout Specifies the TimeOut value to reset the counter. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - assert_param(IS_LPTIM_PULSE(Timeout)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Enable EXTI Line interrupt on the LPTIM Wake-up Timer */ - __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT(); -#if defined(EXTI_IMR_MR23) - /* Enable rising edge trigger on the LPTIM Wake-up Timer Exti line */ - __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE(); -#endif /* EXTI_IMR_MR23 */ - - /* Set TIMOUT bit to enable the timeout function */ - hlptim->Instance->CFGR |= LPTIM_CFGR_TIMOUT; - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Load the Timeout value in the compare register */ - __HAL_LPTIM_COMPARE_SET(hlptim, Timeout); - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Enable Compare match interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM); - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Start timer in continuous mode */ - __HAL_LPTIM_START_CONTINUOUS(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the Timeout function in interrupt mode. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop_IT(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; -#if defined(EXTI_IMR_MR23) - /* Disable rising edge trigger on the LPTIM Wake-up Timer Exti line */ - __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE(); -#endif /* EXTI_IMR_MR23 */ - - /* Disable EXTI Line interrupt on the LPTIM Wake-up Timer */ - __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT(); - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Reset TIMOUT bit to enable the timeout function */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_TIMOUT; - - /* Disable Compare match interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the Counter mode. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Counter_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* If clock source is not ULPTIM clock and counter source is external, then it must not be prescaled */ - if ((hlptim->Init.Clock.Source != LPTIM_CLOCKSOURCE_ULPTIM) - && (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) - { - /* Check if clock is prescaled */ - assert_param(IS_LPTIM_CLOCK_PRESCALERDIV1(hlptim->Init.Clock.Prescaler)); - /* Set clock prescaler to 0 */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_PRESC; - } - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Start timer in continuous mode */ - __HAL_LPTIM_START_CONTINUOUS(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the Counter mode. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Counter_Stop(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Start the Counter mode in interrupt mode. - * @param hlptim LPTIM handle - * @param Period Specifies the Autoreload value. - * This parameter must be a value between 0x0000 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Counter_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - assert_param(IS_LPTIM_PERIOD(Period)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; - - /* Enable EXTI Line interrupt on the LPTIM Wake-up Timer */ - __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT(); -#if defined(EXTI_IMR_MR23) - /* Enable rising edge trigger on the LPTIM Wake-up Timer Exti line */ - __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE(); -#endif /* EXTI_IMR_MR23 */ - - /* If clock source is not ULPTIM clock and counter source is external, then it must not be prescaled */ - if ((hlptim->Init.Clock.Source != LPTIM_CLOCKSOURCE_ULPTIM) - && (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL)) - { - /* Check if clock is prescaled */ - assert_param(IS_LPTIM_CLOCK_PRESCALERDIV1(hlptim->Init.Clock.Prescaler)); - /* Set clock prescaler to 0 */ - hlptim->Instance->CFGR &= ~LPTIM_CFGR_PRESC; - } - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Clear flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Load the period value in the autoreload register */ - __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period); - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Enable Autoreload write complete interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK); - - /* Enable Autoreload match interrupt */ - __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM); - - /* Enable the Peripheral */ - __HAL_LPTIM_ENABLE(hlptim); - - /* Start timer in continuous mode */ - __HAL_LPTIM_START_CONTINUOUS(hlptim); - - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stop the Counter mode in interrupt mode. - * @param hlptim LPTIM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LPTIM_Counter_Stop_IT(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - /* Set the LPTIM state */ - hlptim->State = HAL_LPTIM_STATE_BUSY; -#if defined(EXTI_IMR_MR23) - /* Disable rising edge trigger on the LPTIM Wake-up Timer Exti line */ - __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE(); -#endif /* EXTI_IMR_MR23 */ - - /* Disable EXTI Line interrupt on the LPTIM Wake-up Timer */ - __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT(); - - /* Disable the Peripheral */ - __HAL_LPTIM_DISABLE(hlptim); - - if (HAL_LPTIM_GetState(hlptim) == HAL_LPTIM_STATE_TIMEOUT) - { - return HAL_TIMEOUT; - } - - /* Disable Autoreload write complete interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK); - - /* Disable Autoreload match interrupt */ - __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM); - /* Change the TIM state*/ - hlptim->State = HAL_LPTIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup LPTIM_Exported_Functions_Group3 LPTIM Read operation functions - * @brief Read operation functions. - * -@verbatim - ============================================================================== - ##### LPTIM Read operation functions ##### - ============================================================================== -[..] This section provides LPTIM Reading functions. - (+) Read the counter value. - (+) Read the period (Auto-reload) value. - (+) Read the pulse (Compare)value. -@endverbatim - * @{ - */ - -/** - * @brief Return the current counter value. - * @param hlptim LPTIM handle - * @retval Counter value. - */ -uint32_t HAL_LPTIM_ReadCounter(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - return (hlptim->Instance->CNT); -} - -/** - * @brief Return the current Autoreload (Period) value. - * @param hlptim LPTIM handle - * @retval Autoreload value. - */ -uint32_t HAL_LPTIM_ReadAutoReload(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - return (hlptim->Instance->ARR); -} - -/** - * @brief Return the current Compare (Pulse) value. - * @param hlptim LPTIM handle - * @retval Compare value. - */ -uint32_t HAL_LPTIM_ReadCompare(LPTIM_HandleTypeDef *hlptim) -{ - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(hlptim->Instance)); - - return (hlptim->Instance->CMP); -} - -/** - * @} - */ - -/** @defgroup LPTIM_Exported_Functions_Group4 LPTIM IRQ handler and callbacks - * @brief LPTIM IRQ handler. - * -@verbatim - ============================================================================== - ##### LPTIM IRQ handler and callbacks ##### - ============================================================================== -[..] This section provides LPTIM IRQ handler and callback functions called within - the IRQ handler: - (+) LPTIM interrupt request handler - (+) Compare match Callback - (+) Auto-reload match Callback - (+) External trigger event detection Callback - (+) Compare register write complete Callback - (+) Auto-reload register write complete Callback - (+) Up-counting direction change Callback - (+) Down-counting direction change Callback - -@endverbatim - * @{ - */ - -/** - * @brief Handle LPTIM interrupt request. - * @param hlptim LPTIM handle - * @retval None - */ -void HAL_LPTIM_IRQHandler(LPTIM_HandleTypeDef *hlptim) -{ - /* Compare match interrupt */ - if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_CMPM) != RESET) - { - if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_CMPM) != RESET) - { - /* Clear Compare match flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPM); - - /* Compare match Callback */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - hlptim->CompareMatchCallback(hlptim); -#else - HAL_LPTIM_CompareMatchCallback(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - } - } - - /* Autoreload match interrupt */ - if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_ARRM) != RESET) - { - if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_ARRM) != RESET) - { - /* Clear Autoreload match flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARRM); - - /* Autoreload match Callback */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - hlptim->AutoReloadMatchCallback(hlptim); -#else - HAL_LPTIM_AutoReloadMatchCallback(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - } - } - - /* Trigger detected interrupt */ - if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_EXTTRIG) != RESET) - { - if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_EXTTRIG) != RESET) - { - /* Clear Trigger detected flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_EXTTRIG); - - /* Trigger detected callback */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - hlptim->TriggerCallback(hlptim); -#else - HAL_LPTIM_TriggerCallback(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - } - } - - /* Compare write interrupt */ - if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_CMPOK) != RESET) - { - if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_CMPOK) != RESET) - { - /* Clear Compare write flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - - /* Compare write Callback */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - hlptim->CompareWriteCallback(hlptim); -#else - HAL_LPTIM_CompareWriteCallback(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - } - } - - /* Autoreload write interrupt */ - if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_ARROK) != RESET) - { - if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_ARROK) != RESET) - { - /* Clear Autoreload write flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - - /* Autoreload write Callback */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - hlptim->AutoReloadWriteCallback(hlptim); -#else - HAL_LPTIM_AutoReloadWriteCallback(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - } - } - - /* Direction counter changed from Down to Up interrupt */ - if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_UP) != RESET) - { - if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_UP) != RESET) - { - /* Clear Direction counter changed from Down to Up flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_UP); - - /* Direction counter changed from Down to Up Callback */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - hlptim->DirectionUpCallback(hlptim); -#else - HAL_LPTIM_DirectionUpCallback(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - } - } - - /* Direction counter changed from Up to Down interrupt */ - if (__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_DOWN) != RESET) - { - if (__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_DOWN) != RESET) - { - /* Clear Direction counter changed from Up to Down flag */ - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_DOWN); - - /* Direction counter changed from Up to Down Callback */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - hlptim->DirectionDownCallback(hlptim); -#else - HAL_LPTIM_DirectionDownCallback(hlptim); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - } - } -#if defined(EXTI_IMR_MR23) - __HAL_LPTIM_WAKEUPTIMER_EXTI_CLEAR_FLAG(); -#endif /* EXTI_IMR_MR23 */ -} - -/** - * @brief Compare match callback in non-blocking mode. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_CompareMatchCallback(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_CompareMatchCallback could be implemented in the user file - */ -} - -/** - * @brief Autoreload match callback in non-blocking mode. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_AutoReloadMatchCallback could be implemented in the user file - */ -} - -/** - * @brief Trigger detected callback in non-blocking mode. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_TriggerCallback(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_TriggerCallback could be implemented in the user file - */ -} - -/** - * @brief Compare write callback in non-blocking mode. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_CompareWriteCallback(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_CompareWriteCallback could be implemented in the user file - */ -} - -/** - * @brief Autoreload write callback in non-blocking mode. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_AutoReloadWriteCallback(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_AutoReloadWriteCallback could be implemented in the user file - */ -} - -/** - * @brief Direction counter changed from Down to Up callback in non-blocking mode. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_DirectionUpCallback(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_DirectionUpCallback could be implemented in the user file - */ -} - -/** - * @brief Direction counter changed from Up to Down callback in non-blocking mode. - * @param hlptim LPTIM handle - * @retval None - */ -__weak void HAL_LPTIM_DirectionDownCallback(LPTIM_HandleTypeDef *hlptim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hlptim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LPTIM_DirectionDownCallback could be implemented in the user file - */ -} - -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User LPTIM callback to be used instead of the weak predefined callback - * @param hlptim LPTIM handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_LPTIM_MSPINIT_CB_ID LPTIM Base Msp Init Callback ID - * @arg @ref HAL_LPTIM_MSPDEINIT_CB_ID LPTIM Base Msp DeInit Callback ID - * @arg @ref HAL_LPTIM_COMPARE_MATCH_CB_ID Compare match Callback ID - * @arg @ref HAL_LPTIM_AUTORELOAD_MATCH_CB_ID Auto-reload match Callback ID - * @arg @ref HAL_LPTIM_TRIGGER_CB_ID External trigger event detection Callback ID - * @arg @ref HAL_LPTIM_COMPARE_WRITE_CB_ID Compare register write complete Callback ID - * @arg @ref HAL_LPTIM_AUTORELOAD_WRITE_CB_ID Auto-reload register write complete Callback ID - * @arg @ref HAL_LPTIM_DIRECTION_UP_CB_ID Up-counting direction change Callback ID - * @arg @ref HAL_LPTIM_DIRECTION_DOWN_CB_ID Down-counting direction change Callback ID - * @param pCallback pointer to the callback function - * @retval status - */ -HAL_StatusTypeDef HAL_LPTIM_RegisterCallback(LPTIM_HandleTypeDef *hlptim, - HAL_LPTIM_CallbackIDTypeDef CallbackID, - pLPTIM_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hlptim); - - if (hlptim->State == HAL_LPTIM_STATE_READY) - { - switch (CallbackID) - { - case HAL_LPTIM_MSPINIT_CB_ID : - hlptim->MspInitCallback = pCallback; - break; - - case HAL_LPTIM_MSPDEINIT_CB_ID : - hlptim->MspDeInitCallback = pCallback; - break; - - case HAL_LPTIM_COMPARE_MATCH_CB_ID : - hlptim->CompareMatchCallback = pCallback; - break; - - case HAL_LPTIM_AUTORELOAD_MATCH_CB_ID : - hlptim->AutoReloadMatchCallback = pCallback; - break; - - case HAL_LPTIM_TRIGGER_CB_ID : - hlptim->TriggerCallback = pCallback; - break; - - case HAL_LPTIM_COMPARE_WRITE_CB_ID : - hlptim->CompareWriteCallback = pCallback; - break; - - case HAL_LPTIM_AUTORELOAD_WRITE_CB_ID : - hlptim->AutoReloadWriteCallback = pCallback; - break; - - case HAL_LPTIM_DIRECTION_UP_CB_ID : - hlptim->DirectionUpCallback = pCallback; - break; - - case HAL_LPTIM_DIRECTION_DOWN_CB_ID : - hlptim->DirectionDownCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hlptim->State == HAL_LPTIM_STATE_RESET) - { - switch (CallbackID) - { - case HAL_LPTIM_MSPINIT_CB_ID : - hlptim->MspInitCallback = pCallback; - break; - - case HAL_LPTIM_MSPDEINIT_CB_ID : - hlptim->MspDeInitCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hlptim); - - return status; -} - -/** - * @brief Unregister a LPTIM callback - * LLPTIM callback is redirected to the weak predefined callback - * @param hlptim LPTIM handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_LPTIM_MSPINIT_CB_ID LPTIM Base Msp Init Callback ID - * @arg @ref HAL_LPTIM_MSPDEINIT_CB_ID LPTIM Base Msp DeInit Callback ID - * @arg @ref HAL_LPTIM_COMPARE_MATCH_CB_ID Compare match Callback ID - * @arg @ref HAL_LPTIM_AUTORELOAD_MATCH_CB_ID Auto-reload match Callback ID - * @arg @ref HAL_LPTIM_TRIGGER_CB_ID External trigger event detection Callback ID - * @arg @ref HAL_LPTIM_COMPARE_WRITE_CB_ID Compare register write complete Callback ID - * @arg @ref HAL_LPTIM_AUTORELOAD_WRITE_CB_ID Auto-reload register write complete Callback ID - * @arg @ref HAL_LPTIM_DIRECTION_UP_CB_ID Up-counting direction change Callback ID - * @arg @ref HAL_LPTIM_DIRECTION_DOWN_CB_ID Down-counting direction change Callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_LPTIM_UnRegisterCallback(LPTIM_HandleTypeDef *hlptim, - HAL_LPTIM_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hlptim); - - if (hlptim->State == HAL_LPTIM_STATE_READY) - { - switch (CallbackID) - { - case HAL_LPTIM_MSPINIT_CB_ID : - /* Legacy weak MspInit Callback */ - hlptim->MspInitCallback = HAL_LPTIM_MspInit; - break; - - case HAL_LPTIM_MSPDEINIT_CB_ID : - /* Legacy weak Msp DeInit Callback */ - hlptim->MspDeInitCallback = HAL_LPTIM_MspDeInit; - break; - - case HAL_LPTIM_COMPARE_MATCH_CB_ID : - /* Legacy weak Compare match Callback */ - hlptim->CompareMatchCallback = HAL_LPTIM_CompareMatchCallback; - break; - - case HAL_LPTIM_AUTORELOAD_MATCH_CB_ID : - /* Legacy weak Auto-reload match Callback */ - hlptim->AutoReloadMatchCallback = HAL_LPTIM_AutoReloadMatchCallback; - break; - - case HAL_LPTIM_TRIGGER_CB_ID : - /* Legacy weak External trigger event detection Callback */ - hlptim->TriggerCallback = HAL_LPTIM_TriggerCallback; - break; - - case HAL_LPTIM_COMPARE_WRITE_CB_ID : - /* Legacy weak Compare register write complete Callback */ - hlptim->CompareWriteCallback = HAL_LPTIM_CompareWriteCallback; - break; - - case HAL_LPTIM_AUTORELOAD_WRITE_CB_ID : - /* Legacy weak Auto-reload register write complete Callback */ - hlptim->AutoReloadWriteCallback = HAL_LPTIM_AutoReloadWriteCallback; - break; - - case HAL_LPTIM_DIRECTION_UP_CB_ID : - /* Legacy weak Up-counting direction change Callback */ - hlptim->DirectionUpCallback = HAL_LPTIM_DirectionUpCallback; - break; - - case HAL_LPTIM_DIRECTION_DOWN_CB_ID : - /* Legacy weak Down-counting direction change Callback */ - hlptim->DirectionDownCallback = HAL_LPTIM_DirectionDownCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hlptim->State == HAL_LPTIM_STATE_RESET) - { - switch (CallbackID) - { - case HAL_LPTIM_MSPINIT_CB_ID : - /* Legacy weak MspInit Callback */ - hlptim->MspInitCallback = HAL_LPTIM_MspInit; - break; - - case HAL_LPTIM_MSPDEINIT_CB_ID : - /* Legacy weak Msp DeInit Callback */ - hlptim->MspDeInitCallback = HAL_LPTIM_MspDeInit; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hlptim); - - return status; -} -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup LPTIM_Group5 Peripheral State functions - * @brief Peripheral State functions. - * -@verbatim - ============================================================================== - ##### Peripheral State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Return the LPTIM handle state. - * @param hlptim LPTIM handle - * @retval HAL state - */ -HAL_LPTIM_StateTypeDef HAL_LPTIM_GetState(LPTIM_HandleTypeDef *hlptim) -{ - /* Return LPTIM handle state */ - return hlptim->State; -} - -/** - * @} - */ - - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup LPTIM_Private_Functions LPTIM Private Functions - * @{ - */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -/** - * @brief Reset interrupt callbacks to the legacy weak callbacks. - * @param lptim pointer to a LPTIM_HandleTypeDef structure that contains - * the configuration information for LPTIM module. - * @retval None - */ -static void LPTIM_ResetCallback(LPTIM_HandleTypeDef *lptim) -{ - /* Reset the LPTIM callback to the legacy weak callbacks */ - lptim->CompareMatchCallback = HAL_LPTIM_CompareMatchCallback; - lptim->AutoReloadMatchCallback = HAL_LPTIM_AutoReloadMatchCallback; - lptim->TriggerCallback = HAL_LPTIM_TriggerCallback; - lptim->CompareWriteCallback = HAL_LPTIM_CompareWriteCallback; - lptim->AutoReloadWriteCallback = HAL_LPTIM_AutoReloadWriteCallback; - lptim->DirectionUpCallback = HAL_LPTIM_DirectionUpCallback; - lptim->DirectionDownCallback = HAL_LPTIM_DirectionDownCallback; -} -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - -/** - * @brief LPTimer Wait for flag set - * @param hlptim pointer to a LPTIM_HandleTypeDef structure that contains - * the configuration information for LPTIM module. - * @param flag The lptim flag - * @retval HAL status - */ -static HAL_StatusTypeDef LPTIM_WaitForFlag(LPTIM_HandleTypeDef *hlptim, uint32_t flag) -{ - HAL_StatusTypeDef result = HAL_OK; - uint32_t count = TIMEOUT * (SystemCoreClock / 20UL / 1000UL); - do - { - count--; - if (count == 0UL) - { - result = HAL_TIMEOUT; - } - } while ((!(__HAL_LPTIM_GET_FLAG((hlptim), (flag)))) && (count != 0UL)); - - return result; -} - -/** - * @brief Disable LPTIM HW instance. - * @param hlptim pointer to a LPTIM_HandleTypeDef structure that contains - * the configuration information for LPTIM module. - * @note The following sequence is required to solve LPTIM disable HW limitation. - * Please check Errata Sheet ES0335 for more details under "MCU may remain - * stuck in LPTIM interrupt when entering Stop mode" section. - * @retval None - */ -void LPTIM_Disable(LPTIM_HandleTypeDef *hlptim) -{ - uint32_t tmpclksource = 0; - uint32_t tmpIER; - uint32_t tmpCFGR; - uint32_t tmpCMP; - uint32_t tmpARR; - uint32_t tmpOR; - - __disable_irq(); - - /*********** Save LPTIM Config ***********/ - /* Save LPTIM source clock */ - switch ((uint32_t)hlptim->Instance) - { - case LPTIM1_BASE: - tmpclksource = __HAL_RCC_GET_LPTIM1_SOURCE(); - break; - default: - break; - } - - /* Save LPTIM configuration registers */ - tmpIER = hlptim->Instance->IER; - tmpCFGR = hlptim->Instance->CFGR; - tmpCMP = hlptim->Instance->CMP; - tmpARR = hlptim->Instance->ARR; - tmpOR = hlptim->Instance->OR; - - /*********** Reset LPTIM ***********/ - switch ((uint32_t)hlptim->Instance) - { - case LPTIM1_BASE: - __HAL_RCC_LPTIM1_FORCE_RESET(); - __HAL_RCC_LPTIM1_RELEASE_RESET(); - break; - default: - break; - } - - /*********** Restore LPTIM Config ***********/ - if ((tmpCMP != 0UL) || (tmpARR != 0UL)) - { - /* Force LPTIM source kernel clock from APB */ - switch ((uint32_t)hlptim->Instance) - { - case LPTIM1_BASE: - __HAL_RCC_LPTIM1_CONFIG(RCC_LPTIM1CLKSOURCE_PCLK1); - break; - default: - break; - } - - if (tmpCMP != 0UL) - { - /* Restore CMP register (LPTIM should be enabled first) */ - hlptim->Instance->CR |= LPTIM_CR_ENABLE; - hlptim->Instance->CMP = tmpCMP; - - /* Wait for the completion of the write operation to the LPTIM_CMP register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_CMPOK) == HAL_TIMEOUT) - { - hlptim->State = HAL_LPTIM_STATE_TIMEOUT; - } - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK); - } - - if (tmpARR != 0UL) - { - /* Restore ARR register (LPTIM should be enabled first) */ - hlptim->Instance->CR |= LPTIM_CR_ENABLE; - hlptim->Instance->ARR = tmpARR; - - /* Wait for the completion of the write operation to the LPTIM_ARR register */ - if (LPTIM_WaitForFlag(hlptim, LPTIM_FLAG_ARROK) == HAL_TIMEOUT) - { - hlptim->State = HAL_LPTIM_STATE_TIMEOUT; - } - - __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK); - } - - /* Restore LPTIM source kernel clock */ - switch ((uint32_t)hlptim->Instance) - { - case LPTIM1_BASE: - __HAL_RCC_LPTIM1_CONFIG(tmpclksource); - break; - default: - break; - } - } - - /* Restore configuration registers (LPTIM should be disabled first) */ - hlptim->Instance->CR &= ~(LPTIM_CR_ENABLE); - hlptim->Instance->IER = tmpIER; - hlptim->Instance->CFGR = tmpCFGR; - hlptim->Instance->OR = tmpOR; - - __enable_irq(); -} -/** - * @} - */ -#endif /* LPTIM1 */ - -#endif /* HAL_LPTIM_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc.c deleted file mode 100644 index 7e4413067fb8932..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc.c +++ /dev/null @@ -1,2163 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_ltdc.c - * @author MCD Application Team - * @brief LTDC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the LTDC peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Errors functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LTDC HAL driver can be used as follows: - - (#) Declare a LTDC_HandleTypeDef handle structure, for example: LTDC_HandleTypeDef hltdc; - - (#) Initialize the LTDC low level resources by implementing the HAL_LTDC_MspInit() API: - (##) Enable the LTDC interface clock - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the LTDC interrupt priority - (+++) Enable the NVIC LTDC IRQ Channel - - (#) Initialize the required configuration through the following parameters: - the LTDC timing, the horizontal and vertical polarity, the pixel clock polarity, - Data Enable polarity and the LTDC background color value using HAL_LTDC_Init() function - - *** Configuration *** - ========================= - [..] - (#) Program the required configuration through the following parameters: - the pixel format, the blending factors, input alpha value, the window size - and the image size using HAL_LTDC_ConfigLayer() function for foreground - or/and background layer. - - (#) Optionally, configure and enable the CLUT using HAL_LTDC_ConfigCLUT() and - HAL_LTDC_EnableCLUT functions. - - (#) Optionally, enable the Dither using HAL_LTDC_EnableDither(). - - (#) Optionally, configure and enable the Color keying using HAL_LTDC_ConfigColorKeying() - and HAL_LTDC_EnableColorKeying functions. - - (#) Optionally, configure LineInterrupt using HAL_LTDC_ProgramLineEvent() - function - - (#) If needed, reconfigure and change the pixel format value, the alpha value - value, the window size, the window position and the layer start address - for foreground or/and background layer using respectively the following - functions: HAL_LTDC_SetPixelFormat(), HAL_LTDC_SetAlpha(), HAL_LTDC_SetWindowSize(), - HAL_LTDC_SetWindowPosition() and HAL_LTDC_SetAddress(). - - (#) Variant functions with _NoReload suffix allows to set the LTDC configuration/settings without immediate reload. - This is useful in case when the program requires to modify serval LTDC settings (on one or both layers) - then applying(reload) these settings in one shot by calling the function HAL_LTDC_Reload(). - - After calling the _NoReload functions to set different color/format/layer settings, - the program shall call the function HAL_LTDC_Reload() to apply(reload) these settings. - Function HAL_LTDC_Reload() can be called with the parameter ReloadType set to LTDC_RELOAD_IMMEDIATE if - an immediate reload is required. - Function HAL_LTDC_Reload() can be called with the parameter ReloadType set to LTDC_RELOAD_VERTICAL_BLANKING if - the reload should be done in the next vertical blanking period, - this option allows to avoid display flicker by applying the new settings during the vertical blanking period. - - - (#) To control LTDC state you can use the following function: HAL_LTDC_GetState() - - *** LTDC HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in LTDC HAL driver. - - (+) __HAL_LTDC_ENABLE: Enable the LTDC. - (+) __HAL_LTDC_DISABLE: Disable the LTDC. - (+) __HAL_LTDC_LAYER_ENABLE: Enable an LTDC Layer. - (+) __HAL_LTDC_LAYER_DISABLE: Disable an LTDC Layer. - (+) __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG: Reload Layer Configuration. - (+) __HAL_LTDC_GET_FLAG: Get the LTDC pending flags. - (+) __HAL_LTDC_CLEAR_FLAG: Clear the LTDC pending flags. - (+) __HAL_LTDC_ENABLE_IT: Enable the specified LTDC interrupts. - (+) __HAL_LTDC_DISABLE_IT: Disable the specified LTDC interrupts. - (+) __HAL_LTDC_GET_IT_SOURCE: Check whether the specified LTDC interrupt has occurred or not. - - [..] - (@) You can refer to the LTDC HAL driver header file for more useful macros - - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_LTDC_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use function HAL_LTDC_RegisterCallback() to register a callback. - - [..] - Function HAL_LTDC_RegisterCallback() allows to register following callbacks: - (+) LineEventCallback : LTDC Line Event Callback. - (+) ReloadEventCallback : LTDC Reload Event Callback. - (+) ErrorCallback : LTDC Error Callback - (+) MspInitCallback : LTDC MspInit. - (+) MspDeInitCallback : LTDC MspDeInit. - [..] - This function takes as parameters the HAL peripheral handle, the callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_LTDC_UnRegisterCallback() to reset a callback to the default - weak function. - HAL_LTDC_UnRegisterCallback() takes as parameters the HAL peripheral handle - and the callback ID. - [..] - This function allows to reset following callbacks: - (+) LineEventCallback : LTDC Line Event Callback - (+) ReloadEventCallback : LTDC Reload Event Callback - (+) ErrorCallback : LTDC Error Callback - (+) MspInitCallback : LTDC MspInit - (+) MspDeInitCallback : LTDC MspDeInit. - - [..] - By default, after the HAL_LTDC_Init and when the state is HAL_LTDC_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_LTDC_LineEventCallback(), HAL_LTDC_ErrorCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak (surcharged) functions in the HAL_LTDC_Init() and HAL_LTDC_DeInit() - only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_LTDC_Init() and HAL_LTDC_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in HAL_LTDC_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_LTDC_STATE_READY or HAL_LTDC_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_LTDC_RegisterCallback() before calling HAL_LTDC_DeInit() - or HAL_LTDC_Init() function. - - [..] - When the compilation define USE_HAL_LTDC_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_LTDC_MODULE_ENABLED - -#if defined (LTDC) - -/** @defgroup LTDC LTDC - * @brief LTDC HAL module driver - * @{ - */ - - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -static void LTDC_SetConfig(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx); -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup LTDC_Exported_Functions LTDC Exported Functions - * @{ - */ - -/** @defgroup LTDC_Exported_Functions_Group1 Initialization and Configuration functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the LTDC - (+) De-initialize the LTDC - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the LTDC according to the specified parameters in the LTDC_InitTypeDef. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_Init(LTDC_HandleTypeDef *hltdc) -{ - uint32_t tmp, tmp1; - - /* Check the LTDC peripheral state */ - if (hltdc == NULL) - { - return HAL_ERROR; - } - - /* Check function parameters */ - assert_param(IS_LTDC_ALL_INSTANCE(hltdc->Instance)); - assert_param(IS_LTDC_HSYNC(hltdc->Init.HorizontalSync)); - assert_param(IS_LTDC_VSYNC(hltdc->Init.VerticalSync)); - assert_param(IS_LTDC_AHBP(hltdc->Init.AccumulatedHBP)); - assert_param(IS_LTDC_AVBP(hltdc->Init.AccumulatedVBP)); - assert_param(IS_LTDC_AAH(hltdc->Init.AccumulatedActiveH)); - assert_param(IS_LTDC_AAW(hltdc->Init.AccumulatedActiveW)); - assert_param(IS_LTDC_TOTALH(hltdc->Init.TotalHeigh)); - assert_param(IS_LTDC_TOTALW(hltdc->Init.TotalWidth)); - assert_param(IS_LTDC_HSPOL(hltdc->Init.HSPolarity)); - assert_param(IS_LTDC_VSPOL(hltdc->Init.VSPolarity)); - assert_param(IS_LTDC_DEPOL(hltdc->Init.DEPolarity)); - assert_param(IS_LTDC_PCPOL(hltdc->Init.PCPolarity)); - -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) - if (hltdc->State == HAL_LTDC_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hltdc->Lock = HAL_UNLOCKED; - - /* Reset the LTDC callback to the legacy weak callbacks */ - hltdc->LineEventCallback = HAL_LTDC_LineEventCallback; /* Legacy weak LineEventCallback */ - hltdc->ReloadEventCallback = HAL_LTDC_ReloadEventCallback; /* Legacy weak ReloadEventCallback */ - hltdc->ErrorCallback = HAL_LTDC_ErrorCallback; /* Legacy weak ErrorCallback */ - - if (hltdc->MspInitCallback == NULL) - { - hltdc->MspInitCallback = HAL_LTDC_MspInit; - } - /* Init the low level hardware */ - hltdc->MspInitCallback(hltdc); - } -#else - if (hltdc->State == HAL_LTDC_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hltdc->Lock = HAL_UNLOCKED; - /* Init the low level hardware */ - HAL_LTDC_MspInit(hltdc); - } -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Configure the HS, VS, DE and PC polarity */ - hltdc->Instance->GCR &= ~(LTDC_GCR_HSPOL | LTDC_GCR_VSPOL | LTDC_GCR_DEPOL | LTDC_GCR_PCPOL); - hltdc->Instance->GCR |= (uint32_t)(hltdc->Init.HSPolarity | hltdc->Init.VSPolarity | \ - hltdc->Init.DEPolarity | hltdc->Init.PCPolarity); - - /* Set Synchronization size */ - hltdc->Instance->SSCR &= ~(LTDC_SSCR_VSH | LTDC_SSCR_HSW); - tmp = (hltdc->Init.HorizontalSync << 16U); - hltdc->Instance->SSCR |= (tmp | hltdc->Init.VerticalSync); - - /* Set Accumulated Back porch */ - hltdc->Instance->BPCR &= ~(LTDC_BPCR_AVBP | LTDC_BPCR_AHBP); - tmp = (hltdc->Init.AccumulatedHBP << 16U); - hltdc->Instance->BPCR |= (tmp | hltdc->Init.AccumulatedVBP); - - /* Set Accumulated Active Width */ - hltdc->Instance->AWCR &= ~(LTDC_AWCR_AAH | LTDC_AWCR_AAW); - tmp = (hltdc->Init.AccumulatedActiveW << 16U); - hltdc->Instance->AWCR |= (tmp | hltdc->Init.AccumulatedActiveH); - - /* Set Total Width */ - hltdc->Instance->TWCR &= ~(LTDC_TWCR_TOTALH | LTDC_TWCR_TOTALW); - tmp = (hltdc->Init.TotalWidth << 16U); - hltdc->Instance->TWCR |= (tmp | hltdc->Init.TotalHeigh); - - /* Set the background color value */ - tmp = ((uint32_t)(hltdc->Init.Backcolor.Green) << 8U); - tmp1 = ((uint32_t)(hltdc->Init.Backcolor.Red) << 16U); - hltdc->Instance->BCCR &= ~(LTDC_BCCR_BCBLUE | LTDC_BCCR_BCGREEN | LTDC_BCCR_BCRED); - hltdc->Instance->BCCR |= (tmp1 | tmp | hltdc->Init.Backcolor.Blue); - - /* Enable the Transfer Error and FIFO underrun interrupts */ - __HAL_LTDC_ENABLE_IT(hltdc, LTDC_IT_TE | LTDC_IT_FU); - - /* Enable LTDC by setting LTDCEN bit */ - __HAL_LTDC_ENABLE(hltdc); - - /* Initialize the error code */ - hltdc->ErrorCode = HAL_LTDC_ERROR_NONE; - - /* Initialize the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - return HAL_OK; -} - -/** - * @brief De-initialize the LTDC peripheral. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval None - */ - -HAL_StatusTypeDef HAL_LTDC_DeInit(LTDC_HandleTypeDef *hltdc) -{ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) - if (hltdc->MspDeInitCallback == NULL) - { - hltdc->MspDeInitCallback = HAL_LTDC_MspDeInit; - } - /* DeInit the low level hardware */ - hltdc->MspDeInitCallback(hltdc); -#else - /* DeInit the low level hardware */ - HAL_LTDC_MspDeInit(hltdc); -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - - /* Initialize the error code */ - hltdc->ErrorCode = HAL_LTDC_ERROR_NONE; - - /* Initialize the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Initialize the LTDC MSP. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval None - */ -__weak void HAL_LTDC_MspInit(LTDC_HandleTypeDef *hltdc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hltdc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LTDC_MspInit could be implemented in the user file - */ -} - -/** - * @brief De-initialize the LTDC MSP. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval None - */ -__weak void HAL_LTDC_MspDeInit(LTDC_HandleTypeDef *hltdc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hltdc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LTDC_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User LTDC Callback - * To be used instead of the weak predefined callback - * @param hltdc ltdc handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_LTDC_LINE_EVENT_CB_ID Line Event Callback ID - * @arg @ref HAL_LTDC_RELOAD_EVENT_CB_ID Reload Event Callback ID - * @arg @ref HAL_LTDC_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_LTDC_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_LTDC_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_LTDC_RegisterCallback(LTDC_HandleTypeDef *hltdc, HAL_LTDC_CallbackIDTypeDef CallbackID, pLTDC_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hltdc); - - if (hltdc->State == HAL_LTDC_STATE_READY) - { - switch (CallbackID) - { - case HAL_LTDC_LINE_EVENT_CB_ID : - hltdc->LineEventCallback = pCallback; - break; - - case HAL_LTDC_RELOAD_EVENT_CB_ID : - hltdc->ReloadEventCallback = pCallback; - break; - - case HAL_LTDC_ERROR_CB_ID : - hltdc->ErrorCallback = pCallback; - break; - - case HAL_LTDC_MSPINIT_CB_ID : - hltdc->MspInitCallback = pCallback; - break; - - case HAL_LTDC_MSPDEINIT_CB_ID : - hltdc->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hltdc->State == HAL_LTDC_STATE_RESET) - { - switch (CallbackID) - { - case HAL_LTDC_MSPINIT_CB_ID : - hltdc->MspInitCallback = pCallback; - break; - - case HAL_LTDC_MSPDEINIT_CB_ID : - hltdc->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hltdc); - - return status; -} - -/** - * @brief Unregister an LTDC Callback - * LTDC callabck is redirected to the weak predefined callback - * @param hltdc ltdc handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_LTDC_LINE_EVENT_CB_ID Line Event Callback ID - * @arg @ref HAL_LTDC_RELOAD_EVENT_CB_ID Reload Event Callback ID - * @arg @ref HAL_LTDC_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_LTDC_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_LTDC_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_LTDC_UnRegisterCallback(LTDC_HandleTypeDef *hltdc, HAL_LTDC_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hltdc); - - if (hltdc->State == HAL_LTDC_STATE_READY) - { - switch (CallbackID) - { - case HAL_LTDC_LINE_EVENT_CB_ID : - hltdc->LineEventCallback = HAL_LTDC_LineEventCallback; /* Legacy weak LineEventCallback */ - break; - - case HAL_LTDC_RELOAD_EVENT_CB_ID : - hltdc->ReloadEventCallback = HAL_LTDC_ReloadEventCallback; /* Legacy weak ReloadEventCallback */ - break; - - case HAL_LTDC_ERROR_CB_ID : - hltdc->ErrorCallback = HAL_LTDC_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_LTDC_MSPINIT_CB_ID : - hltdc->MspInitCallback = HAL_LTDC_MspInit; /* Legcay weak MspInit Callback */ - break; - - case HAL_LTDC_MSPDEINIT_CB_ID : - hltdc->MspDeInitCallback = HAL_LTDC_MspDeInit; /* Legcay weak MspDeInit Callback */ - break; - - default : - /* Update the error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hltdc->State == HAL_LTDC_STATE_RESET) - { - switch (CallbackID) - { - case HAL_LTDC_MSPINIT_CB_ID : - hltdc->MspInitCallback = HAL_LTDC_MspInit; /* Legcay weak MspInit Callback */ - break; - - case HAL_LTDC_MSPDEINIT_CB_ID : - hltdc->MspDeInitCallback = HAL_LTDC_MspDeInit; /* Legcay weak MspDeInit Callback */ - break; - - default : - /* Update the error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hltdc); - - return status; -} -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup LTDC_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] This section provides function allowing to: - (+) Handle LTDC interrupt request - -@endverbatim - * @{ - */ -/** - * @brief Handle LTDC interrupt request. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval HAL status - */ -void HAL_LTDC_IRQHandler(LTDC_HandleTypeDef *hltdc) -{ - uint32_t isrflags = READ_REG(hltdc->Instance->ISR); - uint32_t itsources = READ_REG(hltdc->Instance->IER); - - /* Transfer Error Interrupt management ***************************************/ - if (((isrflags & LTDC_ISR_TERRIF) != 0U) && ((itsources & LTDC_IER_TERRIE) != 0U)) - { - /* Disable the transfer Error interrupt */ - __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_TE); - - /* Clear the transfer error flag */ - __HAL_LTDC_CLEAR_FLAG(hltdc, LTDC_FLAG_TE); - - /* Update error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_TE; - - /* Change LTDC state */ - hltdc->State = HAL_LTDC_STATE_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - /* Transfer error Callback */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hltdc->ErrorCallback(hltdc); -#else - /* Call legacy error callback*/ - HAL_LTDC_ErrorCallback(hltdc); -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - } - - /* FIFO underrun Interrupt management ***************************************/ - if (((isrflags & LTDC_ISR_FUIF) != 0U) && ((itsources & LTDC_IER_FUIE) != 0U)) - { - /* Disable the FIFO underrun interrupt */ - __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_FU); - - /* Clear the FIFO underrun flag */ - __HAL_LTDC_CLEAR_FLAG(hltdc, LTDC_FLAG_FU); - - /* Update error code */ - hltdc->ErrorCode |= HAL_LTDC_ERROR_FU; - - /* Change LTDC state */ - hltdc->State = HAL_LTDC_STATE_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - /* Transfer error Callback */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - hltdc->ErrorCallback(hltdc); -#else - /* Call legacy error callback*/ - HAL_LTDC_ErrorCallback(hltdc); -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - } - - /* Line Interrupt management ************************************************/ - if (((isrflags & LTDC_ISR_LIF) != 0U) && ((itsources & LTDC_IER_LIE) != 0U)) - { - /* Disable the Line interrupt */ - __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_LI); - - /* Clear the Line interrupt flag */ - __HAL_LTDC_CLEAR_FLAG(hltdc, LTDC_FLAG_LI); - - /* Change LTDC state */ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - /* Line interrupt Callback */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) - /*Call registered Line Event callback */ - hltdc->LineEventCallback(hltdc); -#else - /*Call Legacy Line Event callback */ - HAL_LTDC_LineEventCallback(hltdc); -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - } - - /* Register reload Interrupt management ***************************************/ - if (((isrflags & LTDC_ISR_RRIF) != 0U) && ((itsources & LTDC_IER_RRIE) != 0U)) - { - /* Disable the register reload interrupt */ - __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_RR); - - /* Clear the register reload flag */ - __HAL_LTDC_CLEAR_FLAG(hltdc, LTDC_FLAG_RR); - - /* Change LTDC state */ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - /* Reload interrupt Callback */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) - /*Call registered reload Event callback */ - hltdc->ReloadEventCallback(hltdc); -#else - /*Call Legacy Reload Event callback */ - HAL_LTDC_ReloadEventCallback(hltdc); -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Error LTDC callback. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval None - */ -__weak void HAL_LTDC_ErrorCallback(LTDC_HandleTypeDef *hltdc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hltdc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LTDC_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief Line Event callback. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval None - */ -__weak void HAL_LTDC_LineEventCallback(LTDC_HandleTypeDef *hltdc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hltdc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LTDC_LineEventCallback could be implemented in the user file - */ -} - -/** - * @brief Reload Event callback. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval None - */ -__weak void HAL_LTDC_ReloadEventCallback(LTDC_HandleTypeDef *hltdc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hltdc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_LTDC_ReloadEvenCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup LTDC_Exported_Functions_Group3 Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Configure the LTDC foreground or/and background parameters. - (+) Set the active layer. - (+) Configure the color keying. - (+) Configure the C-LUT. - (+) Enable / Disable the color keying. - (+) Enable / Disable the C-LUT. - (+) Update the layer position. - (+) Update the layer size. - (+) Update pixel format on the fly. - (+) Update transparency on the fly. - (+) Update address on the fly. - -@endverbatim - * @{ - */ - -/** - * @brief Configure the LTDC Layer according to the specified - * parameters in the LTDC_InitTypeDef and create the associated handle. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param pLayerCfg pointer to a LTDC_LayerCfgTypeDef structure that contains - * the configuration information for the Layer. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_ConfigLayer(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - assert_param(IS_LTDC_HCONFIGST(pLayerCfg->WindowX0)); - assert_param(IS_LTDC_HCONFIGSP(pLayerCfg->WindowX1)); - assert_param(IS_LTDC_VCONFIGST(pLayerCfg->WindowY0)); - assert_param(IS_LTDC_VCONFIGSP(pLayerCfg->WindowY1)); - assert_param(IS_LTDC_PIXEL_FORMAT(pLayerCfg->PixelFormat)); - assert_param(IS_LTDC_ALPHA(pLayerCfg->Alpha)); - assert_param(IS_LTDC_ALPHA(pLayerCfg->Alpha0)); - assert_param(IS_LTDC_BLENDING_FACTOR1(pLayerCfg->BlendingFactor1)); - assert_param(IS_LTDC_BLENDING_FACTOR2(pLayerCfg->BlendingFactor2)); - assert_param(IS_LTDC_CFBLL(pLayerCfg->ImageWidth)); - assert_param(IS_LTDC_CFBLNBR(pLayerCfg->ImageHeight)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Copy new layer configuration into handle structure */ - hltdc->LayerCfg[LayerIdx] = *pLayerCfg; - - /* Configure the LTDC Layer */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Initialize the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Configure the color keying. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param RGBValue the color key value - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_ConfigColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t RGBValue, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Configure the default color values */ - LTDC_LAYER(hltdc, LayerIdx)->CKCR &= ~(LTDC_LxCKCR_CKBLUE | LTDC_LxCKCR_CKGREEN | LTDC_LxCKCR_CKRED); - LTDC_LAYER(hltdc, LayerIdx)->CKCR = RGBValue; - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Load the color lookup table. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param pCLUT pointer to the color lookup table address. - * @param CLUTSize the color lookup table size. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_ConfigCLUT(LTDC_HandleTypeDef *hltdc, uint32_t *pCLUT, uint32_t CLUTSize, uint32_t LayerIdx) -{ - uint32_t tmp; - uint32_t counter; - uint32_t *pcolorlut = pCLUT; - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - for (counter = 0U; (counter < CLUTSize); counter++) - { - if (hltdc->LayerCfg[LayerIdx].PixelFormat == LTDC_PIXEL_FORMAT_AL44) - { - tmp = (((counter + (16U*counter)) << 24U) | ((uint32_t)(*pcolorlut) & 0xFFU) | ((uint32_t)(*pcolorlut) & 0xFF00U) | ((uint32_t)(*pcolorlut) & 0xFF0000U)); - } - else - { - tmp = ((counter << 24U) | ((uint32_t)(*pcolorlut) & 0xFFU) | ((uint32_t)(*pcolorlut) & 0xFF00U) | ((uint32_t)(*pcolorlut) & 0xFF0000U)); - } - - pcolorlut++; - - /* Specifies the C-LUT address and RGB value */ - LTDC_LAYER(hltdc, LayerIdx)->CLUTWR = tmp; - } - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Enable the color keying. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_EnableColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Enable LTDC color keying by setting COLKEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_COLKEN; - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Disable the color keying. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_DisableColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Disable LTDC color keying by setting COLKEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR &= ~(uint32_t)LTDC_LxCR_COLKEN; - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Enable the color lookup table. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_EnableCLUT(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Enable LTDC color lookup table by setting CLUTEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_CLUTEN; - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Disable the color lookup table. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_DisableCLUT(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Disable LTDC color lookup table by setting CLUTEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR &= ~(uint32_t)LTDC_LxCR_CLUTEN; - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Enable Dither. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval HAL status - */ - -HAL_StatusTypeDef HAL_LTDC_EnableDither(LTDC_HandleTypeDef *hltdc) -{ - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Enable Dither by setting DTEN bit */ - LTDC->GCR |= (uint32_t)LTDC_GCR_DEN; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Disable Dither. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval HAL status - */ - -HAL_StatusTypeDef HAL_LTDC_DisableDither(LTDC_HandleTypeDef *hltdc) -{ - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Disable Dither by setting DTEN bit */ - LTDC->GCR &= ~(uint32_t)LTDC_GCR_DEN; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Set the LTDC window size. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param XSize LTDC Pixel per line - * @param YSize LTDC Line number - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetWindowSize(LTDC_HandleTypeDef *hltdc, uint32_t XSize, uint32_t YSize, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters (Layers parameters)*/ - assert_param(IS_LTDC_LAYER(LayerIdx)); - assert_param(IS_LTDC_CFBLL(XSize)); - assert_param(IS_LTDC_CFBLNBR(YSize)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* update horizontal stop */ - pLayerCfg->WindowX1 = XSize + pLayerCfg->WindowX0; - - /* update vertical stop */ - pLayerCfg->WindowY1 = YSize + pLayerCfg->WindowY0; - - /* Reconfigures the color frame buffer pitch in byte */ - pLayerCfg->ImageWidth = XSize; - - /* Reconfigures the frame buffer line number */ - pLayerCfg->ImageHeight = YSize; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Set the LTDC window position. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param X0 LTDC window X offset - * @param Y0 LTDC window Y offset - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetWindowPosition(LTDC_HandleTypeDef *hltdc, uint32_t X0, uint32_t Y0, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - assert_param(IS_LTDC_CFBLL(X0)); - assert_param(IS_LTDC_CFBLNBR(Y0)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* update horizontal start/stop */ - pLayerCfg->WindowX0 = X0; - pLayerCfg->WindowX1 = X0 + pLayerCfg->ImageWidth; - - /* update vertical start/stop */ - pLayerCfg->WindowY0 = Y0; - pLayerCfg->WindowY1 = Y0 + pLayerCfg->ImageHeight; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Reconfigure the pixel format. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param Pixelformat new pixel format value. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetPixelFormat(LTDC_HandleTypeDef *hltdc, uint32_t Pixelformat, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters */ - assert_param(IS_LTDC_PIXEL_FORMAT(Pixelformat)); - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* Reconfigure the pixel format */ - pLayerCfg->PixelFormat = Pixelformat; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Reconfigure the layer alpha value. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param Alpha new alpha value. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetAlpha(LTDC_HandleTypeDef *hltdc, uint32_t Alpha, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters */ - assert_param(IS_LTDC_ALPHA(Alpha)); - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* Reconfigure the Alpha value */ - pLayerCfg->Alpha = Alpha; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} -/** - * @brief Reconfigure the frame buffer Address. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param Address new address value. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetAddress(LTDC_HandleTypeDef *hltdc, uint32_t Address, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* Reconfigure the Address */ - pLayerCfg->FBStartAdress = Address; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Set the Immediate Reload type */ - hltdc->Instance->SRCR = LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Function used to reconfigure the pitch for specific cases where the attached LayerIdx buffer have a width that is - * larger than the one intended to be displayed on screen. Example of a buffer 800x480 attached to layer for which we - * want to read and display on screen only a portion 320x240 taken in the center of the buffer. The pitch in pixels - * will be in that case 800 pixels and not 320 pixels as initially configured by previous call to HAL_LTDC_ConfigLayer(). - * @note This function should be called only after a previous call to HAL_LTDC_ConfigLayer() to modify the default pitch - * configured by HAL_LTDC_ConfigLayer() when required (refer to example described just above). - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LinePitchInPixels New line pitch in pixels to configure for LTDC layer 'LayerIdx'. - * @param LayerIdx LTDC layer index concerned by the modification of line pitch. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetPitch(LTDC_HandleTypeDef *hltdc, uint32_t LinePitchInPixels, uint32_t LayerIdx) -{ - uint32_t tmp; - uint32_t pitchUpdate; - uint32_t pixelFormat; - - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* get LayerIdx used pixel format */ - pixelFormat = hltdc->LayerCfg[LayerIdx].PixelFormat; - - if (pixelFormat == LTDC_PIXEL_FORMAT_ARGB8888) - { - tmp = 4U; - } - else if (pixelFormat == LTDC_PIXEL_FORMAT_RGB888) - { - tmp = 3U; - } - else if ((pixelFormat == LTDC_PIXEL_FORMAT_ARGB4444) || \ - (pixelFormat == LTDC_PIXEL_FORMAT_RGB565) || \ - (pixelFormat == LTDC_PIXEL_FORMAT_ARGB1555) || \ - (pixelFormat == LTDC_PIXEL_FORMAT_AL88)) - { - tmp = 2U; - } - else - { - tmp = 1U; - } - - pitchUpdate = ((LinePitchInPixels * tmp) << 16U); - - /* Clear previously set standard pitch */ - LTDC_LAYER(hltdc, LayerIdx)->CFBLR &= ~LTDC_LxCFBLR_CFBP; - - /* Set the Reload type as immediate update of LTDC pitch configured above */ - LTDC->SRCR |= LTDC_SRCR_IMR; - - /* Set new line pitch value */ - LTDC_LAYER(hltdc, LayerIdx)->CFBLR |= pitchUpdate; - - /* Set the Reload type as immediate update of LTDC pitch configured above */ - LTDC->SRCR |= LTDC_SRCR_IMR; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Define the position of the line interrupt. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param Line Line Interrupt Position. - * @note User application may resort to HAL_LTDC_LineEventCallback() at line interrupt generation. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_ProgramLineEvent(LTDC_HandleTypeDef *hltdc, uint32_t Line) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LIPOS(Line)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Disable the Line interrupt */ - __HAL_LTDC_DISABLE_IT(hltdc, LTDC_IT_LI); - - /* Set the Line Interrupt position */ - LTDC->LIPCR = (uint32_t)Line; - - /* Enable the Line interrupt */ - __HAL_LTDC_ENABLE_IT(hltdc, LTDC_IT_LI); - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Reload LTDC Layers configuration. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param ReloadType This parameter can be one of the following values : - * LTDC_RELOAD_IMMEDIATE : Immediate Reload - * LTDC_RELOAD_VERTICAL_BLANKING : Reload in the next Vertical Blanking - * @note User application may resort to HAL_LTDC_ReloadEventCallback() at reload interrupt generation. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_Reload(LTDC_HandleTypeDef *hltdc, uint32_t ReloadType) -{ - /* Check the parameters */ - assert_param(IS_LTDC_RELOAD(ReloadType)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Enable the Reload interrupt */ - __HAL_LTDC_ENABLE_IT(hltdc, LTDC_IT_RR); - - /* Apply Reload type */ - hltdc->Instance->SRCR = ReloadType; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Configure the LTDC Layer according to the specified without reloading - * parameters in the LTDC_InitTypeDef and create the associated handle. - * Variant of the function HAL_LTDC_ConfigLayer without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param pLayerCfg pointer to a LTDC_LayerCfgTypeDef structure that contains - * the configuration information for the Layer. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_ConfigLayer_NoReload(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - assert_param(IS_LTDC_HCONFIGST(pLayerCfg->WindowX0)); - assert_param(IS_LTDC_HCONFIGSP(pLayerCfg->WindowX1)); - assert_param(IS_LTDC_VCONFIGST(pLayerCfg->WindowY0)); - assert_param(IS_LTDC_VCONFIGSP(pLayerCfg->WindowY1)); - assert_param(IS_LTDC_PIXEL_FORMAT(pLayerCfg->PixelFormat)); - assert_param(IS_LTDC_ALPHA(pLayerCfg->Alpha)); - assert_param(IS_LTDC_ALPHA(pLayerCfg->Alpha0)); - assert_param(IS_LTDC_BLENDING_FACTOR1(pLayerCfg->BlendingFactor1)); - assert_param(IS_LTDC_BLENDING_FACTOR2(pLayerCfg->BlendingFactor2)); - assert_param(IS_LTDC_CFBLL(pLayerCfg->ImageWidth)); - assert_param(IS_LTDC_CFBLNBR(pLayerCfg->ImageHeight)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Copy new layer configuration into handle structure */ - hltdc->LayerCfg[LayerIdx] = *pLayerCfg; - - /* Configure the LTDC Layer */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Initialize the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Set the LTDC window size without reloading. - * Variant of the function HAL_LTDC_SetWindowSize without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param XSize LTDC Pixel per line - * @param YSize LTDC Line number - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetWindowSize_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t XSize, uint32_t YSize, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters (Layers parameters)*/ - assert_param(IS_LTDC_LAYER(LayerIdx)); - assert_param(IS_LTDC_CFBLL(XSize)); - assert_param(IS_LTDC_CFBLNBR(YSize)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* update horizontal stop */ - pLayerCfg->WindowX1 = XSize + pLayerCfg->WindowX0; - - /* update vertical stop */ - pLayerCfg->WindowY1 = YSize + pLayerCfg->WindowY0; - - /* Reconfigures the color frame buffer pitch in byte */ - pLayerCfg->ImageWidth = XSize; - - /* Reconfigures the frame buffer line number */ - pLayerCfg->ImageHeight = YSize; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Set the LTDC window position without reloading. - * Variant of the function HAL_LTDC_SetWindowPosition without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param X0 LTDC window X offset - * @param Y0 LTDC window Y offset - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetWindowPosition_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t X0, uint32_t Y0, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - assert_param(IS_LTDC_CFBLL(X0)); - assert_param(IS_LTDC_CFBLNBR(Y0)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* update horizontal start/stop */ - pLayerCfg->WindowX0 = X0; - pLayerCfg->WindowX1 = X0 + pLayerCfg->ImageWidth; - - /* update vertical start/stop */ - pLayerCfg->WindowY0 = Y0; - pLayerCfg->WindowY1 = Y0 + pLayerCfg->ImageHeight; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Reconfigure the pixel format without reloading. - * Variant of the function HAL_LTDC_SetPixelFormat without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDfef structure that contains - * the configuration information for the LTDC. - * @param Pixelformat new pixel format value. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetPixelFormat_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Pixelformat, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters */ - assert_param(IS_LTDC_PIXEL_FORMAT(Pixelformat)); - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* Reconfigure the pixel format */ - pLayerCfg->PixelFormat = Pixelformat; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Reconfigure the layer alpha value without reloading. - * Variant of the function HAL_LTDC_SetAlpha without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param Alpha new alpha value. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetAlpha_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Alpha, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters */ - assert_param(IS_LTDC_ALPHA(Alpha)); - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* Reconfigure the Alpha value */ - pLayerCfg->Alpha = Alpha; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Reconfigure the frame buffer Address without reloading. - * Variant of the function HAL_LTDC_SetAddress without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param Address new address value. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetAddress_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Address, uint32_t LayerIdx) -{ - LTDC_LayerCfgTypeDef *pLayerCfg; - - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Get layer configuration from handle structure */ - pLayerCfg = &hltdc->LayerCfg[LayerIdx]; - - /* Reconfigure the Address */ - pLayerCfg->FBStartAdress = Address; - - /* Set LTDC parameters */ - LTDC_SetConfig(hltdc, pLayerCfg, LayerIdx); - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Function used to reconfigure the pitch for specific cases where the attached LayerIdx buffer have a width that is - * larger than the one intended to be displayed on screen. Example of a buffer 800x480 attached to layer for which we - * want to read and display on screen only a portion 320x240 taken in the center of the buffer. The pitch in pixels - * will be in that case 800 pixels and not 320 pixels as initially configured by previous call to HAL_LTDC_ConfigLayer(). - * @note This function should be called only after a previous call to HAL_LTDC_ConfigLayer() to modify the default pitch - * configured by HAL_LTDC_ConfigLayer() when required (refer to example described just above). - * Variant of the function HAL_LTDC_SetPitch without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LinePitchInPixels New line pitch in pixels to configure for LTDC layer 'LayerIdx'. - * @param LayerIdx LTDC layer index concerned by the modification of line pitch. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_SetPitch_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LinePitchInPixels, uint32_t LayerIdx) -{ - uint32_t tmp; - uint32_t pitchUpdate; - uint32_t pixelFormat; - - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* get LayerIdx used pixel format */ - pixelFormat = hltdc->LayerCfg[LayerIdx].PixelFormat; - - if (pixelFormat == LTDC_PIXEL_FORMAT_ARGB8888) - { - tmp = 4U; - } - else if (pixelFormat == LTDC_PIXEL_FORMAT_RGB888) - { - tmp = 3U; - } - else if ((pixelFormat == LTDC_PIXEL_FORMAT_ARGB4444) || \ - (pixelFormat == LTDC_PIXEL_FORMAT_RGB565) || \ - (pixelFormat == LTDC_PIXEL_FORMAT_ARGB1555) || \ - (pixelFormat == LTDC_PIXEL_FORMAT_AL88)) - { - tmp = 2U; - } - else - { - tmp = 1U; - } - - pitchUpdate = ((LinePitchInPixels * tmp) << 16U); - - /* Clear previously set standard pitch */ - LTDC_LAYER(hltdc, LayerIdx)->CFBLR &= ~LTDC_LxCFBLR_CFBP; - - /* Set new line pitch value */ - LTDC_LAYER(hltdc, LayerIdx)->CFBLR |= pitchUpdate; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - - -/** - * @brief Configure the color keying without reloading. - * Variant of the function HAL_LTDC_ConfigColorKeying without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param RGBValue the color key value - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_ConfigColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t RGBValue, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Configure the default color values */ - LTDC_LAYER(hltdc, LayerIdx)->CKCR &= ~(LTDC_LxCKCR_CKBLUE | LTDC_LxCKCR_CKGREEN | LTDC_LxCKCR_CKRED); - LTDC_LAYER(hltdc, LayerIdx)->CKCR = RGBValue; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Enable the color keying without reloading. - * Variant of the function HAL_LTDC_EnableColorKeying without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_EnableColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Enable LTDC color keying by setting COLKEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_COLKEN; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Disable the color keying without reloading. - * Variant of the function HAL_LTDC_DisableColorKeying without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_DisableColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Disable LTDC color keying by setting COLKEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR &= ~(uint32_t)LTDC_LxCR_COLKEN; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Enable the color lookup table without reloading. - * Variant of the function HAL_LTDC_EnableCLUT without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_EnableCLUT_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Disable LTDC color lookup table by setting CLUTEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_CLUTEN; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @brief Disable the color lookup table without reloading. - * Variant of the function HAL_LTDC_DisableCLUT without immediate reload. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: - * LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDC_DisableCLUT_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LTDC_LAYER(LayerIdx)); - - /* Process locked */ - __HAL_LOCK(hltdc); - - /* Change LTDC peripheral state */ - hltdc->State = HAL_LTDC_STATE_BUSY; - - /* Disable LTDC color lookup table by setting CLUTEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR &= ~(uint32_t)LTDC_LxCR_CLUTEN; - - /* Change the LTDC state*/ - hltdc->State = HAL_LTDC_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hltdc); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup LTDC_Exported_Functions_Group4 Peripheral State and Errors functions - * @brief Peripheral State and Errors functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Check the LTDC handle state. - (+) Get the LTDC handle error code. - -@endverbatim - * @{ - */ - -/** - * @brief Return the LTDC handle state. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval HAL state - */ -HAL_LTDC_StateTypeDef HAL_LTDC_GetState(LTDC_HandleTypeDef *hltdc) -{ - return hltdc->State; -} - -/** - * @brief Return the LTDC handle error code. - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @retval LTDC Error Code - */ -uint32_t HAL_LTDC_GetError(LTDC_HandleTypeDef *hltdc) -{ - return hltdc->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup LTDC_Private_Functions LTDC Private Functions - * @{ - */ - -/** - * @brief Configure the LTDC peripheral - * @param hltdc Pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param pLayerCfg Pointer LTDC Layer Configuration structure - * @param LayerIdx LTDC Layer index. - * This parameter can be one of the following values: LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1) - * @retval None - */ -static void LTDC_SetConfig(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx) -{ - uint32_t tmp; - uint32_t tmp1; - uint32_t tmp2; - - /* Configure the horizontal start and stop position */ - tmp = ((pLayerCfg->WindowX1 + ((hltdc->Instance->BPCR & LTDC_BPCR_AHBP) >> 16U)) << 16U); - LTDC_LAYER(hltdc, LayerIdx)->WHPCR &= ~(LTDC_LxWHPCR_WHSTPOS | LTDC_LxWHPCR_WHSPPOS); - LTDC_LAYER(hltdc, LayerIdx)->WHPCR = ((pLayerCfg->WindowX0 + ((hltdc->Instance->BPCR & LTDC_BPCR_AHBP) >> 16U) + 1U) | tmp); - - /* Configure the vertical start and stop position */ - tmp = ((pLayerCfg->WindowY1 + (hltdc->Instance->BPCR & LTDC_BPCR_AVBP)) << 16U); - LTDC_LAYER(hltdc, LayerIdx)->WVPCR &= ~(LTDC_LxWVPCR_WVSTPOS | LTDC_LxWVPCR_WVSPPOS); - LTDC_LAYER(hltdc, LayerIdx)->WVPCR = ((pLayerCfg->WindowY0 + (hltdc->Instance->BPCR & LTDC_BPCR_AVBP) + 1U) | tmp); - - /* Specifies the pixel format */ - LTDC_LAYER(hltdc, LayerIdx)->PFCR &= ~(LTDC_LxPFCR_PF); - LTDC_LAYER(hltdc, LayerIdx)->PFCR = (pLayerCfg->PixelFormat); - - /* Configure the default color values */ - tmp = ((uint32_t)(pLayerCfg->Backcolor.Green) << 8U); - tmp1 = ((uint32_t)(pLayerCfg->Backcolor.Red) << 16U); - tmp2 = (pLayerCfg->Alpha0 << 24U); - LTDC_LAYER(hltdc, LayerIdx)->DCCR &= ~(LTDC_LxDCCR_DCBLUE | LTDC_LxDCCR_DCGREEN | LTDC_LxDCCR_DCRED | LTDC_LxDCCR_DCALPHA); - LTDC_LAYER(hltdc, LayerIdx)->DCCR = (pLayerCfg->Backcolor.Blue | tmp | tmp1 | tmp2); - - /* Specifies the constant alpha value */ - LTDC_LAYER(hltdc, LayerIdx)->CACR &= ~(LTDC_LxCACR_CONSTA); - LTDC_LAYER(hltdc, LayerIdx)->CACR = (pLayerCfg->Alpha); - - /* Specifies the blending factors */ - LTDC_LAYER(hltdc, LayerIdx)->BFCR &= ~(LTDC_LxBFCR_BF2 | LTDC_LxBFCR_BF1); - LTDC_LAYER(hltdc, LayerIdx)->BFCR = (pLayerCfg->BlendingFactor1 | pLayerCfg->BlendingFactor2); - - /* Configure the color frame buffer start address */ - LTDC_LAYER(hltdc, LayerIdx)->CFBAR &= ~(LTDC_LxCFBAR_CFBADD); - LTDC_LAYER(hltdc, LayerIdx)->CFBAR = (pLayerCfg->FBStartAdress); - - if (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_ARGB8888) - { - tmp = 4U; - } - else if (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_RGB888) - { - tmp = 3U; - } - else if ((pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_ARGB4444) || \ - (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_RGB565) || \ - (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_ARGB1555) || \ - (pLayerCfg->PixelFormat == LTDC_PIXEL_FORMAT_AL88)) - { - tmp = 2U; - } - else - { - tmp = 1U; - } - - /* Configure the color frame buffer pitch in byte */ - LTDC_LAYER(hltdc, LayerIdx)->CFBLR &= ~(LTDC_LxCFBLR_CFBLL | LTDC_LxCFBLR_CFBP); - LTDC_LAYER(hltdc, LayerIdx)->CFBLR = (((pLayerCfg->ImageWidth * tmp) << 16U) | (((pLayerCfg->WindowX1 - pLayerCfg->WindowX0) * tmp) + 3U)); - /* Configure the frame buffer line number */ - LTDC_LAYER(hltdc, LayerIdx)->CFBLNR &= ~(LTDC_LxCFBLNR_CFBLNBR); - LTDC_LAYER(hltdc, LayerIdx)->CFBLNR = (pLayerCfg->ImageHeight); - - /* Enable LTDC_Layer by setting LEN bit */ - LTDC_LAYER(hltdc, LayerIdx)->CR |= (uint32_t)LTDC_LxCR_LEN; -} - -/** - * @} - */ - - -/** - * @} - */ - -#endif /* LTDC */ - -#endif /* HAL_LTDC_MODULE_ENABLED */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc_ex.c deleted file mode 100644 index 8c39194a665afbb..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_ltdc_ex.c +++ /dev/null @@ -1,149 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_ltdc_ex.c - * @author MCD Application Team - * @brief LTDC Extension HAL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined(HAL_LTDC_MODULE_ENABLED) && defined(HAL_DSI_MODULE_ENABLED) - -#if defined (LTDC) && defined (DSI) - -/** @defgroup LTDCEx LTDCEx - * @brief LTDC HAL module driver - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup LTDCEx_Exported_Functions LTDC Extended Exported Functions - * @{ - */ - -/** @defgroup LTDCEx_Exported_Functions_Group1 Initialization and Configuration functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize and configure the LTDC - -@endverbatim - * @{ - */ - -/** - * @brief Retrieve common parameters from DSI Video mode configuration structure - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param VidCfg pointer to a DSI_VidCfgTypeDef structure that contains - * the DSI video mode configuration parameters - * @note The implementation of this function is taking into account the LTDC - * polarities inversion as described in the current LTDC specification - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDCEx_StructInitFromVideoConfig(LTDC_HandleTypeDef *hltdc, DSI_VidCfgTypeDef *VidCfg) -{ - /* Retrieve signal polarities from DSI */ - - /* The following polarity is inverted: - LTDC_DEPOLARITY_AL <-> LTDC_DEPOLARITY_AH */ - - /* Note 1 : Code in line w/ Current LTDC specification */ - hltdc->Init.DEPolarity = (VidCfg->DEPolarity == DSI_DATA_ENABLE_ACTIVE_HIGH) ? LTDC_DEPOLARITY_AL : LTDC_DEPOLARITY_AH; - hltdc->Init.VSPolarity = (VidCfg->VSPolarity == DSI_VSYNC_ACTIVE_HIGH) ? LTDC_VSPOLARITY_AH : LTDC_VSPOLARITY_AL; - hltdc->Init.HSPolarity = (VidCfg->HSPolarity == DSI_HSYNC_ACTIVE_HIGH) ? LTDC_HSPOLARITY_AH : LTDC_HSPOLARITY_AL; - - /* Note 2: Code to be used in case LTDC polarities inversion updated in the specification */ - /* hltdc->Init.DEPolarity = VidCfg->DEPolarity << 29; - hltdc->Init.VSPolarity = VidCfg->VSPolarity << 29; - hltdc->Init.HSPolarity = VidCfg->HSPolarity << 29; */ - - /* Retrieve vertical timing parameters from DSI */ - hltdc->Init.VerticalSync = VidCfg->VerticalSyncActive - 1U; - hltdc->Init.AccumulatedVBP = VidCfg->VerticalSyncActive + VidCfg->VerticalBackPorch - 1U; - hltdc->Init.AccumulatedActiveH = VidCfg->VerticalSyncActive + VidCfg->VerticalBackPorch + VidCfg->VerticalActive - 1U; - hltdc->Init.TotalHeigh = VidCfg->VerticalSyncActive + VidCfg->VerticalBackPorch + VidCfg->VerticalActive + VidCfg->VerticalFrontPorch - 1U; - - return HAL_OK; -} - -/** - * @brief Retrieve common parameters from DSI Adapted command mode configuration structure - * @param hltdc pointer to a LTDC_HandleTypeDef structure that contains - * the configuration information for the LTDC. - * @param CmdCfg pointer to a DSI_CmdCfgTypeDef structure that contains - * the DSI command mode configuration parameters - * @note The implementation of this function is taking into account the LTDC - * polarities inversion as described in the current LTDC specification - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LTDCEx_StructInitFromAdaptedCommandConfig(LTDC_HandleTypeDef *hltdc, DSI_CmdCfgTypeDef *CmdCfg) -{ - /* Retrieve signal polarities from DSI */ - - /* The following polarities are inverted: - LTDC_DEPOLARITY_AL <-> LTDC_DEPOLARITY_AH - LTDC_VSPOLARITY_AL <-> LTDC_VSPOLARITY_AH - LTDC_HSPOLARITY_AL <-> LTDC_HSPOLARITY_AH)*/ - - /* Note 1 : Code in line w/ Current LTDC specification */ - hltdc->Init.DEPolarity = (CmdCfg->DEPolarity == DSI_DATA_ENABLE_ACTIVE_HIGH) ? LTDC_DEPOLARITY_AL : LTDC_DEPOLARITY_AH; - hltdc->Init.VSPolarity = (CmdCfg->VSPolarity == DSI_VSYNC_ACTIVE_HIGH) ? LTDC_VSPOLARITY_AL : LTDC_VSPOLARITY_AH; - hltdc->Init.HSPolarity = (CmdCfg->HSPolarity == DSI_HSYNC_ACTIVE_HIGH) ? LTDC_HSPOLARITY_AL : LTDC_HSPOLARITY_AH; - - /* Note 2: Code to be used in case LTDC polarities inversion updated in the specification */ - /* hltdc->Init.DEPolarity = CmdCfg->DEPolarity << 29; - hltdc->Init.VSPolarity = CmdCfg->VSPolarity << 29; - hltdc->Init.HSPolarity = CmdCfg->HSPolarity << 29; */ - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* LTDC && DSI */ - -#endif /* HAL_LTCD_MODULE_ENABLED && HAL_DSI_MODULE_ENABLED */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_mmc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_mmc.c deleted file mode 100644 index b0827f70a1ebcee..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_mmc.c +++ /dev/null @@ -1,2973 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_mmc.c - * @author MCD Application Team - * @brief MMC card HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Secure Digital (MMC) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + MMC card Control functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - This driver implements a high level communication layer for read and write from/to - this memory. The needed STM32 hardware resources (SDMMC and GPIO) are performed by - the user in HAL_MMC_MspInit() function (MSP layer). - Basically, the MSP layer configuration should be the same as we provide in the - examples. - You can easily tailor this configuration according to hardware resources. - - [..] - This driver is a generic layered driver for SDMMC memories which uses the HAL - SDMMC driver functions to interface with MMC and eMMC cards devices. - It is used as follows: - - (#)Initialize the SDMMC low level resources by implement the HAL_MMC_MspInit() API: - (##) Enable the SDMMC interface clock using __HAL_RCC_SDMMC_CLK_ENABLE(); - (##) SDMMC pins configuration for MMC card - (+++) Enable the clock for the SDMMC GPIOs using the functions __HAL_RCC_GPIOx_CLK_ENABLE(); - (+++) Configure these SDMMC pins as alternate function pull-up using HAL_GPIO_Init() - and according to your pin assignment; - (##) DMA Configuration if you need to use DMA process (HAL_MMC_ReadBlocks_DMA() - and HAL_MMC_WriteBlocks_DMA() APIs). - (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE(); - (+++) Configure the DMA using the function HAL_DMA_Init() with predeclared and filled. - (##) NVIC configuration if you need to use interrupt process when using DMA transfer. - (+++) Configure the SDMMC and DMA interrupt priorities using function HAL_NVIC_SetPriority(); - DMA priority is superior to SDMMC's priority - (+++) Enable the NVIC DMA and SDMMC IRQs using function HAL_NVIC_EnableIRQ() - (+++) SDMMC interrupts are managed using the macros __HAL_MMC_ENABLE_IT() - and __HAL_MMC_DISABLE_IT() inside the communication process. - (+++) SDMMC interrupts pending bits are managed using the macros __HAL_MMC_GET_IT() - and __HAL_MMC_CLEAR_IT() - (##) NVIC configuration if you need to use interrupt process (HAL_MMC_ReadBlocks_IT() - and HAL_MMC_WriteBlocks_IT() APIs). - (+++) Configure the SDMMC interrupt priorities using function HAL_NVIC_SetPriority(); - (+++) Enable the NVIC SDMMC IRQs using function HAL_NVIC_EnableIRQ() - (+++) SDMMC interrupts are managed using the macros __HAL_MMC_ENABLE_IT() - and __HAL_MMC_DISABLE_IT() inside the communication process. - (+++) SDMMC interrupts pending bits are managed using the macros __HAL_MMC_GET_IT() - and __HAL_MMC_CLEAR_IT() - (#) At this stage, you can perform MMC read/write/erase operations after MMC card initialization - - - *** MMC Card Initialization and configuration *** - ================================================ - [..] - To initialize the MMC Card, use the HAL_MMC_Init() function. It Initializes - SDMMC Peripheral (STM32 side) and the MMC Card, and put it into StandBy State (Ready for data transfer). - This function provide the following operations: - - (#) Initialize the SDMMC peripheral interface with defaullt configuration. - The initialization process is done at 400KHz. You can change or adapt - this frequency by adjusting the "ClockDiv" field. - The MMC Card frequency (SDMMC_CK) is computed as follows: - - SDMMC_CK = SDMMCCLK / (ClockDiv + 2) - - In initialization mode and according to the MMC Card standard, - make sure that the SDMMC_CK frequency doesn't exceed 400KHz. - - This phase of initialization is done through SDMMC_Init() and - SDMMC_PowerState_ON() SDMMC low level APIs. - - (#) Initialize the MMC card. The API used is HAL_MMC_InitCard(). - This phase allows the card initialization and identification - and check the MMC Card type (Standard Capacity or High Capacity) - The initialization flow is compatible with MMC standard. - - This API (HAL_MMC_InitCard()) could be used also to reinitialize the card in case - of plug-off plug-in. - - (#) Configure the MMC Card Data transfer frequency. By Default, the card transfer - frequency is set to 24MHz. You can change or adapt this frequency by adjusting - the "ClockDiv" field. - In transfer mode and according to the MMC Card standard, make sure that the - SDMMC_CK frequency doesn't exceed 25MHz and 50MHz in High-speed mode switch. - To be able to use a frequency higher than 24MHz, you should use the SDMMC - peripheral in bypass mode. Refer to the corresponding reference manual - for more details. - - (#) Select the corresponding MMC Card according to the address read with the step 2. - - (#) Configure the MMC Card in wide bus mode: 4-bits data. - - *** MMC Card Read operation *** - ============================== - [..] - (+) You can read from MMC card in polling mode by using function HAL_MMC_ReadBlocks(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_MMC_GetCardState() function for MMC card state. - - (+) You can read from MMC card in DMA mode by using function HAL_MMC_ReadBlocks_DMA(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_MMC_GetCardState() function for MMC card state. - You could also check the DMA transfer process through the MMC Rx interrupt event. - - (+) You can read from MMC card in Interrupt mode by using function HAL_MMC_ReadBlocks_IT(). - This function allows the read of 512 bytes blocks. - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_MMC_GetCardState() function for MMC card state. - You could also check the IT transfer process through the MMC Rx interrupt event. - - *** MMC Card Write operation *** - =============================== - [..] - (+) You can write to MMC card in polling mode by using function HAL_MMC_WriteBlocks(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_MMC_GetCardState() function for MMC card state. - - (+) You can write to MMC card in DMA mode by using function HAL_MMC_WriteBlocks_DMA(). - This function support only 512-bytes block length (the block size should be - chosen as 512 byte). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_MMC_GetCardState() function for MMC card state. - You could also check the DMA transfer process through the MMC Tx interrupt event. - - (+) You can write to MMC card in Interrupt mode by using function HAL_MMC_WriteBlocks_IT(). - This function allows the read of 512 bytes blocks. - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_MMC_GetCardState() function for MMC card state. - You could also check the IT transfer process through the MMC Tx interrupt event. - - *** MMC card information *** - =========================== - [..] - (+) To get MMC card information, you can use the function HAL_MMC_GetCardInfo(). - It returns useful information about the MMC card such as block size, card type, - block number ... - - *** MMC card CSD register *** - ============================ - [..] - (+) The HAL_MMC_GetCardCSD() API allows to get the parameters of the CSD register. - Some of the CSD parameters are useful for card initialization and identification. - - *** MMC card CID register *** - ============================ - [..] - (+) The HAL_MMC_GetCardCID() API allows to get the parameters of the CID register. - Some of the CID parameters are useful for card initialization and identification. - - *** MMC HAL driver macros list *** - ================================== - [..] - Below the list of most used macros in MMC HAL driver. - - (+) __HAL_MMC_ENABLE : Enable the MMC device - (+) __HAL_MMC_DISABLE : Disable the MMC device - (+) __HAL_MMC_DMA_ENABLE: Enable the SDMMC DMA transfer - (+) __HAL_MMC_DMA_DISABLE: Disable the SDMMC DMA transfer - (+) __HAL_MMC_ENABLE_IT: Enable the MMC device interrupt - (+) __HAL_MMC_DISABLE_IT: Disable the MMC device interrupt - (+) __HAL_MMC_GET_FLAG:Check whether the specified MMC flag is set or not - (+) __HAL_MMC_CLEAR_FLAG: Clear the MMC's pending flags - - [..] - (@) You can refer to the MMC HAL driver header file for more useful macros - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_MMC_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions HAL_MMC_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) TxCpltCallback : callback when a transmission transfer is completed. - (+) RxCpltCallback : callback when a reception transfer is completed. - (+) ErrorCallback : callback when error occurs. - (+) AbortCpltCallback : callback when abort is completed. - (+) MspInitCallback : MMC MspInit. - (+) MspDeInitCallback : MMC MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function HAL_MMC_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) TxCpltCallback : callback when a transmission transfer is completed. - (+) RxCpltCallback : callback when a reception transfer is completed. - (+) ErrorCallback : callback when error occurs. - (+) AbortCpltCallback : callback when abort is completed. - (+) MspInitCallback : MMC MspInit. - (+) MspDeInitCallback : MMC MspDeInit. - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the HAL_MMC_Init and if the state is HAL_MMC_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the HAL_MMC_Init - and HAL_MMC_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_MMC_Init and HAL_MMC_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_MMC_RegisterCallback before calling HAL_MMC_DeInit - or HAL_MMC_Init function. - - When The compilation define USE_HAL_MMC_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup MMC MMC - * @brief MMC HAL module driver - * @{ - */ - -#ifdef HAL_MMC_MODULE_ENABLED - -#if defined(SDIO) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup MMC_Private_Defines - * @{ - */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup MMC_Private_Functions MMC Private Functions - * @{ - */ -static uint32_t MMC_InitCard(MMC_HandleTypeDef *hmmc); -static uint32_t MMC_PowerON(MMC_HandleTypeDef *hmmc); -static uint32_t MMC_SendStatus(MMC_HandleTypeDef *hmmc, uint32_t *pCardStatus); -static uint32_t MMC_ReadExtCSD(MMC_HandleTypeDef *hmmc, uint32_t *pFieldData, uint16_t FieldIndex, uint32_t Timeout); -static void MMC_PowerOFF(MMC_HandleTypeDef *hmmc); -static void MMC_Write_IT(MMC_HandleTypeDef *hmmc); -static void MMC_Read_IT(MMC_HandleTypeDef *hmmc); -static void MMC_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void MMC_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void MMC_DMAError(DMA_HandleTypeDef *hdma); -static void MMC_DMATxAbort(DMA_HandleTypeDef *hdma); -static void MMC_DMARxAbort(DMA_HandleTypeDef *hdma); -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup MMC_Exported_Functions - * @{ - */ - -/** @addtogroup MMC_Exported_Functions_Group1 - * @brief Initialization and de-initialization functions - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to initialize/de-initialize the MMC - card device to be ready for use. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the MMC according to the specified parameters in the - MMC_HandleTypeDef and create the associated handle. - * @param hmmc: Pointer to the MMC handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_Init(MMC_HandleTypeDef *hmmc) -{ - /* Check the MMC handle allocation */ - if(hmmc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SDIO_ALL_INSTANCE(hmmc->Instance)); - assert_param(IS_SDIO_CLOCK_EDGE(hmmc->Init.ClockEdge)); - assert_param(IS_SDIO_CLOCK_BYPASS(hmmc->Init.ClockBypass)); - assert_param(IS_SDIO_CLOCK_POWER_SAVE(hmmc->Init.ClockPowerSave)); - assert_param(IS_SDIO_BUS_WIDE(hmmc->Init.BusWide)); - assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(hmmc->Init.HardwareFlowControl)); - assert_param(IS_SDIO_CLKDIV(hmmc->Init.ClockDiv)); - - if(hmmc->State == HAL_MMC_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hmmc->Lock = HAL_UNLOCKED; -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - /* Reset Callback pointers in HAL_MMC_STATE_RESET only */ - hmmc->TxCpltCallback = HAL_MMC_TxCpltCallback; - hmmc->RxCpltCallback = HAL_MMC_RxCpltCallback; - hmmc->ErrorCallback = HAL_MMC_ErrorCallback; - hmmc->AbortCpltCallback = HAL_MMC_AbortCallback; - - if(hmmc->MspInitCallback == NULL) - { - hmmc->MspInitCallback = HAL_MMC_MspInit; - } - - /* Init the low level hardware */ - hmmc->MspInitCallback(hmmc); -#else - /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ - HAL_MMC_MspInit(hmmc); -#endif - } - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Initialize the Card parameters */ - if(HAL_MMC_InitCard(hmmc) == HAL_ERROR) - { - return HAL_ERROR; - } - - /* Initialize the error code */ - hmmc->ErrorCode = HAL_DMA_ERROR_NONE; - - /* Initialize the MMC operation */ - hmmc->Context = MMC_CONTEXT_NONE; - - /* Initialize the MMC state */ - hmmc->State = HAL_MMC_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initializes the MMC Card. - * @param hmmc: Pointer to MMC handle - * @note This function initializes the MMC card. It could be used when a card - re-initialization is needed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_InitCard(MMC_HandleTypeDef *hmmc) -{ - uint32_t errorstate; - MMC_InitTypeDef Init; - HAL_StatusTypeDef status; - - /* Default SDIO peripheral configuration for MMC card initialization */ - Init.ClockEdge = SDIO_CLOCK_EDGE_RISING; - Init.ClockBypass = SDIO_CLOCK_BYPASS_DISABLE; - Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_DISABLE; - Init.BusWide = SDIO_BUS_WIDE_1B; - Init.HardwareFlowControl = SDIO_HARDWARE_FLOW_CONTROL_DISABLE; - Init.ClockDiv = SDIO_INIT_CLK_DIV; - - /* Initialize SDIO peripheral interface with default configuration */ - status = SDIO_Init(hmmc->Instance, Init); - if(status == HAL_ERROR) - { - return HAL_ERROR; - } - - /* Disable SDIO Clock */ - __HAL_MMC_DISABLE(hmmc); - - /* Set Power State to ON */ - status = SDIO_PowerState_ON(hmmc->Instance); - if(status == HAL_ERROR) - { - return HAL_ERROR; - } - - /* Enable MMC Clock */ - __HAL_MMC_ENABLE(hmmc); - - /* Identify card operating voltage */ - errorstate = MMC_PowerON(hmmc); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->State = HAL_MMC_STATE_READY; - hmmc->ErrorCode |= errorstate; - return HAL_ERROR; - } - - /* Card initialization */ - errorstate = MMC_InitCard(hmmc); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->State = HAL_MMC_STATE_READY; - hmmc->ErrorCode |= errorstate; - return HAL_ERROR; - } - - /* Set Block Size for Card */ - errorstate = SDMMC_CmdBlockLength(hmmc->Instance, MMC_BLOCKSIZE); - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief De-Initializes the MMC card. - * @param hmmc: Pointer to MMC handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_DeInit(MMC_HandleTypeDef *hmmc) -{ - /* Check the MMC handle allocation */ - if(hmmc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SDIO_ALL_INSTANCE(hmmc->Instance)); - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Set MMC power state to off */ - MMC_PowerOFF(hmmc); - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - if(hmmc->MspDeInitCallback == NULL) - { - hmmc->MspDeInitCallback = HAL_MMC_MspDeInit; - } - - /* DeInit the low level hardware */ - hmmc->MspDeInitCallback(hmmc); -#else - /* De-Initialize the MSP layer */ - HAL_MMC_MspDeInit(hmmc); -#endif - - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - hmmc->State = HAL_MMC_STATE_RESET; - - return HAL_OK; -} - - -/** - * @brief Initializes the MMC MSP. - * @param hmmc: Pointer to MMC handle - * @retval None - */ -__weak void HAL_MMC_MspInit(MMC_HandleTypeDef *hmmc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hmmc); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_MMC_MspInit could be implemented in the user file - */ -} - -/** - * @brief De-Initialize MMC MSP. - * @param hmmc: Pointer to MMC handle - * @retval None - */ -__weak void HAL_MMC_MspDeInit(MMC_HandleTypeDef *hmmc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hmmc); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_MMC_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @addtogroup MMC_Exported_Functions_Group2 - * @brief Data transfer functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to manage the data - transfer from/to MMC card. - -@endverbatim - * @{ - */ - -/** - * @brief Reads block(s) from a specified address in a card. The Data transfer - * is managed by polling mode. - * @note This API should be followed by a check on the card state through - * HAL_MMC_GetCardState(). - * @param hmmc: Pointer to MMC handle - * @param pData: pointer to the buffer that will contain the received data - * @param BlockAdd: Block Address from where data is to be read - * @param NumberOfBlocks: Number of MMC blocks to read - * @param Timeout: Specify timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t tickstart = HAL_GetTick(); - uint32_t count, data, dataremaining; - uint32_t add = BlockAdd; - uint8_t *tempbuff = pData; - - if(NULL == pData) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; - return HAL_ERROR; - } - - if(hmmc->State == HAL_MMC_STATE_READY) - { - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - - if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Initialize data control register */ - hmmc->Instance->DCTRL = 0U; - - if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) - { - add *= 512U; - } - - /* Configure the MMC DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = NumberOfBlocks * MMC_BLOCKSIZE; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hmmc->Instance, &config); - - /* Read block(s) in polling mode */ - if(NumberOfBlocks > 1U) - { - hmmc->Context = MMC_CONTEXT_READ_MULTIPLE_BLOCK; - - /* Read Multi Block command */ - errorstate = SDMMC_CmdReadMultiBlock(hmmc->Instance, add); - } - else - { - hmmc->Context = MMC_CONTEXT_READ_SINGLE_BLOCK; - - /* Read Single Block command */ - errorstate = SDMMC_CmdReadSingleBlock(hmmc->Instance, add); - } - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - /* Poll on SDIO flags */ - dataremaining = config.DataLength; -#if defined(SDIO_STA_STBITERR) - while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND | SDIO_FLAG_STBITERR)) -#else /* SDIO_STA_STBITERR not defined */ - while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) -#endif /* SDIO_STA_STBITERR */ - { - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXFIFOHF) && (dataremaining > 0U)) - { - /* Read data from SDIO Rx FIFO */ - for(count = 0U; count < 8U; count++) - { - data = SDIO_ReadFIFO(hmmc->Instance); - *tempbuff = (uint8_t)(data & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 8U) & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 16U) & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 24U) & 0xFFU); - tempbuff++; - dataremaining--; - } - } - - if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_TIMEOUT; - hmmc->State= HAL_MMC_STATE_READY; - return HAL_TIMEOUT; - } - } - - /* Send stop transmission command in case of multiblock read */ - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DATAEND) && (NumberOfBlocks > 1U)) - { - /* Send stop transmission command */ - errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - } - - /* Get error state */ - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DTIMEOUT)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_TIMEOUT; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_CRC_FAIL; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_RX_OVERRUN; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else - { - /* Nothing to do */ - } - - /* Empty FIFO if there is still any data */ - while ((__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXDAVL)) && (dataremaining > 0U)) - { - data = SDIO_ReadFIFO(hmmc->Instance); - *tempbuff = (uint8_t)(data & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 8U) & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 16U) & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 24U) & 0xFFU); - tempbuff++; - dataremaining--; - - if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_TIMEOUT; - hmmc->State= HAL_MMC_STATE_READY; - return HAL_ERROR; - } - } - - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); - - hmmc->State = HAL_MMC_STATE_READY; - - return HAL_OK; - } - else - { - hmmc->ErrorCode |= HAL_MMC_ERROR_BUSY; - return HAL_ERROR; - } -} - -/** - * @brief Allows to write block(s) to a specified address in a card. The Data - * transfer is managed by polling mode. - * @note This API should be followed by a check on the card state through - * HAL_MMC_GetCardState(). - * @param hmmc: Pointer to MMC handle - * @param pData: pointer to the buffer that will contain the data to transmit - * @param BlockAdd: Block Address where data will be written - * @param NumberOfBlocks: Number of MMC blocks to write - * @param Timeout: Specify timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_WriteBlocks(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t tickstart = HAL_GetTick(); - uint32_t count, data, dataremaining; - uint32_t add = BlockAdd; - uint8_t *tempbuff = pData; - - if(NULL == pData) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; - return HAL_ERROR; - } - - if(hmmc->State == HAL_MMC_STATE_READY) - { - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - - if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Initialize data control register */ - hmmc->Instance->DCTRL = 0U; - - if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) - { - add *= 512U; - } - - /* Write Blocks in Polling mode */ - if(NumberOfBlocks > 1U) - { - hmmc->Context = MMC_CONTEXT_WRITE_MULTIPLE_BLOCK; - - /* Write Multi Block command */ - errorstate = SDMMC_CmdWriteMultiBlock(hmmc->Instance, add); - } - else - { - hmmc->Context = MMC_CONTEXT_WRITE_SINGLE_BLOCK; - - /* Write Single Block command */ - errorstate = SDMMC_CmdWriteSingleBlock(hmmc->Instance, add); - } - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - /* Configure the MMC DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = NumberOfBlocks * MMC_BLOCKSIZE; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hmmc->Instance, &config); - - /* Write block(s) in polling mode */ - dataremaining = config.DataLength; -#if defined(SDIO_STA_STBITERR) - while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND | SDIO_FLAG_STBITERR)) -#else /* SDIO_STA_STBITERR not defined */ - while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) -#endif /* SDIO_STA_STBITERR */ - { - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXFIFOHE) && (dataremaining > 0U)) - { - /* Write data to SDIO Tx FIFO */ - for(count = 0U; count < 8U; count++) - { - data = (uint32_t)(*tempbuff); - tempbuff++; - dataremaining--; - data |= ((uint32_t)(*tempbuff) << 8U); - tempbuff++; - dataremaining--; - data |= ((uint32_t)(*tempbuff) << 16U); - tempbuff++; - dataremaining--; - data |= ((uint32_t)(*tempbuff) << 24U); - tempbuff++; - dataremaining--; - (void)SDIO_WriteFIFO(hmmc->Instance, &data); - } - } - - if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_TIMEOUT; - } - } - - /* Send stop transmission command in case of multiblock write */ - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DATAEND) && (NumberOfBlocks > 1U)) - { - /* Send stop transmission command */ - errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - } - - /* Get error state */ - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DTIMEOUT)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_TIMEOUT; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_CRC_FAIL; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXUNDERR)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_TX_UNDERRUN; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else - { - /* Nothing to do */ - } - - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); - - hmmc->State = HAL_MMC_STATE_READY; - - return HAL_OK; - } - else - { - hmmc->ErrorCode |= HAL_MMC_ERROR_BUSY; - return HAL_ERROR; - } -} - -/** - * @brief Reads block(s) from a specified address in a card. The Data transfer - * is managed in interrupt mode. - * @note This API should be followed by a check on the card state through - * HAL_MMC_GetCardState(). - * @note You could also check the IT transfer process through the MMC Rx - * interrupt event. - * @param hmmc: Pointer to MMC handle - * @param pData: Pointer to the buffer that will contain the received data - * @param BlockAdd: Block Address from where data is to be read - * @param NumberOfBlocks: Number of blocks to read. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks_IT(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t add = BlockAdd; - - if(NULL == pData) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; - return HAL_ERROR; - } - - if(hmmc->State == HAL_MMC_STATE_READY) - { - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - - if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Initialize data control register */ - hmmc->Instance->DCTRL = 0U; - - hmmc->pRxBuffPtr = pData; - hmmc->RxXferSize = MMC_BLOCKSIZE * NumberOfBlocks; - -#if defined(SDIO_STA_STBITERR) - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_FLAG_RXFIFOHF | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_FLAG_RXFIFOHF)); -#endif /* SDIO_STA_STBITERR */ - - if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) - { - add *= 512U; - } - - /* Configure the MMC DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = MMC_BLOCKSIZE * NumberOfBlocks; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hmmc->Instance, &config); - - /* Read Blocks in IT mode */ - if(NumberOfBlocks > 1U) - { - hmmc->Context = (MMC_CONTEXT_READ_MULTIPLE_BLOCK | MMC_CONTEXT_IT); - - /* Read Multi Block command */ - errorstate = SDMMC_CmdReadMultiBlock(hmmc->Instance, add); - } - else - { - hmmc->Context = (MMC_CONTEXT_READ_SINGLE_BLOCK | MMC_CONTEXT_IT); - - /* Read Single Block command */ - errorstate = SDMMC_CmdReadSingleBlock(hmmc->Instance, add); - } - - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Writes block(s) to a specified address in a card. The Data transfer - * is managed in interrupt mode. - * @note This API should be followed by a check on the card state through - * HAL_MMC_GetCardState(). - * @note You could also check the IT transfer process through the MMC Tx - * interrupt event. - * @param hmmc: Pointer to MMC handle - * @param pData: Pointer to the buffer that will contain the data to transmit - * @param BlockAdd: Block Address where data will be written - * @param NumberOfBlocks: Number of blocks to write - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_WriteBlocks_IT(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t add = BlockAdd; - - if(NULL == pData) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; - return HAL_ERROR; - } - - if(hmmc->State == HAL_MMC_STATE_READY) - { - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - - if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Initialize data control register */ - hmmc->Instance->DCTRL = 0U; - - hmmc->pTxBuffPtr = pData; - hmmc->TxXferSize = MMC_BLOCKSIZE * NumberOfBlocks; - - /* Enable transfer interrupts */ -#if defined(SDIO_STA_STBITERR) - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE)); -#endif /* SDIO_STA_STBITERR */ - - if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) - { - add *= 512U; - } - - /* Write Blocks in Polling mode */ - if(NumberOfBlocks > 1U) - { - hmmc->Context = (MMC_CONTEXT_WRITE_MULTIPLE_BLOCK| MMC_CONTEXT_IT); - - /* Write Multi Block command */ - errorstate = SDMMC_CmdWriteMultiBlock(hmmc->Instance, add); - } - else - { - hmmc->Context = (MMC_CONTEXT_WRITE_SINGLE_BLOCK | MMC_CONTEXT_IT); - - /* Write Single Block command */ - errorstate = SDMMC_CmdWriteSingleBlock(hmmc->Instance, add); - } - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - /* Configure the MMC DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = MMC_BLOCKSIZE * NumberOfBlocks; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hmmc->Instance, &config); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Reads block(s) from a specified address in a card. The Data transfer - * is managed by DMA mode. - * @note This API should be followed by a check on the card state through - * HAL_MMC_GetCardState(). - * @note You could also check the DMA transfer process through the MMC Rx - * interrupt event. - * @param hmmc: Pointer MMC handle - * @param pData: Pointer to the buffer that will contain the received data - * @param BlockAdd: Block Address from where data is to be read - * @param NumberOfBlocks: Number of blocks to read. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks_DMA(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t add = BlockAdd; - - if(NULL == pData) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; - return HAL_ERROR; - } - - if(hmmc->State == HAL_MMC_STATE_READY) - { - hmmc->ErrorCode = HAL_DMA_ERROR_NONE; - - if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Initialize data control register */ - hmmc->Instance->DCTRL = 0U; - -#if defined(SDIO_STA_STBITERR) - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); -#endif /* SDIO_STA_STBITERR */ - - /* Set the DMA transfer complete callback */ - hmmc->hdmarx->XferCpltCallback = MMC_DMAReceiveCplt; - - /* Set the DMA error callback */ - hmmc->hdmarx->XferErrorCallback = MMC_DMAError; - - /* Set the DMA Abort callback */ - hmmc->hdmarx->XferAbortCallback = NULL; - - if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) - { - add *= 512U; - } - - /* Force DMA Direction */ - hmmc->hdmarx->Init.Direction = DMA_PERIPH_TO_MEMORY; - MODIFY_REG(hmmc->hdmarx->Instance->CR, DMA_SxCR_DIR, hmmc->hdmarx->Init.Direction); - - /* Enable the DMA Channel */ - if(HAL_DMA_Start_IT(hmmc->hdmarx, (uint32_t)&hmmc->Instance->FIFO, (uint32_t)pData, (uint32_t)(MMC_BLOCKSIZE * NumberOfBlocks)/4) != HAL_OK) - { - __HAL_MMC_DISABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode = HAL_MMC_ERROR_DMA; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else - { - /* Enable MMC DMA transfer */ - __HAL_MMC_DMA_ENABLE(hmmc); - - /* Configure the MMC DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = MMC_BLOCKSIZE * NumberOfBlocks; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hmmc->Instance, &config); - - /* Read Blocks in DMA mode */ - if(NumberOfBlocks > 1U) - { - hmmc->Context = (MMC_CONTEXT_READ_MULTIPLE_BLOCK | MMC_CONTEXT_DMA); - - /* Read Multi Block command */ - errorstate = SDMMC_CmdReadMultiBlock(hmmc->Instance, add); - } - else - { - hmmc->Context = (MMC_CONTEXT_READ_SINGLE_BLOCK | MMC_CONTEXT_DMA); - - /* Read Single Block command */ - errorstate = SDMMC_CmdReadSingleBlock(hmmc->Instance, add); - } - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - __HAL_MMC_DISABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); - hmmc->ErrorCode = errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - return HAL_OK; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Writes block(s) to a specified address in a card. The Data transfer - * is managed by DMA mode. - * @note This API should be followed by a check on the card state through - * HAL_MMC_GetCardState(). - * @note You could also check the DMA transfer process through the MMC Tx - * interrupt event. - * @param hmmc: Pointer to MMC handle - * @param pData: Pointer to the buffer that will contain the data to transmit - * @param BlockAdd: Block Address where data will be written - * @param NumberOfBlocks: Number of blocks to write - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_WriteBlocks_DMA(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t add = BlockAdd; - - if(NULL == pData) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; - return HAL_ERROR; - } - - if(hmmc->State == HAL_MMC_STATE_READY) - { - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - - if((BlockAdd + NumberOfBlocks) > (hmmc->MmcCard.LogBlockNbr)) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Initialize data control register */ - hmmc->Instance->DCTRL = 0U; - - /* Enable MMC Error interrupts */ -#if defined(SDIO_STA_STBITERR) - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR)); -#endif /* SDIO_STA_STBITERR */ - - /* Set the DMA transfer complete callback */ - hmmc->hdmatx->XferCpltCallback = MMC_DMATransmitCplt; - - /* Set the DMA error callback */ - hmmc->hdmatx->XferErrorCallback = MMC_DMAError; - - /* Set the DMA Abort callback */ - hmmc->hdmatx->XferAbortCallback = NULL; - - if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) - { - add *= 512U; - } - - - /* Write Blocks in Polling mode */ - if(NumberOfBlocks > 1U) - { - hmmc->Context = (MMC_CONTEXT_WRITE_MULTIPLE_BLOCK | MMC_CONTEXT_DMA); - - /* Write Multi Block command */ - errorstate = SDMMC_CmdWriteMultiBlock(hmmc->Instance, add); - } - else - { - hmmc->Context = (MMC_CONTEXT_WRITE_SINGLE_BLOCK | MMC_CONTEXT_DMA); - - /* Write Single Block command */ - errorstate = SDMMC_CmdWriteSingleBlock(hmmc->Instance, add); - } - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - __HAL_MMC_DISABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND)); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - /* Enable SDIO DMA transfer */ - __HAL_MMC_DMA_ENABLE(hmmc); - - /* Force DMA Direction */ - hmmc->hdmatx->Init.Direction = DMA_MEMORY_TO_PERIPH; - MODIFY_REG(hmmc->hdmatx->Instance->CR, DMA_SxCR_DIR, hmmc->hdmatx->Init.Direction); - - /* Enable the DMA Channel */ - if(HAL_DMA_Start_IT(hmmc->hdmatx, (uint32_t)pData, (uint32_t)&hmmc->Instance->FIFO, (uint32_t)(MMC_BLOCKSIZE * NumberOfBlocks)/4) != HAL_OK) - { - __HAL_MMC_DISABLE_IT(hmmc, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND)); - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_DMA; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else - { - /* Configure the MMC DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = MMC_BLOCKSIZE * NumberOfBlocks; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hmmc->Instance, &config); - - return HAL_OK; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Erases the specified memory area of the given MMC card. - * @note This API should be followed by a check on the card state through - * HAL_MMC_GetCardState(). - * @param hmmc: Pointer to MMC handle - * @param BlockStartAdd: Start Block address - * @param BlockEndAdd: End Block address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_Erase(MMC_HandleTypeDef *hmmc, uint32_t BlockStartAdd, uint32_t BlockEndAdd) -{ - uint32_t errorstate; - uint32_t start_add = BlockStartAdd; - uint32_t end_add = BlockEndAdd; - - if(hmmc->State == HAL_MMC_STATE_READY) - { - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - - if(end_add < start_add) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; - return HAL_ERROR; - } - - if(end_add > (hmmc->MmcCard.LogBlockNbr)) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Check if the card command class supports erase command */ - if(((hmmc->MmcCard.Class) & SDIO_CCCC_ERASE) == 0U) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - if((SDIO_GetResponse(hmmc->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_LOCK_UNLOCK_FAILED; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - if ((hmmc->MmcCard.CardType) != MMC_HIGH_CAPACITY_CARD) - { - start_add *= 512U; - end_add *= 512U; - } - - /* Send CMD35 MMC_ERASE_GRP_START with argument as addr */ - errorstate = SDMMC_CmdEraseStartAdd(hmmc->Instance, start_add); - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - /* Send CMD36 MMC_ERASE_GRP_END with argument as addr */ - errorstate = SDMMC_CmdEraseEndAdd(hmmc->Instance, end_add); - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - /* Send CMD38 ERASE */ - errorstate = SDMMC_CmdErase(hmmc->Instance); - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - hmmc->State = HAL_MMC_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief This function handles MMC card interrupt request. - * @param hmmc: Pointer to MMC handle - * @retval None - */ -void HAL_MMC_IRQHandler(MMC_HandleTypeDef *hmmc) -{ - uint32_t errorstate; - uint32_t context = hmmc->Context; - - /* Check for SDIO interrupt flags */ - if((__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXFIFOHF) != RESET) && ((context & MMC_CONTEXT_IT) != 0U)) - { - MMC_Read_IT(hmmc); - } - - else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DATAEND) != RESET) - { - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_FLAG_DATAEND); - -#if defined(SDIO_STA_STBITERR) - __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR | SDIO_IT_STBITERR); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT |\ - SDIO_IT_TXUNDERR | SDIO_IT_RXOVERR | SDIO_IT_TXFIFOHE |\ - SDIO_IT_RXFIFOHF); -#endif /* SDIO_STA_STBITERR */ - - hmmc->Instance->DCTRL &= ~(SDIO_DCTRL_DTEN); - - if((context & MMC_CONTEXT_DMA) != 0U) - { - if((context & MMC_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U) - { - errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->ErrorCallback(hmmc); -#else - HAL_MMC_ErrorCallback(hmmc); -#endif - } - } - if(((context & MMC_CONTEXT_READ_SINGLE_BLOCK) == 0U) && ((context & MMC_CONTEXT_READ_MULTIPLE_BLOCK) == 0U)) - { - /* Disable the DMA transfer for transmit request by setting the DMAEN bit - in the MMC DCTRL register */ - hmmc->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); - - hmmc->State = HAL_MMC_STATE_READY; - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->TxCpltCallback(hmmc); -#else - HAL_MMC_TxCpltCallback(hmmc); -#endif - } - } - else if((context & MMC_CONTEXT_IT) != 0U) - { - /* Stop Transfer for Write Multi blocks or Read Multi blocks */ - if(((context & MMC_CONTEXT_READ_MULTIPLE_BLOCK) != 0U) || ((context & MMC_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) - { - errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->ErrorCallback(hmmc); -#else - HAL_MMC_ErrorCallback(hmmc); -#endif - } - } - - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); - - hmmc->State = HAL_MMC_STATE_READY; - if(((context & MMC_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & MMC_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) - { -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->RxCpltCallback(hmmc); -#else - HAL_MMC_RxCpltCallback(hmmc); -#endif - } - else - { -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->TxCpltCallback(hmmc); -#else - HAL_MMC_TxCpltCallback(hmmc); -#endif - } - } - else - { - /* Nothing to do */ - } - } - - else if((__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXFIFOHE) != RESET) && ((context & MMC_CONTEXT_IT) != 0U)) - { - MMC_Write_IT(hmmc); - } - -#if defined(SDIO_STA_STBITERR) - else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_RXOVERR | SDIO_FLAG_TXUNDERR | SDIO_FLAG_STBITERR) != RESET) -#else /* SDIO_STA_STBITERR not defined */ - else if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_RXOVERR | SDIO_FLAG_TXUNDERR) != RESET) -#endif /* SDIO_STA_STBITERR */ - { - /* Set Error code */ - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DCRCFAIL) != RESET) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_CRC_FAIL; - } - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_DTIMEOUT) != RESET) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_TIMEOUT; - } - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR) != RESET) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_RX_OVERRUN; - } - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_TXUNDERR) != RESET) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_TX_UNDERRUN; - } -#if defined(SDIO_STA_STBITERR) - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_STBITERR) != RESET) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_DATA_TIMEOUT; - } -#endif /* SDIO_STA_STBITERR */ - -#if defined(SDIO_STA_STBITERR) - /* Clear All flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS | SDIO_FLAG_STBITERR); - - /* Disable all interrupts */ - __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR | SDIO_IT_STBITERR); -#else /* SDIO_STA_STBITERR */ - /* Clear All flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); - - /* Disable all interrupts */ - __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); -#endif /* SDIO_STA_STBITERR */ - - hmmc->ErrorCode |= SDMMC_CmdStopTransfer(hmmc->Instance); - - if((context & MMC_CONTEXT_IT) != 0U) - { - /* Set the MMC state to ready to be able to start again the process */ - hmmc->State = HAL_MMC_STATE_READY; -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->ErrorCallback(hmmc); -#else - HAL_MMC_ErrorCallback(hmmc); -#endif /* USE_HAL_MMC_REGISTER_CALLBACKS */ - } - else if((context & MMC_CONTEXT_DMA) != 0U) - { - /* Abort the MMC DMA Streams */ - if(hmmc->hdmatx != NULL) - { - /* Set the DMA Tx abort callback */ - hmmc->hdmatx->XferAbortCallback = MMC_DMATxAbort; - /* Abort DMA in IT mode */ - if(HAL_DMA_Abort_IT(hmmc->hdmatx) != HAL_OK) - { - MMC_DMATxAbort(hmmc->hdmatx); - } - } - else if(hmmc->hdmarx != NULL) - { - /* Set the DMA Rx abort callback */ - hmmc->hdmarx->XferAbortCallback = MMC_DMARxAbort; - /* Abort DMA in IT mode */ - if(HAL_DMA_Abort_IT(hmmc->hdmarx) != HAL_OK) - { - MMC_DMARxAbort(hmmc->hdmarx); - } - } - else - { - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - hmmc->State = HAL_MMC_STATE_READY; -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->AbortCpltCallback(hmmc); -#else - HAL_MMC_AbortCallback(hmmc); -#endif - } - } - else - { - /* Nothing to do */ - } - } - - else - { - /* Nothing to do */ - } -} - -/** - * @brief return the MMC state - * @param hmmc: Pointer to mmc handle - * @retval HAL state - */ -HAL_MMC_StateTypeDef HAL_MMC_GetState(MMC_HandleTypeDef *hmmc) -{ - return hmmc->State; -} - -/** -* @brief Return the MMC error code -* @param hmmc : Pointer to a MMC_HandleTypeDef structure that contains - * the configuration information. -* @retval MMC Error Code -*/ -uint32_t HAL_MMC_GetError(MMC_HandleTypeDef *hmmc) -{ - return hmmc->ErrorCode; -} - -/** - * @brief Tx Transfer completed callbacks - * @param hmmc: Pointer to MMC handle - * @retval None - */ -__weak void HAL_MMC_TxCpltCallback(MMC_HandleTypeDef *hmmc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hmmc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_MMC_TxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callbacks - * @param hmmc: Pointer MMC handle - * @retval None - */ -__weak void HAL_MMC_RxCpltCallback(MMC_HandleTypeDef *hmmc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hmmc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_MMC_RxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief MMC error callbacks - * @param hmmc: Pointer MMC handle - * @retval None - */ -__weak void HAL_MMC_ErrorCallback(MMC_HandleTypeDef *hmmc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hmmc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_MMC_ErrorCallback can be implemented in the user file - */ -} - -/** - * @brief MMC Abort callbacks - * @param hmmc: Pointer MMC handle - * @retval None - */ -__weak void HAL_MMC_AbortCallback(MMC_HandleTypeDef *hmmc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hmmc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_MMC_AbortCallback can be implemented in the user file - */ -} - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -/** - * @brief Register a User MMC Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hmmc : MMC handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_MMC_TX_CPLT_CB_ID MMC Tx Complete Callback ID - * @arg @ref HAL_MMC_RX_CPLT_CB_ID MMC Rx Complete Callback ID - * @arg @ref HAL_MMC_ERROR_CB_ID MMC Error Callback ID - * @arg @ref HAL_MMC_ABORT_CB_ID MMC Abort Callback ID - * @arg @ref HAL_MMC_MSP_INIT_CB_ID MMC MspInit Callback ID - * @arg @ref HAL_MMC_MSP_DEINIT_CB_ID MMC MspDeInit Callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_MMC_RegisterCallback(MMC_HandleTypeDef *hmmc, HAL_MMC_CallbackIDTypeDef CallbackId, pMMC_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - /* Update the error code */ - hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hmmc); - - if(hmmc->State == HAL_MMC_STATE_READY) - { - switch (CallbackId) - { - case HAL_MMC_TX_CPLT_CB_ID : - hmmc->TxCpltCallback = pCallback; - break; - case HAL_MMC_RX_CPLT_CB_ID : - hmmc->RxCpltCallback = pCallback; - break; - case HAL_MMC_ERROR_CB_ID : - hmmc->ErrorCallback = pCallback; - break; - case HAL_MMC_ABORT_CB_ID : - hmmc->AbortCpltCallback = pCallback; - break; - case HAL_MMC_MSP_INIT_CB_ID : - hmmc->MspInitCallback = pCallback; - break; - case HAL_MMC_MSP_DEINIT_CB_ID : - hmmc->MspDeInitCallback = pCallback; - break; - default : - /* Update the error code */ - hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (hmmc->State == HAL_MMC_STATE_RESET) - { - switch (CallbackId) - { - case HAL_MMC_MSP_INIT_CB_ID : - hmmc->MspInitCallback = pCallback; - break; - case HAL_MMC_MSP_DEINIT_CB_ID : - hmmc->MspDeInitCallback = pCallback; - break; - default : - /* Update the error code */ - hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hmmc); - return status; -} - -/** - * @brief Unregister a User MMC Callback - * MMC Callback is redirected to the weak (surcharged) predefined callback - * @param hmmc : MMC handle - * @param CallbackId : ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_MMC_TX_CPLT_CB_ID MMC Tx Complete Callback ID - * @arg @ref HAL_MMC_RX_CPLT_CB_ID MMC Rx Complete Callback ID - * @arg @ref HAL_MMC_ERROR_CB_ID MMC Error Callback ID - * @arg @ref HAL_MMC_ABORT_CB_ID MMC Abort Callback ID - * @arg @ref HAL_MMC_MSP_INIT_CB_ID MMC MspInit Callback ID - * @arg @ref HAL_MMC_MSP_DEINIT_CB_ID MMC MspDeInit Callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_MMC_UnRegisterCallback(MMC_HandleTypeDef *hmmc, HAL_MMC_CallbackIDTypeDef CallbackId) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hmmc); - - if(hmmc->State == HAL_MMC_STATE_READY) - { - switch (CallbackId) - { - case HAL_MMC_TX_CPLT_CB_ID : - hmmc->TxCpltCallback = HAL_MMC_TxCpltCallback; - break; - case HAL_MMC_RX_CPLT_CB_ID : - hmmc->RxCpltCallback = HAL_MMC_RxCpltCallback; - break; - case HAL_MMC_ERROR_CB_ID : - hmmc->ErrorCallback = HAL_MMC_ErrorCallback; - break; - case HAL_MMC_ABORT_CB_ID : - hmmc->AbortCpltCallback = HAL_MMC_AbortCallback; - break; - case HAL_MMC_MSP_INIT_CB_ID : - hmmc->MspInitCallback = HAL_MMC_MspInit; - break; - case HAL_MMC_MSP_DEINIT_CB_ID : - hmmc->MspDeInitCallback = HAL_MMC_MspDeInit; - break; - default : - /* Update the error code */ - hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (hmmc->State == HAL_MMC_STATE_RESET) - { - switch (CallbackId) - { - case HAL_MMC_MSP_INIT_CB_ID : - hmmc->MspInitCallback = HAL_MMC_MspInit; - break; - case HAL_MMC_MSP_DEINIT_CB_ID : - hmmc->MspDeInitCallback = HAL_MMC_MspDeInit; - break; - default : - /* Update the error code */ - hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hmmc->ErrorCode |= HAL_MMC_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hmmc); - return status; -} -#endif - -/** - * @} - */ - -/** @addtogroup MMC_Exported_Functions_Group3 - * @brief management functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control the MMC card - operations and get the related information - -@endverbatim - * @{ - */ - -/** - * @brief Returns information the information of the card which are stored on - * the CID register. - * @param hmmc: Pointer to MMC handle - * @param pCID: Pointer to a HAL_MMC_CIDTypedef structure that - * contains all CID register parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_GetCardCID(MMC_HandleTypeDef *hmmc, HAL_MMC_CardCIDTypeDef *pCID) -{ - pCID->ManufacturerID = (uint8_t)((hmmc->CID[0] & 0xFF000000U) >> 24U); - - pCID->OEM_AppliID = (uint16_t)((hmmc->CID[0] & 0x00FFFF00U) >> 8U); - - pCID->ProdName1 = (((hmmc->CID[0] & 0x000000FFU) << 24U) | ((hmmc->CID[1] & 0xFFFFFF00U) >> 8U)); - - pCID->ProdName2 = (uint8_t)(hmmc->CID[1] & 0x000000FFU); - - pCID->ProdRev = (uint8_t)((hmmc->CID[2] & 0xFF000000U) >> 24U); - - pCID->ProdSN = (((hmmc->CID[2] & 0x00FFFFFFU) << 8U) | ((hmmc->CID[3] & 0xFF000000U) >> 24U)); - - pCID->Reserved1 = (uint8_t)((hmmc->CID[3] & 0x00F00000U) >> 20U); - - pCID->ManufactDate = (uint16_t)((hmmc->CID[3] & 0x000FFF00U) >> 8U); - - pCID->CID_CRC = (uint8_t)((hmmc->CID[3] & 0x000000FEU) >> 1U); - - pCID->Reserved2 = 1U; - - return HAL_OK; -} - -/** - * @brief Returns information the information of the card which are stored on - * the CSD register. - * @param hmmc: Pointer to MMC handle - * @param pCSD: Pointer to a HAL_MMC_CardCSDTypeDef structure that - * contains all CSD register parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_GetCardCSD(MMC_HandleTypeDef *hmmc, HAL_MMC_CardCSDTypeDef *pCSD) -{ - uint32_t block_nbr = 0; - - pCSD->CSDStruct = (uint8_t)((hmmc->CSD[0] & 0xC0000000U) >> 30U); - - pCSD->SysSpecVersion = (uint8_t)((hmmc->CSD[0] & 0x3C000000U) >> 26U); - - pCSD->Reserved1 = (uint8_t)((hmmc->CSD[0] & 0x03000000U) >> 24U); - - pCSD->TAAC = (uint8_t)((hmmc->CSD[0] & 0x00FF0000U) >> 16U); - - pCSD->NSAC = (uint8_t)((hmmc->CSD[0] & 0x0000FF00U) >> 8U); - - pCSD->MaxBusClkFrec = (uint8_t)(hmmc->CSD[0] & 0x000000FFU); - - pCSD->CardComdClasses = (uint16_t)((hmmc->CSD[1] & 0xFFF00000U) >> 20U); - - pCSD->RdBlockLen = (uint8_t)((hmmc->CSD[1] & 0x000F0000U) >> 16U); - - pCSD->PartBlockRead = (uint8_t)((hmmc->CSD[1] & 0x00008000U) >> 15U); - - pCSD->WrBlockMisalign = (uint8_t)((hmmc->CSD[1] & 0x00004000U) >> 14U); - - pCSD->RdBlockMisalign = (uint8_t)((hmmc->CSD[1] & 0x00002000U) >> 13U); - - pCSD->DSRImpl = (uint8_t)((hmmc->CSD[1] & 0x00001000U) >> 12U); - - pCSD->Reserved2 = 0U; /*!< Reserved */ - - pCSD->DeviceSize = (((hmmc->CSD[1] & 0x000003FFU) << 2U) | ((hmmc->CSD[2] & 0xC0000000U) >> 30U)); - - pCSD->MaxRdCurrentVDDMin = (uint8_t)((hmmc->CSD[2] & 0x38000000U) >> 27U); - - pCSD->MaxRdCurrentVDDMax = (uint8_t)((hmmc->CSD[2] & 0x07000000U) >> 24U); - - pCSD->MaxWrCurrentVDDMin = (uint8_t)((hmmc->CSD[2] & 0x00E00000U) >> 21U); - - pCSD->MaxWrCurrentVDDMax = (uint8_t)((hmmc->CSD[2] & 0x001C0000U) >> 18U); - - pCSD->DeviceSizeMul = (uint8_t)((hmmc->CSD[2] & 0x00038000U) >> 15U); - - if(MMC_ReadExtCSD(hmmc, &block_nbr, 212, 0x0FFFFFFFU) != HAL_OK) /* Field SEC_COUNT [215:212] */ - { - return HAL_ERROR; - } - - if(hmmc->MmcCard.CardType == MMC_LOW_CAPACITY_CARD) - { - hmmc->MmcCard.BlockNbr = (pCSD->DeviceSize + 1U) ; - hmmc->MmcCard.BlockNbr *= (1UL << ((pCSD->DeviceSizeMul & 0x07U) + 2U)); - hmmc->MmcCard.BlockSize = (1UL << (pCSD->RdBlockLen & 0x0FU)); - hmmc->MmcCard.LogBlockNbr = (hmmc->MmcCard.BlockNbr) * ((hmmc->MmcCard.BlockSize) / 512U); - hmmc->MmcCard.LogBlockSize = 512U; - } - else if(hmmc->MmcCard.CardType == MMC_HIGH_CAPACITY_CARD) - { - hmmc->MmcCard.BlockNbr = block_nbr; - hmmc->MmcCard.LogBlockNbr = hmmc->MmcCard.BlockNbr; - hmmc->MmcCard.BlockSize = 512U; - hmmc->MmcCard.LogBlockSize = hmmc->MmcCard.BlockSize; - } - else - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_UNSUPPORTED_FEATURE; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - pCSD->EraseGrSize = (uint8_t)((hmmc->CSD[2] & 0x00004000U) >> 14U); - - pCSD->EraseGrMul = (uint8_t)((hmmc->CSD[2] & 0x00003F80U) >> 7U); - - pCSD->WrProtectGrSize = (uint8_t)(hmmc->CSD[2] & 0x0000007FU); - - pCSD->WrProtectGrEnable = (uint8_t)((hmmc->CSD[3] & 0x80000000U) >> 31U); - - pCSD->ManDeflECC = (uint8_t)((hmmc->CSD[3] & 0x60000000U) >> 29U); - - pCSD->WrSpeedFact = (uint8_t)((hmmc->CSD[3] & 0x1C000000U) >> 26U); - - pCSD->MaxWrBlockLen= (uint8_t)((hmmc->CSD[3] & 0x03C00000U) >> 22U); - - pCSD->WriteBlockPaPartial = (uint8_t)((hmmc->CSD[3] & 0x00200000U) >> 21U); - - pCSD->Reserved3 = 0; - - pCSD->ContentProtectAppli = (uint8_t)((hmmc->CSD[3] & 0x00010000U) >> 16U); - - pCSD->FileFormatGroup = (uint8_t)((hmmc->CSD[3] & 0x00008000U) >> 15U); - - pCSD->CopyFlag = (uint8_t)((hmmc->CSD[3] & 0x00004000U) >> 14U); - - pCSD->PermWrProtect = (uint8_t)((hmmc->CSD[3] & 0x00002000U) >> 13U); - - pCSD->TempWrProtect = (uint8_t)((hmmc->CSD[3] & 0x00001000U) >> 12U); - - pCSD->FileFormat = (uint8_t)((hmmc->CSD[3] & 0x00000C00U) >> 10U); - - pCSD->ECC= (uint8_t)((hmmc->CSD[3] & 0x00000300U) >> 8U); - - pCSD->CSD_CRC = (uint8_t)((hmmc->CSD[3] & 0x000000FEU) >> 1U); - - pCSD->Reserved4 = 1; - - return HAL_OK; -} - -/** - * @brief Gets the MMC card info. - * @param hmmc: Pointer to MMC handle - * @param pCardInfo: Pointer to the HAL_MMC_CardInfoTypeDef structure that - * will contain the MMC card status information - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_GetCardInfo(MMC_HandleTypeDef *hmmc, HAL_MMC_CardInfoTypeDef *pCardInfo) -{ - pCardInfo->CardType = (uint32_t)(hmmc->MmcCard.CardType); - pCardInfo->Class = (uint32_t)(hmmc->MmcCard.Class); - pCardInfo->RelCardAdd = (uint32_t)(hmmc->MmcCard.RelCardAdd); - pCardInfo->BlockNbr = (uint32_t)(hmmc->MmcCard.BlockNbr); - pCardInfo->BlockSize = (uint32_t)(hmmc->MmcCard.BlockSize); - pCardInfo->LogBlockNbr = (uint32_t)(hmmc->MmcCard.LogBlockNbr); - pCardInfo->LogBlockSize = (uint32_t)(hmmc->MmcCard.LogBlockSize); - - return HAL_OK; -} - -/** - * @brief Enables wide bus operation for the requested card if supported by - * card. - * @param hmmc: Pointer to MMC handle - * @param WideMode: Specifies the MMC card wide bus mode - * This parameter can be one of the following values: - * @arg SDIO_BUS_WIDE_8B: 8-bit data transfer - * @arg SDIO_BUS_WIDE_4B: 4-bit data transfer - * @arg SDIO_BUS_WIDE_1B: 1-bit data transfer - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_ConfigWideBusOperation(MMC_HandleTypeDef *hmmc, uint32_t WideMode) -{ - __IO uint32_t count = 0U; - SDIO_InitTypeDef Init; - uint32_t errorstate; - uint32_t response = 0U, busy = 0U; - - /* Check the parameters */ - assert_param(IS_SDIO_BUS_WIDE(WideMode)); - - /* Change State */ - hmmc->State = HAL_MMC_STATE_BUSY; - - /* Update Clock for Bus mode update */ - Init.ClockEdge = SDIO_CLOCK_EDGE_RISING; - Init.ClockBypass = SDIO_CLOCK_BYPASS_DISABLE; - Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_DISABLE; - Init.BusWide = WideMode; - Init.HardwareFlowControl = SDIO_HARDWARE_FLOW_CONTROL_DISABLE; - Init.ClockDiv = SDIO_INIT_CLK_DIV; - /* Initialize SDIO*/ - (void)SDIO_Init(hmmc->Instance, Init); - - if(WideMode == SDIO_BUS_WIDE_8B) - { - errorstate = SDMMC_CmdSwitch(hmmc->Instance, 0x03B70200U); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; - } - } - else if(WideMode == SDIO_BUS_WIDE_4B) - { - errorstate = SDMMC_CmdSwitch(hmmc->Instance, 0x03B70100U); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; - } - } - else if(WideMode == SDIO_BUS_WIDE_1B) - { - errorstate = SDMMC_CmdSwitch(hmmc->Instance, 0x03B70000U); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; - } - } - else - { - /* WideMode is not a valid argument*/ - hmmc->ErrorCode |= HAL_MMC_ERROR_PARAM; - } - - /* Check for switch error and violation of the trial number of sending CMD 13 */ - while(busy == 0U) - { - if(count == SDMMC_MAX_TRIAL) - { - hmmc->State = HAL_MMC_STATE_READY; - hmmc->ErrorCode |= HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE; - return HAL_ERROR; - } - count++; - - /* While card is not ready for data and trial number for sending CMD13 is not exceeded */ - errorstate = SDMMC_CmdSendStatus(hmmc->Instance, (uint32_t)(((uint32_t)hmmc->MmcCard.RelCardAdd) << 16U)); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; - } - - /* Get command response */ - response = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); - - /* Get operating voltage*/ - busy = (((response >> 7U) == 1U) ? 0U : 1U); - } - - /* While card is not ready for data and trial number for sending CMD13 is not exceeded */ - count = SDMMC_DATATIMEOUT; - while((response & 0x00000100U) == 0U) - { - if(count == 0U) - { - hmmc->State = HAL_MMC_STATE_READY; - hmmc->ErrorCode |= HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE; - return HAL_ERROR; - } - count--; - - /* While card is not ready for data and trial number for sending CMD13 is not exceeded */ - errorstate = SDMMC_CmdSendStatus(hmmc->Instance, (uint32_t)(((uint32_t)hmmc->MmcCard.RelCardAdd) << 16U)); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; - } - - /* Get command response */ - response = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); - } - - if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - else - { - /* Configure the SDIO peripheral */ - Init.ClockEdge = hmmc->Init.ClockEdge; - Init.ClockBypass = hmmc->Init.ClockBypass; - Init.ClockPowerSave = hmmc->Init.ClockPowerSave; - Init.BusWide = WideMode; - Init.HardwareFlowControl = hmmc->Init.HardwareFlowControl; - Init.ClockDiv = hmmc->Init.ClockDiv; - (void)SDIO_Init(hmmc->Instance, Init); - } - - /* Change State */ - hmmc->State = HAL_MMC_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Gets the current mmc card data state. - * @param hmmc: pointer to MMC handle - * @retval Card state - */ -HAL_MMC_CardStateTypeDef HAL_MMC_GetCardState(MMC_HandleTypeDef *hmmc) -{ - uint32_t cardstate; - uint32_t errorstate; - uint32_t resp1 = 0U; - - errorstate = MMC_SendStatus(hmmc, &resp1); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; - } - - cardstate = ((resp1 >> 9U) & 0x0FU); - - return (HAL_MMC_CardStateTypeDef)cardstate; -} - -/** - * @brief Abort the current transfer and disable the MMC. - * @param hmmc: pointer to a MMC_HandleTypeDef structure that contains - * the configuration information for MMC module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_Abort(MMC_HandleTypeDef *hmmc) -{ - HAL_MMC_CardStateTypeDef CardState; - - /* DIsable All interrupts */ - __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); - - /* Clear All flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); - - if((hmmc->hdmatx != NULL) || (hmmc->hdmarx != NULL)) - { - /* Disable the MMC DMA request */ - hmmc->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); - - /* Abort the MMC DMA Tx Stream */ - if(hmmc->hdmatx != NULL) - { - if(HAL_DMA_Abort(hmmc->hdmatx) != HAL_OK) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_DMA; - } - } - /* Abort the MMC DMA Rx Stream */ - if(hmmc->hdmarx != NULL) - { - if(HAL_DMA_Abort(hmmc->hdmarx) != HAL_OK) - { - hmmc->ErrorCode |= HAL_MMC_ERROR_DMA; - } - } - } - - hmmc->State = HAL_MMC_STATE_READY; - - /* Initialize the MMC operation */ - hmmc->Context = MMC_CONTEXT_NONE; - - CardState = HAL_MMC_GetCardState(hmmc); - if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) - { - hmmc->ErrorCode = SDMMC_CmdStopTransfer(hmmc->Instance); - } - if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) - { - return HAL_ERROR; - } - return HAL_OK; -} - -/** - * @brief Abort the current transfer and disable the MMC (IT mode). - * @param hmmc: pointer to a MMC_HandleTypeDef structure that contains - * the configuration information for MMC module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MMC_Abort_IT(MMC_HandleTypeDef *hmmc) -{ - HAL_MMC_CardStateTypeDef CardState; - - /* DIsable All interrupts */ - __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); - - /* Clear All flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); - - if((hmmc->hdmatx != NULL) || (hmmc->hdmarx != NULL)) - { - /* Disable the MMC DMA request */ - hmmc->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); - - /* Abort the MMC DMA Tx Stream */ - if(hmmc->hdmatx != NULL) - { - hmmc->hdmatx->XferAbortCallback = MMC_DMATxAbort; - if(HAL_DMA_Abort_IT(hmmc->hdmatx) != HAL_OK) - { - hmmc->hdmatx = NULL; - } - } - /* Abort the MMC DMA Rx Stream */ - if(hmmc->hdmarx != NULL) - { - hmmc->hdmarx->XferAbortCallback = MMC_DMARxAbort; - if(HAL_DMA_Abort_IT(hmmc->hdmarx) != HAL_OK) - { - hmmc->hdmarx = NULL; - } - } - } - - /* No transfer ongoing on both DMA channels*/ - if((hmmc->hdmatx == NULL) && (hmmc->hdmarx == NULL)) - { - CardState = HAL_MMC_GetCardState(hmmc); - hmmc->State = HAL_MMC_STATE_READY; - - if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) - { - hmmc->ErrorCode = SDMMC_CmdStopTransfer(hmmc->Instance); - } - if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) - { - return HAL_ERROR; - } - else - { -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->AbortCpltCallback(hmmc); -#else - HAL_MMC_AbortCallback(hmmc); -#endif - } - } - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -/* Private function ----------------------------------------------------------*/ -/** @addtogroup MMC_Private_Functions - * @{ - */ - -/** - * @brief DMA MMC transmit process complete callback - * @param hdma: DMA handle - * @retval None - */ -static void MMC_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); - - /* Enable DATAEND Interrupt */ - __HAL_MMC_ENABLE_IT(hmmc, (SDIO_IT_DATAEND)); -} - -/** - * @brief DMA MMC receive process complete callback - * @param hdma: DMA handle - * @retval None - */ -static void MMC_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); - uint32_t errorstate; - - /* Send stop command in multiblock write */ - if(hmmc->Context == (MMC_CONTEXT_READ_MULTIPLE_BLOCK | MMC_CONTEXT_DMA)) - { - errorstate = SDMMC_CmdStopTransfer(hmmc->Instance); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->ErrorCallback(hmmc); -#else - HAL_MMC_ErrorCallback(hmmc); -#endif - } - } - - /* Disable the DMA transfer for transmit request by setting the DMAEN bit - in the MMC DCTRL register */ - hmmc->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); - - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); - - hmmc->State = HAL_MMC_STATE_READY; - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->RxCpltCallback(hmmc); -#else - HAL_MMC_RxCpltCallback(hmmc); -#endif -} - -/** - * @brief DMA MMC communication error callback - * @param hdma: DMA handle - * @retval None - */ -static void MMC_DMAError(DMA_HandleTypeDef *hdma) -{ - MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); - HAL_MMC_CardStateTypeDef CardState; - uint32_t RxErrorCode, TxErrorCode; - - /* if DMA error is FIFO error ignore it */ - if(HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) - { - RxErrorCode = hmmc->hdmarx->ErrorCode; - TxErrorCode = hmmc->hdmatx->ErrorCode; - if((RxErrorCode == HAL_DMA_ERROR_TE) || (TxErrorCode == HAL_DMA_ERROR_TE)) - { - /* Clear All flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - - /* Disable All interrupts */ - __HAL_MMC_DISABLE_IT(hmmc, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); - - hmmc->ErrorCode |= HAL_MMC_ERROR_DMA; - CardState = HAL_MMC_GetCardState(hmmc); - if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) - { - hmmc->ErrorCode |= SDMMC_CmdStopTransfer(hmmc->Instance); - } - - hmmc->State= HAL_MMC_STATE_READY; - } - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->ErrorCallback(hmmc); -#else - HAL_MMC_ErrorCallback(hmmc); -#endif - } -} - -/** - * @brief DMA MMC Tx Abort callback - * @param hdma: DMA handle - * @retval None - */ -static void MMC_DMATxAbort(DMA_HandleTypeDef *hdma) -{ - MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); - HAL_MMC_CardStateTypeDef CardState; - - if(hmmc->hdmatx != NULL) - { - hmmc->hdmatx = NULL; - } - - /* All DMA channels are aborted */ - if(hmmc->hdmarx == NULL) - { - CardState = HAL_MMC_GetCardState(hmmc); - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - hmmc->State = HAL_MMC_STATE_READY; - if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) - { - hmmc->ErrorCode |= SDMMC_CmdStopTransfer(hmmc->Instance); - - if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) - { -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->AbortCpltCallback(hmmc); -#else - HAL_MMC_AbortCallback(hmmc); -#endif - } - else - { -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->ErrorCallback(hmmc); -#else - HAL_MMC_ErrorCallback(hmmc); -#endif - } - } - } -} - -/** - * @brief DMA MMC Rx Abort callback - * @param hdma: DMA handle - * @retval None - */ -static void MMC_DMARxAbort(DMA_HandleTypeDef *hdma) -{ - MMC_HandleTypeDef* hmmc = (MMC_HandleTypeDef* )(hdma->Parent); - HAL_MMC_CardStateTypeDef CardState; - - if(hmmc->hdmarx != NULL) - { - hmmc->hdmarx = NULL; - } - - /* All DMA channels are aborted */ - if(hmmc->hdmatx == NULL) - { - CardState = HAL_MMC_GetCardState(hmmc); - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - hmmc->State = HAL_MMC_STATE_READY; - if((CardState == HAL_MMC_CARD_RECEIVING) || (CardState == HAL_MMC_CARD_SENDING)) - { - hmmc->ErrorCode |= SDMMC_CmdStopTransfer(hmmc->Instance); - - if(hmmc->ErrorCode != HAL_MMC_ERROR_NONE) - { -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->AbortCpltCallback(hmmc); -#else - HAL_MMC_AbortCallback(hmmc); -#endif - } - else - { -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - hmmc->ErrorCallback(hmmc); -#else - HAL_MMC_ErrorCallback(hmmc); -#endif - } - } - } -} - -/** - * @brief Initializes the mmc card. - * @param hmmc: Pointer to MMC handle - * @retval MMC Card error state - */ -static uint32_t MMC_InitCard(MMC_HandleTypeDef *hmmc) -{ - HAL_MMC_CardCSDTypeDef CSD; - uint32_t errorstate; - uint16_t mmc_rca = 1U; - - /* Check the power State */ - if(SDIO_GetPowerState(hmmc->Instance) == 0U) - { - /* Power off */ - return HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE; - } - - /* Send CMD2 ALL_SEND_CID */ - errorstate = SDMMC_CmdSendCID(hmmc->Instance); - if(errorstate != HAL_MMC_ERROR_NONE) - { - return errorstate; - } - else - { - /* Get Card identification number data */ - hmmc->CID[0U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); - hmmc->CID[1U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP2); - hmmc->CID[2U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP3); - hmmc->CID[3U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP4); - } - - /* Send CMD3 SET_REL_ADDR with argument 0 */ - /* MMC Card publishes its RCA. */ - errorstate = SDMMC_CmdSetRelAdd(hmmc->Instance, &mmc_rca); - if(errorstate != HAL_MMC_ERROR_NONE) - { - return errorstate; - } - - /* Get the MMC card RCA */ - hmmc->MmcCard.RelCardAdd = mmc_rca; - - /* Send CMD9 SEND_CSD with argument as card's RCA */ - errorstate = SDMMC_CmdSendCSD(hmmc->Instance, (uint32_t)(hmmc->MmcCard.RelCardAdd << 16U)); - if(errorstate != HAL_MMC_ERROR_NONE) - { - return errorstate; - } - else - { - /* Get Card Specific Data */ - hmmc->CSD[0U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); - hmmc->CSD[1U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP2); - hmmc->CSD[2U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP3); - hmmc->CSD[3U] = SDIO_GetResponse(hmmc->Instance, SDIO_RESP4); - } - - /* Get the Card Class */ - hmmc->MmcCard.Class = (SDIO_GetResponse(hmmc->Instance, SDIO_RESP2) >> 20U); - - /* Get CSD parameters */ - if (HAL_MMC_GetCardCSD(hmmc, &CSD) != HAL_OK) - { - return hmmc->ErrorCode; - } - - /* Select the Card */ - errorstate = SDMMC_CmdSelDesel(hmmc->Instance, (uint32_t)(((uint32_t)hmmc->MmcCard.RelCardAdd) << 16U)); - if(errorstate != HAL_MMC_ERROR_NONE) - { - return errorstate; - } - - /* Configure SDIO peripheral interface */ - (void)SDIO_Init(hmmc->Instance, hmmc->Init); - - /* All cards are initialized */ - return HAL_MMC_ERROR_NONE; -} - -/** - * @brief Enquires cards about their operating voltage and configures clock - * controls and stores MMC information that will be needed in future - * in the MMC handle. - * @param hmmc: Pointer to MMC handle - * @retval error state - */ -static uint32_t MMC_PowerON(MMC_HandleTypeDef *hmmc) -{ - __IO uint32_t count = 0U; - uint32_t response = 0U, validvoltage = 0U; - uint32_t errorstate; - - /* CMD0: GO_IDLE_STATE */ - errorstate = SDMMC_CmdGoIdleState(hmmc->Instance); - if(errorstate != HAL_MMC_ERROR_NONE) - { - return errorstate; - } - - while(validvoltage == 0U) - { - if(count++ == SDMMC_MAX_VOLT_TRIAL) - { - return HAL_MMC_ERROR_INVALID_VOLTRANGE; - } - - /* SEND CMD1 APP_CMD with MMC_HIGH_VOLTAGE_RANGE(0xC0FF8000) as argument */ - errorstate = SDMMC_CmdOpCondition(hmmc->Instance, eMMC_HIGH_VOLTAGE_RANGE); - if(errorstate != HAL_MMC_ERROR_NONE) - { - return HAL_MMC_ERROR_UNSUPPORTED_FEATURE; - } - - /* Get command response */ - response = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); - - /* Get operating voltage*/ - validvoltage = (((response >> 31U) == 1U) ? 1U : 0U); - } - - /* When power routine is finished and command returns valid voltage */ - if (((response & (0xFF000000U)) >> 24U) == 0xC0U) - { - hmmc->MmcCard.CardType = MMC_HIGH_CAPACITY_CARD; - } - else - { - hmmc->MmcCard.CardType = MMC_LOW_CAPACITY_CARD; - } - - return HAL_MMC_ERROR_NONE; -} - -/** - * @brief Turns the SDIO output signals off. - * @param hmmc: Pointer to MMC handle - * @retval None - */ -static void MMC_PowerOFF(MMC_HandleTypeDef *hmmc) -{ - /* Set Power State to OFF */ - (void)SDIO_PowerState_OFF(hmmc->Instance); -} - -/** - * @brief Returns the current card's status. - * @param hmmc: Pointer to MMC handle - * @param pCardStatus: pointer to the buffer that will contain the MMC card - * status (Card Status register) - * @retval error state - */ -static uint32_t MMC_SendStatus(MMC_HandleTypeDef *hmmc, uint32_t *pCardStatus) -{ - uint32_t errorstate; - - if(pCardStatus == NULL) - { - return HAL_MMC_ERROR_PARAM; - } - - /* Send Status command */ - errorstate = SDMMC_CmdSendStatus(hmmc->Instance, (uint32_t)(hmmc->MmcCard.RelCardAdd << 16U)); - if(errorstate != HAL_MMC_ERROR_NONE) - { - return errorstate; - } - - /* Get MMC card status */ - *pCardStatus = SDIO_GetResponse(hmmc->Instance, SDIO_RESP1); - - return HAL_MMC_ERROR_NONE; -} - -/** - * @brief Reads extended CSD register to get the sectors number of the device - * @param hmmc: Pointer to MMC handle - * @param pFieldData: Pointer to the read buffer - * @param FieldIndex: Index of the field to be read - * @param Timeout: Specify timeout value - * @retval HAL status - */ -static uint32_t MMC_ReadExtCSD(MMC_HandleTypeDef *hmmc, uint32_t *pFieldData, uint16_t FieldIndex, uint32_t Timeout) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t tickstart = HAL_GetTick(); - uint32_t count; - uint32_t i = 0; - uint32_t tmp_data; - - hmmc->ErrorCode = HAL_MMC_ERROR_NONE; - - /* Initialize data control register */ - hmmc->Instance->DCTRL = 0; - - /* Configure the MMC DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = 512; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hmmc->Instance, &config); - - /* Set Block Size for Card */ - errorstate = SDMMC_CmdSendEXTCSD(hmmc->Instance, 0); - if(errorstate != HAL_MMC_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= errorstate; - hmmc->State = HAL_MMC_STATE_READY; - return HAL_ERROR; - } - - /* Poll on SDMMC flags */ - while(!__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) - { - if(__HAL_MMC_GET_FLAG(hmmc, SDIO_FLAG_RXFIFOHF)) - { - /* Read data from SDMMC Rx FIFO */ - for(count = 0U; count < 8U; count++) - { - tmp_data = SDIO_ReadFIFO(hmmc->Instance); - /* eg : SEC_COUNT : FieldIndex = 212 => i+count = 53 */ - /* DEVICE_TYPE : FieldIndex = 196 => i+count = 49 */ - if ((i + count) == ((uint32_t)FieldIndex/4U)) - { - *pFieldData = tmp_data; - } - } - i += 8U; - } - - if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) - { - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_FLAGS); - hmmc->ErrorCode |= HAL_MMC_ERROR_TIMEOUT; - hmmc->State= HAL_MMC_STATE_READY; - return HAL_TIMEOUT; - } - } - - /* While card is not ready for data and trial number for sending CMD13 is not exceeded */ - errorstate = SDMMC_CmdSendStatus(hmmc->Instance, (uint32_t)(((uint32_t)hmmc->MmcCard.RelCardAdd) << 16)); - if(errorstate != HAL_MMC_ERROR_NONE) - { - hmmc->ErrorCode |= errorstate; - } - - /* Clear all the static flags */ - __HAL_MMC_CLEAR_FLAG(hmmc, SDIO_STATIC_DATA_FLAGS); - - hmmc->State = HAL_MMC_STATE_READY; - - return HAL_OK; -} - - -/** - * @brief Wrap up reading in non-blocking mode. - * @param hmmc: pointer to a MMC_HandleTypeDef structure that contains - * the configuration information. - * @retval None - */ -static void MMC_Read_IT(MMC_HandleTypeDef *hmmc) -{ - uint32_t count, data, dataremaining; - uint8_t* tmp; - - tmp = hmmc->pRxBuffPtr; - dataremaining = hmmc->RxXferSize; - - if (dataremaining > 0U) - { - /* Read data from SDIO Rx FIFO */ - for(count = 0U; count < 8U; count++) - { - data = SDIO_ReadFIFO(hmmc->Instance); - *tmp = (uint8_t)(data & 0xFFU); - tmp++; - dataremaining--; - *tmp = (uint8_t)((data >> 8U) & 0xFFU); - tmp++; - dataremaining--; - *tmp = (uint8_t)((data >> 16U) & 0xFFU); - tmp++; - dataremaining--; - *tmp = (uint8_t)((data >> 24U) & 0xFFU); - tmp++; - dataremaining--; - } - - hmmc->pRxBuffPtr = tmp; - hmmc->RxXferSize = dataremaining; - } -} - -/** - * @brief Wrap up writing in non-blocking mode. - * @param hmmc: pointer to a MMC_HandleTypeDef structure that contains - * the configuration information. - * @retval None - */ -static void MMC_Write_IT(MMC_HandleTypeDef *hmmc) -{ - uint32_t count, data, dataremaining; - uint8_t* tmp; - - tmp = hmmc->pTxBuffPtr; - dataremaining = hmmc->TxXferSize; - - if (dataremaining > 0U) - { - /* Write data to SDIO Tx FIFO */ - for(count = 0U; count < 8U; count++) - { - data = (uint32_t)(*tmp); - tmp++; - dataremaining--; - data |= ((uint32_t)(*tmp) << 8U); - tmp++; - dataremaining--; - data |= ((uint32_t)(*tmp) << 16U); - tmp++; - dataremaining--; - data |= ((uint32_t)(*tmp) << 24U); - tmp++; - dataremaining--; - (void)SDIO_WriteFIFO(hmmc->Instance, &data); - } - - hmmc->pTxBuffPtr = tmp; - hmmc->TxXferSize = dataremaining; - } -} - -/** - * @} - */ - -#endif /* SDIO */ - -#endif /* HAL_MMC_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_msp_template.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_msp_template.c deleted file mode 100644 index 67f658c0dc11fbb..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_msp_template.c +++ /dev/null @@ -1,101 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_msp_template.c - * @author MCD Application Team - * @brief This file contains the HAL System and Peripheral (PPP) MSP initialization - * and de-initialization functions. - * It should be copied to the application folder and renamed into 'stm32f4xx_hal_msp.c'. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup HAL_MSP HAL MSP - * @brief HAL MSP module. - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup HAL_MSP_Private_Functions HAL MSP Private Functions - * @{ - */ - -/** - * @brief Initializes the Global MSP. - * @note This function is called from HAL_Init() function to perform system - * level initialization (GPIOs, clock, DMA, interrupt). - * @retval None - */ -void HAL_MspInit(void) -{ - -} - -/** - * @brief DeInitializes the Global MSP. - * @note This functiona is called from HAL_DeInit() function to perform system - * level de-initialization (GPIOs, clock, DMA, interrupt). - * @retval None - */ -void HAL_MspDeInit(void) -{ - -} - -/** - * @brief Initializes the PPP MSP. - * @note This functiona is called from HAL_PPP_Init() function to perform - * peripheral(PPP) system level initialization (GPIOs, clock, DMA, interrupt) - * @retval None - */ -void HAL_PPP_MspInit(void) -{ - -} - -/** - * @brief DeInitializes the PPP MSP. - * @note This functiona is called from HAL_PPP_DeInit() function to perform - * peripheral(PPP) system level de-initialization (GPIOs, clock, DMA, interrupt) - * @retval None - */ -void HAL_PPP_MspDeInit(void) -{ - -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nand.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nand.c deleted file mode 100644 index 2bff47fc564f8d8..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nand.c +++ /dev/null @@ -1,2045 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_nand.c - * @author MCD Application Team - * @brief NAND HAL module driver. - * This file provides a generic firmware to drive NAND memories mounted - * as external device. - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - This driver is a generic layered driver which contains a set of APIs used to - control NAND flash memories. It uses the FMC/FSMC layer functions to interface - with NAND devices. This driver is used as follows: - - (+) NAND flash memory configuration sequence using the function HAL_NAND_Init() - with control and timing parameters for both common and attribute spaces. - - (+) Read NAND flash memory maker and device IDs using the function - HAL_NAND_Read_ID(). The read information is stored in the NAND_ID_TypeDef - structure declared by the function caller. - - (+) Access NAND flash memory by read/write operations using the functions - HAL_NAND_Read_Page_8b()/HAL_NAND_Read_SpareArea_8b(), - HAL_NAND_Write_Page_8b()/HAL_NAND_Write_SpareArea_8b(), - HAL_NAND_Read_Page_16b()/HAL_NAND_Read_SpareArea_16b(), - HAL_NAND_Write_Page_16b()/HAL_NAND_Write_SpareArea_16b() - to read/write page(s)/spare area(s). These functions use specific device - information (Block, page size..) predefined by the user in the HAL_NAND_Info_TypeDef - structure. The read/write address information is contained by the Nand_Address_Typedef - structure passed as parameter. - - (+) Perform NAND flash Reset chip operation using the function HAL_NAND_Reset(). - - (+) Perform NAND flash erase block operation using the function HAL_NAND_Erase_Block(). - The erase block address information is contained in the Nand_Address_Typedef - structure passed as parameter. - - (+) Read the NAND flash status operation using the function HAL_NAND_Read_Status(). - - (+) You can also control the NAND device by calling the control APIs HAL_NAND_ECC_Enable()/ - HAL_NAND_ECC_Disable() to respectively enable/disable the ECC code correction - feature or the function HAL_NAND_GetECC() to get the ECC correction code. - - (+) You can monitor the NAND device HAL state by calling the function - HAL_NAND_GetState() - - [..] - (@) This driver is a set of generic APIs which handle standard NAND flash operations. - If a NAND flash device contains different operations and/or implementations, - it should be implemented separately. - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_NAND_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions @ref HAL_NAND_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) MspInitCallback : NAND MspInit. - (+) MspDeInitCallback : NAND MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function @ref HAL_NAND_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) MspInitCallback : NAND MspInit. - (+) MspDeInitCallback : NAND MspDeInit. - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the @ref HAL_NAND_Init and if the state is HAL_NAND_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the @ref HAL_NAND_Init - and @ref HAL_NAND_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the @ref HAL_NAND_Init and @ref HAL_NAND_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_NAND_RegisterCallback before calling @ref HAL_NAND_DeInit - or @ref HAL_NAND_Init function. - - When The compilation define USE_HAL_NAND_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - - -#ifdef HAL_NAND_MODULE_ENABLED - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** @defgroup NAND NAND - * @brief NAND HAL module driver - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @defgroup NAND_Private_Constants NAND Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/** @defgroup NAND_Private_Macros NAND Private Macros - * @{ - */ - -/** - * @} - */ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup NAND_Exported_Functions NAND Exported Functions - * @{ - */ - -/** @defgroup NAND_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * - @verbatim - ============================================================================== - ##### NAND Initialization and de-initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to initialize/de-initialize - the NAND memory - -@endverbatim - * @{ - */ - -/** - * @brief Perform NAND memory Initialization sequence - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param ComSpace_Timing pointer to Common space timing structure - * @param AttSpace_Timing pointer to Attribute space timing structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Init(NAND_HandleTypeDef *hnand, FMC_NAND_PCC_TimingTypeDef *ComSpace_Timing, FMC_NAND_PCC_TimingTypeDef *AttSpace_Timing) -{ - /* Check the NAND handle state */ - if(hnand == NULL) - { - return HAL_ERROR; - } - - if(hnand->State == HAL_NAND_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hnand->Lock = HAL_UNLOCKED; - -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) - if(hnand->MspInitCallback == NULL) - { - hnand->MspInitCallback = HAL_NAND_MspInit; - } - hnand->ItCallback = HAL_NAND_ITCallback; - - /* Init the low level hardware */ - hnand->MspInitCallback(hnand); -#else - /* Initialize the low level hardware (MSP) */ - HAL_NAND_MspInit(hnand); -#endif - } - - /* Initialize NAND control Interface */ - FMC_NAND_Init(hnand->Instance, &(hnand->Init)); - - /* Initialize NAND common space timing Interface */ - FMC_NAND_CommonSpace_Timing_Init(hnand->Instance, ComSpace_Timing, hnand->Init.NandBank); - - /* Initialize NAND attribute space timing Interface */ - FMC_NAND_AttributeSpace_Timing_Init(hnand->Instance, AttSpace_Timing, hnand->Init.NandBank); - - /* Enable the NAND device */ - __FMC_NAND_ENABLE(hnand->Instance, hnand->Init.NandBank); - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Perform NAND memory De-Initialization sequence - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_DeInit(NAND_HandleTypeDef *hnand) -{ -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) - if(hnand->MspDeInitCallback == NULL) - { - hnand->MspDeInitCallback = HAL_NAND_MspDeInit; - } - - /* DeInit the low level hardware */ - hnand->MspDeInitCallback(hnand); -#else - /* Initialize the low level hardware (MSP) */ - HAL_NAND_MspDeInit(hnand); -#endif - - /* Configure the NAND registers with their reset values */ - FMC_NAND_DeInit(hnand->Instance, hnand->Init.NandBank); - - /* Reset the NAND controller state */ - hnand->State = HAL_NAND_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief NAND MSP Init - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval None - */ -__weak void HAL_NAND_MspInit(NAND_HandleTypeDef *hnand) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hnand); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_NAND_MspInit could be implemented in the user file - */ -} - -/** - * @brief NAND MSP DeInit - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval None - */ -__weak void HAL_NAND_MspDeInit(NAND_HandleTypeDef *hnand) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hnand); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_NAND_MspDeInit could be implemented in the user file - */ -} - - -/** - * @brief This function handles NAND device interrupt request. - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval HAL status -*/ -void HAL_NAND_IRQHandler(NAND_HandleTypeDef *hnand) -{ - /* Check NAND interrupt Rising edge flag */ - if(__FMC_NAND_GET_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_RISING_EDGE)) - { - /* NAND interrupt callback*/ -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) - hnand->ItCallback(hnand); -#else - HAL_NAND_ITCallback(hnand); -#endif - - /* Clear NAND interrupt Rising edge pending bit */ - __FMC_NAND_CLEAR_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_RISING_EDGE); - } - - /* Check NAND interrupt Level flag */ - if(__FMC_NAND_GET_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_LEVEL)) - { - /* NAND interrupt callback*/ -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) - hnand->ItCallback(hnand); -#else - HAL_NAND_ITCallback(hnand); -#endif - - /* Clear NAND interrupt Level pending bit */ - __FMC_NAND_CLEAR_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_LEVEL); - } - - /* Check NAND interrupt Falling edge flag */ - if(__FMC_NAND_GET_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_FALLING_EDGE)) - { - /* NAND interrupt callback*/ -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) - hnand->ItCallback(hnand); -#else - HAL_NAND_ITCallback(hnand); -#endif - - /* Clear NAND interrupt Falling edge pending bit */ - __FMC_NAND_CLEAR_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_FALLING_EDGE); - } - - /* Check NAND interrupt FIFO empty flag */ - if(__FMC_NAND_GET_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_FEMPT)) - { - /* NAND interrupt callback*/ -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) - hnand->ItCallback(hnand); -#else - HAL_NAND_ITCallback(hnand); -#endif - - /* Clear NAND interrupt FIFO empty pending bit */ - __FMC_NAND_CLEAR_FLAG(hnand->Instance, hnand->Init.NandBank, FMC_FLAG_FEMPT); - } -} - -/** - * @brief NAND interrupt feature callback - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval None - */ -__weak void HAL_NAND_ITCallback(NAND_HandleTypeDef *hnand) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hnand); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_NAND_ITCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup NAND_Exported_Functions_Group2 Input and Output functions - * @brief Input Output and memory control functions - * - @verbatim - ============================================================================== - ##### NAND Input and Output functions ##### - ============================================================================== - [..] - This section provides functions allowing to use and control the NAND - memory - -@endverbatim - * @{ - */ - -/** - * @brief Read the NAND memory electronic signature - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pNAND_ID NAND ID structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Read_ID(NAND_HandleTypeDef *hnand, NAND_IDTypeDef *pNAND_ID) -{ - __IO uint32_t data = 0U; - __IO uint32_t data1 = 0U; - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* Send Read ID command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_READID; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - - /* Read the electronic signature from NAND flash */ -#ifdef FSMC_PCR2_PWID - if (hnand->Init.MemoryDataWidth == FSMC_NAND_PCC_MEM_BUS_WIDTH_8) -#else /* FMC_PCR2_PWID is defined */ - if (hnand->Init.MemoryDataWidth == FMC_NAND_PCC_MEM_BUS_WIDTH_8) -#endif - { - data = *(__IO uint32_t *)deviceaddress; - - /* Return the data read */ - pNAND_ID->Maker_Id = ADDR_1ST_CYCLE(data); - pNAND_ID->Device_Id = ADDR_2ND_CYCLE(data); - pNAND_ID->Third_Id = ADDR_3RD_CYCLE(data); - pNAND_ID->Fourth_Id = ADDR_4TH_CYCLE(data); - } - else - { - data = *(__IO uint32_t *)deviceaddress; - data1 = *((__IO uint32_t *)deviceaddress + 4U); - - /* Return the data read */ - pNAND_ID->Maker_Id = ADDR_1ST_CYCLE(data); - pNAND_ID->Device_Id = ADDR_3RD_CYCLE(data); - pNAND_ID->Third_Id = ADDR_1ST_CYCLE(data1); - pNAND_ID->Fourth_Id = ADDR_3RD_CYCLE(data1); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief NAND memory reset - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Reset(NAND_HandleTypeDef *hnand) -{ - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* Send NAND reset command */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = 0xFF; - - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; - -} - -/** - * @brief Configure the device: Enter the physical parameters of the device - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pDeviceConfig pointer to NAND_DeviceConfigTypeDef structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_ConfigDevice(NAND_HandleTypeDef *hnand, NAND_DeviceConfigTypeDef *pDeviceConfig) -{ - hnand->Config.PageSize = pDeviceConfig->PageSize; - hnand->Config.SpareAreaSize = pDeviceConfig->SpareAreaSize; - hnand->Config.BlockSize = pDeviceConfig->BlockSize; - hnand->Config.BlockNbr = pDeviceConfig->BlockNbr; - hnand->Config.PlaneSize = pDeviceConfig->PlaneSize; - hnand->Config.PlaneNbr = pDeviceConfig->PlaneNbr; - hnand->Config.ExtraCommandEnable = pDeviceConfig->ExtraCommandEnable; - - return HAL_OK; -} - -/** - * @brief Read Page(s) from NAND memory block (8-bits addressing) - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @param pBuffer pointer to destination read buffer - * @param NumPageToRead number of pages to read from block - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Read_Page_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumPageToRead) -{ - __IO uint32_t index = 0U; - uint32_t tickstart = 0U; - uint32_t deviceaddress = 0U, size = 0U, numPagesRead = 0U, nandaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* NAND raw address calculation */ - nandaddress = ARRAY_ADDRESS(pAddress, hnand); - - /* Page(s) read loop */ - while((NumPageToRead != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) - { - /* update the buffer size */ - size = (hnand->Config.PageSize) + ((hnand->Config.PageSize) * numPagesRead); - - /* Send read page command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; - - /* Cards with page size <= 512 bytes */ - if((hnand->Config.PageSize) <= 512U) - { - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - else /* (hnand->Config.PageSize) > 512 */ - { - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_TRUE1; - - /* Check if an extra command is needed for reading pages */ - if(hnand->Config.ExtraCommandEnable == ENABLE) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - return HAL_TIMEOUT; - } - } - - /* Go back to read mode */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = ((uint8_t)0x00); - __DSB(); - } - - /* Get Data into Buffer */ - for(; index < size; index++) - { - *(uint8_t *)pBuffer++ = *(uint8_t *)deviceaddress; - } - - /* Increment read pages number */ - numPagesRead++; - - /* Decrement pages to read */ - NumPageToRead--; - - /* Increment the NAND address */ - nandaddress = (uint32_t)(nandaddress + 1U); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief Read Page(s) from NAND memory block (16-bits addressing) - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @param pBuffer pointer to destination read buffer. pBuffer should be 16bits aligned - * @param NumPageToRead number of pages to read from block - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Read_Page_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumPageToRead) -{ - __IO uint32_t index = 0U; - uint32_t tickstart = 0U; - uint32_t deviceaddress = 0U, size = 0U, numPagesRead = 0U, nandaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* NAND raw address calculation */ - nandaddress = ARRAY_ADDRESS(pAddress, hnand); - - /* Page(s) read loop */ - while((NumPageToRead != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) - { - /* update the buffer size */ - size = (hnand->Config.PageSize) + ((hnand->Config.PageSize) * numPagesRead); - - /* Send read page command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; - __DSB(); - - /* Cards with page size <= 512 bytes */ - if((hnand->Config.PageSize) <= 512U) - { - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - else /* (hnand->Config.PageSize) > 512 */ - { - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_TRUE1; - - if(hnand->Config.ExtraCommandEnable == ENABLE) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - return HAL_TIMEOUT; - } - } - - /* Go back to read mode */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = ((uint8_t)0x00); - } - - /* Calculate PageSize */ -#ifdef FSMC_PCR2_PWID - if (hnand->Init.MemoryDataWidth == FSMC_NAND_PCC_MEM_BUS_WIDTH_8) -#else /* FMC_PCR2_PWID is defined */ - if (hnand->Init.MemoryDataWidth == FMC_NAND_PCC_MEM_BUS_WIDTH_8) -#endif - { - size = size / 2U; - } - else - { - /* Do nothing */ - /* Keep the same PageSize for FMC_NAND_MEM_BUS_WIDTH_16*/ - } - - /* Get Data into Buffer */ - for(; index < size; index++) - { - *(uint16_t *)pBuffer++ = *(uint16_t *)deviceaddress; - } - - /* Increment read pages number */ - numPagesRead++; - - /* Decrement pages to read */ - NumPageToRead--; - - /* Increment the NAND address */ - nandaddress = (uint32_t)(nandaddress + 1U); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief Write Page(s) to NAND memory block (8-bits addressing) - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @param pBuffer pointer to source buffer to write - * @param NumPageToWrite number of pages to write to block - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Write_Page_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumPageToWrite) -{ - __IO uint32_t index = 0U; - uint32_t tickstart = 0U; - uint32_t deviceaddress = 0U, size = 0U, numPagesWritten = 0U, nandaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* NAND raw address calculation */ - nandaddress = ARRAY_ADDRESS(pAddress, hnand); - - /* Page(s) write loop */ - while((NumPageToWrite != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) - { - /* update the buffer size */ - size = hnand->Config.PageSize + ((hnand->Config.PageSize) * numPagesWritten); - - /* Send write page command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; - - /* Cards with page size <= 512 bytes */ - if((hnand->Config.PageSize) <= 512U) - { - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - else /* (hnand->Config.PageSize) > 512 */ - { - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - __DSB(); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - __DSB(); - } - } - - - /* Write data to memory */ - for(; index < size; index++) - { - *(__IO uint8_t *)deviceaddress = *(uint8_t *)pBuffer++; - } - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE_TRUE1; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - return HAL_TIMEOUT; - } - } - - /* Increment written pages number */ - numPagesWritten++; - - /* Decrement pages to write */ - NumPageToWrite--; - - /* Increment the NAND address */ - nandaddress = (uint32_t)(nandaddress + 1U); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief Write Page(s) to NAND memory block (16-bits addressing) - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @param pBuffer pointer to source buffer to write. pBuffer should be 16bits aligned - * @param NumPageToWrite number of pages to write to block - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Write_Page_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumPageToWrite) -{ - __IO uint32_t index = 0U; - uint32_t tickstart = 0U; - uint32_t deviceaddress = 0U, size = 0U, numPagesWritten = 0U, nandaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* NAND raw address calculation */ - nandaddress = ARRAY_ADDRESS(pAddress, hnand); - - /* Page(s) write loop */ - while((NumPageToWrite != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) - { - /* update the buffer size */ - size = (hnand->Config.PageSize) + ((hnand->Config.PageSize) * numPagesWritten); - - /* Send write page command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; - __DSB(); - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; - __DSB(); - - /* Cards with page size <= 512 bytes */ - if((hnand->Config.PageSize) <= 512U) - { - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - else /* (hnand->Config.PageSize) > 512 */ - { - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - - /* Calculate PageSize */ -#ifdef FSMC_PCR2_PWID - if (hnand->Init.MemoryDataWidth == FSMC_NAND_PCC_MEM_BUS_WIDTH_8) -#else /* FMC_PCR2_PWID is defined */ - if (hnand->Init.MemoryDataWidth == FMC_NAND_PCC_MEM_BUS_WIDTH_8) -#endif - { - size = size / 2U; - } - else - { - /* Do nothing */ - /* Keep the same PageSize for FMC_NAND_MEM_BUS_WIDTH_16*/ - } - - /* Write data to memory */ - for(; index < size; index++) - { - *(__IO uint16_t *)deviceaddress = *(uint16_t *)pBuffer++; - } - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE_TRUE1; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - return HAL_TIMEOUT; - } - } - - /* Increment written pages number */ - numPagesWritten++; - - /* Decrement pages to write */ - NumPageToWrite--; - - /* Increment the NAND address */ - nandaddress = (uint32_t)(nandaddress + 1U); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief Read Spare area(s) from NAND memory - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @param pBuffer pointer to source buffer to write - * @param NumSpareAreaToRead Number of spare area to read - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_NAND_Read_SpareArea_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumSpareAreaToRead) -{ - __IO uint32_t index = 0U; - uint32_t tickstart = 0U; - uint32_t deviceaddress = 0U, size = 0U, numSpareAreaRead = 0U, nandaddress = 0U, columnaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* NAND raw address calculation */ - nandaddress = ARRAY_ADDRESS(pAddress, hnand); - - /* Column in page address */ - columnaddress = COLUMN_ADDRESS(hnand); - - /* Spare area(s) read loop */ - while((NumSpareAreaToRead != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) - { - /* update the buffer size */ - size = (hnand->Config.SpareAreaSize) + ((hnand->Config.SpareAreaSize) * numSpareAreaRead); - - /* Cards with page size <= 512 bytes */ - if((hnand->Config.PageSize) <= 512U) - { - /* Send read spare area command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_C; - - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - else /* (hnand->Config.PageSize) > 512 */ - { - /* Send read spare area command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; - - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_TRUE1; - - if(hnand->Config.ExtraCommandEnable == ENABLE) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - return HAL_TIMEOUT; - } - } - - /* Go back to read mode */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = ((uint8_t)0x00); - } - - /* Get Data into Buffer */ - for(; index < size; index++) - { - *(uint8_t *)pBuffer++ = *(uint8_t *)deviceaddress; - } - - /* Increment read spare areas number */ - numSpareAreaRead++; - - /* Decrement spare areas to read */ - NumSpareAreaToRead--; - - /* Increment the NAND address */ - nandaddress = (uint32_t)(nandaddress + 1U); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief Read Spare area(s) from NAND memory (16-bits addressing) - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @param pBuffer pointer to source buffer to write. pBuffer should be 16bits aligned. - * @param NumSpareAreaToRead Number of spare area to read - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_NAND_Read_SpareArea_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumSpareAreaToRead) -{ - __IO uint32_t index = 0U; - uint32_t tickstart = 0U; - uint32_t deviceaddress = 0U, size = 0U, numSpareAreaRead = 0U, nandaddress = 0U, columnaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* NAND raw address calculation */ - nandaddress = ARRAY_ADDRESS(pAddress, hnand); - - /* Column in page address */ - columnaddress = (uint32_t)(COLUMN_ADDRESS(hnand)); - - /* Spare area(s) read loop */ - while((NumSpareAreaToRead != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) - { - /* update the buffer size */ - size = (hnand->Config.SpareAreaSize) + ((hnand->Config.SpareAreaSize) * numSpareAreaRead); - - /* Cards with page size <= 512 bytes */ - if((hnand->Config.PageSize) <= 512U) - { - /* Send read spare area command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_C; - - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - else /* (hnand->Config.PageSize) > 512 */ - { - /* Send read spare area command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; - - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_TRUE1; - - if(hnand->Config.ExtraCommandEnable == ENABLE) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - return HAL_TIMEOUT; - } - } - - /* Go back to read mode */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = ((uint8_t)0x00); - } - - /* Get Data into Buffer */ - for(; index < size; index++) - { - *(uint16_t *)pBuffer++ = *(uint16_t *)deviceaddress; - } - - /* Increment read spare areas number */ - numSpareAreaRead++; - - /* Decrement spare areas to read */ - NumSpareAreaToRead--; - - /* Increment the NAND address */ - nandaddress = (uint32_t)(nandaddress + 1U); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief Write Spare area(s) to NAND memory - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @param pBuffer pointer to source buffer to write - * @param NumSpareAreaTowrite number of spare areas to write to block - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Write_SpareArea_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumSpareAreaTowrite) -{ - __IO uint32_t index = 0U; - uint32_t tickstart = 0U; - uint32_t deviceaddress = 0U, size = 0U, numSpareAreaWritten = 0U, nandaddress = 0U, columnaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the FMC_NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* Page address calculation */ - nandaddress = ARRAY_ADDRESS(pAddress, hnand); - - /* Column in page address */ - columnaddress = COLUMN_ADDRESS(hnand); - - /* Spare area(s) write loop */ - while((NumSpareAreaTowrite != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) - { - /* update the buffer size */ - size = (hnand->Config.SpareAreaSize) + ((hnand->Config.SpareAreaSize) * numSpareAreaWritten); - - /* Cards with page size <= 512 bytes */ - if((hnand->Config.PageSize) <= 512U) - { - /* Send write Spare area command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_C; - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; - - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - else /* (hnand->Config.PageSize) > 512 */ - { - /* Send write Spare area command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; - - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - - /* Write data to memory */ - for(; index < size; index++) - { - *(__IO uint8_t *)deviceaddress = *(uint8_t *)pBuffer++; - } - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE_TRUE1; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - return HAL_TIMEOUT; - } - } - - /* Increment written spare areas number */ - numSpareAreaWritten++; - - /* Decrement spare areas to write */ - NumSpareAreaTowrite--; - - /* Increment the NAND address */ - nandaddress = (uint32_t)(nandaddress + 1U); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief Write Spare area(s) to NAND memory (16-bits addressing) - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @param pBuffer pointer to source buffer to write. pBuffer should be 16bits aligned. - * @param NumSpareAreaTowrite number of spare areas to write to block - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Write_SpareArea_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumSpareAreaTowrite) -{ - __IO uint32_t index = 0U; - uint32_t tickstart = 0U; - uint32_t deviceaddress = 0U, size = 0U, numSpareAreaWritten = 0U, nandaddress = 0U, columnaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the FMC_NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* NAND raw address calculation */ - nandaddress = ARRAY_ADDRESS(pAddress, hnand); - - /* Column in page address */ - columnaddress = (uint32_t)(COLUMN_ADDRESS(hnand)); - - /* Spare area(s) write loop */ - while((NumSpareAreaTowrite != 0U) && (nandaddress < ((hnand->Config.BlockSize) * (hnand->Config.BlockNbr)))) - { - /* update the buffer size */ - size = (hnand->Config.SpareAreaSize) + ((hnand->Config.SpareAreaSize) * numSpareAreaWritten); - - /* Cards with page size <= 512 bytes */ - if((hnand->Config.PageSize) <= 512U) - { - /* Send write Spare area command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_C; - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; - - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = 0x00; - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - else /* (hnand->Config.PageSize) > 512 */ - { - /* Send write Spare area command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_AREA_A; - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE0; - - if (((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) <= 65535U) - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - } - else /* ((hnand->Config.BlockSize)*(hnand->Config.BlockNbr)) > 65535 */ - { - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_1ST_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = COLUMN_2ND_CYCLE(columnaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(nandaddress); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(nandaddress); - } - } - - /* Write data to memory */ - for(; index < size; index++) - { - *(__IO uint16_t *)deviceaddress = *(uint16_t *)pBuffer++; - } - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_WRITE_TRUE1; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - return HAL_TIMEOUT; - } - } - - /* Increment written spare areas number */ - numSpareAreaWritten++; - - /* Decrement spare areas to write */ - NumSpareAreaTowrite--; - - /* Increment the NAND address */ - nandaddress = (uint32_t)(nandaddress + 1U); - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief NAND memory Block erase - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_Erase_Block(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress) -{ - uint32_t deviceaddress = 0U; - uint32_t tickstart = 0U; - - /* Process Locked */ - __HAL_LOCK(hnand); - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* Send Erase block command sequence */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_ERASE0; - - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_1ST_CYCLE(ARRAY_ADDRESS(pAddress, hnand)); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_2ND_CYCLE(ARRAY_ADDRESS(pAddress, hnand)); - *(__IO uint8_t *)((uint32_t)(deviceaddress | ADDR_AREA)) = ADDR_3RD_CYCLE(ARRAY_ADDRESS(pAddress, hnand)); - - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_ERASE1; - - /* Update the NAND controller state */ - hnand->State = HAL_NAND_STATE_READY; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Read status until NAND is ready */ - while(HAL_NAND_Read_Status(hnand) != NAND_READY) - { - if((HAL_GetTick() - tickstart ) > NAND_WRITE_TIMEOUT) - { - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_TIMEOUT; - } - } - - /* Process unlocked */ - __HAL_UNLOCK(hnand); - - return HAL_OK; -} - -/** - * @brief NAND memory read status - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval NAND status - */ -uint32_t HAL_NAND_Read_Status(NAND_HandleTypeDef *hnand) -{ - uint32_t data = 0U; - uint32_t deviceaddress = 0U; - - /* Identify the device address */ - if(hnand->Init.NandBank == FMC_NAND_BANK2) - { - deviceaddress = NAND_DEVICE1; - } - else - { - deviceaddress = NAND_DEVICE2; - } - - /* Send Read status operation command */ - *(__IO uint8_t *)((uint32_t)(deviceaddress | CMD_AREA)) = NAND_CMD_STATUS; - - /* Read status register data */ - data = *(__IO uint8_t *)deviceaddress; - - /* Return the status */ - if((data & NAND_ERROR) == NAND_ERROR) - { - return NAND_ERROR; - } - else if((data & NAND_READY) == NAND_READY) - { - return NAND_READY; - } - - return NAND_BUSY; -} - -/** - * @brief Increment the NAND memory address - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param pAddress pointer to NAND address structure - * @retval The new status of the increment address operation. It can be: - * - NAND_VALID_ADDRESS: When the new address is valid address - * - NAND_INVALID_ADDRESS: When the new address is invalid address - */ -uint32_t HAL_NAND_Address_Inc(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress) -{ - uint32_t status = NAND_VALID_ADDRESS; - - /* Increment page address */ - pAddress->Page++; - - /* Check NAND address is valid */ - if(pAddress->Page == hnand->Config.BlockSize) - { - pAddress->Page = 0U; - pAddress->Block++; - - if(pAddress->Block == hnand->Config.PlaneSize) - { - pAddress->Block = 0U; - pAddress->Plane++; - - if(pAddress->Plane == (hnand->Config.PlaneNbr)) - { - status = NAND_INVALID_ADDRESS; - } - } - } - - return (status); -} - -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User NAND Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hnand : NAND handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_NAND_MSP_INIT_CB_ID NAND MspInit callback ID - * @arg @ref HAL_NAND_MSP_DEINIT_CB_ID NAND MspDeInit callback ID - * @arg @ref HAL_NAND_IT_CB_ID NAND IT callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_NAND_RegisterCallback (NAND_HandleTypeDef *hnand, HAL_NAND_CallbackIDTypeDef CallbackId, pNAND_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hnand); - - if(hnand->State == HAL_NAND_STATE_READY) - { - switch (CallbackId) - { - case HAL_NAND_MSP_INIT_CB_ID : - hnand->MspInitCallback = pCallback; - break; - case HAL_NAND_MSP_DEINIT_CB_ID : - hnand->MspDeInitCallback = pCallback; - break; - case HAL_NAND_IT_CB_ID : - hnand->ItCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(hnand->State == HAL_NAND_STATE_RESET) - { - switch (CallbackId) - { - case HAL_NAND_MSP_INIT_CB_ID : - hnand->MspInitCallback = pCallback; - break; - case HAL_NAND_MSP_DEINIT_CB_ID : - hnand->MspDeInitCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hnand); - return status; -} - -/** - * @brief Unregister a User NAND Callback - * NAND Callback is redirected to the weak (surcharged) predefined callback - * @param hnand : NAND handle - * @param CallbackId : ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_NAND_MSP_INIT_CB_ID NAND MspInit callback ID - * @arg @ref HAL_NAND_MSP_DEINIT_CB_ID NAND MspDeInit callback ID - * @arg @ref HAL_NAND_IT_CB_ID NAND IT callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_NAND_UnRegisterCallback (NAND_HandleTypeDef *hnand, HAL_NAND_CallbackIDTypeDef CallbackId) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hnand); - - if(hnand->State == HAL_NAND_STATE_READY) - { - switch (CallbackId) - { - case HAL_NAND_MSP_INIT_CB_ID : - hnand->MspInitCallback = HAL_NAND_MspInit; - break; - case HAL_NAND_MSP_DEINIT_CB_ID : - hnand->MspDeInitCallback = HAL_NAND_MspDeInit; - break; - case HAL_NAND_IT_CB_ID : - hnand->ItCallback = HAL_NAND_ITCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(hnand->State == HAL_NAND_STATE_RESET) - { - switch (CallbackId) - { - case HAL_NAND_MSP_INIT_CB_ID : - hnand->MspInitCallback = HAL_NAND_MspInit; - break; - case HAL_NAND_MSP_DEINIT_CB_ID : - hnand->MspDeInitCallback = HAL_NAND_MspDeInit; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hnand); - return status; -} -#endif - -/** - * @} - */ - -/** @defgroup NAND_Exported_Functions_Group3 Peripheral Control functions - * @brief management functions - * -@verbatim - ============================================================================== - ##### NAND Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the NAND interface. - -@endverbatim - * @{ - */ - - -/** - * @brief Enables dynamically NAND ECC feature. - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_ECC_Enable(NAND_HandleTypeDef *hnand) -{ - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the NAND state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* Enable ECC feature */ - FMC_NAND_ECC_Enable(hnand->Instance, hnand->Init.NandBank); - - /* Update the NAND state */ - hnand->State = HAL_NAND_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Disables dynamically FMC_NAND ECC feature. - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_ECC_Disable(NAND_HandleTypeDef *hnand) -{ - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the NAND state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* Disable ECC feature */ - FMC_NAND_ECC_Disable(hnand->Instance, hnand->Init.NandBank); - - /* Update the NAND state */ - hnand->State = HAL_NAND_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Disables dynamically NAND ECC feature. - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @param ECCval pointer to ECC value - * @param Timeout maximum timeout to wait - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NAND_GetECC(NAND_HandleTypeDef *hnand, uint32_t *ECCval, uint32_t Timeout) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the NAND controller state */ - if(hnand->State == HAL_NAND_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the NAND state */ - hnand->State = HAL_NAND_STATE_BUSY; - - /* Get NAND ECC value */ - status = FMC_NAND_GetECC(hnand->Instance, ECCval, hnand->Init.NandBank, Timeout); - - /* Update the NAND state */ - hnand->State = HAL_NAND_STATE_READY; - - return status; -} - -/** - * @} - */ - - -/** @defgroup NAND_Exported_Functions_Group4 Peripheral State functions - * @brief Peripheral State functions - * -@verbatim - ============================================================================== - ##### NAND State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the NAND controller - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief return the NAND state - * @param hnand pointer to a NAND_HandleTypeDef structure that contains - * the configuration information for NAND module. - * @retval HAL state - */ -HAL_NAND_StateTypeDef HAL_NAND_GetState(NAND_HandleTypeDef *hnand) -{ - return hnand->State; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ - STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx ||\ - STM32F446xx || STM32F469xx || STM32F479xx */ -#endif /* HAL_NAND_MODULE_ENABLED */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nor.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nor.c deleted file mode 100644 index 34a009cafb80728..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_nor.c +++ /dev/null @@ -1,1193 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_nor.c - * @author MCD Application Team - * @brief NOR HAL module driver. - * This file provides a generic firmware to drive NOR memories mounted - * as external device. - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - This driver is a generic layered driver which contains a set of APIs used to - control NOR flash memories. It uses the FMC/FSMC layer functions to interface - with NOR devices. This driver is used as follows: - - (+) NOR flash memory configuration sequence using the function HAL_NOR_Init() - with control and timing parameters for both normal and extended mode. - - (+) Read NOR flash memory manufacturer code and device IDs using the function - HAL_NOR_Read_ID(). The read information is stored in the NOR_ID_TypeDef - structure declared by the function caller. - - (+) Access NOR flash memory by read/write data unit operations using the functions - HAL_NOR_Read(), HAL_NOR_Program(). - - (+) Perform NOR flash erase block/chip operations using the functions - HAL_NOR_Erase_Block() and HAL_NOR_Erase_Chip(). - - (+) Read the NOR flash CFI (common flash interface) IDs using the function - HAL_NOR_Read_CFI(). The read information is stored in the NOR_CFI_TypeDef - structure declared by the function caller. - - (+) You can also control the NOR device by calling the control APIs HAL_NOR_WriteOperation_Enable()/ - HAL_NOR_WriteOperation_Disable() to respectively enable/disable the NOR write operation - - (+) You can monitor the NOR device HAL state by calling the function - HAL_NOR_GetState() - [..] - (@) This driver is a set of generic APIs which handle standard NOR flash operations. - If a NOR flash device contains different operations and/or implementations, - it should be implemented separately. - - *** NOR HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in NOR HAL driver. - - (+) NOR_WRITE : NOR memory write data to specified address - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_NOR_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions @ref HAL_NOR_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) MspInitCallback : NOR MspInit. - (+) MspDeInitCallback : NOR MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function @ref HAL_NOR_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) MspInitCallback : NOR MspInit. - (+) MspDeInitCallback : NOR MspDeInit. - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the @ref HAL_NOR_Init and if the state is HAL_NOR_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the @ref HAL_NOR_Init - and @ref HAL_NOR_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the @ref HAL_NOR_Init and @ref HAL_NOR_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_NOR_RegisterCallback before calling @ref HAL_NOR_DeInit - or @ref HAL_NOR_Init function. - - When The compilation define USE_HAL_NOR_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup NOR NOR - * @brief NOR driver modules - * @{ - */ -#ifdef HAL_NOR_MODULE_ENABLED -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ - -/** @defgroup NOR_Private_Defines NOR Private Defines - * @{ - */ - -/* Constants to define address to set to write a command */ -#define NOR_CMD_ADDRESS_FIRST (uint16_t)0x0555 -#define NOR_CMD_ADDRESS_FIRST_CFI (uint16_t)0x0055 -#define NOR_CMD_ADDRESS_SECOND (uint16_t)0x02AA -#define NOR_CMD_ADDRESS_THIRD (uint16_t)0x0555 -#define NOR_CMD_ADDRESS_FOURTH (uint16_t)0x0555 -#define NOR_CMD_ADDRESS_FIFTH (uint16_t)0x02AA -#define NOR_CMD_ADDRESS_SIXTH (uint16_t)0x0555 - -/* Constants to define data to program a command */ -#define NOR_CMD_DATA_READ_RESET (uint16_t)0x00F0 -#define NOR_CMD_DATA_FIRST (uint16_t)0x00AA -#define NOR_CMD_DATA_SECOND (uint16_t)0x0055 -#define NOR_CMD_DATA_AUTO_SELECT (uint16_t)0x0090 -#define NOR_CMD_DATA_PROGRAM (uint16_t)0x00A0 -#define NOR_CMD_DATA_CHIP_BLOCK_ERASE_THIRD (uint16_t)0x0080 -#define NOR_CMD_DATA_CHIP_BLOCK_ERASE_FOURTH (uint16_t)0x00AA -#define NOR_CMD_DATA_CHIP_BLOCK_ERASE_FIFTH (uint16_t)0x0055 -#define NOR_CMD_DATA_CHIP_ERASE (uint16_t)0x0010 -#define NOR_CMD_DATA_CFI (uint16_t)0x0098 - -#define NOR_CMD_DATA_BUFFER_AND_PROG (uint8_t)0x25 -#define NOR_CMD_DATA_BUFFER_AND_PROG_CONFIRM (uint8_t)0x29 -#define NOR_CMD_DATA_BLOCK_ERASE (uint8_t)0x30 - -/* Mask on NOR STATUS REGISTER */ -#define NOR_MASK_STATUS_DQ5 (uint16_t)0x0020 -#define NOR_MASK_STATUS_DQ6 (uint16_t)0x0040 - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup NOR_Private_Variables NOR Private Variables - * @{ - */ - -static uint32_t uwNORMemoryDataWidth = NOR_MEMORY_8B; - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup NOR_Exported_Functions NOR Exported Functions - * @{ - */ - -/** @defgroup NOR_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * - @verbatim - ============================================================================== - ##### NOR Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to initialize/de-initialize - the NOR memory - -@endverbatim - * @{ - */ - -/** - * @brief Perform the NOR memory Initialization sequence - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param Timing pointer to NOR control timing structure - * @param ExtTiming pointer to NOR extended mode timing structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_Init(NOR_HandleTypeDef *hnor, FMC_NORSRAM_TimingTypeDef *Timing, FMC_NORSRAM_TimingTypeDef *ExtTiming) -{ - /* Check the NOR handle parameter */ - if(hnor == NULL) - { - return HAL_ERROR; - } - - if(hnor->State == HAL_NOR_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hnor->Lock = HAL_UNLOCKED; - -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) - if(hnor->MspInitCallback == NULL) - { - hnor->MspInitCallback = HAL_NOR_MspInit; - } - - /* Init the low level hardware */ - hnor->MspInitCallback(hnor); -#else - /* Initialize the low level hardware (MSP) */ - HAL_NOR_MspInit(hnor); -#endif /* (USE_HAL_NOR_REGISTER_CALLBACKS) */ - } - - /* Initialize NOR control Interface */ - FMC_NORSRAM_Init(hnor->Instance, &(hnor->Init)); - - /* Initialize NOR timing Interface */ - FMC_NORSRAM_Timing_Init(hnor->Instance, Timing, hnor->Init.NSBank); - - /* Initialize NOR extended mode timing Interface */ - FMC_NORSRAM_Extended_Timing_Init(hnor->Extended, ExtTiming, hnor->Init.NSBank, hnor->Init.ExtendedMode); - - /* Enable the NORSRAM device */ - __FMC_NORSRAM_ENABLE(hnor->Instance, hnor->Init.NSBank); - - /* Initialize NOR Memory Data Width*/ - if (hnor->Init.MemoryDataWidth == FMC_NORSRAM_MEM_BUS_WIDTH_8) - { - uwNORMemoryDataWidth = NOR_MEMORY_8B; - } - else - { - uwNORMemoryDataWidth = NOR_MEMORY_16B; - } - - /* Check the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Perform NOR memory De-Initialization sequence - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_DeInit(NOR_HandleTypeDef *hnor) -{ -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) - if(hnor->MspDeInitCallback == NULL) - { - hnor->MspDeInitCallback = HAL_NOR_MspDeInit; - } - - /* DeInit the low level hardware */ - hnor->MspDeInitCallback(hnor); -#else - /* De-Initialize the low level hardware (MSP) */ - HAL_NOR_MspDeInit(hnor); -#endif /* (USE_HAL_NOR_REGISTER_CALLBACKS) */ - - /* Configure the NOR registers with their reset values */ - FMC_NORSRAM_DeInit(hnor->Instance, hnor->Extended, hnor->Init.NSBank); - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @brief NOR MSP Init - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @retval None - */ -__weak void HAL_NOR_MspInit(NOR_HandleTypeDef *hnor) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hnor); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_NOR_MspInit could be implemented in the user file - */ -} - -/** - * @brief NOR MSP DeInit - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @retval None - */ -__weak void HAL_NOR_MspDeInit(NOR_HandleTypeDef *hnor) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hnor); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_NOR_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief NOR MSP Wait for Ready/Busy signal - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param Timeout Maximum timeout value - * @retval None - */ -__weak void HAL_NOR_MspWait(NOR_HandleTypeDef *hnor, uint32_t Timeout) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hnor); - UNUSED(Timeout); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_NOR_MspWait could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup NOR_Exported_Functions_Group2 Input and Output functions - * @brief Input Output and memory control functions - * - @verbatim - ============================================================================== - ##### NOR Input and Output functions ##### - ============================================================================== - [..] - This section provides functions allowing to use and control the NOR memory - -@endverbatim - * @{ - */ - -/** - * @brief Read NOR flash IDs - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param pNOR_ID pointer to NOR ID structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_Read_ID(NOR_HandleTypeDef *hnor, NOR_IDTypeDef *pNOR_ID) -{ - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Send read ID command */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_AUTO_SELECT); - - /* Read the NOR IDs */ - pNOR_ID->Manufacturer_Code = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, MC_ADDRESS); - pNOR_ID->Device_Code1 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, DEVICE_CODE1_ADDR); - pNOR_ID->Device_Code2 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, DEVICE_CODE2_ADDR); - pNOR_ID->Device_Code3 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, DEVICE_CODE3_ADDR); - - /* Check the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @brief Returns the NOR memory to Read mode. - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_ReturnToReadMode(NOR_HandleTypeDef *hnor) -{ - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - NOR_WRITE(deviceaddress, NOR_CMD_DATA_READ_RESET); - - /* Check the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @brief Read data from NOR memory - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param pAddress pointer to Device address - * @param pData pointer to read data - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_Read(NOR_HandleTypeDef *hnor, uint32_t *pAddress, uint16_t *pData) -{ - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Send read data command */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_READ_RESET); - - /* Read the data */ - *pData = *(__IO uint32_t *)(uint32_t)pAddress; - - /* Check the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @brief Program data to NOR memory - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param pAddress Device address - * @param pData pointer to the data to write - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_Program(NOR_HandleTypeDef *hnor, uint32_t *pAddress, uint16_t *pData) -{ - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Send program data command */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_PROGRAM); - - /* Write the data */ - NOR_WRITE(pAddress, *pData); - - /* Check the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @brief Reads a half-word buffer from the NOR memory. - * @param hnor pointer to the NOR handle - * @param uwAddress NOR memory internal address to read from. - * @param pData pointer to the buffer that receives the data read from the - * NOR memory. - * @param uwBufferSize number of Half word to read. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_ReadBuffer(NOR_HandleTypeDef *hnor, uint32_t uwAddress, uint16_t *pData, uint32_t uwBufferSize) -{ - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Send read data command */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_READ_RESET); - - /* Read buffer */ - while( uwBufferSize > 0U) - { - *pData++ = *(__IO uint16_t *)uwAddress; - uwAddress += 2U; - uwBufferSize--; - } - - /* Check the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @brief Writes a half-word buffer to the NOR memory. This function must be used - only with S29GL128P NOR memory. - * @param hnor pointer to the NOR handle - * @param uwAddress NOR memory internal start write address - * @param pData pointer to source data buffer. - * @param uwBufferSize Size of the buffer to write - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_ProgramBuffer(NOR_HandleTypeDef *hnor, uint32_t uwAddress, uint16_t *pData, uint32_t uwBufferSize) -{ - uint16_t * p_currentaddress = (uint16_t *)NULL; - uint16_t * p_endaddress = (uint16_t *)NULL; - uint32_t lastloadedaddress = 0U, deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Initialize variables */ - p_currentaddress = (uint16_t*)((uint32_t)(uwAddress)); - p_endaddress = p_currentaddress + (uwBufferSize-1U); - lastloadedaddress = (uint32_t)(uwAddress); - - /* Issue unlock command sequence */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); - - /* Write Buffer Load Command */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, uwAddress), NOR_CMD_DATA_BUFFER_AND_PROG); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, uwAddress), (uwBufferSize - 1U)); - - /* Load Data into NOR Buffer */ - while(p_currentaddress <= p_endaddress) - { - /* Store last loaded address & data value (for polling) */ - lastloadedaddress = (uint32_t)p_currentaddress; - - NOR_WRITE(p_currentaddress, *pData++); - - p_currentaddress ++; - } - - NOR_WRITE((uint32_t)(lastloadedaddress), NOR_CMD_DATA_BUFFER_AND_PROG_CONFIRM); - - /* Check the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; - -} - -/** - * @brief Erase the specified block of the NOR memory - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param BlockAddress Block to erase address - * @param Address Device address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_Erase_Block(NOR_HandleTypeDef *hnor, uint32_t BlockAddress, uint32_t Address) -{ - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Send block erase command sequence */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_CHIP_BLOCK_ERASE_THIRD); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FOURTH), NOR_CMD_DATA_CHIP_BLOCK_ERASE_FOURTH); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIFTH), NOR_CMD_DATA_CHIP_BLOCK_ERASE_FIFTH); - NOR_WRITE((uint32_t)(BlockAddress + Address), NOR_CMD_DATA_BLOCK_ERASE); - - /* Check the NOR memory status and update the controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; - -} - -/** - * @brief Erase the entire NOR chip. - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param Address Device address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_Erase_Chip(NOR_HandleTypeDef *hnor, uint32_t Address) -{ - uint32_t deviceaddress = 0U; - - /* Prevent unused argument(s) compilation warning */ - UNUSED(Address); - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Send NOR chip erase command sequence */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST), NOR_CMD_DATA_FIRST); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SECOND), NOR_CMD_DATA_SECOND); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_THIRD), NOR_CMD_DATA_CHIP_BLOCK_ERASE_THIRD); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FOURTH), NOR_CMD_DATA_CHIP_BLOCK_ERASE_FOURTH); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIFTH), NOR_CMD_DATA_CHIP_BLOCK_ERASE_FIFTH); - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_SIXTH), NOR_CMD_DATA_CHIP_ERASE); - - /* Check the NOR memory status and update the controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @brief Read NOR flash CFI IDs - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param pNOR_CFI pointer to NOR CFI IDs structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_Read_CFI(NOR_HandleTypeDef *hnor, NOR_CFITypeDef *pNOR_CFI) -{ - uint32_t deviceaddress = 0U; - - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Check the NOR controller state */ - if(hnor->State == HAL_NOR_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Select the NOR device address */ - if (hnor->Init.NSBank == FMC_NORSRAM_BANK1) - { - deviceaddress = NOR_MEMORY_ADRESS1; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK2) - { - deviceaddress = NOR_MEMORY_ADRESS2; - } - else if (hnor->Init.NSBank == FMC_NORSRAM_BANK3) - { - deviceaddress = NOR_MEMORY_ADRESS3; - } - else /* FMC_NORSRAM_BANK4 */ - { - deviceaddress = NOR_MEMORY_ADRESS4; - } - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Send read CFI query command */ - NOR_WRITE(NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, NOR_CMD_ADDRESS_FIRST_CFI), NOR_CMD_DATA_CFI); - - /* read the NOR CFI information */ - pNOR_CFI->CFI_1 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, CFI1_ADDRESS); - pNOR_CFI->CFI_2 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, CFI2_ADDRESS); - pNOR_CFI->CFI_3 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, CFI3_ADDRESS); - pNOR_CFI->CFI_4 = *(__IO uint16_t *) NOR_ADDR_SHIFT(deviceaddress, uwNORMemoryDataWidth, CFI4_ADDRESS); - - /* Check the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User NOR Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hnor : NOR handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_NOR_MSP_INIT_CB_ID NOR MspInit callback ID - * @arg @ref HAL_NOR_MSP_DEINIT_CB_ID NOR MspDeInit callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_NOR_RegisterCallback (NOR_HandleTypeDef *hnor, HAL_NOR_CallbackIDTypeDef CallbackId, pNOR_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_NOR_StateTypeDef state; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hnor); - - state = hnor->State; - if((state == HAL_NOR_STATE_READY) || (state == HAL_NOR_STATE_RESET) || (state == HAL_NOR_STATE_PROTECTED)) - { - switch (CallbackId) - { - case HAL_NOR_MSP_INIT_CB_ID : - hnor->MspInitCallback = pCallback; - break; - case HAL_NOR_MSP_DEINIT_CB_ID : - hnor->MspDeInitCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hnor); - return status; -} - -/** - * @brief Unregister a User NOR Callback - * NOR Callback is redirected to the weak (surcharged) predefined callback - * @param hnor : NOR handle - * @param CallbackId : ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_NOR_MSP_INIT_CB_ID NOR MspInit callback ID - * @arg @ref HAL_NOR_MSP_DEINIT_CB_ID NOR MspDeInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_NOR_UnRegisterCallback (NOR_HandleTypeDef *hnor, HAL_NOR_CallbackIDTypeDef CallbackId) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_NOR_StateTypeDef state; - - /* Process locked */ - __HAL_LOCK(hnor); - - state = hnor->State; - if((state == HAL_NOR_STATE_READY) || (state == HAL_NOR_STATE_RESET) || (state == HAL_NOR_STATE_PROTECTED)) - { - switch (CallbackId) - { - case HAL_NOR_MSP_INIT_CB_ID : - hnor->MspInitCallback = HAL_NOR_MspInit; - break; - case HAL_NOR_MSP_DEINIT_CB_ID : - hnor->MspDeInitCallback = HAL_NOR_MspDeInit; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hnor); - return status; -} -#endif /* (USE_HAL_NOR_REGISTER_CALLBACKS) */ -/** - * @} - */ - -/** @defgroup NOR_Exported_Functions_Group3 NOR Control functions - * @brief management functions - * -@verbatim - ============================================================================== - ##### NOR Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the NOR interface. - -@endverbatim - * @{ - */ - -/** - * @brief Enables dynamically NOR write operation. - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_WriteOperation_Enable(NOR_HandleTypeDef *hnor) -{ - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Enable write operation */ - FMC_NORSRAM_WriteOperation_Enable(hnor->Instance, hnor->Init.NSBank); - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @brief Disables dynamically NOR write operation. - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_NOR_WriteOperation_Disable(NOR_HandleTypeDef *hnor) -{ - /* Process Locked */ - __HAL_LOCK(hnor); - - /* Update the SRAM controller state */ - hnor->State = HAL_NOR_STATE_BUSY; - - /* Disable write operation */ - FMC_NORSRAM_WriteOperation_Disable(hnor->Instance, hnor->Init.NSBank); - - /* Update the NOR controller state */ - hnor->State = HAL_NOR_STATE_PROTECTED; - - /* Process unlocked */ - __HAL_UNLOCK(hnor); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup NOR_Exported_Functions_Group4 NOR State functions - * @brief Peripheral State functions - * -@verbatim - ============================================================================== - ##### NOR State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the NOR controller - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief return the NOR controller state - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @retval NOR controller state - */ -HAL_NOR_StateTypeDef HAL_NOR_GetState(NOR_HandleTypeDef *hnor) -{ - return hnor->State; -} - -/** - * @brief Returns the NOR operation status. - * @param hnor pointer to a NOR_HandleTypeDef structure that contains - * the configuration information for NOR module. - * @param Address Device address - * @param Timeout NOR programming Timeout - * @retval NOR_Status: The returned value can be: HAL_NOR_STATUS_SUCCESS, HAL_NOR_STATUS_ERROR - * or HAL_NOR_STATUS_TIMEOUT - */ -HAL_NOR_StatusTypeDef HAL_NOR_GetStatus(NOR_HandleTypeDef *hnor, uint32_t Address, uint32_t Timeout) -{ - HAL_NOR_StatusTypeDef status = HAL_NOR_STATUS_ONGOING; - uint16_t tmpSR1 = 0, tmpSR2 = 0; - uint32_t tickstart = 0U; - - /* Poll on NOR memory Ready/Busy signal ------------------------------------*/ - HAL_NOR_MspWait(hnor, Timeout); - - /* Get the NOR memory operation status -------------------------------------*/ - - /* Get tick */ - tickstart = HAL_GetTick(); - while((status != HAL_NOR_STATUS_SUCCESS ) && (status != HAL_NOR_STATUS_TIMEOUT)) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - status = HAL_NOR_STATUS_TIMEOUT; - } - } - - /* Read NOR status register (DQ6 and DQ5) */ - tmpSR1 = *(__IO uint16_t *)Address; - tmpSR2 = *(__IO uint16_t *)Address; - - /* If DQ6 did not toggle between the two reads then return HAL_NOR_STATUS_SUCCESS */ - if((tmpSR1 & NOR_MASK_STATUS_DQ6) == (tmpSR2 & NOR_MASK_STATUS_DQ6)) - { - return HAL_NOR_STATUS_SUCCESS ; - } - - if((tmpSR1 & NOR_MASK_STATUS_DQ5) == NOR_MASK_STATUS_DQ5) - { - status = HAL_NOR_STATUS_ONGOING; - } - - tmpSR1 = *(__IO uint16_t *)Address; - tmpSR2 = *(__IO uint16_t *)Address; - - /* If DQ6 did not toggle between the two reads then return HAL_NOR_STATUS_SUCCESS */ - if((tmpSR1 & NOR_MASK_STATUS_DQ6) == (tmpSR2 & NOR_MASK_STATUS_DQ6)) - { - return HAL_NOR_STATUS_SUCCESS; - } - if((tmpSR1 & NOR_MASK_STATUS_DQ5) == NOR_MASK_STATUS_DQ5) - { - return HAL_NOR_STATUS_ERROR; - } - } - - /* Return the operation status */ - return status; -} - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx ||\ - STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ - STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx ||\ - STM32F423xx */ -#endif /* HAL_NOR_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pccard.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pccard.c deleted file mode 100644 index 2f7d3e0ff5247ec..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pccard.c +++ /dev/null @@ -1,942 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pccard.c - * @author MCD Application Team - * @brief PCCARD HAL module driver. - * This file provides a generic firmware to drive PCCARD memories mounted - * as external device. - * - @verbatim - =============================================================================== - ##### How to use this driver ##### - =============================================================================== - [..] - This driver is a generic layered driver which contains a set of APIs used to - control PCCARD/compact flash memories. It uses the FMC/FSMC layer functions - to interface with PCCARD devices. This driver is used for: - - (+) PCCARD/Compact Flash memory configuration sequence using the function - HAL_PCCARD_Init()/HAL_CF_Init() with control and timing parameters for - both common and attribute spaces. - - (+) Read PCCARD/Compact Flash memory maker and device IDs using the function - HAL_PCCARD_Read_ID()/HAL_CF_Read_ID(). The read information is stored in - the CompactFlash_ID structure declared by the function caller. - - (+) Access PCCARD/Compact Flash memory by read/write operations using the functions - HAL_PCCARD_Read_Sector()/ HAL_PCCARD_Write_Sector() - - HAL_CF_Read_Sector()/HAL_CF_Write_Sector(), to read/write sector. - - (+) Perform PCCARD/Compact Flash Reset chip operation using the function - HAL_PCCARD_Reset()/HAL_CF_Reset. - - (+) Perform PCCARD/Compact Flash erase sector operation using the function - HAL_PCCARD_Erase_Sector()/HAL_CF_Erase_Sector. - - (+) Read the PCCARD/Compact Flash status operation using the function - HAL_PCCARD_ReadStatus()/HAL_CF_ReadStatus(). - - (+) You can monitor the PCCARD/Compact Flash device HAL state by calling - the function HAL_PCCARD_GetState()/HAL_CF_GetState() - - [..] - (@) This driver is a set of generic APIs which handle standard PCCARD/compact flash - operations. If a PCCARD/Compact Flash device contains different operations - and/or implementations, it should be implemented separately. - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_PCCARD_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions @ref HAL_PCCARD_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) MspInitCallback : PCCARD MspInit. - (+) MspDeInitCallback : PCCARD MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function @ref HAL_PCCARD_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) MspInitCallback : PCCARD MspInit. - (+) MspDeInitCallback : PCCARD MspDeInit. - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the @ref HAL_PCCARD_Init and if the state is HAL_PCCARD_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the @ref HAL_PCCARD_Init - and @ref HAL_PCCARD_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the @ref HAL_PCCARD_Init and @ref HAL_PCCARD_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_PCCARD_RegisterCallback before calling @ref HAL_PCCARD_DeInit - or @ref HAL_PCCARD_Init function. - - When The compilation define USE_HAL_PCCARD_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_PCCARD_MODULE_ENABLED -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @defgroup PCCARD PCCARD - * @brief PCCARD HAL module driver - * @{ - */ -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ - -/** @defgroup PCCARD_Private_Defines PCCARD Private Defines - * @{ - */ -#define PCCARD_TIMEOUT_READ_ID 0x0000FFFFU -#define PCCARD_TIMEOUT_READ_WRITE_SECTOR 0x0000FFFFU -#define PCCARD_TIMEOUT_ERASE_SECTOR 0x00000400U -#define PCCARD_TIMEOUT_STATUS 0x01000000U - -#define PCCARD_STATUS_OK (uint8_t)0x58 -#define PCCARD_STATUS_WRITE_OK (uint8_t)0x50 -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function ----------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup PCCARD_Exported_Functions PCCARD Exported Functions - * @{ - */ - -/** @defgroup PCCARD_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * - @verbatim - ============================================================================== - ##### PCCARD Initialization and de-initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to initialize/de-initialize - the PCCARD memory - -@endverbatim - * @{ - */ - -/** - * @brief Perform the PCCARD memory Initialization sequence - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @param ComSpaceTiming Common space timing structure - * @param AttSpaceTiming Attribute space timing structure - * @param IOSpaceTiming IO space timing structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCCARD_Init(PCCARD_HandleTypeDef *hpccard, FMC_NAND_PCC_TimingTypeDef *ComSpaceTiming, FMC_NAND_PCC_TimingTypeDef *AttSpaceTiming, FMC_NAND_PCC_TimingTypeDef *IOSpaceTiming) -{ - /* Check the PCCARD controller state */ - if(hpccard == NULL) - { - return HAL_ERROR; - } - - if(hpccard->State == HAL_PCCARD_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hpccard->Lock = HAL_UNLOCKED; -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) - if(hpccard->MspInitCallback == NULL) - { - hpccard->MspInitCallback = HAL_PCCARD_MspInit; - } - hpccard->ItCallback = HAL_PCCARD_ITCallback; - - /* Init the low level hardware */ - hpccard->MspInitCallback(hpccard); -#else - /* Initialize the low level hardware (MSP) */ - HAL_PCCARD_MspInit(hpccard); -#endif - } - - /* Initialize the PCCARD state */ - hpccard->State = HAL_PCCARD_STATE_BUSY; - - /* Initialize PCCARD control Interface */ - FMC_PCCARD_Init(hpccard->Instance, &(hpccard->Init)); - - /* Init PCCARD common space timing Interface */ - FMC_PCCARD_CommonSpace_Timing_Init(hpccard->Instance, ComSpaceTiming); - - /* Init PCCARD attribute space timing Interface */ - FMC_PCCARD_AttributeSpace_Timing_Init(hpccard->Instance, AttSpaceTiming); - - /* Init PCCARD IO space timing Interface */ - FMC_PCCARD_IOSpace_Timing_Init(hpccard->Instance, IOSpaceTiming); - - /* Enable the PCCARD device */ - __FMC_PCCARD_ENABLE(hpccard->Instance); - - /* Update the PCCARD state */ - hpccard->State = HAL_PCCARD_STATE_READY; - - return HAL_OK; - -} - -/** - * @brief Perform the PCCARD memory De-initialization sequence - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCCARD_DeInit(PCCARD_HandleTypeDef *hpccard) -{ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) - if(hpccard->MspDeInitCallback == NULL) - { - hpccard->MspDeInitCallback = HAL_PCCARD_MspDeInit; - } - - /* DeInit the low level hardware */ - hpccard->MspDeInitCallback(hpccard); -#else - /* De-Initialize the low level hardware (MSP) */ - HAL_PCCARD_MspDeInit(hpccard); -#endif - - /* Configure the PCCARD registers with their reset values */ - FMC_PCCARD_DeInit(hpccard->Instance); - - /* Update the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hpccard); - - return HAL_OK; -} - -/** - * @brief PCCARD MSP Init - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval None - */ -__weak void HAL_PCCARD_MspInit(PCCARD_HandleTypeDef *hpccard) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpccard); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_PCCARD_MspInit could be implemented in the user file - */ -} - -/** - * @brief PCCARD MSP DeInit - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval None - */ -__weak void HAL_PCCARD_MspDeInit(PCCARD_HandleTypeDef *hpccard) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpccard); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_PCCARD_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup PCCARD_Exported_Functions_Group2 Input and Output functions - * @brief Input Output and memory control functions - * - @verbatim - ============================================================================== - ##### PCCARD Input and Output functions ##### - ============================================================================== - [..] - This section provides functions allowing to use and control the PCCARD memory - -@endverbatim - * @{ - */ - -/** - * @brief Read Compact Flash's ID. - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @param CompactFlash_ID Compact flash ID structure. - * @param pStatus pointer to compact flash status - * @retval HAL status - * - */ -HAL_StatusTypeDef HAL_PCCARD_Read_ID(PCCARD_HandleTypeDef *hpccard, uint8_t CompactFlash_ID[], uint8_t *pStatus) -{ - uint32_t timeout = PCCARD_TIMEOUT_READ_ID, index = 0U; - uint8_t status = 0; - - /* Process Locked */ - __HAL_LOCK(hpccard); - - /* Check the PCCARD controller state */ - if(hpccard->State == HAL_PCCARD_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_BUSY; - - /* Initialize the PCCARD status */ - *pStatus = PCCARD_READY; - - /* Send the Identify Command */ - *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD) = 0xECEC; - - /* Read PCCARD IDs and timeout treatment */ - do - { - /* Read the PCCARD status */ - status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - - timeout--; - }while((status != PCCARD_STATUS_OK) && timeout); - - if(timeout == 0U) - { - *pStatus = PCCARD_TIMEOUT_ERROR; - } - else - { - /* Read PCCARD ID bytes */ - for(index = 0U; index < 16U; index++) - { - CompactFlash_ID[index] = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_DATA); - } - } - - /* Update the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hpccard); - - return HAL_OK; -} - -/** - * @brief Read sector from PCCARD memory - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @param pBuffer pointer to destination read buffer - * @param SectorAddress Sector address to read - * @param pStatus pointer to PCCARD status - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCCARD_Read_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t *pBuffer, uint16_t SectorAddress, uint8_t *pStatus) -{ - uint32_t timeout = PCCARD_TIMEOUT_READ_WRITE_SECTOR, index = 0U; - uint8_t status = 0; - - /* Process Locked */ - __HAL_LOCK(hpccard); - - /* Check the PCCARD controller state */ - if(hpccard->State == HAL_PCCARD_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_BUSY; - - /* Initialize PCCARD status */ - *pStatus = PCCARD_READY; - - /* Set the parameters to write a sector */ - *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CYLINDER_HIGH) = (uint16_t)0x00; - *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_SECTOR_COUNT) = ((uint16_t)0x0100) | ((uint16_t)SectorAddress); - *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD) = (uint16_t)0xE4A0; - - do - { - /* wait till the Status = 0x80 */ - status = *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - timeout--; - }while((status == 0x80) && timeout); - - if(timeout == 0U) - { - *pStatus = PCCARD_TIMEOUT_ERROR; - } - - timeout = PCCARD_TIMEOUT_READ_WRITE_SECTOR; - - do - { - /* wait till the Status = PCCARD_STATUS_OK */ - status = *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - timeout--; - }while((status != PCCARD_STATUS_OK) && timeout); - - if(timeout == 0U) - { - *pStatus = PCCARD_TIMEOUT_ERROR; - } - - /* Read bytes */ - for(; index < PCCARD_SECTOR_SIZE; index++) - { - *(uint16_t *)pBuffer++ = *(uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR); - } - - /* Update the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hpccard); - - return HAL_OK; -} - - -/** - * @brief Write sector to PCCARD memory - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @param pBuffer pointer to source write buffer - * @param SectorAddress Sector address to write - * @param pStatus pointer to PCCARD status - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCCARD_Write_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t *pBuffer, uint16_t SectorAddress, uint8_t *pStatus) -{ - uint32_t timeout = PCCARD_TIMEOUT_READ_WRITE_SECTOR, index = 0U; - uint8_t status = 0; - - /* Process Locked */ - __HAL_LOCK(hpccard); - - /* Check the PCCARD controller state */ - if(hpccard->State == HAL_PCCARD_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_BUSY; - - /* Initialize PCCARD status */ - *pStatus = PCCARD_READY; - - /* Set the parameters to write a sector */ - *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CYLINDER_HIGH) = (uint16_t)0x00; - *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_SECTOR_COUNT) = ((uint16_t)0x0100) | ((uint16_t)SectorAddress); - *(__IO uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD) = (uint16_t)0x30A0; - - do - { - /* Wait till the Status = PCCARD_STATUS_OK */ - status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - timeout--; - }while((status != PCCARD_STATUS_OK) && timeout); - - if(timeout == 0U) - { - *pStatus = PCCARD_TIMEOUT_ERROR; - } - - /* Write bytes */ - for(; index < PCCARD_SECTOR_SIZE; index++) - { - *(uint16_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR) = *(uint16_t *)pBuffer++; - } - - do - { - /* Wait till the Status = PCCARD_STATUS_WRITE_OK */ - status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - timeout--; - }while((status != PCCARD_STATUS_WRITE_OK) && timeout); - - if(timeout == 0U) - { - *pStatus = PCCARD_TIMEOUT_ERROR; - } - - /* Update the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hpccard); - - return HAL_OK; -} - - -/** - * @brief Erase sector from PCCARD memory - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @param SectorAddress Sector address to erase - * @param pStatus pointer to PCCARD status - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCCARD_Erase_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t SectorAddress, uint8_t *pStatus) -{ - uint32_t timeout = PCCARD_TIMEOUT_ERASE_SECTOR; - uint8_t status = 0; - - /* Process Locked */ - __HAL_LOCK(hpccard); - - /* Check the PCCARD controller state */ - if(hpccard->State == HAL_PCCARD_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_BUSY; - - /* Initialize PCCARD status */ - *pStatus = PCCARD_READY; - - /* Set the parameters to write a sector */ - *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CYLINDER_LOW) = 0x00; - *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CYLINDER_HIGH) = 0x00; - *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_SECTOR_NUMBER) = SectorAddress; - *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_SECTOR_COUNT) = 0x01; - *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_CARD_HEAD) = 0xA0; - *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD) = ATA_ERASE_SECTOR_CMD; - - /* wait till the PCCARD is ready */ - status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - - while((status != PCCARD_STATUS_WRITE_OK) && timeout) - { - status = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - timeout--; - } - - if(timeout == 0U) - { - *pStatus = PCCARD_TIMEOUT_ERROR; - } - - /* Check the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hpccard); - - return HAL_OK; -} - -/** - * @brief Reset the PCCARD memory - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCCARD_Reset(PCCARD_HandleTypeDef *hpccard) -{ - /* Process Locked */ - __HAL_LOCK(hpccard); - - /* Check the PCCARD controller state */ - if(hpccard->State == HAL_PCCARD_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Provide a SW reset and Read and verify the: - - PCCard Configuration Option Register at address 0x98000200 --> 0x80 - - Card Configuration and Status Register at address 0x98000202 --> 0x00 - - Pin Replacement Register at address 0x98000204 --> 0x0C - - Socket and Copy Register at address 0x98000206 --> 0x00 - */ - - /* Check the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_BUSY; - - *(__IO uint8_t *)(PCCARD_ATTRIBUTE_SPACE_ADDRESS | ATA_CARD_CONFIGURATION ) = 0x01; - - /* Check the PCCARD controller state */ - hpccard->State = HAL_PCCARD_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hpccard); - - return HAL_OK; -} - -/** - * @brief This function handles PCCARD device interrupt request. - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval HAL status -*/ -void HAL_PCCARD_IRQHandler(PCCARD_HandleTypeDef *hpccard) -{ - /* Check PCCARD interrupt Rising edge flag */ - if(__FMC_PCCARD_GET_FLAG(hpccard->Instance, FMC_FLAG_RISING_EDGE)) - { - /* PCCARD interrupt callback*/ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) - hpccard->ItCallback(hpccard); -#else - HAL_PCCARD_ITCallback(hpccard); -#endif - - /* Clear PCCARD interrupt Rising edge pending bit */ - __FMC_PCCARD_CLEAR_FLAG(hpccard->Instance, FMC_FLAG_RISING_EDGE); - } - - /* Check PCCARD interrupt Level flag */ - if(__FMC_PCCARD_GET_FLAG(hpccard->Instance, FMC_FLAG_LEVEL)) - { - /* PCCARD interrupt callback*/ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) - hpccard->ItCallback(hpccard); -#else - HAL_PCCARD_ITCallback(hpccard); -#endif - - /* Clear PCCARD interrupt Level pending bit */ - __FMC_PCCARD_CLEAR_FLAG(hpccard->Instance, FMC_FLAG_LEVEL); - } - - /* Check PCCARD interrupt Falling edge flag */ - if(__FMC_PCCARD_GET_FLAG(hpccard->Instance, FMC_FLAG_FALLING_EDGE)) - { - /* PCCARD interrupt callback*/ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) - hpccard->ItCallback(hpccard); -#else - HAL_PCCARD_ITCallback(hpccard); -#endif - - /* Clear PCCARD interrupt Falling edge pending bit */ - __FMC_PCCARD_CLEAR_FLAG(hpccard->Instance, FMC_FLAG_FALLING_EDGE); - } - - /* Check PCCARD interrupt FIFO empty flag */ - if(__FMC_PCCARD_GET_FLAG(hpccard->Instance, FMC_FLAG_FEMPT)) - { - /* PCCARD interrupt callback*/ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) - hpccard->ItCallback(hpccard); -#else - HAL_PCCARD_ITCallback(hpccard); -#endif - - /* Clear PCCARD interrupt FIFO empty pending bit */ - __FMC_PCCARD_CLEAR_FLAG(hpccard->Instance, FMC_FLAG_FEMPT); - } -} - -/** - * @brief PCCARD interrupt feature callback - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval None - */ -__weak void HAL_PCCARD_ITCallback(PCCARD_HandleTypeDef *hpccard) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpccard); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_PCCARD_ITCallback could be implemented in the user file - */ -} - -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User PCCARD Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hpccard : PCCARD handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_PCCARD_MSP_INIT_CB_ID PCCARD MspInit callback ID - * @arg @ref HAL_PCCARD_MSP_DEINIT_CB_ID PCCARD MspDeInit callback ID - * @arg @ref HAL_PCCARD_IT_CB_ID PCCARD IT callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_PCCARD_RegisterCallback (PCCARD_HandleTypeDef *hpccard, HAL_PCCARD_CallbackIDTypeDef CallbackId, pPCCARD_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpccard); - - if(hpccard->State == HAL_PCCARD_STATE_READY) - { - switch (CallbackId) - { - case HAL_PCCARD_MSP_INIT_CB_ID : - hpccard->MspInitCallback = pCallback; - break; - case HAL_PCCARD_MSP_DEINIT_CB_ID : - hpccard->MspDeInitCallback = pCallback; - break; - case HAL_PCCARD_IT_CB_ID : - hpccard->ItCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(hpccard->State == HAL_PCCARD_STATE_RESET) - { - switch (CallbackId) - { - case HAL_PCCARD_MSP_INIT_CB_ID : - hpccard->MspInitCallback = pCallback; - break; - case HAL_PCCARD_MSP_DEINIT_CB_ID : - hpccard->MspDeInitCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpccard); - return status; -} - -/** - * @brief Unregister a User PCCARD Callback - * PCCARD Callback is redirected to the weak (surcharged) predefined callback - * @param hpccard : PCCARD handle - * @param CallbackId : ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_PCCARD_MSP_INIT_CB_ID PCCARD MspInit callback ID - * @arg @ref HAL_PCCARD_MSP_DEINIT_CB_ID PCCARD MspDeInit callback ID - * @arg @ref HAL_PCCARD_IT_CB_ID PCCARD IT callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_PCCARD_UnRegisterCallback (PCCARD_HandleTypeDef *hpccard, HAL_PCCARD_CallbackIDTypeDef CallbackId) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpccard); - - if(hpccard->State == HAL_PCCARD_STATE_READY) - { - switch (CallbackId) - { - case HAL_PCCARD_MSP_INIT_CB_ID : - hpccard->MspInitCallback = HAL_PCCARD_MspInit; - break; - case HAL_PCCARD_MSP_DEINIT_CB_ID : - hpccard->MspDeInitCallback = HAL_PCCARD_MspDeInit; - break; - case HAL_PCCARD_IT_CB_ID : - hpccard->ItCallback = HAL_PCCARD_ITCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(hpccard->State == HAL_PCCARD_STATE_RESET) - { - switch (CallbackId) - { - case HAL_PCCARD_MSP_INIT_CB_ID : - hpccard->MspInitCallback = HAL_PCCARD_MspInit; - break; - case HAL_PCCARD_MSP_DEINIT_CB_ID : - hpccard->MspDeInitCallback = HAL_PCCARD_MspDeInit; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpccard); - return status; -} -#endif - -/** - * @} - */ - -/** @defgroup PCCARD_Exported_Functions_Group3 State functions - * @brief Peripheral State functions - * -@verbatim - ============================================================================== - ##### PCCARD State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the PCCARD controller - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief return the PCCARD controller state - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval HAL state - */ -HAL_PCCARD_StateTypeDef HAL_PCCARD_GetState(PCCARD_HandleTypeDef *hpccard) -{ - return hpccard->State; -} - -/** - * @brief Get the compact flash memory status - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval New status of the PCCARD operation. This parameter can be: - * - CompactFlash_TIMEOUT_ERROR: when the previous operation generate - * a Timeout error - * - CompactFlash_READY: when memory is ready for the next operation - */ -HAL_PCCARD_StatusTypeDef HAL_PCCARD_GetStatus(PCCARD_HandleTypeDef *hpccard) -{ - uint32_t timeout = PCCARD_TIMEOUT_STATUS, status_pccard = 0U; - - /* Check the PCCARD controller state */ - if(hpccard->State == HAL_PCCARD_STATE_BUSY) - { - return HAL_PCCARD_STATUS_ONGOING; - } - - status_pccard = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - - while((status_pccard == PCCARD_BUSY) && timeout) - { - status_pccard = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - timeout--; - } - - if(timeout == 0U) - { - status_pccard = PCCARD_TIMEOUT_ERROR; - } - - /* Return the operation status */ - return (HAL_PCCARD_StatusTypeDef) status_pccard; -} - -/** - * @brief Reads the Compact Flash memory status using the Read status command - * @param hpccard pointer to a PCCARD_HandleTypeDef structure that contains - * the configuration information for PCCARD module. - * @retval The status of the Compact Flash memory. This parameter can be: - * - CompactFlash_BUSY: when memory is busy - * - CompactFlash_READY: when memory is ready for the next operation - * - CompactFlash_ERROR: when the previous operation generates error - */ -HAL_PCCARD_StatusTypeDef HAL_PCCARD_ReadStatus(PCCARD_HandleTypeDef *hpccard) -{ - uint8_t data = 0U, status_pccard = PCCARD_BUSY; - - /* Check the PCCARD controller state */ - if(hpccard->State == HAL_PCCARD_STATE_BUSY) - { - return HAL_PCCARD_STATUS_ONGOING; - } - - /* Read status operation */ - data = *(__IO uint8_t *)(PCCARD_IO_SPACE_PRIMARY_ADDR | ATA_STATUS_CMD_ALTERNATE); - - if((data & PCCARD_TIMEOUT_ERROR) == PCCARD_TIMEOUT_ERROR) - { - status_pccard = PCCARD_TIMEOUT_ERROR; - } - else if((data & PCCARD_READY) == PCCARD_READY) - { - status_pccard = PCCARD_READY; - } - - return (HAL_PCCARD_StatusTypeDef) status_pccard; -} - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ - STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ -#endif /* HAL_PCCARD_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c deleted file mode 100644 index aa9702eed3f93bc..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd.c +++ /dev/null @@ -1,2258 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd.c - * @author MCD Application Team - * @brief PCD HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the USB Peripheral Controller: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The PCD HAL driver can be used as follows: - - (#) Declare a PCD_HandleTypeDef handle structure, for example: - PCD_HandleTypeDef hpcd; - - (#) Fill parameters of Init structure in HCD handle - - (#) Call HAL_PCD_Init() API to initialize the PCD peripheral (Core, Device core, ...) - - (#) Initialize the PCD low level resources through the HAL_PCD_MspInit() API: - (##) Enable the PCD/USB Low Level interface clock using - (+++) __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - (+++) __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); (For High Speed Mode) - - (##) Initialize the related GPIO clocks - (##) Configure PCD pin-out - (##) Configure PCD NVIC interrupt - - (#)Associate the Upper USB device stack to the HAL PCD Driver: - (##) hpcd.pData = pdev; - - (#)Enable PCD transmission and reception: - (##) HAL_PCD_Start(); - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup PCD PCD - * @brief PCD HAL module driver - * @{ - */ - -#ifdef HAL_PCD_MODULE_ENABLED - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PCD_Private_Macros PCD Private Macros - * @{ - */ -#define PCD_MIN(a, b) (((a) < (b)) ? (a) : (b)) -#define PCD_MAX(a, b) (((a) > (b)) ? (a) : (b)) -/** - * @} - */ - -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup PCD_Private_Functions PCD Private Functions - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum); -static HAL_StatusTypeDef PCD_EP_OutXfrComplete_int(PCD_HandleTypeDef *hpcd, uint32_t epnum); -static HAL_StatusTypeDef PCD_EP_OutSetupPacket_int(PCD_HandleTypeDef *hpcd, uint32_t epnum); -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup PCD_Exported_Functions PCD Exported Functions - * @{ - */ - -/** @defgroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to: - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the PCD according to the specified - * parameters in the PCD_InitTypeDef and initialize the associated handle. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx; - uint8_t i; - - /* Check the PCD handle allocation */ - if (hpcd == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_PCD_ALL_INSTANCE(hpcd->Instance)); - - USBx = hpcd->Instance; - - if (hpcd->State == HAL_PCD_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hpcd->Lock = HAL_UNLOCKED; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SOFCallback = HAL_PCD_SOFCallback; - hpcd->SetupStageCallback = HAL_PCD_SetupStageCallback; - hpcd->ResetCallback = HAL_PCD_ResetCallback; - hpcd->SuspendCallback = HAL_PCD_SuspendCallback; - hpcd->ResumeCallback = HAL_PCD_ResumeCallback; - hpcd->ConnectCallback = HAL_PCD_ConnectCallback; - hpcd->DisconnectCallback = HAL_PCD_DisconnectCallback; - hpcd->DataOutStageCallback = HAL_PCD_DataOutStageCallback; - hpcd->DataInStageCallback = HAL_PCD_DataInStageCallback; - hpcd->ISOOUTIncompleteCallback = HAL_PCD_ISOOUTIncompleteCallback; - hpcd->ISOINIncompleteCallback = HAL_PCD_ISOINIncompleteCallback; - hpcd->LPMCallback = HAL_PCDEx_LPM_Callback; - hpcd->BCDCallback = HAL_PCDEx_BCD_Callback; - - if (hpcd->MspInitCallback == NULL) - { - hpcd->MspInitCallback = HAL_PCD_MspInit; - } - - /* Init the low level hardware */ - hpcd->MspInitCallback(hpcd); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC... */ - HAL_PCD_MspInit(hpcd); -#endif /* (USE_HAL_PCD_REGISTER_CALLBACKS) */ - } - - hpcd->State = HAL_PCD_STATE_BUSY; - - /* Disable DMA mode for FS instance */ - if ((USBx->CID & (0x1U << 8)) == 0U) - { - hpcd->Init.dma_enable = 0U; - } - - /* Disable the Interrupts */ - __HAL_PCD_DISABLE(hpcd); - - /*Init the Core (common init.) */ - if (USB_CoreInit(hpcd->Instance, hpcd->Init) != HAL_OK) - { - hpcd->State = HAL_PCD_STATE_ERROR; - return HAL_ERROR; - } - - /* Force Device Mode*/ - (void)USB_SetCurrentMode(hpcd->Instance, USB_DEVICE_MODE); - - /* Init endpoints structures */ - for (i = 0U; i < hpcd->Init.dev_endpoints; i++) - { - /* Init ep structure */ - hpcd->IN_ep[i].is_in = 1U; - hpcd->IN_ep[i].num = i; - hpcd->IN_ep[i].tx_fifo_num = i; - /* Control until ep is activated */ - hpcd->IN_ep[i].type = EP_TYPE_CTRL; - hpcd->IN_ep[i].maxpacket = 0U; - hpcd->IN_ep[i].xfer_buff = 0U; - hpcd->IN_ep[i].xfer_len = 0U; - } - - for (i = 0U; i < hpcd->Init.dev_endpoints; i++) - { - hpcd->OUT_ep[i].is_in = 0U; - hpcd->OUT_ep[i].num = i; - /* Control until ep is activated */ - hpcd->OUT_ep[i].type = EP_TYPE_CTRL; - hpcd->OUT_ep[i].maxpacket = 0U; - hpcd->OUT_ep[i].xfer_buff = 0U; - hpcd->OUT_ep[i].xfer_len = 0U; - } - - /* Init Device */ - if (USB_DevInit(hpcd->Instance, hpcd->Init) != HAL_OK) - { - hpcd->State = HAL_PCD_STATE_ERROR; - return HAL_ERROR; - } - - hpcd->USB_Address = 0U; - hpcd->State = HAL_PCD_STATE_READY; -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Activate LPM */ - if (hpcd->Init.lpm_enable == 1U) - { - (void)HAL_PCDEx_ActivateLPM(hpcd); - } -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ - (void)USB_DevDisconnect(hpcd->Instance); - - return HAL_OK; -} - -/** - * @brief DeInitializes the PCD peripheral. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd) -{ - /* Check the PCD handle allocation */ - if (hpcd == NULL) - { - return HAL_ERROR; - } - - hpcd->State = HAL_PCD_STATE_BUSY; - - /* Stop Device */ - if (USB_StopDevice(hpcd->Instance) != HAL_OK) - { - return HAL_ERROR; - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - if (hpcd->MspDeInitCallback == NULL) - { - hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware */ - hpcd->MspDeInitCallback(hpcd); -#else - /* DeInit the low level hardware: CLOCK, NVIC.*/ - HAL_PCD_MspDeInit(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - hpcd->State = HAL_PCD_STATE_RESET; - - return HAL_OK; -} - -/** - * @brief Initializes the PCD MSP. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes PCD MSP. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -/** - * @brief Register a User USB PCD Callback - * To be used instead of the weak predefined callback - * @param hpcd USB PCD handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_PCD_SOF_CB_ID USB PCD SOF callback ID - * @arg @ref HAL_PCD_SETUPSTAGE_CB_ID USB PCD Setup callback ID - * @arg @ref HAL_PCD_RESET_CB_ID USB PCD Reset callback ID - * @arg @ref HAL_PCD_SUSPEND_CB_ID USB PCD Suspend callback ID - * @arg @ref HAL_PCD_RESUME_CB_ID USB PCD Resume callback ID - * @arg @ref HAL_PCD_CONNECT_CB_ID USB PCD Connect callback ID - * @arg @ref HAL_PCD_DISCONNECT_CB_ID OTG PCD Disconnect callback ID - * @arg @ref HAL_PCD_MSPINIT_CB_ID MspDeInit callback ID - * @arg @ref HAL_PCD_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterCallback(PCD_HandleTypeDef *hpcd, - HAL_PCD_CallbackIDTypeDef CallbackID, - pPCD_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - switch (CallbackID) - { - case HAL_PCD_SOF_CB_ID : - hpcd->SOFCallback = pCallback; - break; - - case HAL_PCD_SETUPSTAGE_CB_ID : - hpcd->SetupStageCallback = pCallback; - break; - - case HAL_PCD_RESET_CB_ID : - hpcd->ResetCallback = pCallback; - break; - - case HAL_PCD_SUSPEND_CB_ID : - hpcd->SuspendCallback = pCallback; - break; - - case HAL_PCD_RESUME_CB_ID : - hpcd->ResumeCallback = pCallback; - break; - - case HAL_PCD_CONNECT_CB_ID : - hpcd->ConnectCallback = pCallback; - break; - - case HAL_PCD_DISCONNECT_CB_ID : - hpcd->DisconnectCallback = pCallback; - break; - - case HAL_PCD_MSPINIT_CB_ID : - hpcd->MspInitCallback = pCallback; - break; - - case HAL_PCD_MSPDEINIT_CB_ID : - hpcd->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hpcd->State == HAL_PCD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_PCD_MSPINIT_CB_ID : - hpcd->MspInitCallback = pCallback; - break; - - case HAL_PCD_MSPDEINIT_CB_ID : - hpcd->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - return status; -} - -/** - * @brief Unregister an USB PCD Callback - * USB PCD callabck is redirected to the weak predefined callback - * @param hpcd USB PCD handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_PCD_SOF_CB_ID USB PCD SOF callback ID - * @arg @ref HAL_PCD_SETUPSTAGE_CB_ID USB PCD Setup callback ID - * @arg @ref HAL_PCD_RESET_CB_ID USB PCD Reset callback ID - * @arg @ref HAL_PCD_SUSPEND_CB_ID USB PCD Suspend callback ID - * @arg @ref HAL_PCD_RESUME_CB_ID USB PCD Resume callback ID - * @arg @ref HAL_PCD_CONNECT_CB_ID USB PCD Connect callback ID - * @arg @ref HAL_PCD_DISCONNECT_CB_ID OTG PCD Disconnect callback ID - * @arg @ref HAL_PCD_MSPINIT_CB_ID MspDeInit callback ID - * @arg @ref HAL_PCD_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterCallback(PCD_HandleTypeDef *hpcd, HAL_PCD_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - /* Setup Legacy weak Callbacks */ - if (hpcd->State == HAL_PCD_STATE_READY) - { - switch (CallbackID) - { - case HAL_PCD_SOF_CB_ID : - hpcd->SOFCallback = HAL_PCD_SOFCallback; - break; - - case HAL_PCD_SETUPSTAGE_CB_ID : - hpcd->SetupStageCallback = HAL_PCD_SetupStageCallback; - break; - - case HAL_PCD_RESET_CB_ID : - hpcd->ResetCallback = HAL_PCD_ResetCallback; - break; - - case HAL_PCD_SUSPEND_CB_ID : - hpcd->SuspendCallback = HAL_PCD_SuspendCallback; - break; - - case HAL_PCD_RESUME_CB_ID : - hpcd->ResumeCallback = HAL_PCD_ResumeCallback; - break; - - case HAL_PCD_CONNECT_CB_ID : - hpcd->ConnectCallback = HAL_PCD_ConnectCallback; - break; - - case HAL_PCD_DISCONNECT_CB_ID : - hpcd->DisconnectCallback = HAL_PCD_DisconnectCallback; - break; - - case HAL_PCD_MSPINIT_CB_ID : - hpcd->MspInitCallback = HAL_PCD_MspInit; - break; - - case HAL_PCD_MSPDEINIT_CB_ID : - hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; - break; - - default : - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hpcd->State == HAL_PCD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_PCD_MSPINIT_CB_ID : - hpcd->MspInitCallback = HAL_PCD_MspInit; - break; - - case HAL_PCD_MSPDEINIT_CB_ID : - hpcd->MspDeInitCallback = HAL_PCD_MspDeInit; - break; - - default : - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - return status; -} - -/** - * @brief Register USB PCD Data OUT Stage Callback - * To be used instead of the weak HAL_PCD_DataOutStageCallback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD Data OUT Stage Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataOutStageCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->DataOutStageCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD Data OUT Stage Callback - * USB PCD Data OUT Stage Callback is redirected to the weak HAL_PCD_DataOutStageCallback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->DataOutStageCallback = HAL_PCD_DataOutStageCallback; /* Legacy weak DataOutStageCallback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD Data IN Stage Callback - * To be used instead of the weak HAL_PCD_DataInStageCallback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD Data IN Stage Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterDataInStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataInStageCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->DataInStageCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD Data IN Stage Callback - * USB PCD Data OUT Stage Callback is redirected to the weak HAL_PCD_DataInStageCallback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterDataInStageCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->DataInStageCallback = HAL_PCD_DataInStageCallback; /* Legacy weak DataInStageCallback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD Iso OUT incomplete Callback - * To be used instead of the weak HAL_PCD_ISOOUTIncompleteCallback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD Iso OUT incomplete Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoOutIncpltCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->ISOOUTIncompleteCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD Iso OUT incomplete Callback - * USB PCD Iso OUT incomplete Callback is redirected - * to the weak HAL_PCD_ISOOUTIncompleteCallback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->ISOOUTIncompleteCallback = HAL_PCD_ISOOUTIncompleteCallback; /* Legacy weak ISOOUTIncompleteCallback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD Iso IN incomplete Callback - * To be used instead of the weak HAL_PCD_ISOINIncompleteCallback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD Iso IN incomplete Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoInIncpltCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->ISOINIncompleteCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD Iso IN incomplete Callback - * USB PCD Iso IN incomplete Callback is redirected - * to the weak HAL_PCD_ISOINIncompleteCallback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->ISOINIncompleteCallback = HAL_PCD_ISOINIncompleteCallback; /* Legacy weak ISOINIncompleteCallback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD BCD Callback - * To be used instead of the weak HAL_PCDEx_BCD_Callback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD BCD Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterBcdCallback(PCD_HandleTypeDef *hpcd, pPCD_BcdCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->BCDCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD BCD Callback - * USB BCD Callback is redirected to the weak HAL_PCDEx_BCD_Callback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterBcdCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->BCDCallback = HAL_PCDEx_BCD_Callback; /* Legacy weak HAL_PCDEx_BCD_Callback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Register USB PCD LPM Callback - * To be used instead of the weak HAL_PCDEx_LPM_Callback() predefined callback - * @param hpcd PCD handle - * @param pCallback pointer to the USB PCD LPM Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_RegisterLpmCallback(PCD_HandleTypeDef *hpcd, pPCD_LpmCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->LPMCallback = pCallback; - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} - -/** - * @brief Unregister the USB PCD LPM Callback - * USB LPM Callback is redirected to the weak HAL_PCDEx_LPM_Callback() predefined callback - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_UnRegisterLpmCallback(PCD_HandleTypeDef *hpcd) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hpcd); - - if (hpcd->State == HAL_PCD_STATE_READY) - { - hpcd->LPMCallback = HAL_PCDEx_LPM_Callback; /* Legacy weak HAL_PCDEx_LPM_Callback */ - } - else - { - /* Update the error code */ - hpcd->ErrorCode |= HAL_PCD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hpcd); - - return status; -} -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup PCD_Exported_Functions_Group2 Input and Output operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the PCD data - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Start the USB device - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - __HAL_LOCK(hpcd); - - if ((hpcd->Init.battery_charging_enable == 1U) && - (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) - { - /* Enable USB Transceiver */ - USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; - } - - __HAL_PCD_ENABLE(hpcd); - (void)USB_DevConnect(hpcd->Instance); - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Stop the USB device. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - __HAL_LOCK(hpcd); - __HAL_PCD_DISABLE(hpcd); - (void)USB_DevDisconnect(hpcd->Instance); - - (void)USB_FlushTxFifo(hpcd->Instance, 0x10U); - - if ((hpcd->Init.battery_charging_enable == 1U) && - (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) - { - /* Disable USB Transceiver */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - } - - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** - * @brief Handles PCD interrupt request. - * @param hpcd PCD handle - * @retval HAL status - */ -void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - USB_OTG_EPTypeDef *ep; - uint32_t i; - uint32_t ep_intr; - uint32_t epint; - uint32_t epnum; - uint32_t fifoemptymsk; - uint32_t temp; - - /* ensure that we are in device mode */ - if (USB_GetMode(hpcd->Instance) == USB_OTG_MODE_DEVICE) - { - /* avoid spurious interrupt */ - if (__HAL_PCD_IS_INVALID_INTERRUPT(hpcd)) - { - return; - } - - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_MMIS)) - { - /* incorrect mode, acknowledge the interrupt */ - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_MMIS); - } - - /* Handle RxQLevel Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_RXFLVL)) - { - USB_MASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL); - - temp = USBx->GRXSTSP; - - ep = &hpcd->OUT_ep[temp & USB_OTG_GRXSTSP_EPNUM]; - - if (((temp & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_DATA_UPDT) - { - if ((temp & USB_OTG_GRXSTSP_BCNT) != 0U) - { - (void)USB_ReadPacket(USBx, ep->xfer_buff, - (uint16_t)((temp & USB_OTG_GRXSTSP_BCNT) >> 4)); - - ep->xfer_buff += (temp & USB_OTG_GRXSTSP_BCNT) >> 4; - ep->xfer_count += (temp & USB_OTG_GRXSTSP_BCNT) >> 4; - } - } - else if (((temp & USB_OTG_GRXSTSP_PKTSTS) >> 17) == STS_SETUP_UPDT) - { - (void)USB_ReadPacket(USBx, (uint8_t *)hpcd->Setup, 8U); - ep->xfer_count += (temp & USB_OTG_GRXSTSP_BCNT) >> 4; - } - else - { - /* ... */ - } - USB_UNMASK_INTERRUPT(hpcd->Instance, USB_OTG_GINTSTS_RXFLVL); - } - - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OEPINT)) - { - epnum = 0U; - - /* Read in the device interrupt bits */ - ep_intr = USB_ReadDevAllOutEpInterrupt(hpcd->Instance); - - while (ep_intr != 0U) - { - if ((ep_intr & 0x1U) != 0U) - { - epint = USB_ReadDevOutEPInterrupt(hpcd->Instance, (uint8_t)epnum); - - if ((epint & USB_OTG_DOEPINT_XFRC) == USB_OTG_DOEPINT_XFRC) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_XFRC); - (void)PCD_EP_OutXfrComplete_int(hpcd, epnum); - } - - if ((epint & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STUP); - /* Class B setup phase done for previous decoded setup */ - (void)PCD_EP_OutSetupPacket_int(hpcd, epnum); - } - - if ((epint & USB_OTG_DOEPINT_OTEPDIS) == USB_OTG_DOEPINT_OTEPDIS) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPDIS); - } - - /* Clear Status Phase Received interrupt */ - if ((epint & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); - } - - /* Clear OUT NAK interrupt */ - if ((epint & USB_OTG_DOEPINT_NAK) == USB_OTG_DOEPINT_NAK) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_NAK); - } - } - epnum++; - ep_intr >>= 1U; - } - } - - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IEPINT)) - { - /* Read in the device interrupt bits */ - ep_intr = USB_ReadDevAllInEpInterrupt(hpcd->Instance); - - epnum = 0U; - - while (ep_intr != 0U) - { - if ((ep_intr & 0x1U) != 0U) /* In ITR */ - { - epint = USB_ReadDevInEPInterrupt(hpcd->Instance, (uint8_t)epnum); - - if ((epint & USB_OTG_DIEPINT_XFRC) == USB_OTG_DIEPINT_XFRC) - { - fifoemptymsk = (uint32_t)(0x1UL << (epnum & EP_ADDR_MSK)); - USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk; - - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_XFRC); - - if (hpcd->Init.dma_enable == 1U) - { - hpcd->IN_ep[epnum].xfer_buff += hpcd->IN_ep[epnum].maxpacket; - - /* this is ZLP, so prepare EP0 for next setup */ - if ((epnum == 0U) && (hpcd->IN_ep[epnum].xfer_len == 0U)) - { - /* prepare to rx more setup packets */ - (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); - } - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DataInStageCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_DataInStageCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - if ((epint & USB_OTG_DIEPINT_TOC) == USB_OTG_DIEPINT_TOC) - { - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_TOC); - } - if ((epint & USB_OTG_DIEPINT_ITTXFE) == USB_OTG_DIEPINT_ITTXFE) - { - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_ITTXFE); - } - if ((epint & USB_OTG_DIEPINT_INEPNE) == USB_OTG_DIEPINT_INEPNE) - { - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_INEPNE); - } - if ((epint & USB_OTG_DIEPINT_EPDISD) == USB_OTG_DIEPINT_EPDISD) - { - CLEAR_IN_EP_INTR(epnum, USB_OTG_DIEPINT_EPDISD); - } - if ((epint & USB_OTG_DIEPINT_TXFE) == USB_OTG_DIEPINT_TXFE) - { - (void)PCD_WriteEmptyTxFifo(hpcd, epnum); - } - } - epnum++; - ep_intr >>= 1U; - } - } - - /* Handle Resume Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT)) - { - /* Clear the Remote Wake-up Signaling */ - USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG; - - if (hpcd->LPM_State == LPM_L1) - { - hpcd->LPM_State = LPM_L0; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->LPMCallback(hpcd, PCD_LPM_L0_ACTIVE); -#else - HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L0_ACTIVE); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ResumeCallback(hpcd); -#else - HAL_PCD_ResumeCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_WKUINT); - } - - /* Handle Suspend Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP)) - { - if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SuspendCallback(hpcd); -#else - HAL_PCD_SuspendCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBSUSP); - } -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Handle LPM Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT)) - { - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_LPMINT); - - if (hpcd->LPM_State == LPM_L0) - { - hpcd->LPM_State = LPM_L1; - hpcd->BESL = (hpcd->Instance->GLPMCFG & USB_OTG_GLPMCFG_BESL) >> 2U; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->LPMCallback(hpcd, PCD_LPM_L1_ACTIVE); -#else - HAL_PCDEx_LPM_Callback(hpcd, PCD_LPM_L1_ACTIVE); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SuspendCallback(hpcd); -#else - HAL_PCD_SuspendCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ - /* Handle Reset Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_USBRST)) - { - USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_RWUSIG; - (void)USB_FlushTxFifo(hpcd->Instance, 0x10U); - - for (i = 0U; i < hpcd->Init.dev_endpoints; i++) - { - USBx_INEP(i)->DIEPINT = 0xFB7FU; - USBx_INEP(i)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; - USBx_INEP(i)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; - USBx_OUTEP(i)->DOEPINT = 0xFB7FU; - USBx_OUTEP(i)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; - USBx_OUTEP(i)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; - } - USBx_DEVICE->DAINTMSK |= 0x10001U; - - if (hpcd->Init.use_dedicated_ep1 != 0U) - { - USBx_DEVICE->DOUTEP1MSK |= USB_OTG_DOEPMSK_STUPM | - USB_OTG_DOEPMSK_XFRCM | - USB_OTG_DOEPMSK_EPDM; - - USBx_DEVICE->DINEP1MSK |= USB_OTG_DIEPMSK_TOM | - USB_OTG_DIEPMSK_XFRCM | - USB_OTG_DIEPMSK_EPDM; - } - else - { - USBx_DEVICE->DOEPMSK |= USB_OTG_DOEPMSK_STUPM | - USB_OTG_DOEPMSK_XFRCM | - USB_OTG_DOEPMSK_EPDM | - USB_OTG_DOEPMSK_OTEPSPRM | - USB_OTG_DOEPMSK_NAKM; - - USBx_DEVICE->DIEPMSK |= USB_OTG_DIEPMSK_TOM | - USB_OTG_DIEPMSK_XFRCM | - USB_OTG_DIEPMSK_EPDM; - } - - /* Set Default Address to 0 */ - USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD; - - /* setup EP0 to receive SETUP packets */ - (void)USB_EP0_OutStart(hpcd->Instance, (uint8_t)hpcd->Init.dma_enable, - (uint8_t *)hpcd->Setup); - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_USBRST); - } - - /* Handle Enumeration done Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE)) - { - (void)USB_ActivateSetup(hpcd->Instance); - hpcd->Init.speed = USB_GetDevSpeed(hpcd->Instance); - - /* Set USB Turnaround time */ - (void)USB_SetTurnaroundTime(hpcd->Instance, - HAL_RCC_GetHCLKFreq(), - (uint8_t)hpcd->Init.speed); - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ResetCallback(hpcd); -#else - HAL_PCD_ResetCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_ENUMDNE); - } - - /* Handle SOF Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SOF)) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SOFCallback(hpcd); -#else - HAL_PCD_SOFCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SOF); - } - - /* Handle Incomplete ISO IN Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR)) - { - /* Keep application checking the corresponding Iso IN endpoint - causing the incomplete Interrupt */ - epnum = 0U; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ISOINIncompleteCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_ISOINIncompleteCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_IISOIXFR); - } - - /* Handle Incomplete ISO OUT Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT)) - { - /* Keep application checking the corresponding Iso OUT endpoint - causing the incomplete Interrupt */ - epnum = 0U; - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ISOOUTIncompleteCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_ISOOUTIncompleteCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_PXFR_INCOMPISOOUT); - } - - /* Handle Connection event Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT)) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->ConnectCallback(hpcd); -#else - HAL_PCD_ConnectCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - __HAL_PCD_CLEAR_FLAG(hpcd, USB_OTG_GINTSTS_SRQINT); - } - - /* Handle Disconnection event Interrupt */ - if (__HAL_PCD_GET_FLAG(hpcd, USB_OTG_GINTSTS_OTGINT)) - { - temp = hpcd->Instance->GOTGINT; - - if ((temp & USB_OTG_GOTGINT_SEDET) == USB_OTG_GOTGINT_SEDET) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DisconnectCallback(hpcd); -#else - HAL_PCD_DisconnectCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - hpcd->Instance->GOTGINT |= temp; - } - } -} - - -/** - * @brief Handles PCD Wakeup interrupt request. - * @param hpcd PCD handle - * @retval HAL status - */ -void HAL_PCD_WKUP_IRQHandler(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx; - - USBx = hpcd->Instance; - - if ((USBx->CID & (0x1U << 8)) == 0U) - { - /* Clear EXTI pending Bit */ - __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG(); - } - else - { - /* Clear EXTI pending Bit */ - __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG(); - } -} -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @brief Data OUT stage callback. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval None - */ -__weak void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(epnum); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_DataOutStageCallback could be implemented in the user file - */ -} - -/** - * @brief Data IN stage callback - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval None - */ -__weak void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(epnum); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_DataInStageCallback could be implemented in the user file - */ -} -/** - * @brief Setup stage callback - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_SetupStageCallback could be implemented in the user file - */ -} - -/** - * @brief USB Start Of Frame callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_SOFCallback could be implemented in the user file - */ -} - -/** - * @brief USB Reset callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ResetCallback could be implemented in the user file - */ -} - -/** - * @brief Suspend event callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_SuspendCallback could be implemented in the user file - */ -} - -/** - * @brief Resume event callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ResumeCallback could be implemented in the user file - */ -} - -/** - * @brief Incomplete ISO OUT callback. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval None - */ -__weak void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(epnum); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ISOOUTIncompleteCallback could be implemented in the user file - */ -} - -/** - * @brief Incomplete ISO IN callback. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval None - */ -__weak void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(epnum); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ISOINIncompleteCallback could be implemented in the user file - */ -} - -/** - * @brief Connection event callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_ConnectCallback could be implemented in the user file - */ -} - -/** - * @brief Disconnection event callback. - * @param hpcd PCD handle - * @retval None - */ -__weak void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCD_DisconnectCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup PCD_Exported_Functions_Group3 Peripheral Control functions - * @brief management functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the PCD data - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Connect the USB device - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - __HAL_LOCK(hpcd); - - if ((hpcd->Init.battery_charging_enable == 1U) && - (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) - { - /* Enable USB Transceiver */ - USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; - } - (void)USB_DevConnect(hpcd->Instance); - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Disconnect the USB device. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - __HAL_LOCK(hpcd); - (void)USB_DevDisconnect(hpcd->Instance); - - if ((hpcd->Init.battery_charging_enable == 1U) && - (hpcd->Init.phy_itface != USB_OTG_ULPI_PHY)) - { - /* Disable USB Transceiver */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - } - - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Set the USB Device address. - * @param hpcd PCD handle - * @param address new device address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address) -{ - __HAL_LOCK(hpcd); - hpcd->USB_Address = address; - (void)USB_SetDevAddress(hpcd->Instance, address); - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} -/** - * @brief Open and configure an endpoint. - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @param ep_mps endpoint max packet size - * @param ep_type endpoint type - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, - uint16_t ep_mps, uint8_t ep_type) -{ - HAL_StatusTypeDef ret = HAL_OK; - PCD_EPTypeDef *ep; - - if ((ep_addr & 0x80U) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 1U; - } - else - { - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 0U; - } - - ep->num = ep_addr & EP_ADDR_MSK; - ep->maxpacket = ep_mps; - ep->type = ep_type; - - if (ep->is_in != 0U) - { - /* Assign a Tx FIFO */ - ep->tx_fifo_num = ep->num; - } - /* Set initial data PID. */ - if (ep_type == EP_TYPE_BULK) - { - ep->data_pid_start = 0U; - } - - __HAL_LOCK(hpcd); - (void)USB_ActivateEndpoint(hpcd->Instance, ep); - __HAL_UNLOCK(hpcd); - - return ret; -} - -/** - * @brief Deactivate an endpoint. - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - PCD_EPTypeDef *ep; - - if ((ep_addr & 0x80U) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 1U; - } - else - { - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 0U; - } - ep->num = ep_addr & EP_ADDR_MSK; - - __HAL_LOCK(hpcd); - (void)USB_DeactivateEndpoint(hpcd->Instance, ep); - __HAL_UNLOCK(hpcd); - return HAL_OK; -} - - -/** - * @brief Receive an amount of data. - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @param pBuf pointer to the reception buffer - * @param len amount of data to be received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len) -{ - PCD_EPTypeDef *ep; - - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - - /*setup and start the Xfer */ - ep->xfer_buff = pBuf; - ep->xfer_len = len; - ep->xfer_count = 0U; - ep->is_in = 0U; - ep->num = ep_addr & EP_ADDR_MSK; - - if (hpcd->Init.dma_enable == 1U) - { - ep->dma_addr = (uint32_t)pBuf; - } - - if ((ep_addr & EP_ADDR_MSK) == 0U) - { - (void)USB_EP0StartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); - } - else - { - (void)USB_EPStartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); - } - - return HAL_OK; -} - -/** - * @brief Get Received Data Size - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval Data Size - */ -uint32_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - return hpcd->OUT_ep[ep_addr & EP_ADDR_MSK].xfer_count; -} -/** - * @brief Send an amount of data - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @param pBuf pointer to the transmission buffer - * @param len amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, uint8_t *pBuf, uint32_t len) -{ - PCD_EPTypeDef *ep; - - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - - /*setup and start the Xfer */ - ep->xfer_buff = pBuf; - ep->xfer_len = len; - ep->xfer_count = 0U; - ep->is_in = 1U; - ep->num = ep_addr & EP_ADDR_MSK; - - if (hpcd->Init.dma_enable == 1U) - { - ep->dma_addr = (uint32_t)pBuf; - } - - if ((ep_addr & EP_ADDR_MSK) == 0U) - { - (void)USB_EP0StartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); - } - else - { - (void)USB_EPStartXfer(hpcd->Instance, ep, (uint8_t)hpcd->Init.dma_enable); - } - - return HAL_OK; -} - -/** - * @brief Set a STALL condition over an endpoint - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - PCD_EPTypeDef *ep; - - if (((uint32_t)ep_addr & EP_ADDR_MSK) > hpcd->Init.dev_endpoints) - { - return HAL_ERROR; - } - - if ((0x80U & ep_addr) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 1U; - } - else - { - ep = &hpcd->OUT_ep[ep_addr]; - ep->is_in = 0U; - } - - ep->is_stall = 1U; - ep->num = ep_addr & EP_ADDR_MSK; - - __HAL_LOCK(hpcd); - - (void)USB_EPSetStall(hpcd->Instance, ep); - - if ((ep_addr & EP_ADDR_MSK) == 0U) - { - (void)USB_EP0_OutStart(hpcd->Instance, (uint8_t)hpcd->Init.dma_enable, (uint8_t *)hpcd->Setup); - } - - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Clear a STALL condition over in an endpoint - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - PCD_EPTypeDef *ep; - - if (((uint32_t)ep_addr & 0x0FU) > hpcd->Init.dev_endpoints) - { - return HAL_ERROR; - } - - if ((0x80U & ep_addr) == 0x80U) - { - ep = &hpcd->IN_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 1U; - } - else - { - ep = &hpcd->OUT_ep[ep_addr & EP_ADDR_MSK]; - ep->is_in = 0U; - } - - ep->is_stall = 0U; - ep->num = ep_addr & EP_ADDR_MSK; - - __HAL_LOCK(hpcd); - (void)USB_EPClearStall(hpcd->Instance, ep); - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Flush an endpoint - * @param hpcd PCD handle - * @param ep_addr endpoint address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr) -{ - __HAL_LOCK(hpcd); - - if ((ep_addr & 0x80U) == 0x80U) - { - (void)USB_FlushTxFifo(hpcd->Instance, (uint32_t)ep_addr & EP_ADDR_MSK); - } - else - { - (void)USB_FlushRxFifo(hpcd->Instance); - } - - __HAL_UNLOCK(hpcd); - - return HAL_OK; -} - -/** - * @brief Activate remote wakeup signalling - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd) -{ - return (USB_ActivateRemoteWakeup(hpcd->Instance)); -} - -/** - * @brief De-activate remote wakeup signalling. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd) -{ - return (USB_DeActivateRemoteWakeup(hpcd->Instance)); -} - -/** - * @} - */ - -/** @defgroup PCD_Exported_Functions_Group4 Peripheral State functions - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the PCD handle state. - * @param hpcd PCD handle - * @retval HAL state - */ -PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd) -{ - return hpcd->State; -} - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup PCD_Private_Functions - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** - * @brief Check FIFO for the next packet to be loaded. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval HAL status - */ -static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t epnum) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - USB_OTG_EPTypeDef *ep; - uint32_t len; - uint32_t len32b; - uint32_t fifoemptymsk; - - ep = &hpcd->IN_ep[epnum]; - - if (ep->xfer_count > ep->xfer_len) - { - return HAL_ERROR; - } - - len = ep->xfer_len - ep->xfer_count; - - if (len > ep->maxpacket) - { - len = ep->maxpacket; - } - - len32b = (len + 3U) / 4U; - - while (((USBx_INEP(epnum)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= len32b) && - (ep->xfer_count < ep->xfer_len) && (ep->xfer_len != 0U)) - { - /* Write the FIFO */ - len = ep->xfer_len - ep->xfer_count; - - if (len > ep->maxpacket) - { - len = ep->maxpacket; - } - len32b = (len + 3U) / 4U; - - (void)USB_WritePacket(USBx, ep->xfer_buff, (uint8_t)epnum, (uint16_t)len, - (uint8_t)hpcd->Init.dma_enable); - - ep->xfer_buff += len; - ep->xfer_count += len; - } - - if (ep->xfer_len <= ep->xfer_count) - { - fifoemptymsk = (uint32_t)(0x1UL << (epnum & EP_ADDR_MSK)); - USBx_DEVICE->DIEPEMPMSK &= ~fifoemptymsk; - } - - return HAL_OK; -} - - -/** - * @brief process EP OUT transfer complete interrupt. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval HAL status - */ -static HAL_StatusTypeDef PCD_EP_OutXfrComplete_int(PCD_HandleTypeDef *hpcd, uint32_t epnum) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); - uint32_t DoepintReg = USBx_OUTEP(epnum)->DOEPINT; - - if (hpcd->Init.dma_enable == 1U) - { - if ((DoepintReg & USB_OTG_DOEPINT_STUP) == USB_OTG_DOEPINT_STUP) /* Class C */ - { - /* StupPktRcvd = 1 this is a setup packet */ - if ((gSNPSiD > USB_OTG_CORE_ID_300A) && - ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); - } - } - else if ((DoepintReg & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) /* Class E */ - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); - } - else if ((DoepintReg & (USB_OTG_DOEPINT_STUP | USB_OTG_DOEPINT_OTEPSPR)) == 0U) - { - /* StupPktRcvd = 1 this is a setup packet */ - if ((gSNPSiD > USB_OTG_CORE_ID_300A) && - ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); - } - else - { - /* out data packet received over EP0 */ - hpcd->OUT_ep[epnum].xfer_count = - hpcd->OUT_ep[epnum].maxpacket - - (USBx_OUTEP(epnum)->DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ); - - hpcd->OUT_ep[epnum].xfer_buff += hpcd->OUT_ep[epnum].maxpacket; - - if ((epnum == 0U) && (hpcd->OUT_ep[epnum].xfer_len == 0U)) - { - /* this is ZLP, so prepare EP0 for next setup */ - (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); - } -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } - else - { - /* ... */ - } - } - else - { - if (gSNPSiD == USB_OTG_CORE_ID_310A) - { - /* StupPktRcvd = 1 this is a setup packet */ - if ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); - } - else - { - if ((DoepintReg & USB_OTG_DOEPINT_OTEPSPR) == USB_OTG_DOEPINT_OTEPSPR) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_OTEPSPR); - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } - else - { - if ((epnum == 0U) && (hpcd->OUT_ep[epnum].xfer_len == 0U)) - { - /* this is ZLP, so prepare EP0 for next setup */ - (void)USB_EP0_OutStart(hpcd->Instance, 0U, (uint8_t *)hpcd->Setup); - } - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->DataOutStageCallback(hpcd, (uint8_t)epnum); -#else - HAL_PCD_DataOutStageCallback(hpcd, (uint8_t)epnum); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } - - return HAL_OK; -} - - -/** - * @brief process EP OUT setup packet received interrupt. - * @param hpcd PCD handle - * @param epnum endpoint number - * @retval HAL status - */ -static HAL_StatusTypeDef PCD_EP_OutSetupPacket_int(PCD_HandleTypeDef *hpcd, uint32_t epnum) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); - uint32_t DoepintReg = USBx_OUTEP(epnum)->DOEPINT; - - if ((gSNPSiD > USB_OTG_CORE_ID_300A) && - ((DoepintReg & USB_OTG_DOEPINT_STPKTRX) == USB_OTG_DOEPINT_STPKTRX)) - { - CLEAR_OUT_EP_INTR(epnum, USB_OTG_DOEPINT_STPKTRX); - } - - /* Inform the upper layer that a setup packet is available */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->SetupStageCallback(hpcd); -#else - HAL_PCD_SetupStageCallback(hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - if ((gSNPSiD > USB_OTG_CORE_ID_300A) && (hpcd->Init.dma_enable == 1U)) - { - (void)USB_EP0_OutStart(hpcd->Instance, 1U, (uint8_t *)hpcd->Setup); - } - - return HAL_OK; -} -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -#endif /* HAL_PCD_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c deleted file mode 100644 index 7c7697c67688f0b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pcd_ex.c +++ /dev/null @@ -1,348 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd_ex.c - * @author MCD Application Team - * @brief PCD Extended HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the USB Peripheral Controller: - * + Extended features functions - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup PCDEx PCDEx - * @brief PCD Extended HAL module driver - * @{ - */ - -#ifdef HAL_PCD_MODULE_ENABLED - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup PCDEx_Exported_Functions PCDEx Exported Functions - * @{ - */ - -/** @defgroup PCDEx_Exported_Functions_Group1 Peripheral Control functions - * @brief PCDEx control functions - * -@verbatim - =============================================================================== - ##### Extended features functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Update FIFO configuration - -@endverbatim - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** - * @brief Set Tx FIFO - * @param hpcd PCD handle - * @param fifo The number of Tx fifo - * @param size Fifo size - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size) -{ - uint8_t i; - uint32_t Tx_Offset; - - /* TXn min size = 16 words. (n : Transmit FIFO index) - When a TxFIFO is not used, the Configuration should be as follows: - case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) - --> Txm can use the space allocated for Txn. - case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) - --> Txn should be configured with the minimum space of 16 words - The FIFO is used optimally when used TxFIFOs are allocated in the top - of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. - When DMA is used 3n * FIFO locations should be reserved for internal DMA registers */ - - Tx_Offset = hpcd->Instance->GRXFSIZ; - - if (fifo == 0U) - { - hpcd->Instance->DIEPTXF0_HNPTXFSIZ = ((uint32_t)size << 16) | Tx_Offset; - } - else - { - Tx_Offset += (hpcd->Instance->DIEPTXF0_HNPTXFSIZ) >> 16; - for (i = 0U; i < (fifo - 1U); i++) - { - Tx_Offset += (hpcd->Instance->DIEPTXF[i] >> 16); - } - - /* Multiply Tx_Size by 2 to get higher performance */ - hpcd->Instance->DIEPTXF[fifo - 1U] = ((uint32_t)size << 16) | Tx_Offset; - } - - return HAL_OK; -} - -/** - * @brief Set Rx FIFO - * @param hpcd PCD handle - * @param size Size of Rx fifo - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size) -{ - hpcd->Instance->GRXFSIZ = size; - - return HAL_OK; -} -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Activate LPM feature. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - hpcd->lpm_active = 1U; - hpcd->LPM_State = LPM_L0; - USBx->GINTMSK |= USB_OTG_GINTMSK_LPMINTM; - USBx->GLPMCFG |= (USB_OTG_GLPMCFG_LPMEN | USB_OTG_GLPMCFG_LPMACK | USB_OTG_GLPMCFG_ENBESL); - - return HAL_OK; -} - -/** - * @brief Deactivate LPM feature. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - hpcd->lpm_active = 0U; - USBx->GINTMSK &= ~USB_OTG_GINTMSK_LPMINTM; - USBx->GLPMCFG &= ~(USB_OTG_GLPMCFG_LPMEN | USB_OTG_GLPMCFG_LPMACK | USB_OTG_GLPMCFG_ENBESL); - - return HAL_OK; -} -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Handle BatteryCharging Process. - * @param hpcd PCD handle - * @retval HAL status - */ -void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - uint32_t tickstart = HAL_GetTick(); - - /* Enable DCD : Data Contact Detect */ - USBx->GCCFG |= USB_OTG_GCCFG_DCDEN; - - /* Wait Detect flag or a timeout is happen */ - while ((USBx->GCCFG & USB_OTG_GCCFG_DCDET) == 0U) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > 1000U) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_ERROR); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_ERROR); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - - return; - } - } - - /* Right response got */ - HAL_Delay(200U); - - /* Check Detect flag*/ - if ((USBx->GCCFG & USB_OTG_GCCFG_DCDET) == USB_OTG_GCCFG_DCDET) - { -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_CONTACT_DETECTION); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_CONTACT_DETECTION); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - - /*Primary detection: checks if connected to Standard Downstream Port - (without charging capability) */ - USBx->GCCFG &= ~ USB_OTG_GCCFG_DCDEN; - HAL_Delay(50U); - USBx->GCCFG |= USB_OTG_GCCFG_PDEN; - HAL_Delay(50U); - - if ((USBx->GCCFG & USB_OTG_GCCFG_PDET) == 0U) - { - /* Case of Standard Downstream Port */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_STD_DOWNSTREAM_PORT); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_STD_DOWNSTREAM_PORT); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { - /* start secondary detection to check connection to Charging Downstream - Port or Dedicated Charging Port */ - USBx->GCCFG &= ~ USB_OTG_GCCFG_PDEN; - HAL_Delay(50U); - USBx->GCCFG |= USB_OTG_GCCFG_SDEN; - HAL_Delay(50U); - - if ((USBx->GCCFG & USB_OTG_GCCFG_SDET) == USB_OTG_GCCFG_SDET) - { - /* case Dedicated Charging Port */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_DEDICATED_CHARGING_PORT); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_DEDICATED_CHARGING_PORT); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - else - { - /* case Charging Downstream Port */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_CHARGING_DOWNSTREAM_PORT); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_CHARGING_DOWNSTREAM_PORT); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - } - } - - /* Battery Charging capability discovery finished */ - (void)HAL_PCDEx_DeActivateBCD(hpcd); - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - hpcd->BCDCallback(hpcd, PCD_BCD_DISCOVERY_COMPLETED); -#else - HAL_PCDEx_BCD_Callback(hpcd, PCD_BCD_DISCOVERY_COMPLETED); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -} - -/** - * @brief Activate BatteryCharging feature. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - USBx->GCCFG &= ~(USB_OTG_GCCFG_PDEN); - USBx->GCCFG &= ~(USB_OTG_GCCFG_SDEN); - - /* Power Down USB transceiver */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - - /* Enable Battery charging */ - USBx->GCCFG |= USB_OTG_GCCFG_BCDEN; - - hpcd->battery_charging_active = 1U; - - return HAL_OK; -} - -/** - * @brief Deactivate BatteryCharging feature. - * @param hpcd PCD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd) -{ - USB_OTG_GlobalTypeDef *USBx = hpcd->Instance; - - USBx->GCCFG &= ~(USB_OTG_GCCFG_SDEN); - USBx->GCCFG &= ~(USB_OTG_GCCFG_PDEN); - - /* Disable Battery charging */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN); - - hpcd->battery_charging_active = 0U; - - return HAL_OK; -} -#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/** - * @brief Send LPM message to user layer callback. - * @param hpcd PCD handle - * @param msg LPM message - * @retval HAL status - */ -__weak void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(msg); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCDEx_LPM_Callback could be implemented in the user file - */ -} - -/** - * @brief Send BatteryCharging message to user layer callback. - * @param hpcd PCD handle - * @param msg LPM message - * @retval HAL status - */ -__weak void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hpcd); - UNUSED(msg); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_PCDEx_BCD_Callback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -#endif /* HAL_PCD_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c deleted file mode 100644 index 5359d69b0e8ef97..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c +++ /dev/null @@ -1,576 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr.c - * @author MCD Application Team - * @brief PWR HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Power Controller (PWR) peripheral: - * + Initialization and de-initialization functions - * + Peripheral Control functions - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup PWR PWR - * @brief PWR HAL module driver - * @{ - */ - -#ifdef HAL_PWR_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup PWR_Private_Constants - * @{ - */ - -/** @defgroup PWR_PVD_Mode_Mask PWR PVD Mode Mask - * @{ - */ -#define PVD_MODE_IT 0x00010000U -#define PVD_MODE_EVT 0x00020000U -#define PVD_RISING_EDGE 0x00000001U -#define PVD_FALLING_EDGE 0x00000002U -/** - * @} - */ - -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup PWR_Exported_Functions PWR Exported Functions - * @{ - */ - -/** @defgroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and de-initialization functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] - After reset, the backup domain (RTC registers, RTC backup data - registers and backup SRAM) is protected against possible unwanted - write accesses. - To enable access to the RTC Domain and RTC registers, proceed as follows: - (+) Enable the Power Controller (PWR) APB1 interface clock using the - __HAL_RCC_PWR_CLK_ENABLE() macro. - (+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function. - -@endverbatim - * @{ - */ - -/** - * @brief Deinitializes the HAL PWR peripheral registers to their default reset values. - * @retval None - */ -void HAL_PWR_DeInit(void) -{ - __HAL_RCC_PWR_FORCE_RESET(); - __HAL_RCC_PWR_RELEASE_RESET(); -} - -/** - * @brief Enables access to the backup domain (RTC registers, RTC - * backup data registers and backup SRAM). - * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the - * Backup Domain Access should be kept enabled. - * @note The following sequence is required to bypass the delay between - * DBP bit programming and the effective enabling of the backup domain. - * Please check the Errata Sheet for more details under "Possible delay - * in backup domain protection disabling/enabling after programming the - * DBP bit" section. - * @retval None - */ -void HAL_PWR_EnableBkUpAccess(void) -{ - __IO uint32_t dummyread; - *(__IO uint32_t *) CR_DBP_BB = (uint32_t)ENABLE; - dummyread = PWR->CR; - UNUSED(dummyread); -} - -/** - * @brief Disables access to the backup domain (RTC registers, RTC - * backup data registers and backup SRAM). - * @note If the HSE divided by 2, 3, ..31 is used as the RTC clock, the - * Backup Domain Access should be kept enabled. - * @note The following sequence is required to bypass the delay between - * DBP bit programming and the effective disabling of the backup domain. - * Please check the Errata Sheet for more details under "Possible delay - * in backup domain protection disabling/enabling after programming the - * DBP bit" section. - * @retval None - */ -void HAL_PWR_DisableBkUpAccess(void) -{ - __IO uint32_t dummyread; - *(__IO uint32_t *) CR_DBP_BB = (uint32_t)DISABLE; - dummyread = PWR->CR; - UNUSED(dummyread); -} - -/** - * @} - */ - -/** @defgroup PWR_Exported_Functions_Group2 Peripheral Control functions - * @brief Low Power modes configuration functions - * -@verbatim - - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - - *** PVD configuration *** - ========================= - [..] - (+) The PVD is used to monitor the VDD power supply by comparing it to a - threshold selected by the PVD Level (PLS[2:0] bits in the PWR_CR). - (+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower - than the PVD threshold. This event is internally connected to the EXTI - line16 and can generate an interrupt if enabled. This is done through - __HAL_PWR_PVD_EXTI_ENABLE_IT() macro. - (+) The PVD is stopped in Standby mode. - - *** Wake-up pin configuration *** - ================================ - [..] - (+) Wake-up pin is used to wake up the system from Standby mode. This pin is - forced in input pull-down configuration and is active on rising edges. - (+) There is one Wake-up pin: Wake-up Pin 1 on PA.00. - (++) For STM32F446xx there are two Wake-Up pins: Pin1 on PA.00 and Pin2 on PC.13 - (++) For STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx there are three Wake-Up pins: Pin1 on PA.00, Pin2 on PC.00 and Pin3 on PC.01 - - *** Low Power modes configuration *** - ===================================== - [..] - The devices feature 3 low-power modes: - (+) Sleep mode: Cortex-M4 core stopped, peripherals kept running. - (+) Stop mode: all clocks are stopped, regulator running, regulator - in low power mode - (+) Standby mode: 1.2V domain powered off. - - *** Sleep mode *** - ================== - [..] - (+) Entry: - The Sleep mode is entered by using the HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI) - functions with - (++) PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction - (++) PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction - - -@@- The Regulator parameter is not used for the STM32F4 family - and is kept as parameter just to maintain compatibility with the - lower power families (STM32L). - (+) Exit: - Any peripheral interrupt acknowledged by the nested vectored interrupt - controller (NVIC) can wake up the device from Sleep mode. - - *** Stop mode *** - ================= - [..] - In Stop mode, all clocks in the 1.2V domain are stopped, the PLL, the HSI, - and the HSE RC oscillators are disabled. Internal SRAM and register contents - are preserved. - The voltage regulator can be configured either in normal or low-power mode. - To minimize the consumption In Stop mode, FLASH can be powered off before - entering the Stop mode using the HAL_PWREx_EnableFlashPowerDown() function. - It can be switched on again by software after exiting the Stop mode using - the HAL_PWREx_DisableFlashPowerDown() function. - - (+) Entry: - The Stop mode is entered using the HAL_PWR_EnterSTOPMode(PWR_MAINREGULATOR_ON) - function with: - (++) Main regulator ON. - (++) Low Power regulator ON. - (+) Exit: - Any EXTI Line (Internal or External) configured in Interrupt/Event mode. - - *** Standby mode *** - ==================== - [..] - (+) - The Standby mode allows to achieve the lowest power consumption. It is based - on the Cortex-M4 deep sleep mode, with the voltage regulator disabled. - The 1.2V domain is consequently powered off. The PLL, the HSI oscillator and - the HSE oscillator are also switched off. SRAM and register contents are lost - except for the RTC registers, RTC backup registers, backup SRAM and Standby - circuitry. - - The voltage regulator is OFF. - - (++) Entry: - (+++) The Standby mode is entered using the HAL_PWR_EnterSTANDBYMode() function. - (++) Exit: - (+++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wake-up, - tamper event, time-stamp event, external reset in NRST pin, IWDG reset. - - *** Auto-wake-up (AWU) from low-power mode *** - ============================================= - [..] - - (+) The MCU can be woken up from low-power mode by an RTC Alarm event, an RTC - Wake-up event, a tamper event or a time-stamp event, without depending on - an external interrupt (Auto-wake-up mode). - - (+) RTC auto-wake-up (AWU) from the Stop and Standby modes - - (++) To wake up from the Stop mode with an RTC alarm event, it is necessary to - configure the RTC to generate the RTC alarm using the HAL_RTC_SetAlarm_IT() function. - - (++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it - is necessary to configure the RTC to detect the tamper or time stamp event using the - HAL_RTCEx_SetTimeStamp_IT() or HAL_RTCEx_SetTamper_IT() functions. - - (++) To wake up from the Stop mode with an RTC Wake-up event, it is necessary to - configure the RTC to generate the RTC Wake-up event using the HAL_RTCEx_SetWakeUpTimer_IT() function. - -@endverbatim - * @{ - */ - -/** - * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). - * @param sConfigPVD pointer to an PWR_PVDTypeDef structure that contains the configuration - * information for the PVD. - * @note Refer to the electrical characteristics of your device datasheet for - * more details about the voltage threshold corresponding to each - * detection level. - * @retval None - */ -void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD) -{ - /* Check the parameters */ - assert_param(IS_PWR_PVD_LEVEL(sConfigPVD->PVDLevel)); - assert_param(IS_PWR_PVD_MODE(sConfigPVD->Mode)); - - /* Set PLS[7:5] bits according to PVDLevel value */ - MODIFY_REG(PWR->CR, PWR_CR_PLS, sConfigPVD->PVDLevel); - - /* Clear any previous config. Keep it clear if no event or IT mode is selected */ - __HAL_PWR_PVD_EXTI_DISABLE_EVENT(); - __HAL_PWR_PVD_EXTI_DISABLE_IT(); - __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE(); - __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); - - /* Configure interrupt mode */ - if((sConfigPVD->Mode & PVD_MODE_IT) == PVD_MODE_IT) - { - __HAL_PWR_PVD_EXTI_ENABLE_IT(); - } - - /* Configure event mode */ - if((sConfigPVD->Mode & PVD_MODE_EVT) == PVD_MODE_EVT) - { - __HAL_PWR_PVD_EXTI_ENABLE_EVENT(); - } - - /* Configure the edge */ - if((sConfigPVD->Mode & PVD_RISING_EDGE) == PVD_RISING_EDGE) - { - __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE(); - } - - if((sConfigPVD->Mode & PVD_FALLING_EDGE) == PVD_FALLING_EDGE) - { - __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE(); - } -} - -/** - * @brief Enables the Power Voltage Detector(PVD). - * @retval None - */ -void HAL_PWR_EnablePVD(void) -{ - *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables the Power Voltage Detector(PVD). - * @retval None - */ -void HAL_PWR_DisablePVD(void) -{ - *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)DISABLE; -} - -/** - * @brief Enables the Wake-up PINx functionality. - * @param WakeUpPinx Specifies the Power Wake-Up pin to enable. - * This parameter can be one of the following values: - * @arg PWR_WAKEUP_PIN1 - * @arg PWR_WAKEUP_PIN2 available only on STM32F410xx/STM32F446xx/STM32F412xx/STM32F413xx/STM32F423xx devices - * @arg PWR_WAKEUP_PIN3 available only on STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx devices - * @retval None - */ -void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx) -{ - /* Check the parameter */ - assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); - - /* Enable the wake up pin */ - SET_BIT(PWR->CSR, WakeUpPinx); -} - -/** - * @brief Disables the Wake-up PINx functionality. - * @param WakeUpPinx Specifies the Power Wake-Up pin to disable. - * This parameter can be one of the following values: - * @arg PWR_WAKEUP_PIN1 - * @arg PWR_WAKEUP_PIN2 available only on STM32F410xx/STM32F446xx/STM32F412xx/STM32F413xx/STM32F423xx devices - * @arg PWR_WAKEUP_PIN3 available only on STM32F410xx/STM32F412xx/STM32F413xx/STM32F423xx devices - * @retval None - */ -void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx) -{ - /* Check the parameter */ - assert_param(IS_PWR_WAKEUP_PIN(WakeUpPinx)); - - /* Disable the wake up pin */ - CLEAR_BIT(PWR->CSR, WakeUpPinx); -} - -/** - * @brief Enters Sleep mode. - * - * @note In Sleep mode, all I/O pins keep the same state as in Run mode. - * - * @note In Sleep mode, the systick is stopped to avoid exit from this mode with - * systick interrupt when used as time base for Timeout - * - * @param Regulator Specifies the regulator state in SLEEP mode. - * This parameter can be one of the following values: - * @arg PWR_MAINREGULATOR_ON: SLEEP mode with regulator ON - * @arg PWR_LOWPOWERREGULATOR_ON: SLEEP mode with low power regulator ON - * @note This parameter is not used for the STM32F4 family and is kept as parameter - * just to maintain compatibility with the lower power families. - * @param SLEEPEntry Specifies if SLEEP mode in entered with WFI or WFE instruction. - * This parameter can be one of the following values: - * @arg PWR_SLEEPENTRY_WFI: enter SLEEP mode with WFI instruction - * @arg PWR_SLEEPENTRY_WFE: enter SLEEP mode with WFE instruction - * @retval None - */ -void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry) -{ - /* Check the parameters */ - assert_param(IS_PWR_REGULATOR(Regulator)); - assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry)); - UNUSED(Regulator); - - /* Clear SLEEPDEEP bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); - - /* Select SLEEP mode entry -------------------------------------------------*/ - if(SLEEPEntry == PWR_SLEEPENTRY_WFI) - { - /* Request Wait For Interrupt */ - __WFI(); - } - else - { - /* Request Wait For Event */ - __SEV(); - __WFE(); - __WFE(); - } -} - -/** - * @brief Enters Stop mode. - * @note In Stop mode, all I/O pins keep the same state as in Run mode. - * @note When exiting Stop mode by issuing an interrupt or a wake-up event, - * the HSI RC oscillator is selected as system clock. - * @note When the voltage regulator operates in low power mode, an additional - * startup delay is incurred when waking up from Stop mode. - * By keeping the internal regulator ON during Stop mode, the consumption - * is higher although the startup time is reduced. - * @param Regulator Specifies the regulator state in Stop mode. - * This parameter can be one of the following values: - * @arg PWR_MAINREGULATOR_ON: Stop mode with regulator ON - * @arg PWR_LOWPOWERREGULATOR_ON: Stop mode with low power regulator ON - * @param STOPEntry Specifies if Stop mode in entered with WFI or WFE instruction. - * This parameter can be one of the following values: - * @arg PWR_STOPENTRY_WFI: Enter Stop mode with WFI instruction - * @arg PWR_STOPENTRY_WFE: Enter Stop mode with WFE instruction - * @retval None - */ -void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry) -{ - /* Check the parameters */ - assert_param(IS_PWR_REGULATOR(Regulator)); - assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); - - /* Select the regulator state in Stop mode: Set PDDS and LPDS bits according to PWR_Regulator value */ - MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS), Regulator); - - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); - - /* Select Stop mode entry --------------------------------------------------*/ - if(STOPEntry == PWR_STOPENTRY_WFI) - { - /* Request Wait For Interrupt */ - __WFI(); - } - else - { - /* Request Wait For Event */ - __SEV(); - __WFE(); - __WFE(); - } - /* Reset SLEEPDEEP bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); -} - -/** - * @brief Enters Standby mode. - * @note In Standby mode, all I/O pins are high impedance except for: - * - Reset pad (still available) - * - RTC_AF1 pin (PC13) if configured for tamper, time-stamp, RTC - * Alarm out, or RTC clock calibration out. - * - RTC_AF2 pin (PI8) if configured for tamper or time-stamp. - * - WKUP pin 1 (PA0) if enabled. - * @retval None - */ -void HAL_PWR_EnterSTANDBYMode(void) -{ - /* Select Standby mode */ - SET_BIT(PWR->CR, PWR_CR_PDDS); - - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); - - /* This option is used to ensure that store operations are completed */ -#if defined ( __CC_ARM) - __force_stores(); -#endif - /* Request Wait For Interrupt */ - __WFI(); -} - -/** - * @brief This function handles the PWR PVD interrupt request. - * @note This API should be called under the PVD_IRQHandler(). - * @retval None - */ -void HAL_PWR_PVD_IRQHandler(void) -{ - /* Check PWR Exti flag */ - if(__HAL_PWR_PVD_EXTI_GET_FLAG() != RESET) - { - /* PWR PVD interrupt user callback */ - HAL_PWR_PVDCallback(); - - /* Clear PWR Exti pending bit */ - __HAL_PWR_PVD_EXTI_CLEAR_FLAG(); - } -} - -/** - * @brief PWR PVD interrupt callback - * @retval None - */ -__weak void HAL_PWR_PVDCallback(void) -{ - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_PWR_PVDCallback could be implemented in the user file - */ -} - -/** - * @brief Indicates Sleep-On-Exit when returning from Handler mode to Thread mode. - * @note Set SLEEPONEXIT bit of SCR register. When this bit is set, the processor - * re-enters SLEEP mode when an interruption handling is over. - * Setting this bit is useful when the processor is expected to run only on - * interruptions handling. - * @retval None - */ -void HAL_PWR_EnableSleepOnExit(void) -{ - /* Set SLEEPONEXIT bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Disables Sleep-On-Exit feature when returning from Handler mode to Thread mode. - * @note Clears SLEEPONEXIT bit of SCR register. When this bit is set, the processor - * re-enters SLEEP mode when an interruption handling is over. - * @retval None - */ -void HAL_PWR_DisableSleepOnExit(void) -{ - /* Clear SLEEPONEXIT bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Enables CORTEX M4 SEVONPEND bit. - * @note Sets SEVONPEND bit of SCR register. When this bit is set, this causes - * WFE to wake up when an interrupt moves from inactive to pended. - * @retval None - */ -void HAL_PWR_EnableSEVOnPend(void) -{ - /* Set SEVONPEND bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @brief Disables CORTEX M4 SEVONPEND bit. - * @note Clears SEVONPEND bit of SCR register. When this bit is set, this causes - * WFE to wake up when an interrupt moves from inactive to pended. - * @retval None - */ -void HAL_PWR_DisableSEVOnPend(void) -{ - /* Clear SEVONPEND bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_PWR_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c deleted file mode 100644 index 0d26083a4b1500b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c +++ /dev/null @@ -1,604 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr_ex.c - * @author MCD Application Team - * @brief Extended PWR HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of PWR extension peripheral: - * + Peripheral Extended features functions - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup PWREx PWREx - * @brief PWR HAL module driver - * @{ - */ - -#ifdef HAL_PWR_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup PWREx_Private_Constants - * @{ - */ -#define PWR_OVERDRIVE_TIMEOUT_VALUE 1000U -#define PWR_UDERDRIVE_TIMEOUT_VALUE 1000U -#define PWR_BKPREG_TIMEOUT_VALUE 1000U -#define PWR_VOSRDY_TIMEOUT_VALUE 1000U -/** - * @} - */ - - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup PWREx_Exported_Functions PWREx Exported Functions - * @{ - */ - -/** @defgroup PWREx_Exported_Functions_Group1 Peripheral Extended features functions - * @brief Peripheral Extended features functions - * -@verbatim - - =============================================================================== - ##### Peripheral extended features functions ##### - =============================================================================== - - *** Main and Backup Regulators configuration *** - ================================================ - [..] - (+) The backup domain includes 4 Kbytes of backup SRAM accessible only from - the CPU, and address in 32-bit, 16-bit or 8-bit mode. Its content is - retained even in Standby or VBAT mode when the low power backup regulator - is enabled. It can be considered as an internal EEPROM when VBAT is - always present. You can use the HAL_PWREx_EnableBkUpReg() function to - enable the low power backup regulator. - - (+) When the backup domain is supplied by VDD (analog switch connected to VDD) - the backup SRAM is powered from VDD which replaces the VBAT power supply to - save battery life. - - (+) The backup SRAM is not mass erased by a tamper event. It is read - protected to prevent confidential data, such as cryptographic private - key, from being accessed. The backup SRAM can be erased only through - the Flash interface when a protection level change from level 1 to - level 0 is requested. - -@- Refer to the description of Read protection (RDP) in the Flash - programming manual. - - (+) The main internal regulator can be configured to have a tradeoff between - performance and power consumption when the device does not operate at - the maximum frequency. This is done through __HAL_PWR_MAINREGULATORMODE_CONFIG() - macro which configure VOS bit in PWR_CR register - - Refer to the product datasheets for more details. - - *** FLASH Power Down configuration **** - ======================================= - [..] - (+) By setting the FPDS bit in the PWR_CR register by using the - HAL_PWREx_EnableFlashPowerDown() function, the Flash memory also enters power - down mode when the device enters Stop mode. When the Flash memory - is in power down mode, an additional startup delay is incurred when - waking up from Stop mode. - - (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, the scale can be modified only when the PLL - is OFF and the HSI or HSE clock source is selected as system clock. - The new value programmed is active only when the PLL is ON. - When the PLL is OFF, the voltage scale 3 is automatically selected. - Refer to the datasheets for more details. - - *** Over-Drive and Under-Drive configuration **** - ================================================= - [..] - (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, in Run mode: the main regulator has - 2 operating modes available: - (++) Normal mode: The CPU and core logic operate at maximum frequency at a given - voltage scaling (scale 1, scale 2 or scale 3) - (++) Over-drive mode: This mode allows the CPU and the core logic to operate at a - higher frequency than the normal mode for a given voltage scaling (scale 1, - scale 2 or scale 3). This mode is enabled through HAL_PWREx_EnableOverDrive() function and - disabled by HAL_PWREx_DisableOverDrive() function, to enter or exit from Over-drive mode please follow - the sequence described in Reference manual. - - (+) For STM32F42xxx/43xxx/446xx/469xx/479xx Devices, in Stop mode: the main regulator or low power regulator - supplies a low power voltage to the 1.2V domain, thus preserving the content of registers - and internal SRAM. 2 operating modes are available: - (++) Normal mode: the 1.2V domain is preserved in nominal leakage mode. This mode is only - available when the main regulator or the low power regulator is used in Scale 3 or - low voltage mode. - (++) Under-drive mode: the 1.2V domain is preserved in reduced leakage mode. This mode is only - available when the main regulator or the low power regulator is in low voltage mode. - -@endverbatim - * @{ - */ - -/** - * @brief Enables the Backup Regulator. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PWREx_EnableBkUpReg(void) -{ - uint32_t tickstart = 0U; - - *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)ENABLE; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till Backup regulator ready flag is set */ - while(__HAL_PWR_GET_FLAG(PWR_FLAG_BRR) == RESET) - { - if((HAL_GetTick() - tickstart ) > PWR_BKPREG_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - return HAL_OK; -} - -/** - * @brief Disables the Backup Regulator. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PWREx_DisableBkUpReg(void) -{ - uint32_t tickstart = 0U; - - *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)DISABLE; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till Backup regulator ready flag is set */ - while(__HAL_PWR_GET_FLAG(PWR_FLAG_BRR) != RESET) - { - if((HAL_GetTick() - tickstart ) > PWR_BKPREG_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - return HAL_OK; -} - -/** - * @brief Enables the Flash Power Down in Stop mode. - * @retval None - */ -void HAL_PWREx_EnableFlashPowerDown(void) -{ - *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables the Flash Power Down in Stop mode. - * @retval None - */ -void HAL_PWREx_DisableFlashPowerDown(void) -{ - *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)DISABLE; -} - -/** - * @brief Return Voltage Scaling Range. - * @retval The configured scale for the regulator voltage(VOS bit field). - * The returned value can be one of the following: - * - @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode - * - @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode - * - @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode - */ -uint32_t HAL_PWREx_GetVoltageRange(void) -{ - return (PWR->CR & PWR_CR_VOS); -} - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief Configures the main internal regulator output voltage. - * @param VoltageScaling specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption. - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output range 1 mode, - * the maximum value of fHCLK = 168 MHz. - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output range 2 mode, - * the maximum value of fHCLK = 144 MHz. - * @note When moving from Range 1 to Range 2, the system frequency must be decreased to - * a value below 144 MHz before calling HAL_PWREx_ConfigVoltageScaling() API. - * When moving from Range 2 to Range 1, the system frequency can be increased to - * a value up to 168 MHz after calling HAL_PWREx_ConfigVoltageScaling() API. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling) -{ - uint32_t tickstart = 0U; - - assert_param(IS_PWR_VOLTAGE_SCALING_RANGE(VoltageScaling)); - - /* Enable PWR RCC Clock Peripheral */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Set Range */ - __HAL_PWR_VOLTAGESCALING_CONFIG(VoltageScaling); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - while((__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY) == RESET)) - { - if((HAL_GetTick() - tickstart ) > PWR_VOSRDY_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) || \ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Configures the main internal regulator output voltage. - * @param VoltageScaling specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption. - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output range 1 mode, - * the maximum value of fHCLK is 168 MHz. It can be extended to - * 180 MHz by activating the over-drive mode. - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output range 2 mode, - * the maximum value of fHCLK is 144 MHz. It can be extended to, - * 168 MHz by activating the over-drive mode. - * @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output range 3 mode, - * the maximum value of fHCLK is 120 MHz. - * @note To update the system clock frequency(SYSCLK): - * - Set the HSI or HSE as system clock frequency using the HAL_RCC_ClockConfig(). - * - Call the HAL_RCC_OscConfig() to configure the PLL. - * - Call HAL_PWREx_ConfigVoltageScaling() API to adjust the voltage scale. - * - Set the new system clock frequency using the HAL_RCC_ClockConfig(). - * @note The scale can be modified only when the HSI or HSE clock source is selected - * as system clock source, otherwise the API returns HAL_ERROR. - * @note When the PLL is OFF, the voltage scale 3 is automatically selected and the VOS bits - * value in the PWR_CR1 register are not taken in account. - * @note This API forces the PLL state ON to allow the possibility to configure the voltage scale 1 or 2. - * @note The new voltage scale is active only when the PLL is ON. - * @retval HAL Status - */ -HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling) -{ - uint32_t tickstart = 0U; - - assert_param(IS_PWR_VOLTAGE_SCALING_RANGE(VoltageScaling)); - - /* Enable PWR RCC Clock Peripheral */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Check if the PLL is used as system clock or not */ - if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) - { - /* Disable the main PLL */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - /* Wait till PLL is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Set Range */ - __HAL_PWR_VOLTAGESCALING_CONFIG(VoltageScaling); - - /* Enable the main PLL */ - __HAL_RCC_PLL_ENABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - while((__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY) == RESET)) - { - if((HAL_GetTick() - tickstart ) > PWR_VOSRDY_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - return HAL_ERROR; - } - - return HAL_OK; -} -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) ||\ - defined(STM32F411xE) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Enables Main Regulator low voltage mode. - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ - * STM32F413xx/STM32F423xx devices. - * @retval None - */ -void HAL_PWREx_EnableMainRegulatorLowVoltage(void) -{ - *(__IO uint32_t *) CR_MRLVDS_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables Main Regulator low voltage mode. - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ - * STM32F413xx/STM32F423xxdevices. - * @retval None - */ -void HAL_PWREx_DisableMainRegulatorLowVoltage(void) -{ - *(__IO uint32_t *) CR_MRLVDS_BB = (uint32_t)DISABLE; -} - -/** - * @brief Enables Low Power Regulator low voltage mode. - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ - * STM32F413xx/STM32F423xx devices. - * @retval None - */ -void HAL_PWREx_EnableLowRegulatorLowVoltage(void) -{ - *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables Low Power Regulator low voltage mode. - * @note This mode is only available for STM32F401xx/STM32F410xx/STM32F411xx/STM32F412Zx/STM32F412Rx/STM32F412Vx/STM32F412Cx/ - * STM32F413xx/STM32F423xx devices. - * @retval None - */ -void HAL_PWREx_DisableLowRegulatorLowVoltage(void) -{ - *(__IO uint32_t *) CR_LPLVDS_BB = (uint32_t)DISABLE; -} - -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F412Zx || STM32F412Rx || STM32F412Vx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Activates the Over-Drive mode. - * @note This function can be used only for STM32F42xx/STM32F43xx/STM32F446xx/STM32F469xx/STM32F479xx devices. - * This mode allows the CPU and the core logic to operate at a higher frequency - * than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3). - * @note It is recommended to enter or exit Over-drive mode when the application is not running - * critical tasks and when the system clock source is either HSI or HSE. - * During the Over-drive switch activation, no peripheral clocks should be enabled. - * The peripheral clocks must be enabled once the Over-drive mode is activated. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PWREx_EnableOverDrive(void) -{ - uint32_t tickstart = 0U; - - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable the Over-drive to extend the clock frequency to 180 Mhz */ - __HAL_PWR_OVERDRIVE_ENABLE(); - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(!__HAL_PWR_GET_FLAG(PWR_FLAG_ODRDY)) - { - if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Enable the Over-drive switch */ - __HAL_PWR_OVERDRIVESWITCHING_ENABLE(); - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(!__HAL_PWR_GET_FLAG(PWR_FLAG_ODSWRDY)) - { - if((HAL_GetTick() - tickstart ) > PWR_OVERDRIVE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - return HAL_OK; -} - -/** - * @brief Deactivates the Over-Drive mode. - * @note This function can be used only for STM32F42xx/STM32F43xx/STM32F446xx/STM32F469xx/STM32F479xx devices. - * This mode allows the CPU and the core logic to operate at a higher frequency - * than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3). - * @note It is recommended to enter or exit Over-drive mode when the application is not running - * critical tasks and when the system clock source is either HSI or HSE. - * During the Over-drive switch activation, no peripheral clocks should be enabled. - * The peripheral clocks must be enabled once the Over-drive mode is activated. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_PWREx_DisableOverDrive(void) -{ - uint32_t tickstart = 0U; - - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Disable the Over-drive switch */ - __HAL_PWR_OVERDRIVESWITCHING_DISABLE(); - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_PWR_GET_FLAG(PWR_FLAG_ODSWRDY)) - { - if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Disable the Over-drive */ - __HAL_PWR_OVERDRIVE_DISABLE(); - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_PWR_GET_FLAG(PWR_FLAG_ODRDY)) - { - if((HAL_GetTick() - tickstart) > PWR_OVERDRIVE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -/** - * @brief Enters in Under-Drive STOP mode. - * - * @note This mode is only available for STM32F42xxx/STM32F43xxx/STM32F446xx/STM32F469xx/STM32F479xx devices. - * - * @note This mode can be selected only when the Under-Drive is already active - * - * @note This mode is enabled only with STOP low power mode. - * In this mode, the 1.2V domain is preserved in reduced leakage mode. This - * mode is only available when the main regulator or the low power regulator - * is in low voltage mode - * - * @note If the Under-drive mode was enabled, it is automatically disabled after - * exiting Stop mode. - * When the voltage regulator operates in Under-drive mode, an additional - * startup delay is induced when waking up from Stop mode. - * - * @note In Stop mode, all I/O pins keep the same state as in Run mode. - * - * @note When exiting Stop mode by issuing an interrupt or a wake-up event, - * the HSI RC oscillator is selected as system clock. - * - * @note When the voltage regulator operates in low power mode, an additional - * startup delay is incurred when waking up from Stop mode. - * By keeping the internal regulator ON during Stop mode, the consumption - * is higher although the startup time is reduced. - * - * @param Regulator specifies the regulator state in STOP mode. - * This parameter can be one of the following values: - * @arg PWR_MAINREGULATOR_UNDERDRIVE_ON: Main Regulator in under-drive mode - * and Flash memory in power-down when the device is in Stop under-drive mode - * @arg PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON: Low Power Regulator in under-drive mode - * and Flash memory in power-down when the device is in Stop under-drive mode - * @param STOPEntry specifies if STOP mode in entered with WFI or WFE instruction. - * This parameter can be one of the following values: - * @arg PWR_SLEEPENTRY_WFI: enter STOP mode with WFI instruction - * @arg PWR_SLEEPENTRY_WFE: enter STOP mode with WFE instruction - * @retval None - */ -HAL_StatusTypeDef HAL_PWREx_EnterUnderDriveSTOPMode(uint32_t Regulator, uint8_t STOPEntry) -{ - uint32_t tmpreg1 = 0U; - - /* Check the parameters */ - assert_param(IS_PWR_REGULATOR_UNDERDRIVE(Regulator)); - assert_param(IS_PWR_STOP_ENTRY(STOPEntry)); - - /* Enable Power ctrl clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - /* Enable the Under-drive Mode ---------------------------------------------*/ - /* Clear Under-drive flag */ - __HAL_PWR_CLEAR_ODRUDR_FLAG(); - - /* Enable the Under-drive */ - __HAL_PWR_UNDERDRIVE_ENABLE(); - - /* Select the regulator state in STOP mode ---------------------------------*/ - tmpreg1 = PWR->CR; - /* Clear PDDS, LPDS, MRLUDS and LPLUDS bits */ - tmpreg1 &= (uint32_t)~(PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_LPUDS | PWR_CR_MRUDS); - - /* Set LPDS, MRLUDS and LPLUDS bits according to PWR_Regulator value */ - tmpreg1 |= Regulator; - - /* Store the new value */ - PWR->CR = tmpreg1; - - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk; - - /* Select STOP mode entry --------------------------------------------------*/ - if(STOPEntry == PWR_SLEEPENTRY_WFI) - { - /* Request Wait For Interrupt */ - __WFI(); - } - else - { - /* Request Wait For Event */ - __WFE(); - } - /* Reset SLEEPDEEP bit of Cortex System Control Register */ - SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk); - - return HAL_OK; -} - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_PWR_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_qspi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_qspi.c deleted file mode 100644 index 5763d077501aa36..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_qspi.c +++ /dev/null @@ -1,2903 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_qspi.c - * @author MCD Application Team - * @brief QSPI HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the QuadSPI interface (QSPI). - * + Initialization and de-initialization functions - * + Indirect functional mode management - * + Memory-mapped functional mode management - * + Auto-polling functional mode management - * + Interrupts and flags management - * + DMA channel configuration for indirect functional mode - * + Errors management and abort functionality - * - * - @verbatim - =============================================================================== - ##### How to use this driver ##### - =============================================================================== - [..] - *** Initialization *** - ====================== - [..] - (#) As prerequisite, fill in the HAL_QSPI_MspInit() : - (++) Enable QuadSPI clock interface with __HAL_RCC_QSPI_CLK_ENABLE(). - (++) Reset QuadSPI Peripheral with __HAL_RCC_QSPI_FORCE_RESET() and __HAL_RCC_QSPI_RELEASE_RESET(). - (++) Enable the clocks for the QuadSPI GPIOS with __HAL_RCC_GPIOx_CLK_ENABLE(). - (++) Configure these QuadSPI pins in alternate mode using HAL_GPIO_Init(). - (++) If interrupt mode is used, enable and configure QuadSPI global - interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ(). - (++) If DMA mode is used, enable the clocks for the QuadSPI DMA channel - with __HAL_RCC_DMAx_CLK_ENABLE(), configure DMA with HAL_DMA_Init(), - link it with QuadSPI handle using __HAL_LINKDMA(), enable and configure - DMA channel global interrupt with HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ(). - (#) Configure the flash size, the clock prescaler, the fifo threshold, the - clock mode, the sample shifting and the CS high time using the HAL_QSPI_Init() function. - - *** Indirect functional mode *** - ================================ - [..] - (#) Configure the command sequence using the HAL_QSPI_Command() or HAL_QSPI_Command_IT() - functions : - (++) Instruction phase : the mode used and if present the instruction opcode. - (++) Address phase : the mode used and if present the size and the address value. - (++) Alternate-bytes phase : the mode used and if present the size and the alternate - bytes values. - (++) Dummy-cycles phase : the number of dummy cycles (mode used is same as data phase). - (++) Data phase : the mode used and if present the number of bytes. - (++) Double Data Rate (DDR) mode : the activation (or not) of this mode and the delay - if activated. - (++) Sending Instruction Only Once (SIOO) mode : the activation (or not) of this mode. - (#) If no data is required for the command, it is sent directly to the memory : - (++) In polling mode, the output of the function is done when the transfer is complete. - (++) In interrupt mode, HAL_QSPI_CmdCpltCallback() will be called when the transfer is complete. - (#) For the indirect write mode, use HAL_QSPI_Transmit(), HAL_QSPI_Transmit_DMA() or - HAL_QSPI_Transmit_IT() after the command configuration : - (++) In polling mode, the output of the function is done when the transfer is complete. - (++) In interrupt mode, HAL_QSPI_FifoThresholdCallback() will be called when the fifo threshold - is reached and HAL_QSPI_TxCpltCallback() will be called when the transfer is complete. - (++) In DMA mode, HAL_QSPI_TxHalfCpltCallback() will be called at the half transfer and - HAL_QSPI_TxCpltCallback() will be called when the transfer is complete. - (#) For the indirect read mode, use HAL_QSPI_Receive(), HAL_QSPI_Receive_DMA() or - HAL_QSPI_Receive_IT() after the command configuration : - (++) In polling mode, the output of the function is done when the transfer is complete. - (++) In interrupt mode, HAL_QSPI_FifoThresholdCallback() will be called when the fifo threshold - is reached and HAL_QSPI_RxCpltCallback() will be called when the transfer is complete. - (++) In DMA mode, HAL_QSPI_RxHalfCpltCallback() will be called at the half transfer and - HAL_QSPI_RxCpltCallback() will be called when the transfer is complete. - - *** Auto-polling functional mode *** - ==================================== - [..] - (#) Configure the command sequence and the auto-polling functional mode using the - HAL_QSPI_AutoPolling() or HAL_QSPI_AutoPolling_IT() functions : - (++) Instruction phase : the mode used and if present the instruction opcode. - (++) Address phase : the mode used and if present the size and the address value. - (++) Alternate-bytes phase : the mode used and if present the size and the alternate - bytes values. - (++) Dummy-cycles phase : the number of dummy cycles (mode used is same as data phase). - (++) Data phase : the mode used. - (++) Double Data Rate (DDR) mode : the activation (or not) of this mode and the delay - if activated. - (++) Sending Instruction Only Once (SIOO) mode : the activation (or not) of this mode. - (++) The size of the status bytes, the match value, the mask used, the match mode (OR/AND), - the polling interval and the automatic stop activation. - (#) After the configuration : - (++) In polling mode, the output of the function is done when the status match is reached. The - automatic stop is activated to avoid an infinite loop. - (++) In interrupt mode, HAL_QSPI_StatusMatchCallback() will be called each time the status match is reached. - - *** Memory-mapped functional mode *** - ===================================== - [..] - (#) Configure the command sequence and the memory-mapped functional mode using the - HAL_QSPI_MemoryMapped() functions : - (++) Instruction phase : the mode used and if present the instruction opcode. - (++) Address phase : the mode used and the size. - (++) Alternate-bytes phase : the mode used and if present the size and the alternate - bytes values. - (++) Dummy-cycles phase : the number of dummy cycles (mode used is same as data phase). - (++) Data phase : the mode used. - (++) Double Data Rate (DDR) mode : the activation (or not) of this mode and the delay - if activated. - (++) Sending Instruction Only Once (SIOO) mode : the activation (or not) of this mode. - (++) The timeout activation and the timeout period. - (#) After the configuration, the QuadSPI will be used as soon as an access on the AHB is done on - the address range. HAL_QSPI_TimeOutCallback() will be called when the timeout expires. - - *** Errors management and abort functionality *** - ================================================= - [..] - (#) HAL_QSPI_GetError() function gives the error raised during the last operation. - (#) HAL_QSPI_Abort() and HAL_QSPI_AbortIT() functions aborts any on-going operation and - flushes the fifo : - (++) In polling mode, the output of the function is done when the transfer - complete bit is set and the busy bit cleared. - (++) In interrupt mode, HAL_QSPI_AbortCpltCallback() will be called when - the transfer complete bit is set. - - *** Control functions *** - ========================= - [..] - (#) HAL_QSPI_GetState() function gives the current state of the HAL QuadSPI driver. - (#) HAL_QSPI_SetTimeout() function configures the timeout value used in the driver. - (#) HAL_QSPI_SetFifoThreshold() function configures the threshold on the Fifo of the QSPI IP. - (#) HAL_QSPI_GetFifoThreshold() function gives the current of the Fifo's threshold - (#) HAL_QSPI_SetFlashID() function configures the index of the flash memory to be accessed. - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_QSPI_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions HAL_QSPI_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) ErrorCallback : callback when error occurs. - (+) AbortCpltCallback : callback when abort is completed. - (+) FifoThresholdCallback : callback when the fifo threshold is reached. - (+) CmdCpltCallback : callback when a command without data is completed. - (+) RxCpltCallback : callback when a reception transfer is completed. - (+) TxCpltCallback : callback when a transmission transfer is completed. - (+) RxHalfCpltCallback : callback when half of the reception transfer is completed. - (+) TxHalfCpltCallback : callback when half of the transmission transfer is completed. - (+) StatusMatchCallback : callback when a status match occurs. - (+) TimeOutCallback : callback when the timeout perioed expires. - (+) MspInitCallback : QSPI MspInit. - (+) MspDeInitCallback : QSPI MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function HAL_QSPI_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) ErrorCallback : callback when error occurs. - (+) AbortCpltCallback : callback when abort is completed. - (+) FifoThresholdCallback : callback when the fifo threshold is reached. - (+) CmdCpltCallback : callback when a command without data is completed. - (+) RxCpltCallback : callback when a reception transfer is completed. - (+) TxCpltCallback : callback when a transmission transfer is completed. - (+) RxHalfCpltCallback : callback when half of the reception transfer is completed. - (+) TxHalfCpltCallback : callback when half of the transmission transfer is completed. - (+) StatusMatchCallback : callback when a status match occurs. - (+) TimeOutCallback : callback when the timeout perioed expires. - (+) MspInitCallback : QSPI MspInit. - (+) MspDeInitCallback : QSPI MspDeInit. - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the HAL_QSPI_Init and if the state is HAL_QSPI_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the HAL_QSPI_Init - and HAL_QSPI_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_QSPI_Init and HAL_QSPI_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_QSPI_RegisterCallback before calling HAL_QSPI_DeInit - or HAL_QSPI_Init function. - - When The compilation define USE_HAL_QSPI_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - *** Workarounds linked to Silicon Limitation *** - ==================================================== - [..] - (#) Workarounds Implemented inside HAL Driver - (++) Extra data written in the FIFO at the end of a read transfer - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -#if defined(QUADSPI) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup QSPI QSPI - * @brief QSPI HAL module driver - * @{ - */ -#ifdef HAL_QSPI_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ - -/* Private define ------------------------------------------------------------*/ -/** @defgroup QSPI_Private_Constants QSPI Private Constants - * @{ - */ -#define QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE 0x00000000U /*!Instance)); - assert_param(IS_QSPI_CLOCK_PRESCALER(hqspi->Init.ClockPrescaler)); - assert_param(IS_QSPI_FIFO_THRESHOLD(hqspi->Init.FifoThreshold)); - assert_param(IS_QSPI_SSHIFT(hqspi->Init.SampleShifting)); - assert_param(IS_QSPI_FLASH_SIZE(hqspi->Init.FlashSize)); - assert_param(IS_QSPI_CS_HIGH_TIME(hqspi->Init.ChipSelectHighTime)); - assert_param(IS_QSPI_CLOCK_MODE(hqspi->Init.ClockMode)); - assert_param(IS_QSPI_DUAL_FLASH_MODE(hqspi->Init.DualFlash)); - - if (hqspi->Init.DualFlash != QSPI_DUALFLASH_ENABLE ) - { - assert_param(IS_QSPI_FLASH_ID(hqspi->Init.FlashID)); - } - - if(hqspi->State == HAL_QSPI_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hqspi->Lock = HAL_UNLOCKED; - -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - /* Reset Callback pointers in HAL_QSPI_STATE_RESET only */ - hqspi->ErrorCallback = HAL_QSPI_ErrorCallback; - hqspi->AbortCpltCallback = HAL_QSPI_AbortCpltCallback; - hqspi->FifoThresholdCallback = HAL_QSPI_FifoThresholdCallback; - hqspi->CmdCpltCallback = HAL_QSPI_CmdCpltCallback; - hqspi->RxCpltCallback = HAL_QSPI_RxCpltCallback; - hqspi->TxCpltCallback = HAL_QSPI_TxCpltCallback; - hqspi->RxHalfCpltCallback = HAL_QSPI_RxHalfCpltCallback; - hqspi->TxHalfCpltCallback = HAL_QSPI_TxHalfCpltCallback; - hqspi->StatusMatchCallback = HAL_QSPI_StatusMatchCallback; - hqspi->TimeOutCallback = HAL_QSPI_TimeOutCallback; - - if(hqspi->MspInitCallback == NULL) - { - hqspi->MspInitCallback = HAL_QSPI_MspInit; - } - - /* Init the low level hardware */ - hqspi->MspInitCallback(hqspi); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_QSPI_MspInit(hqspi); -#endif - - /* Configure the default timeout for the QSPI memory access */ - HAL_QSPI_SetTimeout(hqspi, HAL_QSPI_TIMEOUT_DEFAULT_VALUE); - } - - /* Configure QSPI FIFO Threshold */ - MODIFY_REG(hqspi->Instance->CR, QUADSPI_CR_FTHRES, - ((hqspi->Init.FifoThreshold - 1U) << QUADSPI_CR_FTHRES_Pos)); - - /* Wait till BUSY flag reset */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, hqspi->Timeout); - - if(status == HAL_OK) - { - /* Configure QSPI Clock Prescaler and Sample Shift */ - MODIFY_REG(hqspi->Instance->CR, (QUADSPI_CR_PRESCALER | QUADSPI_CR_SSHIFT | QUADSPI_CR_FSEL | QUADSPI_CR_DFM), - ((hqspi->Init.ClockPrescaler << QUADSPI_CR_PRESCALER_Pos) | - hqspi->Init.SampleShifting | hqspi->Init.FlashID | hqspi->Init.DualFlash)); - - /* Configure QSPI Flash Size, CS High Time and Clock Mode */ - MODIFY_REG(hqspi->Instance->DCR, (QUADSPI_DCR_FSIZE | QUADSPI_DCR_CSHT | QUADSPI_DCR_CKMODE), - ((hqspi->Init.FlashSize << QUADSPI_DCR_FSIZE_Pos) | - hqspi->Init.ChipSelectHighTime | hqspi->Init.ClockMode)); - - /* Enable the QSPI peripheral */ - __HAL_QSPI_ENABLE(hqspi); - - /* Set QSPI error code to none */ - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - /* Initialize the QSPI state */ - hqspi->State = HAL_QSPI_STATE_READY; - } - - /* Release Lock */ - __HAL_UNLOCK(hqspi); - - /* Return function status */ - return status; -} - -/** - * @brief De-Initialize the QSPI peripheral. - * @param hqspi : QSPI handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_DeInit(QSPI_HandleTypeDef *hqspi) -{ - /* Check the QSPI handle allocation */ - if(hqspi == NULL) - { - return HAL_ERROR; - } - - /* Disable the QSPI Peripheral Clock */ - __HAL_QSPI_DISABLE(hqspi); - -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - if(hqspi->MspDeInitCallback == NULL) - { - hqspi->MspDeInitCallback = HAL_QSPI_MspDeInit; - } - - /* DeInit the low level hardware */ - hqspi->MspDeInitCallback(hqspi); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ - HAL_QSPI_MspDeInit(hqspi); -#endif - - /* Set QSPI error code to none */ - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - /* Initialize the QSPI state */ - hqspi->State = HAL_QSPI_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hqspi); - - return HAL_OK; -} - -/** - * @brief Initialize the QSPI MSP. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_MspInit(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_QSPI_MspInit can be implemented in the user file - */ -} - -/** - * @brief DeInitialize the QSPI MSP. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_MspDeInit(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_QSPI_MspDeInit can be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup QSPI_Exported_Functions_Group2 Input and Output operation functions - * @brief QSPI Transmit/Receive functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to : - (+) Handle the interrupts. - (+) Handle the command sequence. - (+) Transmit data in blocking, interrupt or DMA mode. - (+) Receive data in blocking, interrupt or DMA mode. - (+) Manage the auto-polling functional mode. - (+) Manage the memory-mapped functional mode. - -@endverbatim - * @{ - */ - -/** - * @brief Handle QSPI interrupt request. - * @param hqspi : QSPI handle - * @retval None - */ -void HAL_QSPI_IRQHandler(QSPI_HandleTypeDef *hqspi) -{ - __IO uint32_t *data_reg; - uint32_t flag = READ_REG(hqspi->Instance->SR); - uint32_t itsource = READ_REG(hqspi->Instance->CR); - - /* QSPI Fifo Threshold interrupt occurred ----------------------------------*/ - if(((flag & QSPI_FLAG_FT) != 0U) && ((itsource & QSPI_IT_FT) != 0U)) - { - data_reg = &hqspi->Instance->DR; - - if(hqspi->State == HAL_QSPI_STATE_BUSY_INDIRECT_TX) - { - /* Transmission process */ - while(__HAL_QSPI_GET_FLAG(hqspi, QSPI_FLAG_FT) != RESET) - { - if (hqspi->TxXferCount > 0U) - { - /* Fill the FIFO until the threshold is reached */ - *((__IO uint8_t *)data_reg) = *hqspi->pTxBuffPtr; - hqspi->pTxBuffPtr++; - hqspi->TxXferCount--; - } - else - { - /* No more data available for the transfer */ - /* Disable the QSPI FIFO Threshold Interrupt */ - __HAL_QSPI_DISABLE_IT(hqspi, QSPI_IT_FT); - break; - } - } - } - else if(hqspi->State == HAL_QSPI_STATE_BUSY_INDIRECT_RX) - { - /* Receiving Process */ - while(__HAL_QSPI_GET_FLAG(hqspi, QSPI_FLAG_FT) != RESET) - { - if (hqspi->RxXferCount > 0U) - { - /* Read the FIFO until the threshold is reached */ - *hqspi->pRxBuffPtr = *((__IO uint8_t *)data_reg); - hqspi->pRxBuffPtr++; - hqspi->RxXferCount--; - } - else - { - /* All data have been received for the transfer */ - /* Disable the QSPI FIFO Threshold Interrupt */ - __HAL_QSPI_DISABLE_IT(hqspi, QSPI_IT_FT); - break; - } - } - } - else - { - /* Nothing to do */ - } - - /* FIFO Threshold callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->FifoThresholdCallback(hqspi); -#else - HAL_QSPI_FifoThresholdCallback(hqspi); -#endif - } - - /* QSPI Transfer Complete interrupt occurred -------------------------------*/ - else if(((flag & QSPI_FLAG_TC) != 0U) && ((itsource & QSPI_IT_TC) != 0U)) - { - /* Clear interrupt */ - WRITE_REG(hqspi->Instance->FCR, QSPI_FLAG_TC); - - /* Disable the QSPI FIFO Threshold, Transfer Error and Transfer complete Interrupts */ - __HAL_QSPI_DISABLE_IT(hqspi, QSPI_IT_TC | QSPI_IT_TE | QSPI_IT_FT); - - /* Transfer complete callback */ - if(hqspi->State == HAL_QSPI_STATE_BUSY_INDIRECT_TX) - { - if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) - { - /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ - CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - - /* Disable the DMA channel */ - __HAL_DMA_DISABLE(hqspi->hdma); - } - - /* Clear Busy bit */ - HAL_QSPI_Abort_IT(hqspi); - - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - - /* TX Complete callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->TxCpltCallback(hqspi); -#else - HAL_QSPI_TxCpltCallback(hqspi); -#endif - } - else if(hqspi->State == HAL_QSPI_STATE_BUSY_INDIRECT_RX) - { - if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) - { - /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ - CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - - /* Disable the DMA channel */ - __HAL_DMA_DISABLE(hqspi->hdma); - } - else - { - data_reg = &hqspi->Instance->DR; - while(READ_BIT(hqspi->Instance->SR, QUADSPI_SR_FLEVEL) != 0U) - { - if (hqspi->RxXferCount > 0U) - { - /* Read the last data received in the FIFO until it is empty */ - *hqspi->pRxBuffPtr = *((__IO uint8_t *)data_reg); - hqspi->pRxBuffPtr++; - hqspi->RxXferCount--; - } - else - { - /* All data have been received for the transfer */ - break; - } - } - } - - /* Workaround - Extra data written in the FIFO at the end of a read transfer */ - HAL_QSPI_Abort_IT(hqspi); - - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - - /* RX Complete callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->RxCpltCallback(hqspi); -#else - HAL_QSPI_RxCpltCallback(hqspi); -#endif - } - else if(hqspi->State == HAL_QSPI_STATE_BUSY) - { - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - - /* Command Complete callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->CmdCpltCallback(hqspi); -#else - HAL_QSPI_CmdCpltCallback(hqspi); -#endif - } - else if(hqspi->State == HAL_QSPI_STATE_ABORT) - { - /* Reset functional mode configuration to indirect write mode by default */ - CLEAR_BIT(hqspi->Instance->CCR, QUADSPI_CCR_FMODE); - - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - - if (hqspi->ErrorCode == HAL_QSPI_ERROR_NONE) - { - /* Abort called by the user */ - - /* Abort Complete callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->AbortCpltCallback(hqspi); -#else - HAL_QSPI_AbortCpltCallback(hqspi); -#endif - } - else - { - /* Abort due to an error (eg : DMA error) */ - - /* Error callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->ErrorCallback(hqspi); -#else - HAL_QSPI_ErrorCallback(hqspi); -#endif - } - } - else - { - /* Nothing to do */ - } - } - - /* QSPI Status Match interrupt occurred ------------------------------------*/ - else if(((flag & QSPI_FLAG_SM) != 0U) && ((itsource & QSPI_IT_SM) != 0U)) - { - /* Clear interrupt */ - WRITE_REG(hqspi->Instance->FCR, QSPI_FLAG_SM); - - /* Check if the automatic poll mode stop is activated */ - if(READ_BIT(hqspi->Instance->CR, QUADSPI_CR_APMS) != 0U) - { - /* Disable the QSPI Transfer Error and Status Match Interrupts */ - __HAL_QSPI_DISABLE_IT(hqspi, (QSPI_IT_SM | QSPI_IT_TE)); - - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - } - - /* Status match callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->StatusMatchCallback(hqspi); -#else - HAL_QSPI_StatusMatchCallback(hqspi); -#endif - } - - /* QSPI Transfer Error interrupt occurred ----------------------------------*/ - else if(((flag & QSPI_FLAG_TE) != 0U) && ((itsource & QSPI_IT_TE) != 0U)) - { - /* Clear interrupt */ - WRITE_REG(hqspi->Instance->FCR, QSPI_FLAG_TE); - - /* Disable all the QSPI Interrupts */ - __HAL_QSPI_DISABLE_IT(hqspi, QSPI_IT_SM | QSPI_IT_TC | QSPI_IT_TE | QSPI_IT_FT); - - /* Set error code */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_TRANSFER; - - if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) - { - /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ - CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - - /* Disable the DMA channel */ - hqspi->hdma->XferAbortCallback = QSPI_DMAAbortCplt; - if (HAL_DMA_Abort_IT(hqspi->hdma) != HAL_OK) - { - /* Set error code to DMA */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; - - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - - /* Error callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->ErrorCallback(hqspi); -#else - HAL_QSPI_ErrorCallback(hqspi); -#endif - } - } - else - { - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - - /* Error callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->ErrorCallback(hqspi); -#else - HAL_QSPI_ErrorCallback(hqspi); -#endif - } - } - - /* QSPI Timeout interrupt occurred -----------------------------------------*/ - else if(((flag & QSPI_FLAG_TO) != 0U) && ((itsource & QSPI_IT_TO) != 0U)) - { - /* Clear interrupt */ - WRITE_REG(hqspi->Instance->FCR, QSPI_FLAG_TO); - - /* Timeout callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->TimeOutCallback(hqspi); -#else - HAL_QSPI_TimeOutCallback(hqspi); -#endif - } - - else - { - /* Nothing to do */ - } -} - -/** - * @brief Set the command configuration. - * @param hqspi : QSPI handle - * @param cmd : structure that contains the command configuration information - * @param Timeout : Timeout duration - * @note This function is used only in Indirect Read or Write Modes - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_Command(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, uint32_t Timeout) -{ - HAL_StatusTypeDef status; - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); - if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) - { - assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); - } - - assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); - } - - assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); - if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) - { - assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); - } - - assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); - assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); - - assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); - assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); - assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - /* Update QSPI state */ - hqspi->State = HAL_QSPI_STATE_BUSY; - - /* Wait till BUSY flag reset */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, Timeout); - - if (status == HAL_OK) - { - /* Call the configuration function */ - QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); - - if (cmd->DataMode == QSPI_DATA_NONE) - { - /* When there is no data phase, the transfer start as soon as the configuration is done - so wait until TC flag is set to go back in idle state */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_TC, SET, tickstart, Timeout); - - if (status == HAL_OK) - { - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); - - /* Update QSPI state */ - hqspi->State = HAL_QSPI_STATE_READY; - } - } - else - { - /* Update QSPI state */ - hqspi->State = HAL_QSPI_STATE_READY; - } - } - } - else - { - status = HAL_BUSY; - } - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Return function status */ - return status; -} - -/** - * @brief Set the command configuration in interrupt mode. - * @param hqspi : QSPI handle - * @param cmd : structure that contains the command configuration information - * @note This function is used only in Indirect Read or Write Modes - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_Command_IT(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd) -{ - HAL_StatusTypeDef status; - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); - if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) - { - assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); - } - - assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); - } - - assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); - if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) - { - assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); - } - - assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); - assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); - - assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); - assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); - assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - /* Update QSPI state */ - hqspi->State = HAL_QSPI_STATE_BUSY; - - /* Wait till BUSY flag reset */ - status = QSPI_WaitFlagStateUntilTimeout_CPUCycle(hqspi, QSPI_FLAG_BUSY, RESET, hqspi->Timeout); - - if (status == HAL_OK) - { - if (cmd->DataMode == QSPI_DATA_NONE) - { - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TE | QSPI_FLAG_TC); - } - - /* Call the configuration function */ - QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); - - if (cmd->DataMode == QSPI_DATA_NONE) - { - /* When there is no data phase, the transfer start as soon as the configuration is done - so activate TC and TE interrupts */ - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Enable the QSPI Transfer Error Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE | QSPI_IT_TC); - } - else - { - /* Update QSPI state */ - hqspi->State = HAL_QSPI_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - } - else - { - status = HAL_BUSY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - - /* Return function status */ - return status; -} - -/** - * @brief Transmit an amount of data in blocking mode. - * @param hqspi : QSPI handle - * @param pData : pointer to data buffer - * @param Timeout : Timeout duration - * @note This function is used only in Indirect Write Mode - - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_Transmit(QSPI_HandleTypeDef *hqspi, uint8_t *pData, uint32_t Timeout) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tickstart = HAL_GetTick(); - __IO uint32_t *data_reg = &hqspi->Instance->DR; - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - if(pData != NULL ) - { - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_TX; - - /* Configure counters and size of the handle */ - hqspi->TxXferCount = READ_REG(hqspi->Instance->DLR) + 1U; - hqspi->TxXferSize = READ_REG(hqspi->Instance->DLR) + 1U; - hqspi->pTxBuffPtr = pData; - - /* Configure QSPI: CCR register with functional as indirect write */ - MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); - - while(hqspi->TxXferCount > 0U) - { - /* Wait until FT flag is set to send data */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_FT, SET, tickstart, Timeout); - - if (status != HAL_OK) - { - break; - } - - *((__IO uint8_t *)data_reg) = *hqspi->pTxBuffPtr; - hqspi->pTxBuffPtr++; - hqspi->TxXferCount--; - } - - if (status == HAL_OK) - { - /* Wait until TC flag is set to go back in idle state */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_TC, SET, tickstart, Timeout); - - if (status == HAL_OK) - { - /* Clear Transfer Complete bit */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); - - /* Clear Busy bit */ - status = HAL_QSPI_Abort(hqspi); - } - } - - /* Update QSPI state */ - hqspi->State = HAL_QSPI_STATE_READY; - } - else - { - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - } - } - else - { - status = HAL_BUSY; - } - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - return status; -} - - -/** - * @brief Receive an amount of data in blocking mode. - * @param hqspi : QSPI handle - * @param pData : pointer to data buffer - * @param Timeout : Timeout duration - * @note This function is used only in Indirect Read Mode - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_Receive(QSPI_HandleTypeDef *hqspi, uint8_t *pData, uint32_t Timeout) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tickstart = HAL_GetTick(); - uint32_t addr_reg = READ_REG(hqspi->Instance->AR); - __IO uint32_t *data_reg = &hqspi->Instance->DR; - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - if(pData != NULL ) - { - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_RX; - - /* Configure counters and size of the handle */ - hqspi->RxXferCount = READ_REG(hqspi->Instance->DLR) + 1U; - hqspi->RxXferSize = READ_REG(hqspi->Instance->DLR) + 1U; - hqspi->pRxBuffPtr = pData; - - /* Configure QSPI: CCR register with functional as indirect read */ - MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_READ); - - /* Start the transfer by re-writing the address in AR register */ - WRITE_REG(hqspi->Instance->AR, addr_reg); - - while(hqspi->RxXferCount > 0U) - { - /* Wait until FT or TC flag is set to read received data */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, (QSPI_FLAG_FT | QSPI_FLAG_TC), SET, tickstart, Timeout); - - if (status != HAL_OK) - { - break; - } - - *hqspi->pRxBuffPtr = *((__IO uint8_t *)data_reg); - hqspi->pRxBuffPtr++; - hqspi->RxXferCount--; - } - - if (status == HAL_OK) - { - /* Wait until TC flag is set to go back in idle state */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_TC, SET, tickstart, Timeout); - - if (status == HAL_OK) - { - /* Clear Transfer Complete bit */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); - - /* Workaround - Extra data written in the FIFO at the end of a read transfer */ - status = HAL_QSPI_Abort(hqspi); - } - } - - /* Update QSPI state */ - hqspi->State = HAL_QSPI_STATE_READY; - } - else - { - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - } - } - else - { - status = HAL_BUSY; - } - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - return status; -} - -/** - * @brief Send an amount of data in non-blocking mode with interrupt. - * @param hqspi : QSPI handle - * @param pData : pointer to data buffer - * @note This function is used only in Indirect Write Mode - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_Transmit_IT(QSPI_HandleTypeDef *hqspi, uint8_t *pData) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - if(pData != NULL ) - { - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_TX; - - /* Configure counters and size of the handle */ - hqspi->TxXferCount = READ_REG(hqspi->Instance->DLR) + 1U; - hqspi->TxXferSize = READ_REG(hqspi->Instance->DLR) + 1U; - hqspi->pTxBuffPtr = pData; - - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TE | QSPI_FLAG_TC); - - /* Configure QSPI: CCR register with functional as indirect write */ - MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Enable the QSPI transfer error, FIFO threshold and transfer complete Interrupts */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE | QSPI_IT_FT | QSPI_IT_TC); - } - else - { - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - } - else - { - status = HAL_BUSY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - - return status; -} - -/** - * @brief Receive an amount of data in non-blocking mode with interrupt. - * @param hqspi : QSPI handle - * @param pData : pointer to data buffer - * @note This function is used only in Indirect Read Mode - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_Receive_IT(QSPI_HandleTypeDef *hqspi, uint8_t *pData) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t addr_reg = READ_REG(hqspi->Instance->AR); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - if(pData != NULL ) - { - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_RX; - - /* Configure counters and size of the handle */ - hqspi->RxXferCount = READ_REG(hqspi->Instance->DLR) + 1U; - hqspi->RxXferSize = READ_REG(hqspi->Instance->DLR) + 1U; - hqspi->pRxBuffPtr = pData; - - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TE | QSPI_FLAG_TC); - - /* Configure QSPI: CCR register with functional as indirect read */ - MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_READ); - - /* Start the transfer by re-writing the address in AR register */ - WRITE_REG(hqspi->Instance->AR, addr_reg); - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Enable the QSPI transfer error, FIFO threshold and transfer complete Interrupts */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE | QSPI_IT_FT | QSPI_IT_TC); - } - else - { - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - } - else - { - status = HAL_BUSY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - - return status; -} - -/** - * @brief Send an amount of data in non-blocking mode with DMA. - * @param hqspi : QSPI handle - * @param pData : pointer to data buffer - * @note This function is used only in Indirect Write Mode - * @note If DMA peripheral access is configured as halfword, the number - * of data and the fifo threshold should be aligned on halfword - * @note If DMA peripheral access is configured as word, the number - * of data and the fifo threshold should be aligned on word - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_Transmit_DMA(QSPI_HandleTypeDef *hqspi, uint8_t *pData) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t data_size = (READ_REG(hqspi->Instance->DLR) + 1U); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - /* Clear the error code */ - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - if(pData != NULL ) - { - /* Configure counters of the handle */ - if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_BYTE) - { - hqspi->TxXferCount = data_size; - } - else if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_HALFWORD) - { - if (((data_size % 2U) != 0U) || ((hqspi->Init.FifoThreshold % 2U) != 0U)) - { - /* The number of data or the fifo threshold is not aligned on halfword - => no transfer possible with DMA peripheral access configured as halfword */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - else - { - hqspi->TxXferCount = (data_size >> 1U); - } - } - else if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_WORD) - { - if (((data_size % 4U) != 0U) || ((hqspi->Init.FifoThreshold % 4U) != 0U)) - { - /* The number of data or the fifo threshold is not aligned on word - => no transfer possible with DMA peripheral access configured as word */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - else - { - hqspi->TxXferCount = (data_size >> 2U); - } - } - else - { - /* Nothing to do */ - } - - if (status == HAL_OK) - { - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_TX; - - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, (QSPI_FLAG_TE | QSPI_FLAG_TC)); - - /* Configure size and pointer of the handle */ - hqspi->TxXferSize = hqspi->TxXferCount; - hqspi->pTxBuffPtr = pData; - - /* Configure QSPI: CCR register with functional mode as indirect write */ - MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); - - /* Set the QSPI DMA transfer complete callback */ - hqspi->hdma->XferCpltCallback = QSPI_DMATxCplt; - - /* Set the QSPI DMA Half transfer complete callback */ - hqspi->hdma->XferHalfCpltCallback = QSPI_DMATxHalfCplt; - - /* Set the DMA error callback */ - hqspi->hdma->XferErrorCallback = QSPI_DMAError; - - /* Clear the DMA abort callback */ - hqspi->hdma->XferAbortCallback = NULL; - -#if defined (QSPI1_V2_1L) - /* Bug "ES0305 section 2.1.8 In some specific cases, DMA2 data corruption occurs when managing - AHB and APB2 peripherals in a concurrent way" Workaround Implementation: - Change the following configuration of DMA peripheral - - Enable peripheral increment - - Disable memory increment - - Set DMA direction as peripheral to memory mode */ - - /* Enable peripheral increment mode of the DMA */ - hqspi->hdma->Init.PeriphInc = DMA_PINC_ENABLE; - - /* Disable memory increment mode of the DMA */ - hqspi->hdma->Init.MemInc = DMA_MINC_DISABLE; - - /* Update peripheral/memory increment mode bits */ - MODIFY_REG(hqspi->hdma->Instance->CR, (DMA_SxCR_MINC | DMA_SxCR_PINC), (hqspi->hdma->Init.MemInc | hqspi->hdma->Init.PeriphInc)); - - /* Configure the direction of the DMA */ - hqspi->hdma->Init.Direction = DMA_PERIPH_TO_MEMORY; -#else - /* Configure the direction of the DMA */ - hqspi->hdma->Init.Direction = DMA_MEMORY_TO_PERIPH; -#endif /* QSPI1_V2_1L */ - - /* Update direction mode bit */ - MODIFY_REG(hqspi->hdma->Instance->CR, DMA_SxCR_DIR, hqspi->hdma->Init.Direction); - - /* Enable the QSPI transmit DMA Channel */ - if (HAL_DMA_Start_IT(hqspi->hdma, (uint32_t)pData, (uint32_t)&hqspi->Instance->DR, hqspi->TxXferSize) == HAL_OK) - { - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Enable the QSPI transfer error Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE); - - /* Enable the DMA transfer by setting the DMAEN bit in the QSPI CR register */ - SET_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - } - else - { - status = HAL_ERROR; - hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; - hqspi->State = HAL_QSPI_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - } - } - else - { - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - } - else - { - status = HAL_BUSY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - - return status; -} - -/** - * @brief Receive an amount of data in non-blocking mode with DMA. - * @param hqspi : QSPI handle - * @param pData : pointer to data buffer. - * @note This function is used only in Indirect Read Mode - * @note If DMA peripheral access is configured as halfword, the number - * of data and the fifo threshold should be aligned on halfword - * @note If DMA peripheral access is configured as word, the number - * of data and the fifo threshold should be aligned on word - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_Receive_DMA(QSPI_HandleTypeDef *hqspi, uint8_t *pData) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t addr_reg = READ_REG(hqspi->Instance->AR); - uint32_t data_size = (READ_REG(hqspi->Instance->DLR) + 1U); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - /* Clear the error code */ - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - if(pData != NULL ) - { - /* Configure counters of the handle */ - if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_BYTE) - { - hqspi->RxXferCount = data_size; - } - else if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_HALFWORD) - { - if (((data_size % 2U) != 0U) || ((hqspi->Init.FifoThreshold % 2U) != 0U)) - { - /* The number of data or the fifo threshold is not aligned on halfword - => no transfer possible with DMA peripheral access configured as halfword */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - else - { - hqspi->RxXferCount = (data_size >> 1U); - } - } - else if (hqspi->hdma->Init.PeriphDataAlignment == DMA_PDATAALIGN_WORD) - { - if (((data_size % 4U) != 0U) || ((hqspi->Init.FifoThreshold % 4U) != 0U)) - { - /* The number of data or the fifo threshold is not aligned on word - => no transfer possible with DMA peripheral access configured as word */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - else - { - hqspi->RxXferCount = (data_size >> 2U); - } - } - else - { - /* Nothing to do */ - } - - if (status == HAL_OK) - { - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_INDIRECT_RX; - - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, (QSPI_FLAG_TE | QSPI_FLAG_TC)); - - /* Configure size and pointer of the handle */ - hqspi->RxXferSize = hqspi->RxXferCount; - hqspi->pRxBuffPtr = pData; - - /* Set the QSPI DMA transfer complete callback */ - hqspi->hdma->XferCpltCallback = QSPI_DMARxCplt; - - /* Set the QSPI DMA Half transfer complete callback */ - hqspi->hdma->XferHalfCpltCallback = QSPI_DMARxHalfCplt; - - /* Set the DMA error callback */ - hqspi->hdma->XferErrorCallback = QSPI_DMAError; - - /* Clear the DMA abort callback */ - hqspi->hdma->XferAbortCallback = NULL; - -#if defined (QSPI1_V2_1L) - /* Bug "ES0305 section 2.1.8 In some specific cases, DMA2 data corruption occurs when managing - AHB and APB2 peripherals in a concurrent way" Workaround Implementation: - Change the following configuration of DMA peripheral - - Enable peripheral increment - - Disable memory increment - - Set DMA direction as memory to peripheral mode - - 4 Extra words (32-bits) are added for read operation to guarantee - the last data is transferred from DMA FIFO to RAM memory */ - - /* Enable peripheral increment of the DMA */ - hqspi->hdma->Init.PeriphInc = DMA_PINC_ENABLE; - - /* Disable memory increment of the DMA */ - hqspi->hdma->Init.MemInc = DMA_MINC_DISABLE; - - /* Update peripheral/memory increment mode bits */ - MODIFY_REG(hqspi->hdma->Instance->CR, (DMA_SxCR_MINC | DMA_SxCR_PINC), (hqspi->hdma->Init.MemInc | hqspi->hdma->Init.PeriphInc)); - - /* Configure the direction of the DMA */ - hqspi->hdma->Init.Direction = DMA_MEMORY_TO_PERIPH; - - /* 4 Extra words (32-bits) are needed for read operation to guarantee - the last data is transferred from DMA FIFO to RAM memory */ - WRITE_REG(hqspi->Instance->DLR, (data_size - 1U + 16U)); - - /* Update direction mode bit */ - MODIFY_REG(hqspi->hdma->Instance->CR, DMA_SxCR_DIR, hqspi->hdma->Init.Direction); - - /* Configure QSPI: CCR register with functional as indirect read */ - MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_READ); - - /* Start the transfer by re-writing the address in AR register */ - WRITE_REG(hqspi->Instance->AR, addr_reg); - - /* Enable the DMA Channel */ - if(HAL_DMA_Start_IT(hqspi->hdma, (uint32_t)&hqspi->Instance->DR, (uint32_t)pData, hqspi->RxXferSize) == HAL_OK) - { - /* Enable the DMA transfer by setting the DMAEN bit in the QSPI CR register */ - SET_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Enable the QSPI transfer error Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE); - } - else - { - status = HAL_ERROR; - hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; - hqspi->State = HAL_QSPI_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } -#else - /* Configure the direction of the DMA */ - hqspi->hdma->Init.Direction = DMA_PERIPH_TO_MEMORY; - - /* Update direction mode bit */ - MODIFY_REG(hqspi->hdma->Instance->CR, DMA_SxCR_DIR, hqspi->hdma->Init.Direction); - - /* Enable the DMA Channel */ - if(HAL_DMA_Start_IT(hqspi->hdma, (uint32_t)&hqspi->Instance->DR, (uint32_t)pData, hqspi->RxXferSize)== HAL_OK) - { - /* Configure QSPI: CCR register with functional as indirect read */ - MODIFY_REG(hqspi->Instance->CCR, QUADSPI_CCR_FMODE, QSPI_FUNCTIONAL_MODE_INDIRECT_READ); - - /* Start the transfer by re-writing the address in AR register */ - WRITE_REG(hqspi->Instance->AR, addr_reg); - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Enable the QSPI transfer error Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TE); - - /* Enable the DMA transfer by setting the DMAEN bit in the QSPI CR register */ - SET_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - } - else - { - status = HAL_ERROR; - hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; - hqspi->State = HAL_QSPI_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } -#endif /* QSPI1_V2_1L */ - } - } - else - { - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_PARAM; - status = HAL_ERROR; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - } - else - { - status = HAL_BUSY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - - return status; -} - -/** - * @brief Configure the QSPI Automatic Polling Mode in blocking mode. - * @param hqspi : QSPI handle - * @param cmd : structure that contains the command configuration information. - * @param cfg : structure that contains the polling configuration information. - * @param Timeout : Timeout duration - * @note This function is used only in Automatic Polling Mode - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_AutoPolling(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_AutoPollingTypeDef *cfg, uint32_t Timeout) -{ - HAL_StatusTypeDef status; - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); - if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) - { - assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); - } - - assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); - } - - assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); - if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) - { - assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); - } - - assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); - assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); - - assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); - assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); - assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); - - assert_param(IS_QSPI_INTERVAL(cfg->Interval)); - assert_param(IS_QSPI_STATUS_BYTES_SIZE(cfg->StatusBytesSize)); - assert_param(IS_QSPI_MATCH_MODE(cfg->MatchMode)); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_AUTO_POLLING; - - /* Wait till BUSY flag reset */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, Timeout); - - if (status == HAL_OK) - { - /* Configure QSPI: PSMAR register with the status match value */ - WRITE_REG(hqspi->Instance->PSMAR, cfg->Match); - - /* Configure QSPI: PSMKR register with the status mask value */ - WRITE_REG(hqspi->Instance->PSMKR, cfg->Mask); - - /* Configure QSPI: PIR register with the interval value */ - WRITE_REG(hqspi->Instance->PIR, cfg->Interval); - - /* Configure QSPI: CR register with Match mode and Automatic stop enabled - (otherwise there will be an infinite loop in blocking mode) */ - MODIFY_REG(hqspi->Instance->CR, (QUADSPI_CR_PMM | QUADSPI_CR_APMS), - (cfg->MatchMode | QSPI_AUTOMATIC_STOP_ENABLE)); - - /* Call the configuration function */ - cmd->NbData = cfg->StatusBytesSize; - QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_AUTO_POLLING); - - /* Wait until SM flag is set to go back in idle state */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_SM, SET, tickstart, Timeout); - - if (status == HAL_OK) - { - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_SM); - - /* Update state */ - hqspi->State = HAL_QSPI_STATE_READY; - } - } - } - else - { - status = HAL_BUSY; - } - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Return function status */ - return status; -} - -/** - * @brief Configure the QSPI Automatic Polling Mode in non-blocking mode. - * @param hqspi : QSPI handle - * @param cmd : structure that contains the command configuration information. - * @param cfg : structure that contains the polling configuration information. - * @note This function is used only in Automatic Polling Mode - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_AutoPolling_IT(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_AutoPollingTypeDef *cfg) -{ - HAL_StatusTypeDef status; - - /* Check the parameters */ - assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); - if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) - { - assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); - } - - assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); - } - - assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); - if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) - { - assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); - } - - assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); - assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); - - assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); - assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); - assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); - - assert_param(IS_QSPI_INTERVAL(cfg->Interval)); - assert_param(IS_QSPI_STATUS_BYTES_SIZE(cfg->StatusBytesSize)); - assert_param(IS_QSPI_MATCH_MODE(cfg->MatchMode)); - assert_param(IS_QSPI_AUTOMATIC_STOP(cfg->AutomaticStop)); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_AUTO_POLLING; - - /* Wait till BUSY flag reset */ - status = QSPI_WaitFlagStateUntilTimeout_CPUCycle(hqspi, QSPI_FLAG_BUSY, RESET, hqspi->Timeout); - - if (status == HAL_OK) - { - /* Configure QSPI: PSMAR register with the status match value */ - WRITE_REG(hqspi->Instance->PSMAR, cfg->Match); - - /* Configure QSPI: PSMKR register with the status mask value */ - WRITE_REG(hqspi->Instance->PSMKR, cfg->Mask); - - /* Configure QSPI: PIR register with the interval value */ - WRITE_REG(hqspi->Instance->PIR, cfg->Interval); - - /* Configure QSPI: CR register with Match mode and Automatic stop mode */ - MODIFY_REG(hqspi->Instance->CR, (QUADSPI_CR_PMM | QUADSPI_CR_APMS), - (cfg->MatchMode | cfg->AutomaticStop)); - - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TE | QSPI_FLAG_SM); - - /* Call the configuration function */ - cmd->NbData = cfg->StatusBytesSize; - QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_AUTO_POLLING); - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Enable the QSPI Transfer Error and status match Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, (QSPI_IT_SM | QSPI_IT_TE)); - - } - else - { - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - } - else - { - status = HAL_BUSY; - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - } - - /* Return function status */ - return status; -} - -/** - * @brief Configure the Memory Mapped mode. - * @param hqspi : QSPI handle - * @param cmd : structure that contains the command configuration information. - * @param cfg : structure that contains the memory mapped configuration information. - * @note This function is used only in Memory mapped Mode - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_MemoryMapped(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_MemoryMappedTypeDef *cfg) -{ - HAL_StatusTypeDef status; - uint32_t tickstart = HAL_GetTick(); - - /* Check the parameters */ - assert_param(IS_QSPI_INSTRUCTION_MODE(cmd->InstructionMode)); - if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) - { - assert_param(IS_QSPI_INSTRUCTION(cmd->Instruction)); - } - - assert_param(IS_QSPI_ADDRESS_MODE(cmd->AddressMode)); - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - assert_param(IS_QSPI_ADDRESS_SIZE(cmd->AddressSize)); - } - - assert_param(IS_QSPI_ALTERNATE_BYTES_MODE(cmd->AlternateByteMode)); - if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) - { - assert_param(IS_QSPI_ALTERNATE_BYTES_SIZE(cmd->AlternateBytesSize)); - } - - assert_param(IS_QSPI_DUMMY_CYCLES(cmd->DummyCycles)); - assert_param(IS_QSPI_DATA_MODE(cmd->DataMode)); - - assert_param(IS_QSPI_DDR_MODE(cmd->DdrMode)); - assert_param(IS_QSPI_DDR_HHC(cmd->DdrHoldHalfCycle)); - assert_param(IS_QSPI_SIOO_MODE(cmd->SIOOMode)); - - assert_param(IS_QSPI_TIMEOUT_ACTIVATION(cfg->TimeOutActivation)); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - hqspi->ErrorCode = HAL_QSPI_ERROR_NONE; - - /* Update state */ - hqspi->State = HAL_QSPI_STATE_BUSY_MEM_MAPPED; - - /* Wait till BUSY flag reset */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, hqspi->Timeout); - - if (status == HAL_OK) - { - /* Configure QSPI: CR register with timeout counter enable */ - MODIFY_REG(hqspi->Instance->CR, QUADSPI_CR_TCEN, cfg->TimeOutActivation); - - if (cfg->TimeOutActivation == QSPI_TIMEOUT_COUNTER_ENABLE) - { - assert_param(IS_QSPI_TIMEOUT_PERIOD(cfg->TimeOutPeriod)); - - /* Configure QSPI: LPTR register with the low-power timeout value */ - WRITE_REG(hqspi->Instance->LPTR, cfg->TimeOutPeriod); - - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TO); - - /* Enable the QSPI TimeOut Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TO); - } - - /* Call the configuration function */ - QSPI_Config(hqspi, cmd, QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED); - } - } - else - { - status = HAL_BUSY; - } - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Return function status */ - return status; -} - -/** - * @brief Transfer Error callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_ErrorCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_QSPI_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief Abort completed callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_AbortCpltCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_QSPI_AbortCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Command completed callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_CmdCpltCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_QSPI_CmdCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_RxCpltCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_QSPI_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx Transfer completed callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_TxCpltCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_QSPI_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Half Transfer completed callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_RxHalfCpltCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_QSPI_RxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx Half Transfer completed callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_TxHalfCpltCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_QSPI_TxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief FIFO Threshold callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_FifoThresholdCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_QSPI_FIFOThresholdCallback could be implemented in the user file - */ -} - -/** - * @brief Status Match callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_StatusMatchCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_QSPI_StatusMatchCallback could be implemented in the user file - */ -} - -/** - * @brief Timeout callback. - * @param hqspi : QSPI handle - * @retval None - */ -__weak void HAL_QSPI_TimeOutCallback(QSPI_HandleTypeDef *hqspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hqspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_QSPI_TimeOutCallback could be implemented in the user file - */ -} -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User QSPI Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hqspi : QSPI handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_QSPI_ERROR_CB_ID QSPI Error Callback ID - * @arg @ref HAL_QSPI_ABORT_CB_ID QSPI Abort Callback ID - * @arg @ref HAL_QSPI_FIFO_THRESHOLD_CB_ID QSPI FIFO Threshold Callback ID - * @arg @ref HAL_QSPI_CMD_CPLT_CB_ID QSPI Command Complete Callback ID - * @arg @ref HAL_QSPI_RX_CPLT_CB_ID QSPI Rx Complete Callback ID - * @arg @ref HAL_QSPI_TX_CPLT_CB_ID QSPI Tx Complete Callback ID - * @arg @ref HAL_QSPI_RX_HALF_CPLT_CB_ID QSPI Rx Half Complete Callback ID - * @arg @ref HAL_QSPI_TX_HALF_CPLT_CB_ID QSPI Tx Half Complete Callback ID - * @arg @ref HAL_QSPI_STATUS_MATCH_CB_ID QSPI Status Match Callback ID - * @arg @ref HAL_QSPI_TIMEOUT_CB_ID QSPI Timeout Callback ID - * @arg @ref HAL_QSPI_MSP_INIT_CB_ID QSPI MspInit callback ID - * @arg @ref HAL_QSPI_MSP_DEINIT_CB_ID QSPI MspDeInit callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_QSPI_RegisterCallback (QSPI_HandleTypeDef *hqspi, HAL_QSPI_CallbackIDTypeDef CallbackId, pQSPI_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - /* Update the error code */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - switch (CallbackId) - { - case HAL_QSPI_ERROR_CB_ID : - hqspi->ErrorCallback = pCallback; - break; - case HAL_QSPI_ABORT_CB_ID : - hqspi->AbortCpltCallback = pCallback; - break; - case HAL_QSPI_FIFO_THRESHOLD_CB_ID : - hqspi->FifoThresholdCallback = pCallback; - break; - case HAL_QSPI_CMD_CPLT_CB_ID : - hqspi->CmdCpltCallback = pCallback; - break; - case HAL_QSPI_RX_CPLT_CB_ID : - hqspi->RxCpltCallback = pCallback; - break; - case HAL_QSPI_TX_CPLT_CB_ID : - hqspi->TxCpltCallback = pCallback; - break; - case HAL_QSPI_RX_HALF_CPLT_CB_ID : - hqspi->RxHalfCpltCallback = pCallback; - break; - case HAL_QSPI_TX_HALF_CPLT_CB_ID : - hqspi->TxHalfCpltCallback = pCallback; - break; - case HAL_QSPI_STATUS_MATCH_CB_ID : - hqspi->StatusMatchCallback = pCallback; - break; - case HAL_QSPI_TIMEOUT_CB_ID : - hqspi->TimeOutCallback = pCallback; - break; - case HAL_QSPI_MSP_INIT_CB_ID : - hqspi->MspInitCallback = pCallback; - break; - case HAL_QSPI_MSP_DEINIT_CB_ID : - hqspi->MspDeInitCallback = pCallback; - break; - default : - /* Update the error code */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (hqspi->State == HAL_QSPI_STATE_RESET) - { - switch (CallbackId) - { - case HAL_QSPI_MSP_INIT_CB_ID : - hqspi->MspInitCallback = pCallback; - break; - case HAL_QSPI_MSP_DEINIT_CB_ID : - hqspi->MspDeInitCallback = pCallback; - break; - default : - /* Update the error code */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hqspi); - return status; -} - -/** - * @brief Unregister a User QSPI Callback - * QSPI Callback is redirected to the weak (surcharged) predefined callback - * @param hqspi : QSPI handle - * @param CallbackId : ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_QSPI_ERROR_CB_ID QSPI Error Callback ID - * @arg @ref HAL_QSPI_ABORT_CB_ID QSPI Abort Callback ID - * @arg @ref HAL_QSPI_FIFO_THRESHOLD_CB_ID QSPI FIFO Threshold Callback ID - * @arg @ref HAL_QSPI_CMD_CPLT_CB_ID QSPI Command Complete Callback ID - * @arg @ref HAL_QSPI_RX_CPLT_CB_ID QSPI Rx Complete Callback ID - * @arg @ref HAL_QSPI_TX_CPLT_CB_ID QSPI Tx Complete Callback ID - * @arg @ref HAL_QSPI_RX_HALF_CPLT_CB_ID QSPI Rx Half Complete Callback ID - * @arg @ref HAL_QSPI_TX_HALF_CPLT_CB_ID QSPI Tx Half Complete Callback ID - * @arg @ref HAL_QSPI_STATUS_MATCH_CB_ID QSPI Status Match Callback ID - * @arg @ref HAL_QSPI_TIMEOUT_CB_ID QSPI Timeout Callback ID - * @arg @ref HAL_QSPI_MSP_INIT_CB_ID QSPI MspInit callback ID - * @arg @ref HAL_QSPI_MSP_DEINIT_CB_ID QSPI MspDeInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_QSPI_UnRegisterCallback (QSPI_HandleTypeDef *hqspi, HAL_QSPI_CallbackIDTypeDef CallbackId) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - switch (CallbackId) - { - case HAL_QSPI_ERROR_CB_ID : - hqspi->ErrorCallback = HAL_QSPI_ErrorCallback; - break; - case HAL_QSPI_ABORT_CB_ID : - hqspi->AbortCpltCallback = HAL_QSPI_AbortCpltCallback; - break; - case HAL_QSPI_FIFO_THRESHOLD_CB_ID : - hqspi->FifoThresholdCallback = HAL_QSPI_FifoThresholdCallback; - break; - case HAL_QSPI_CMD_CPLT_CB_ID : - hqspi->CmdCpltCallback = HAL_QSPI_CmdCpltCallback; - break; - case HAL_QSPI_RX_CPLT_CB_ID : - hqspi->RxCpltCallback = HAL_QSPI_RxCpltCallback; - break; - case HAL_QSPI_TX_CPLT_CB_ID : - hqspi->TxCpltCallback = HAL_QSPI_TxCpltCallback; - break; - case HAL_QSPI_RX_HALF_CPLT_CB_ID : - hqspi->RxHalfCpltCallback = HAL_QSPI_RxHalfCpltCallback; - break; - case HAL_QSPI_TX_HALF_CPLT_CB_ID : - hqspi->TxHalfCpltCallback = HAL_QSPI_TxHalfCpltCallback; - break; - case HAL_QSPI_STATUS_MATCH_CB_ID : - hqspi->StatusMatchCallback = HAL_QSPI_StatusMatchCallback; - break; - case HAL_QSPI_TIMEOUT_CB_ID : - hqspi->TimeOutCallback = HAL_QSPI_TimeOutCallback; - break; - case HAL_QSPI_MSP_INIT_CB_ID : - hqspi->MspInitCallback = HAL_QSPI_MspInit; - break; - case HAL_QSPI_MSP_DEINIT_CB_ID : - hqspi->MspDeInitCallback = HAL_QSPI_MspDeInit; - break; - default : - /* Update the error code */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (hqspi->State == HAL_QSPI_STATE_RESET) - { - switch (CallbackId) - { - case HAL_QSPI_MSP_INIT_CB_ID : - hqspi->MspInitCallback = HAL_QSPI_MspInit; - break; - case HAL_QSPI_MSP_DEINIT_CB_ID : - hqspi->MspDeInitCallback = HAL_QSPI_MspDeInit; - break; - default : - /* Update the error code */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hqspi->ErrorCode |= HAL_QSPI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hqspi); - return status; -} -#endif - -/** - * @} - */ - -/** @defgroup QSPI_Exported_Functions_Group3 Peripheral Control and State functions - * @brief QSPI control and State functions - * -@verbatim - =============================================================================== - ##### Peripheral Control and State functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to : - (+) Check in run-time the state of the driver. - (+) Check the error code set during last operation. - (+) Abort any operation. - - -@endverbatim - * @{ - */ - -/** - * @brief Return the QSPI handle state. - * @param hqspi : QSPI handle - * @retval HAL state - */ -HAL_QSPI_StateTypeDef HAL_QSPI_GetState(QSPI_HandleTypeDef *hqspi) -{ - /* Return QSPI handle state */ - return hqspi->State; -} - -/** -* @brief Return the QSPI error code. -* @param hqspi : QSPI handle -* @retval QSPI Error Code -*/ -uint32_t HAL_QSPI_GetError(QSPI_HandleTypeDef *hqspi) -{ - return hqspi->ErrorCode; -} - -/** -* @brief Abort the current transmission. -* @param hqspi : QSPI handle -* @retval HAL status -*/ -HAL_StatusTypeDef HAL_QSPI_Abort(QSPI_HandleTypeDef *hqspi) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tickstart = HAL_GetTick(); - - /* Check if the state is in one of the busy states */ - if (((uint32_t)hqspi->State & 0x2U) != 0U) - { - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) - { - /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ - CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - - /* Abort DMA channel */ - status = HAL_DMA_Abort(hqspi->hdma); - if(status != HAL_OK) - { - hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; - } - } - - /* Configure QSPI: CR register with Abort request */ - SET_BIT(hqspi->Instance->CR, QUADSPI_CR_ABORT); - - /* Wait until TC flag is set to go back in idle state */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_TC, SET, tickstart, hqspi->Timeout); - - if (status == HAL_OK) - { - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); - - /* Wait until BUSY flag is reset */ - status = QSPI_WaitFlagStateUntilTimeout(hqspi, QSPI_FLAG_BUSY, RESET, tickstart, hqspi->Timeout); - } - - if (status == HAL_OK) - { - /* Reset functional mode configuration to indirect write mode by default */ - CLEAR_BIT(hqspi->Instance->CCR, QUADSPI_CCR_FMODE); - - /* Update state */ - hqspi->State = HAL_QSPI_STATE_READY; - } - } - - return status; -} - -/** -* @brief Abort the current transmission (non-blocking function) -* @param hqspi : QSPI handle -* @retval HAL status -*/ -HAL_StatusTypeDef HAL_QSPI_Abort_IT(QSPI_HandleTypeDef *hqspi) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check if the state is in one of the busy states */ - if (((uint32_t)hqspi->State & 0x2U) != 0U) - { - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Update QSPI state */ - hqspi->State = HAL_QSPI_STATE_ABORT; - - /* Disable all interrupts */ - __HAL_QSPI_DISABLE_IT(hqspi, (QSPI_IT_TO | QSPI_IT_SM | QSPI_IT_FT | QSPI_IT_TC | QSPI_IT_TE)); - - if ((hqspi->Instance->CR & QUADSPI_CR_DMAEN) != 0U) - { - /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ - CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - - /* Abort DMA channel */ - hqspi->hdma->XferAbortCallback = QSPI_DMAAbortCplt; - if (HAL_DMA_Abort_IT(hqspi->hdma) != HAL_OK) - { - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - - /* Abort Complete callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->AbortCpltCallback(hqspi); -#else - HAL_QSPI_AbortCpltCallback(hqspi); -#endif - } - } - else - { - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); - - /* Enable the QSPI Transfer Complete Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TC); - - /* Configure QSPI: CR register with Abort request */ - SET_BIT(hqspi->Instance->CR, QUADSPI_CR_ABORT); - } - } - return status; -} - -/** @brief Set QSPI timeout. - * @param hqspi : QSPI handle. - * @param Timeout : Timeout for the QSPI memory access. - * @retval None - */ -void HAL_QSPI_SetTimeout(QSPI_HandleTypeDef *hqspi, uint32_t Timeout) -{ - hqspi->Timeout = Timeout; -} - -/** @brief Set QSPI Fifo threshold. - * @param hqspi : QSPI handle. - * @param Threshold : Threshold of the Fifo (value between 1 and 16). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_SetFifoThreshold(QSPI_HandleTypeDef *hqspi, uint32_t Threshold) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - /* Synchronize init structure with new FIFO threshold value */ - hqspi->Init.FifoThreshold = Threshold; - - /* Configure QSPI FIFO Threshold */ - MODIFY_REG(hqspi->Instance->CR, QUADSPI_CR_FTHRES, - ((hqspi->Init.FifoThreshold - 1U) << QUADSPI_CR_FTHRES_Pos)); - } - else - { - status = HAL_BUSY; - } - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Return function status */ - return status; -} - -/** @brief Get QSPI Fifo threshold. - * @param hqspi : QSPI handle. - * @retval Fifo threshold (value between 1 and 16) - */ -uint32_t HAL_QSPI_GetFifoThreshold(QSPI_HandleTypeDef *hqspi) -{ - return ((READ_BIT(hqspi->Instance->CR, QUADSPI_CR_FTHRES) >> QUADSPI_CR_FTHRES_Pos) + 1U); -} - -/** @brief Set FlashID. - * @param hqspi : QSPI handle. - * @param FlashID : Index of the flash memory to be accessed. - * This parameter can be a value of @ref QSPI_Flash_Select. - * @note The FlashID is ignored when dual flash mode is enabled. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_QSPI_SetFlashID(QSPI_HandleTypeDef *hqspi, uint32_t FlashID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameter */ - assert_param(IS_QSPI_FLASH_ID(FlashID)); - - /* Process locked */ - __HAL_LOCK(hqspi); - - if(hqspi->State == HAL_QSPI_STATE_READY) - { - /* Synchronize init structure with new FlashID value */ - hqspi->Init.FlashID = FlashID; - - /* Configure QSPI FlashID */ - MODIFY_REG(hqspi->Instance->CR, QUADSPI_CR_FSEL, FlashID); - } - else - { - status = HAL_BUSY; - } - - /* Process unlocked */ - __HAL_UNLOCK(hqspi); - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup QSPI_Private_Functions QSPI Private Functions - * @{ - */ - -/** - * @brief DMA QSPI receive process complete callback. - * @param hdma : DMA handle - * @retval None - */ -static void QSPI_DMARxCplt(DMA_HandleTypeDef *hdma) -{ - QSPI_HandleTypeDef* hqspi = (QSPI_HandleTypeDef*)(hdma->Parent); - hqspi->RxXferCount = 0U; - - /* Enable the QSPI transfer complete Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TC); -} - -/** - * @brief DMA QSPI transmit process complete callback. - * @param hdma : DMA handle - * @retval None - */ -static void QSPI_DMATxCplt(DMA_HandleTypeDef *hdma) -{ - QSPI_HandleTypeDef* hqspi = (QSPI_HandleTypeDef*)(hdma->Parent); - hqspi->TxXferCount = 0U; - - /* Enable the QSPI transfer complete Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TC); -} - -/** - * @brief DMA QSPI receive process half complete callback. - * @param hdma : DMA handle - * @retval None - */ -static void QSPI_DMARxHalfCplt(DMA_HandleTypeDef *hdma) -{ - QSPI_HandleTypeDef* hqspi = (QSPI_HandleTypeDef*)(hdma->Parent); - -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->RxHalfCpltCallback(hqspi); -#else - HAL_QSPI_RxHalfCpltCallback(hqspi); -#endif -} - -/** - * @brief DMA QSPI transmit process half complete callback. - * @param hdma : DMA handle - * @retval None - */ -static void QSPI_DMATxHalfCplt(DMA_HandleTypeDef *hdma) -{ - QSPI_HandleTypeDef* hqspi = (QSPI_HandleTypeDef*)(hdma->Parent); - -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->TxHalfCpltCallback(hqspi); -#else - HAL_QSPI_TxHalfCpltCallback(hqspi); -#endif -} - -/** - * @brief DMA QSPI communication error callback. - * @param hdma : DMA handle - * @retval None - */ -static void QSPI_DMAError(DMA_HandleTypeDef *hdma) -{ - QSPI_HandleTypeDef* hqspi = ( QSPI_HandleTypeDef* )(hdma->Parent); - - /* if DMA error is FIFO error ignore it */ - if(HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) - { - hqspi->RxXferCount = 0U; - hqspi->TxXferCount = 0U; - hqspi->ErrorCode |= HAL_QSPI_ERROR_DMA; - - /* Disable the DMA transfer by clearing the DMAEN bit in the QSPI CR register */ - CLEAR_BIT(hqspi->Instance->CR, QUADSPI_CR_DMAEN); - - /* Abort the QSPI */ - (void)HAL_QSPI_Abort_IT(hqspi); - - } -} - -/** - * @brief DMA QSPI abort complete callback. - * @param hdma : DMA handle - * @retval None - */ -static void QSPI_DMAAbortCplt(DMA_HandleTypeDef *hdma) -{ - QSPI_HandleTypeDef* hqspi = ( QSPI_HandleTypeDef* )(hdma->Parent); - - hqspi->RxXferCount = 0U; - hqspi->TxXferCount = 0U; - - if(hqspi->State == HAL_QSPI_STATE_ABORT) - { - /* DMA Abort called by QSPI abort */ - /* Clear interrupt */ - __HAL_QSPI_CLEAR_FLAG(hqspi, QSPI_FLAG_TC); - - /* Enable the QSPI Transfer Complete Interrupt */ - __HAL_QSPI_ENABLE_IT(hqspi, QSPI_IT_TC); - - /* Configure QSPI: CR register with Abort request */ - SET_BIT(hqspi->Instance->CR, QUADSPI_CR_ABORT); - } - else - { - /* DMA Abort called due to a transfer error interrupt */ - /* Change state of QSPI */ - hqspi->State = HAL_QSPI_STATE_READY; - - /* Error callback */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - hqspi->ErrorCallback(hqspi); -#else - HAL_QSPI_ErrorCallback(hqspi); -#endif - } -} - -/** - * @brief Wait for a flag state until timeout. - * @param hqspi : QSPI handle - * @param Flag : Flag checked - * @param State : Value of the flag expected - * @param Tickstart : Tick start value - * @param Timeout : Duration of the timeout - * @retval HAL status - */ -static HAL_StatusTypeDef QSPI_WaitFlagStateUntilTimeout(QSPI_HandleTypeDef *hqspi, uint32_t Flag, - FlagStatus State, uint32_t Tickstart, uint32_t Timeout) -{ - /* Wait until flag is in expected state */ - while((__HAL_QSPI_GET_FLAG(hqspi, Flag)) != State) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if(((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) - { - hqspi->State = HAL_QSPI_STATE_ERROR; - hqspi->ErrorCode |= HAL_QSPI_ERROR_TIMEOUT; - - return HAL_ERROR; - } - } - } - return HAL_OK; -} - -/** - * @brief Wait for a flag state until timeout using CPU cycle. - * @param hqspi : QSPI handle - * @param Flag : Flag checked - * @param State : Value of the flag expected - * @param Timeout : Duration of the timeout - * @retval HAL status - */ -static HAL_StatusTypeDef QSPI_WaitFlagStateUntilTimeout_CPUCycle(QSPI_HandleTypeDef *hqspi, uint32_t Flag, FlagStatus State, uint32_t Timeout) -{ - __IO uint32_t count = Timeout * (SystemCoreClock / 16U / 1000U); - do - { - if (count-- == 0U) - { - hqspi->State = HAL_QSPI_STATE_ERROR; - hqspi->ErrorCode |= HAL_QSPI_ERROR_TIMEOUT; - return HAL_TIMEOUT; - } - } - while ((__HAL_QSPI_GET_FLAG(hqspi, Flag)) != State); - - return HAL_OK; -} - -/** - * @brief Configure the communication registers. - * @param hqspi : QSPI handle - * @param cmd : structure that contains the command configuration information - * @param FunctionalMode : functional mode to configured - * This parameter can be one of the following values: - * @arg QSPI_FUNCTIONAL_MODE_INDIRECT_WRITE: Indirect write mode - * @arg QSPI_FUNCTIONAL_MODE_INDIRECT_READ: Indirect read mode - * @arg QSPI_FUNCTIONAL_MODE_AUTO_POLLING: Automatic polling mode - * @arg QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED: Memory-mapped mode - * @retval None - */ -static void QSPI_Config(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, uint32_t FunctionalMode) -{ - assert_param(IS_QSPI_FUNCTIONAL_MODE(FunctionalMode)); - - if ((cmd->DataMode != QSPI_DATA_NONE) && (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED)) - { - /* Configure QSPI: DLR register with the number of data to read or write */ - WRITE_REG(hqspi->Instance->DLR, (cmd->NbData - 1U)); - } - - if (cmd->InstructionMode != QSPI_INSTRUCTION_NONE) - { - if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) - { - /* Configure QSPI: ABR register with alternate bytes value */ - WRITE_REG(hqspi->Instance->ABR, cmd->AlternateBytes); - - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - /*---- Command with instruction, address and alternate bytes ----*/ - /* Configure QSPI: CCR register with all communications parameters */ - WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | - cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | - cmd->AlternateBytesSize | cmd->AlternateByteMode | - cmd->AddressSize | cmd->AddressMode | cmd->InstructionMode | - cmd->Instruction | FunctionalMode)); - - if (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED) - { - /* Configure QSPI: AR register with address value */ - WRITE_REG(hqspi->Instance->AR, cmd->Address); - } - } - else - { - /*---- Command with instruction and alternate bytes ----*/ - /* Configure QSPI: CCR register with all communications parameters */ - WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | - cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | - cmd->AlternateBytesSize | cmd->AlternateByteMode | - cmd->AddressMode | cmd->InstructionMode | - cmd->Instruction | FunctionalMode)); - } - } - else - { - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - /*---- Command with instruction and address ----*/ - /* Configure QSPI: CCR register with all communications parameters */ - WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | - cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | - cmd->AlternateByteMode | cmd->AddressSize | cmd->AddressMode | - cmd->InstructionMode | cmd->Instruction | FunctionalMode)); - - if (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED) - { - /* Configure QSPI: AR register with address value */ - WRITE_REG(hqspi->Instance->AR, cmd->Address); - } - } - else - { - /*---- Command with only instruction ----*/ - /* Configure QSPI: CCR register with all communications parameters */ - WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | - cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | - cmd->AlternateByteMode | cmd->AddressMode | - cmd->InstructionMode | cmd->Instruction | FunctionalMode)); - } - } - } - else - { - if (cmd->AlternateByteMode != QSPI_ALTERNATE_BYTES_NONE) - { - /* Configure QSPI: ABR register with alternate bytes value */ - WRITE_REG(hqspi->Instance->ABR, cmd->AlternateBytes); - - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - /*---- Command with address and alternate bytes ----*/ - /* Configure QSPI: CCR register with all communications parameters */ - WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | - cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | - cmd->AlternateBytesSize | cmd->AlternateByteMode | - cmd->AddressSize | cmd->AddressMode | - cmd->InstructionMode | FunctionalMode)); - - if (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED) - { - /* Configure QSPI: AR register with address value */ - WRITE_REG(hqspi->Instance->AR, cmd->Address); - } - } - else - { - /*---- Command with only alternate bytes ----*/ - /* Configure QSPI: CCR register with all communications parameters */ - WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | - cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | - cmd->AlternateBytesSize | cmd->AlternateByteMode | - cmd->AddressMode | cmd->InstructionMode | FunctionalMode)); - } - } - else - { - if (cmd->AddressMode != QSPI_ADDRESS_NONE) - { - /*---- Command with only address ----*/ - /* Configure QSPI: CCR register with all communications parameters */ - WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | - cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | - cmd->AlternateByteMode | cmd->AddressSize | - cmd->AddressMode | cmd->InstructionMode | FunctionalMode)); - - if (FunctionalMode != QSPI_FUNCTIONAL_MODE_MEMORY_MAPPED) - { - /* Configure QSPI: AR register with address value */ - WRITE_REG(hqspi->Instance->AR, cmd->Address); - } - } - else - { - /*---- Command with only data phase ----*/ - if (cmd->DataMode != QSPI_DATA_NONE) - { - /* Configure QSPI: CCR register with all communications parameters */ - WRITE_REG(hqspi->Instance->CCR, (cmd->DdrMode | cmd->DdrHoldHalfCycle | cmd->SIOOMode | - cmd->DataMode | (cmd->DummyCycles << QUADSPI_CCR_DCYC_Pos) | - cmd->AlternateByteMode | cmd->AddressMode | - cmd->InstructionMode | FunctionalMode)); - } - } - } - } -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_QSPI_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(QUADSPI) */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c deleted file mode 100644 index 552ef18ed80a3d2..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c +++ /dev/null @@ -1,1125 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc.c - * @author MCD Application Team - * @brief RCC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Reset and Clock Control (RCC) peripheral: - * + Initialization and de-initialization functions - * + Peripheral Control functions - * - @verbatim - ============================================================================== - ##### RCC specific features ##### - ============================================================================== - [..] - After reset the device is running from Internal High Speed oscillator - (HSI 16MHz) with Flash 0 wait state, Flash prefetch buffer, D-Cache - and I-Cache are disabled, and all peripherals are off except internal - SRAM, Flash and JTAG. - (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses; - all peripherals mapped on these busses are running at HSI speed. - (+) The clock for all peripherals is switched off, except the SRAM and FLASH. - (+) All GPIOs are in input floating state, except the JTAG pins which - are assigned to be used for debug purpose. - - [..] - Once the device started from reset, the user application has to: - (+) Configure the clock source to be used to drive the System clock - (if the application needs higher frequency/performance) - (+) Configure the System clock frequency and Flash settings - (+) Configure the AHB and APB busses prescalers - (+) Enable the clock for the peripheral(s) to be used - (+) Configure the clock source(s) for peripherals which clocks are not - derived from the System clock (I2S, RTC, ADC, USB OTG FS/SDIO/RNG) - - ##### RCC Limitations ##### - ============================================================================== - [..] - A delay between an RCC peripheral clock enable and the effective peripheral - enabling should be taken into account in order to manage the peripheral read/write - from/to registers. - (+) This delay depends on the peripheral mapping. - (+) If peripheral is mapped on AHB: the delay is 2 AHB clock cycle - after the clock enable bit is set on the hardware register - (+) If peripheral is mapped on APB: the delay is 2 APB clock cycle - after the clock enable bit is set on the hardware register - - [..] - Implemented Workaround: - (+) For AHB & APB peripherals, a dummy read to the peripheral register has been - inserted in each __HAL_RCC_PPP_CLK_ENABLE() macro. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup RCC RCC - * @brief RCC HAL module driver - * @{ - */ - -#ifdef HAL_RCC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup RCC_Private_Constants - * @{ - */ - -/* Private macro -------------------------------------------------------------*/ -#define __MCO1_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() -#define MCO1_GPIO_PORT GPIOA -#define MCO1_PIN GPIO_PIN_8 - -#define __MCO2_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE() -#define MCO2_GPIO_PORT GPIOC -#define MCO2_PIN GPIO_PIN_9 -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup RCC_Private_Variables RCC Private Variables - * @{ - */ -/** - * @} - */ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup RCC_Exported_Functions RCC Exported Functions - * @{ - */ - -/** @defgroup RCC_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] - This section provides functions allowing to configure the internal/external oscillators - (HSE, HSI, LSE, LSI, PLL, CSS and MCO) and the System busses clocks (SYSCLK, AHB, APB1 - and APB2). - - [..] Internal/external clock and PLL configuration - (#) HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through - the PLL as System clock source. - - (#) LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC - clock source. - - (#) HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or - through the PLL as System clock source. Can be used also as RTC clock source. - - (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source. - - (#) PLL (clocked by HSI or HSE), featuring two different output clocks: - (++) The first output is used to generate the high speed system clock (up to 168 MHz) - (++) The second output is used to generate the clock for the USB OTG FS (48 MHz), - the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz). - - (#) CSS (Clock security system), once enable using the macro __HAL_RCC_CSS_ENABLE() - and if a HSE clock failure occurs(HSE used directly or through PLL as System - clock source), the System clocks automatically switched to HSI and an interrupt - is generated if enabled. The interrupt is linked to the Cortex-M4 NMI - (Non-Maskable Interrupt) exception vector. - - (#) MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL - clock (through a configurable prescaler) on PA8 pin. - - (#) MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S - clock (through a configurable prescaler) on PC9 pin. - - [..] System, AHB and APB busses clocks configuration - (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI, - HSE and PLL. - The AHB clock (HCLK) is derived from System clock through configurable - prescaler and used to clock the CPU, memory and peripherals mapped - on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived - from AHB clock through configurable prescalers and used to clock - the peripherals mapped on these busses. You can use - "HAL_RCC_GetSysClockFreq()" function to retrieve the frequencies of these clocks. - - (#) For the STM32F405xx/07xx and STM32F415xx/17xx devices, the maximum - frequency of the SYSCLK and HCLK is 168 MHz, PCLK2 84 MHz and PCLK1 42 MHz. - Depending on the device voltage range, the maximum frequency should - be adapted accordingly (refer to the product datasheets for more details). - - (#) For the STM32F42xxx, STM32F43xxx, STM32F446xx, STM32F469xx and STM32F479xx devices, - the maximum frequency of the SYSCLK and HCLK is 180 MHz, PCLK2 90 MHz and PCLK1 45 MHz. - Depending on the device voltage range, the maximum frequency should - be adapted accordingly (refer to the product datasheets for more details). - - (#) For the STM32F401xx, the maximum frequency of the SYSCLK and HCLK is 84 MHz, - PCLK2 84 MHz and PCLK1 42 MHz. - Depending on the device voltage range, the maximum frequency should - be adapted accordingly (refer to the product datasheets for more details). - - (#) For the STM32F41xxx, the maximum frequency of the SYSCLK and HCLK is 100 MHz, - PCLK2 100 MHz and PCLK1 50 MHz. - Depending on the device voltage range, the maximum frequency should - be adapted accordingly (refer to the product datasheets for more details). - -@endverbatim - * @{ - */ - -/** - * @brief Resets the RCC clock configuration to the default reset state. - * @note The default reset state of the clock configuration is given below: - * - HSI ON and used as system clock source - * - HSE and PLL OFF - * - AHB, APB1 and APB2 prescaler set to 1. - * - CSS, MCO1 and MCO2 OFF - * - All interrupts disabled - * @note This function doesn't modify the configuration of the - * - Peripheral clocks - * - LSI, LSE and RTC clocks - * @retval HAL status - */ -__weak HAL_StatusTypeDef HAL_RCC_DeInit(void) -{ - return HAL_OK; -} - -/** - * @brief Initializes the RCC Oscillators according to the specified parameters in the - * RCC_OscInitTypeDef. - * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that - * contains the configuration information for the RCC Oscillators. - * @note The PLL is not disabled when used as system clock. - * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not - * supported by this API. User should request a transition to LSE Off - * first and then LSE On or LSE Bypass. - * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not - * supported by this API. User should request a transition to HSE Off - * first and then HSE On or HSE Bypass. - * @retval HAL status - */ -__weak HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) -{ - uint32_t tickstart, pll_config; - - /* Check Null pointer */ - if(RCC_OscInitStruct == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); - /*------------------------------- HSE Configuration ------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) - { - /* Check the parameters */ - assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); - /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */ - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) - { - if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) - { - return HAL_ERROR; - } - } - else - { - /* Set the new HSE configuration ---------------------------------------*/ - __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); - - /* Check the HSE State */ - if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF) - { - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till HSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till HSE is bypassed or disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - } - /*----------------------------- HSI Configuration --------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) - { - /* Check the parameters */ - assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); - assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); - - /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) - { - /* When HSI is used as system clock it will not disabled */ - if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) - { - return HAL_ERROR; - } - /* Otherwise, just the calibration is allowed */ - else - { - /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ - __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - } - } - else - { - /* Check the HSI State */ - if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) - { - /* Enable the Internal High Speed oscillator (HSI). */ - __HAL_RCC_HSI_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Adjusts the Internal High Speed oscillator (HSI) calibration value. */ - __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - } - else - { - /* Disable the Internal High Speed oscillator (HSI). */ - __HAL_RCC_HSI_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - } - /*------------------------------ LSI Configuration -------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) - { - /* Check the parameters */ - assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); - - /* Check the LSI State */ - if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) - { - /* Enable the Internal Low Speed oscillator (LSI). */ - __HAL_RCC_LSI_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Disable the Internal Low Speed oscillator (LSI). */ - __HAL_RCC_LSI_DISABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - /*------------------------------ LSE Configuration -------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) - { - FlagStatus pwrclkchanged = RESET; - - /* Check the parameters */ - assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); - - /* Update LSE configuration in Backup Domain control register */ - /* Requires to enable write access to Backup Domain of necessary */ - if(__HAL_RCC_PWR_IS_CLK_DISABLED()) - { - __HAL_RCC_PWR_CLK_ENABLE(); - pwrclkchanged = SET; - } - - if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) - { - /* Enable write access to Backup domain */ - SET_BIT(PWR->CR, PWR_CR_DBP); - - /* Wait for Backup domain Write protection disable */ - tickstart = HAL_GetTick(); - - while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) - { - if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Set the new LSE configuration -----------------------------------------*/ - __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); - /* Check the LSE State */ - if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Restore clock configuration if changed */ - if(pwrclkchanged == SET) - { - __HAL_RCC_PWR_CLK_DISABLE(); - } - } - /*-------------------------------- PLL Configuration -----------------------*/ - /* Check the parameters */ - assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); - if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) - { - /* Check if the PLL is used as system clock or not */ - if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) - { - if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) - { - /* Check the parameters */ - assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource)); - assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM)); - assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN)); - assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP)); - assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ)); - - /* Disable the main PLL. */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Configure the main PLL clock source, multiplication and division factors. */ - WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \ - RCC_OscInitStruct->PLL.PLLM | \ - (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \ - (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \ - (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))); - /* Enable the main PLL. */ - __HAL_RCC_PLL_ENABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Disable the main PLL. */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - else - { - /* Check if there is a request to disable the PLL used as System clock source */ - if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) - { - return HAL_ERROR; - } - else - { - /* Do not return HAL_ERROR if request repeats the current configuration */ - pll_config = RCC->PLLCFGR; -#if defined (RCC_PLLCFGR_PLLR) - if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLR) != (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))) -#else - if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))) -#endif - { - return HAL_ERROR; - } - } - } - } - return HAL_OK; -} - -/** - * @brief Initializes the CPU, AHB and APB busses clocks according to the specified - * parameters in the RCC_ClkInitStruct. - * @param RCC_ClkInitStruct pointer to an RCC_OscInitTypeDef structure that - * contains the configuration information for the RCC peripheral. - * @param FLatency FLASH Latency, this parameter depend on device selected - * - * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency - * and updated by HAL_RCC_GetHCLKFreq() function called within this function - * - * @note The HSI is used (enabled by hardware) as system clock source after - * startup from Reset, wake-up from STOP and STANDBY mode, or in case - * of failure of the HSE used directly or indirectly as system clock - * (if the Clock Security System CSS is enabled). - * - * @note A switch from one clock source to another occurs only if the target - * clock source is ready (clock stable after startup delay or PLL locked). - * If a clock source which is not yet ready is selected, the switch will - * occur when the clock source will be ready. - * - * @note Depending on the device voltage range, the software has to set correctly - * HPRE[3:0] bits to ensure that HCLK not exceed the maximum allowed frequency - * (for more details refer to section above "Initialization/de-initialization functions") - * @retval None - */ -HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency) -{ - uint32_t tickstart; - - /* Check Null pointer */ - if(RCC_ClkInitStruct == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_RCC_CLOCKTYPE(RCC_ClkInitStruct->ClockType)); - assert_param(IS_FLASH_LATENCY(FLatency)); - - /* To correctly read data from FLASH memory, the number of wait states (LATENCY) - must be correctly programmed according to the frequency of the CPU clock - (HCLK) and the supply voltage of the device. */ - - /* Increasing the number of wait states because of higher CPU frequency */ - if(FLatency > __HAL_FLASH_GET_LATENCY()) - { - /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ - __HAL_FLASH_SET_LATENCY(FLatency); - - /* Check that the new number of wait states is taken into account to access the Flash - memory by reading the FLASH_ACR register */ - if(__HAL_FLASH_GET_LATENCY() != FLatency) - { - return HAL_ERROR; - } - } - - /*-------------------------- HCLK Configuration --------------------------*/ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_HCLK) == RCC_CLOCKTYPE_HCLK) - { - /* Set the highest APBx dividers in order to ensure that we do not go through - a non-spec phase whatever we decrease or increase HCLK. */ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) - { - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_HCLK_DIV16); - } - - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) - { - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, (RCC_HCLK_DIV16 << 3)); - } - - assert_param(IS_RCC_HCLK(RCC_ClkInitStruct->AHBCLKDivider)); - MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, RCC_ClkInitStruct->AHBCLKDivider); - } - - /*------------------------- SYSCLK Configuration ---------------------------*/ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_SYSCLK) == RCC_CLOCKTYPE_SYSCLK) - { - assert_param(IS_RCC_SYSCLKSOURCE(RCC_ClkInitStruct->SYSCLKSource)); - - /* HSE is selected as System Clock Source */ - if(RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_HSE) - { - /* Check the HSE ready flag */ - if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - { - return HAL_ERROR; - } - } - /* PLL is selected as System Clock Source */ - else if((RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLCLK) || - (RCC_ClkInitStruct->SYSCLKSource == RCC_SYSCLKSOURCE_PLLRCLK)) - { - /* Check the PLL ready flag */ - if(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - { - return HAL_ERROR; - } - } - /* HSI is selected as System Clock Source */ - else - { - /* Check the HSI ready flag */ - if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - { - return HAL_ERROR; - } - } - - __HAL_RCC_SYSCLK_CONFIG(RCC_ClkInitStruct->SYSCLKSource); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - while (__HAL_RCC_GET_SYSCLK_SOURCE() != (RCC_ClkInitStruct->SYSCLKSource << RCC_CFGR_SWS_Pos)) - { - if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Decreasing the number of wait states because of lower CPU frequency */ - if(FLatency < __HAL_FLASH_GET_LATENCY()) - { - /* Program the new number of wait states to the LATENCY bits in the FLASH_ACR register */ - __HAL_FLASH_SET_LATENCY(FLatency); - - /* Check that the new number of wait states is taken into account to access the Flash - memory by reading the FLASH_ACR register */ - if(__HAL_FLASH_GET_LATENCY() != FLatency) - { - return HAL_ERROR; - } - } - - /*-------------------------- PCLK1 Configuration ---------------------------*/ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK1) == RCC_CLOCKTYPE_PCLK1) - { - assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB1CLKDivider)); - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, RCC_ClkInitStruct->APB1CLKDivider); - } - - /*-------------------------- PCLK2 Configuration ---------------------------*/ - if(((RCC_ClkInitStruct->ClockType) & RCC_CLOCKTYPE_PCLK2) == RCC_CLOCKTYPE_PCLK2) - { - assert_param(IS_RCC_PCLK(RCC_ClkInitStruct->APB2CLKDivider)); - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, ((RCC_ClkInitStruct->APB2CLKDivider) << 3U)); - } - - /* Update the SystemCoreClock global variable */ - SystemCoreClock = HAL_RCC_GetSysClockFreq() >> AHBPrescTable[(RCC->CFGR & RCC_CFGR_HPRE)>> RCC_CFGR_HPRE_Pos]; - - /* Configure the source of time base considering new system clocks settings */ - HAL_InitTick (uwTickPrio); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup RCC_Exported_Functions_Group2 Peripheral Control functions - * @brief RCC clocks control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the RCC Clocks - frequencies. - -@endverbatim - * @{ - */ - -/** - * @brief Selects the clock source to output on MCO1 pin(PA8) or on MCO2 pin(PC9). - * @note PA8/PC9 should be configured in alternate function mode. - * @param RCC_MCOx specifies the output direction for the clock source. - * This parameter can be one of the following values: - * @arg RCC_MCO1: Clock source to output on MCO1 pin(PA8). - * @arg RCC_MCO2: Clock source to output on MCO2 pin(PC9). - * @param RCC_MCOSource specifies the clock source to output. - * This parameter can be one of the following values: - * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source - * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx - * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410Rx devices - * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source - * @param RCC_MCODiv specifies the MCOx prescaler. - * This parameter can be one of the following values: - * @arg RCC_MCODIV_1: no division applied to MCOx clock - * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock - * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock - * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock - * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock - * @note For STM32F410Rx devices to output I2SCLK clock on MCO2 you should have - * at last one of the SPI clocks enabled (SPI1, SPI2 or SPI5). - * @retval None - */ -void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv) -{ - GPIO_InitTypeDef GPIO_InitStruct; - /* Check the parameters */ - assert_param(IS_RCC_MCO(RCC_MCOx)); - assert_param(IS_RCC_MCODIV(RCC_MCODiv)); - /* RCC_MCO1 */ - if(RCC_MCOx == RCC_MCO1) - { - assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource)); - - /* MCO1 Clock Enable */ - __MCO1_CLK_ENABLE(); - - /* Configure the MCO1 pin in alternate function mode */ - GPIO_InitStruct.Pin = MCO1_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF0_MCO; - HAL_GPIO_Init(MCO1_GPIO_PORT, &GPIO_InitStruct); - - /* Mask MCO1 and MCO1PRE[2:0] bits then Select MCO1 clock source and prescaler */ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), (RCC_MCOSource | RCC_MCODiv)); - - /* This RCC MCO1 enable feature is available only on STM32F410xx devices */ -#if defined(RCC_CFGR_MCO1EN) - __HAL_RCC_MCO1_ENABLE(); -#endif /* RCC_CFGR_MCO1EN */ - } -#if defined(RCC_CFGR_MCO2) - else - { - assert_param(IS_RCC_MCO2SOURCE(RCC_MCOSource)); - - /* MCO2 Clock Enable */ - __MCO2_CLK_ENABLE(); - - /* Configure the MCO2 pin in alternate function mode */ - GPIO_InitStruct.Pin = MCO2_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Alternate = GPIO_AF0_MCO; - HAL_GPIO_Init(MCO2_GPIO_PORT, &GPIO_InitStruct); - - /* Mask MCO2 and MCO2PRE[2:0] bits then Select MCO2 clock source and prescaler */ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), (RCC_MCOSource | (RCC_MCODiv << 3U))); - - /* This RCC MCO2 enable feature is available only on STM32F410Rx devices */ -#if defined(RCC_CFGR_MCO2EN) - __HAL_RCC_MCO2_ENABLE(); -#endif /* RCC_CFGR_MCO2EN */ - } -#endif /* RCC_CFGR_MCO2 */ -} - -/** - * @brief Enables the Clock Security System. - * @note If a failure is detected on the HSE oscillator clock, this oscillator - * is automatically disabled and an interrupt is generated to inform the - * software about the failure (Clock Security System Interrupt, CSSI), - * allowing the MCU to perform rescue operations. The CSSI is linked to - * the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector. - * @retval None - */ -void HAL_RCC_EnableCSS(void) -{ - *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)ENABLE; -} - -/** - * @brief Disables the Clock Security System. - * @retval None - */ -void HAL_RCC_DisableCSS(void) -{ - *(__IO uint32_t *) RCC_CR_CSSON_BB = (uint32_t)DISABLE; -} - -/** - * @brief Returns the SYSCLK frequency - * - * @note The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) - * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) - * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * @note (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * @note (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 25 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * @note The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @note This function can be used by the user application to compute the - * baudrate for the communication peripherals or configure other parameters. - * - * @note Each time SYSCLK changes, this function must be called to update the - * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect. - * - * - * @retval SYSCLK frequency - */ -__weak uint32_t HAL_RCC_GetSysClockFreq(void) -{ - uint32_t pllm = 0U, pllvco = 0U, pllp = 0U; - uint32_t sysclockfreq = 0U; - - /* Get SYSCLK source -------------------------------------------------------*/ - switch (RCC->CFGR & RCC_CFGR_SWS) - { - case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ - { - sysclockfreq = HSI_VALUE; - break; - } - case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ - { - sysclockfreq = HSE_VALUE; - break; - } - case RCC_CFGR_SWS_PLL: /* PLL used as system clock source */ - { - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SYSCLK = PLL_VCO / PLLP */ - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) - { - /* HSE used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U); - - sysclockfreq = pllvco/pllp; - break; - } - default: - { - sysclockfreq = HSI_VALUE; - break; - } - } - return sysclockfreq; -} - -/** - * @brief Returns the HCLK frequency - * @note Each time HCLK changes, this function must be called to update the - * right HCLK value. Otherwise, any configuration based on this function will be incorrect. - * - * @note The SystemCoreClock CMSIS variable is used to store System Clock Frequency - * and updated within this function - * @retval HCLK frequency - */ -uint32_t HAL_RCC_GetHCLKFreq(void) -{ - return SystemCoreClock; -} - -/** - * @brief Returns the PCLK1 frequency - * @note Each time PCLK1 changes, this function must be called to update the - * right PCLK1 value. Otherwise, any configuration based on this function will be incorrect. - * @retval PCLK1 frequency - */ -uint32_t HAL_RCC_GetPCLK1Freq(void) -{ - /* Get HCLK source and Compute PCLK1 frequency ---------------------------*/ - return (HAL_RCC_GetHCLKFreq() >> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE1)>> RCC_CFGR_PPRE1_Pos]); -} - -/** - * @brief Returns the PCLK2 frequency - * @note Each time PCLK2 changes, this function must be called to update the - * right PCLK2 value. Otherwise, any configuration based on this function will be incorrect. - * @retval PCLK2 frequency - */ -uint32_t HAL_RCC_GetPCLK2Freq(void) -{ - /* Get HCLK source and Compute PCLK2 frequency ---------------------------*/ - return (HAL_RCC_GetHCLKFreq()>> APBPrescTable[(RCC->CFGR & RCC_CFGR_PPRE2)>> RCC_CFGR_PPRE2_Pos]); -} - -/** - * @brief Configures the RCC_OscInitStruct according to the internal - * RCC configuration registers. - * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that - * will be configured. - * @retval None - */ -__weak void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) -{ - /* Set all possible values for the Oscillator type parameter ---------------*/ - RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI; - - /* Get the HSE configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP) - { - RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS; - } - else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON) - { - RCC_OscInitStruct->HSEState = RCC_HSE_ON; - } - else - { - RCC_OscInitStruct->HSEState = RCC_HSE_OFF; - } - - /* Get the HSI configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION) - { - RCC_OscInitStruct->HSIState = RCC_HSI_ON; - } - else - { - RCC_OscInitStruct->HSIState = RCC_HSI_OFF; - } - - RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); - - /* Get the LSE configuration -----------------------------------------------*/ - if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP) - { - RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS; - } - else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON) - { - RCC_OscInitStruct->LSEState = RCC_LSE_ON; - } - else - { - RCC_OscInitStruct->LSEState = RCC_LSE_OFF; - } - - /* Get the LSI configuration -----------------------------------------------*/ - if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION) - { - RCC_OscInitStruct->LSIState = RCC_LSI_ON; - } - else - { - RCC_OscInitStruct->LSIState = RCC_LSI_OFF; - } - - /* Get the PLL configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON) - { - RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON; - } - else - { - RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF; - } - RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); - RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); - RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); - RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos); - RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos); -} - -/** - * @brief Configures the RCC_ClkInitStruct according to the internal - * RCC configuration registers. - * @param RCC_ClkInitStruct pointer to an RCC_ClkInitTypeDef structure that - * will be configured. - * @param pFLatency Pointer on the Flash Latency. - * @retval None - */ -void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency) -{ - /* Set all possible values for the Clock type parameter --------------------*/ - RCC_ClkInitStruct->ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2; - - /* Get the SYSCLK configuration --------------------------------------------*/ - RCC_ClkInitStruct->SYSCLKSource = (uint32_t)(RCC->CFGR & RCC_CFGR_SW); - - /* Get the HCLK configuration ----------------------------------------------*/ - RCC_ClkInitStruct->AHBCLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_HPRE); - - /* Get the APB1 configuration ----------------------------------------------*/ - RCC_ClkInitStruct->APB1CLKDivider = (uint32_t)(RCC->CFGR & RCC_CFGR_PPRE1); - - /* Get the APB2 configuration ----------------------------------------------*/ - RCC_ClkInitStruct->APB2CLKDivider = (uint32_t)((RCC->CFGR & RCC_CFGR_PPRE2) >> 3U); - - /* Get the Flash Wait State (Latency) configuration ------------------------*/ - *pFLatency = (uint32_t)(FLASH->ACR & FLASH_ACR_LATENCY); -} - -/** - * @brief This function handles the RCC CSS interrupt request. - * @note This API should be called under the NMI_Handler(). - * @retval None - */ -void HAL_RCC_NMI_IRQHandler(void) -{ - /* Check RCC CSSF flag */ - if(__HAL_RCC_GET_IT(RCC_IT_CSS)) - { - /* RCC Clock Security System interrupt user callback */ - HAL_RCC_CSSCallback(); - - /* Clear RCC CSS pending bit */ - __HAL_RCC_CLEAR_IT(RCC_IT_CSS); - } -} - -/** - * @brief RCC Clock Security System interrupt callback - * @retval None - */ -__weak void HAL_RCC_CSSCallback(void) -{ - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RCC_CSSCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_RCC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c deleted file mode 100644 index e42b850a62e1962..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c +++ /dev/null @@ -1,3787 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc_ex.c - * @author MCD Application Team - * @brief Extension RCC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities RCC extension peripheral: - * + Extended Peripheral Control functions - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup RCCEx RCCEx - * @brief RCCEx HAL module driver - * @{ - */ - -#ifdef HAL_RCC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup RCCEx_Private_Constants - * @{ - */ -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Functions RCCEx Exported Functions - * @{ - */ - -/** @defgroup RCCEx_Exported_Functions_Group1 Extended Peripheral Control functions - * @brief Extended Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Extended Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the RCC Clocks - frequencies. - [..] - (@) Important note: Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to - select the RTC clock source; in this case the Backup domain will be reset in - order to modify the RTC Clock source, as consequence RTC registers (including - the backup registers) and RCC_BDCR register are set to their reset values. - -@endverbatim - * @{ - */ - -#if defined(STM32F446xx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified - * parameters in the RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals - * clocks(I2S, SAI, LTDC RTC and TIM). - * - * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select - * the RTC clock source; in this case the Backup domain will be reset in - * order to modify the RTC Clock source, as consequence RTC registers (including - * the backup registers) and RCC_BDCR register are set to their reset values. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - uint32_t plli2sp = 0U; - uint32_t plli2sq = 0U; - uint32_t plli2sr = 0U; - uint32_t pllsaip = 0U; - uint32_t pllsaiq = 0U; - uint32_t plli2sused = 0U; - uint32_t pllsaiused = 0U; - - /* Check the peripheral clock selection parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*------------------------ I2S APB1 configuration --------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == (RCC_PERIPHCLK_I2S_APB1)) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPB1CLKSOURCE(PeriphClkInit->I2sApb1ClockSelection)); - - /* Configure I2S Clock source */ - __HAL_RCC_I2S_APB1_CONFIG(PeriphClkInit->I2sApb1ClockSelection); - /* Enable the PLLI2S when it's used as clock source for I2S */ - if(PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- I2S APB2 configuration ----------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == (RCC_PERIPHCLK_I2S_APB2)) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPB2CLKSOURCE(PeriphClkInit->I2sApb2ClockSelection)); - - /* Configure I2S Clock source */ - __HAL_RCC_I2S_APB2_CONFIG(PeriphClkInit->I2sApb2ClockSelection); - /* Enable the PLLI2S when it's used as clock source for I2S */ - if(PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*--------------------------- SAI1 configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == (RCC_PERIPHCLK_SAI1)) - { - /* Check the parameters */ - assert_param(IS_RCC_SAI1CLKSOURCE(PeriphClkInit->Sai1ClockSelection)); - - /* Configure SAI1 Clock source */ - __HAL_RCC_SAI1_CONFIG(PeriphClkInit->Sai1ClockSelection); - /* Enable the PLLI2S when it's used as clock source for SAI */ - if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - /* Enable the PLLSAI when it's used as clock source for SAI */ - if(PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI) - { - pllsaiused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*-------------------------- SAI2 configuration ----------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == (RCC_PERIPHCLK_SAI2)) - { - /* Check the parameters */ - assert_param(IS_RCC_SAI2CLKSOURCE(PeriphClkInit->Sai2ClockSelection)); - - /* Configure SAI2 Clock source */ - __HAL_RCC_SAI2_CONFIG(PeriphClkInit->Sai2ClockSelection); - - /* Enable the PLLI2S when it's used as clock source for SAI */ - if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - /* Enable the PLLSAI when it's used as clock source for SAI */ - if(PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI) - { - pllsaiused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------- RTC configuration --------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - /* Configure Timer Prescaler */ - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- FMPI2C1 Configuration -----------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) - { - /* Check the parameters */ - assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); - - /* Configure the FMPI2C1 clock source */ - __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------ CEC Configuration -------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CEC) == RCC_PERIPHCLK_CEC) - { - /* Check the parameters */ - assert_param(IS_RCC_CECCLKSOURCE(PeriphClkInit->CecClockSelection)); - - /* Configure the CEC clock source */ - __HAL_RCC_CEC_CONFIG(PeriphClkInit->CecClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------- CLK48 Configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) - { - /* Check the parameters */ - assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); - - /* Configure the CLK48 clock source */ - __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); - - /* Enable the PLLSAI when it's used as clock source for CLK48 */ - if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP) - { - pllsaiused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------- SDIO Configuration -------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); - - /* Configure the SDIO clock source */ - __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------ SPDIFRX Configuration ---------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) - { - /* Check the parameters */ - assert_param(IS_RCC_SPDIFRXCLKSOURCE(PeriphClkInit->SpdifClockSelection)); - - /* Configure the SPDIFRX clock source */ - __HAL_RCC_SPDIFRX_CONFIG(PeriphClkInit->SpdifClockSelection); - /* Enable the PLLI2S when it's used as clock source for SPDIFRX */ - if(PeriphClkInit->SpdifClockSelection == RCC_SPDIFRXCLKSOURCE_PLLI2SP) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- PLLI2S Configuration ------------------------*/ - /* PLLI2S is configured when a peripheral will use it as source clock : SAI1, SAI2, I2S on APB1, - I2S on APB2 or SPDIFRX */ - if((plli2sused == 1U) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) - { - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* check for common PLLI2S Parameters */ - assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); - - /*------ In Case of PLLI2S is selected as source clock for I2S -----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == RCC_PERIPHCLK_I2S_APB1) && (PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == RCC_PERIPHCLK_I2S_APB2) && (PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S))) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - - /* Read PLLI2SP/PLLI2SQ value from PLLI2SCFGR register (this value is not needed for I2S configuration) */ - plli2sp = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); - plli2sq = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , plli2sp, plli2sq, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /*------- In Case of PLLI2S is selected as source clock for SAI ----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLI2S)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLI2S))) - { - /* Check for PLLI2S Parameters */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - /* Check for PLLI2S/DIVQ parameters */ - assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); - - /* Read PLLI2SP/PLLI2SR value from PLLI2SCFGR register (this value is not needed for SAI configuration) */ - plli2sp = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); - plli2sr = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , plli2sp, PeriphClkInit->PLLI2S.PLLI2SQ, plli2sr); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); - } - - /*------ In Case of PLLI2S is selected as source clock for SPDIFRX -------*/ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SPDIFRX) == RCC_PERIPHCLK_SPDIFRX) && (PeriphClkInit->SpdifClockSelection == RCC_SPDIFRXCLKSOURCE_PLLI2SP)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); - /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ - plli2sq = ((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); - plli2sr = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, plli2sq, plli2sr); - } - - /*----------------- In Case of PLLI2S is just selected -----------------*/ - if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - { - /* Check for Parameters */ - assert_param(IS_RCC_PLLI2SP_VALUE(PeriphClkInit->PLLI2S.PLLI2SP)); - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SP, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------- PLLSAI Configuration -----------------------*/ - /* PLLSAI is configured when a peripheral will use it as source clock : SAI1, SAI2, CLK48 or SDIO */ - if(pllsaiused == 1U) - { - /* Disable PLLSAI Clock */ - __HAL_RCC_PLLSAI_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is disabled */ - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* Check the PLLSAI division factors */ - assert_param(IS_RCC_PLLSAIM_VALUE(PeriphClkInit->PLLSAI.PLLSAIM)); - assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); - - /*------ In Case of PLLSAI is selected as source clock for SAI -----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI1) == RCC_PERIPHCLK_SAI1) && (PeriphClkInit->Sai1ClockSelection == RCC_SAI1CLKSOURCE_PLLSAI)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI2) == RCC_PERIPHCLK_SAI2) && (PeriphClkInit->Sai2ClockSelection == RCC_SAI2CLKSOURCE_PLLSAI))) - { - /* check for PLLSAIQ Parameter */ - assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); - /* check for PLLSAI/DIVQ Parameter */ - assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); - - /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ - pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIM, PeriphClkInit->PLLSAI.PLLSAIN , pllsaip, PeriphClkInit->PLLSAI.PLLSAIQ, 0U); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); - } - - /*------ In Case of PLLSAI is selected as source clock for CLK48 ---------*/ - /* In Case of PLLI2S is selected as source clock for CLK48 */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); - /* Read PLLSAIQ value from PLLI2SCFGR register (this value is not need for SAI configuration) */ - pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Configure the PLLSAI division factors */ - /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * (PLLI2SN/PLLSAIM) */ - /* 48CLK = f(PLLSAI clock output) = f(VCO clock) / PLLSAIP */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIM, PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIP, pllsaiq, 0U); - } - - /* Enable PLLSAI Clock */ - __HAL_RCC_PLLSAI_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is ready */ - while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - return HAL_OK; -} - -/** - * @brief Get the RCC_PeriphCLKInitTypeDef according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ - RCC_PERIPHCLK_SAI1 | RCC_PERIPHCLK_SAI2 |\ - RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ - RCC_PERIPHCLK_CEC | RCC_PERIPHCLK_FMPI2C1 |\ - RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO |\ - RCC_PERIPHCLK_SPDIFRX; - - /* Get the PLLI2S Clock configuration --------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM) >> RCC_PLLI2SCFGR_PLLI2SM_Pos); - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SP = (uint32_t)((((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SP) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) << 1U); - PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Get the PLLSAI Clock configuration --------------------------------------*/ - PeriphClkInit->PLLSAI.PLLSAIM = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM) >> RCC_PLLSAICFGR_PLLSAIM_Pos); - PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); - PeriphClkInit->PLLSAI.PLLSAIP = (uint32_t)((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); - PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Get the PLLSAI/PLLI2S division factors ----------------------------------*/ - PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); - PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); - - /* Get the SAI1 clock configuration ----------------------------------------*/ - PeriphClkInit->Sai1ClockSelection = __HAL_RCC_GET_SAI1_SOURCE(); - - /* Get the SAI2 clock configuration ----------------------------------------*/ - PeriphClkInit->Sai2ClockSelection = __HAL_RCC_GET_SAI2_SOURCE(); - - /* Get the I2S APB1 clock configuration ------------------------------------*/ - PeriphClkInit->I2sApb1ClockSelection = __HAL_RCC_GET_I2S_APB1_SOURCE(); - - /* Get the I2S APB2 clock configuration ------------------------------------*/ - PeriphClkInit->I2sApb2ClockSelection = __HAL_RCC_GET_I2S_APB2_SOURCE(); - - /* Get the RTC Clock configuration -----------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - /* Get the CEC clock configuration -----------------------------------------*/ - PeriphClkInit->CecClockSelection = __HAL_RCC_GET_CEC_SOURCE(); - - /* Get the FMPI2C1 clock configuration -------------------------------------*/ - PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); - - /* Get the CLK48 clock configuration ----------------------------------------*/ - PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); - - /* Get the SDIO clock configuration ----------------------------------------*/ - PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); - - /* Get the SPDIFRX clock configuration -------------------------------------*/ - PeriphClkInit->SpdifClockSelection = __HAL_RCC_GET_SPDIFRX_SOURCE(); - - /* Get the TIM Prescaler configuration -------------------------------------*/ - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_SAI1: SAI1 peripheral clock - * @arg RCC_PERIPHCLK_SAI2: SAI2 peripheral clock - * @arg RCC_PERIPHCLK_I2S_APB1: I2S APB1 peripheral clock - * @arg RCC_PERIPHCLK_I2S_APB2: I2S APB2 peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - uint32_t tmpreg1 = 0U; - /* This variable used to store the SAI clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - /* This variable used to store the SAI clock source */ - uint32_t saiclocksource = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_SAI1: - case RCC_PERIPHCLK_SAI2: - { - saiclocksource = RCC->DCKCFGR; - saiclocksource &= (RCC_DCKCFGR_SAI1SRC | RCC_DCKCFGR_SAI2SRC); - switch (saiclocksource) - { - case 0U: /* PLLSAI is the clock source for SAI*/ - { - /* Configure the PLLSAI division factor */ - /* PLLSAI_VCO Input = PLL_SOURCE/PLLSAIM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM)); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIM))); - } - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - tmpreg1 = (RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> 24U; - frequency = (vcoinput * ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> 6U))/(tmpreg1); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - tmpreg1 = (((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> 8U) + 1U); - frequency = frequency/(tmpreg1); - break; - } - case RCC_DCKCFGR_SAI1SRC_0: /* PLLI2S is the clock source for SAI*/ - case RCC_DCKCFGR_SAI2SRC_0: /* PLLI2S is the clock source for SAI*/ - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM))); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - tmpreg1 = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> 24U; - frequency = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U))/(tmpreg1); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - tmpreg1 = ((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) + 1U); - frequency = frequency/(tmpreg1); - break; - } - case RCC_DCKCFGR_SAI1SRC_1: /* PLLR is the clock source for SAI*/ - case RCC_DCKCFGR_SAI2SRC_1: /* PLLR is the clock source for SAI*/ - { - /* Configure the PLLI2S division factor */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM))); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - /* SAI_CLK_x = PLL_VCO Output/PLLR */ - tmpreg1 = (RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U; - frequency = (vcoinput * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U))/(tmpreg1); - break; - } - case RCC_DCKCFGR_SAI1SRC: /* External clock is the clock source for SAI*/ - { - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - case RCC_DCKCFGR_SAI2SRC: /* PLLSRC(HSE or HSI) is the clock source for SAI*/ - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - frequency = (uint32_t)(HSI_VALUE); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - frequency = (uint32_t)(HSE_VALUE); - } - break; - } - default : - { - break; - } - } - break; - } - case RCC_PERIPHCLK_I2S_APB1: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_APB1_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_PLLI2S: - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPB1CLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - case RCC_PERIPHCLK_I2S_APB2: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_APB2_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_PLLI2S: - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPB2CLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified - * parameters in the RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals - * clocks(I2S, SAI, LTDC, RTC and TIM). - * - * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select - * the RTC clock source; in this case the Backup domain will be reset in - * order to modify the RTC Clock source, as consequence RTC registers (including - * the backup registers) and RCC_BDCR register are set to their reset values. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - uint32_t pllsaip = 0U; - uint32_t pllsaiq = 0U; - uint32_t pllsair = 0U; - - /* Check the parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*--------------------------- CLK48 Configuration --------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) - { - /* Check the parameters */ - assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); - - /* Configure the CLK48 clock source */ - __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------ SDIO Configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); - - /* Configure the SDIO clock source */ - __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*----------------------- SAI/I2S Configuration (PLLI2S) -------------------*/ - /*------------------- Common configuration SAI/I2S -------------------------*/ - /* In Case of SAI or I2S Clock Configuration through PLLI2S, PLLI2SN division - factor is common parameters for both peripherals */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == RCC_PERIPHCLK_SAI_PLLI2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); - - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /*---------------------- I2S configuration -------------------------------*/ - /* In Case of I2S Clock Configuration through PLLI2S, PLLI2SR must be added - only for I2S configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x (PLLI2SN/PLLM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); - } - - /*---------------------------- SAI configuration -------------------------*/ - /* In Case of SAI Clock Configuration through PLLI2S, PLLI2SQ and PLLI2S_DIVQ must - be added only for SAI configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == (RCC_PERIPHCLK_SAI_PLLI2S)) - { - /* Check the PLLI2S division factors */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); - - /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ - tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ , tmpreg1); - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); - } - - /*----------------- In Case of PLLI2S is just selected -----------------*/ - if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - { - /* Check for Parameters */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - - /* Configure the PLLI2S multiplication and division factors */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------- SAI/LTDC Configuration (PLLSAI) ------------------*/ - /*----------------------- Common configuration SAI/LTDC --------------------*/ - /* In Case of SAI, LTDC or CLK48 Clock Configuration through PLLSAI, PLLSAIN division - factor is common parameters for these peripherals */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == RCC_PERIPHCLK_SAI_PLLSAI) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && - (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP))) - { - /* Check the PLLSAI division factors */ - assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); - - /* Disable PLLSAI Clock */ - __HAL_RCC_PLLSAI_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is disabled */ - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /*---------------------------- SAI configuration -------------------------*/ - /* In Case of SAI Clock Configuration through PLLSAI, PLLSAIQ and PLLSAI_DIVQ must - be added only for SAI configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == (RCC_PERIPHCLK_SAI_PLLSAI)) - { - assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); - assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); - - /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ - pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); - /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ - pllsair = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, pllsaip, PeriphClkInit->PLLSAI.PLLSAIQ, pllsair); - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); - } - - /*---------------------------- LTDC configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) - { - assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); - assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); - - /* Read PLLSAIP value from PLLSAICFGR register (this value is not needed for SAI configuration) */ - pllsaip = ((((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIP) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) << 1U); - /* Read PLLSAIQ value from PLLSAICFGR register (this value is not need for SAI configuration) */ - pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, pllsaip, pllsaiq, PeriphClkInit->PLLSAI.PLLSAIR); - /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); - } - - /*---------------------------- CLK48 configuration ------------------------*/ - /* Configure the PLLSAI when it is used as clock source for CLK48 */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == (RCC_PERIPHCLK_CLK48)) && - (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLSAIP)) - { - assert_param(IS_RCC_PLLSAIP_VALUE(PeriphClkInit->PLLSAI.PLLSAIP)); - - /* Read PLLSAIQ value from PLLSAICFGR register (this value is not need for SAI configuration) */ - pllsaiq = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ - pllsair = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* CLK48_CLK(first level) = PLLSAI_VCO Output/PLLSAIP */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN, PeriphClkInit->PLLSAI.PLLSAIP, pllsaiq, pllsair); - } - - /* Enable PLLSAI Clock */ - __HAL_RCC_PLLSAI_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is ready */ - while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - - /*--------------------------------------------------------------------------*/ - - /*---------------------------- RTC configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - return HAL_OK; -} - -/** - * @brief Configures the RCC_PeriphCLKInitTypeDef according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_SAI_PLLSAI |\ - RCC_PERIPHCLK_SAI_PLLI2S | RCC_PERIPHCLK_LTDC |\ - RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ - RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO; - - /* Get the PLLI2S Clock configuration --------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - /* Get the PLLSAI Clock configuration --------------------------------------*/ - PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); - PeriphClkInit->PLLSAI.PLLSAIR = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Get the PLLSAI/PLLI2S division factors ----------------------------------*/ - PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); - PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); - PeriphClkInit->PLLSAIDivR = (uint32_t)(RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVR); - /* Get the RTC Clock configuration -----------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - /* Get the CLK48 clock configuration -------------------------------------*/ - PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); - - /* Get the SDIO clock configuration ----------------------------------------*/ - PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); - - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SCLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SCLKSOURCE_PLLI2S: - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified - * parameters in the RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals - * clocks(I2S, LTDC RTC and TIM). - * - * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select - * the RTC clock source; in this case the Backup domain will be reset in - * order to modify the RTC Clock source, as consequence RTC registers (including - * the backup registers) and RCC_BDCR register are set to their reset values. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; -#if defined(STM32F413xx) || defined(STM32F423xx) - uint32_t plli2sq = 0U; -#endif /* STM32F413xx || STM32F423xx */ - uint32_t plli2sused = 0U; - - /* Check the peripheral clock selection parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*----------------------------------- I2S APB1 configuration ---------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == (RCC_PERIPHCLK_I2S_APB1)) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPB1CLKSOURCE(PeriphClkInit->I2sApb1ClockSelection)); - - /* Configure I2S Clock source */ - __HAL_RCC_I2S_APB1_CONFIG(PeriphClkInit->I2sApb1ClockSelection); - /* Enable the PLLI2S when it's used as clock source for I2S */ - if(PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------------------- I2S APB2 configuration ---------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == (RCC_PERIPHCLK_I2S_APB2)) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPB2CLKSOURCE(PeriphClkInit->I2sApb2ClockSelection)); - - /* Configure I2S Clock source */ - __HAL_RCC_I2S_APB2_CONFIG(PeriphClkInit->I2sApb2ClockSelection); - /* Enable the PLLI2S when it's used as clock source for I2S */ - if(PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - -#if defined(STM32F413xx) || defined(STM32F423xx) - /*----------------------- SAI1 Block A configuration -----------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIA) == (RCC_PERIPHCLK_SAIA)) - { - /* Check the parameters */ - assert_param(IS_RCC_SAIACLKSOURCE(PeriphClkInit->SaiAClockSelection)); - - /* Configure SAI1 Clock source */ - __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(PeriphClkInit->SaiAClockSelection); - /* Enable the PLLI2S when it's used as clock source for SAI */ - if(PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLI2SR) - { - plli2sused = 1U; - } - /* Enable the PLLSAI when it's used as clock source for SAI */ - if(PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLR) - { - /* Check for PLL/DIVR parameters */ - assert_param(IS_RCC_PLL_DIVR_VALUE(PeriphClkInit->PLLDivR)); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ - __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLDivR); - } - } - /*--------------------------------------------------------------------------*/ - - /*---------------------- SAI1 Block B configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIB) == (RCC_PERIPHCLK_SAIB)) - { - /* Check the parameters */ - assert_param(IS_RCC_SAIBCLKSOURCE(PeriphClkInit->SaiBClockSelection)); - - /* Configure SAI1 Clock source */ - __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(PeriphClkInit->SaiBClockSelection); - /* Enable the PLLI2S when it's used as clock source for SAI */ - if(PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLI2SR) - { - plli2sused = 1U; - } - /* Enable the PLLSAI when it's used as clock source for SAI */ - if(PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLR) - { - /* Check for PLL/DIVR parameters */ - assert_param(IS_RCC_PLL_DIVR_VALUE(PeriphClkInit->PLLDivR)); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ - __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLDivR); - } - } - /*--------------------------------------------------------------------------*/ -#endif /* STM32F413xx || STM32F423xx */ - - /*------------------------------------ RTC configuration -------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------------ TIM configuration -------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - /* Configure Timer Prescaler */ - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------------- FMPI2C1 Configuration --------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) - { - /* Check the parameters */ - assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); - - /* Configure the FMPI2C1 clock source */ - __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------------- CLK48 Configuration ----------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) - { - /* Check the parameters */ - assert_param(IS_RCC_CLK48CLKSOURCE(PeriphClkInit->Clk48ClockSelection)); - - /* Configure the SDIO clock source */ - __HAL_RCC_CLK48_CONFIG(PeriphClkInit->Clk48ClockSelection); - - /* Enable the PLLI2S when it's used as clock source for CLK48 */ - if(PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ) - { - plli2sused = 1U; - } - } - /*--------------------------------------------------------------------------*/ - - /*------------------------------------- SDIO Configuration -----------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_SDIOCLKSOURCE(PeriphClkInit->SdioClockSelection)); - - /* Configure the SDIO clock source */ - __HAL_RCC_SDIO_CONFIG(PeriphClkInit->SdioClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*-------------------------------------- PLLI2S Configuration --------------*/ - /* PLLI2S is configured when a peripheral will use it as source clock : I2S on APB1 or - I2S on APB2*/ - if((plli2sused == 1U) || (PeriphClkInit->PeriphClockSelection == RCC_PERIPHCLK_PLLI2S)) - { - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* check for common PLLI2S Parameters */ - assert_param(IS_RCC_PLLI2SCLKSOURCE(PeriphClkInit->PLLI2SSelection)); - assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); - /*-------------------- Set the PLL I2S clock -----------------------------*/ - __HAL_RCC_PLL_I2S_CONFIG(PeriphClkInit->PLLI2SSelection); - - /*------- In Case of PLLI2S is selected as source clock for I2S ----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB1) == RCC_PERIPHCLK_I2S_APB1) && (PeriphClkInit->I2sApb1ClockSelection == RCC_I2SAPB1CLKSOURCE_PLLI2S)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S_APB2) == RCC_PERIPHCLK_I2S_APB2) && (PeriphClkInit->I2sApb2ClockSelection == RCC_I2SAPB2CLKSOURCE_PLLI2S)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_CLK48) == RCC_PERIPHCLK_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SDIO) == RCC_PERIPHCLK_SDIO) && (PeriphClkInit->SdioClockSelection == RCC_SDIOCLKSOURCE_CLK48) && (PeriphClkInit->Clk48ClockSelection == RCC_CLK48CLKSOURCE_PLLI2SQ))) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - -#if defined(STM32F413xx) || defined(STM32F423xx) - /*------- In Case of PLLI2S is selected as source clock for SAI ----------*/ - if(((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIA) == RCC_PERIPHCLK_SAIA) && (PeriphClkInit->SaiAClockSelection == RCC_SAIACLKSOURCE_PLLI2SR)) || - ((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAIB) == RCC_PERIPHCLK_SAIB) && (PeriphClkInit->SaiBClockSelection == RCC_SAIBCLKSOURCE_PLLI2SR))) - { - /* Check for PLLI2S Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - /* Check for PLLI2S/DIVR parameters */ - assert_param(IS_RCC_PLLI2S_DIVR_VALUE(PeriphClkInit->PLLI2SDivR)); - - /* Read PLLI2SQ value from PLLI2SCFGR register (this value is not needed for SAI configuration) */ - plli2sq = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN, plli2sq, PeriphClkInit->PLLI2S.PLLI2SR); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVR */ - __HAL_RCC_PLLI2S_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLI2SDivR); - } -#endif /* STM32F413xx || STM32F423xx */ - - /*----------------- In Case of PLLI2S is just selected ------------------*/ - if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - { - /* Check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ - /* SPDIFRXCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SP */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*-------------------- DFSDM1 clock source configuration -------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1) == RCC_PERIPHCLK_DFSDM1) - { - /* Check the parameters */ - assert_param(IS_RCC_DFSDM1CLKSOURCE(PeriphClkInit->Dfsdm1ClockSelection)); - - /* Configure the DFSDM1 interface clock source */ - __HAL_RCC_DFSDM1_CONFIG(PeriphClkInit->Dfsdm1ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*-------------------- DFSDM1 Audio clock source configuration -------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM1_AUDIO) == RCC_PERIPHCLK_DFSDM1_AUDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_DFSDM1AUDIOCLKSOURCE(PeriphClkInit->Dfsdm1AudioClockSelection)); - - /* Configure the DFSDM1 Audio interface clock source */ - __HAL_RCC_DFSDM1AUDIO_CONFIG(PeriphClkInit->Dfsdm1AudioClockSelection); - } - /*--------------------------------------------------------------------------*/ - -#if defined(STM32F413xx) || defined(STM32F423xx) - /*-------------------- DFSDM2 clock source configuration -------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM2) == RCC_PERIPHCLK_DFSDM2) - { - /* Check the parameters */ - assert_param(IS_RCC_DFSDM2CLKSOURCE(PeriphClkInit->Dfsdm2ClockSelection)); - - /* Configure the DFSDM1 interface clock source */ - __HAL_RCC_DFSDM2_CONFIG(PeriphClkInit->Dfsdm2ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*-------------------- DFSDM2 Audio clock source configuration -------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_DFSDM2_AUDIO) == RCC_PERIPHCLK_DFSDM2_AUDIO) - { - /* Check the parameters */ - assert_param(IS_RCC_DFSDM2AUDIOCLKSOURCE(PeriphClkInit->Dfsdm2AudioClockSelection)); - - /* Configure the DFSDM1 Audio interface clock source */ - __HAL_RCC_DFSDM2AUDIO_CONFIG(PeriphClkInit->Dfsdm2AudioClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- LPTIM1 Configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) - { - /* Check the parameters */ - assert_param(IS_RCC_LPTIM1CLKSOURCE(PeriphClkInit->Lptim1ClockSelection)); - - /* Configure the LPTIM1 clock source */ - __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); - } - /*--------------------------------------------------------------------------*/ -#endif /* STM32F413xx || STM32F423xx */ - - return HAL_OK; -} - -/** - * @brief Get the RCC_PeriphCLKInitTypeDef according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ - RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ - RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_CLK48 |\ - RCC_PERIPHCLK_SDIO | RCC_PERIPHCLK_DFSDM1 |\ - RCC_PERIPHCLK_DFSDM1_AUDIO | RCC_PERIPHCLK_DFSDM2 |\ - RCC_PERIPHCLK_DFSDM2_AUDIO | RCC_PERIPHCLK_LPTIM1 |\ - RCC_PERIPHCLK_SAIA | RCC_PERIPHCLK_SAIB; -#else /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S_APB1 | RCC_PERIPHCLK_I2S_APB2 |\ - RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC |\ - RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_CLK48 |\ - RCC_PERIPHCLK_SDIO | RCC_PERIPHCLK_DFSDM1 |\ - RCC_PERIPHCLK_DFSDM1_AUDIO; -#endif /* STM32F413xx || STM32F423xx */ - - - - /* Get the PLLI2S Clock configuration --------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM) >> RCC_PLLI2SCFGR_PLLI2SM_Pos); - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); -#if defined(STM32F413xx) || defined(STM32F423xx) - /* Get the PLL/PLLI2S division factors -------------------------------------*/ - PeriphClkInit->PLLI2SDivR = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVR) >> RCC_DCKCFGR_PLLI2SDIVR_Pos); - PeriphClkInit->PLLDivR = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLDIVR) >> RCC_DCKCFGR_PLLDIVR_Pos); -#endif /* STM32F413xx || STM32F423xx */ - - /* Get the I2S APB1 clock configuration ------------------------------------*/ - PeriphClkInit->I2sApb1ClockSelection = __HAL_RCC_GET_I2S_APB1_SOURCE(); - - /* Get the I2S APB2 clock configuration ------------------------------------*/ - PeriphClkInit->I2sApb2ClockSelection = __HAL_RCC_GET_I2S_APB2_SOURCE(); - - /* Get the RTC Clock configuration -----------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - /* Get the FMPI2C1 clock configuration -------------------------------------*/ - PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); - - /* Get the CLK48 clock configuration ---------------------------------------*/ - PeriphClkInit->Clk48ClockSelection = __HAL_RCC_GET_CLK48_SOURCE(); - - /* Get the SDIO clock configuration ----------------------------------------*/ - PeriphClkInit->SdioClockSelection = __HAL_RCC_GET_SDIO_SOURCE(); - - /* Get the DFSDM1 clock configuration --------------------------------------*/ - PeriphClkInit->Dfsdm1ClockSelection = __HAL_RCC_GET_DFSDM1_SOURCE(); - - /* Get the DFSDM1 Audio clock configuration --------------------------------*/ - PeriphClkInit->Dfsdm1AudioClockSelection = __HAL_RCC_GET_DFSDM1AUDIO_SOURCE(); - -#if defined(STM32F413xx) || defined(STM32F423xx) - /* Get the DFSDM2 clock configuration --------------------------------------*/ - PeriphClkInit->Dfsdm2ClockSelection = __HAL_RCC_GET_DFSDM2_SOURCE(); - - /* Get the DFSDM2 Audio clock configuration --------------------------------*/ - PeriphClkInit->Dfsdm2AudioClockSelection = __HAL_RCC_GET_DFSDM2AUDIO_SOURCE(); - - /* Get the LPTIM1 clock configuration --------------------------------------*/ - PeriphClkInit->Lptim1ClockSelection = __HAL_RCC_GET_LPTIM1_SOURCE(); - - /* Get the SAI1 Block Aclock configuration ---------------------------------*/ - PeriphClkInit->SaiAClockSelection = __HAL_RCC_GET_SAI_BLOCKA_SOURCE(); - - /* Get the SAI1 Block B clock configuration --------------------------------*/ - PeriphClkInit->SaiBClockSelection = __HAL_RCC_GET_SAI_BLOCKB_SOURCE(); -#endif /* STM32F413xx || STM32F423xx */ - - /* Get the TIM Prescaler configuration -------------------------------------*/ - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(I2S..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S_APB1: I2S APB1 peripheral clock - * @arg RCC_PERIPHCLK_I2S_APB2: I2S APB2 peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S_APB1: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_APB1_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_PLLI2S: - { - if((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SSRC) == RCC_PLLI2SCFGR_PLLI2SSRC) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(EXTERNAL_CLOCK_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - } - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPB1CLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPB1CLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - case RCC_PERIPHCLK_I2S_APB2: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_APB2_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_PLLI2S: - { - if((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SSRC) == RCC_PLLI2SCFGR_PLLI2SSRC) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(EXTERNAL_CLOCK_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - } - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPB2CLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPB2CLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the - * RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals clocks(I2S and RTC clocks). - * - * @note A caution to be taken when HAL_RCCEx_PeriphCLKConfig() is used to select RTC clock selection, in this case - * the Reset of Backup domain will be applied in order to modify the RTC Clock source as consequence all backup - * domain (RTC and RCC_BDCR register expect BKPSRAM) will be reset - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - - /* Check the parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*---------------------------- RTC configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- FMPI2C1 Configuration -----------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_FMPI2C1) == RCC_PERIPHCLK_FMPI2C1) - { - /* Check the parameters */ - assert_param(IS_RCC_FMPI2C1CLKSOURCE(PeriphClkInit->Fmpi2c1ClockSelection)); - - /* Configure the FMPI2C1 clock source */ - __HAL_RCC_FMPI2C1_CONFIG(PeriphClkInit->Fmpi2c1ClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- LPTIM1 Configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LPTIM1) == RCC_PERIPHCLK_LPTIM1) - { - /* Check the parameters */ - assert_param(IS_RCC_LPTIM1CLKSOURCE(PeriphClkInit->Lptim1ClockSelection)); - - /* Configure the LPTIM1 clock source */ - __HAL_RCC_LPTIM1_CONFIG(PeriphClkInit->Lptim1ClockSelection); - } - - /*---------------------------- I2S Configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) - { - /* Check the parameters */ - assert_param(IS_RCC_I2SAPBCLKSOURCE(PeriphClkInit->I2SClockSelection)); - - /* Configure the I2S clock source */ - __HAL_RCC_I2S_CONFIG(PeriphClkInit->I2SClockSelection); - } - - return HAL_OK; -} - -/** - * @brief Configures the RCC_OscInitStruct according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_FMPI2C1 | RCC_PERIPHCLK_LPTIM1 | RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC; - - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } - /* Get the FMPI2C1 clock configuration -------------------------------------*/ - PeriphClkInit->Fmpi2c1ClockSelection = __HAL_RCC_GET_FMPI2C1_SOURCE(); - - /* Get the I2S clock configuration -----------------------------------------*/ - PeriphClkInit->I2SClockSelection = __HAL_RCC_GET_I2S_SOURCE(); - - -} -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SAPBCLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLL VCO Output divided by PLLR used as I2S clock */ - case RCC_I2SAPBCLKSOURCE_PLLR: - { - /* Configure the PLL division factor R */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U) & (RCC_PLLCFGR_PLLN >> 6U))); - /* I2S_CLK = PLL_VCO Output/PLLR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U) & (RCC_PLLCFGR_PLLR >> 28U))); - break; - } - /* Check if I2S clock selection is HSI or HSE depending from PLL source Clock */ - case RCC_I2SAPBCLKSOURCE_PLLSRC: - { - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - frequency = HSE_VALUE; - } - else - { - frequency = HSI_VALUE; - } - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified - * parameters in the RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals - * clocks(I2S, SAI, LTDC RTC and TIM). - * - * @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select - * the RTC clock source; in this case the Backup domain will be reset in - * order to modify the RTC Clock source, as consequence RTC registers (including - * the backup registers) and RCC_BDCR register are set to their reset values. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - - /* Check the parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*----------------------- SAI/I2S Configuration (PLLI2S) -------------------*/ - /*----------------------- Common configuration SAI/I2S ---------------------*/ - /* In Case of SAI or I2S Clock Configuration through PLLI2S, PLLI2SN division - factor is common parameters for both peripherals */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == RCC_PERIPHCLK_SAI_PLLI2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); - - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /*---------------------------- I2S configuration -------------------------*/ - /* In Case of I2S Clock Configuration through PLLI2S, PLLI2SR must be added - only for I2S configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == (RCC_PERIPHCLK_I2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); - } - - /*---------------------------- SAI configuration -------------------------*/ - /* In Case of SAI Clock Configuration through PLLI2S, PLLI2SQ and PLLI2S_DIVQ must - be added only for SAI configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLI2S) == (RCC_PERIPHCLK_SAI_PLLI2S)) - { - /* Check the PLLI2S division factors */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(PeriphClkInit->PLLI2SDivQ)); - - /* Read PLLI2SR value from PLLI2SCFGR register (this value is not need for SAI configuration) */ - tmpreg1 = ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SQ , tmpreg1); - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLI2SDivQ); - } - - /*----------------- In Case of PLLI2S is just selected -----------------*/ - if((PeriphClkInit->PeriphClockSelection & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S) - { - /* Check for Parameters */ - assert_param(IS_RCC_PLLI2SQ_VALUE(PeriphClkInit->PLLI2S.PLLI2SQ)); - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - - /* Configure the PLLI2S multiplication and division factors */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SQ, PeriphClkInit->PLLI2S.PLLI2SR); - } - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*----------------------- SAI/LTDC Configuration (PLLSAI) ------------------*/ - /*----------------------- Common configuration SAI/LTDC --------------------*/ - /* In Case of SAI or LTDC Clock Configuration through PLLSAI, PLLSAIN division - factor is common parameters for both peripherals */ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == RCC_PERIPHCLK_SAI_PLLSAI) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == RCC_PERIPHCLK_LTDC)) - { - /* Check the PLLSAI division factors */ - assert_param(IS_RCC_PLLSAIN_VALUE(PeriphClkInit->PLLSAI.PLLSAIN)); - - /* Disable PLLSAI Clock */ - __HAL_RCC_PLLSAI_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is disabled */ - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /*---------------------------- SAI configuration -------------------------*/ - /* In Case of SAI Clock Configuration through PLLSAI, PLLSAIQ and PLLSAI_DIVQ must - be added only for SAI configuration */ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_SAI_PLLSAI) == (RCC_PERIPHCLK_SAI_PLLSAI)) - { - assert_param(IS_RCC_PLLSAIQ_VALUE(PeriphClkInit->PLLSAI.PLLSAIQ)); - assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(PeriphClkInit->PLLSAIDivQ)); - - /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ - tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , PeriphClkInit->PLLSAI.PLLSAIQ, tmpreg1); - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(PeriphClkInit->PLLSAIDivQ); - } - - /*---------------------------- LTDC configuration ------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_LTDC) == (RCC_PERIPHCLK_LTDC)) - { - assert_param(IS_RCC_PLLSAIR_VALUE(PeriphClkInit->PLLSAI.PLLSAIR)); - assert_param(IS_RCC_PLLSAI_DIVR_VALUE(PeriphClkInit->PLLSAIDivR)); - - /* Read PLLSAIR value from PLLSAICFGR register (this value is not need for SAI configuration) */ - tmpreg1 = ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* LTDC_CLK(first level) = PLLSAI_VCO Output/PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PeriphClkInit->PLLSAI.PLLSAIN , tmpreg1, PeriphClkInit->PLLSAI.PLLSAIR); - /* LTDC_CLK = LTDC_CLK(first level)/PLLSAIDIVR */ - __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(PeriphClkInit->PLLSAIDivR); - } - /* Enable PLLSAI Clock */ - __HAL_RCC_PLLSAI_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLSAI is ready */ - while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- RTC configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } - /*--------------------------------------------------------------------------*/ - - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } - return HAL_OK; -} - -/** - * @brief Configures the PeriphClkInit according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_SAI_PLLSAI | RCC_PERIPHCLK_SAI_PLLI2S | RCC_PERIPHCLK_LTDC | RCC_PERIPHCLK_TIM | RCC_PERIPHCLK_RTC; - - /* Get the PLLI2S Clock configuration -----------------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); - PeriphClkInit->PLLI2S.PLLI2SQ = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos); - /* Get the PLLSAI Clock configuration -----------------------------------------------*/ - PeriphClkInit->PLLSAI.PLLSAIN = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); - PeriphClkInit->PLLSAI.PLLSAIR = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIR) >> RCC_PLLSAICFGR_PLLSAIR_Pos); - PeriphClkInit->PLLSAI.PLLSAIQ = (uint32_t)((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> RCC_PLLSAICFGR_PLLSAIQ_Pos); - /* Get the PLLSAI/PLLI2S division factors -----------------------------------------------*/ - PeriphClkInit->PLLI2SDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos); - PeriphClkInit->PLLSAIDivQ = (uint32_t)((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos); - PeriphClkInit->PLLSAIDivR = (uint32_t)(RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVR); - /* Get the RTC Clock configuration -----------------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SCLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SCLKSOURCE_PLLI2S: - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -/** - * @brief Initializes the RCC extended peripherals clocks according to the specified parameters in the - * RCC_PeriphCLKInitTypeDef. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * contains the configuration information for the Extended Peripherals clocks(I2S and RTC clocks). - * - * @note A caution to be taken when HAL_RCCEx_PeriphCLKConfig() is used to select RTC clock selection, in this case - * the Reset of Backup domain will be applied in order to modify the RTC Clock source as consequence all backup - * domain (RTC and RCC_BDCR register expect BKPSRAM) will be reset - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg1 = 0U; - - /* Check the parameters */ - assert_param(IS_RCC_PERIPHCLOCK(PeriphClkInit->PeriphClockSelection)); - - /*---------------------------- I2S configuration ---------------------------*/ - if((((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_I2S) == RCC_PERIPHCLK_I2S) || - (((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_PLLI2S) == RCC_PERIPHCLK_PLLI2S)) - { - /* check for Parameters */ - assert_param(IS_RCC_PLLI2SR_VALUE(PeriphClkInit->PLLI2S.PLLI2SR)); - assert_param(IS_RCC_PLLI2SN_VALUE(PeriphClkInit->PLLI2S.PLLI2SN)); -#if defined(STM32F411xE) - assert_param(IS_RCC_PLLI2SM_VALUE(PeriphClkInit->PLLI2S.PLLI2SM)); -#endif /* STM32F411xE */ - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - -#if defined(STM32F411xE) - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_I2SCLK_CONFIG(PeriphClkInit->PLLI2S.PLLI2SM, PeriphClkInit->PLLI2S.PLLI2SN, PeriphClkInit->PLLI2S.PLLI2SR); -#else - /* Configure the PLLI2S division factors */ - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLM) */ - /* I2SCLK = f(PLLI2S clock output) = f(VCO clock) / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PeriphClkInit->PLLI2S.PLLI2SN , PeriphClkInit->PLLI2S.PLLI2SR); -#endif /* STM32F411xE */ - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - /* Get tick */ - tickstart = HAL_GetTick(); - /* Wait till PLLI2S is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - } - - /*---------------------------- RTC configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_RTC) == (RCC_PERIPHCLK_RTC)) - { - /* Check for RTC Parameters used to output RTCCLK */ - assert_param(IS_RCC_RTCCLKSOURCE(PeriphClkInit->RTCClockSelection)); - - /* Enable Power Clock*/ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* Enable write access to Backup domain */ - PWR->CR |= PWR_CR_DBP; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while((PWR->CR & PWR_CR_DBP) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - /* Reset the Backup domain only if the RTC Clock source selection is modified from reset value */ - tmpreg1 = (RCC->BDCR & RCC_BDCR_RTCSEL); - if((tmpreg1 != 0x00000000U) && ((tmpreg1) != (PeriphClkInit->RTCClockSelection & RCC_BDCR_RTCSEL))) - { - /* Store the content of BDCR register before the reset of Backup Domain */ - tmpreg1 = (RCC->BDCR & ~(RCC_BDCR_RTCSEL)); - /* RTC Clock selection can be changed only if the Backup Domain is reset */ - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - /* Restore the Content of BDCR register */ - RCC->BDCR = tmpreg1; - - /* Wait for LSE reactivation if LSE was enable prior to Backup Domain reset */ - if(HAL_IS_BIT_SET(RCC->BDCR, RCC_BDCR_LSEON)) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - __HAL_RCC_RTC_CONFIG(PeriphClkInit->RTCClockSelection); - } -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) - /*---------------------------- TIM configuration ---------------------------*/ - if(((PeriphClkInit->PeriphClockSelection) & RCC_PERIPHCLK_TIM) == (RCC_PERIPHCLK_TIM)) - { - __HAL_RCC_TIMCLKPRESCALER(PeriphClkInit->TIMPresSelection); - } -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - return HAL_OK; -} - -/** - * @brief Configures the RCC_OscInitStruct according to the internal - * RCC configuration registers. - * @param PeriphClkInit pointer to an RCC_PeriphCLKInitTypeDef structure that - * will be configured. - * @retval None - */ -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit) -{ - uint32_t tempreg; - - /* Set all possible values for the extended clock type parameter------------*/ - PeriphClkInit->PeriphClockSelection = RCC_PERIPHCLK_I2S | RCC_PERIPHCLK_RTC; - - /* Get the PLLI2S Clock configuration --------------------------------------*/ - PeriphClkInit->PLLI2S.PLLI2SN = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); - PeriphClkInit->PLLI2S.PLLI2SR = (uint32_t)((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> RCC_PLLI2SCFGR_PLLI2SR_Pos); -#if defined(STM32F411xE) - PeriphClkInit->PLLI2S.PLLI2SM = (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM); -#endif /* STM32F411xE */ - /* Get the RTC Clock configuration -----------------------------------------*/ - tempreg = (RCC->CFGR & RCC_CFGR_RTCPRE); - PeriphClkInit->RTCClockSelection = (uint32_t)((tempreg) | (RCC->BDCR & RCC_BDCR_RTCSEL)); - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) - /* Get the TIM Prescaler configuration -------------------------------------*/ - if ((RCC->DCKCFGR & RCC_DCKCFGR_TIMPRE) == RESET) - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_DESACTIVATED; - } - else - { - PeriphClkInit->TIMPresSelection = RCC_TIMPRES_ACTIVATED; - } -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ -} - -/** - * @brief Return the peripheral clock frequency for a given peripheral(SAI..) - * @note Return 0 if peripheral clock identifier not managed by this API - * @param PeriphClk Peripheral clock identifier - * This parameter can be one of the following values: - * @arg RCC_PERIPHCLK_I2S: I2S peripheral clock - * @retval Frequency in KHz - */ -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk) -{ - /* This variable used to store the I2S clock frequency (value in Hz) */ - uint32_t frequency = 0U; - /* This variable used to store the VCO Input (value in Hz) */ - uint32_t vcoinput = 0U; - uint32_t srcclk = 0U; - /* This variable used to store the VCO Output (value in Hz) */ - uint32_t vcooutput = 0U; - switch (PeriphClk) - { - case RCC_PERIPHCLK_I2S: - { - /* Get the current I2S source */ - srcclk = __HAL_RCC_GET_I2S_SOURCE(); - switch (srcclk) - { - /* Check if I2S clock selection is External clock mapped on the I2S_CKIN pin used as I2S clock */ - case RCC_I2SCLKSOURCE_EXT: - { - /* Set the I2S clock to the external clock value */ - frequency = EXTERNAL_CLOCK_VALUE; - break; - } - /* Check if I2S clock selection is PLLI2S VCO output clock divided by PLLI2SR used as I2S clock */ - case RCC_I2SCLKSOURCE_PLLI2S: - { -#if defined(STM32F411xE) - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLI2SM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SM)); - } -#else - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* Get the I2S source clock value */ - vcoinput = (uint32_t)(HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } -#endif /* STM32F411xE */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - vcooutput = (uint32_t)(vcoinput * (((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U) & (RCC_PLLI2SCFGR_PLLI2SN >> 6U))); - /* I2S_CLK = PLLI2S_VCO Output/PLLI2SR */ - frequency = (uint32_t)(vcooutput /(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U) & (RCC_PLLI2SCFGR_PLLI2SR >> 28U))); - break; - } - /* Clock not enabled for I2S*/ - default: - { - frequency = 0U; - break; - } - } - break; - } - } - return frequency; -} -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Select LSE mode - * - * @note This mode is only available for STM32F410xx/STM32F411xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices. - * - * @param Mode specifies the LSE mode. - * This parameter can be one of the following values: - * @arg RCC_LSE_LOWPOWER_MODE: LSE oscillator in low power mode selection - * @arg RCC_LSE_HIGHDRIVE_MODE: LSE oscillator in High Drive mode selection - * @retval None - */ -void HAL_RCCEx_SelectLSEMode(uint8_t Mode) -{ - /* Check the parameters */ - assert_param(IS_RCC_LSE_MODE(Mode)); - if(Mode == RCC_LSE_HIGHDRIVE_MODE) - { - SET_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); - } - else - { - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); - } -} - -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** @defgroup RCCEx_Exported_Functions_Group2 Extended Clock management functions - * @brief Extended Clock management functions - * -@verbatim - =============================================================================== - ##### Extended clock management functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the - activation or deactivation of PLLI2S, PLLSAI. -@endverbatim - * @{ - */ - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Enable PLLI2S. - * @param PLLI2SInit pointer to an RCC_PLLI2SInitTypeDef structure that - * contains the configuration information for the PLLI2S - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_EnablePLLI2S(RCC_PLLI2SInitTypeDef *PLLI2SInit) -{ - uint32_t tickstart; - - /* Check for parameters */ - assert_param(IS_RCC_PLLI2SN_VALUE(PLLI2SInit->PLLI2SN)); - assert_param(IS_RCC_PLLI2SR_VALUE(PLLI2SInit->PLLI2SR)); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - assert_param(IS_RCC_PLLI2SM_VALUE(PLLI2SInit->PLLI2SM)); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ -#if defined(RCC_PLLI2SCFGR_PLLI2SP) - assert_param(IS_RCC_PLLI2SP_VALUE(PLLI2SInit->PLLI2SP)); -#endif /* RCC_PLLI2SCFGR_PLLI2SP */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) - assert_param(IS_RCC_PLLI2SQ_VALUE(PLLI2SInit->PLLI2SQ)); -#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ - - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - - /* Wait till PLLI2S is disabled */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* Configure the PLLI2S division factors */ -#if defined(STM32F446xx) - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* I2SPCLK = PLLI2S_VCO / PLLI2SP */ - /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, \ - PLLI2SInit->PLLI2SP, PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); -#elif defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM)*/ - /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, \ - PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); -#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * PLLI2SN */ - /* I2SQCLK = PLLI2S_VCO / PLLI2SQ */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_SAICLK_CONFIG(PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SQ, PLLI2SInit->PLLI2SR); -#elif defined(STM32F411xE) - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) * (PLLI2SN/PLLI2SM) */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_I2SCLK_CONFIG(PLLI2SInit->PLLI2SM, PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SR); -#else - /* PLLI2S_VCO = f(VCO clock) = f(PLLI2S clock input) x PLLI2SN */ - /* I2SRCLK = PLLI2S_VCO / PLLI2SR */ - __HAL_RCC_PLLI2S_CONFIG(PLLI2SInit->PLLI2SN, PLLI2SInit->PLLI2SR); -#endif /* STM32F446xx */ - - /* Enable the PLLI2S */ - __HAL_RCC_PLLI2S_ENABLE(); - - /* Wait till PLLI2S is ready */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLI2SRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -/** - * @brief Disable PLLI2S. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_DisablePLLI2S(void) -{ - uint32_t tickstart; - - /* Disable the PLLI2S */ - __HAL_RCC_PLLI2S_DISABLE(); - - /* Wait till PLLI2S is disabled */ - tickstart = HAL_GetTick(); - while(READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) != RESET) - { - if((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Enable PLLSAI. - * @param PLLSAIInit pointer to an RCC_PLLSAIInitTypeDef structure that - * contains the configuration information for the PLLSAI - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_EnablePLLSAI(RCC_PLLSAIInitTypeDef *PLLSAIInit) -{ - uint32_t tickstart; - - /* Check for parameters */ - assert_param(IS_RCC_PLLSAIN_VALUE(PLLSAIInit->PLLSAIN)); - assert_param(IS_RCC_PLLSAIQ_VALUE(PLLSAIInit->PLLSAIQ)); -#if defined(RCC_PLLSAICFGR_PLLSAIM) - assert_param(IS_RCC_PLLSAIM_VALUE(PLLSAIInit->PLLSAIM)); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ -#if defined(RCC_PLLSAICFGR_PLLSAIP) - assert_param(IS_RCC_PLLSAIP_VALUE(PLLSAIInit->PLLSAIP)); -#endif /* RCC_PLLSAICFGR_PLLSAIP */ -#if defined(RCC_PLLSAICFGR_PLLSAIR) - assert_param(IS_RCC_PLLSAIR_VALUE(PLLSAIInit->PLLSAIR)); -#endif /* RCC_PLLSAICFGR_PLLSAIR */ - - /* Disable the PLLSAI */ - __HAL_RCC_PLLSAI_DISABLE(); - - /* Wait till PLLSAI is disabled */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - /* Configure the PLLSAI division factors */ -#if defined(STM32F446xx) - /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * (PLLSAIN/PLLSAIM) */ - /* SAIPCLK = PLLSAI_VCO / PLLSAIP */ - /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ - /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIM, PLLSAIInit->PLLSAIN, \ - PLLSAIInit->PLLSAIP, PLLSAIInit->PLLSAIQ, 0U); -#elif defined(STM32F469xx) || defined(STM32F479xx) - /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) * PLLSAIN */ - /* SAIPCLK = PLLSAI_VCO / PLLSAIP */ - /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ - /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIN, PLLSAIInit->PLLSAIP, \ - PLLSAIInit->PLLSAIQ, PLLSAIInit->PLLSAIR); -#else - /* PLLSAI_VCO = f(VCO clock) = f(PLLSAI clock input) x PLLSAIN */ - /* SAIQCLK = PLLSAI_VCO / PLLSAIQ */ - /* SAIRCLK = PLLSAI_VCO / PLLSAIR */ - __HAL_RCC_PLLSAI_CONFIG(PLLSAIInit->PLLSAIN, PLLSAIInit->PLLSAIQ, PLLSAIInit->PLLSAIR); -#endif /* STM32F446xx */ - - /* Enable the PLLSAI */ - __HAL_RCC_PLLSAI_ENABLE(); - - /* Wait till PLLSAI is ready */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_PLLSAI_GET_FLAG() == RESET) - { - if((HAL_GetTick() - tickstart ) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -/** - * @brief Disable PLLSAI. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCCEx_DisablePLLSAI(void) -{ - uint32_t tickstart; - - /* Disable the PLLSAI */ - __HAL_RCC_PLLSAI_DISABLE(); - - /* Wait till PLLSAI is disabled */ - tickstart = HAL_GetTick(); - while(__HAL_RCC_PLLSAI_GET_FLAG() != RESET) - { - if((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) - { - /* return in case of Timeout detected */ - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @} - */ - -#if defined(STM32F446xx) -/** - * @brief Returns the SYSCLK frequency - * - * @note This function implementation is valid only for STM32F446xx devices. - * @note This function add the PLL/PLLR System clock source - * - * @note The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(*) - * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(**) - * @note If SYSCLK source is PLL or PLLR, function returns values based on HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * @note (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * @note (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 25 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * @note The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @note This function can be used by the user application to compute the - * baudrate for the communication peripherals or configure other parameters. - * - * @note Each time SYSCLK changes, this function must be called to update the - * right SYSCLK value. Otherwise, any configuration based on this function will be incorrect. - * - * - * @retval SYSCLK frequency - */ -uint32_t HAL_RCC_GetSysClockFreq(void) -{ - uint32_t pllm = 0U; - uint32_t pllvco = 0U; - uint32_t pllp = 0U; - uint32_t pllr = 0U; - uint32_t sysclockfreq = 0U; - - /* Get SYSCLK source -------------------------------------------------------*/ - switch (RCC->CFGR & RCC_CFGR_SWS) - { - case RCC_CFGR_SWS_HSI: /* HSI used as system clock source */ - { - sysclockfreq = HSI_VALUE; - break; - } - case RCC_CFGR_SWS_HSE: /* HSE used as system clock source */ - { - sysclockfreq = HSE_VALUE; - break; - } - case RCC_CFGR_SWS_PLL: /* PLL/PLLP used as system clock source */ - { - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SYSCLK = PLL_VCO / PLLP */ - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) - { - /* HSE used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - pllp = ((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >> RCC_PLLCFGR_PLLP_Pos) + 1U) *2U); - - sysclockfreq = pllvco/pllp; - break; - } - case RCC_CFGR_SWS_PLLR: /* PLL/PLLR used as system clock source */ - { - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SYSCLK = PLL_VCO / PLLR */ - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - if(__HAL_RCC_GET_PLL_OSCSOURCE() != RCC_PLLSOURCE_HSI) - { - /* HSE used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSE_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (uint32_t) ((((uint64_t) HSI_VALUE * ((uint64_t) ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos)))) / (uint64_t)pllm); - } - pllr = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos); - - sysclockfreq = pllvco/pllr; - break; - } - default: - { - sysclockfreq = HSI_VALUE; - break; - } - } - return sysclockfreq; -} -#endif /* STM32F446xx */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @brief Resets the RCC clock configuration to the default reset state. - * @note The default reset state of the clock configuration is given below: - * - HSI ON and used as system clock source - * - HSE, PLL, PLLI2S and PLLSAI OFF - * - AHB, APB1 and APB2 prescaler set to 1. - * - CSS, MCO1 and MCO2 OFF - * - All interrupts disabled - * @note This function doesn't modify the configuration of the - * - Peripheral clocks - * - LSI, LSE and RTC clocks - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCC_DeInit(void) -{ - uint32_t tickstart; - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Set HSION bit to the reset value */ - SET_BIT(RCC->CR, RCC_CR_HSION); - - /* Wait till HSI is ready */ - while (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == RESET) - { - if ((HAL_GetTick() - tickstart) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Set HSITRIM[4:0] bits to the reset value */ - SET_BIT(RCC->CR, RCC_CR_HSITRIM_4); - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Reset CFGR register */ - CLEAR_REG(RCC->CFGR); - - /* Wait till clock switch is ready */ - while (READ_BIT(RCC->CFGR, RCC_CFGR_SWS) != RESET) - { - if ((HAL_GetTick() - tickstart) > CLOCKSWITCH_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Clear HSEON, HSEBYP and CSSON bits */ - CLEAR_BIT(RCC->CR, RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_CSSON); - - /* Wait till HSE is disabled */ - while (READ_BIT(RCC->CR, RCC_CR_HSERDY) != RESET) - { - if ((HAL_GetTick() - tickstart) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Clear PLLON bit */ - CLEAR_BIT(RCC->CR, RCC_CR_PLLON); - - /* Wait till PLL is disabled */ - while (READ_BIT(RCC->CR, RCC_CR_PLLRDY) != RESET) - { - if ((HAL_GetTick() - tickstart) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - -#if defined(RCC_PLLI2S_SUPPORT) - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Reset PLLI2SON bit */ - CLEAR_BIT(RCC->CR, RCC_CR_PLLI2SON); - - /* Wait till PLLI2S is disabled */ - while (READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) != RESET) - { - if ((HAL_GetTick() - tickstart) > PLLI2S_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) - /* Get Start Tick */ - tickstart = HAL_GetTick(); - - /* Reset PLLSAI bit */ - CLEAR_BIT(RCC->CR, RCC_CR_PLLSAION); - - /* Wait till PLLSAI is disabled */ - while (READ_BIT(RCC->CR, RCC_CR_PLLSAIRDY) != RESET) - { - if ((HAL_GetTick() - tickstart) > PLLSAI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } -#endif /* RCC_PLLSAI_SUPPORT */ - - /* Once PLL, PLLI2S and PLLSAI are OFF, reset PLLCFGR register to default value */ -#if defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || \ - defined(STM32F423xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - RCC->PLLCFGR = RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLR_1; -#elif defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) - RCC->PLLCFGR = RCC_PLLCFGR_PLLR_0 | RCC_PLLCFGR_PLLR_1 | RCC_PLLCFGR_PLLR_2 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_0 | RCC_PLLCFGR_PLLQ_1 | RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLQ_3; -#else - RCC->PLLCFGR = RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_7 | RCC_PLLCFGR_PLLQ_2; -#endif /* STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F446xx || STM32F469xx || STM32F479xx */ - - /* Reset PLLI2SCFGR register to default value */ -#if defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || \ - defined(STM32F423xx) || defined(STM32F446xx) - RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SR_1; -#elif defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) - RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1; -#elif defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SR_1; -#elif defined(STM32F411xE) - RCC->PLLI2SCFGR = RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SN_6 | RCC_PLLI2SCFGR_PLLI2SN_7 | RCC_PLLI2SCFGR_PLLI2SR_1; -#endif /* STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F446xx */ - - /* Reset PLLSAICFGR register */ -#if defined(STM32F427xx) || defined(STM32F429xx) || defined(STM32F437xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - RCC->PLLSAICFGR = RCC_PLLSAICFGR_PLLSAIN_6 | RCC_PLLSAICFGR_PLLSAIN_7 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIR_1; -#elif defined(STM32F446xx) - RCC->PLLSAICFGR = RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIN_6 | RCC_PLLSAICFGR_PLLSAIN_7 | RCC_PLLSAICFGR_PLLSAIQ_2; -#endif /* STM32F427xx || STM32F429xx || STM32F437xx || STM32F439xx || STM32F469xx || STM32F479xx */ - - /* Disable all interrupts */ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE | RCC_CIR_LSERDYIE | RCC_CIR_HSIRDYIE | RCC_CIR_HSERDYIE | RCC_CIR_PLLRDYIE); - -#if defined(RCC_CIR_PLLI2SRDYIE) - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -#endif /* RCC_CIR_PLLI2SRDYIE */ - -#if defined(RCC_CIR_PLLSAIRDYIE) - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -#endif /* RCC_CIR_PLLSAIRDYIE */ - - /* Clear all interrupt flags */ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC | RCC_CIR_LSERDYC | RCC_CIR_HSIRDYC | RCC_CIR_HSERDYC | RCC_CIR_PLLRDYC | RCC_CIR_CSSC); - -#if defined(RCC_CIR_PLLI2SRDYC) - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); -#endif /* RCC_CIR_PLLI2SRDYC */ - -#if defined(RCC_CIR_PLLSAIRDYC) - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); -#endif /* RCC_CIR_PLLSAIRDYC */ - - /* Clear LSION bit */ - CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); - - /* Reset all CSR flags */ - SET_BIT(RCC->CSR, RCC_CSR_RMVF); - - /* Update the SystemCoreClock global variable */ - SystemCoreClock = HSI_VALUE; - - /* Adapt Systick interrupt period */ - if(HAL_InitTick(uwTickPrio) != HAL_OK) - { - return HAL_ERROR; - } - else - { - return HAL_OK; - } -} - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief Initializes the RCC Oscillators according to the specified parameters in the - * RCC_OscInitTypeDef. - * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that - * contains the configuration information for the RCC Oscillators. - * @note The PLL is not disabled when used as system clock. - * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not - * supported by this API. User should request a transition to LSE Off - * first and then LSE On or LSE Bypass. - * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not - * supported by this API. User should request a transition to HSE Off - * first and then HSE On or HSE Bypass. - * @note This function add the PLL/PLLR factor management during PLL configuration this feature - * is only available in STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) -{ - uint32_t tickstart, pll_config; - - /* Check Null pointer */ - if(RCC_OscInitStruct == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_RCC_OSCILLATORTYPE(RCC_OscInitStruct->OscillatorType)); - /*------------------------------- HSE Configuration ------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) - { - /* Check the parameters */ - assert_param(IS_RCC_HSE(RCC_OscInitStruct->HSEState)); - /* When the HSE is used as system clock or clock source for PLL in these cases HSE will not disabled */ -#if defined(STM32F446xx) - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE)) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLLR) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) -#else - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSE) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE))) -#endif /* STM32F446xx */ - { - if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) && (RCC_OscInitStruct->HSEState == RCC_HSE_OFF)) - { - return HAL_ERROR; - } - } - else - { - /* Set the new HSE configuration ---------------------------------------*/ - __HAL_RCC_HSE_CONFIG(RCC_OscInitStruct->HSEState); - - /* Check the HSE State */ - if((RCC_OscInitStruct->HSEState) != RCC_HSE_OFF) - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSE is bypassed or disabled */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSERDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > HSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - } - /*----------------------------- HSI Configuration --------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) - { - /* Check the parameters */ - assert_param(IS_RCC_HSI(RCC_OscInitStruct->HSIState)); - assert_param(IS_RCC_CALIBRATION_VALUE(RCC_OscInitStruct->HSICalibrationValue)); - - /* Check if HSI is used as system clock or as PLL source when PLL is selected as system clock */ -#if defined(STM32F446xx) - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI)) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLLR) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) -#else - if((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_HSI) ||\ - ((__HAL_RCC_GET_SYSCLK_SOURCE() == RCC_CFGR_SWS_PLL) && ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSI))) -#endif /* STM32F446xx */ - { - /* When HSI is used as system clock it will not disabled */ - if((__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) && (RCC_OscInitStruct->HSIState != RCC_HSI_ON)) - { - return HAL_ERROR; - } - /* Otherwise, just the calibration is allowed */ - else - { - /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ - __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - } - } - else - { - /* Check the HSI State */ - if((RCC_OscInitStruct->HSIState)!= RCC_HSI_OFF) - { - /* Enable the Internal High Speed oscillator (HSI). */ - __HAL_RCC_HSI_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Adjusts the Internal High Speed oscillator (HSI) calibration value.*/ - __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(RCC_OscInitStruct->HSICalibrationValue); - } - else - { - /* Disable the Internal High Speed oscillator (HSI). */ - __HAL_RCC_HSI_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till HSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > HSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - } - /*------------------------------ LSI Configuration -------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) - { - /* Check the parameters */ - assert_param(IS_RCC_LSI(RCC_OscInitStruct->LSIState)); - - /* Check the LSI State */ - if((RCC_OscInitStruct->LSIState)!= RCC_LSI_OFF) - { - /* Enable the Internal Low Speed oscillator (LSI). */ - __HAL_RCC_LSI_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Disable the Internal Low Speed oscillator (LSI). */ - __HAL_RCC_LSI_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSI is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > LSI_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - /*------------------------------ LSE Configuration -------------------------*/ - if(((RCC_OscInitStruct->OscillatorType) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE) - { - FlagStatus pwrclkchanged = RESET; - - /* Check the parameters */ - assert_param(IS_RCC_LSE(RCC_OscInitStruct->LSEState)); - - /* Update LSE configuration in Backup Domain control register */ - /* Requires to enable write access to Backup Domain of necessary */ - if(__HAL_RCC_PWR_IS_CLK_DISABLED()) - { - __HAL_RCC_PWR_CLK_ENABLE(); - pwrclkchanged = SET; - } - - if(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) - { - /* Enable write access to Backup domain */ - SET_BIT(PWR->CR, PWR_CR_DBP); - - /* Wait for Backup domain Write protection disable */ - tickstart = HAL_GetTick(); - - while(HAL_IS_BIT_CLR(PWR->CR, PWR_CR_DBP)) - { - if((HAL_GetTick() - tickstart) > RCC_DBP_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Set the new LSE configuration -----------------------------------------*/ - __HAL_RCC_LSE_CONFIG(RCC_OscInitStruct->LSEState); - /* Check the LSE State */ - if((RCC_OscInitStruct->LSEState) != RCC_LSE_OFF) - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till LSE is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > RCC_LSE_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - /* Restore clock configuration if changed */ - if(pwrclkchanged == SET) - { - __HAL_RCC_PWR_CLK_DISABLE(); - } - } - /*-------------------------------- PLL Configuration -----------------------*/ - /* Check the parameters */ - assert_param(IS_RCC_PLL(RCC_OscInitStruct->PLL.PLLState)); - if ((RCC_OscInitStruct->PLL.PLLState) != RCC_PLL_NONE) - { - /* Check if the PLL is used as system clock or not */ - if(__HAL_RCC_GET_SYSCLK_SOURCE() != RCC_CFGR_SWS_PLL) - { - if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_ON) - { - /* Check the parameters */ - assert_param(IS_RCC_PLLSOURCE(RCC_OscInitStruct->PLL.PLLSource)); - assert_param(IS_RCC_PLLM_VALUE(RCC_OscInitStruct->PLL.PLLM)); - assert_param(IS_RCC_PLLN_VALUE(RCC_OscInitStruct->PLL.PLLN)); - assert_param(IS_RCC_PLLP_VALUE(RCC_OscInitStruct->PLL.PLLP)); - assert_param(IS_RCC_PLLQ_VALUE(RCC_OscInitStruct->PLL.PLLQ)); - assert_param(IS_RCC_PLLR_VALUE(RCC_OscInitStruct->PLL.PLLR)); - - /* Disable the main PLL. */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - /* Configure the main PLL clock source, multiplication and division factors. */ - WRITE_REG(RCC->PLLCFGR, (RCC_OscInitStruct->PLL.PLLSource | \ - RCC_OscInitStruct->PLL.PLLM | \ - (RCC_OscInitStruct->PLL.PLLN << RCC_PLLCFGR_PLLN_Pos) | \ - (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U) << RCC_PLLCFGR_PLLP_Pos) | \ - (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos) | \ - (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))); - /* Enable the main PLL. */ - __HAL_RCC_PLL_ENABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) == RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - else - { - /* Disable the main PLL. */ - __HAL_RCC_PLL_DISABLE(); - - /* Get Start Tick*/ - tickstart = HAL_GetTick(); - - /* Wait till PLL is ready */ - while(__HAL_RCC_GET_FLAG(RCC_FLAG_PLLRDY) != RESET) - { - if((HAL_GetTick() - tickstart ) > PLL_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - } - else - { - /* Check if there is a request to disable the PLL used as System clock source */ - if((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) - { - return HAL_ERROR; - } - else - { - /* Do not return HAL_ERROR if request repeats the current configuration */ - pll_config = RCC->PLLCFGR; -#if defined (RCC_PLLCFGR_PLLR) - if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos)) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLR) != (RCC_OscInitStruct->PLL.PLLR << RCC_PLLCFGR_PLLR_Pos))) -#else - if (((RCC_OscInitStruct->PLL.PLLState) == RCC_PLL_OFF) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLSRC) != RCC_OscInitStruct->PLL.PLLSource) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLM) != (RCC_OscInitStruct->PLL.PLLM) << RCC_PLLCFGR_PLLM_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLN) != (RCC_OscInitStruct->PLL.PLLN) << RCC_PLLCFGR_PLLN_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLP) != (((RCC_OscInitStruct->PLL.PLLP >> 1U) - 1U)) << RCC_PLLCFGR_PLLP_Pos) || - (READ_BIT(pll_config, RCC_PLLCFGR_PLLQ) != (RCC_OscInitStruct->PLL.PLLQ << RCC_PLLCFGR_PLLQ_Pos))) -#endif - { - return HAL_ERROR; - } - } - } - } - return HAL_OK; -} - -/** - * @brief Configures the RCC_OscInitStruct according to the internal - * RCC configuration registers. - * @param RCC_OscInitStruct pointer to an RCC_OscInitTypeDef structure that will be configured. - * - * @note This function is only available in case of STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx/STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx devices. - * @note This function add the PLL/PLLR factor management - * @retval None - */ -void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct) -{ - /* Set all possible values for the Oscillator type parameter ---------------*/ - RCC_OscInitStruct->OscillatorType = RCC_OSCILLATORTYPE_HSE | RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_LSI; - - /* Get the HSE configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_HSEBYP) == RCC_CR_HSEBYP) - { - RCC_OscInitStruct->HSEState = RCC_HSE_BYPASS; - } - else if((RCC->CR &RCC_CR_HSEON) == RCC_CR_HSEON) - { - RCC_OscInitStruct->HSEState = RCC_HSE_ON; - } - else - { - RCC_OscInitStruct->HSEState = RCC_HSE_OFF; - } - - /* Get the HSI configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_HSION) == RCC_CR_HSION) - { - RCC_OscInitStruct->HSIState = RCC_HSI_ON; - } - else - { - RCC_OscInitStruct->HSIState = RCC_HSI_OFF; - } - - RCC_OscInitStruct->HSICalibrationValue = (uint32_t)((RCC->CR &RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); - - /* Get the LSE configuration -----------------------------------------------*/ - if((RCC->BDCR &RCC_BDCR_LSEBYP) == RCC_BDCR_LSEBYP) - { - RCC_OscInitStruct->LSEState = RCC_LSE_BYPASS; - } - else if((RCC->BDCR &RCC_BDCR_LSEON) == RCC_BDCR_LSEON) - { - RCC_OscInitStruct->LSEState = RCC_LSE_ON; - } - else - { - RCC_OscInitStruct->LSEState = RCC_LSE_OFF; - } - - /* Get the LSI configuration -----------------------------------------------*/ - if((RCC->CSR &RCC_CSR_LSION) == RCC_CSR_LSION) - { - RCC_OscInitStruct->LSIState = RCC_LSI_ON; - } - else - { - RCC_OscInitStruct->LSIState = RCC_LSI_OFF; - } - - /* Get the PLL configuration -----------------------------------------------*/ - if((RCC->CR &RCC_CR_PLLON) == RCC_CR_PLLON) - { - RCC_OscInitStruct->PLL.PLLState = RCC_PLL_ON; - } - else - { - RCC_OscInitStruct->PLL.PLLState = RCC_PLL_OFF; - } - RCC_OscInitStruct->PLL.PLLSource = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); - RCC_OscInitStruct->PLL.PLLM = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM); - RCC_OscInitStruct->PLL.PLLN = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); - RCC_OscInitStruct->PLL.PLLP = (uint32_t)((((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) + RCC_PLLCFGR_PLLP_0) << 1U) >> RCC_PLLCFGR_PLLP_Pos); - RCC_OscInitStruct->PLL.PLLQ = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLQ) >> RCC_PLLCFGR_PLLQ_Pos); - RCC_OscInitStruct->PLL.PLLR = (uint32_t)((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos); -} -#endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#endif /* HAL_RCC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rng.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rng.c deleted file mode 100644 index a9b233837d325dd..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rng.c +++ /dev/null @@ -1,868 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rng.c - * @author MCD Application Team - * @brief RNG HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Random Number Generator (RNG) peripheral: - * + Initialization and configuration functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The RNG HAL driver can be used as follows: - - (#) Enable the RNG controller clock using __HAL_RCC_RNG_CLK_ENABLE() macro - in HAL_RNG_MspInit(). - (#) Activate the RNG peripheral using HAL_RNG_Init() function. - (#) Wait until the 32 bit Random Number Generator contains a valid - random data using (polling/interrupt) mode. - (#) Get the 32 bit random number using HAL_RNG_GenerateRandomNumber() function. - - ##### Callback registration ##### - ================================== - - [..] - The compilation define USE_HAL_RNG_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - [..] - Use Function HAL_RNG_RegisterCallback() to register a user callback. - Function HAL_RNG_RegisterCallback() allows to register following callbacks: - (+) ErrorCallback : RNG Error Callback. - (+) MspInitCallback : RNG MspInit. - (+) MspDeInitCallback : RNG MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_RNG_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - HAL_RNG_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) ErrorCallback : RNG Error Callback. - (+) MspInitCallback : RNG MspInit. - (+) MspDeInitCallback : RNG MspDeInit. - - [..] - For specific callback ReadyDataCallback, use dedicated register callbacks: - respectively HAL_RNG_RegisterReadyDataCallback() , HAL_RNG_UnRegisterReadyDataCallback(). - - [..] - By default, after the HAL_RNG_Init() and when the state is HAL_RNG_STATE_RESET - all callbacks are set to the corresponding weak (surcharged) functions: - example HAL_RNG_ErrorCallback(). - Exception done for MspInit and MspDeInit functions that are respectively - reset to the legacy weak (surcharged) functions in the HAL_RNG_Init() - and HAL_RNG_DeInit() only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_RNG_Init() and HAL_RNG_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in HAL_RNG_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_RNG_STATE_READY or HAL_RNG_STATE_RESET state, thus registered (user) - MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_RNG_RegisterCallback() before calling HAL_RNG_DeInit() - or HAL_RNG_Init() function. - - [..] - When The compilation define USE_HAL_RNG_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (RNG) - -/** @addtogroup RNG - * @brief RNG HAL module driver. - * @{ - */ - -#ifdef HAL_RNG_MODULE_ENABLED - -/* Private types -------------------------------------------------------------*/ -/* Private defines -----------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RNG_Private_Constants RNG Private Constants - * @{ - */ -#define RNG_TIMEOUT_VALUE 2U -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/* Private functions prototypes ----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup RNG_Exported_Functions - * @{ - */ - -/** @addtogroup RNG_Exported_Functions_Group1 - * @brief Initialization and configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and configuration functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Initialize the RNG according to the specified parameters - in the RNG_InitTypeDef and create the associated handle - (+) DeInitialize the RNG peripheral - (+) Initialize the RNG MSP - (+) DeInitialize RNG MSP - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the RNG peripheral and creates the associated handle. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RNG_Init(RNG_HandleTypeDef *hrng) -{ - /* Check the RNG handle allocation */ - if (hrng == NULL) - { - return HAL_ERROR; - } - /* Check the parameters */ - assert_param(IS_RNG_ALL_INSTANCE(hrng->Instance)); - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) - if (hrng->State == HAL_RNG_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hrng->Lock = HAL_UNLOCKED; - - hrng->ReadyDataCallback = HAL_RNG_ReadyDataCallback; /* Legacy weak ReadyDataCallback */ - hrng->ErrorCallback = HAL_RNG_ErrorCallback; /* Legacy weak ErrorCallback */ - - if (hrng->MspInitCallback == NULL) - { - hrng->MspInitCallback = HAL_RNG_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware */ - hrng->MspInitCallback(hrng); - } -#else - if (hrng->State == HAL_RNG_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hrng->Lock = HAL_UNLOCKED; - - /* Init the low level hardware */ - HAL_RNG_MspInit(hrng); - } -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - - /* Change RNG peripheral state */ - hrng->State = HAL_RNG_STATE_BUSY; - - - /* Enable the RNG Peripheral */ - __HAL_RNG_ENABLE(hrng); - - /* Initialize the RNG state */ - hrng->State = HAL_RNG_STATE_READY; - - /* Initialise the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_NONE; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief DeInitializes the RNG peripheral. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RNG_DeInit(RNG_HandleTypeDef *hrng) -{ - /* Check the RNG handle allocation */ - if (hrng == NULL) - { - return HAL_ERROR; - } - - /* Disable the RNG Peripheral */ - CLEAR_BIT(hrng->Instance->CR, RNG_CR_IE | RNG_CR_RNGEN); - - /* Clear RNG interrupt status flags */ - CLEAR_BIT(hrng->Instance->SR, RNG_SR_CEIS | RNG_SR_SEIS); - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) - if (hrng->MspDeInitCallback == NULL) - { - hrng->MspDeInitCallback = HAL_RNG_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware */ - hrng->MspDeInitCallback(hrng); -#else - /* DeInit the low level hardware */ - HAL_RNG_MspDeInit(hrng); -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - - /* Update the RNG state */ - hrng->State = HAL_RNG_STATE_RESET; - - /* Initialise the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_NONE; - - /* Release Lock */ - __HAL_UNLOCK(hrng); - - /* Return the function status */ - return HAL_OK; -} - -/** - * @brief Initializes the RNG MSP. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval None - */ -__weak void HAL_RNG_MspInit(RNG_HandleTypeDef *hrng) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrng); - /* NOTE : This function should not be modified. When the callback is needed, - function HAL_RNG_MspInit must be implemented in the user file. - */ -} - -/** - * @brief DeInitializes the RNG MSP. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval None - */ -__weak void HAL_RNG_MspDeInit(RNG_HandleTypeDef *hrng) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrng); - /* NOTE : This function should not be modified. When the callback is needed, - function HAL_RNG_MspDeInit must be implemented in the user file. - */ -} - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User RNG Callback - * To be used instead of the weak predefined callback - * @param hrng RNG handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_RNG_ERROR_CB_ID Error callback ID - * @arg @ref HAL_RNG_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_RNG_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RNG_RegisterCallback(RNG_HandleTypeDef *hrng, HAL_RNG_CallbackIDTypeDef CallbackID, - pRNG_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hrng); - - if (HAL_RNG_STATE_READY == hrng->State) - { - switch (CallbackID) - { - case HAL_RNG_ERROR_CB_ID : - hrng->ErrorCallback = pCallback; - break; - - case HAL_RNG_MSPINIT_CB_ID : - hrng->MspInitCallback = pCallback; - break; - - case HAL_RNG_MSPDEINIT_CB_ID : - hrng->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_RNG_STATE_RESET == hrng->State) - { - switch (CallbackID) - { - case HAL_RNG_MSPINIT_CB_ID : - hrng->MspInitCallback = pCallback; - break; - - case HAL_RNG_MSPDEINIT_CB_ID : - hrng->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hrng); - return status; -} - -/** - * @brief Unregister an RNG Callback - * RNG callabck is redirected to the weak predefined callback - * @param hrng RNG handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_RNG_ERROR_CB_ID Error callback ID - * @arg @ref HAL_RNG_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_RNG_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RNG_UnRegisterCallback(RNG_HandleTypeDef *hrng, HAL_RNG_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hrng); - - if (HAL_RNG_STATE_READY == hrng->State) - { - switch (CallbackID) - { - case HAL_RNG_ERROR_CB_ID : - hrng->ErrorCallback = HAL_RNG_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_RNG_MSPINIT_CB_ID : - hrng->MspInitCallback = HAL_RNG_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_RNG_MSPDEINIT_CB_ID : - hrng->MspDeInitCallback = HAL_RNG_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_RNG_STATE_RESET == hrng->State) - { - switch (CallbackID) - { - case HAL_RNG_MSPINIT_CB_ID : - hrng->MspInitCallback = HAL_RNG_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_RNG_MSPDEINIT_CB_ID : - hrng->MspDeInitCallback = HAL_RNG_MspDeInit; /* Legacy weak MspInit */ - break; - - default : - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hrng); - return status; -} - -/** - * @brief Register Data Ready RNG Callback - * To be used instead of the weak HAL_RNG_ReadyDataCallback() predefined callback - * @param hrng RNG handle - * @param pCallback pointer to the Data Ready Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RNG_RegisterReadyDataCallback(RNG_HandleTypeDef *hrng, pRNG_ReadyDataCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hrng); - - if (HAL_RNG_STATE_READY == hrng->State) - { - hrng->ReadyDataCallback = pCallback; - } - else - { - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hrng); - return status; -} - -/** - * @brief UnRegister the Data Ready RNG Callback - * Data Ready RNG Callback is redirected to the weak HAL_RNG_ReadyDataCallback() predefined callback - * @param hrng RNG handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RNG_UnRegisterReadyDataCallback(RNG_HandleTypeDef *hrng) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hrng); - - if (HAL_RNG_STATE_READY == hrng->State) - { - hrng->ReadyDataCallback = HAL_RNG_ReadyDataCallback; /* Legacy weak ReadyDataCallback */ - } - else - { - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hrng); - return status; -} - -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup RNG_Exported_Functions_Group2 - * @brief Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) Get the 32 bit Random number - (+) Get the 32 bit Random number with interrupt enabled - (+) Handle RNG interrupt request - -@endverbatim - * @{ - */ - -/** - * @brief Generates a 32-bit random number. - * @note Each time the random number data is read the RNG_FLAG_DRDY flag - * is automatically cleared. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @param random32bit pointer to generated random number variable if successful. - * @retval HAL status - */ - -HAL_StatusTypeDef HAL_RNG_GenerateRandomNumber(RNG_HandleTypeDef *hrng, uint32_t *random32bit) -{ - uint32_t tickstart; - HAL_StatusTypeDef status = HAL_OK; - - /* Process Locked */ - __HAL_LOCK(hrng); - - /* Check RNG peripheral state */ - if (hrng->State == HAL_RNG_STATE_READY) - { - /* Change RNG peripheral state */ - hrng->State = HAL_RNG_STATE_BUSY; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Check if data register contains valid random data */ - while (__HAL_RNG_GET_FLAG(hrng, RNG_FLAG_DRDY) == RESET) - { - if ((HAL_GetTick() - tickstart) > RNG_TIMEOUT_VALUE) - { - /* New check to avoid false timeout detection in case of preemption */ - if (__HAL_RNG_GET_FLAG(hrng, RNG_FLAG_DRDY) == RESET) - { - hrng->State = HAL_RNG_STATE_READY; - hrng->ErrorCode = HAL_RNG_ERROR_TIMEOUT; - /* Process Unlocked */ - __HAL_UNLOCK(hrng); - return HAL_ERROR; - } - } - } - - /* Get a 32bit Random number */ - hrng->RandomNumber = hrng->Instance->DR; - *random32bit = hrng->RandomNumber; - - hrng->State = HAL_RNG_STATE_READY; - } - else - { - hrng->ErrorCode = HAL_RNG_ERROR_BUSY; - status = HAL_ERROR; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hrng); - - return status; -} - -/** - * @brief Generates a 32-bit random number in interrupt mode. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RNG_GenerateRandomNumber_IT(RNG_HandleTypeDef *hrng) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process Locked */ - __HAL_LOCK(hrng); - - /* Check RNG peripheral state */ - if (hrng->State == HAL_RNG_STATE_READY) - { - /* Change RNG peripheral state */ - hrng->State = HAL_RNG_STATE_BUSY; - - /* Enable the RNG Interrupts: Data Ready, Clock error, Seed error */ - __HAL_RNG_ENABLE_IT(hrng); - } - else - { - /* Process Unlocked */ - __HAL_UNLOCK(hrng); - - hrng->ErrorCode = HAL_RNG_ERROR_BUSY; - status = HAL_ERROR; - } - - return status; -} - -/** - * @brief Returns generated random number in polling mode (Obsolete) - * Use HAL_RNG_GenerateRandomNumber() API instead. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval Random value - */ -uint32_t HAL_RNG_GetRandomNumber(RNG_HandleTypeDef *hrng) -{ - if (HAL_RNG_GenerateRandomNumber(hrng, &(hrng->RandomNumber)) == HAL_OK) - { - return hrng->RandomNumber; - } - else - { - return 0U; - } -} - -/** - * @brief Returns a 32-bit random number with interrupt enabled (Obsolete), - * Use HAL_RNG_GenerateRandomNumber_IT() API instead. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval 32-bit random number - */ -uint32_t HAL_RNG_GetRandomNumber_IT(RNG_HandleTypeDef *hrng) -{ - uint32_t random32bit = 0U; - - /* Process locked */ - __HAL_LOCK(hrng); - - /* Change RNG peripheral state */ - hrng->State = HAL_RNG_STATE_BUSY; - - /* Get a 32bit Random number */ - random32bit = hrng->Instance->DR; - - /* Enable the RNG Interrupts: Data Ready, Clock error, Seed error */ - __HAL_RNG_ENABLE_IT(hrng); - - /* Return the 32 bit random number */ - return random32bit; -} - -/** - * @brief Handles RNG interrupt request. - * @note In the case of a clock error, the RNG is no more able to generate - * random numbers because the PLL48CLK clock is not correct. User has - * to check that the clock controller is correctly configured to provide - * the RNG clock and clear the CEIS bit using __HAL_RNG_CLEAR_IT(). - * The clock error has no impact on the previously generated - * random numbers, and the RNG_DR register contents can be used. - * @note In the case of a seed error, the generation of random numbers is - * interrupted as long as the SECS bit is '1'. If a number is - * available in the RNG_DR register, it must not be used because it may - * not have enough entropy. In this case, it is recommended to clear the - * SEIS bit using __HAL_RNG_CLEAR_IT(), then disable and enable - * the RNG peripheral to reinitialize and restart the RNG. - * @note User-written HAL_RNG_ErrorCallback() API is called once whether SEIS - * or CEIS are set. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval None - - */ -void HAL_RNG_IRQHandler(RNG_HandleTypeDef *hrng) -{ - uint32_t rngclockerror = 0U; - - /* RNG clock error interrupt occurred */ - if (__HAL_RNG_GET_IT(hrng, RNG_IT_CEI) != RESET) - { - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_CLOCK; - rngclockerror = 1U; - } - else if (__HAL_RNG_GET_IT(hrng, RNG_IT_SEI) != RESET) - { - /* Update the error code */ - hrng->ErrorCode = HAL_RNG_ERROR_SEED; - rngclockerror = 1U; - } - else - { - /* Nothing to do */ - } - - if (rngclockerror == 1U) - { - /* Change RNG peripheral state */ - hrng->State = HAL_RNG_STATE_ERROR; - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) - /* Call registered Error callback */ - hrng->ErrorCallback(hrng); -#else - /* Call legacy weak Error callback */ - HAL_RNG_ErrorCallback(hrng); -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - - /* Clear the clock error flag */ - __HAL_RNG_CLEAR_IT(hrng, RNG_IT_CEI | RNG_IT_SEI); - - return; - } - - /* Check RNG data ready interrupt occurred */ - if (__HAL_RNG_GET_IT(hrng, RNG_IT_DRDY) != RESET) - { - /* Generate random number once, so disable the IT */ - __HAL_RNG_DISABLE_IT(hrng); - - /* Get the 32bit Random number (DRDY flag automatically cleared) */ - hrng->RandomNumber = hrng->Instance->DR; - - if (hrng->State != HAL_RNG_STATE_ERROR) - { - /* Change RNG peripheral state */ - hrng->State = HAL_RNG_STATE_READY; - /* Process Unlocked */ - __HAL_UNLOCK(hrng); - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) - /* Call registered Data Ready callback */ - hrng->ReadyDataCallback(hrng, hrng->RandomNumber); -#else - /* Call legacy weak Data Ready callback */ - HAL_RNG_ReadyDataCallback(hrng, hrng->RandomNumber); -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief Read latest generated random number. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval random value - */ -uint32_t HAL_RNG_ReadLastRandomNumber(RNG_HandleTypeDef *hrng) -{ - return (hrng->RandomNumber); -} - -/** - * @brief Data Ready callback in non-blocking mode. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @param random32bit generated random number. - * @retval None - */ -__weak void HAL_RNG_ReadyDataCallback(RNG_HandleTypeDef *hrng, uint32_t random32bit) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrng); - UNUSED(random32bit); - /* NOTE : This function should not be modified. When the callback is needed, - function HAL_RNG_ReadyDataCallback must be implemented in the user file. - */ -} - -/** - * @brief RNG error callbacks. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval None - */ -__weak void HAL_RNG_ErrorCallback(RNG_HandleTypeDef *hrng) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrng); - /* NOTE : This function should not be modified. When the callback is needed, - function HAL_RNG_ErrorCallback must be implemented in the user file. - */ -} -/** - * @} - */ - - -/** @addtogroup RNG_Exported_Functions_Group3 - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Returns the RNG state. - * @param hrng pointer to a RNG_HandleTypeDef structure that contains - * the configuration information for RNG. - * @retval HAL state - */ -HAL_RNG_StateTypeDef HAL_RNG_GetState(RNG_HandleTypeDef *hrng) -{ - return hrng->State; -} - -/** - * @brief Return the RNG handle error code. - * @param hrng: pointer to a RNG_HandleTypeDef structure. - * @retval RNG Error Code - */ -uint32_t HAL_RNG_GetError(RNG_HandleTypeDef *hrng) -{ - /* Return RNG Error Code */ - return hrng->ErrorCode; -} -/** - * @} - */ - -/** - * @} - */ - - -#endif /* HAL_RNG_MODULE_ENABLED */ -/** - * @} - */ - -#endif /* RNG */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c deleted file mode 100644 index 00f9e4b03e1817f..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc.c +++ /dev/null @@ -1,1903 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rtc.c - * @author MCD Application Team - * @brief RTC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Real Time Clock (RTC) peripheral: - * + Initialization and de-initialization functions - * + RTC Time and Date functions - * + RTC Alarm functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### Backup Domain Operating Condition ##### - ============================================================================== - [..] The real-time clock (RTC), the RTC backup registers, and the backup - SRAM (BKP SRAM) can be powered from the VBAT voltage when the main - VDD supply is powered off. - To retain the content of the RTC backup registers, backup SRAM, and supply - the RTC when VDD is turned off, VBAT pin can be connected to an optional - standby voltage supplied by a battery or by another source. - - [..] To allow the RTC operating even when the main digital supply (VDD) is turned - off, the VBAT pin powers the following blocks: - (#) The RTC - (#) The LSE oscillator - (#) The backup SRAM when the low power backup regulator is enabled - (#) PC13 to PC15 I/Os, plus PI8 I/O (when available) - - [..] When the backup domain is supplied by VDD (analog switch connected to VDD), - the following pins are available: - (#) PC14 and PC15 can be used as either GPIO or LSE pins - (#) PC13 can be used as a GPIO or as the RTC_AF1 pin - (#) PI8 can be used as a GPIO or as the RTC_AF2 pin - - [..] When the backup domain is supplied by VBAT (analog switch connected to VBAT - because VDD is not present), the following pins are available: - (#) PC14 and PC15 can be used as LSE pins only - (#) PC13 can be used as the RTC_AF1 pin - (#) PI8 can be used as the RTC_AF2 pin - - ##### Backup Domain Reset ##### - ================================================================== - [..] The backup domain reset sets all RTC registers and the RCC_BDCR register - to their reset values. The BKPSRAM is not affected by this reset. The only - way to reset the BKPSRAM is through the Flash interface by requesting - a protection level change from 1 to 0. - [..] A backup domain reset is generated when one of the following events occurs: - (#) Software reset, triggered by setting the BDRST bit in the - RCC Backup domain control register (RCC_BDCR). - (#) VDD or VBAT power on, if both supplies have previously been powered off. - - ##### Backup Domain Access ##### - ================================================================== - [..] After reset, the backup domain (RTC registers, RTC backup data - registers and backup SRAM) is protected against possible unwanted write - accesses. - [..] To enable access to the RTC Domain and RTC registers, proceed as follows: - (+) Enable the Power Controller (PWR) APB1 interface clock using the - __HAL_RCC_PWR_CLK_ENABLE() function. - (+) Enable access to RTC domain using the HAL_PWR_EnableBkUpAccess() function. - (+) Select the RTC clock source using the __HAL_RCC_RTC_CONFIG() function. - (+) Enable RTC Clock using the __HAL_RCC_RTC_ENABLE() function. - - - ##### How to use this driver ##### - ================================================================== - [..] - (+) Enable the RTC domain access (see description in the section above). - (+) Configure the RTC Prescaler (Asynchronous and Synchronous) and RTC hour - format using the HAL_RTC_Init() function. - - *** Time and Date configuration *** - =================================== - [..] - (+) To configure the RTC Calendar (Time and Date) use the HAL_RTC_SetTime() - and HAL_RTC_SetDate() functions. - (+) To read the RTC Calendar, use the HAL_RTC_GetTime() and HAL_RTC_GetDate() functions. - - *** Alarm configuration *** - =========================== - [..] - (+) To configure the RTC Alarm use the HAL_RTC_SetAlarm() function. - You can also configure the RTC Alarm with interrupt mode using the HAL_RTC_SetAlarm_IT() function. - (+) To read the RTC Alarm, use the HAL_RTC_GetAlarm() function. - - ##### RTC and low power modes ##### - ================================================================== - [..] The MCU can be woken up from a low power mode by an RTC alternate - function. - [..] The RTC alternate functions are the RTC alarms (Alarm A and Alarm B), - RTC wake-up, RTC tamper event detection and RTC time stamp event detection. - These RTC alternate functions can wake up the system from the Stop and - Standby low power modes. - [..] The system can also wake up from low power modes without depending - on an external interrupt (Auto-wake-up mode), by using the RTC alarm - or the RTC wake-up events. - [..] The RTC provides a programmable time base for waking up from the - Stop or Standby mode at regular intervals. - Wake-up from STOP and STANDBY modes is possible only when the RTC clock source - is LSE or LSI. - - *** Callback registration *** - ============================================= - - [..] - The compilation define USE_HAL_RTC_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Function HAL_RTC_RegisterCallback() to register an interrupt callback. - - [..] - Function HAL_RTC_RegisterCallback() allows to register following callbacks: - (+) AlarmAEventCallback : RTC Alarm A Event callback. - (+) AlarmBEventCallback : RTC Alarm B Event callback. - (+) TimeStampEventCallback : RTC TimeStamp Event callback. - (+) WakeUpTimerEventCallback : RTC WakeUpTimer Event callback. - (+) Tamper1EventCallback : RTC Tamper 1 Event callback. - (+) Tamper2EventCallback : RTC Tamper 2 Event callback. - (+) MspInitCallback : RTC MspInit callback. - (+) MspDeInitCallback : RTC MspDeInit callback. - [..] - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_RTC_UnRegisterCallback() to reset a callback to the default - weak function. - HAL_RTC_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) AlarmAEventCallback : RTC Alarm A Event callback. - (+) AlarmBEventCallback : RTC Alarm B Event callback. - (+) TimeStampEventCallback : RTC TimeStamp Event callback. - (+) WakeUpTimerEventCallback : RTC WakeUpTimer Event callback. - (+) Tamper1EventCallback : RTC Tamper 1 Event callback. - (+) Tamper2EventCallback : RTC Tamper 2 Event callback. - (+) MspInitCallback : RTC MspInit callback. - (+) MspDeInitCallback : RTC MspDeInit callback. - - [..] - By default, after the HAL_RTC_Init() and when the state is HAL_RTC_STATE_RESET, - all callbacks are set to the corresponding weak functions : - examples AlarmAEventCallback(), WakeUpTimerEventCallback(). - Exception done for MspInit and MspDeInit callbacks that are reset to the legacy weak function - in the HAL_RTC_Init()/HAL_RTC_DeInit() only when these callbacks are null - (not registered beforehand). - If not, MspInit or MspDeInit are not null, HAL_RTC_Init()/HAL_RTC_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - [..] - Callbacks can be registered/unregistered in HAL_RTC_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_RTC_STATE_READY or HAL_RTC_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_RTC_RegisterCallback() before calling HAL_RTC_DeInit() - or HAL_RTC_Init() function. - - [..] - When The compilation define USE_HAL_RTC_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - @endverbatim - - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup RTC RTC - * @brief RTC HAL module driver - * @{ - */ - -#ifdef HAL_RTC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup RTC_Exported_Functions RTC Exported Functions - * @{ - */ - -/** @defgroup RTC_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to initialize and configure the - RTC Prescaler (Synchronous and Asynchronous), RTC Hour format, disable - RTC registers Write protection, enter and exit the RTC initialization mode, - RTC registers synchronization check and reference clock detection enable. - (#) The RTC Prescaler is programmed to generate the RTC 1Hz time base. - It is split into 2 programmable prescalers to minimize power consumption. - (++) A 7-bit asynchronous prescaler and a 13-bit synchronous prescaler. - (++) When both prescalers are used, it is recommended to configure the - asynchronous prescaler to a high value to minimize power consumption. - (#) All RTC registers are Write protected. Writing to the RTC registers - is enabled by writing a key into the Write Protection register, RTC_WPR. - (#) To configure the RTC Calendar, user application should enter - initialization mode. In this mode, the calendar counter is stopped - and its value can be updated. When the initialization sequence is - complete, the calendar restarts counting after 4 RTCCLK cycles. - (#) To read the calendar through the shadow registers after Calendar - initialization, calendar update or after wake-up from low power modes - the software must first clear the RSF flag. The software must then - wait until it is set again before reading the calendar, which means - that the calendar registers have been correctly copied into the - RTC_TR and RTC_DR shadow registers.The HAL_RTC_WaitForSynchro() function - implements the above software sequence (RSF clear and RSF check). - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the RTC peripheral - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_Init(RTC_HandleTypeDef *hrtc) -{ - /* Check the RTC peripheral state */ - if(hrtc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_RTC_HOUR_FORMAT(hrtc->Init.HourFormat)); - assert_param(IS_RTC_ASYNCH_PREDIV(hrtc->Init.AsynchPrediv)); - assert_param(IS_RTC_SYNCH_PREDIV(hrtc->Init.SynchPrediv)); - assert_param (IS_RTC_OUTPUT(hrtc->Init.OutPut)); - assert_param (IS_RTC_OUTPUT_POL(hrtc->Init.OutPutPolarity)); - assert_param(IS_RTC_OUTPUT_TYPE(hrtc->Init.OutPutType)); - -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - if(hrtc->State == HAL_RTC_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hrtc->Lock = HAL_UNLOCKED; - - hrtc->AlarmAEventCallback = HAL_RTC_AlarmAEventCallback; /* Legacy weak AlarmAEventCallback */ - hrtc->AlarmBEventCallback = HAL_RTCEx_AlarmBEventCallback; /* Legacy weak AlarmBEventCallback */ - hrtc->TimeStampEventCallback = HAL_RTCEx_TimeStampEventCallback; /* Legacy weak TimeStampEventCallback */ - hrtc->WakeUpTimerEventCallback = HAL_RTCEx_WakeUpTimerEventCallback; /* Legacy weak WakeUpTimerEventCallback */ - hrtc->Tamper1EventCallback = HAL_RTCEx_Tamper1EventCallback; /* Legacy weak Tamper1EventCallback */ - hrtc->Tamper2EventCallback = HAL_RTCEx_Tamper2EventCallback; /* Legacy weak Tamper2EventCallback */ - - if(hrtc->MspInitCallback == NULL) - { - hrtc->MspInitCallback = HAL_RTC_MspInit; - } - /* Init the low level hardware */ - hrtc->MspInitCallback(hrtc); - - if(hrtc->MspDeInitCallback == NULL) - { - hrtc->MspDeInitCallback = HAL_RTC_MspDeInit; - } - } -#else - if(hrtc->State == HAL_RTC_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hrtc->Lock = HAL_UNLOCKED; - - /* Initialize RTC MSP */ - HAL_RTC_MspInit(hrtc); - } -#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ - - /* Set RTC state */ - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set Initialization mode */ - if(RTC_EnterInitMode(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state */ - hrtc->State = HAL_RTC_STATE_ERROR; - - return HAL_ERROR; - } - else - { - /* Clear RTC_CR FMT, OSEL and POL Bits */ - hrtc->Instance->CR &= ((uint32_t)~(RTC_CR_FMT | RTC_CR_OSEL | RTC_CR_POL)); - /* Set RTC_CR register */ - hrtc->Instance->CR |= (uint32_t)(hrtc->Init.HourFormat | hrtc->Init.OutPut | hrtc->Init.OutPutPolarity); - - /* Configure the RTC PRER */ - hrtc->Instance->PRER = (uint32_t)(hrtc->Init.SynchPrediv); - hrtc->Instance->PRER |= (uint32_t)(hrtc->Init.AsynchPrediv << 16U); - - /* Exit Initialization mode */ - hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - - /* If CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ - if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) - { - if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_ERROR; - - return HAL_ERROR; - } - } - - hrtc->Instance->TAFCR &= (uint32_t)~RTC_TAFCR_ALARMOUTTYPE; - hrtc->Instance->TAFCR |= (uint32_t)(hrtc->Init.OutPutType); - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - return HAL_OK; - } -} - -/** - * @brief DeInitializes the RTC peripheral - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @note This function doesn't reset the RTC Backup Data registers. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_DeInit(RTC_HandleTypeDef *hrtc) -{ - uint32_t tickstart = 0U; - - /* Set RTC state */ - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set Initialization mode */ - if(RTC_EnterInitMode(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state */ - hrtc->State = HAL_RTC_STATE_ERROR; - - return HAL_ERROR; - } - else - { - /* Reset TR, DR and CR registers */ - hrtc->Instance->TR = 0x00000000U; - hrtc->Instance->DR = 0x00002101U; - /* Reset All CR bits except CR[2:0] */ - hrtc->Instance->CR &= 0x00000007U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till WUTWF flag is set and if Time out is reached exit */ - while(((hrtc->Instance->ISR) & RTC_ISR_WUTWF) == (uint32_t)RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state */ - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - return HAL_TIMEOUT; - } - } - - /* Reset all RTC CR register bits */ - hrtc->Instance->CR &= 0x00000000U; - hrtc->Instance->WUTR = 0x0000FFFFU; - hrtc->Instance->PRER = 0x007F00FFU; - hrtc->Instance->CALIBR = 0x00000000U; - hrtc->Instance->ALRMAR = 0x00000000U; - hrtc->Instance->ALRMBR = 0x00000000U; - hrtc->Instance->SHIFTR = 0x00000000U; - hrtc->Instance->CALR = 0x00000000U; - hrtc->Instance->ALRMASSR = 0x00000000U; - hrtc->Instance->ALRMBSSR = 0x00000000U; - - /* Reset ISR register and exit initialization mode */ - hrtc->Instance->ISR = 0x00000000U; - - /* Reset Tamper and alternate functions configuration register */ - hrtc->Instance->TAFCR = 0x00000000U; - - /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ - if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) - { - if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_ERROR; - - return HAL_ERROR; - } - } - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - if(hrtc->MspDeInitCallback == NULL) - { - hrtc->MspDeInitCallback = HAL_RTC_MspDeInit; - } - - /* DeInit the low level hardware: CLOCK, NVIC.*/ - hrtc->MspDeInitCallback(hrtc); - -#else - /* De-Initialize RTC MSP */ - HAL_RTC_MspDeInit(hrtc); -#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ - - hrtc->State = HAL_RTC_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User RTC Callback - * To be used instead of the weak predefined callback - * @param hrtc RTC handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_RTC_ALARM_A_EVENT_CB_ID Alarm A Event Callback ID - * @arg @ref HAL_RTC_ALARM_B_EVENT_CB_ID Alarm B Event Callback ID - * @arg @ref HAL_RTC_TIMESTAMP_EVENT_CB_ID TimeStamp Event Callback ID - * @arg @ref HAL_RTC_WAKEUPTIMER_EVENT_CB_ID Wake-Up Timer Event Callback ID - * @arg @ref HAL_RTC_TAMPER1_EVENT_CB_ID Tamper 1 Callback ID - * @arg @ref HAL_RTC_TAMPER2_EVENT_CB_ID Tamper 2 Callback ID - * @arg @ref HAL_RTC_MSPINIT_CB_ID Msp Init callback ID - * @arg @ref HAL_RTC_MSPDEINIT_CB_ID Msp DeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_RegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID, pRTC_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hrtc); - - if(HAL_RTC_STATE_READY == hrtc->State) - { - switch (CallbackID) - { - case HAL_RTC_ALARM_A_EVENT_CB_ID : - hrtc->AlarmAEventCallback = pCallback; - break; - - case HAL_RTC_ALARM_B_EVENT_CB_ID : - hrtc->AlarmBEventCallback = pCallback; - break; - - case HAL_RTC_TIMESTAMP_EVENT_CB_ID : - hrtc->TimeStampEventCallback = pCallback; - break; - - case HAL_RTC_WAKEUPTIMER_EVENT_CB_ID : - hrtc->WakeUpTimerEventCallback = pCallback; - break; - - case HAL_RTC_TAMPER1_EVENT_CB_ID : - hrtc->Tamper1EventCallback = pCallback; - break; - - case HAL_RTC_TAMPER2_EVENT_CB_ID : - hrtc->Tamper2EventCallback = pCallback; - break; - - case HAL_RTC_MSPINIT_CB_ID : - hrtc->MspInitCallback = pCallback; - break; - - case HAL_RTC_MSPDEINIT_CB_ID : - hrtc->MspDeInitCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if(HAL_RTC_STATE_RESET == hrtc->State) - { - switch (CallbackID) - { - case HAL_RTC_MSPINIT_CB_ID : - hrtc->MspInitCallback = pCallback; - break; - - case HAL_RTC_MSPDEINIT_CB_ID : - hrtc->MspDeInitCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hrtc); - - return status; -} - -/** - * @brief Unregister an RTC Callback - * RTC callabck is redirected to the weak predefined callback - * @param hrtc RTC handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_RTC_ALARM_A_EVENT_CB_ID Alarm A Event Callback ID - * @arg @ref HAL_RTC_ALARM_B_EVENT_CB_ID Alarm B Event Callback ID - * @arg @ref HAL_RTC_TIMESTAMP_EVENT_CB_ID TimeStamp Event Callback ID - * @arg @ref HAL_RTC_WAKEUPTIMER_EVENT_CB_ID Wake-Up Timer Event Callback ID - * @arg @ref HAL_RTC_TAMPER1_EVENT_CB_ID Tamper 1 Callback ID - * @arg @ref HAL_RTC_TAMPER2_EVENT_CB_ID Tamper 2 Callback ID - * @arg @ref HAL_RTC_MSPINIT_CB_ID Msp Init callback ID - * @arg @ref HAL_RTC_MSPDEINIT_CB_ID Msp DeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_UnRegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hrtc); - - if(HAL_RTC_STATE_READY == hrtc->State) - { - switch (CallbackID) - { - case HAL_RTC_ALARM_A_EVENT_CB_ID : - hrtc->AlarmAEventCallback = HAL_RTC_AlarmAEventCallback; /* Legacy weak AlarmAEventCallback */ - break; - - case HAL_RTC_ALARM_B_EVENT_CB_ID : - hrtc->AlarmBEventCallback = HAL_RTCEx_AlarmBEventCallback; /* Legacy weak AlarmBEventCallback */ - break; - - case HAL_RTC_TIMESTAMP_EVENT_CB_ID : - hrtc->TimeStampEventCallback = HAL_RTCEx_TimeStampEventCallback; /* Legacy weak TimeStampEventCallback */ - break; - - case HAL_RTC_WAKEUPTIMER_EVENT_CB_ID : - hrtc->WakeUpTimerEventCallback = HAL_RTCEx_WakeUpTimerEventCallback; /* Legacy weak WakeUpTimerEventCallback */ - break; - - case HAL_RTC_TAMPER1_EVENT_CB_ID : - hrtc->Tamper1EventCallback = HAL_RTCEx_Tamper1EventCallback; /* Legacy weak Tamper1EventCallback */ - break; - - case HAL_RTC_TAMPER2_EVENT_CB_ID : - hrtc->Tamper2EventCallback = HAL_RTCEx_Tamper2EventCallback; /* Legacy weak Tamper2EventCallback */ - break; - - case HAL_RTC_MSPINIT_CB_ID : - hrtc->MspInitCallback = HAL_RTC_MspInit; - break; - - case HAL_RTC_MSPDEINIT_CB_ID : - hrtc->MspDeInitCallback = HAL_RTC_MspDeInit; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if(HAL_RTC_STATE_RESET == hrtc->State) - { - switch (CallbackID) - { - case HAL_RTC_MSPINIT_CB_ID : - hrtc->MspInitCallback = HAL_RTC_MspInit; - break; - - case HAL_RTC_MSPDEINIT_CB_ID : - hrtc->MspDeInitCallback = HAL_RTC_MspDeInit; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hrtc); - - return status; -} -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - -/** - * @brief Initializes the RTC MSP. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -__weak void HAL_RTC_MspInit(RTC_HandleTypeDef* hrtc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrtc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RTC_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes the RTC MSP. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -__weak void HAL_RTC_MspDeInit(RTC_HandleTypeDef* hrtc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrtc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RTC_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup RTC_Exported_Functions_Group2 RTC Time and Date functions - * @brief RTC Time and Date functions - * -@verbatim - =============================================================================== - ##### RTC Time and Date functions ##### - =============================================================================== - - [..] This section provides functions allowing to configure Time and Date features - -@endverbatim - * @{ - */ - -/** - * @brief Sets RTC current time. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sTime Pointer to Time structure - * @param Format Specifies the format of the entered parameters. - * This parameter can be one of the following values: - * @arg RTC_FORMAT_BIN: Binary data format - * @arg RTC_FORMAT_BCD: BCD data format - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_SetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format) -{ - uint32_t tmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_FORMAT(Format)); - assert_param(IS_RTC_DAYLIGHT_SAVING(sTime->DayLightSaving)); - assert_param(IS_RTC_STORE_OPERATION(sTime->StoreOperation)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - if(Format == RTC_FORMAT_BIN) - { - if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) - { - assert_param(IS_RTC_HOUR12(sTime->Hours)); - assert_param(IS_RTC_HOURFORMAT12(sTime->TimeFormat)); - } - else - { - sTime->TimeFormat = 0x00U; - assert_param(IS_RTC_HOUR24(sTime->Hours)); - } - assert_param(IS_RTC_MINUTES(sTime->Minutes)); - assert_param(IS_RTC_SECONDS(sTime->Seconds)); - - tmpreg = (uint32_t)(((uint32_t)RTC_ByteToBcd2(sTime->Hours) << 16U) | \ - ((uint32_t)RTC_ByteToBcd2(sTime->Minutes) << 8U) | \ - ((uint32_t)RTC_ByteToBcd2(sTime->Seconds)) | \ - (((uint32_t)sTime->TimeFormat) << 16U)); - } - else - { - if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) - { - assert_param(IS_RTC_HOUR12(RTC_Bcd2ToByte(sTime->Hours))); - assert_param(IS_RTC_HOURFORMAT12(sTime->TimeFormat)); - } - else - { - sTime->TimeFormat = 0x00U; - assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(sTime->Hours))); - } - assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(sTime->Minutes))); - assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(sTime->Seconds))); - tmpreg = (((uint32_t)(sTime->Hours) << 16U) | \ - ((uint32_t)(sTime->Minutes) << 8U) | \ - ((uint32_t)sTime->Seconds) | \ - ((uint32_t)(sTime->TimeFormat) << 16U)); - } - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set Initialization mode */ - if(RTC_EnterInitMode(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state */ - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - else - { - /* Set the RTC_TR register */ - hrtc->Instance->TR = (uint32_t)(tmpreg & RTC_TR_RESERVED_MASK); - - /* This interface is deprecated. To manage Daylight Saving Time, please use HAL_RTC_DST_xxx functions */ - hrtc->Instance->CR &= (uint32_t)~RTC_CR_BCK; - - /* This interface is deprecated. To manage Daylight Saving Time, please use HAL_RTC_DST_xxx functions */ - hrtc->Instance->CR |= (uint32_t)(sTime->DayLightSaving | sTime->StoreOperation); - - /* Exit Initialization mode */ - hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - - /* If CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ - if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) - { - if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY; - - __HAL_UNLOCK(hrtc); - - return HAL_OK; - } -} - -/** - * @brief Gets RTC current time. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sTime Pointer to Time structure - * @param Format Specifies the format of the entered parameters. - * This parameter can be one of the following values: - * @arg RTC_FORMAT_BIN: Binary data format - * @arg RTC_FORMAT_BCD: BCD data format - * @note You can use SubSeconds and SecondFraction (sTime structure fields returned) to convert SubSeconds - * value in second fraction ratio with time unit following generic formula: - * Second fraction ratio * time_unit= [(SecondFraction-SubSeconds)/(SecondFraction+1)] * time_unit - * This conversion can be performed only if no shift operation is pending (ie. SHFP=0) when PREDIV_S >= SS - * @note You must call HAL_RTC_GetDate() after HAL_RTC_GetTime() to unlock the values - * in the higher-order calendar shadow registers to ensure consistency between the time and date values. - * Reading RTC current time locks the values in calendar shadow registers until current date is read. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_GetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format) -{ - uint32_t tmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_FORMAT(Format)); - - /* Get subseconds structure field from the corresponding register */ - sTime->SubSeconds = (uint32_t)(hrtc->Instance->SSR); - - /* Get SecondFraction structure field from the corresponding register field*/ - sTime->SecondFraction = (uint32_t)(hrtc->Instance->PRER & RTC_PRER_PREDIV_S); - - /* Get the TR register */ - tmpreg = (uint32_t)(hrtc->Instance->TR & RTC_TR_RESERVED_MASK); - - /* Fill the structure fields with the read parameters */ - sTime->Hours = (uint8_t)((tmpreg & (RTC_TR_HT | RTC_TR_HU)) >> 16U); - sTime->Minutes = (uint8_t)((tmpreg & (RTC_TR_MNT | RTC_TR_MNU)) >> 8U); - sTime->Seconds = (uint8_t)(tmpreg & (RTC_TR_ST | RTC_TR_SU)); - sTime->TimeFormat = (uint8_t)((tmpreg & (RTC_TR_PM)) >> 16U); - - /* Check the input parameters format */ - if(Format == RTC_FORMAT_BIN) - { - /* Convert the time structure parameters to Binary format */ - sTime->Hours = (uint8_t)RTC_Bcd2ToByte(sTime->Hours); - sTime->Minutes = (uint8_t)RTC_Bcd2ToByte(sTime->Minutes); - sTime->Seconds = (uint8_t)RTC_Bcd2ToByte(sTime->Seconds); - } - - return HAL_OK; -} - -/** - * @brief Sets RTC current date. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sDate Pointer to date structure - * @param Format specifies the format of the entered parameters. - * This parameter can be one of the following values: - * @arg RTC_FORMAT_BIN: Binary data format - * @arg RTC_FORMAT_BCD: BCD data format - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_SetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format) -{ - uint32_t datetmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_FORMAT(Format)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - if((Format == RTC_FORMAT_BIN) && ((sDate->Month & 0x10U) == 0x10U)) - { - sDate->Month = (uint8_t)((sDate->Month & (uint8_t)~(0x10U)) + (uint8_t)0x0AU); - } - - assert_param(IS_RTC_WEEKDAY(sDate->WeekDay)); - - if(Format == RTC_FORMAT_BIN) - { - assert_param(IS_RTC_YEAR(sDate->Year)); - assert_param(IS_RTC_MONTH(sDate->Month)); - assert_param(IS_RTC_DATE(sDate->Date)); - - datetmpreg = (((uint32_t)RTC_ByteToBcd2(sDate->Year) << 16U) | \ - ((uint32_t)RTC_ByteToBcd2(sDate->Month) << 8U) | \ - ((uint32_t)RTC_ByteToBcd2(sDate->Date)) | \ - ((uint32_t)sDate->WeekDay << 13U)); - } - else - { - assert_param(IS_RTC_YEAR(RTC_Bcd2ToByte(sDate->Year))); - assert_param(IS_RTC_MONTH(RTC_Bcd2ToByte(sDate->Month))); - assert_param(IS_RTC_DATE(RTC_Bcd2ToByte(sDate->Date))); - - datetmpreg = ((((uint32_t)sDate->Year) << 16U) | \ - (((uint32_t)sDate->Month) << 8U) | \ - ((uint32_t)sDate->Date) | \ - (((uint32_t)sDate->WeekDay) << 13U)); - } - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set Initialization mode */ - if(RTC_EnterInitMode(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state*/ - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - else - { - /* Set the RTC_DR register */ - hrtc->Instance->DR = (uint32_t)(datetmpreg & RTC_DR_RESERVED_MASK); - - /* Exit Initialization mode */ - hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - - /* If CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ - if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) - { - if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY ; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; - } -} - -/** - * @brief Gets RTC current date. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sDate Pointer to Date structure - * @param Format Specifies the format of the entered parameters. - * This parameter can be one of the following values: - * @arg RTC_FORMAT_BIN: Binary data format - * @arg RTC_FORMAT_BCD: BCD data format - * @note You must call HAL_RTC_GetDate() after HAL_RTC_GetTime() to unlock the values - * in the higher-order calendar shadow registers to ensure consistency between the time and date values. - * Reading RTC current time locks the values in calendar shadow registers until Current date is read. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_GetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format) -{ - uint32_t datetmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_FORMAT(Format)); - - /* Get the DR register */ - datetmpreg = (uint32_t)(hrtc->Instance->DR & RTC_DR_RESERVED_MASK); - - /* Fill the structure fields with the read parameters */ - sDate->Year = (uint8_t)((datetmpreg & (RTC_DR_YT | RTC_DR_YU)) >> 16U); - sDate->Month = (uint8_t)((datetmpreg & (RTC_DR_MT | RTC_DR_MU)) >> 8U); - sDate->Date = (uint8_t)(datetmpreg & (RTC_DR_DT | RTC_DR_DU)); - sDate->WeekDay = (uint8_t)((datetmpreg & (RTC_DR_WDU)) >> 13U); - - /* Check the input parameters format */ - if(Format == RTC_FORMAT_BIN) - { - /* Convert the date structure parameters to Binary format */ - sDate->Year = (uint8_t)RTC_Bcd2ToByte(sDate->Year); - sDate->Month = (uint8_t)RTC_Bcd2ToByte(sDate->Month); - sDate->Date = (uint8_t)RTC_Bcd2ToByte(sDate->Date); - } - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup RTC_Exported_Functions_Group3 RTC Alarm functions - * @brief RTC Alarm functions - * -@verbatim - =============================================================================== - ##### RTC Alarm functions ##### - =============================================================================== - - [..] This section provides functions allowing to configure Alarm feature - -@endverbatim - * @{ - */ -/** - * @brief Sets the specified RTC Alarm. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sAlarm Pointer to Alarm structure - * @param Format Specifies the format of the entered parameters. - * This parameter can be one of the following values: - * @arg RTC_FORMAT_BIN: Binary data format - * @arg RTC_FORMAT_BCD: BCD data format - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_SetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format) -{ - uint32_t tickstart = 0U; - uint32_t tmpreg = 0U, subsecondtmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_FORMAT(Format)); - assert_param(IS_RTC_ALARM(sAlarm->Alarm)); - assert_param(IS_RTC_ALARM_MASK(sAlarm->AlarmMask)); - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_SEL(sAlarm->AlarmDateWeekDaySel)); - assert_param(IS_RTC_ALARM_SUB_SECOND_VALUE(sAlarm->AlarmTime.SubSeconds)); - assert_param(IS_RTC_ALARM_SUB_SECOND_MASK(sAlarm->AlarmSubSecondMask)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - if(Format == RTC_FORMAT_BIN) - { - if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) - { - assert_param(IS_RTC_HOUR12(sAlarm->AlarmTime.Hours)); - assert_param(IS_RTC_HOURFORMAT12(sAlarm->AlarmTime.TimeFormat)); - } - else - { - sAlarm->AlarmTime.TimeFormat = 0x00U; - assert_param(IS_RTC_HOUR24(sAlarm->AlarmTime.Hours)); - } - assert_param(IS_RTC_MINUTES(sAlarm->AlarmTime.Minutes)); - assert_param(IS_RTC_SECONDS(sAlarm->AlarmTime.Seconds)); - - if(sAlarm->AlarmDateWeekDaySel == RTC_ALARMDATEWEEKDAYSEL_DATE) - { - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(sAlarm->AlarmDateWeekDay)); - } - else - { - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(sAlarm->AlarmDateWeekDay)); - } - - tmpreg = (((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Hours) << 16U) | \ - ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Minutes) << 8U) | \ - ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Seconds)) | \ - ((uint32_t)(sAlarm->AlarmTime.TimeFormat) << 16U) | \ - ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmDateWeekDay) << 24U) | \ - ((uint32_t)sAlarm->AlarmDateWeekDaySel) | \ - ((uint32_t)sAlarm->AlarmMask)); - } - else - { - if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) - { - assert_param(IS_RTC_HOUR12(RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours))); - assert_param(IS_RTC_HOURFORMAT12(sAlarm->AlarmTime.TimeFormat)); - } - else - { - sAlarm->AlarmTime.TimeFormat = 0x00U; - assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours))); - } - - assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(sAlarm->AlarmTime.Minutes))); - assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(sAlarm->AlarmTime.Seconds))); - - if(sAlarm->AlarmDateWeekDaySel == RTC_ALARMDATEWEEKDAYSEL_DATE) - { - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay))); - } - else - { - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay))); - } - - tmpreg = (((uint32_t)(sAlarm->AlarmTime.Hours) << 16U) | \ - ((uint32_t)(sAlarm->AlarmTime.Minutes) << 8U) | \ - ((uint32_t) sAlarm->AlarmTime.Seconds) | \ - ((uint32_t)(sAlarm->AlarmTime.TimeFormat) << 16U) | \ - ((uint32_t)(sAlarm->AlarmDateWeekDay) << 24U) | \ - ((uint32_t)sAlarm->AlarmDateWeekDaySel) | \ - ((uint32_t)sAlarm->AlarmMask)); - } - - /* Configure the Alarm A or Alarm B Sub Second registers */ - subsecondtmpreg = (uint32_t)((uint32_t)(sAlarm->AlarmTime.SubSeconds) | (uint32_t)(sAlarm->AlarmSubSecondMask)); - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Configure the Alarm register */ - if(sAlarm->Alarm == RTC_ALARM_A) - { - /* Disable the Alarm A interrupt */ - __HAL_RTC_ALARMA_DISABLE(hrtc); - - /* In case of interrupt mode is used, the interrupt source must disabled */ - __HAL_RTC_ALARM_DISABLE_IT(hrtc, RTC_IT_ALRA); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till RTC ALRAWF flag is set and if Time out is reached exit */ - while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAWF) == RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - - hrtc->Instance->ALRMAR = (uint32_t)tmpreg; - /* Configure the Alarm A Sub Second register */ - hrtc->Instance->ALRMASSR = subsecondtmpreg; - /* Configure the Alarm state: Enable Alarm */ - __HAL_RTC_ALARMA_ENABLE(hrtc); - } - else - { - /* Disable the Alarm B interrupt */ - __HAL_RTC_ALARMB_DISABLE(hrtc); - - /* In case of interrupt mode is used, the interrupt source must disabled */ - __HAL_RTC_ALARM_DISABLE_IT(hrtc, RTC_IT_ALRB); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till RTC ALRBWF flag is set and if Time out is reached exit */ - while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBWF) == RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - - hrtc->Instance->ALRMBR = (uint32_t)tmpreg; - /* Configure the Alarm B Sub Second register */ - hrtc->Instance->ALRMBSSR = subsecondtmpreg; - /* Configure the Alarm state: Enable Alarm */ - __HAL_RTC_ALARMB_ENABLE(hrtc); - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Sets the specified RTC Alarm with Interrupt - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sAlarm Pointer to Alarm structure - * @param Format Specifies the format of the entered parameters. - * This parameter can be one of the following values: - * @arg RTC_FORMAT_BIN: Binary data format - * @arg RTC_FORMAT_BCD: BCD data format - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_SetAlarm_IT(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format) -{ - uint32_t tmpreg = 0U, subsecondtmpreg = 0U; - __IO uint32_t count = RTC_TIMEOUT_VALUE * (SystemCoreClock / 32U / 1000U) ; - - /* Check the parameters */ - assert_param(IS_RTC_FORMAT(Format)); - assert_param(IS_RTC_ALARM(sAlarm->Alarm)); - assert_param(IS_RTC_ALARM_MASK(sAlarm->AlarmMask)); - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_SEL(sAlarm->AlarmDateWeekDaySel)); - assert_param(IS_RTC_ALARM_SUB_SECOND_VALUE(sAlarm->AlarmTime.SubSeconds)); - assert_param(IS_RTC_ALARM_SUB_SECOND_MASK(sAlarm->AlarmSubSecondMask)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - if(Format == RTC_FORMAT_BIN) - { - if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) - { - assert_param(IS_RTC_HOUR12(sAlarm->AlarmTime.Hours)); - assert_param(IS_RTC_HOURFORMAT12(sAlarm->AlarmTime.TimeFormat)); - } - else - { - sAlarm->AlarmTime.TimeFormat = 0x00U; - assert_param(IS_RTC_HOUR24(sAlarm->AlarmTime.Hours)); - } - assert_param(IS_RTC_MINUTES(sAlarm->AlarmTime.Minutes)); - assert_param(IS_RTC_SECONDS(sAlarm->AlarmTime.Seconds)); - - if(sAlarm->AlarmDateWeekDaySel == RTC_ALARMDATEWEEKDAYSEL_DATE) - { - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(sAlarm->AlarmDateWeekDay)); - } - else - { - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(sAlarm->AlarmDateWeekDay)); - } - tmpreg = (((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Hours) << 16U) | \ - ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Minutes) << 8U) | \ - ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmTime.Seconds)) | \ - ((uint32_t)(sAlarm->AlarmTime.TimeFormat) << 16U) | \ - ((uint32_t)RTC_ByteToBcd2(sAlarm->AlarmDateWeekDay) << 24U) | \ - ((uint32_t)sAlarm->AlarmDateWeekDaySel) | \ - ((uint32_t)sAlarm->AlarmMask)); - } - else - { - if((hrtc->Instance->CR & RTC_CR_FMT) != (uint32_t)RESET) - { - assert_param(IS_RTC_HOUR12(RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours))); - assert_param(IS_RTC_HOURFORMAT12(sAlarm->AlarmTime.TimeFormat)); - } - else - { - sAlarm->AlarmTime.TimeFormat = 0x00U; - assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours))); - } - - assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(sAlarm->AlarmTime.Minutes))); - assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(sAlarm->AlarmTime.Seconds))); - - if(sAlarm->AlarmDateWeekDaySel == RTC_ALARMDATEWEEKDAYSEL_DATE) - { - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay))); - } - else - { - assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay))); - } - tmpreg = (((uint32_t)(sAlarm->AlarmTime.Hours) << 16U) | \ - ((uint32_t)(sAlarm->AlarmTime.Minutes) << 8U) | \ - ((uint32_t) sAlarm->AlarmTime.Seconds) | \ - ((uint32_t)(sAlarm->AlarmTime.TimeFormat) << 16U) | \ - ((uint32_t)(sAlarm->AlarmDateWeekDay) << 24U) | \ - ((uint32_t)sAlarm->AlarmDateWeekDaySel) | \ - ((uint32_t)sAlarm->AlarmMask)); - } - /* Configure the Alarm A or Alarm B Sub Second registers */ - subsecondtmpreg = (uint32_t)((uint32_t)(sAlarm->AlarmTime.SubSeconds) | (uint32_t)(sAlarm->AlarmSubSecondMask)); - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Configure the Alarm register */ - if(sAlarm->Alarm == RTC_ALARM_A) - { - /* Disable the Alarm A interrupt */ - __HAL_RTC_ALARMA_DISABLE(hrtc); - - /* Clear flag alarm A */ - __HAL_RTC_ALARM_CLEAR_FLAG(hrtc, RTC_FLAG_ALRAF); - - /* Wait till RTC ALRAWF flag is set and if Time out is reached exit */ - do - { - if (count-- == 0U) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - while (__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAWF) == RESET); - - hrtc->Instance->ALRMAR = (uint32_t)tmpreg; - /* Configure the Alarm A Sub Second register */ - hrtc->Instance->ALRMASSR = subsecondtmpreg; - /* Configure the Alarm state: Enable Alarm */ - __HAL_RTC_ALARMA_ENABLE(hrtc); - /* Configure the Alarm interrupt */ - __HAL_RTC_ALARM_ENABLE_IT(hrtc,RTC_IT_ALRA); - } - else - { - /* Disable the Alarm B interrupt */ - __HAL_RTC_ALARMB_DISABLE(hrtc); - - /* Clear flag alarm B */ - __HAL_RTC_ALARM_CLEAR_FLAG(hrtc, RTC_FLAG_ALRBF); - - /* Wait till RTC ALRBWF flag is set and if Time out is reached exit */ - do - { - if (count-- == 0U) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - while (__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBWF) == RESET); - - hrtc->Instance->ALRMBR = (uint32_t)tmpreg; - /* Configure the Alarm B Sub Second register */ - hrtc->Instance->ALRMBSSR = subsecondtmpreg; - /* Configure the Alarm state: Enable Alarm */ - __HAL_RTC_ALARMB_ENABLE(hrtc); - /* Configure the Alarm interrupt */ - __HAL_RTC_ALARM_ENABLE_IT(hrtc, RTC_IT_ALRB); - } - - /* RTC Alarm Interrupt Configuration: EXTI configuration */ - __HAL_RTC_ALARM_EXTI_ENABLE_IT(); - - EXTI->RTSR |= RTC_EXTI_LINE_ALARM_EVENT; - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Deactivate the specified RTC Alarm - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param Alarm Specifies the Alarm. - * This parameter can be one of the following values: - * @arg RTC_ALARM_A: AlarmA - * @arg RTC_ALARM_B: AlarmB - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_DeactivateAlarm(RTC_HandleTypeDef *hrtc, uint32_t Alarm) -{ - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_ALARM(Alarm)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - if(Alarm == RTC_ALARM_A) - { - /* AlarmA */ - __HAL_RTC_ALARMA_DISABLE(hrtc); - - /* In case of interrupt mode is used, the interrupt source must disabled */ - __HAL_RTC_ALARM_DISABLE_IT(hrtc, RTC_IT_ALRA); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till RTC ALRxWF flag is set and if Time out is reached exit */ - while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAWF) == RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - } - else - { - /* AlarmB */ - __HAL_RTC_ALARMB_DISABLE(hrtc); - - /* In case of interrupt mode is used, the interrupt source must disabled */ - __HAL_RTC_ALARM_DISABLE_IT(hrtc,RTC_IT_ALRB); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till RTC ALRxWF flag is set and if Time out is reached exit */ - while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBWF) == RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - } - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Gets the RTC Alarm value and masks. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sAlarm Pointer to Date structure - * @param Alarm Specifies the Alarm. - * This parameter can be one of the following values: - * @arg RTC_ALARM_A: AlarmA - * @arg RTC_ALARM_B: AlarmB - * @param Format Specifies the format of the entered parameters. - * This parameter can be one of the following values: - * @arg RTC_FORMAT_BIN: Binary data format - * @arg RTC_FORMAT_BCD: BCD data format - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_GetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Alarm, uint32_t Format) -{ - uint32_t tmpreg = 0U, subsecondtmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_FORMAT(Format)); - assert_param(IS_RTC_ALARM(Alarm)); - - if(Alarm == RTC_ALARM_A) - { - /* AlarmA */ - sAlarm->Alarm = RTC_ALARM_A; - - tmpreg = (uint32_t)(hrtc->Instance->ALRMAR); - subsecondtmpreg = (uint32_t)((hrtc->Instance->ALRMASSR ) & RTC_ALRMASSR_SS); - } - else - { - sAlarm->Alarm = RTC_ALARM_B; - - tmpreg = (uint32_t)(hrtc->Instance->ALRMBR); - subsecondtmpreg = (uint32_t)((hrtc->Instance->ALRMBSSR) & RTC_ALRMBSSR_SS); - } - - /* Fill the structure with the read parameters */ - sAlarm->AlarmTime.Hours = (uint32_t)((tmpreg & (RTC_ALRMAR_HT | RTC_ALRMAR_HU)) >> 16U); - sAlarm->AlarmTime.Minutes = (uint32_t)((tmpreg & (RTC_ALRMAR_MNT | RTC_ALRMAR_MNU)) >> 8U); - sAlarm->AlarmTime.Seconds = (uint32_t)(tmpreg & (RTC_ALRMAR_ST | RTC_ALRMAR_SU)); - sAlarm->AlarmTime.TimeFormat = (uint32_t)((tmpreg & RTC_ALRMAR_PM) >> 16U); - sAlarm->AlarmTime.SubSeconds = (uint32_t) subsecondtmpreg; - sAlarm->AlarmDateWeekDay = (uint32_t)((tmpreg & (RTC_ALRMAR_DT | RTC_ALRMAR_DU)) >> 24U); - sAlarm->AlarmDateWeekDaySel = (uint32_t)(tmpreg & RTC_ALRMAR_WDSEL); - sAlarm->AlarmMask = (uint32_t)(tmpreg & RTC_ALARMMASK_ALL); - - if(Format == RTC_FORMAT_BIN) - { - sAlarm->AlarmTime.Hours = RTC_Bcd2ToByte(sAlarm->AlarmTime.Hours); - sAlarm->AlarmTime.Minutes = RTC_Bcd2ToByte(sAlarm->AlarmTime.Minutes); - sAlarm->AlarmTime.Seconds = RTC_Bcd2ToByte(sAlarm->AlarmTime.Seconds); - sAlarm->AlarmDateWeekDay = RTC_Bcd2ToByte(sAlarm->AlarmDateWeekDay); - } - - return HAL_OK; -} - -/** - * @brief This function handles Alarm interrupt request. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -void HAL_RTC_AlarmIRQHandler(RTC_HandleTypeDef* hrtc) -{ - /* Get the AlarmA interrupt source enable status */ - if(__HAL_RTC_ALARM_GET_IT_SOURCE(hrtc, RTC_IT_ALRA) != (uint32_t)RESET) - { - /* Get the pending status of the AlarmA Interrupt */ - if(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAF) != (uint32_t)RESET) - { - /* AlarmA callback */ - #if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - hrtc->AlarmAEventCallback(hrtc); - #else - HAL_RTC_AlarmAEventCallback(hrtc); - #endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - - /* Clear the AlarmA interrupt pending bit */ - __HAL_RTC_ALARM_CLEAR_FLAG(hrtc,RTC_FLAG_ALRAF); - } - } - - /* Get the AlarmB interrupt source enable status */ - if(__HAL_RTC_ALARM_GET_IT_SOURCE(hrtc, RTC_IT_ALRB) != (uint32_t)RESET) - { - /* Get the pending status of the AlarmB Interrupt */ - if(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBF) != (uint32_t)RESET) - { - /* AlarmB callback */ - #if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - hrtc->AlarmBEventCallback(hrtc); - #else - HAL_RTCEx_AlarmBEventCallback(hrtc); - #endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - - /* Clear the AlarmB interrupt pending bit */ - __HAL_RTC_ALARM_CLEAR_FLAG(hrtc,RTC_FLAG_ALRBF); - } - } - - /* Clear the EXTI's line Flag for RTC Alarm */ - __HAL_RTC_ALARM_EXTI_CLEAR_FLAG(); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; -} - -/** - * @brief Alarm A callback. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -__weak void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrtc); - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_RTC_AlarmAEventCallback could be implemented in the user file - */ -} - -/** - * @brief This function handles AlarmA Polling request. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_PollForAlarmAEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRAF) == RESET) - { - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - hrtc->State = HAL_RTC_STATE_TIMEOUT; - return HAL_TIMEOUT; - } - } - } - - /* Clear the Alarm interrupt pending bit */ - __HAL_RTC_ALARM_CLEAR_FLAG(hrtc, RTC_FLAG_ALRAF); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup RTC_Exported_Functions_Group4 Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Wait for RTC Time and Date Synchronization - -@endverbatim - * @{ - */ - -/** - * @brief Waits until the RTC Time and Date registers (RTC_TR and RTC_DR) are - * synchronized with RTC APB clock. - * @note The RTC Resynchronization mode is write protected, use the - * __HAL_RTC_WRITEPROTECTION_DISABLE() before calling this function. - * @note To read the calendar through the shadow registers after Calendar - * initialization, calendar update or after wake-up from low power modes - * the software must first clear the RSF flag. - * The software must then wait until it is set again before reading - * the calendar, which means that the calendar registers have been - * correctly copied into the RTC_TR and RTC_DR shadow registers. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTC_WaitForSynchro(RTC_HandleTypeDef* hrtc) -{ - uint32_t tickstart = 0U; - - /* Clear RSF flag */ - hrtc->Instance->ISR &= (uint32_t)RTC_RSF_MASK; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait the registers to be synchronised */ - while((hrtc->Instance->ISR & RTC_ISR_RSF) == (uint32_t)RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup RTC_Exported_Functions_Group5 Peripheral State functions - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Get RTC state - -@endverbatim - * @{ - */ -/** - * @brief Returns the RTC state. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL state - */ -HAL_RTCStateTypeDef HAL_RTC_GetState(RTC_HandleTypeDef* hrtc) -{ - return hrtc->State; -} - -/** - * @brief Daylight Saving Time, Add one hour to the calendar in one single operation - * without going through the initialization procedure. - * @param hrtc RTC handle - * @retval None - */ -void HAL_RTC_DST_Add1Hour(RTC_HandleTypeDef *hrtc) -{ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - SET_BIT(hrtc->Instance->CR, RTC_CR_ADD1H); - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); -} - -/** - * @brief Daylight Saving Time, Substract one hour from the calendar in one - * single operation without going through the initialization procedure. - * @param hrtc RTC handle - * @retval None - */ -void HAL_RTC_DST_Sub1Hour(RTC_HandleTypeDef *hrtc) -{ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - SET_BIT(hrtc->Instance->CR, RTC_CR_SUB1H); - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); -} - -/** - * @brief Daylight Saving Time, Set the store operation bit. - * @note It can be used by the software in order to memorize the DST status. - * @param hrtc RTC handle - * @retval None - */ -void HAL_RTC_DST_SetStoreOperation(RTC_HandleTypeDef *hrtc) -{ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - SET_BIT(hrtc->Instance->CR, RTC_CR_BKP); - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); -} - -/** - * @brief Daylight Saving Time, Clear the store operation bit. - * @param hrtc RTC handle - * @retval None - */ -void HAL_RTC_DST_ClearStoreOperation(RTC_HandleTypeDef *hrtc) -{ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - CLEAR_BIT(hrtc->Instance->CR, RTC_CR_BKP); - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); -} - -/** - * @brief Daylight Saving Time, Read the store operation bit. - * @param hrtc RTC handle - * @retval operation see RTC_StoreOperation_Definitions - */ -uint32_t HAL_RTC_DST_ReadStoreOperation(RTC_HandleTypeDef *hrtc) -{ - return READ_BIT(hrtc->Instance->CR, RTC_CR_BKP); -} - -/** - * @} - */ - -/** - * @brief Enters the RTC Initialization mode. - * @note The RTC Initialization mode is write protected, use the - * __HAL_RTC_WRITEPROTECTION_DISABLE() before calling this function. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -HAL_StatusTypeDef RTC_EnterInitMode(RTC_HandleTypeDef* hrtc) -{ - uint32_t tickstart = 0U; - - /* Check if the Initialization mode is set */ - if((hrtc->Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) - { - /* Set the Initialization mode */ - hrtc->Instance->ISR = (uint32_t)RTC_INIT_MASK; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till RTC is in INIT state and if Time out is reached exit */ - while((hrtc->Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - return HAL_TIMEOUT; - } - } - } - - return HAL_OK; -} - - -/** - * @brief Converts a 2 digit decimal to BCD format. - * @param Value Byte to be converted - * @retval Converted byte - */ -uint8_t RTC_ByteToBcd2(uint8_t Value) -{ - uint32_t bcdhigh = 0U; - - while(Value >= 10U) - { - bcdhigh++; - Value -= 10U; - } - - return ((uint8_t)(bcdhigh << 4U) | Value); -} - -/** - * @brief Converts from 2 digit BCD to Binary. - * @param Value BCD value to be converted - * @retval Converted word - */ -uint8_t RTC_Bcd2ToByte(uint8_t Value) -{ - uint32_t tmp = 0U; - tmp = ((uint8_t)(Value & (uint8_t)0xF0) >> (uint8_t)0x4) * 10; - return (tmp + (Value & (uint8_t)0x0F)); -} - -/** - * @} - */ - -#endif /* HAL_RTC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c deleted file mode 100644 index 8e07b4e22e10bed..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rtc_ex.c +++ /dev/null @@ -1,1784 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rtc_ex.c - * @author MCD Application Team - * @brief RTC HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Real Time Clock (RTC) Extension peripheral: - * + RTC Time Stamp functions - * + RTC Tamper functions - * + RTC Wake-up functions - * + Extension Control functions - * + Extension RTC features functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (+) Enable the RTC domain access. - (+) Configure the RTC Prescaler (Asynchronous and Synchronous) and RTC hour - format using the HAL_RTC_Init() function. - - *** RTC Wake-up configuration *** - ================================ - [..] - (+) To configure the RTC Wake-up Clock source and Counter use the HAL_RTCEx_SetWakeUpTimer() - function. You can also configure the RTC Wake-up timer in interrupt mode - using the HAL_RTCEx_SetWakeUpTimer_IT() function. - (+) To read the RTC Wake-up Counter register, use the HAL_RTCEx_GetWakeUpTimer() - function. - - *** TimeStamp configuration *** - =============================== - [..] - (+) Configure the RTC_AFx trigger and enable the RTC TimeStamp using the - HAL_RTCEx_SetTimeStamp() function. You can also configure the RTC TimeStamp with - interrupt mode using the HAL_RTCEx_SetTimeStamp_IT() function. - (+) To read the RTC TimeStamp Time and Date register, use the HAL_RTCEx_GetTimeStamp() - function. - (+) The TIMESTAMP alternate function can be mapped either to RTC_AF1 (PC13) - or RTC_AF2 (PI8 or PA0 only for STM32F446xx devices) depending on the value of TSINSEL bit in - RTC_TAFCR register. The corresponding pin is also selected by HAL_RTCEx_SetTimeStamp() - or HAL_RTCEx_SetTimeStamp_IT() function. - - *** Tamper configuration *** - ============================ - [..] - (+) Enable the RTC Tamper and configure the Tamper filter count, trigger Edge - or Level according to the Tamper filter (if equal to 0 Edge else Level) - value, sampling frequency, precharge or discharge and Pull-UP using the - HAL_RTCEx_SetTamper() function. You can configure RTC Tamper in interrupt - mode using HAL_RTCEx_SetTamper_IT() function. - (+) The TAMPER1 alternate function can be mapped either to RTC_AF1 (PC13) - or RTC_AF2 (PI8 or PA0 only for STM32F446xx devices) depending on the value of TAMP1INSEL bit in - RTC_TAFCR register. The corresponding pin is also selected by HAL_RTCEx_SetTamper() - or HAL_RTCEx_SetTamper_IT() function. - - *** Backup Data Registers configuration *** - =========================================== - [..] - (+) To write to the RTC Backup Data registers, use the HAL_RTCEx_BKUPWrite() - function. - (+) To read the RTC Backup Data registers, use the HAL_RTCEx_BKUPRead() - function. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup RTCEx RTCEx - * @brief RTC HAL module driver - * @{ - */ - -#ifdef HAL_RTC_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup RTCEx_Exported_Functions RTCEx Exported Functions - * @{ - */ - -/** @defgroup RTCEx_Exported_Functions_Group1 RTC TimeStamp and Tamper functions - * @brief RTC TimeStamp and Tamper functions - * -@verbatim - =============================================================================== - ##### RTC TimeStamp and Tamper functions ##### - =============================================================================== - - [..] This section provides functions allowing to configure TimeStamp feature - -@endverbatim - * @{ - */ - -/** - * @brief Sets TimeStamp. - * @note This API must be called before enabling the TimeStamp feature. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param TimeStampEdge Specifies the pin edge on which the TimeStamp is - * activated. - * This parameter can be one of the following values: - * @arg RTC_TIMESTAMPEDGE_RISING: the Time stamp event occurs on the - * rising edge of the related pin. - * @arg RTC_TIMESTAMPEDGE_FALLING: the Time stamp event occurs on the - * falling edge of the related pin. - * @param RTC_TimeStampPin specifies the RTC TimeStamp Pin. - * This parameter can be one of the following values: - * @arg RTC_TIMESTAMPPIN_DEFAULT: PC13 is selected as RTC TimeStamp Pin. - * @arg RTC_TIMESTAMPPIN_POS1: PI8/PA0 is selected as RTC TimeStamp Pin. - * (not applicable in the case of STM32F412xx, STM32F413xx and STM32F423xx devices) - * (PI8 for all STM32 devices except for STM32F446xx devices the PA0 is used) - * @arg RTC_TIMESTAMPPIN_PA0: PA0 is selected as RTC TimeStamp Pin only for STM32F446xx devices - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin) -{ - uint32_t tmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_TIMESTAMP_EDGE(TimeStampEdge)); - assert_param(IS_RTC_TIMESTAMP_PIN(RTC_TimeStampPin)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Get the RTC_CR register and clear the bits to be configured */ - tmpreg = (uint32_t)(hrtc->Instance->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE)); - - tmpreg|= TimeStampEdge; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - hrtc->Instance->TAFCR &= (uint32_t)~RTC_TAFCR_TSINSEL; - hrtc->Instance->TAFCR |= (uint32_t)(RTC_TimeStampPin); - - /* Configure the Time Stamp TSEDGE and Enable bits */ - hrtc->Instance->CR = (uint32_t)tmpreg; - - __HAL_RTC_TIMESTAMP_ENABLE(hrtc); - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Sets TimeStamp with Interrupt. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @note This API must be called before enabling the TimeStamp feature. - * @param TimeStampEdge Specifies the pin edge on which the TimeStamp is - * activated. - * This parameter can be one of the following values: - * @arg RTC_TIMESTAMPEDGE_RISING: the Time stamp event occurs on the - * rising edge of the related pin. - * @arg RTC_TIMESTAMPEDGE_FALLING: the Time stamp event occurs on the - * falling edge of the related pin. - * @param RTC_TimeStampPin Specifies the RTC TimeStamp Pin. - * This parameter can be one of the following values: - * @arg RTC_TIMESTAMPPIN_DEFAULT: PC13 is selected as RTC TimeStamp Pin. - * @arg RTC_TIMESTAMPPIN_PI8: PI8 is selected as RTC TimeStamp Pin. (not applicable in the case of STM32F446xx, STM32F412xx, STM32F413xx and STM32F423xx devices) - * @arg RTC_TIMESTAMPPIN_PA0: PA0 is selected as RTC TimeStamp Pin only for STM32F446xx devices - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp_IT(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin) -{ - uint32_t tmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_TIMESTAMP_EDGE(TimeStampEdge)); - assert_param(IS_RTC_TIMESTAMP_PIN(RTC_TimeStampPin)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Get the RTC_CR register and clear the bits to be configured */ - tmpreg = (uint32_t)(hrtc->Instance->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE)); - - tmpreg |= TimeStampEdge; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Configure the Time Stamp TSEDGE and Enable bits */ - hrtc->Instance->CR = (uint32_t)tmpreg; - - hrtc->Instance->TAFCR &= (uint32_t)~RTC_TAFCR_TSINSEL; - hrtc->Instance->TAFCR |= (uint32_t)(RTC_TimeStampPin); - - /* Clear RTC Timestamp flag */ - __HAL_RTC_TIMESTAMP_CLEAR_FLAG(hrtc, RTC_FLAG_TSF); - - __HAL_RTC_TIMESTAMP_ENABLE(hrtc); - - /* Enable IT timestamp */ - __HAL_RTC_TIMESTAMP_ENABLE_IT(hrtc,RTC_IT_TS); - - /* RTC timestamp Interrupt Configuration: EXTI configuration */ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT(); - - EXTI->RTSR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT; - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Deactivates TimeStamp. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_DeactivateTimeStamp(RTC_HandleTypeDef *hrtc) -{ - uint32_t tmpreg = 0U; - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* In case of interrupt mode is used, the interrupt source must disabled */ - __HAL_RTC_TIMESTAMP_DISABLE_IT(hrtc, RTC_IT_TS); - - /* Get the RTC_CR register and clear the bits to be configured */ - tmpreg = (uint32_t)(hrtc->Instance->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE)); - - /* Configure the Time Stamp TSEDGE and Enable bits */ - hrtc->Instance->CR = (uint32_t)tmpreg; - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Gets the RTC TimeStamp value. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sTimeStamp Pointer to Time structure - * @param sTimeStampDate Pointer to Date structure - * @param Format specifies the format of the entered parameters. - * This parameter can be one of the following values: - * RTC_FORMAT_BIN: Binary data format - * RTC_FORMAT_BCD: BCD data format - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_GetTimeStamp(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef* sTimeStamp, RTC_DateTypeDef* sTimeStampDate, uint32_t Format) -{ - uint32_t tmptime = 0U, tmpdate = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_FORMAT(Format)); - - /* Get the TimeStamp time and date registers values */ - tmptime = (uint32_t)(hrtc->Instance->TSTR & RTC_TR_RESERVED_MASK); - tmpdate = (uint32_t)(hrtc->Instance->TSDR & RTC_DR_RESERVED_MASK); - - /* Fill the Time structure fields with the read parameters */ - sTimeStamp->Hours = (uint8_t)((tmptime & (RTC_TR_HT | RTC_TR_HU)) >> 16U); - sTimeStamp->Minutes = (uint8_t)((tmptime & (RTC_TR_MNT | RTC_TR_MNU)) >> 8U); - sTimeStamp->Seconds = (uint8_t)(tmptime & (RTC_TR_ST | RTC_TR_SU)); - sTimeStamp->TimeFormat = (uint8_t)((tmptime & (RTC_TR_PM)) >> 16U); - sTimeStamp->SubSeconds = (uint32_t) hrtc->Instance->TSSSR; - - /* Fill the Date structure fields with the read parameters */ - sTimeStampDate->Year = 0U; - sTimeStampDate->Month = (uint8_t)((tmpdate & (RTC_DR_MT | RTC_DR_MU)) >> 8U); - sTimeStampDate->Date = (uint8_t)(tmpdate & (RTC_DR_DT | RTC_DR_DU)); - sTimeStampDate->WeekDay = (uint8_t)((tmpdate & (RTC_DR_WDU)) >> 13U); - - /* Check the input parameters format */ - if(Format == RTC_FORMAT_BIN) - { - /* Convert the TimeStamp structure parameters to Binary format */ - sTimeStamp->Hours = (uint8_t)RTC_Bcd2ToByte(sTimeStamp->Hours); - sTimeStamp->Minutes = (uint8_t)RTC_Bcd2ToByte(sTimeStamp->Minutes); - sTimeStamp->Seconds = (uint8_t)RTC_Bcd2ToByte(sTimeStamp->Seconds); - - /* Convert the DateTimeStamp structure parameters to Binary format */ - sTimeStampDate->Month = (uint8_t)RTC_Bcd2ToByte(sTimeStampDate->Month); - sTimeStampDate->Date = (uint8_t)RTC_Bcd2ToByte(sTimeStampDate->Date); - sTimeStampDate->WeekDay = (uint8_t)RTC_Bcd2ToByte(sTimeStampDate->WeekDay); - } - - /* Clear the TIMESTAMP Flag */ - __HAL_RTC_TIMESTAMP_CLEAR_FLAG(hrtc, RTC_FLAG_TSF); - - return HAL_OK; -} - -/** - * @brief Sets Tamper - * @note By calling this API we disable the tamper interrupt for all tampers. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sTamper Pointer to Tamper Structure. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetTamper(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper) -{ - uint32_t tmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_TAMPER(sTamper->Tamper)); - assert_param(IS_RTC_TAMPER_PIN(sTamper->PinSelection)); - assert_param(IS_RTC_TAMPER_TRIGGER(sTamper->Trigger)); - assert_param(IS_RTC_TAMPER_FILTER(sTamper->Filter)); - assert_param(IS_RTC_TAMPER_SAMPLING_FREQ(sTamper->SamplingFrequency)); - assert_param(IS_RTC_TAMPER_PRECHARGE_DURATION(sTamper->PrechargeDuration)); - assert_param(IS_RTC_TAMPER_PULLUP_STATE(sTamper->TamperPullUp)); - assert_param(IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION(sTamper->TimeStampOnTamperDetection)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - if(sTamper->Trigger != RTC_TAMPERTRIGGER_RISINGEDGE) - { - sTamper->Trigger = (uint32_t)(sTamper->Tamper << 1U); - } - - tmpreg = ((uint32_t)sTamper->Tamper | (uint32_t)sTamper->PinSelection | (uint32_t)sTamper->Trigger |\ - (uint32_t)sTamper->Filter | (uint32_t)sTamper->SamplingFrequency | (uint32_t)sTamper->PrechargeDuration |\ - (uint32_t)sTamper->TamperPullUp | sTamper->TimeStampOnTamperDetection); - - hrtc->Instance->TAFCR &= (uint32_t)~((uint32_t)sTamper->Tamper | (uint32_t)(sTamper->Tamper << 1U) | (uint32_t)RTC_TAFCR_TAMPTS |\ - (uint32_t)RTC_TAFCR_TAMPFREQ | (uint32_t)RTC_TAFCR_TAMPFLT | (uint32_t)RTC_TAFCR_TAMPPRCH |\ - (uint32_t)RTC_TAFCR_TAMPPUDIS | (uint32_t)RTC_TAFCR_TAMPINSEL | (uint32_t)RTC_TAFCR_TAMPIE); - - hrtc->Instance->TAFCR |= tmpreg; - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Sets Tamper with interrupt. - * @note By calling this API we force the tamper interrupt for all tampers. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param sTamper Pointer to RTC Tamper. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetTamper_IT(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper) -{ - uint32_t tmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_TAMPER(sTamper->Tamper)); - assert_param(IS_RTC_TAMPER_PIN(sTamper->PinSelection)); - assert_param(IS_RTC_TAMPER_TRIGGER(sTamper->Trigger)); - assert_param(IS_RTC_TAMPER_FILTER(sTamper->Filter)); - assert_param(IS_RTC_TAMPER_SAMPLING_FREQ(sTamper->SamplingFrequency)); - assert_param(IS_RTC_TAMPER_PRECHARGE_DURATION(sTamper->PrechargeDuration)); - assert_param(IS_RTC_TAMPER_PULLUP_STATE(sTamper->TamperPullUp)); - assert_param(IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION(sTamper->TimeStampOnTamperDetection)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Configure the tamper trigger */ - if(sTamper->Trigger != RTC_TAMPERTRIGGER_RISINGEDGE) - { - sTamper->Trigger = (uint32_t)(sTamper->Tamper << 1U); - } - - tmpreg = ((uint32_t)sTamper->Tamper | (uint32_t)sTamper->PinSelection | (uint32_t)sTamper->Trigger |\ - (uint32_t)sTamper->Filter | (uint32_t)sTamper->SamplingFrequency | (uint32_t)sTamper->PrechargeDuration |\ - (uint32_t)sTamper->TamperPullUp | sTamper->TimeStampOnTamperDetection); - - hrtc->Instance->TAFCR &= (uint32_t)~((uint32_t)sTamper->Tamper | (uint32_t)(sTamper->Tamper << 1U) | (uint32_t)RTC_TAFCR_TAMPTS |\ - (uint32_t)RTC_TAFCR_TAMPFREQ | (uint32_t)RTC_TAFCR_TAMPFLT | (uint32_t)RTC_TAFCR_TAMPPRCH |\ - (uint32_t)RTC_TAFCR_TAMPPUDIS | (uint32_t)RTC_TAFCR_TAMPINSEL); - - hrtc->Instance->TAFCR |= tmpreg; - - /* Configure the Tamper Interrupt in the RTC_TAFCR */ - hrtc->Instance->TAFCR |= (uint32_t)RTC_TAFCR_TAMPIE; - - if(sTamper->Tamper == RTC_TAMPER_1) - { - /* Clear RTC Tamper 1 flag */ - __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP1F); - } - else - { - /* Clear RTC Tamper 2 flag */ - __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP2F); - } - - /* RTC Tamper Interrupt Configuration: EXTI configuration */ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT(); - - EXTI->RTSR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT; - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Deactivates Tamper. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param Tamper Selected tamper pin. - * This parameter can be RTC_Tamper_1 and/or RTC_TAMPER_2. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_DeactivateTamper(RTC_HandleTypeDef *hrtc, uint32_t Tamper) -{ - assert_param(IS_RTC_TAMPER(Tamper)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the selected Tamper pin */ - hrtc->Instance->TAFCR &= (uint32_t)~Tamper; - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief This function handles TimeStamp interrupt request. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -void HAL_RTCEx_TamperTimeStampIRQHandler(RTC_HandleTypeDef *hrtc) -{ - /* Get the TimeStamp interrupt source enable status */ - if(__HAL_RTC_TIMESTAMP_GET_IT_SOURCE(hrtc, RTC_IT_TS) != (uint32_t)RESET) - { - /* Get the pending status of the TIMESTAMP Interrupt */ - if(__HAL_RTC_TIMESTAMP_GET_FLAG(hrtc, RTC_FLAG_TSF) != (uint32_t)RESET) - { - /* TIMESTAMP callback */ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - hrtc->TimeStampEventCallback(hrtc); -#else - HAL_RTCEx_TimeStampEventCallback(hrtc); -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - - /* Clear the TIMESTAMP interrupt pending bit */ - __HAL_RTC_TIMESTAMP_CLEAR_FLAG(hrtc,RTC_FLAG_TSF); - } - } - - /* Get the Tamper1 interrupt source enable status */ - if(__HAL_RTC_TAMPER_GET_IT_SOURCE(hrtc, RTC_IT_TAMP) != (uint32_t)RESET) - { - /* Get the pending status of the Tamper1 Interrupt */ - if(__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP1F) != (uint32_t)RESET) - { - /* Tamper callback */ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - hrtc->Tamper1EventCallback(hrtc); -#else - HAL_RTCEx_Tamper1EventCallback(hrtc); -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - - /* Clear the Tamper interrupt pending bit */ - __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc,RTC_FLAG_TAMP1F); - } - } - - /* Get the Tamper2 interrupt source enable status */ - if(__HAL_RTC_TAMPER_GET_IT_SOURCE(hrtc, RTC_IT_TAMP) != (uint32_t)RESET) - { - /* Get the pending status of the Tamper2 Interrupt */ - if(__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP2F) != (uint32_t)RESET) - { - /* Tamper callback */ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - hrtc->Tamper2EventCallback(hrtc); -#else - HAL_RTCEx_Tamper2EventCallback(hrtc); -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - - /* Clear the Tamper interrupt pending bit */ - __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP2F); - } - } - - /* Clear the EXTI's Flag for RTC TimeStamp and Tamper */ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG(); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; -} - -/** - * @brief TimeStamp callback. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -__weak void HAL_RTCEx_TimeStampEventCallback(RTC_HandleTypeDef *hrtc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrtc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RTC_TimeStampEventCallback could be implemented in the user file - */ -} - -/** - * @brief Tamper 1 callback. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -__weak void HAL_RTCEx_Tamper1EventCallback(RTC_HandleTypeDef *hrtc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrtc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RTC_Tamper1EventCallback could be implemented in the user file - */ -} - -/** - * @brief Tamper 2 callback. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -__weak void HAL_RTCEx_Tamper2EventCallback(RTC_HandleTypeDef *hrtc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrtc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RTC_Tamper2EventCallback could be implemented in the user file - */ -} - -/** - * @brief This function handles TimeStamp polling request. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_PollForTimeStampEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_RTC_TIMESTAMP_GET_FLAG(hrtc, RTC_FLAG_TSF) == RESET) - { - if(__HAL_RTC_TIMESTAMP_GET_FLAG(hrtc, RTC_FLAG_TSOVF) != RESET) - { - /* Clear the TIMESTAMP Overrun Flag */ - __HAL_RTC_TIMESTAMP_CLEAR_FLAG(hrtc, RTC_FLAG_TSOVF); - - /* Change TIMESTAMP state */ - hrtc->State = HAL_RTC_STATE_ERROR; - - return HAL_ERROR; - } - - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - hrtc->State = HAL_RTC_STATE_TIMEOUT; - return HAL_TIMEOUT; - } - } - } - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - return HAL_OK; -} - -/** - * @brief This function handles Tamper1 Polling. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_PollForTamper1Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Get the status of the Interrupt */ - while(__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP1F)== RESET) - { - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - hrtc->State = HAL_RTC_STATE_TIMEOUT; - return HAL_TIMEOUT; - } - } - } - - /* Clear the Tamper Flag */ - __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc,RTC_FLAG_TAMP1F); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - return HAL_OK; -} - -/** - * @brief This function handles Tamper2 Polling. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_PollForTamper2Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Get the status of the Interrupt */ - while(__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP2F) == RESET) - { - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - hrtc->State = HAL_RTC_STATE_TIMEOUT; - return HAL_TIMEOUT; - } - } - } - - /* Clear the Tamper Flag */ - __HAL_RTC_TAMPER_CLEAR_FLAG(hrtc,RTC_FLAG_TAMP2F); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup RTCEx_Exported_Functions_Group2 RTC Wake-up functions - * @brief RTC Wake-up functions - * -@verbatim - =============================================================================== - ##### RTC Wake-up functions ##### - =============================================================================== - - [..] This section provides functions allowing to configure Wake-up feature - -@endverbatim - * @{ - */ - -/** - * @brief Sets wake up timer. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param WakeUpCounter Wake up counter - * @param WakeUpClock Wake up clock - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock) -{ - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_WAKEUP_CLOCK(WakeUpClock)); - assert_param(IS_RTC_WAKEUP_COUNTER(WakeUpCounter)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /*Check RTC WUTWF flag is reset only when wake up timer enabled*/ - if((hrtc->Instance->CR & RTC_CR_WUTE) != RESET) - { - tickstart = HAL_GetTick(); - - /* Wait till RTC WUTWF flag is reset and if Time out is reached exit */ - while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == SET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - } - - __HAL_RTC_WAKEUPTIMER_DISABLE(hrtc); - - tickstart = HAL_GetTick(); - - /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ - while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - - /* Clear the Wake-up Timer clock source bits in CR register */ - hrtc->Instance->CR &= (uint32_t)~RTC_CR_WUCKSEL; - - /* Configure the clock source */ - hrtc->Instance->CR |= (uint32_t)WakeUpClock; - - /* Configure the Wake-up Timer counter */ - hrtc->Instance->WUTR = (uint32_t)WakeUpCounter; - - /* Enable the Wake-up Timer */ - __HAL_RTC_WAKEUPTIMER_ENABLE(hrtc); - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Sets wake up timer with interrupt - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param WakeUpCounter Wake up counter - * @param WakeUpClock Wake up clock - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer_IT(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock) -{ - __IO uint32_t count; - - /* Check the parameters */ - assert_param(IS_RTC_WAKEUP_CLOCK(WakeUpClock)); - assert_param(IS_RTC_WAKEUP_COUNTER(WakeUpCounter)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Check RTC WUTWF flag is reset only when wake up timer enabled */ - if((hrtc->Instance->CR & RTC_CR_WUTE) != RESET) - { - /* Wait till RTC WUTWF flag is reset and if Time out is reached exit */ - count = RTC_TIMEOUT_VALUE * (SystemCoreClock / 32U / 1000U); - do - { - if(count-- == 0U) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == SET); - } - - __HAL_RTC_WAKEUPTIMER_DISABLE(hrtc); - - /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ - count = RTC_TIMEOUT_VALUE * (SystemCoreClock / 32U / 1000U); - do - { - if(count-- == 0U) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == RESET); - - /* Configure the Wake-up Timer counter */ - hrtc->Instance->WUTR = (uint32_t)WakeUpCounter; - - /* Clear the Wake-up Timer clock source bits in CR register */ - hrtc->Instance->CR &= (uint32_t)~RTC_CR_WUCKSEL; - - /* Configure the clock source */ - hrtc->Instance->CR |= (uint32_t)WakeUpClock; - - /* RTC WakeUpTimer Interrupt Configuration: EXTI configuration */ - __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT(); - - EXTI->RTSR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT; - - /* Clear RTC Wake Up timer Flag */ - __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(hrtc, RTC_FLAG_WUTF); - - /* Configure the Interrupt in the RTC_CR register */ - __HAL_RTC_WAKEUPTIMER_ENABLE_IT(hrtc,RTC_IT_WUT); - - /* Enable the Wake-up Timer */ - __HAL_RTC_WAKEUPTIMER_ENABLE(hrtc); - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Deactivates wake up timer counter. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -uint32_t HAL_RTCEx_DeactivateWakeUpTimer(RTC_HandleTypeDef *hrtc) -{ - uint32_t tickstart = 0U; - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Disable the Wake-up Timer */ - __HAL_RTC_WAKEUPTIMER_DISABLE(hrtc); - - /* In case of interrupt mode is used, the interrupt source must disabled */ - __HAL_RTC_WAKEUPTIMER_DISABLE_IT(hrtc,RTC_IT_WUT); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait till RTC WUTWF flag is set and if Time out is reached exit */ - while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTWF) == RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Gets wake up timer counter. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval Counter value - */ -uint32_t HAL_RTCEx_GetWakeUpTimer(RTC_HandleTypeDef *hrtc) -{ - /* Get the counter value */ - return ((uint32_t)(hrtc->Instance->WUTR & RTC_WUTR_WUT)); -} - -/** - * @brief This function handles Wake Up Timer interrupt request. - * @note Unlike alarm interrupt line (shared by AlarmA and AlarmB) and tamper - * interrupt line (shared by timestamp and tampers) wakeup timer - * interrupt line is exclusive to the wakeup timer. - * There is no need in this case to check on the interrupt enable - * status via __HAL_RTC_WAKEUPTIMER_GET_IT_SOURCE(). - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -void HAL_RTCEx_WakeUpTimerIRQHandler(RTC_HandleTypeDef *hrtc) -{ - /* Get the pending status of the WAKEUPTIMER Interrupt */ - if(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTF) != (uint32_t)RESET) - { - /* WAKEUPTIMER callback */ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - hrtc->WakeUpTimerEventCallback(hrtc); -#else - HAL_RTCEx_WakeUpTimerEventCallback(hrtc); -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - - /* Clear the WAKEUPTIMER interrupt pending bit */ - __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(hrtc, RTC_FLAG_WUTF); - } - - /* Clear the EXTI's line Flag for RTC WakeUpTimer */ - __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG(); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; -} - -/** - * @brief Wake Up Timer callback. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -__weak void HAL_RTCEx_WakeUpTimerEventCallback(RTC_HandleTypeDef *hrtc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrtc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RTC_WakeUpTimerEventCallback could be implemented in the user file - */ -} - -/** - * @brief This function handles Wake Up Timer Polling. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_PollForWakeUpTimerEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_RTC_WAKEUPTIMER_GET_FLAG(hrtc, RTC_FLAG_WUTF) == RESET) - { - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - return HAL_TIMEOUT; - } - } - } - - /* Clear the WAKEUPTIMER Flag */ - __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(hrtc, RTC_FLAG_WUTF); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - return HAL_OK; -} - -/** - * @} - */ - - -/** @defgroup RTCEx_Exported_Functions_Group3 Extension Peripheral Control functions - * @brief Extension Peripheral Control functions - * -@verbatim - =============================================================================== - ##### Extension Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides functions allowing to - (+) Write a data in a specified RTC Backup data register - (+) Read a data in a specified RTC Backup data register - (+) Set the Coarse calibration parameters. - (+) Deactivate the Coarse calibration parameters - (+) Set the Smooth calibration parameters. - (+) Configure the Synchronization Shift Control Settings. - (+) Configure the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). - (+) Deactivate the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). - (+) Enable the RTC reference clock detection. - (+) Disable the RTC reference clock detection. - (+) Enable the Bypass Shadow feature. - (+) Disable the Bypass Shadow feature. - -@endverbatim - * @{ - */ - -/** - * @brief Writes a data in a specified RTC Backup data register. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param BackupRegister RTC Backup data Register number. - * This parameter can be: RTC_BKP_DRx where x can be from 0 to 19 to - * specify the register. - * @param Data Data to be written in the specified RTC Backup data register. - * @retval None - */ -void HAL_RTCEx_BKUPWrite(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister, uint32_t Data) -{ - uint32_t tmp = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_BKP(BackupRegister)); - - tmp = (uint32_t)&(hrtc->Instance->BKP0R); - tmp += (BackupRegister * 4U); - - /* Write the specified register */ - *(__IO uint32_t *)tmp = (uint32_t)Data; -} - -/** - * @brief Reads data from the specified RTC Backup data Register. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param BackupRegister RTC Backup data Register number. - * This parameter can be: RTC_BKP_DRx where x can be from 0 to 19 to - * specify the register. - * @retval Read value - */ -uint32_t HAL_RTCEx_BKUPRead(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister) -{ - uint32_t tmp = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_BKP(BackupRegister)); - - tmp = (uint32_t)&(hrtc->Instance->BKP0R); - tmp += (BackupRegister * 4U); - - /* Read the specified register */ - return (*(__IO uint32_t *)tmp); -} - -/** - * @brief Sets the Coarse calibration parameters. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param CalibSign Specifies the sign of the coarse calibration value. - * This parameter can be one of the following values : - * @arg RTC_CALIBSIGN_POSITIVE: The value sign is positive - * @arg RTC_CALIBSIGN_NEGATIVE: The value sign is negative - * @param Value value of coarse calibration expressed in ppm (coded on 5 bits). - * - * @note This Calibration value should be between 0 and 63 when using negative - * sign with a 2-ppm step. - * - * @note This Calibration value should be between 0 and 126 when using positive - * sign with a 4-ppm step. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetCoarseCalib(RTC_HandleTypeDef* hrtc, uint32_t CalibSign, uint32_t Value) -{ - /* Check the parameters */ - assert_param(IS_RTC_CALIB_SIGN(CalibSign)); - assert_param(IS_RTC_CALIB_VALUE(Value)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set Initialization mode */ - if(RTC_EnterInitMode(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state*/ - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - else - { - /* Enable the Coarse Calibration */ - __HAL_RTC_COARSE_CALIB_ENABLE(hrtc); - - /* Set the coarse calibration value */ - hrtc->Instance->CALIBR = (uint32_t)(CalibSign|Value); - - /* Exit Initialization mode */ - hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Deactivates the Coarse calibration parameters. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_DeactivateCoarseCalib(RTC_HandleTypeDef* hrtc) -{ - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set Initialization mode */ - if(RTC_EnterInitMode(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state*/ - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - else - { - /* Enable the Coarse Calibration */ - __HAL_RTC_COARSE_CALIB_DISABLE(hrtc); - - /* Exit Initialization mode */ - hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Sets the Smooth calibration parameters. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param SmoothCalibPeriod Select the Smooth Calibration Period. - * This parameter can be can be one of the following values : - * @arg RTC_SMOOTHCALIB_PERIOD_32SEC: The smooth calibration period is 32s. - * @arg RTC_SMOOTHCALIB_PERIOD_16SEC: The smooth calibration period is 16s. - * @arg RTC_SMOOTHCALIB_PERIOD_8SEC: The smooth calibration period is 8s. - * @param SmoothCalibPlusPulses Select to Set or reset the CALP bit. - * This parameter can be one of the following values: - * @arg RTC_SMOOTHCALIB_PLUSPULSES_SET: Add one RTCCLK pulse every 2*11 pulses. - * @arg RTC_SMOOTHCALIB_PLUSPULSES_RESET: No RTCCLK pulses are added. - * @param SmouthCalibMinusPulsesValue Select the value of CALM[80] bits. - * This parameter can be one any value from 0 to 0x000001FF. - * @note To deactivate the smooth calibration, the field SmoothCalibPlusPulses - * must be equal to SMOOTHCALIB_PLUSPULSES_RESET and the field - * SmouthCalibMinusPulsesValue must be equal to 0. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetSmoothCalib(RTC_HandleTypeDef* hrtc, uint32_t SmoothCalibPeriod, uint32_t SmoothCalibPlusPulses, uint32_t SmouthCalibMinusPulsesValue) -{ - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_SMOOTH_CALIB_PERIOD(SmoothCalibPeriod)); - assert_param(IS_RTC_SMOOTH_CALIB_PLUS(SmoothCalibPlusPulses)); - assert_param(IS_RTC_SMOOTH_CALIB_MINUS(SmouthCalibMinusPulsesValue)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* check if a calibration is pending*/ - if((hrtc->Instance->ISR & RTC_ISR_RECALPF) != RESET) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* check if a calibration is pending*/ - while((hrtc->Instance->ISR & RTC_ISR_RECALPF) != RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - } - - /* Configure the Smooth calibration settings */ - hrtc->Instance->CALR = (uint32_t)((uint32_t)SmoothCalibPeriod | (uint32_t)SmoothCalibPlusPulses | (uint32_t)SmouthCalibMinusPulsesValue); - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Configures the Synchronization Shift Control Settings. - * @note When REFCKON is set, firmware must not write to Shift control register. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param ShiftAdd1S Select to add or not 1 second to the time calendar. - * This parameter can be one of the following values : - * @arg RTC_SHIFTADD1S_SET: Add one second to the clock calendar. - * @arg RTC_SHIFTADD1S_RESET: No effect. - * @param ShiftSubFS Select the number of Second Fractions to substitute. - * This parameter can be one any value from 0 to 0x7FFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetSynchroShift(RTC_HandleTypeDef* hrtc, uint32_t ShiftAdd1S, uint32_t ShiftSubFS) -{ - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_RTC_SHIFT_ADD1S(ShiftAdd1S)); - assert_param(IS_RTC_SHIFT_SUBFS(ShiftSubFS)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until the shift is completed*/ - while((hrtc->Instance->ISR & RTC_ISR_SHPF) != RESET) - { - if((HAL_GetTick() - tickstart ) > RTC_TIMEOUT_VALUE) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_TIMEOUT; - } - } - - /* Check if the reference clock detection is disabled */ - if((hrtc->Instance->CR & RTC_CR_REFCKON) == RESET) - { - /* Configure the Shift settings */ - hrtc->Instance->SHIFTR = (uint32_t)(uint32_t)(ShiftSubFS) | (uint32_t)(ShiftAdd1S); - - /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ - if((hrtc->Instance->CR & RTC_CR_BYPSHAD) == RESET) - { - if(HAL_RTC_WaitForSynchro(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - } - } - else - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Configures the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param CalibOutput Select the Calibration output Selection . - * This parameter can be one of the following values: - * @arg RTC_CALIBOUTPUT_512HZ: A signal has a regular waveform at 512Hz. - * @arg RTC_CALIBOUTPUT_1HZ: A signal has a regular waveform at 1Hz. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetCalibrationOutPut(RTC_HandleTypeDef* hrtc, uint32_t CalibOutput) -{ - /* Check the parameters */ - assert_param(IS_RTC_CALIB_OUTPUT(CalibOutput)); - - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Clear flags before config */ - hrtc->Instance->CR &= (uint32_t)~RTC_CR_COSEL; - - /* Configure the RTC_CR register */ - hrtc->Instance->CR |= (uint32_t)CalibOutput; - - __HAL_RTC_CALIBRATION_OUTPUT_ENABLE(hrtc); - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Deactivates the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz). - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_DeactivateCalibrationOutPut(RTC_HandleTypeDef* hrtc) -{ - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - __HAL_RTC_CALIBRATION_OUTPUT_DISABLE(hrtc); - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Enables the RTC reference clock detection. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_SetRefClock(RTC_HandleTypeDef* hrtc) -{ - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set Initialization mode */ - if(RTC_EnterInitMode(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state*/ - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - else - { - __HAL_RTC_CLOCKREF_DETECTION_ENABLE(hrtc); - - /* Exit Initialization mode */ - hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Disable the RTC reference clock detection. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_DeactivateRefClock(RTC_HandleTypeDef* hrtc) -{ - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set Initialization mode */ - if(RTC_EnterInitMode(hrtc) != HAL_OK) - { - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Set RTC state*/ - hrtc->State = HAL_RTC_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_ERROR; - } - else - { - __HAL_RTC_CLOCKREF_DETECTION_DISABLE(hrtc); - - /* Exit Initialization mode */ - hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - } - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Enables the Bypass Shadow feature. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @note When the Bypass Shadow is enabled the calendar value are taken - * directly from the Calendar counter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_EnableBypassShadow(RTC_HandleTypeDef* hrtc) -{ - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set the BYPSHAD bit */ - hrtc->Instance->CR |= (uint8_t)RTC_CR_BYPSHAD; - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @brief Disables the Bypass Shadow feature. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @note When the Bypass Shadow is enabled the calendar value are taken - * directly from the Calendar counter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_DisableBypassShadow(RTC_HandleTypeDef* hrtc) -{ - /* Process Locked */ - __HAL_LOCK(hrtc); - - hrtc->State = HAL_RTC_STATE_BUSY; - - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Reset the BYPSHAD bit */ - hrtc->Instance->CR &= (uint8_t)~RTC_CR_BYPSHAD; - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hrtc); - - return HAL_OK; -} - -/** - * @} - */ - - /** @defgroup RTCEx_Exported_Functions_Group4 Extended features functions - * @brief Extended features functions - * -@verbatim - =============================================================================== - ##### Extended features functions ##### - =============================================================================== - [..] This section provides functions allowing to: - (+) RTC Alarm B callback - (+) RTC Poll for Alarm B request - -@endverbatim - * @{ - */ - -/** - * @brief Alarm B callback. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @retval None - */ -__weak void HAL_RTCEx_AlarmBEventCallback(RTC_HandleTypeDef *hrtc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hrtc); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_RTC_AlarmBEventCallback could be implemented in the user file - */ -} - -/** - * @brief This function handles AlarmB Polling request. - * @param hrtc pointer to a RTC_HandleTypeDef structure that contains - * the configuration information for RTC. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_RTCEx_PollForAlarmBEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - while(__HAL_RTC_ALARM_GET_FLAG(hrtc, RTC_FLAG_ALRBF) == RESET) - { - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - hrtc->State = HAL_RTC_STATE_TIMEOUT; - return HAL_TIMEOUT; - } - } - } - - /* Clear the Alarm Flag */ - __HAL_RTC_ALARM_CLEAR_FLAG(hrtc, RTC_FLAG_ALRBF); - - /* Change RTC state */ - hrtc->State = HAL_RTC_STATE_READY; - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_RTC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai.c deleted file mode 100644 index 7d157ccbca33096..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai.c +++ /dev/null @@ -1,2556 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sai.c - * @author MCD Application Team - * @brief SAI HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Serial Audio Interface (SAI) peripheral: - * + Initialization/de-initialization functions - * + I/O operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - - [..] - The SAI HAL driver can be used as follows: - - (#) Declare a SAI_HandleTypeDef handle structure (eg. SAI_HandleTypeDef hsai). - (#) Initialize the SAI low level resources by implementing the HAL_SAI_MspInit() API: - (##) Enable the SAI interface clock. - (##) SAI pins configuration: - (+++) Enable the clock for the SAI GPIOs. - (+++) Configure these SAI pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_SAI_Transmit_IT() - and HAL_SAI_Receive_IT() APIs): - (+++) Configure the SAI interrupt priority. - (+++) Enable the NVIC SAI IRQ handle. - - (##) DMA Configuration if you need to use DMA process (HAL_SAI_Transmit_DMA() - and HAL_SAI_Receive_DMA() APIs): - (+++) Declare a DMA handle structure for the Tx/Rx stream. - (+++) Enable the DMAx interface clock. - (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. - (+++) Configure the DMA Tx/Rx Stream. - (+++) Associate the initialized DMA handle to the SAI DMA Tx/Rx handle. - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the - DMA Tx/Rx Stream. - - (#) The initialization can be done by two ways - (##) Expert mode : Initialize the structures Init, FrameInit and SlotInit and call HAL_SAI_Init(). - (##) Simplified mode : Initialize the high part of Init Structure and call HAL_SAI_InitProtocol(). - - [..] - (@) The specific SAI interrupts (FIFO request and Overrun underrun interrupt) - will be managed using the macros __HAL_SAI_ENABLE_IT() and __HAL_SAI_DISABLE_IT() - inside the transmit and receive process. - - [..] - (@) SAI Clock Source configuration is managed differently depending on the selected - STM32F4 devices : - (+@) For STM32F446xx devices, the configuration is managed through RCCEx_PeriphCLKConfig() - function in the HAL RCC drivers - (+@) For STM32F439xx/STM32F437xx/STM32F429xx/STM32F427xx devices, the configuration - is managed within HAL SAI drivers through HAL_SAI_Init() function using - ClockSource field of SAI_InitTypeDef structure. - [..] - (@) Make sure that either: - (+@) I2S PLL is configured or - (+@) SAI PLL is configured or - (+@) External clock source is configured after setting correctly - the define constant EXTERNAL_CLOCK_VALUE in the stm32f4xx_hal_conf.h file. - [..] - (@) In master Tx mode: enabling the audio block immediately generates the bit clock - for the external slaves even if there is no data in the FIFO, However FS signal - generation is conditioned by the presence of data in the FIFO. - - [..] - (@) In master Rx mode: enabling the audio block immediately generates the bit clock - and FS signal for the external slaves. - - [..] - (@) It is mandatory to respect the following conditions in order to avoid bad SAI behavior: - (+@) First bit Offset <= (SLOT size - Data size) - (+@) Data size <= SLOT size - (+@) Number of SLOT x SLOT size = Frame length - (+@) The number of slots should be even when SAI_FS_CHANNEL_IDENTIFICATION is selected. - - [..] - Three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Send an amount of data in blocking mode using HAL_SAI_Transmit() - (+) Receive an amount of data in blocking mode using HAL_SAI_Receive() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Send an amount of data in non-blocking mode using HAL_SAI_Transmit_IT() - (+) At transmission end of transfer HAL_SAI_TxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SAI_TxCpltCallback() - (+) Receive an amount of data in non-blocking mode using HAL_SAI_Receive_IT() - (+) At reception end of transfer HAL_SAI_RxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SAI_RxCpltCallback() - (+) In case of flag error, HAL_SAI_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_SAI_ErrorCallback() - - *** DMA mode IO operation *** - ============================= - [..] - (+) Send an amount of data in non-blocking mode (DMA) using HAL_SAI_Transmit_DMA() - (+) At transmission end of transfer HAL_SAI_TxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SAI_TxCpltCallback() - (+) Receive an amount of data in non-blocking mode (DMA) using HAL_SAI_Receive_DMA() - (+) At reception end of transfer HAL_SAI_RxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SAI_RxCpltCallback() - (+) In case of flag error, HAL_SAI_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_SAI_ErrorCallback() - (+) Pause the DMA Transfer using HAL_SAI_DMAPause() - (+) Resume the DMA Transfer using HAL_SAI_DMAResume() - (+) Stop the DMA Transfer using HAL_SAI_DMAStop() - - *** SAI HAL driver additional function list *** - =============================================== - [..] - Below the list the others API available SAI HAL driver : - - (+) HAL_SAI_EnableTxMuteMode(): Enable the mute in tx mode - (+) HAL_SAI_DisableTxMuteMode(): Disable the mute in tx mode - (+) HAL_SAI_EnableRxMuteMode(): Enable the mute in Rx mode - (+) HAL_SAI_DisableRxMuteMode(): Disable the mute in Rx mode - (+) HAL_SAI_FlushRxFifo(): Flush the rx fifo. - (+) HAL_SAI_Abort(): Abort the current transfer - - *** SAI HAL driver macros list *** - ================================== - [..] - Below the list of most used macros in SAI HAL driver : - - (+) __HAL_SAI_ENABLE(): Enable the SAI peripheral - (+) __HAL_SAI_DISABLE(): Disable the SAI peripheral - (+) __HAL_SAI_ENABLE_IT(): Enable the specified SAI interrupts - (+) __HAL_SAI_DISABLE_IT(): Disable the specified SAI interrupts - (+) __HAL_SAI_GET_IT_SOURCE(): Check if the specified SAI interrupt source is - enabled or disabled - (+) __HAL_SAI_GET_FLAG(): Check whether the specified SAI flag is set or not - - *** Callback registration *** - ============================= - [..] - The compilation define USE_HAL_SAI_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use functions HAL_SAI_RegisterCallback() to register a user callback. - - [..] - Function HAL_SAI_RegisterCallback() allows to register following callbacks: - (+) RxCpltCallback : SAI receive complete. - (+) RxHalfCpltCallback : SAI receive half complete. - (+) TxCpltCallback : SAI transmit complete. - (+) TxHalfCpltCallback : SAI transmit half complete. - (+) ErrorCallback : SAI error. - (+) MspInitCallback : SAI MspInit. - (+) MspDeInitCallback : SAI MspDeInit. - [..] - This function takes as parameters the HAL peripheral handle, the callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_SAI_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - HAL_SAI_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the callback ID. - [..] - This function allows to reset following callbacks: - (+) RxCpltCallback : SAI receive complete. - (+) RxHalfCpltCallback : SAI receive half complete. - (+) TxCpltCallback : SAI transmit complete. - (+) TxHalfCpltCallback : SAI transmit half complete. - (+) ErrorCallback : SAI error. - (+) MspInitCallback : SAI MspInit. - (+) MspDeInitCallback : SAI MspDeInit. - - [..] - By default, after the HAL_SAI_Init and if the state is HAL_SAI_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions: - examples HAL_SAI_RxCpltCallback(), HAL_SAI_ErrorCallback(). - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the HAL_SAI_Init - and HAL_SAI_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_SAI_Init and HAL_SAI_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_SAI_RegisterCallback before calling HAL_SAI_DeInit - or HAL_SAI_Init function. - - [..] - When the compilation define USE_HAL_SAI_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SAI SAI - * @brief SAI HAL module driver - * @{ - */ - -#ifdef HAL_SAI_MODULE_ENABLED - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) - -/** @defgroup SAI_Private_Typedefs SAI Private Typedefs - * @{ - */ -typedef enum -{ - SAI_MODE_DMA, - SAI_MODE_IT -} SAI_ModeTypedef; -/** - * @} - */ - -/* Private define ------------------------------------------------------------*/ - -/** @defgroup SAI_Private_Constants SAI Private Constants - * @{ - */ -#define SAI_DEFAULT_TIMEOUT 4U /* 4ms */ -#define SAI_LONG_TIMEOUT 1000U /* 1s */ -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup SAI_Private_Functions SAI Private Functions - * @{ - */ -static void SAI_FillFifo(SAI_HandleTypeDef *hsai); -static uint32_t SAI_InterruptFlag(SAI_HandleTypeDef *hsai, uint32_t mode); -static HAL_StatusTypeDef SAI_InitI2S(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot); -static HAL_StatusTypeDef SAI_InitPCM(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot); - -static HAL_StatusTypeDef SAI_Disable(SAI_HandleTypeDef *hsai); -static void SAI_Transmit_IT8Bit(SAI_HandleTypeDef *hsai); -static void SAI_Transmit_IT16Bit(SAI_HandleTypeDef *hsai); -static void SAI_Transmit_IT32Bit(SAI_HandleTypeDef *hsai); -static void SAI_Receive_IT8Bit(SAI_HandleTypeDef *hsai); -static void SAI_Receive_IT16Bit(SAI_HandleTypeDef *hsai); -static void SAI_Receive_IT32Bit(SAI_HandleTypeDef *hsai); - -static void SAI_DMATxCplt(DMA_HandleTypeDef *hdma); -static void SAI_DMATxHalfCplt(DMA_HandleTypeDef *hdma); -static void SAI_DMARxCplt(DMA_HandleTypeDef *hdma); -static void SAI_DMARxHalfCplt(DMA_HandleTypeDef *hdma); -static void SAI_DMAError(DMA_HandleTypeDef *hdma); -static void SAI_DMAAbort(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ -/** @defgroup SAI_Exported_Functions SAI Exported Functions - * @{ - */ - -/** @defgroup SAI_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - de-initialize the SAIx peripheral: - - (+) User must implement HAL_SAI_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). - - (+) Call the function HAL_SAI_Init() to configure the selected device with - the selected configuration: - (++) Mode (Master/slave TX/RX) - (++) Protocol - (++) Data Size - (++) MCLK Output - (++) Audio frequency - (++) FIFO Threshold - (++) Frame Config - (++) Slot Config - - (+) Call the function HAL_SAI_DeInit() to restore the default configuration - of the selected SAI peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the structure FrameInit, SlotInit and the low part of - * Init according to the specified parameters and call the function - * HAL_SAI_Init to initialize the SAI block. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param protocol one of the supported protocol @ref SAI_Protocol - * @param datasize one of the supported datasize @ref SAI_Protocol_DataSize - * the configuration information for SAI module. - * @param nbslot Number of slot. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_InitProtocol(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_SAI_SUPPORTED_PROTOCOL(protocol)); - assert_param(IS_SAI_PROTOCOL_DATASIZE(datasize)); - - switch (protocol) - { - case SAI_I2S_STANDARD : - case SAI_I2S_MSBJUSTIFIED : - case SAI_I2S_LSBJUSTIFIED : - status = SAI_InitI2S(hsai, protocol, datasize, nbslot); - break; - case SAI_PCM_LONG : - case SAI_PCM_SHORT : - status = SAI_InitPCM(hsai, protocol, datasize, nbslot); - break; - default : - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - status = HAL_SAI_Init(hsai); - } - - return status; -} - -/** - * @brief Initialize the SAI according to the specified parameters. - * in the SAI_InitTypeDef structure and initialize the associated handle. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_Init(SAI_HandleTypeDef *hsai) -{ - uint32_t tmpregisterGCR = 0U; - - /* This variable used to store the SAI_CK_x (value in Hz) */ - uint32_t freq = 0U; - - /* This variable is used to compute CKSTR bits of SAI CR1 according to - ClockStrobing and AudioMode fields */ - uint32_t ckstr_bits = 0U; - uint32_t syncen_bits = 0U; - - /* Check the SAI handle allocation */ - if (hsai == NULL) - { - return HAL_ERROR; - } - - /* check the instance */ - assert_param(IS_SAI_ALL_INSTANCE(hsai->Instance)); - - /* Check the SAI Block parameters */ - assert_param(IS_SAI_AUDIO_FREQUENCY(hsai->Init.AudioFrequency)); - assert_param(IS_SAI_BLOCK_PROTOCOL(hsai->Init.Protocol)); - assert_param(IS_SAI_BLOCK_MODE(hsai->Init.AudioMode)); - assert_param(IS_SAI_BLOCK_SYNCEXT(hsai->Init.SynchroExt)); - assert_param(IS_SAI_BLOCK_DATASIZE(hsai->Init.DataSize)); - assert_param(IS_SAI_BLOCK_FIRST_BIT(hsai->Init.FirstBit)); - assert_param(IS_SAI_BLOCK_CLOCK_STROBING(hsai->Init.ClockStrobing)); - assert_param(IS_SAI_BLOCK_SYNCHRO(hsai->Init.Synchro)); - assert_param(IS_SAI_BLOCK_OUTPUT_DRIVE(hsai->Init.OutputDrive)); - assert_param(IS_SAI_BLOCK_NODIVIDER(hsai->Init.NoDivider)); - assert_param(IS_SAI_BLOCK_FIFO_THRESHOLD(hsai->Init.FIFOThreshold)); - assert_param(IS_SAI_MONO_STEREO_MODE(hsai->Init.MonoStereoMode)); - assert_param(IS_SAI_BLOCK_COMPANDING_MODE(hsai->Init.CompandingMode)); - assert_param(IS_SAI_BLOCK_TRISTATE_MANAGEMENT(hsai->Init.TriState)); - - /* Check the SAI Block Frame parameters */ - assert_param(IS_SAI_BLOCK_FRAME_LENGTH(hsai->FrameInit.FrameLength)); - assert_param(IS_SAI_BLOCK_ACTIVE_FRAME(hsai->FrameInit.ActiveFrameLength)); - assert_param(IS_SAI_BLOCK_FS_DEFINITION(hsai->FrameInit.FSDefinition)); - assert_param(IS_SAI_BLOCK_FS_POLARITY(hsai->FrameInit.FSPolarity)); - assert_param(IS_SAI_BLOCK_FS_OFFSET(hsai->FrameInit.FSOffset)); - - /* Check the SAI Block Slot parameters */ - assert_param(IS_SAI_BLOCK_FIRSTBIT_OFFSET(hsai->SlotInit.FirstBitOffset)); - assert_param(IS_SAI_BLOCK_SLOT_SIZE(hsai->SlotInit.SlotSize)); - assert_param(IS_SAI_BLOCK_SLOT_NUMBER(hsai->SlotInit.SlotNumber)); - assert_param(IS_SAI_SLOT_ACTIVE(hsai->SlotInit.SlotActive)); - - if (hsai->State == HAL_SAI_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hsai->Lock = HAL_UNLOCKED; - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - /* Reset callback pointers to the weak predefined callbacks */ - hsai->RxCpltCallback = HAL_SAI_RxCpltCallback; - hsai->RxHalfCpltCallback = HAL_SAI_RxHalfCpltCallback; - hsai->TxCpltCallback = HAL_SAI_TxCpltCallback; - hsai->TxHalfCpltCallback = HAL_SAI_TxHalfCpltCallback; - hsai->ErrorCallback = HAL_SAI_ErrorCallback; - - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - if (hsai->MspInitCallback == NULL) - { - hsai->MspInitCallback = HAL_SAI_MspInit; - } - hsai->MspInitCallback(hsai); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_SAI_MspInit(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - - hsai->State = HAL_SAI_STATE_BUSY; - - /* Disable the selected SAI peripheral */ - SAI_Disable(hsai); - - /* SAI Block Synchro Configuration -----------------------------------------*/ - SAI_BlockSynchroConfig(hsai); - - /* Configure Master Clock using the following formula : - MCLK_x = SAI_CK_x / (MCKDIV[3:0] * 2) with MCLK_x = 256 * FS - FS = SAI_CK_x / (MCKDIV[3:0] * 2) * 256 - MCKDIV[3:0] = SAI_CK_x / FS * 512 */ - if (hsai->Init.AudioFrequency != SAI_AUDIO_FREQUENCY_MCKDIV) - { - /* Get SAI clock source based on Source clock selection from RCC */ - freq = SAI_GetInputClock(hsai); - - /* (saiclocksource x 10) to keep Significant digits */ - tmpregisterGCR = (((freq * 10U) / ((hsai->Init.AudioFrequency) * 512U))); - - hsai->Init.Mckdiv = tmpregisterGCR / 10U; - - /* Round result to the nearest integer */ - if ((tmpregisterGCR % 10U) > 8U) - { - hsai->Init.Mckdiv += 1U; - } - - /* For SPDIF protocol, SAI shall provide a bit clock twice faster the symbol-rate */ - if (hsai->Init.Protocol == SAI_SPDIF_PROTOCOL) - { - hsai->Init.Mckdiv = hsai->Init.Mckdiv >> 1; - } - } - - /* Check the SAI Block master clock divider parameter */ - assert_param(IS_SAI_BLOCK_MASTER_DIVIDER(hsai->Init.Mckdiv)); - - /* Compute CKSTR bits of SAI CR1 according to ClockStrobing and AudioMode */ - if ((hsai->Init.AudioMode == SAI_MODEMASTER_TX) || (hsai->Init.AudioMode == SAI_MODESLAVE_TX)) - { - ckstr_bits = (hsai->Init.ClockStrobing == SAI_CLOCKSTROBING_RISINGEDGE) ? 0U : SAI_xCR1_CKSTR; - } - else - { - ckstr_bits = (hsai->Init.ClockStrobing == SAI_CLOCKSTROBING_RISINGEDGE) ? SAI_xCR1_CKSTR : 0U; - } - - /* SAI Block Configuration -------------------------------------------------*/ - switch (hsai->Init.Synchro) - { - case SAI_ASYNCHRONOUS : - { - syncen_bits = 0U; - } - break; - case SAI_SYNCHRONOUS : - { - syncen_bits = SAI_xCR1_SYNCEN_0; - } - break; - case SAI_SYNCHRONOUS_EXT_SAI1 : - case SAI_SYNCHRONOUS_EXT_SAI2 : - { - syncen_bits = SAI_xCR1_SYNCEN_1; - } - break; - default: - break; - } - - /* SAI CR1 Configuration */ - hsai->Instance->CR1 &= ~(SAI_xCR1_MODE | SAI_xCR1_PRTCFG | SAI_xCR1_DS | \ - SAI_xCR1_LSBFIRST | SAI_xCR1_CKSTR | SAI_xCR1_SYNCEN | \ - SAI_xCR1_MONO | SAI_xCR1_OUTDRIV | SAI_xCR1_DMAEN | \ - SAI_xCR1_NODIV | SAI_xCR1_MCKDIV); - - hsai->Instance->CR1 |= (hsai->Init.AudioMode | hsai->Init.Protocol | \ - hsai->Init.DataSize | hsai->Init.FirstBit | \ - ckstr_bits | syncen_bits | \ - hsai->Init.MonoStereoMode | hsai->Init.OutputDrive | \ - hsai->Init.NoDivider | (hsai->Init.Mckdiv << 20U)); - - /* SAI CR2 Configuration */ - hsai->Instance->CR2 &= ~(SAI_xCR2_FTH | SAI_xCR2_FFLUSH | SAI_xCR2_COMP | SAI_xCR2_CPL); - hsai->Instance->CR2 |= (hsai->Init.FIFOThreshold | hsai->Init.CompandingMode | hsai->Init.TriState); - - /* SAI Frame Configuration -----------------------------------------*/ - hsai->Instance->FRCR &= (~(SAI_xFRCR_FRL | SAI_xFRCR_FSALL | SAI_xFRCR_FSDEF | \ - SAI_xFRCR_FSPOL | SAI_xFRCR_FSOFF)); - hsai->Instance->FRCR |= ((hsai->FrameInit.FrameLength - 1U) | - hsai->FrameInit.FSOffset | - hsai->FrameInit.FSDefinition | - hsai->FrameInit.FSPolarity | - ((hsai->FrameInit.ActiveFrameLength - 1U) << 8U)); - - /* SAI Block_x SLOT Configuration ------------------------------------------*/ - /* This register has no meaning in AC 97 and SPDIF audio protocol */ - hsai->Instance->SLOTR &= ~(SAI_xSLOTR_FBOFF | SAI_xSLOTR_SLOTSZ | \ - SAI_xSLOTR_NBSLOT | SAI_xSLOTR_SLOTEN); - - hsai->Instance->SLOTR |= hsai->SlotInit.FirstBitOffset | hsai->SlotInit.SlotSize | \ - (hsai->SlotInit.SlotActive << 16U) | ((hsai->SlotInit.SlotNumber - 1U) << 8U); - - /* Initialize the error code */ - hsai->ErrorCode = HAL_SAI_ERROR_NONE; - - /* Initialize the SAI state */ - hsai->State = HAL_SAI_STATE_READY; - - /* Release Lock */ - __HAL_UNLOCK(hsai); - - return HAL_OK; -} - -/** - * @brief DeInitialize the SAI peripheral. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_DeInit(SAI_HandleTypeDef *hsai) -{ - /* Check the SAI handle allocation */ - if (hsai == NULL) - { - return HAL_ERROR; - } - - hsai->State = HAL_SAI_STATE_BUSY; - - /* Disabled All interrupt and clear all the flag */ - hsai->Instance->IMR = 0U; - hsai->Instance->CLRFR = 0xFFFFFFFFU; - - /* Disable the SAI */ - SAI_Disable(hsai); - - /* Flush the fifo */ - SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - if (hsai->MspDeInitCallback == NULL) - { - hsai->MspDeInitCallback = HAL_SAI_MspDeInit; - } - hsai->MspDeInitCallback(hsai); -#else - HAL_SAI_MspDeInit(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - - /* Initialize the error code */ - hsai->ErrorCode = HAL_SAI_ERROR_NONE; - - /* Initialize the SAI state */ - hsai->State = HAL_SAI_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hsai); - - return HAL_OK; -} - -/** - * @brief Initialize the SAI MSP. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -__weak void HAL_SAI_MspInit(SAI_HandleTypeDef *hsai) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsai); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SAI_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize the SAI MSP. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -__weak void HAL_SAI_MspDeInit(SAI_HandleTypeDef *hsai) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsai); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SAI_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -/** - * @brief Register a user SAI callback - * to be used instead of the weak predefined callback. - * @param hsai SAI handle. - * @param CallbackID ID of the callback to be registered. - * This parameter can be one of the following values: - * @arg @ref HAL_SAI_RX_COMPLETE_CB_ID receive complete callback ID. - * @arg @ref HAL_SAI_RX_HALFCOMPLETE_CB_ID receive half complete callback ID. - * @arg @ref HAL_SAI_TX_COMPLETE_CB_ID transmit complete callback ID. - * @arg @ref HAL_SAI_TX_HALFCOMPLETE_CB_ID transmit half complete callback ID. - * @arg @ref HAL_SAI_ERROR_CB_ID error callback ID. - * @arg @ref HAL_SAI_MSPINIT_CB_ID MSP init callback ID. - * @arg @ref HAL_SAI_MSPDEINIT_CB_ID MSP de-init callback ID. - * @param pCallback pointer to the callback function. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_SAI_RegisterCallback(SAI_HandleTypeDef *hsai, - HAL_SAI_CallbackIDTypeDef CallbackID, - pSAI_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* update the error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - else - { - if (HAL_SAI_STATE_READY == hsai->State) - { - switch (CallbackID) - { - case HAL_SAI_RX_COMPLETE_CB_ID : - hsai->RxCpltCallback = pCallback; - break; - case HAL_SAI_RX_HALFCOMPLETE_CB_ID : - hsai->RxHalfCpltCallback = pCallback; - break; - case HAL_SAI_TX_COMPLETE_CB_ID : - hsai->TxCpltCallback = pCallback; - break; - case HAL_SAI_TX_HALFCOMPLETE_CB_ID : - hsai->TxHalfCpltCallback = pCallback; - break; - case HAL_SAI_ERROR_CB_ID : - hsai->ErrorCallback = pCallback; - break; - case HAL_SAI_MSPINIT_CB_ID : - hsai->MspInitCallback = pCallback; - break; - case HAL_SAI_MSPDEINIT_CB_ID : - hsai->MspDeInitCallback = pCallback; - break; - default : - /* update the error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SAI_STATE_RESET == hsai->State) - { - switch (CallbackID) - { - case HAL_SAI_MSPINIT_CB_ID : - hsai->MspInitCallback = pCallback; - break; - case HAL_SAI_MSPDEINIT_CB_ID : - hsai->MspDeInitCallback = pCallback; - break; - default : - /* update the error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update the error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - } - return status; -} - -/** - * @brief Unregister a user SAI callback. - * SAI callback is redirected to the weak predefined callback. - * @param hsai SAI handle. - * @param CallbackID ID of the callback to be unregistered. - * This parameter can be one of the following values: - * @arg @ref HAL_SAI_RX_COMPLETE_CB_ID receive complete callback ID. - * @arg @ref HAL_SAI_RX_HALFCOMPLETE_CB_ID receive half complete callback ID. - * @arg @ref HAL_SAI_TX_COMPLETE_CB_ID transmit complete callback ID. - * @arg @ref HAL_SAI_TX_HALFCOMPLETE_CB_ID transmit half complete callback ID. - * @arg @ref HAL_SAI_ERROR_CB_ID error callback ID. - * @arg @ref HAL_SAI_MSPINIT_CB_ID MSP init callback ID. - * @arg @ref HAL_SAI_MSPDEINIT_CB_ID MSP de-init callback ID. - * @retval HAL status. - */ -HAL_StatusTypeDef HAL_SAI_UnRegisterCallback(SAI_HandleTypeDef *hsai, - HAL_SAI_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (HAL_SAI_STATE_READY == hsai->State) - { - switch (CallbackID) - { - case HAL_SAI_RX_COMPLETE_CB_ID : - hsai->RxCpltCallback = HAL_SAI_RxCpltCallback; - break; - case HAL_SAI_RX_HALFCOMPLETE_CB_ID : - hsai->RxHalfCpltCallback = HAL_SAI_RxHalfCpltCallback; - break; - case HAL_SAI_TX_COMPLETE_CB_ID : - hsai->TxCpltCallback = HAL_SAI_TxCpltCallback; - break; - case HAL_SAI_TX_HALFCOMPLETE_CB_ID : - hsai->TxHalfCpltCallback = HAL_SAI_TxHalfCpltCallback; - break; - case HAL_SAI_ERROR_CB_ID : - hsai->ErrorCallback = HAL_SAI_ErrorCallback; - break; - case HAL_SAI_MSPINIT_CB_ID : - hsai->MspInitCallback = HAL_SAI_MspInit; - break; - case HAL_SAI_MSPDEINIT_CB_ID : - hsai->MspDeInitCallback = HAL_SAI_MspDeInit; - break; - default : - /* update the error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SAI_STATE_RESET == hsai->State) - { - switch (CallbackID) - { - case HAL_SAI_MSPINIT_CB_ID : - hsai->MspInitCallback = HAL_SAI_MspInit; - break; - case HAL_SAI_MSPDEINIT_CB_ID : - hsai->MspDeInitCallback = HAL_SAI_MspDeInit; - break; - default : - /* update the error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update the error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - return status; -} -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup SAI_Exported_Functions_Group2 IO operation functions - * @brief Data transfers functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to manage the SAI data - transfers. - - (+) There are two modes of transfer: - (++) Blocking mode : The communication is performed in the polling mode. - The status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode : The communication is performed using Interrupts - or DMA. These functions return the status of the transfer startup. - The end of the data processing will be indicated through the - dedicated SAI IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - - (+) Blocking mode functions are : - (++) HAL_SAI_Transmit() - (++) HAL_SAI_Receive() - - (+) Non Blocking mode functions with Interrupt are : - (++) HAL_SAI_Transmit_IT() - (++) HAL_SAI_Receive_IT() - - (+) Non Blocking mode functions with DMA are : - (++) HAL_SAI_Transmit_DMA() - (++) HAL_SAI_Receive_DMA() - - (+) A set of Transfer Complete Callbacks are provided in non Blocking mode: - (++) HAL_SAI_TxCpltCallback() - (++) HAL_SAI_RxCpltCallback() - (++) HAL_SAI_ErrorCallback() - -@endverbatim - * @{ - */ - -/** - * @brief Transmit an amount of data in blocking mode. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_Transmit(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart = HAL_GetTick(); - - if ((pData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - if (hsai->State == HAL_SAI_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hsai); - - hsai->XferSize = Size; - hsai->XferCount = Size; - hsai->pBuffPtr = pData; - hsai->State = HAL_SAI_STATE_BUSY_TX; - hsai->ErrorCode = HAL_SAI_ERROR_NONE; - - /* Check if the SAI is already enabled */ - if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) - { - /* fill the fifo with data before to enabled the SAI */ - SAI_FillFifo(hsai); - /* Enable SAI peripheral */ - __HAL_SAI_ENABLE(hsai); - } - - while (hsai->XferCount > 0U) - { - /* Write data if the FIFO is not full */ - if ((hsai->Instance->SR & SAI_xSR_FLVL) != SAI_FIFOSTATUS_FULL) - { - if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) - { - hsai->Instance->DR = (*hsai->pBuffPtr++); - } - else if (hsai->Init.DataSize <= SAI_DATASIZE_16) - { - hsai->Instance->DR = *((uint16_t *)hsai->pBuffPtr); - hsai->pBuffPtr += 2U; - } - else - { - hsai->Instance->DR = *((uint32_t *)hsai->pBuffPtr); - hsai->pBuffPtr += 4U; - } - hsai->XferCount--; - } - else - { - /* Check for the Timeout */ - if ((Timeout != HAL_MAX_DELAY) && ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))) - { - /* Update error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_TIMEOUT; - - /* Clear all the flags */ - hsai->Instance->CLRFR = 0xFFFFFFFFU; - - /* Disable SAI peripheral */ - SAI_Disable(hsai); - - /* Flush the fifo */ - SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); - - /* Change the SAI state */ - hsai->State = HAL_SAI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_ERROR; - } - } - } - - hsai->State = HAL_SAI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in blocking mode. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be received - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_Receive(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart = HAL_GetTick(); - - if ((pData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - if (hsai->State == HAL_SAI_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hsai); - - hsai->pBuffPtr = pData; - hsai->XferSize = Size; - hsai->XferCount = Size; - hsai->State = HAL_SAI_STATE_BUSY_RX; - hsai->ErrorCode = HAL_SAI_ERROR_NONE; - - /* Check if the SAI is already enabled */ - if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) - { - /* Enable SAI peripheral */ - __HAL_SAI_ENABLE(hsai); - } - - /* Receive data */ - while (hsai->XferCount > 0U) - { - if ((hsai->Instance->SR & SAI_xSR_FLVL) != SAI_FIFOSTATUS_EMPTY) - { - if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) - { - (*hsai->pBuffPtr++) = hsai->Instance->DR; - } - else if (hsai->Init.DataSize <= SAI_DATASIZE_16) - { - *((uint16_t *)hsai->pBuffPtr) = hsai->Instance->DR; - hsai->pBuffPtr += 2U; - } - else - { - *((uint32_t *)hsai->pBuffPtr) = hsai->Instance->DR; - hsai->pBuffPtr += 4U; - } - hsai->XferCount--; - } - else - { - /* Check for the Timeout */ - if ((Timeout != HAL_MAX_DELAY) && ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout))) - { - /* Update error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_TIMEOUT; - - /* Clear all the flags */ - hsai->Instance->CLRFR = 0xFFFFFFFFU; - - /* Disable SAI peripheral */ - SAI_Disable(hsai); - - /* Flush the fifo */ - SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); - - /* Change the SAI state */ - hsai->State = HAL_SAI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_ERROR; - } - } - } - - hsai->State = HAL_SAI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Transmit an amount of data in non-blocking mode with Interrupt. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_Transmit_IT(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size) -{ - if ((pData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - if (hsai->State == HAL_SAI_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hsai); - - hsai->pBuffPtr = pData; - hsai->XferSize = Size; - hsai->XferCount = Size; - hsai->ErrorCode = HAL_SAI_ERROR_NONE; - hsai->State = HAL_SAI_STATE_BUSY_TX; - - if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) - { - hsai->InterruptServiceRoutine = SAI_Transmit_IT8Bit; - } - else if (hsai->Init.DataSize <= SAI_DATASIZE_16) - { - hsai->InterruptServiceRoutine = SAI_Transmit_IT16Bit; - } - else - { - hsai->InterruptServiceRoutine = SAI_Transmit_IT32Bit; - } - - /* Fill the fifo before starting the communication */ - SAI_FillFifo(hsai); - - /* Enable FRQ and OVRUDR interrupts */ - __HAL_SAI_ENABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); - - /* Check if the SAI is already enabled */ - if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) - { - /* Enable SAI peripheral */ - __HAL_SAI_ENABLE(hsai); - } - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in non-blocking mode with Interrupt. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_Receive_IT(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size) -{ - if ((pData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - if (hsai->State == HAL_SAI_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hsai); - - hsai->pBuffPtr = pData; - hsai->XferSize = Size; - hsai->XferCount = Size; - hsai->ErrorCode = HAL_SAI_ERROR_NONE; - hsai->State = HAL_SAI_STATE_BUSY_RX; - - if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) - { - hsai->InterruptServiceRoutine = SAI_Receive_IT8Bit; - } - else if (hsai->Init.DataSize <= SAI_DATASIZE_16) - { - hsai->InterruptServiceRoutine = SAI_Receive_IT16Bit; - } - else - { - hsai->InterruptServiceRoutine = SAI_Receive_IT32Bit; - } - - /* Enable TXE and OVRUDR interrupts */ - __HAL_SAI_ENABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); - - /* Check if the SAI is already enabled */ - if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) - { - /* Enable SAI peripheral */ - __HAL_SAI_ENABLE(hsai); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Pause the audio stream playing from the Media. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_DMAPause(SAI_HandleTypeDef *hsai) -{ - /* Process Locked */ - __HAL_LOCK(hsai); - - /* Pause the audio file playing by disabling the SAI DMA requests */ - hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_OK; -} - -/** - * @brief Resume the audio stream playing from the Media. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_DMAResume(SAI_HandleTypeDef *hsai) -{ - /* Process Locked */ - __HAL_LOCK(hsai); - - /* Enable the SAI DMA requests */ - hsai->Instance->CR1 |= SAI_xCR1_DMAEN; - - /* If the SAI peripheral is still not enabled, enable it */ - if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) - { - /* Enable SAI peripheral */ - __HAL_SAI_ENABLE(hsai); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_OK; -} - -/** - * @brief Stop the audio stream playing from the Media. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_DMAStop(SAI_HandleTypeDef *hsai) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process Locked */ - __HAL_LOCK(hsai); - - /* Disable the SAI DMA request */ - hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; - - /* Abort the SAI Tx DMA Stream */ - if ((hsai->hdmatx != NULL) && (hsai->State == HAL_SAI_STATE_BUSY_TX)) - { - if (HAL_DMA_Abort(hsai->hdmatx) != HAL_OK) - { - /* If the DMA Tx errorCode is different from DMA No Transfer then return Error */ - if (hsai->hdmatx->ErrorCode != HAL_DMA_ERROR_NO_XFER) - { - status = HAL_ERROR; - hsai->ErrorCode |= HAL_SAI_ERROR_DMA; - } - } - } - - /* Abort the SAI Rx DMA Stream */ - if ((hsai->hdmarx != NULL) && (hsai->State == HAL_SAI_STATE_BUSY_RX)) - { - if (HAL_DMA_Abort(hsai->hdmarx) != HAL_OK) - { - /* If the DMA Rx errorCode is different from DMA No Transfer then return Error */ - if (hsai->hdmarx->ErrorCode != HAL_DMA_ERROR_NO_XFER) - { - status = HAL_ERROR; - hsai->ErrorCode |= HAL_SAI_ERROR_DMA; - } - } - } - - /* Disable SAI peripheral */ - SAI_Disable(hsai); - - /* Flush the fifo */ - SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); - - /* Set hsai state to ready */ - hsai->State = HAL_SAI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return status; -} - -/** - * @brief Abort the current transfer and disable the SAI. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_Abort(SAI_HandleTypeDef *hsai) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process Locked */ - __HAL_LOCK(hsai); - - /* Check SAI DMA is enabled or not */ - if ((hsai->Instance->CR1 & SAI_xCR1_DMAEN) == SAI_xCR1_DMAEN) - { - /* Disable the SAI DMA request */ - hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; - - /* Abort the SAI Tx DMA Stream */ - if ((hsai->hdmatx != NULL) && (hsai->State == HAL_SAI_STATE_BUSY_TX)) - { - if (HAL_DMA_Abort(hsai->hdmatx) != HAL_OK) - { - /* If the DMA Tx errorCode is different from DMA No Transfer then return Error */ - if (hsai->hdmatx->ErrorCode != HAL_DMA_ERROR_NO_XFER) - { - status = HAL_ERROR; - hsai->ErrorCode |= HAL_SAI_ERROR_DMA; - } - } - } - - /* Abort the SAI Rx DMA Stream */ - if ((hsai->hdmarx != NULL) && (hsai->State == HAL_SAI_STATE_BUSY_RX)) - { - if (HAL_DMA_Abort(hsai->hdmarx) != HAL_OK) - { - /* If the DMA Rx errorCode is different from DMA No Transfer then return Error */ - if (hsai->hdmarx->ErrorCode != HAL_DMA_ERROR_NO_XFER) - { - status = HAL_ERROR; - hsai->ErrorCode |= HAL_SAI_ERROR_DMA; - } - } - } - } - - /* Disabled All interrupt and clear all the flag */ - hsai->Instance->IMR = 0U; - hsai->Instance->CLRFR = 0xFFFFFFFFU; - - /* Disable SAI peripheral */ - SAI_Disable(hsai); - - /* Flush the fifo */ - SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); - - /* Set hsai state to ready */ - hsai->State = HAL_SAI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return status; -} - -/** - * @brief Transmit an amount of data in non-blocking mode with DMA. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_Transmit_DMA(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size) -{ - uint32_t tickstart = HAL_GetTick(); - - if ((pData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - if (hsai->State == HAL_SAI_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hsai); - - hsai->pBuffPtr = pData; - hsai->XferSize = Size; - hsai->XferCount = Size; - hsai->ErrorCode = HAL_SAI_ERROR_NONE; - hsai->State = HAL_SAI_STATE_BUSY_TX; - - /* Set the SAI Tx DMA Half transfer complete callback */ - hsai->hdmatx->XferHalfCpltCallback = SAI_DMATxHalfCplt; - - /* Set the SAI TxDMA transfer complete callback */ - hsai->hdmatx->XferCpltCallback = SAI_DMATxCplt; - - /* Set the DMA error callback */ - hsai->hdmatx->XferErrorCallback = SAI_DMAError; - - /* Set the DMA Tx abort callback */ - hsai->hdmatx->XferAbortCallback = NULL; - - /* Enable the Tx DMA Stream */ - if (HAL_DMA_Start_IT(hsai->hdmatx, (uint32_t)hsai->pBuffPtr, (uint32_t)&hsai->Instance->DR, hsai->XferSize) != HAL_OK) - { - __HAL_UNLOCK(hsai); - return HAL_ERROR; - } - - /* Enable the interrupts for error handling */ - __HAL_SAI_ENABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_DMA)); - - /* Enable SAI Tx DMA Request */ - hsai->Instance->CR1 |= SAI_xCR1_DMAEN; - - /* Wait until FIFO is not empty */ - while ((hsai->Instance->SR & SAI_xSR_FLVL) == SAI_FIFOSTATUS_EMPTY) - { - /* Check for the Timeout */ - if ((HAL_GetTick() - tickstart) > SAI_LONG_TIMEOUT) - { - /* Update error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_TIMEOUT; - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_TIMEOUT; - } - } - - /* Check if the SAI is already enabled */ - if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == 0U) - { - /* Enable SAI peripheral */ - __HAL_SAI_ENABLE(hsai); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in non-blocking mode with DMA. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_Receive_DMA(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size) -{ - if ((pData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - if (hsai->State == HAL_SAI_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hsai); - - hsai->pBuffPtr = pData; - hsai->XferSize = Size; - hsai->XferCount = Size; - hsai->ErrorCode = HAL_SAI_ERROR_NONE; - hsai->State = HAL_SAI_STATE_BUSY_RX; - - /* Set the SAI Rx DMA Half transfer complete callback */ - hsai->hdmarx->XferHalfCpltCallback = SAI_DMARxHalfCplt; - - /* Set the SAI Rx DMA transfer complete callback */ - hsai->hdmarx->XferCpltCallback = SAI_DMARxCplt; - - /* Set the DMA error callback */ - hsai->hdmarx->XferErrorCallback = SAI_DMAError; - - /* Set the DMA Rx abort callback */ - hsai->hdmarx->XferAbortCallback = NULL; - - /* Enable the Rx DMA Stream */ - if (HAL_DMA_Start_IT(hsai->hdmarx, (uint32_t)&hsai->Instance->DR, (uint32_t)hsai->pBuffPtr, hsai->XferSize) != HAL_OK) - { - __HAL_UNLOCK(hsai); - return HAL_ERROR; - } - - /* Enable the interrupts for error handling */ - __HAL_SAI_ENABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_DMA)); - - /* Enable SAI Rx DMA Request */ - hsai->Instance->CR1 |= SAI_xCR1_DMAEN; - - /* Check if the SAI is already enabled */ - if ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) == RESET) - { - /* Enable SAI peripheral */ - __HAL_SAI_ENABLE(hsai); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsai); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Enable the Tx mute mode. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param val value sent during the mute @ref SAI_Block_Mute_Value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_EnableTxMuteMode(SAI_HandleTypeDef *hsai, uint16_t val) -{ - assert_param(IS_SAI_BLOCK_MUTE_VALUE(val)); - - if (hsai->State != HAL_SAI_STATE_RESET) - { - CLEAR_BIT(hsai->Instance->CR2, SAI_xCR2_MUTEVAL | SAI_xCR2_MUTE); - SET_BIT(hsai->Instance->CR2, SAI_xCR2_MUTE | val); - return HAL_OK; - } - return HAL_ERROR; -} - -/** - * @brief Disable the Tx mute mode. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_DisableTxMuteMode(SAI_HandleTypeDef *hsai) -{ - if (hsai->State != HAL_SAI_STATE_RESET) - { - CLEAR_BIT(hsai->Instance->CR2, SAI_xCR2_MUTEVAL | SAI_xCR2_MUTE); - return HAL_OK; - } - return HAL_ERROR; -} - -/** - * @brief Enable the Rx mute detection. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param callback function called when the mute is detected. - * @param counter number a data before mute detection max 63. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_EnableRxMuteMode(SAI_HandleTypeDef *hsai, SAIcallback callback, uint16_t counter) -{ - assert_param(IS_SAI_BLOCK_MUTE_COUNTER(counter)); - - if (hsai->State != HAL_SAI_STATE_RESET) - { - /* set the mute counter */ - CLEAR_BIT(hsai->Instance->CR2, SAI_xCR2_MUTECNT); - SET_BIT(hsai->Instance->CR2, (uint32_t)((uint32_t)counter << SAI_xCR2_MUTECNT_Pos)); - hsai->mutecallback = callback; - /* enable the IT interrupt */ - __HAL_SAI_ENABLE_IT(hsai, SAI_IT_MUTEDET); - return HAL_OK; - } - return HAL_ERROR; -} - -/** - * @brief Disable the Rx mute detection. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SAI_DisableRxMuteMode(SAI_HandleTypeDef *hsai) -{ - if (hsai->State != HAL_SAI_STATE_RESET) - { - /* set the mutecallback to NULL */ - hsai->mutecallback = (SAIcallback)NULL; - /* enable the IT interrupt */ - __HAL_SAI_DISABLE_IT(hsai, SAI_IT_MUTEDET); - return HAL_OK; - } - return HAL_ERROR; -} - -/** - * @brief Handle SAI interrupt request. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -void HAL_SAI_IRQHandler(SAI_HandleTypeDef *hsai) -{ - if (hsai->State != HAL_SAI_STATE_RESET) - { - uint32_t itflags = hsai->Instance->SR; - uint32_t itsources = hsai->Instance->IMR; - uint32_t cr1config = hsai->Instance->CR1; - uint32_t tmperror; - - /* SAI Fifo request interrupt occurred ------------------------------------*/ - if (((itflags & SAI_xSR_FREQ) == SAI_xSR_FREQ) && ((itsources & SAI_IT_FREQ) == SAI_IT_FREQ)) - { - hsai->InterruptServiceRoutine(hsai); - } - /* SAI Overrun error interrupt occurred ----------------------------------*/ - else if (((itflags & SAI_FLAG_OVRUDR) == SAI_FLAG_OVRUDR) && ((itsources & SAI_IT_OVRUDR) == SAI_IT_OVRUDR)) - { - /* Clear the SAI Overrun flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_OVRUDR); - - /* Get the SAI error code */ - tmperror = ((hsai->State == HAL_SAI_STATE_BUSY_RX) ? HAL_SAI_ERROR_OVR : HAL_SAI_ERROR_UDR); - - /* Change the SAI error code */ - hsai->ErrorCode |= tmperror; - - /* the transfer is not stopped, we will forward the information to the user and we let the user decide what needs to be done */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->ErrorCallback(hsai); -#else - HAL_SAI_ErrorCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - /* SAI mutedet interrupt occurred ----------------------------------*/ - else if (((itflags & SAI_FLAG_MUTEDET) == SAI_FLAG_MUTEDET) && ((itsources & SAI_IT_MUTEDET) == SAI_IT_MUTEDET)) - { - /* Clear the SAI mutedet flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_MUTEDET); - - /* call the call back function */ - if (hsai->mutecallback != (SAIcallback)NULL) - { - /* inform the user that an RX mute event has been detected */ - hsai->mutecallback(); - } - } - /* SAI AFSDET interrupt occurred ----------------------------------*/ - else if (((itflags & SAI_FLAG_AFSDET) == SAI_FLAG_AFSDET) && ((itsources & SAI_IT_AFSDET) == SAI_IT_AFSDET)) - { - /* Clear the SAI AFSDET flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_AFSDET); - - /* Change the SAI error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_AFSDET; - - /* Check SAI DMA is enabled or not */ - if ((cr1config & SAI_xCR1_DMAEN) == SAI_xCR1_DMAEN) - { - /* Abort the SAI DMA Streams */ - if (hsai->hdmatx != NULL) - { - /* Set the DMA Tx abort callback */ - hsai->hdmatx->XferAbortCallback = SAI_DMAAbort; - - /* Abort DMA in IT mode */ - HAL_DMA_Abort_IT(hsai->hdmatx); - } - else if (hsai->hdmarx != NULL) - { - /* Set the DMA Rx abort callback */ - hsai->hdmarx->XferAbortCallback = SAI_DMAAbort; - - /* Abort DMA in IT mode */ - HAL_DMA_Abort_IT(hsai->hdmarx); - } - } - else - { - /* Abort SAI */ - HAL_SAI_Abort(hsai); - - /* Set error callback */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->ErrorCallback(hsai); -#else - HAL_SAI_ErrorCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - } - /* SAI LFSDET interrupt occurred ----------------------------------*/ - else if (((itflags & SAI_FLAG_LFSDET) == SAI_FLAG_LFSDET) && ((itsources & SAI_IT_LFSDET) == SAI_IT_LFSDET)) - { - /* Clear the SAI LFSDET flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_LFSDET); - - /* Change the SAI error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_LFSDET; - - /* Check SAI DMA is enabled or not */ - if ((cr1config & SAI_xCR1_DMAEN) == SAI_xCR1_DMAEN) - { - /* Abort the SAI DMA Streams */ - if (hsai->hdmatx != NULL) - { - /* Set the DMA Tx abort callback */ - hsai->hdmatx->XferAbortCallback = SAI_DMAAbort; - - /* Abort DMA in IT mode */ - HAL_DMA_Abort_IT(hsai->hdmatx); - } - else if (hsai->hdmarx != NULL) - { - /* Set the DMA Rx abort callback */ - hsai->hdmarx->XferAbortCallback = SAI_DMAAbort; - - /* Abort DMA in IT mode */ - HAL_DMA_Abort_IT(hsai->hdmarx); - } - } - else - { - /* Abort SAI */ - HAL_SAI_Abort(hsai); - - /* Set error callback */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->ErrorCallback(hsai); -#else - HAL_SAI_ErrorCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - } - /* SAI WCKCFG interrupt occurred ----------------------------------*/ - else if (((itflags & SAI_FLAG_WCKCFG) == SAI_FLAG_WCKCFG) && ((itsources & SAI_IT_WCKCFG) == SAI_IT_WCKCFG)) - { - /* Clear the SAI WCKCFG flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_WCKCFG); - - /* Change the SAI error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_WCKCFG; - - /* Check SAI DMA is enabled or not */ - if ((cr1config & SAI_xCR1_DMAEN) == SAI_xCR1_DMAEN) - { - /* Abort the SAI DMA Streams */ - if (hsai->hdmatx != NULL) - { - /* Set the DMA Tx abort callback */ - hsai->hdmatx->XferAbortCallback = SAI_DMAAbort; - - /* Abort DMA in IT mode */ - HAL_DMA_Abort_IT(hsai->hdmatx); - } - else if (hsai->hdmarx != NULL) - { - /* Set the DMA Rx abort callback */ - hsai->hdmarx->XferAbortCallback = SAI_DMAAbort; - - /* Abort DMA in IT mode */ - HAL_DMA_Abort_IT(hsai->hdmarx); - } - } - else - { - /* If WCKCFG occurs, SAI audio block is automatically disabled */ - /* Disable all interrupts and clear all flags */ - hsai->Instance->IMR = 0U; - hsai->Instance->CLRFR = 0xFFFFFFFFU; - - /* Set the SAI state to ready to be able to start again the process */ - hsai->State = HAL_SAI_STATE_READY; - - /* Initialize XferCount */ - hsai->XferCount = 0U; - - /* SAI error Callback */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->ErrorCallback(hsai); -#else - HAL_SAI_ErrorCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - } - /* SAI CNRDY interrupt occurred ----------------------------------*/ - else if (((itflags & SAI_FLAG_CNRDY) == SAI_FLAG_CNRDY) && ((itsources & SAI_IT_CNRDY) == SAI_IT_CNRDY)) - { - /* Clear the SAI CNRDY flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_CNRDY); - - /* Change the SAI error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_CNREADY; - - /* the transfer is not stopped, we will forward the information to the user and we let the user decide what needs to be done */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->ErrorCallback(hsai); -#else - HAL_SAI_ErrorCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - else - { - /* Nothing to do */ - } - } -} - -/** - * @brief Tx Transfer completed callback. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -__weak void HAL_SAI_TxCpltCallback(SAI_HandleTypeDef *hsai) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsai); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SAI_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx Transfer Half completed callback. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -__weak void HAL_SAI_TxHalfCpltCallback(SAI_HandleTypeDef *hsai) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsai); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SAI_TxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callback. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -__weak void HAL_SAI_RxCpltCallback(SAI_HandleTypeDef *hsai) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsai); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SAI_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer half completed callback. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -__weak void HAL_SAI_RxHalfCpltCallback(SAI_HandleTypeDef *hsai) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsai); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SAI_RxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief SAI error callback. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -__weak void HAL_SAI_ErrorCallback(SAI_HandleTypeDef *hsai) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsai); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SAI_ErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup SAI_Exported_Functions_Group3 Peripheral State functions - * @brief Peripheral State functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the SAI handle state. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval HAL state - */ -HAL_SAI_StateTypeDef HAL_SAI_GetState(SAI_HandleTypeDef *hsai) -{ - return hsai->State; -} - -/** - * @brief Return the SAI error code. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for the specified SAI Block. - * @retval SAI Error Code - */ -uint32_t HAL_SAI_GetError(SAI_HandleTypeDef *hsai) -{ - return hsai->ErrorCode; -} -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup SAI_Private_Functions - * @brief Private functions - * @{ - */ - -/** - * @brief Initialize the SAI I2S protocol according to the specified parameters - * in the SAI_InitTypeDef and create the associated handle. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param protocol one of the supported protocol. - * @param datasize one of the supported datasize @ref SAI_Protocol_DataSize - * the configuration information for SAI module. - * @param nbslot number of slot minimum value is 2 and max is 16. - * the value must be a multiple of 2. - * @retval HAL status - */ -static HAL_StatusTypeDef SAI_InitI2S(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot) -{ - hsai->Init.Protocol = SAI_FREE_PROTOCOL; - hsai->Init.FirstBit = SAI_FIRSTBIT_MSB; - /* Compute ClockStrobing according AudioMode */ - if ((hsai->Init.AudioMode == SAI_MODEMASTER_TX) || (hsai->Init.AudioMode == SAI_MODESLAVE_TX)) - { - /* Transmit */ - hsai->Init.ClockStrobing = SAI_CLOCKSTROBING_FALLINGEDGE; - } - else - { - /* Receive */ - hsai->Init.ClockStrobing = SAI_CLOCKSTROBING_RISINGEDGE; - } - hsai->FrameInit.FSDefinition = SAI_FS_CHANNEL_IDENTIFICATION; - hsai->SlotInit.SlotActive = SAI_SLOTACTIVE_ALL; - hsai->SlotInit.FirstBitOffset = 0U; - hsai->SlotInit.SlotNumber = nbslot; - - /* in IS2 the number of slot must be even */ - if ((nbslot & 0x1U) != 0U) - { - return HAL_ERROR; - } - - if (protocol == SAI_I2S_STANDARD) - { - hsai->FrameInit.FSPolarity = SAI_FS_ACTIVE_LOW; - hsai->FrameInit.FSOffset = SAI_FS_BEFOREFIRSTBIT; - } - else - { - /* SAI_I2S_MSBJUSTIFIED or SAI_I2S_LSBJUSTIFIED */ - hsai->FrameInit.FSPolarity = SAI_FS_ACTIVE_HIGH; - hsai->FrameInit.FSOffset = SAI_FS_FIRSTBIT; - } - - /* Frame definition */ - switch (datasize) - { - case SAI_PROTOCOL_DATASIZE_16BIT: - hsai->Init.DataSize = SAI_DATASIZE_16; - hsai->FrameInit.FrameLength = 32U * (nbslot / 2U); - hsai->FrameInit.ActiveFrameLength = 16U * (nbslot / 2U); - hsai->SlotInit.SlotSize = SAI_SLOTSIZE_16B; - break; - case SAI_PROTOCOL_DATASIZE_16BITEXTENDED : - hsai->Init.DataSize = SAI_DATASIZE_16; - hsai->FrameInit.FrameLength = 64U * (nbslot / 2U); - hsai->FrameInit.ActiveFrameLength = 32U * (nbslot / 2U); - hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; - break; - case SAI_PROTOCOL_DATASIZE_24BIT: - hsai->Init.DataSize = SAI_DATASIZE_24; - hsai->FrameInit.FrameLength = 64U * (nbslot / 2U); - hsai->FrameInit.ActiveFrameLength = 32U * (nbslot / 2U); - hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; - break; - case SAI_PROTOCOL_DATASIZE_32BIT: - hsai->Init.DataSize = SAI_DATASIZE_32; - hsai->FrameInit.FrameLength = 64U * (nbslot / 2U); - hsai->FrameInit.ActiveFrameLength = 32U * (nbslot / 2U); - hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; - break; - default : - return HAL_ERROR; - } - if (protocol == SAI_I2S_LSBJUSTIFIED) - { - if (datasize == SAI_PROTOCOL_DATASIZE_16BITEXTENDED) - { - hsai->SlotInit.FirstBitOffset = 16U; - } - if (datasize == SAI_PROTOCOL_DATASIZE_24BIT) - { - hsai->SlotInit.FirstBitOffset = 8U; - } - } - return HAL_OK; -} - -/** - * @brief Initialize the SAI PCM protocol according to the specified parameters - * in the SAI_InitTypeDef and create the associated handle. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param protocol one of the supported protocol - * @param datasize one of the supported datasize @ref SAI_Protocol_DataSize - * @param nbslot number of slot minimum value is 1 and the max is 16. - * @retval HAL status - */ -static HAL_StatusTypeDef SAI_InitPCM(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot) -{ - hsai->Init.Protocol = SAI_FREE_PROTOCOL; - hsai->Init.FirstBit = SAI_FIRSTBIT_MSB; - /* Compute ClockStrobing according AudioMode */ - if ((hsai->Init.AudioMode == SAI_MODEMASTER_TX) || (hsai->Init.AudioMode == SAI_MODESLAVE_TX)) - { - /* Transmit */ - hsai->Init.ClockStrobing = SAI_CLOCKSTROBING_RISINGEDGE; - } - else - { - /* Receive */ - hsai->Init.ClockStrobing = SAI_CLOCKSTROBING_FALLINGEDGE; - } - hsai->FrameInit.FSDefinition = SAI_FS_STARTFRAME; - hsai->FrameInit.FSPolarity = SAI_FS_ACTIVE_HIGH; - hsai->FrameInit.FSOffset = SAI_FS_BEFOREFIRSTBIT; - hsai->SlotInit.FirstBitOffset = 0U; - hsai->SlotInit.SlotNumber = nbslot; - hsai->SlotInit.SlotActive = SAI_SLOTACTIVE_ALL; - - if (protocol == SAI_PCM_SHORT) - { - hsai->FrameInit.ActiveFrameLength = 1; - } - else - { - /* SAI_PCM_LONG */ - hsai->FrameInit.ActiveFrameLength = 13; - } - - switch (datasize) - { - case SAI_PROTOCOL_DATASIZE_16BIT: - hsai->Init.DataSize = SAI_DATASIZE_16; - hsai->FrameInit.FrameLength = 16U * nbslot; - hsai->SlotInit.SlotSize = SAI_SLOTSIZE_16B; - break; - case SAI_PROTOCOL_DATASIZE_16BITEXTENDED : - hsai->Init.DataSize = SAI_DATASIZE_16; - hsai->FrameInit.FrameLength = 32U * nbslot; - hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; - break; - case SAI_PROTOCOL_DATASIZE_24BIT : - hsai->Init.DataSize = SAI_DATASIZE_24; - hsai->FrameInit.FrameLength = 32U * nbslot; - hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; - break; - case SAI_PROTOCOL_DATASIZE_32BIT: - hsai->Init.DataSize = SAI_DATASIZE_32; - hsai->FrameInit.FrameLength = 32U * nbslot; - hsai->SlotInit.SlotSize = SAI_SLOTSIZE_32B; - break; - default : - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief Fill the fifo. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -static void SAI_FillFifo(SAI_HandleTypeDef *hsai) -{ - /* fill the fifo with data before to enabled the SAI */ - while (((hsai->Instance->SR & SAI_xSR_FLVL) != SAI_FIFOSTATUS_FULL) && (hsai->XferCount > 0U)) - { - if ((hsai->Init.DataSize == SAI_DATASIZE_8) && (hsai->Init.CompandingMode == SAI_NOCOMPANDING)) - { - hsai->Instance->DR = (*hsai->pBuffPtr++); - } - else if (hsai->Init.DataSize <= SAI_DATASIZE_16) - { - hsai->Instance->DR = *((uint32_t *)hsai->pBuffPtr); - hsai->pBuffPtr += 2U; - } - else - { - hsai->Instance->DR = *((uint32_t *)hsai->pBuffPtr); - hsai->pBuffPtr += 4U; - } - hsai->XferCount--; - } -} - -/** - * @brief Return the interrupt flag to set according the SAI setup. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @param mode SAI_MODE_DMA or SAI_MODE_IT - * @retval the list of the IT flag to enable - */ -static uint32_t SAI_InterruptFlag(SAI_HandleTypeDef *hsai, uint32_t mode) -{ - uint32_t tmpIT = SAI_IT_OVRUDR; - - if (mode == SAI_MODE_IT) - { - tmpIT |= SAI_IT_FREQ; - } - - if ((hsai->Init.Protocol == SAI_AC97_PROTOCOL) && - ((hsai->Init.AudioMode == SAI_MODESLAVE_RX) || (hsai->Init.AudioMode == SAI_MODEMASTER_RX))) - { - tmpIT |= SAI_IT_CNRDY; - } - - if ((hsai->Init.AudioMode == SAI_MODESLAVE_RX) || (hsai->Init.AudioMode == SAI_MODESLAVE_TX)) - { - tmpIT |= SAI_IT_AFSDET | SAI_IT_LFSDET; - } - else - { - /* hsai has been configured in master mode */ - tmpIT |= SAI_IT_WCKCFG; - } - return tmpIT; -} - -/** - * @brief Disable the SAI and wait for the disabling. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -static HAL_StatusTypeDef SAI_Disable(SAI_HandleTypeDef *hsai) -{ - uint32_t count = SAI_DEFAULT_TIMEOUT * (SystemCoreClock / 7U / 1000U); - HAL_StatusTypeDef status = HAL_OK; - - /* Disable the SAI instance */ - __HAL_SAI_DISABLE(hsai); - - do - { - /* Check for the Timeout */ - if (count-- == 0U) - { - /* Update error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_TIMEOUT; - status = HAL_TIMEOUT; - break; - } - } - while ((hsai->Instance->CR1 & SAI_xCR1_SAIEN) != RESET); - - return status; -} - -/** - * @brief Tx Handler for Transmit in Interrupt mode 8-Bit transfer. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -static void SAI_Transmit_IT8Bit(SAI_HandleTypeDef *hsai) -{ - if (hsai->XferCount == 0U) - { - /* Handle the end of the transmission */ - /* Disable FREQ and OVRUDR interrupts */ - __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); - hsai->State = HAL_SAI_STATE_READY; -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->TxCpltCallback(hsai); -#else - HAL_SAI_TxCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - else - { - /* Write data on DR register */ - hsai->Instance->DR = (*hsai->pBuffPtr++); - hsai->XferCount--; - } -} - -/** - * @brief Tx Handler for Transmit in Interrupt mode for 16-Bit transfer. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -static void SAI_Transmit_IT16Bit(SAI_HandleTypeDef *hsai) -{ - if (hsai->XferCount == 0U) - { - /* Handle the end of the transmission */ - /* Disable FREQ and OVRUDR interrupts */ - __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); - hsai->State = HAL_SAI_STATE_READY; -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->TxCpltCallback(hsai); -#else - HAL_SAI_TxCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - else - { - /* Write data on DR register */ - hsai->Instance->DR = *(uint16_t *)hsai->pBuffPtr; - hsai->pBuffPtr += 2U; - hsai->XferCount--; - } -} - -/** - * @brief Tx Handler for Transmit in Interrupt mode for 32-Bit transfer. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -static void SAI_Transmit_IT32Bit(SAI_HandleTypeDef *hsai) -{ - if (hsai->XferCount == 0U) - { - /* Handle the end of the transmission */ - /* Disable FREQ and OVRUDR interrupts */ - __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); - hsai->State = HAL_SAI_STATE_READY; -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->TxCpltCallback(hsai); -#else - HAL_SAI_TxCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } - else - { - /* Write data on DR register */ - hsai->Instance->DR = *(uint32_t *)hsai->pBuffPtr; - hsai->pBuffPtr += 4U; - hsai->XferCount--; - } -} - -/** - * @brief Rx Handler for Receive in Interrupt mode 8-Bit transfer. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -static void SAI_Receive_IT8Bit(SAI_HandleTypeDef *hsai) -{ - /* Receive data */ - (*hsai->pBuffPtr++) = hsai->Instance->DR; - hsai->XferCount--; - - /* Check end of the transfer */ - if (hsai->XferCount == 0U) - { - /* Disable TXE and OVRUDR interrupts */ - __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); - - /* Clear the SAI Overrun flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_OVRUDR); - - hsai->State = HAL_SAI_STATE_READY; -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->RxCpltCallback(hsai); -#else - HAL_SAI_RxCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Rx Handler for Receive in Interrupt mode for 16-Bit transfer. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -static void SAI_Receive_IT16Bit(SAI_HandleTypeDef *hsai) -{ - /* Receive data */ - *(uint16_t *)hsai->pBuffPtr = hsai->Instance->DR; - hsai->pBuffPtr += 2U; - hsai->XferCount--; - - /* Check end of the transfer */ - if (hsai->XferCount == 0U) - { - /* Disable TXE and OVRUDR interrupts */ - __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); - - /* Clear the SAI Overrun flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_OVRUDR); - - hsai->State = HAL_SAI_STATE_READY; -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->RxCpltCallback(hsai); -#else - HAL_SAI_RxCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Rx Handler for Receive in Interrupt mode for 32-Bit transfer. - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval None - */ -static void SAI_Receive_IT32Bit(SAI_HandleTypeDef *hsai) -{ - /* Receive data */ - *(uint32_t *)hsai->pBuffPtr = hsai->Instance->DR; - hsai->pBuffPtr += 4U; - hsai->XferCount--; - - /* Check end of the transfer */ - if (hsai->XferCount == 0U) - { - /* Disable TXE and OVRUDR interrupts */ - __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_IT)); - - /* Clear the SAI Overrun flag */ - __HAL_SAI_CLEAR_FLAG(hsai, SAI_FLAG_OVRUDR); - - hsai->State = HAL_SAI_STATE_READY; -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->RxCpltCallback(hsai); -#else - HAL_SAI_RxCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA SAI transmit process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SAI_DMATxCplt(DMA_HandleTypeDef *hdma) -{ - SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma->Init.Mode != DMA_CIRCULAR) - { - hsai->XferCount = 0U; - - /* Disable SAI Tx DMA Request */ - hsai->Instance->CR1 &= (uint32_t)(~SAI_xCR1_DMAEN); - - /* Stop the interrupts error handling */ - __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_DMA)); - - hsai->State = HAL_SAI_STATE_READY; - } -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->TxCpltCallback(hsai); -#else - HAL_SAI_TxCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SAI transmit process half complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SAI_DMATxHalfCplt(DMA_HandleTypeDef *hdma) -{ - SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->TxHalfCpltCallback(hsai); -#else - HAL_SAI_TxHalfCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SAI receive process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SAI_DMARxCplt(DMA_HandleTypeDef *hdma) -{ - SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma->Init.Mode != DMA_CIRCULAR) - { - /* Disable Rx DMA Request */ - hsai->Instance->CR1 &= (uint32_t)(~SAI_xCR1_DMAEN); - hsai->XferCount = 0U; - - /* Stop the interrupts error handling */ - __HAL_SAI_DISABLE_IT(hsai, SAI_InterruptFlag(hsai, SAI_MODE_DMA)); - - hsai->State = HAL_SAI_STATE_READY; - } -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->RxCpltCallback(hsai); -#else - HAL_SAI_RxCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SAI receive process half complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SAI_DMARxHalfCplt(DMA_HandleTypeDef *hdma) -{ - SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->RxHalfCpltCallback(hsai); -#else - HAL_SAI_RxHalfCpltCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SAI communication error callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SAI_DMAError(DMA_HandleTypeDef *hdma) -{ - SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Set SAI error code */ - hsai->ErrorCode |= HAL_SAI_ERROR_DMA; - - if ((hsai->hdmatx->ErrorCode == HAL_DMA_ERROR_TE) || (hsai->hdmarx->ErrorCode == HAL_DMA_ERROR_TE)) - { - /* Disable the SAI DMA request */ - hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; - - /* Disable SAI peripheral */ - SAI_Disable(hsai); - - /* Set the SAI state ready to be able to start again the process */ - hsai->State = HAL_SAI_STATE_READY; - - /* Initialize XferCount */ - hsai->XferCount = 0U; - } - /* SAI error Callback */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->ErrorCallback(hsai); -#else - HAL_SAI_ErrorCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SAI Abort callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SAI_DMAAbort(DMA_HandleTypeDef *hdma) -{ - SAI_HandleTypeDef *hsai = (SAI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Disable DMA request */ - hsai->Instance->CR1 &= ~SAI_xCR1_DMAEN; - - /* Disable all interrupts and clear all flags */ - hsai->Instance->IMR = 0U; - hsai->Instance->CLRFR = 0xFFFFFFFFU; - - if (hsai->ErrorCode != HAL_SAI_ERROR_WCKCFG) - { - /* Disable SAI peripheral */ - SAI_Disable(hsai); - - /* Flush the fifo */ - SET_BIT(hsai->Instance->CR2, SAI_xCR2_FFLUSH); - } - /* Set the SAI state to ready to be able to start again the process */ - hsai->State = HAL_SAI_STATE_READY; - - /* Initialize XferCount */ - hsai->XferCount = 0U; - - /* SAI error Callback */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - hsai->ErrorCallback(hsai); -#else - HAL_SAI_ErrorCallback(hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -} - -/** - * @} - */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ -#endif /* HAL_SAI_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai_ex.c deleted file mode 100644 index 120a27774732ca2..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sai_ex.c +++ /dev/null @@ -1,311 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sai_ex.c - * @author MCD Application Team - * @brief SAI Extension HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of SAI extension peripheral: - * + Extension features functions - * - @verbatim - ============================================================================== - ##### SAI peripheral extension features ##### - ============================================================================== - - [..] Comparing to other previous devices, the SAI interface for STM32F446xx - devices contains the following additional features : - - (+) Possibility to be clocked from PLLR - - ##### How to use this driver ##### - ============================================================================== - [..] This driver provides functions to manage several sources to clock SAI - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SAIEx SAIEx - * @brief SAI Extension HAL module driver - * @{ - */ - -#ifdef HAL_SAI_MODULE_ENABLED - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || \ - defined(STM32F423xx) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* SAI registers Masks */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** @defgroup SAI_Private_Functions SAI Private Functions - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SAIEx_Exported_Functions SAI Extended Exported Functions - * @{ - */ - -/** @defgroup SAIEx_Exported_Functions_Group1 Extension features functions - * @brief Extension features functions - * -@verbatim - =============================================================================== - ##### Extension features Functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the possible - SAI clock sources. - -@endverbatim - * @{ - */ - -/** - * @brief Configure SAI Block synchronization mode - * @param hsai pointer to a SAI_HandleTypeDef structure that contains - * the configuration information for SAI module. - * @retval SAI Clock Input - */ -void SAI_BlockSynchroConfig(SAI_HandleTypeDef *hsai) -{ - uint32_t tmpregisterGCR; - -#if defined(STM32F446xx) - /* This setting must be done with both audio block (A & B) disabled */ - switch (hsai->Init.SynchroExt) - { - case SAI_SYNCEXT_DISABLE : - tmpregisterGCR = 0U; - break; - case SAI_SYNCEXT_OUTBLOCKA_ENABLE : - tmpregisterGCR = SAI_GCR_SYNCOUT_0; - break; - case SAI_SYNCEXT_OUTBLOCKB_ENABLE : - tmpregisterGCR = SAI_GCR_SYNCOUT_1; - break; - default: - tmpregisterGCR = 0U; - break; - } - - if ((hsai->Init.Synchro) == SAI_SYNCHRONOUS_EXT_SAI2) - { - tmpregisterGCR |= SAI_GCR_SYNCIN_0; - } - - if ((hsai->Instance == SAI1_Block_A) || (hsai->Instance == SAI1_Block_B)) - { - SAI1->GCR = tmpregisterGCR; - } - else - { - SAI2->GCR = tmpregisterGCR; - } -#endif /* STM32F446xx */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || defined(STM32F423xx) - /* This setting must be done with both audio block (A & B) disabled */ - switch (hsai->Init.SynchroExt) - { - case SAI_SYNCEXT_DISABLE : - tmpregisterGCR = 0U; - break; - case SAI_SYNCEXT_OUTBLOCKA_ENABLE : - tmpregisterGCR = SAI_GCR_SYNCOUT_0; - break; - case SAI_SYNCEXT_OUTBLOCKB_ENABLE : - tmpregisterGCR = SAI_GCR_SYNCOUT_1; - break; - default: - tmpregisterGCR = 0U; - break; - } - SAI1->GCR = tmpregisterGCR; -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ -} -/** -* @brief Get SAI Input Clock based on SAI source clock selection -* @param hsai pointer to a SAI_HandleTypeDef structure that contains -* the configuration information for SAI module. -* @retval SAI Clock Input -*/ -uint32_t SAI_GetInputClock(SAI_HandleTypeDef *hsai) -{ - /* This variable used to store the SAI_CK_x (value in Hz) */ - uint32_t saiclocksource = 0U; - -#if defined(STM32F446xx) - if ((hsai->Instance == SAI1_Block_A) || (hsai->Instance == SAI1_Block_B)) - { - saiclocksource = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_SAI1); - } - else /* SAI2_Block_A || SAI2_Block_B*/ - { - saiclocksource = HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_SAI2); - } -#endif /* STM32F446xx */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || defined(STM32F423xx) - uint32_t vcoinput = 0U, tmpreg = 0U; - - /* Check the SAI Block parameters */ - assert_param(IS_SAI_CLK_SOURCE(hsai->Init.ClockSource)); - - /* SAI Block clock source selection */ - if (hsai->Instance == SAI1_Block_A) - { - __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(hsai->Init.ClockSource); - } - else - { - __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG((uint32_t)(hsai->Init.ClockSource << 2U)); - } - - /* VCO Input Clock value calculation */ - if ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSI) - { - /* In Case the PLL Source is HSI (Internal Clock) */ - vcoinput = (HSI_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM)); - } - else - { - /* In Case the PLL Source is HSE (External Clock) */ - vcoinput = ((HSE_VALUE / (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM))); - } -#if defined(STM32F413xx) || defined(STM32F423xx) - /* SAI_CLK_x : SAI Block Clock configuration for different clock sources selected */ - if (hsai->Init.ClockSource == SAI_CLKSOURCE_PLLR) - { - /* Configure the PLLI2S division factor */ - /* PLL_VCO Input = PLL_SOURCE/PLLM */ - /* PLL_VCO Output = PLL_VCO Input * PLLN */ - /* SAI_CLK(first level) = PLL_VCO Output/PLLR */ - tmpreg = (RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 28U; - saiclocksource = (vcoinput * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6U)) / (tmpreg); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLDIVR */ - tmpreg = (((RCC->DCKCFGR & RCC_DCKCFGR_PLLDIVR) >> 8U) + 1U); - - saiclocksource = saiclocksource / (tmpreg); - - } - else if (hsai->Init.ClockSource == SAI_CLKSOURCE_PLLI2S) - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SR */ - tmpreg = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28U; - saiclocksource = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U)) / (tmpreg); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVR */ - tmpreg = ((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVR) + 1U); - saiclocksource = saiclocksource / (tmpreg); - } - else if (hsai->Init.ClockSource == SAI_CLKSOURCE_HS) - { - if ((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLSOURCE_HSE) - { - /* Get the I2S source clock value */ - saiclocksource = (uint32_t)(HSE_VALUE); - } - else - { - /* Get the I2S source clock value */ - saiclocksource = (uint32_t)(HSI_VALUE); - } - } - else /* sConfig->ClockSource == SAI_CLKSource_Ext */ - { - saiclocksource = EXTERNAL_CLOCK_VALUE; - } -#else - /* SAI_CLK_x : SAI Block Clock configuration for different clock sources selected */ - if (hsai->Init.ClockSource == SAI_CLKSOURCE_PLLSAI) - { - /* Configure the PLLI2S division factor */ - /* PLLSAI_VCO Input = PLL_SOURCE/PLLM */ - /* PLLSAI_VCO Output = PLLSAI_VCO Input * PLLSAIN */ - /* SAI_CLK(first level) = PLLSAI_VCO Output/PLLSAIQ */ - tmpreg = (RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIQ) >> 24U; - saiclocksource = (vcoinput * ((RCC->PLLSAICFGR & RCC_PLLSAICFGR_PLLSAIN) >> 6U)) / (tmpreg); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLSAIDIVQ */ - tmpreg = (((RCC->DCKCFGR & RCC_DCKCFGR_PLLSAIDIVQ) >> 8U) + 1U); - saiclocksource = saiclocksource / (tmpreg); - - } - else if (hsai->Init.ClockSource == SAI_CLKSOURCE_PLLI2S) - { - /* Configure the PLLI2S division factor */ - /* PLLI2S_VCO Input = PLL_SOURCE/PLLM */ - /* PLLI2S_VCO Output = PLLI2S_VCO Input * PLLI2SN */ - /* SAI_CLK(first level) = PLLI2S_VCO Output/PLLI2SQ */ - tmpreg = (RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SQ) >> 24U; - saiclocksource = (vcoinput * ((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6U)) / (tmpreg); - - /* SAI_CLK_x = SAI_CLK(first level)/PLLI2SDIVQ */ - tmpreg = ((RCC->DCKCFGR & RCC_DCKCFGR_PLLI2SDIVQ) + 1U); - saiclocksource = saiclocksource / (tmpreg); - } - else /* sConfig->ClockSource == SAI_CLKSource_Ext */ - { - /* Enable the External Clock selection */ - __HAL_RCC_I2S_CONFIG(RCC_I2SCLKSOURCE_EXT); - - saiclocksource = EXTERNAL_CLOCK_VALUE; - } -#endif /* STM32F413xx || STM32F423xx */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ - /* the return result is the value of SAI clock */ - return saiclocksource; -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ -#endif /* HAL_SAI_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c deleted file mode 100644 index 0c7b13bc9e9640c..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sd.c +++ /dev/null @@ -1,3276 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sd.c - * @author MCD Application Team - * @brief SD card HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Secure Digital (SD) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - This driver implements a high level communication layer for read and write from/to - this memory. The needed STM32 hardware resources (SDIO and GPIO) are performed by - the user in HAL_SD_MspInit() function (MSP layer). - Basically, the MSP layer configuration should be the same as we provide in the - examples. - You can easily tailor this configuration according to hardware resources. - - [..] - This driver is a generic layered driver for SDIO memories which uses the HAL - SDIO driver functions to interface with SD and uSD cards devices. - It is used as follows: - - (#)Initialize the SDIO low level resources by implementing the HAL_SD_MspInit() API: - (##) Enable the SDIO interface clock using __HAL_RCC_SDIO_CLK_ENABLE(); - (##) SDIO pins configuration for SD card - (+++) Enable the clock for the SDIO GPIOs using the functions __HAL_RCC_GPIOx_CLK_ENABLE(); - (+++) Configure these SDIO pins as alternate function pull-up using HAL_GPIO_Init() - and according to your pin assignment; - (##) DMA configuration if you need to use DMA process (HAL_SD_ReadBlocks_DMA() - and HAL_SD_WriteBlocks_DMA() APIs). - (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE(); - (+++) Configure the DMA using the function HAL_DMA_Init() with predeclared and filled. - (##) NVIC configuration if you need to use interrupt process when using DMA transfer. - (+++) Configure the SDIO and DMA interrupt priorities using functions - HAL_NVIC_SetPriority(); DMA priority is superior to SDIO's priority - (+++) Enable the NVIC DMA and SDIO IRQs using function HAL_NVIC_EnableIRQ() - (+++) SDIO interrupts are managed using the macros __HAL_SD_ENABLE_IT() - and __HAL_SD_DISABLE_IT() inside the communication process. - (+++) SDIO interrupts pending bits are managed using the macros __HAL_SD_GET_IT() - and __HAL_SD_CLEAR_IT() - (##) NVIC configuration if you need to use interrupt process (HAL_SD_ReadBlocks_IT() - and HAL_SD_WriteBlocks_IT() APIs). - (+++) Configure the SDIO interrupt priorities using function HAL_NVIC_SetPriority(); - (+++) Enable the NVIC SDIO IRQs using function HAL_NVIC_EnableIRQ() - (+++) SDIO interrupts are managed using the macros __HAL_SD_ENABLE_IT() - and __HAL_SD_DISABLE_IT() inside the communication process. - (+++) SDIO interrupts pending bits are managed using the macros __HAL_SD_GET_IT() - and __HAL_SD_CLEAR_IT() - (#) At this stage, you can perform SD read/write/erase operations after SD card initialization - - - *** SD Card Initialization and configuration *** - ================================================ - [..] - To initialize the SD Card, use the HAL_SD_Init() function. It Initializes - SDIO Peripheral(STM32 side) and the SD Card, and put it into StandBy State (Ready for data transfer). - This function provide the following operations: - - (#) Apply the SD Card initialization process at 400KHz and check the SD Card - type (Standard Capacity or High Capacity). You can change or adapt this - frequency by adjusting the "ClockDiv" field. - The SD Card frequency (SDIO_CK) is computed as follows: - - SDIO_CK = SDIOCLK / (ClockDiv + 2) - - In initialization mode and according to the SD Card standard, - make sure that the SDIO_CK frequency doesn't exceed 400KHz. - - This phase of initialization is done through SDIO_Init() and - SDIO_PowerState_ON() SDIO low level APIs. - - (#) Initialize the SD card. The API used is HAL_SD_InitCard(). - This phase allows the card initialization and identification - and check the SD Card type (Standard Capacity or High Capacity) - The initialization flow is compatible with SD standard. - - This API (HAL_SD_InitCard()) could be used also to reinitialize the card in case - of plug-off plug-in. - - (#) Configure the SD Card Data transfer frequency. You can change or adapt this - frequency by adjusting the "ClockDiv" field. - In transfer mode and according to the SD Card standard, make sure that the - SDIO_CK frequency doesn't exceed 25MHz and 50MHz in High-speed mode switch. - To be able to use a frequency higher than 24MHz, you should use the SDIO - peripheral in bypass mode. Refer to the corresponding reference manual - for more details. - - (#) Select the corresponding SD Card according to the address read with the step 2. - - (#) Configure the SD Card in wide bus mode: 4-bits data. - - *** SD Card Read operation *** - ============================== - [..] - (+) You can read from SD card in polling mode by using function HAL_SD_ReadBlocks(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_SD_GetCardState() function for SD card state. - - (+) You can read from SD card in DMA mode by using function HAL_SD_ReadBlocks_DMA(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_SD_GetCardState() function for SD card state. - You could also check the DMA transfer process through the SD Rx interrupt event. - - (+) You can read from SD card in Interrupt mode by using function HAL_SD_ReadBlocks_IT(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_SD_GetCardState() function for SD card state. - You could also check the IT transfer process through the SD Rx interrupt event. - - *** SD Card Write operation *** - =============================== - [..] - (+) You can write to SD card in polling mode by using function HAL_SD_WriteBlocks(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_SD_GetCardState() function for SD card state. - - (+) You can write to SD card in DMA mode by using function HAL_SD_WriteBlocks_DMA(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_SD_GetCardState() function for SD card state. - You could also check the DMA transfer process through the SD Tx interrupt event. - - (+) You can write to SD card in Interrupt mode by using function HAL_SD_WriteBlocks_IT(). - This function support only 512-bytes block length (the block size should be - chosen as 512 bytes). - You can choose either one block read operation or multiple block read operation - by adjusting the "NumberOfBlocks" parameter. - After this, you have to ensure that the transfer is done correctly. The check is done - through HAL_SD_GetCardState() function for SD card state. - You could also check the IT transfer process through the SD Tx interrupt event. - - *** SD card status *** - ====================== - [..] - (+) The SD Status contains status bits that are related to the SD Memory - Card proprietary features. To get SD card status use the HAL_SD_GetCardStatus(). - - *** SD card information *** - =========================== - [..] - (+) To get SD card information, you can use the function HAL_SD_GetCardInfo(). - It returns useful information about the SD card such as block size, card type, - block number ... - - *** SD card CSD register *** - ============================ - (+) The HAL_SD_GetCardCSD() API allows to get the parameters of the CSD register. - Some of the CSD parameters are useful for card initialization and identification. - - *** SD card CID register *** - ============================ - (+) The HAL_SD_GetCardCID() API allows to get the parameters of the CID register. - Some of the CSD parameters are useful for card initialization and identification. - - *** SD HAL driver macros list *** - ================================== - [..] - Below the list of most used macros in SD HAL driver. - - (+) __HAL_SD_ENABLE : Enable the SD device - (+) __HAL_SD_DISABLE : Disable the SD device - (+) __HAL_SD_DMA_ENABLE: Enable the SDIO DMA transfer - (+) __HAL_SD_DMA_DISABLE: Disable the SDIO DMA transfer - (+) __HAL_SD_ENABLE_IT: Enable the SD device interrupt - (+) __HAL_SD_DISABLE_IT: Disable the SD device interrupt - (+) __HAL_SD_GET_FLAG:Check whether the specified SD flag is set or not - (+) __HAL_SD_CLEAR_FLAG: Clear the SD's pending flags - - (@) You can refer to the SD HAL driver header file for more useful macros - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_SD_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions HAL_SD_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) TxCpltCallback : callback when a transmission transfer is completed. - (+) RxCpltCallback : callback when a reception transfer is completed. - (+) ErrorCallback : callback when error occurs. - (+) AbortCpltCallback : callback when abort is completed. - (+) MspInitCallback : SD MspInit. - (+) MspDeInitCallback : SD MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function HAL_SD_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) TxCpltCallback : callback when a transmission transfer is completed. - (+) RxCpltCallback : callback when a reception transfer is completed. - (+) ErrorCallback : callback when error occurs. - (+) AbortCpltCallback : callback when abort is completed. - (+) MspInitCallback : SD MspInit. - (+) MspDeInitCallback : SD MspDeInit. - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the HAL_SD_Init and if the state is HAL_SD_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the HAL_SD_Init - and HAL_SD_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_SD_Init and HAL_SD_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_SD_RegisterCallback before calling HAL_SD_DeInit - or HAL_SD_Init function. - - When The compilation define USE_HAL_SD_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -#if defined(SDIO) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SD - * @{ - */ - -#ifdef HAL_SD_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup SD_Private_Defines - * @{ - */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SD_Private_Functions SD Private Functions - * @{ - */ -static uint32_t SD_InitCard(SD_HandleTypeDef *hsd); -static uint32_t SD_PowerON(SD_HandleTypeDef *hsd); -static uint32_t SD_SendSDStatus(SD_HandleTypeDef *hsd, uint32_t *pSDstatus); -static uint32_t SD_SendStatus(SD_HandleTypeDef *hsd, uint32_t *pCardStatus); -static uint32_t SD_WideBus_Enable(SD_HandleTypeDef *hsd); -static uint32_t SD_WideBus_Disable(SD_HandleTypeDef *hsd); -static uint32_t SD_FindSCR(SD_HandleTypeDef *hsd, uint32_t *pSCR); -static void SD_PowerOFF(SD_HandleTypeDef *hsd); -static void SD_Write_IT(SD_HandleTypeDef *hsd); -static void SD_Read_IT(SD_HandleTypeDef *hsd); -static void SD_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void SD_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void SD_DMAError(DMA_HandleTypeDef *hdma); -static void SD_DMATxAbort(DMA_HandleTypeDef *hdma); -static void SD_DMARxAbort(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SD_Exported_Functions - * @{ - */ - -/** @addtogroup SD_Exported_Functions_Group1 - * @brief Initialization and de-initialization functions - * -@verbatim - ============================================================================== - ##### Initialization and de-initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to initialize/de-initialize the SD - card device to be ready for use. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the SD according to the specified parameters in the - SD_HandleTypeDef and create the associated handle. - * @param hsd: Pointer to the SD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_Init(SD_HandleTypeDef *hsd) -{ - /* Check the SD handle allocation */ - if(hsd == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SDIO_ALL_INSTANCE(hsd->Instance)); - assert_param(IS_SDIO_CLOCK_EDGE(hsd->Init.ClockEdge)); - assert_param(IS_SDIO_CLOCK_BYPASS(hsd->Init.ClockBypass)); - assert_param(IS_SDIO_CLOCK_POWER_SAVE(hsd->Init.ClockPowerSave)); - assert_param(IS_SDIO_BUS_WIDE(hsd->Init.BusWide)); - assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(hsd->Init.HardwareFlowControl)); - assert_param(IS_SDIO_CLKDIV(hsd->Init.ClockDiv)); - - if(hsd->State == HAL_SD_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hsd->Lock = HAL_UNLOCKED; -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - /* Reset Callback pointers in HAL_SD_STATE_RESET only */ - hsd->TxCpltCallback = HAL_SD_TxCpltCallback; - hsd->RxCpltCallback = HAL_SD_RxCpltCallback; - hsd->ErrorCallback = HAL_SD_ErrorCallback; - hsd->AbortCpltCallback = HAL_SD_AbortCallback; - - if(hsd->MspInitCallback == NULL) - { - hsd->MspInitCallback = HAL_SD_MspInit; - } - - /* Init the low level hardware */ - hsd->MspInitCallback(hsd); -#else - /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ - HAL_SD_MspInit(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - - hsd->State = HAL_SD_STATE_BUSY; - - /* Initialize the Card parameters */ - if (HAL_SD_InitCard(hsd) != HAL_OK) - { - return HAL_ERROR; - } - - /* Initialize the error code */ - hsd->ErrorCode = HAL_SD_ERROR_NONE; - - /* Initialize the SD operation */ - hsd->Context = SD_CONTEXT_NONE; - - /* Initialize the SD state */ - hsd->State = HAL_SD_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initializes the SD Card. - * @param hsd: Pointer to SD handle - * @note This function initializes the SD card. It could be used when a card - re-initialization is needed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_InitCard(SD_HandleTypeDef *hsd) -{ - uint32_t errorstate; - HAL_StatusTypeDef status; - SD_InitTypeDef Init; - - /* Default SDIO peripheral configuration for SD card initialization */ - Init.ClockEdge = SDIO_CLOCK_EDGE_RISING; - Init.ClockBypass = SDIO_CLOCK_BYPASS_DISABLE; - Init.ClockPowerSave = SDIO_CLOCK_POWER_SAVE_DISABLE; - Init.BusWide = SDIO_BUS_WIDE_1B; - Init.HardwareFlowControl = SDIO_HARDWARE_FLOW_CONTROL_DISABLE; - Init.ClockDiv = SDIO_INIT_CLK_DIV; - - /* Initialize SDIO peripheral interface with default configuration */ - status = SDIO_Init(hsd->Instance, Init); - if(status != HAL_OK) - { - return HAL_ERROR; - } - - /* Disable SDIO Clock */ - __HAL_SD_DISABLE(hsd); - - /* Set Power State to ON */ - (void)SDIO_PowerState_ON(hsd->Instance); - - /* Enable SDIO Clock */ - __HAL_SD_ENABLE(hsd); - - /* Identify card operating voltage */ - errorstate = SD_PowerON(hsd); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->State = HAL_SD_STATE_READY; - hsd->ErrorCode |= errorstate; - return HAL_ERROR; - } - - /* Card initialization */ - errorstate = SD_InitCard(hsd); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->State = HAL_SD_STATE_READY; - hsd->ErrorCode |= errorstate; - return HAL_ERROR; - } - - /* Set Block Size for Card */ - errorstate = SDMMC_CmdBlockLength(hsd->Instance, BLOCKSIZE); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief De-Initializes the SD card. - * @param hsd: Pointer to SD handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_DeInit(SD_HandleTypeDef *hsd) -{ - /* Check the SD handle allocation */ - if(hsd == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SDIO_ALL_INSTANCE(hsd->Instance)); - - hsd->State = HAL_SD_STATE_BUSY; - - /* Set SD power state to off */ - SD_PowerOFF(hsd); - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - if(hsd->MspDeInitCallback == NULL) - { - hsd->MspDeInitCallback = HAL_SD_MspDeInit; - } - - /* DeInit the low level hardware */ - hsd->MspDeInitCallback(hsd); -#else - /* De-Initialize the MSP layer */ - HAL_SD_MspDeInit(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - - hsd->ErrorCode = HAL_SD_ERROR_NONE; - hsd->State = HAL_SD_STATE_RESET; - - return HAL_OK; -} - - -/** - * @brief Initializes the SD MSP. - * @param hsd: Pointer to SD handle - * @retval None - */ -__weak void HAL_SD_MspInit(SD_HandleTypeDef *hsd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SD_MspInit could be implemented in the user file - */ -} - -/** - * @brief De-Initialize SD MSP. - * @param hsd: Pointer to SD handle - * @retval None - */ -__weak void HAL_SD_MspDeInit(SD_HandleTypeDef *hsd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SD_MspDeInit could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @addtogroup SD_Exported_Functions_Group2 - * @brief Data transfer functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to manage the data - transfer from/to SD card. - -@endverbatim - * @{ - */ - -/** - * @brief Reads block(s) from a specified address in a card. The Data transfer - * is managed by polling mode. - * @note This API should be followed by a check on the card state through - * HAL_SD_GetCardState(). - * @param hsd: Pointer to SD handle - * @param pData: pointer to the buffer that will contain the received data - * @param BlockAdd: Block Address from where data is to be read - * @param NumberOfBlocks: Number of SD blocks to read - * @param Timeout: Specify timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_ReadBlocks(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t tickstart = HAL_GetTick(); - uint32_t count, data, dataremaining; - uint32_t add = BlockAdd; - uint8_t *tempbuff = pData; - - if(NULL == pData) - { - hsd->ErrorCode |= HAL_SD_ERROR_PARAM; - return HAL_ERROR; - } - - if(hsd->State == HAL_SD_STATE_READY) - { - hsd->ErrorCode = HAL_SD_ERROR_NONE; - - if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) - { - hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hsd->State = HAL_SD_STATE_BUSY; - - /* Initialize data control register */ - hsd->Instance->DCTRL = 0U; - - if(hsd->SdCard.CardType != CARD_SDHC_SDXC) - { - add *= 512U; - } - - /* Configure the SD DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = NumberOfBlocks * BLOCKSIZE; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hsd->Instance, &config); - - /* Read block(s) in polling mode */ - if(NumberOfBlocks > 1U) - { - hsd->Context = SD_CONTEXT_READ_MULTIPLE_BLOCK; - - /* Read Multi Block command */ - errorstate = SDMMC_CmdReadMultiBlock(hsd->Instance, add); - } - else - { - hsd->Context = SD_CONTEXT_READ_SINGLE_BLOCK; - - /* Read Single Block command */ - errorstate = SDMMC_CmdReadSingleBlock(hsd->Instance, add); - } - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - - /* Poll on SDIO flags */ - dataremaining = config.DataLength; -#if defined(SDIO_STA_STBITERR) - while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND | SDIO_FLAG_STBITERR)) -#else /* SDIO_STA_STBITERR not defined */ - while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) -#endif /* SDIO_STA_STBITERR */ - { - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXFIFOHF) && (dataremaining > 0U)) - { - /* Read data from SDIO Rx FIFO */ - for(count = 0U; count < 8U; count++) - { - data = SDIO_ReadFIFO(hsd->Instance); - *tempbuff = (uint8_t)(data & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 8U) & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 16U) & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 24U) & 0xFFU); - tempbuff++; - dataremaining--; - } - } - - if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_TIMEOUT; - hsd->State= HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_TIMEOUT; - } - } - - /* Send stop transmission command in case of multiblock read */ - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DATAEND) && (NumberOfBlocks > 1U)) - { - if(hsd->SdCard.CardType != CARD_SECURED) - { - /* Send stop transmission command */ - errorstate = SDMMC_CmdStopTransfer(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - } - } - - /* Get error state */ - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_DATA_TIMEOUT; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_DATA_CRC_FAIL; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_RX_OVERRUN; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - else - { - /* Nothing to do */ - } - - /* Empty FIFO if there is still any data */ - while ((__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXDAVL)) && (dataremaining > 0U)) - { - data = SDIO_ReadFIFO(hsd->Instance); - *tempbuff = (uint8_t)(data & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 8U) & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 16U) & 0xFFU); - tempbuff++; - dataremaining--; - *tempbuff = (uint8_t)((data >> 24U) & 0xFFU); - tempbuff++; - dataremaining--; - - if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_TIMEOUT; - hsd->State= HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - } - - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - hsd->State = HAL_SD_STATE_READY; - - return HAL_OK; - } - else - { - hsd->ErrorCode |= HAL_SD_ERROR_BUSY; - return HAL_ERROR; - } -} - -/** - * @brief Allows to write block(s) to a specified address in a card. The Data - * transfer is managed by polling mode. - * @note This API should be followed by a check on the card state through - * HAL_SD_GetCardState(). - * @param hsd: Pointer to SD handle - * @param pData: pointer to the buffer that will contain the data to transmit - * @param BlockAdd: Block Address where data will be written - * @param NumberOfBlocks: Number of SD blocks to write - * @param Timeout: Specify timeout value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_WriteBlocks(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t tickstart = HAL_GetTick(); - uint32_t count, data, dataremaining; - uint32_t add = BlockAdd; - uint8_t *tempbuff = pData; - - if(NULL == pData) - { - hsd->ErrorCode |= HAL_SD_ERROR_PARAM; - return HAL_ERROR; - } - - if(hsd->State == HAL_SD_STATE_READY) - { - hsd->ErrorCode = HAL_SD_ERROR_NONE; - - if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) - { - hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hsd->State = HAL_SD_STATE_BUSY; - - /* Initialize data control register */ - hsd->Instance->DCTRL = 0U; - - if(hsd->SdCard.CardType != CARD_SDHC_SDXC) - { - add *= 512U; - } - - /* Configure the SD DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = NumberOfBlocks * BLOCKSIZE; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hsd->Instance, &config); - - /* Write Blocks in Polling mode */ - if(NumberOfBlocks > 1U) - { - hsd->Context = SD_CONTEXT_WRITE_MULTIPLE_BLOCK; - - /* Write Multi Block command */ - errorstate = SDMMC_CmdWriteMultiBlock(hsd->Instance, add); - } - else - { - hsd->Context = SD_CONTEXT_WRITE_SINGLE_BLOCK; - - /* Write Single Block command */ - errorstate = SDMMC_CmdWriteSingleBlock(hsd->Instance, add); - } - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - - /* Write block(s) in polling mode */ - dataremaining = config.DataLength; -#if defined(SDIO_STA_STBITERR) - while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND | SDIO_FLAG_STBITERR)) -#else /* SDIO_STA_STBITERR not defined */ - while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXUNDERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DATAEND)) -#endif /* SDIO_STA_STBITERR */ - { - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXFIFOHE) && (dataremaining > 0U)) - { - /* Write data to SDIO Tx FIFO */ - for(count = 0U; count < 8U; count++) - { - data = (uint32_t)(*tempbuff); - tempbuff++; - dataremaining--; - data |= ((uint32_t)(*tempbuff) << 8U); - tempbuff++; - dataremaining--; - data |= ((uint32_t)(*tempbuff) << 16U); - tempbuff++; - dataremaining--; - data |= ((uint32_t)(*tempbuff) << 24U); - tempbuff++; - dataremaining--; - (void)SDIO_WriteFIFO(hsd->Instance, &data); - } - } - - if(((HAL_GetTick()-tickstart) >= Timeout) || (Timeout == 0U)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_TIMEOUT; - } - } - - /* Send stop transmission command in case of multiblock write */ - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DATAEND) && (NumberOfBlocks > 1U)) - { - if(hsd->SdCard.CardType != CARD_SECURED) - { - /* Send stop transmission command */ - errorstate = SDMMC_CmdStopTransfer(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - } - } - - /* Get error state */ - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_DATA_TIMEOUT; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_DATA_CRC_FAIL; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXUNDERR)) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_TX_UNDERRUN; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - else - { - /* Nothing to do */ - } - - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - hsd->State = HAL_SD_STATE_READY; - - return HAL_OK; - } - else - { - hsd->ErrorCode |= HAL_SD_ERROR_BUSY; - return HAL_ERROR; - } -} - -/** - * @brief Reads block(s) from a specified address in a card. The Data transfer - * is managed in interrupt mode. - * @note This API should be followed by a check on the card state through - * HAL_SD_GetCardState(). - * @note You could also check the IT transfer process through the SD Rx - * interrupt event. - * @param hsd: Pointer to SD handle - * @param pData: Pointer to the buffer that will contain the received data - * @param BlockAdd: Block Address from where data is to be read - * @param NumberOfBlocks: Number of blocks to read. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_ReadBlocks_IT(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t add = BlockAdd; - - if(NULL == pData) - { - hsd->ErrorCode |= HAL_SD_ERROR_PARAM; - return HAL_ERROR; - } - - if(hsd->State == HAL_SD_STATE_READY) - { - hsd->ErrorCode = HAL_SD_ERROR_NONE; - - if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) - { - hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hsd->State = HAL_SD_STATE_BUSY; - - /* Initialize data control register */ - hsd->Instance->DCTRL = 0U; - - hsd->pRxBuffPtr = pData; - hsd->RxXferSize = BLOCKSIZE * NumberOfBlocks; - -#if defined(SDIO_STA_STBITERR) - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_FLAG_RXFIFOHF | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_FLAG_RXFIFOHF)); -#endif /* SDIO_STA_STBITERR */ - - if(hsd->SdCard.CardType != CARD_SDHC_SDXC) - { - add *= 512U; - } - - /* Configure the SD DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = BLOCKSIZE * NumberOfBlocks; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hsd->Instance, &config); - - /* Read Blocks in IT mode */ - if(NumberOfBlocks > 1U) - { - hsd->Context = (SD_CONTEXT_READ_MULTIPLE_BLOCK | SD_CONTEXT_IT); - - /* Read Multi Block command */ - errorstate = SDMMC_CmdReadMultiBlock(hsd->Instance, add); - } - else - { - hsd->Context = (SD_CONTEXT_READ_SINGLE_BLOCK | SD_CONTEXT_IT); - - /* Read Single Block command */ - errorstate = SDMMC_CmdReadSingleBlock(hsd->Instance, add); - } - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Writes block(s) to a specified address in a card. The Data transfer - * is managed in interrupt mode. - * @note This API should be followed by a check on the card state through - * HAL_SD_GetCardState(). - * @note You could also check the IT transfer process through the SD Tx - * interrupt event. - * @param hsd: Pointer to SD handle - * @param pData: Pointer to the buffer that will contain the data to transmit - * @param BlockAdd: Block Address where data will be written - * @param NumberOfBlocks: Number of blocks to write - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_WriteBlocks_IT(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t add = BlockAdd; - - if(NULL == pData) - { - hsd->ErrorCode |= HAL_SD_ERROR_PARAM; - return HAL_ERROR; - } - - if(hsd->State == HAL_SD_STATE_READY) - { - hsd->ErrorCode = HAL_SD_ERROR_NONE; - - if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) - { - hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hsd->State = HAL_SD_STATE_BUSY; - - /* Initialize data control register */ - hsd->Instance->DCTRL = 0U; - - hsd->pTxBuffPtr = pData; - hsd->TxXferSize = BLOCKSIZE * NumberOfBlocks; - - /* Enable transfer interrupts */ -#if defined(SDIO_STA_STBITERR) - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_DATAEND | SDIO_FLAG_TXFIFOHE)); -#endif /* SDIO_STA_STBITERR */ - - if(hsd->SdCard.CardType != CARD_SDHC_SDXC) - { - add *= 512U; - } - - /* Write Blocks in Polling mode */ - if(NumberOfBlocks > 1U) - { - hsd->Context = (SD_CONTEXT_WRITE_MULTIPLE_BLOCK| SD_CONTEXT_IT); - - /* Write Multi Block command */ - errorstate = SDMMC_CmdWriteMultiBlock(hsd->Instance, add); - } - else - { - hsd->Context = (SD_CONTEXT_WRITE_SINGLE_BLOCK | SD_CONTEXT_IT); - - /* Write Single Block command */ - errorstate = SDMMC_CmdWriteSingleBlock(hsd->Instance, add); - } - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - - /* Configure the SD DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = BLOCKSIZE * NumberOfBlocks; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hsd->Instance, &config); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Reads block(s) from a specified address in a card. The Data transfer - * is managed by DMA mode. - * @note This API should be followed by a check on the card state through - * HAL_SD_GetCardState(). - * @note You could also check the DMA transfer process through the SD Rx - * interrupt event. - * @param hsd: Pointer SD handle - * @param pData: Pointer to the buffer that will contain the received data - * @param BlockAdd: Block Address from where data is to be read - * @param NumberOfBlocks: Number of blocks to read. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_ReadBlocks_DMA(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t add = BlockAdd; - - if(NULL == pData) - { - hsd->ErrorCode |= HAL_SD_ERROR_PARAM; - return HAL_ERROR; - } - - if(hsd->State == HAL_SD_STATE_READY) - { - hsd->ErrorCode = HAL_SD_ERROR_NONE; - - if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) - { - hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hsd->State = HAL_SD_STATE_BUSY; - - /* Initialize data control register */ - hsd->Instance->DCTRL = 0U; - -#if defined(SDIO_STA_STBITERR) - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); -#endif /* SDIO_STA_STBITERR */ - - /* Set the DMA transfer complete callback */ - hsd->hdmarx->XferCpltCallback = SD_DMAReceiveCplt; - - /* Set the DMA error callback */ - hsd->hdmarx->XferErrorCallback = SD_DMAError; - - /* Set the DMA Abort callback */ - hsd->hdmarx->XferAbortCallback = NULL; - - /* Force DMA Direction */ - hsd->hdmarx->Init.Direction = DMA_PERIPH_TO_MEMORY; - MODIFY_REG(hsd->hdmarx->Instance->CR, DMA_SxCR_DIR, hsd->hdmarx->Init.Direction); - - /* Enable the DMA Channel */ - if(HAL_DMA_Start_IT(hsd->hdmarx, (uint32_t)&hsd->Instance->FIFO, (uint32_t)pData, (uint32_t)(BLOCKSIZE * NumberOfBlocks)/4U) != HAL_OK) - { - __HAL_SD_DISABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_RXOVERR | SDIO_IT_DATAEND)); - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_DMA; - hsd->State = HAL_SD_STATE_READY; - return HAL_ERROR; - } - else - { - /* Enable SD DMA transfer */ - __HAL_SD_DMA_ENABLE(hsd); - - if(hsd->SdCard.CardType != CARD_SDHC_SDXC) - { - add *= 512U; - } - - /* Configure the SD DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = BLOCKSIZE * NumberOfBlocks; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hsd->Instance, &config); - - /* Read Blocks in DMA mode */ - if(NumberOfBlocks > 1U) - { - hsd->Context = (SD_CONTEXT_READ_MULTIPLE_BLOCK | SD_CONTEXT_DMA); - - /* Read Multi Block command */ - errorstate = SDMMC_CmdReadMultiBlock(hsd->Instance, add); - } - else - { - hsd->Context = (SD_CONTEXT_READ_SINGLE_BLOCK | SD_CONTEXT_DMA); - - /* Read Single Block command */ - errorstate = SDMMC_CmdReadSingleBlock(hsd->Instance, add); - } - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - - return HAL_OK; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Writes block(s) to a specified address in a card. The Data transfer - * is managed by DMA mode. - * @note This API should be followed by a check on the card state through - * HAL_SD_GetCardState(). - * @note You could also check the DMA transfer process through the SD Tx - * interrupt event. - * @param hsd: Pointer to SD handle - * @param pData: Pointer to the buffer that will contain the data to transmit - * @param BlockAdd: Block Address where data will be written - * @param NumberOfBlocks: Number of blocks to write - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_WriteBlocks_DMA(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t add = BlockAdd; - - if(NULL == pData) - { - hsd->ErrorCode |= HAL_SD_ERROR_PARAM; - return HAL_ERROR; - } - - if(hsd->State == HAL_SD_STATE_READY) - { - hsd->ErrorCode = HAL_SD_ERROR_NONE; - - if((add + NumberOfBlocks) > (hsd->SdCard.LogBlockNbr)) - { - hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hsd->State = HAL_SD_STATE_BUSY; - - /* Initialize data control register */ - hsd->Instance->DCTRL = 0U; - - /* Enable SD Error interrupts */ -#if defined(SDIO_STA_STBITERR) - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR)); -#endif /* SDIO_STA_STBITERR */ - - /* Set the DMA transfer complete callback */ - hsd->hdmatx->XferCpltCallback = SD_DMATransmitCplt; - - /* Set the DMA error callback */ - hsd->hdmatx->XferErrorCallback = SD_DMAError; - - /* Set the DMA Abort callback */ - hsd->hdmatx->XferAbortCallback = NULL; - - if(hsd->SdCard.CardType != CARD_SDHC_SDXC) - { - add *= 512U; - } - - /* Write Blocks in Polling mode */ - if(NumberOfBlocks > 1U) - { - hsd->Context = (SD_CONTEXT_WRITE_MULTIPLE_BLOCK | SD_CONTEXT_DMA); - - /* Write Multi Block command */ - errorstate = SDMMC_CmdWriteMultiBlock(hsd->Instance, add); - } - else - { - hsd->Context = (SD_CONTEXT_WRITE_SINGLE_BLOCK | SD_CONTEXT_DMA); - - /* Write Single Block command */ - errorstate = SDMMC_CmdWriteSingleBlock(hsd->Instance, add); - } - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - - /* Enable SDIO DMA transfer */ - __HAL_SD_DMA_ENABLE(hsd); - - /* Force DMA Direction */ - hsd->hdmatx->Init.Direction = DMA_MEMORY_TO_PERIPH; - MODIFY_REG(hsd->hdmatx->Instance->CR, DMA_SxCR_DIR, hsd->hdmatx->Init.Direction); - - /* Enable the DMA Channel */ - if(HAL_DMA_Start_IT(hsd->hdmatx, (uint32_t)pData, (uint32_t)&hsd->Instance->FIFO, (uint32_t)(BLOCKSIZE * NumberOfBlocks)/4U) != HAL_OK) - { -#if defined(SDIO_STA_STBITERR) - __HAL_SD_DISABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR | SDIO_IT_STBITERR)); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_SD_DISABLE_IT(hsd, (SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT | SDIO_IT_TXUNDERR)); -#endif /* SDIO_STA_STBITERR */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_DMA; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - return HAL_ERROR; - } - else - { - /* Configure the SD DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = BLOCKSIZE * NumberOfBlocks; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_512B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_CARD; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hsd->Instance, &config); - - return HAL_OK; - } - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Erases the specified memory area of the given SD card. - * @note This API should be followed by a check on the card state through - * HAL_SD_GetCardState(). - * @param hsd: Pointer to SD handle - * @param BlockStartAdd: Start Block address - * @param BlockEndAdd: End Block address - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_Erase(SD_HandleTypeDef *hsd, uint32_t BlockStartAdd, uint32_t BlockEndAdd) -{ - uint32_t errorstate; - uint32_t start_add = BlockStartAdd; - uint32_t end_add = BlockEndAdd; - - if(hsd->State == HAL_SD_STATE_READY) - { - hsd->ErrorCode = HAL_SD_ERROR_NONE; - - if(end_add < start_add) - { - hsd->ErrorCode |= HAL_SD_ERROR_PARAM; - return HAL_ERROR; - } - - if(end_add > (hsd->SdCard.LogBlockNbr)) - { - hsd->ErrorCode |= HAL_SD_ERROR_ADDR_OUT_OF_RANGE; - return HAL_ERROR; - } - - hsd->State = HAL_SD_STATE_BUSY; - - /* Check if the card command class supports erase command */ - if(((hsd->SdCard.Class) & SDIO_CCCC_ERASE) == 0U) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_REQUEST_NOT_APPLICABLE; - hsd->State = HAL_SD_STATE_READY; - return HAL_ERROR; - } - - if((SDIO_GetResponse(hsd->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_LOCK_UNLOCK_FAILED; - hsd->State = HAL_SD_STATE_READY; - return HAL_ERROR; - } - - /* Get start and end block for high capacity cards */ - if(hsd->SdCard.CardType != CARD_SDHC_SDXC) - { - start_add *= 512U; - end_add *= 512U; - } - - /* According to sd-card spec 1.0 ERASE_GROUP_START (CMD32) and erase_group_end(CMD33) */ - if(hsd->SdCard.CardType != CARD_SECURED) - { - /* Send CMD32 SD_ERASE_GRP_START with argument as addr */ - errorstate = SDMMC_CmdSDEraseStartAdd(hsd->Instance, start_add); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - return HAL_ERROR; - } - - /* Send CMD33 SD_ERASE_GRP_END with argument as addr */ - errorstate = SDMMC_CmdSDEraseEndAdd(hsd->Instance, end_add); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - return HAL_ERROR; - } - } - - /* Send CMD38 ERASE */ - errorstate = SDMMC_CmdErase(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - return HAL_ERROR; - } - - hsd->State = HAL_SD_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief This function handles SD card interrupt request. - * @param hsd: Pointer to SD handle - * @retval None - */ -void HAL_SD_IRQHandler(SD_HandleTypeDef *hsd) -{ - uint32_t errorstate; - uint32_t context = hsd->Context; - - /* Check for SDIO interrupt flags */ - if((__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXFIFOHF) != RESET) && ((context & SD_CONTEXT_IT) != 0U)) - { - SD_Read_IT(hsd); - } - - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DATAEND) != RESET) - { - __HAL_SD_CLEAR_FLAG(hsd, SDIO_FLAG_DATAEND); - -#if defined(SDIO_STA_STBITERR) - __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR | SDIO_IT_RXOVERR | SDIO_IT_TXFIFOHE |\ - SDIO_IT_RXFIFOHF | SDIO_IT_STBITERR); -#else /* SDIO_STA_STBITERR not defined */ - __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR | SDIO_IT_RXOVERR | SDIO_IT_TXFIFOHE |\ - SDIO_IT_RXFIFOHF); -#endif /* SDIO_STA_STBITERR */ - - hsd->Instance->DCTRL &= ~(SDIO_DCTRL_DTEN); - - if((context & SD_CONTEXT_IT) != 0U) - { - if(((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U) || ((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) - { - errorstate = SDMMC_CmdStopTransfer(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->ErrorCode |= errorstate; -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - hsd->ErrorCallback(hsd); -#else - HAL_SD_ErrorCallback(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - } - - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - if(((context & SD_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) - { -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - hsd->RxCpltCallback(hsd); -#else - HAL_SD_RxCpltCallback(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - else - { -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - hsd->TxCpltCallback(hsd); -#else - HAL_SD_TxCpltCallback(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - } - else if((context & SD_CONTEXT_DMA) != 0U) - { - if((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U) - { - errorstate = SDMMC_CmdStopTransfer(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->ErrorCode |= errorstate; -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - hsd->ErrorCallback(hsd); -#else - HAL_SD_ErrorCallback(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - } - if(((context & SD_CONTEXT_READ_SINGLE_BLOCK) == 0U) && ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) == 0U)) - { - /* Disable the DMA transfer for transmit request by setting the DMAEN bit - in the SD DCTRL register */ - hsd->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); - - hsd->State = HAL_SD_STATE_READY; - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - hsd->TxCpltCallback(hsd); -#else - HAL_SD_TxCpltCallback(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - } - else - { - /* Nothing to do */ - } - } - - else if((__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXFIFOHE) != RESET) && ((context & SD_CONTEXT_IT) != 0U)) - { - SD_Write_IT(hsd); - } - -#if defined(SDIO_STA_STBITERR) - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_RXOVERR | SDIO_FLAG_TXUNDERR | SDIO_FLAG_STBITERR) != RESET) -#else /* SDIO_STA_STBITERR not defined */ - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_RXOVERR | SDIO_FLAG_TXUNDERR) != RESET) -#endif /* SDIO_STA_STBITERR */ - { - /* Set Error code */ - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL) != RESET) - { - hsd->ErrorCode |= HAL_SD_ERROR_DATA_CRC_FAIL; - } - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT) != RESET) - { - hsd->ErrorCode |= HAL_SD_ERROR_DATA_TIMEOUT; - } - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR) != RESET) - { - hsd->ErrorCode |= HAL_SD_ERROR_RX_OVERRUN; - } - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_TXUNDERR) != RESET) - { - hsd->ErrorCode |= HAL_SD_ERROR_TX_UNDERRUN; - } -#if defined(SDIO_STA_STBITERR) - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_STBITERR) != RESET) - { - hsd->ErrorCode |= HAL_SD_ERROR_DATA_TIMEOUT; - } -#endif /* SDIO_STA_STBITERR */ - -#if defined(SDIO_STA_STBITERR) - /* Clear All flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS | SDIO_FLAG_STBITERR); - - /* Disable all interrupts */ - __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR | SDIO_IT_STBITERR); -#else /* SDIO_STA_STBITERR not defined */ - /* Clear All flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - /* Disable all interrupts */ - __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); -#endif /* SDIO_STA_STBITERR */ - - hsd->ErrorCode |= SDMMC_CmdStopTransfer(hsd->Instance); - - if((context & SD_CONTEXT_IT) != 0U) - { - /* Set the SD state to ready to be able to start again the process */ - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - hsd->ErrorCallback(hsd); -#else - HAL_SD_ErrorCallback(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - else if((context & SD_CONTEXT_DMA) != 0U) - { - /* Abort the SD DMA channel */ - if(((context & SD_CONTEXT_WRITE_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) - { - /* Set the DMA Tx abort callback */ - hsd->hdmatx->XferAbortCallback = SD_DMATxAbort; - /* Abort DMA in IT mode */ - if(HAL_DMA_Abort_IT(hsd->hdmatx) != HAL_OK) - { - SD_DMATxAbort(hsd->hdmatx); - } - } - else if(((context & SD_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) - { - /* Set the DMA Rx abort callback */ - hsd->hdmarx->XferAbortCallback = SD_DMARxAbort; - /* Abort DMA in IT mode */ - if(HAL_DMA_Abort_IT(hsd->hdmarx) != HAL_OK) - { - SD_DMARxAbort(hsd->hdmarx); - } - } - else - { - hsd->ErrorCode = HAL_SD_ERROR_NONE; - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - hsd->AbortCpltCallback(hsd); -#else - HAL_SD_AbortCallback(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - } - else - { - /* Nothing to do */ - } - } - else - { - /* Nothing to do */ - } -} - -/** - * @brief return the SD state - * @param hsd: Pointer to sd handle - * @retval HAL state - */ -HAL_SD_StateTypeDef HAL_SD_GetState(SD_HandleTypeDef *hsd) -{ - return hsd->State; -} - -/** -* @brief Return the SD error code -* @param hsd : Pointer to a SD_HandleTypeDef structure that contains - * the configuration information. -* @retval SD Error Code -*/ -uint32_t HAL_SD_GetError(SD_HandleTypeDef *hsd) -{ - return hsd->ErrorCode; -} - -/** - * @brief Tx Transfer completed callbacks - * @param hsd: Pointer to SD handle - * @retval None - */ -__weak void HAL_SD_TxCpltCallback(SD_HandleTypeDef *hsd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SD_TxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callbacks - * @param hsd: Pointer SD handle - * @retval None - */ -__weak void HAL_SD_RxCpltCallback(SD_HandleTypeDef *hsd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SD_RxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief SD error callbacks - * @param hsd: Pointer SD handle - * @retval None - */ -__weak void HAL_SD_ErrorCallback(SD_HandleTypeDef *hsd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SD_ErrorCallback can be implemented in the user file - */ -} - -/** - * @brief SD Abort callbacks - * @param hsd: Pointer SD handle - * @retval None - */ -__weak void HAL_SD_AbortCallback(SD_HandleTypeDef *hsd) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsd); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SD_AbortCallback can be implemented in the user file - */ -} - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -/** - * @brief Register a User SD Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hsd : SD handle - * @param CallbackID : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_SD_TX_CPLT_CB_ID SD Tx Complete Callback ID - * @arg @ref HAL_SD_RX_CPLT_CB_ID SD Rx Complete Callback ID - * @arg @ref HAL_SD_ERROR_CB_ID SD Error Callback ID - * @arg @ref HAL_SD_ABORT_CB_ID SD Abort Callback ID - * @arg @ref HAL_SD_MSP_INIT_CB_ID SD MspInit Callback ID - * @arg @ref HAL_SD_MSP_DEINIT_CB_ID SD MspDeInit Callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_SD_RegisterCallback(SD_HandleTypeDef *hsd, HAL_SD_CallbackIDTypeDef CallbackID, pSD_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - /* Update the error code */ - hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hsd); - - if(hsd->State == HAL_SD_STATE_READY) - { - switch (CallbackID) - { - case HAL_SD_TX_CPLT_CB_ID : - hsd->TxCpltCallback = pCallback; - break; - case HAL_SD_RX_CPLT_CB_ID : - hsd->RxCpltCallback = pCallback; - break; - case HAL_SD_ERROR_CB_ID : - hsd->ErrorCallback = pCallback; - break; - case HAL_SD_ABORT_CB_ID : - hsd->AbortCpltCallback = pCallback; - break; - case HAL_SD_MSP_INIT_CB_ID : - hsd->MspInitCallback = pCallback; - break; - case HAL_SD_MSP_DEINIT_CB_ID : - hsd->MspDeInitCallback = pCallback; - break; - default : - /* Update the error code */ - hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (hsd->State == HAL_SD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_SD_MSP_INIT_CB_ID : - hsd->MspInitCallback = pCallback; - break; - case HAL_SD_MSP_DEINIT_CB_ID : - hsd->MspDeInitCallback = pCallback; - break; - default : - /* Update the error code */ - hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsd); - return status; -} - -/** - * @brief Unregister a User SD Callback - * SD Callback is redirected to the weak (surcharged) predefined callback - * @param hsd : SD handle - * @param CallbackID : ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_SD_TX_CPLT_CB_ID SD Tx Complete Callback ID - * @arg @ref HAL_SD_RX_CPLT_CB_ID SD Rx Complete Callback ID - * @arg @ref HAL_SD_ERROR_CB_ID SD Error Callback ID - * @arg @ref HAL_SD_ABORT_CB_ID SD Abort Callback ID - * @arg @ref HAL_SD_MSP_INIT_CB_ID SD MspInit Callback ID - * @arg @ref HAL_SD_MSP_DEINIT_CB_ID SD MspDeInit Callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_SD_UnRegisterCallback(SD_HandleTypeDef *hsd, HAL_SD_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hsd); - - if(hsd->State == HAL_SD_STATE_READY) - { - switch (CallbackID) - { - case HAL_SD_TX_CPLT_CB_ID : - hsd->TxCpltCallback = HAL_SD_TxCpltCallback; - break; - case HAL_SD_RX_CPLT_CB_ID : - hsd->RxCpltCallback = HAL_SD_RxCpltCallback; - break; - case HAL_SD_ERROR_CB_ID : - hsd->ErrorCallback = HAL_SD_ErrorCallback; - break; - case HAL_SD_ABORT_CB_ID : - hsd->AbortCpltCallback = HAL_SD_AbortCallback; - break; - case HAL_SD_MSP_INIT_CB_ID : - hsd->MspInitCallback = HAL_SD_MspInit; - break; - case HAL_SD_MSP_DEINIT_CB_ID : - hsd->MspDeInitCallback = HAL_SD_MspDeInit; - break; - default : - /* Update the error code */ - hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if (hsd->State == HAL_SD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_SD_MSP_INIT_CB_ID : - hsd->MspInitCallback = HAL_SD_MspInit; - break; - case HAL_SD_MSP_DEINIT_CB_ID : - hsd->MspDeInitCallback = HAL_SD_MspDeInit; - break; - default : - /* Update the error code */ - hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hsd->ErrorCode |= HAL_SD_ERROR_INVALID_CALLBACK; - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsd); - return status; -} -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup SD_Exported_Functions_Group3 - * @brief management functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control the SD card - operations and get the related information - -@endverbatim - * @{ - */ - -/** - * @brief Returns information the information of the card which are stored on - * the CID register. - * @param hsd: Pointer to SD handle - * @param pCID: Pointer to a HAL_SD_CardCIDTypeDef structure that - * contains all CID register parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_GetCardCID(SD_HandleTypeDef *hsd, HAL_SD_CardCIDTypeDef *pCID) -{ - pCID->ManufacturerID = (uint8_t)((hsd->CID[0] & 0xFF000000U) >> 24U); - - pCID->OEM_AppliID = (uint16_t)((hsd->CID[0] & 0x00FFFF00U) >> 8U); - - pCID->ProdName1 = (((hsd->CID[0] & 0x000000FFU) << 24U) | ((hsd->CID[1] & 0xFFFFFF00U) >> 8U)); - - pCID->ProdName2 = (uint8_t)(hsd->CID[1] & 0x000000FFU); - - pCID->ProdRev = (uint8_t)((hsd->CID[2] & 0xFF000000U) >> 24U); - - pCID->ProdSN = (((hsd->CID[2] & 0x00FFFFFFU) << 8U) | ((hsd->CID[3] & 0xFF000000U) >> 24U)); - - pCID->Reserved1 = (uint8_t)((hsd->CID[3] & 0x00F00000U) >> 20U); - - pCID->ManufactDate = (uint16_t)((hsd->CID[3] & 0x000FFF00U) >> 8U); - - pCID->CID_CRC = (uint8_t)((hsd->CID[3] & 0x000000FEU) >> 1U); - - pCID->Reserved2 = 1U; - - return HAL_OK; -} - -/** - * @brief Returns information the information of the card which are stored on - * the CSD register. - * @param hsd: Pointer to SD handle - * @param pCSD: Pointer to a HAL_SD_CardCSDTypeDef structure that - * contains all CSD register parameters - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_GetCardCSD(SD_HandleTypeDef *hsd, HAL_SD_CardCSDTypeDef *pCSD) -{ - pCSD->CSDStruct = (uint8_t)((hsd->CSD[0] & 0xC0000000U) >> 30U); - - pCSD->SysSpecVersion = (uint8_t)((hsd->CSD[0] & 0x3C000000U) >> 26U); - - pCSD->Reserved1 = (uint8_t)((hsd->CSD[0] & 0x03000000U) >> 24U); - - pCSD->TAAC = (uint8_t)((hsd->CSD[0] & 0x00FF0000U) >> 16U); - - pCSD->NSAC = (uint8_t)((hsd->CSD[0] & 0x0000FF00U) >> 8U); - - pCSD->MaxBusClkFrec = (uint8_t)(hsd->CSD[0] & 0x000000FFU); - - pCSD->CardComdClasses = (uint16_t)((hsd->CSD[1] & 0xFFF00000U) >> 20U); - - pCSD->RdBlockLen = (uint8_t)((hsd->CSD[1] & 0x000F0000U) >> 16U); - - pCSD->PartBlockRead = (uint8_t)((hsd->CSD[1] & 0x00008000U) >> 15U); - - pCSD->WrBlockMisalign = (uint8_t)((hsd->CSD[1] & 0x00004000U) >> 14U); - - pCSD->RdBlockMisalign = (uint8_t)((hsd->CSD[1] & 0x00002000U) >> 13U); - - pCSD->DSRImpl = (uint8_t)((hsd->CSD[1] & 0x00001000U) >> 12U); - - pCSD->Reserved2 = 0U; /*!< Reserved */ - - if(hsd->SdCard.CardType == CARD_SDSC) - { - pCSD->DeviceSize = (((hsd->CSD[1] & 0x000003FFU) << 2U) | ((hsd->CSD[2] & 0xC0000000U) >> 30U)); - - pCSD->MaxRdCurrentVDDMin = (uint8_t)((hsd->CSD[2] & 0x38000000U) >> 27U); - - pCSD->MaxRdCurrentVDDMax = (uint8_t)((hsd->CSD[2] & 0x07000000U) >> 24U); - - pCSD->MaxWrCurrentVDDMin = (uint8_t)((hsd->CSD[2] & 0x00E00000U) >> 21U); - - pCSD->MaxWrCurrentVDDMax = (uint8_t)((hsd->CSD[2] & 0x001C0000U) >> 18U); - - pCSD->DeviceSizeMul = (uint8_t)((hsd->CSD[2] & 0x00038000U) >> 15U); - - hsd->SdCard.BlockNbr = (pCSD->DeviceSize + 1U) ; - hsd->SdCard.BlockNbr *= (1UL << ((pCSD->DeviceSizeMul & 0x07U) + 2U)); - hsd->SdCard.BlockSize = (1UL << (pCSD->RdBlockLen & 0x0FU)); - - hsd->SdCard.LogBlockNbr = (hsd->SdCard.BlockNbr) * ((hsd->SdCard.BlockSize) / 512U); - hsd->SdCard.LogBlockSize = 512U; - } - else if(hsd->SdCard.CardType == CARD_SDHC_SDXC) - { - /* Byte 7 */ - pCSD->DeviceSize = (((hsd->CSD[1] & 0x0000003FU) << 16U) | ((hsd->CSD[2] & 0xFFFF0000U) >> 16U)); - - hsd->SdCard.BlockNbr = ((pCSD->DeviceSize + 1U) * 1024U); - hsd->SdCard.LogBlockNbr = hsd->SdCard.BlockNbr; - hsd->SdCard.BlockSize = 512U; - hsd->SdCard.LogBlockSize = hsd->SdCard.BlockSize; - } - else - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= HAL_SD_ERROR_UNSUPPORTED_FEATURE; - hsd->State = HAL_SD_STATE_READY; - return HAL_ERROR; - } - - pCSD->EraseGrSize = (uint8_t)((hsd->CSD[2] & 0x00004000U) >> 14U); - - pCSD->EraseGrMul = (uint8_t)((hsd->CSD[2] & 0x00003F80U) >> 7U); - - pCSD->WrProtectGrSize = (uint8_t)(hsd->CSD[2] & 0x0000007FU); - - pCSD->WrProtectGrEnable = (uint8_t)((hsd->CSD[3] & 0x80000000U) >> 31U); - - pCSD->ManDeflECC = (uint8_t)((hsd->CSD[3] & 0x60000000U) >> 29U); - - pCSD->WrSpeedFact = (uint8_t)((hsd->CSD[3] & 0x1C000000U) >> 26U); - - pCSD->MaxWrBlockLen= (uint8_t)((hsd->CSD[3] & 0x03C00000U) >> 22U); - - pCSD->WriteBlockPaPartial = (uint8_t)((hsd->CSD[3] & 0x00200000U) >> 21U); - - pCSD->Reserved3 = 0; - - pCSD->ContentProtectAppli = (uint8_t)((hsd->CSD[3] & 0x00010000U) >> 16U); - - pCSD->FileFormatGroup = (uint8_t)((hsd->CSD[3] & 0x00008000U) >> 15U); - - pCSD->CopyFlag = (uint8_t)((hsd->CSD[3] & 0x00004000U) >> 14U); - - pCSD->PermWrProtect = (uint8_t)((hsd->CSD[3] & 0x00002000U) >> 13U); - - pCSD->TempWrProtect = (uint8_t)((hsd->CSD[3] & 0x00001000U) >> 12U); - - pCSD->FileFormat = (uint8_t)((hsd->CSD[3] & 0x00000C00U) >> 10U); - - pCSD->ECC= (uint8_t)((hsd->CSD[3] & 0x00000300U) >> 8U); - - pCSD->CSD_CRC = (uint8_t)((hsd->CSD[3] & 0x000000FEU) >> 1U); - - pCSD->Reserved4 = 1; - - return HAL_OK; -} - -/** - * @brief Gets the SD status info. - * @param hsd: Pointer to SD handle - * @param pStatus: Pointer to the HAL_SD_CardStatusTypeDef structure that - * will contain the SD card status information - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_GetCardStatus(SD_HandleTypeDef *hsd, HAL_SD_CardStatusTypeDef *pStatus) -{ - uint32_t sd_status[16]; - uint32_t errorstate; - HAL_StatusTypeDef status = HAL_OK; - - errorstate = SD_SendSDStatus(hsd, sd_status); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - hsd->State = HAL_SD_STATE_READY; - status = HAL_ERROR; - } - else - { - pStatus->DataBusWidth = (uint8_t)((sd_status[0] & 0xC0U) >> 6U); - - pStatus->SecuredMode = (uint8_t)((sd_status[0] & 0x20U) >> 5U); - - pStatus->CardType = (uint16_t)(((sd_status[0] & 0x00FF0000U) >> 8U) | ((sd_status[0] & 0xFF000000U) >> 24U)); - - pStatus->ProtectedAreaSize = (((sd_status[1] & 0xFFU) << 24U) | ((sd_status[1] & 0xFF00U) << 8U) | - ((sd_status[1] & 0xFF0000U) >> 8U) | ((sd_status[1] & 0xFF000000U) >> 24U)); - - pStatus->SpeedClass = (uint8_t)(sd_status[2] & 0xFFU); - - pStatus->PerformanceMove = (uint8_t)((sd_status[2] & 0xFF00U) >> 8U); - - pStatus->AllocationUnitSize = (uint8_t)((sd_status[2] & 0xF00000U) >> 20U); - - pStatus->EraseSize = (uint16_t)(((sd_status[2] & 0xFF000000U) >> 16U) | (sd_status[3] & 0xFFU)); - - pStatus->EraseTimeout = (uint8_t)((sd_status[3] & 0xFC00U) >> 10U); - - pStatus->EraseOffset = (uint8_t)((sd_status[3] & 0x0300U) >> 8U); - } - - /* Set Block Size for Card */ - errorstate = SDMMC_CmdBlockLength(hsd->Instance, BLOCKSIZE); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode = errorstate; - hsd->State = HAL_SD_STATE_READY; - status = HAL_ERROR; - } - - return status; -} - -/** - * @brief Gets the SD card info. - * @param hsd: Pointer to SD handle - * @param pCardInfo: Pointer to the HAL_SD_CardInfoTypeDef structure that - * will contain the SD card status information - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_GetCardInfo(SD_HandleTypeDef *hsd, HAL_SD_CardInfoTypeDef *pCardInfo) -{ - pCardInfo->CardType = (uint32_t)(hsd->SdCard.CardType); - pCardInfo->CardVersion = (uint32_t)(hsd->SdCard.CardVersion); - pCardInfo->Class = (uint32_t)(hsd->SdCard.Class); - pCardInfo->RelCardAdd = (uint32_t)(hsd->SdCard.RelCardAdd); - pCardInfo->BlockNbr = (uint32_t)(hsd->SdCard.BlockNbr); - pCardInfo->BlockSize = (uint32_t)(hsd->SdCard.BlockSize); - pCardInfo->LogBlockNbr = (uint32_t)(hsd->SdCard.LogBlockNbr); - pCardInfo->LogBlockSize = (uint32_t)(hsd->SdCard.LogBlockSize); - - return HAL_OK; -} - -/** - * @brief Enables wide bus operation for the requested card if supported by - * card. - * @param hsd: Pointer to SD handle - * @param WideMode: Specifies the SD card wide bus mode - * This parameter can be one of the following values: - * @arg SDIO_BUS_WIDE_8B: 8-bit data transfer - * @arg SDIO_BUS_WIDE_4B: 4-bit data transfer - * @arg SDIO_BUS_WIDE_1B: 1-bit data transfer - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_ConfigWideBusOperation(SD_HandleTypeDef *hsd, uint32_t WideMode) -{ - SDIO_InitTypeDef Init; - uint32_t errorstate; - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_SDIO_BUS_WIDE(WideMode)); - - /* Change State */ - hsd->State = HAL_SD_STATE_BUSY; - - if(hsd->SdCard.CardType != CARD_SECURED) - { - if(WideMode == SDIO_BUS_WIDE_8B) - { - hsd->ErrorCode |= HAL_SD_ERROR_UNSUPPORTED_FEATURE; - } - else if(WideMode == SDIO_BUS_WIDE_4B) - { - errorstate = SD_WideBus_Enable(hsd); - - hsd->ErrorCode |= errorstate; - } - else if(WideMode == SDIO_BUS_WIDE_1B) - { - errorstate = SD_WideBus_Disable(hsd); - - hsd->ErrorCode |= errorstate; - } - else - { - /* WideMode is not a valid argument*/ - hsd->ErrorCode |= HAL_SD_ERROR_PARAM; - } - } - else - { - /* MMC Card does not support this feature */ - hsd->ErrorCode |= HAL_SD_ERROR_UNSUPPORTED_FEATURE; - } - - if(hsd->ErrorCode != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->State = HAL_SD_STATE_READY; - status = HAL_ERROR; - } - else - { - /* Configure the SDIO peripheral */ - Init.ClockEdge = hsd->Init.ClockEdge; - Init.ClockBypass = hsd->Init.ClockBypass; - Init.ClockPowerSave = hsd->Init.ClockPowerSave; - Init.BusWide = WideMode; - Init.HardwareFlowControl = hsd->Init.HardwareFlowControl; - Init.ClockDiv = hsd->Init.ClockDiv; - (void)SDIO_Init(hsd->Instance, Init); - } - - /* Set Block Size for Card */ - errorstate = SDMMC_CmdBlockLength(hsd->Instance, BLOCKSIZE); - if(errorstate != HAL_SD_ERROR_NONE) - { - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - hsd->ErrorCode |= errorstate; - status = HAL_ERROR; - } - - /* Change State */ - hsd->State = HAL_SD_STATE_READY; - - return status; -} - -/** - * @brief Gets the current sd card data state. - * @param hsd: pointer to SD handle - * @retval Card state - */ -HAL_SD_CardStateTypeDef HAL_SD_GetCardState(SD_HandleTypeDef *hsd) -{ - uint32_t cardstate; - uint32_t errorstate; - uint32_t resp1 = 0; - - errorstate = SD_SendStatus(hsd, &resp1); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->ErrorCode |= errorstate; - } - - cardstate = ((resp1 >> 9U) & 0x0FU); - - return (HAL_SD_CardStateTypeDef)cardstate; -} - -/** - * @brief Abort the current transfer and disable the SD. - * @param hsd: pointer to a SD_HandleTypeDef structure that contains - * the configuration information for SD module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_Abort(SD_HandleTypeDef *hsd) -{ - HAL_SD_CardStateTypeDef CardState; - uint32_t context = hsd->Context; - - /* DIsable All interrupts */ - __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); - - /* Clear All flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - CLEAR_BIT(hsd->Instance->DCTRL, SDIO_DCTRL_DTEN); - - if ((context & SD_CONTEXT_DMA) != 0U) - { - /* Disable the SD DMA request */ - hsd->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); - - /* Abort the SD DMA Tx channel */ - if (((context & SD_CONTEXT_WRITE_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) - { - if(HAL_DMA_Abort(hsd->hdmatx) != HAL_OK) - { - hsd->ErrorCode |= HAL_SD_ERROR_DMA; - } - } - /* Abort the SD DMA Rx channel */ - else if (((context & SD_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) - { - if(HAL_DMA_Abort(hsd->hdmarx) != HAL_OK) - { - hsd->ErrorCode |= HAL_SD_ERROR_DMA; - } - } - else - { - /* Nothing to do */ - } - } - - hsd->State = HAL_SD_STATE_READY; - - /* Initialize the SD operation */ - hsd->Context = SD_CONTEXT_NONE; - - CardState = HAL_SD_GetCardState(hsd); - if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) - { - hsd->ErrorCode = SDMMC_CmdStopTransfer(hsd->Instance); - } - if(hsd->ErrorCode != HAL_SD_ERROR_NONE) - { - return HAL_ERROR; - } - return HAL_OK; -} - -/** - * @brief Abort the current transfer and disable the SD (IT mode). - * @param hsd: pointer to a SD_HandleTypeDef structure that contains - * the configuration information for SD module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SD_Abort_IT(SD_HandleTypeDef *hsd) -{ - HAL_SD_CardStateTypeDef CardState; - uint32_t context = hsd->Context; - - /* Disable All interrupts */ - __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); - - CLEAR_BIT(hsd->Instance->DCTRL, SDIO_DCTRL_DTEN); - - if ((context & SD_CONTEXT_DMA) != 0U) - { - /* Disable the SD DMA request */ - hsd->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); - - /* Abort the SD DMA Tx channel */ - if (((context & SD_CONTEXT_WRITE_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_WRITE_MULTIPLE_BLOCK) != 0U)) - { - hsd->hdmatx->XferAbortCallback = SD_DMATxAbort; - if(HAL_DMA_Abort_IT(hsd->hdmatx) != HAL_OK) - { - hsd->hdmatx = NULL; - } - } - /* Abort the SD DMA Rx channel */ - else if (((context & SD_CONTEXT_READ_SINGLE_BLOCK) != 0U) || ((context & SD_CONTEXT_READ_MULTIPLE_BLOCK) != 0U)) - { - hsd->hdmarx->XferAbortCallback = SD_DMARxAbort; - if(HAL_DMA_Abort_IT(hsd->hdmarx) != HAL_OK) - { - hsd->hdmarx = NULL; - } - } - else - { - /* Nothing to do */ - } - } - /* No transfer ongoing on both DMA channels*/ - else - { - /* Clear All flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - CardState = HAL_SD_GetCardState(hsd); - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) - { - hsd->ErrorCode = SDMMC_CmdStopTransfer(hsd->Instance); - } - if(hsd->ErrorCode != HAL_SD_ERROR_NONE) - { - return HAL_ERROR; - } - else - { -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - hsd->AbortCpltCallback(hsd); -#else - HAL_SD_AbortCallback(hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - } - } - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -/* Private function ----------------------------------------------------------*/ -/** @addtogroup SD_Private_Functions - * @{ - */ - -/** - * @brief DMA SD transmit process complete callback - * @param hdma: DMA handle - * @retval None - */ -static void SD_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); - - /* Enable DATAEND Interrupt */ - __HAL_SD_ENABLE_IT(hsd, (SDIO_IT_DATAEND)); -} - -/** - * @brief DMA SD receive process complete callback - * @param hdma: DMA handle - * @retval None - */ -static void SD_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); - uint32_t errorstate; - - /* Send stop command in multiblock write */ - if(hsd->Context == (SD_CONTEXT_READ_MULTIPLE_BLOCK | SD_CONTEXT_DMA)) - { - errorstate = SDMMC_CmdStopTransfer(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->ErrorCode |= errorstate; -#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) - hsd->ErrorCallback(hsd); -#else - HAL_SD_ErrorCallback(hsd); -#endif - } - } - - /* Disable the DMA transfer for transmit request by setting the DMAEN bit - in the SD DCTRL register */ - hsd->Instance->DCTRL &= (uint32_t)~((uint32_t)SDIO_DCTRL_DMAEN); - - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - -#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) - hsd->RxCpltCallback(hsd); -#else - HAL_SD_RxCpltCallback(hsd); -#endif -} - -/** - * @brief DMA SD communication error callback - * @param hdma: DMA handle - * @retval None - */ -static void SD_DMAError(DMA_HandleTypeDef *hdma) -{ - SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); - HAL_SD_CardStateTypeDef CardState; - uint32_t RxErrorCode, TxErrorCode; - - /* if DMA error is FIFO error ignore it */ - if(HAL_DMA_GetError(hdma) != HAL_DMA_ERROR_FE) - { - RxErrorCode = hsd->hdmarx->ErrorCode; - TxErrorCode = hsd->hdmatx->ErrorCode; - if((RxErrorCode == HAL_DMA_ERROR_TE) || (TxErrorCode == HAL_DMA_ERROR_TE)) - { - /* Clear All flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_FLAGS); - - /* Disable All interrupts */ - __HAL_SD_DISABLE_IT(hsd, SDIO_IT_DATAEND | SDIO_IT_DCRCFAIL | SDIO_IT_DTIMEOUT|\ - SDIO_IT_TXUNDERR| SDIO_IT_RXOVERR); - - hsd->ErrorCode |= HAL_SD_ERROR_DMA; - CardState = HAL_SD_GetCardState(hsd); - if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) - { - hsd->ErrorCode |= SDMMC_CmdStopTransfer(hsd->Instance); - } - - hsd->State= HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - } - -#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) - hsd->ErrorCallback(hsd); -#else - HAL_SD_ErrorCallback(hsd); -#endif - } -} - -/** - * @brief DMA SD Tx Abort callback - * @param hdma: DMA handle - * @retval None - */ -static void SD_DMATxAbort(DMA_HandleTypeDef *hdma) -{ - SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); - HAL_SD_CardStateTypeDef CardState; - - /* Clear All flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - CardState = HAL_SD_GetCardState(hsd); - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) - { - hsd->ErrorCode |= SDMMC_CmdStopTransfer(hsd->Instance); - } - - if(hsd->ErrorCode == HAL_SD_ERROR_NONE) - { -#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) - hsd->AbortCpltCallback(hsd); -#else - HAL_SD_AbortCallback(hsd); -#endif - } - else - { -#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) - hsd->ErrorCallback(hsd); -#else - HAL_SD_ErrorCallback(hsd); -#endif - } -} - -/** - * @brief DMA SD Rx Abort callback - * @param hdma: DMA handle - * @retval None - */ -static void SD_DMARxAbort(DMA_HandleTypeDef *hdma) -{ - SD_HandleTypeDef* hsd = (SD_HandleTypeDef* )(hdma->Parent); - HAL_SD_CardStateTypeDef CardState; - - /* Clear All flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - CardState = HAL_SD_GetCardState(hsd); - hsd->State = HAL_SD_STATE_READY; - hsd->Context = SD_CONTEXT_NONE; - if((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING)) - { - hsd->ErrorCode |= SDMMC_CmdStopTransfer(hsd->Instance); - } - - if(hsd->ErrorCode == HAL_SD_ERROR_NONE) - { -#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) - hsd->AbortCpltCallback(hsd); -#else - HAL_SD_AbortCallback(hsd); -#endif - } - else - { -#if (USE_HAL_SD_REGISTER_CALLBACKS == 1) - hsd->ErrorCallback(hsd); -#else - HAL_SD_ErrorCallback(hsd); -#endif - } -} - -/** - * @brief Initializes the sd card. - * @param hsd: Pointer to SD handle - * @retval SD Card error state - */ -static uint32_t SD_InitCard(SD_HandleTypeDef *hsd) -{ - HAL_SD_CardCSDTypeDef CSD; - uint32_t errorstate; - uint16_t sd_rca = 1U; - - /* Check the power State */ - if(SDIO_GetPowerState(hsd->Instance) == 0U) - { - /* Power off */ - return HAL_SD_ERROR_REQUEST_NOT_APPLICABLE; - } - - if(hsd->SdCard.CardType != CARD_SECURED) - { - /* Send CMD2 ALL_SEND_CID */ - errorstate = SDMMC_CmdSendCID(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - else - { - /* Get Card identification number data */ - hsd->CID[0U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP1); - hsd->CID[1U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP2); - hsd->CID[2U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP3); - hsd->CID[3U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP4); - } - } - - if(hsd->SdCard.CardType != CARD_SECURED) - { - /* Send CMD3 SET_REL_ADDR with argument 0 */ - /* SD Card publishes its RCA. */ - errorstate = SDMMC_CmdSetRelAdd(hsd->Instance, &sd_rca); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - } - if(hsd->SdCard.CardType != CARD_SECURED) - { - /* Get the SD card RCA */ - hsd->SdCard.RelCardAdd = sd_rca; - - /* Send CMD9 SEND_CSD with argument as card's RCA */ - errorstate = SDMMC_CmdSendCSD(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - else - { - /* Get Card Specific Data */ - hsd->CSD[0U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP1); - hsd->CSD[1U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP2); - hsd->CSD[2U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP3); - hsd->CSD[3U] = SDIO_GetResponse(hsd->Instance, SDIO_RESP4); - } - } - - /* Get the Card Class */ - hsd->SdCard.Class = (SDIO_GetResponse(hsd->Instance, SDIO_RESP2) >> 20U); - - /* Get CSD parameters */ - if (HAL_SD_GetCardCSD(hsd, &CSD) != HAL_OK) - { - return HAL_SD_ERROR_UNSUPPORTED_FEATURE; - } - - /* Select the Card */ - errorstate = SDMMC_CmdSelDesel(hsd->Instance, (uint32_t)(((uint32_t)hsd->SdCard.RelCardAdd) << 16U)); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* Configure SDIO peripheral interface */ - (void)SDIO_Init(hsd->Instance, hsd->Init); - - /* All cards are initialized */ - return HAL_SD_ERROR_NONE; -} - -/** - * @brief Enquires cards about their operating voltage and configures clock - * controls and stores SD information that will be needed in future - * in the SD handle. - * @param hsd: Pointer to SD handle - * @retval error state - */ -static uint32_t SD_PowerON(SD_HandleTypeDef *hsd) -{ - __IO uint32_t count = 0U; - uint32_t response = 0U, validvoltage = 0U; - uint32_t errorstate; - - /* CMD0: GO_IDLE_STATE */ - errorstate = SDMMC_CmdGoIdleState(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* CMD8: SEND_IF_COND: Command available only on V2.0 cards */ - errorstate = SDMMC_CmdOperCond(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->SdCard.CardVersion = CARD_V1_X; - /* CMD0: GO_IDLE_STATE */ - errorstate = SDMMC_CmdGoIdleState(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - } - else - { - hsd->SdCard.CardVersion = CARD_V2_X; - } - - if( hsd->SdCard.CardVersion == CARD_V2_X) - { - /* SEND CMD55 APP_CMD with RCA as 0 */ - errorstate = SDMMC_CmdAppCommand(hsd->Instance, 0); - if(errorstate != HAL_SD_ERROR_NONE) - { - return HAL_SD_ERROR_UNSUPPORTED_FEATURE; - } - } - /* SD CARD */ - /* Send ACMD41 SD_APP_OP_COND with Argument 0x80100000 */ - while((count < SDMMC_MAX_VOLT_TRIAL) && (validvoltage == 0U)) - { - /* SEND CMD55 APP_CMD with RCA as 0 */ - errorstate = SDMMC_CmdAppCommand(hsd->Instance, 0); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* Send CMD41 */ - errorstate = SDMMC_CmdAppOperCommand(hsd->Instance, SDMMC_VOLTAGE_WINDOW_SD | SDMMC_HIGH_CAPACITY | SD_SWITCH_1_8V_CAPACITY); - if(errorstate != HAL_SD_ERROR_NONE) - { - return HAL_SD_ERROR_UNSUPPORTED_FEATURE; - } - - /* Get command response */ - response = SDIO_GetResponse(hsd->Instance, SDIO_RESP1); - - /* Get operating voltage*/ - validvoltage = (((response >> 31U) == 1U) ? 1U : 0U); - - count++; - } - - if(count >= SDMMC_MAX_VOLT_TRIAL) - { - return HAL_SD_ERROR_INVALID_VOLTRANGE; - } - - if((response & SDMMC_HIGH_CAPACITY) == SDMMC_HIGH_CAPACITY) /* (response &= SD_HIGH_CAPACITY) */ - { - hsd->SdCard.CardType = CARD_SDHC_SDXC; - } - else - { - hsd->SdCard.CardType = CARD_SDSC; - } - - - return HAL_SD_ERROR_NONE; -} - -/** - * @brief Turns the SDIO output signals off. - * @param hsd: Pointer to SD handle - * @retval None - */ -static void SD_PowerOFF(SD_HandleTypeDef *hsd) -{ - /* Set Power State to OFF */ - (void)SDIO_PowerState_OFF(hsd->Instance); -} - -/** - * @brief Send Status info command. - * @param hsd: pointer to SD handle - * @param pSDstatus: Pointer to the buffer that will contain the SD card status - * SD Status register) - * @retval error state - */ -static uint32_t SD_SendSDStatus(SD_HandleTypeDef *hsd, uint32_t *pSDstatus) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t tickstart = HAL_GetTick(); - uint32_t count; - uint32_t *pData = pSDstatus; - - /* Check SD response */ - if((SDIO_GetResponse(hsd->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) - { - return HAL_SD_ERROR_LOCK_UNLOCK_FAILED; - } - - /* Set block size for card if it is not equal to current block size for card */ - errorstate = SDMMC_CmdBlockLength(hsd->Instance, 64U); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->ErrorCode |= HAL_SD_ERROR_NONE; - return errorstate; - } - - /* Send CMD55 */ - errorstate = SDMMC_CmdAppCommand(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->ErrorCode |= HAL_SD_ERROR_NONE; - return errorstate; - } - - /* Configure the SD DPSM (Data Path State Machine) */ - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = 64U; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_64B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hsd->Instance, &config); - - /* Send ACMD13 (SD_APP_STAUS) with argument as card's RCA */ - errorstate = SDMMC_CmdStatusRegister(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - hsd->ErrorCode |= HAL_SD_ERROR_NONE; - return errorstate; - } - - /* Get status data */ - while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_DBCKEND)) - { - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXFIFOHF)) - { - for(count = 0U; count < 8U; count++) - { - *pData = SDIO_ReadFIFO(hsd->Instance); - pData++; - } - } - - if((HAL_GetTick() - tickstart) >= SDMMC_DATATIMEOUT) - { - return HAL_SD_ERROR_TIMEOUT; - } - } - - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT)) - { - return HAL_SD_ERROR_DATA_TIMEOUT; - } - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL)) - { - return HAL_SD_ERROR_DATA_CRC_FAIL; - } - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR)) - { - return HAL_SD_ERROR_RX_OVERRUN; - } - else - { - /* Nothing to do */ - } - - while ((__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXDAVL))) - { - *pData = SDIO_ReadFIFO(hsd->Instance); - pData++; - - if((HAL_GetTick() - tickstart) >= SDMMC_DATATIMEOUT) - { - return HAL_SD_ERROR_TIMEOUT; - } - } - - /* Clear all the static status flags*/ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - return HAL_SD_ERROR_NONE; -} - -/** - * @brief Returns the current card's status. - * @param hsd: Pointer to SD handle - * @param pCardStatus: pointer to the buffer that will contain the SD card - * status (Card Status register) - * @retval error state - */ -static uint32_t SD_SendStatus(SD_HandleTypeDef *hsd, uint32_t *pCardStatus) -{ - uint32_t errorstate; - - if(pCardStatus == NULL) - { - return HAL_SD_ERROR_PARAM; - } - - /* Send Status command */ - errorstate = SDMMC_CmdSendStatus(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* Get SD card status */ - *pCardStatus = SDIO_GetResponse(hsd->Instance, SDIO_RESP1); - - return HAL_SD_ERROR_NONE; -} - -/** - * @brief Enables the SDIO wide bus mode. - * @param hsd: pointer to SD handle - * @retval error state - */ -static uint32_t SD_WideBus_Enable(SD_HandleTypeDef *hsd) -{ - uint32_t scr[2U] = {0U, 0U}; - uint32_t errorstate; - - if((SDIO_GetResponse(hsd->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) - { - return HAL_SD_ERROR_LOCK_UNLOCK_FAILED; - } - - /* Get SCR Register */ - errorstate = SD_FindSCR(hsd, scr); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* If requested card supports wide bus operation */ - if((scr[1U] & SDMMC_WIDE_BUS_SUPPORT) != SDMMC_ALLZERO) - { - /* Send CMD55 APP_CMD with argument as card's RCA.*/ - errorstate = SDMMC_CmdAppCommand(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* Send ACMD6 APP_CMD with argument as 2 for wide bus mode */ - errorstate = SDMMC_CmdBusWidth(hsd->Instance, 2U); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - return HAL_SD_ERROR_NONE; - } - else - { - return HAL_SD_ERROR_REQUEST_NOT_APPLICABLE; - } -} - -/** - * @brief Disables the SDIO wide bus mode. - * @param hsd: Pointer to SD handle - * @retval error state - */ -static uint32_t SD_WideBus_Disable(SD_HandleTypeDef *hsd) -{ - uint32_t scr[2U] = {0U, 0U}; - uint32_t errorstate; - - if((SDIO_GetResponse(hsd->Instance, SDIO_RESP1) & SDMMC_CARD_LOCKED) == SDMMC_CARD_LOCKED) - { - return HAL_SD_ERROR_LOCK_UNLOCK_FAILED; - } - - /* Get SCR Register */ - errorstate = SD_FindSCR(hsd, scr); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* If requested card supports 1 bit mode operation */ - if((scr[1U] & SDMMC_SINGLE_BUS_SUPPORT) != SDMMC_ALLZERO) - { - /* Send CMD55 APP_CMD with argument as card's RCA */ - errorstate = SDMMC_CmdAppCommand(hsd->Instance, (uint32_t)(hsd->SdCard.RelCardAdd << 16U)); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* Send ACMD6 APP_CMD with argument as 0 for single bus mode */ - errorstate = SDMMC_CmdBusWidth(hsd->Instance, 0U); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - return HAL_SD_ERROR_NONE; - } - else - { - return HAL_SD_ERROR_REQUEST_NOT_APPLICABLE; - } -} - - -/** - * @brief Finds the SD card SCR register value. - * @param hsd: Pointer to SD handle - * @param pSCR: pointer to the buffer that will contain the SCR value - * @retval error state - */ -static uint32_t SD_FindSCR(SD_HandleTypeDef *hsd, uint32_t *pSCR) -{ - SDIO_DataInitTypeDef config; - uint32_t errorstate; - uint32_t tickstart = HAL_GetTick(); - uint32_t index = 0U; - uint32_t tempscr[2U] = {0U, 0U}; - uint32_t *scr = pSCR; - - /* Set Block Size To 8 Bytes */ - errorstate = SDMMC_CmdBlockLength(hsd->Instance, 8U); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - /* Send CMD55 APP_CMD with argument as card's RCA */ - errorstate = SDMMC_CmdAppCommand(hsd->Instance, (uint32_t)((hsd->SdCard.RelCardAdd) << 16U)); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - config.DataTimeOut = SDMMC_DATATIMEOUT; - config.DataLength = 8U; - config.DataBlockSize = SDIO_DATABLOCK_SIZE_8B; - config.TransferDir = SDIO_TRANSFER_DIR_TO_SDIO; - config.TransferMode = SDIO_TRANSFER_MODE_BLOCK; - config.DPSM = SDIO_DPSM_ENABLE; - (void)SDIO_ConfigData(hsd->Instance, &config); - - /* Send ACMD51 SD_APP_SEND_SCR with argument as 0 */ - errorstate = SDMMC_CmdSendSCR(hsd->Instance); - if(errorstate != HAL_SD_ERROR_NONE) - { - return errorstate; - } - - while(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT)) - { - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXDAVL)) - { - *(tempscr + index) = SDIO_ReadFIFO(hsd->Instance); - index++; - } - else if(!__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXACT)) - { - break; - } - - if((HAL_GetTick() - tickstart) >= SDMMC_DATATIMEOUT) - { - return HAL_SD_ERROR_TIMEOUT; - } - } - - if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DTIMEOUT)) - { - __HAL_SD_CLEAR_FLAG(hsd, SDIO_FLAG_DTIMEOUT); - - return HAL_SD_ERROR_DATA_TIMEOUT; - } - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_DCRCFAIL)) - { - __HAL_SD_CLEAR_FLAG(hsd, SDIO_FLAG_DCRCFAIL); - - return HAL_SD_ERROR_DATA_CRC_FAIL; - } - else if(__HAL_SD_GET_FLAG(hsd, SDIO_FLAG_RXOVERR)) - { - __HAL_SD_CLEAR_FLAG(hsd, SDIO_FLAG_RXOVERR); - - return HAL_SD_ERROR_RX_OVERRUN; - } - else - { - /* No error flag set */ - /* Clear all the static flags */ - __HAL_SD_CLEAR_FLAG(hsd, SDIO_STATIC_DATA_FLAGS); - - *scr = (((tempscr[1] & SDMMC_0TO7BITS) << 24) | ((tempscr[1] & SDMMC_8TO15BITS) << 8) |\ - ((tempscr[1] & SDMMC_16TO23BITS) >> 8) | ((tempscr[1] & SDMMC_24TO31BITS) >> 24)); - scr++; - *scr = (((tempscr[0] & SDMMC_0TO7BITS) << 24) | ((tempscr[0] & SDMMC_8TO15BITS) << 8) |\ - ((tempscr[0] & SDMMC_16TO23BITS) >> 8) | ((tempscr[0] & SDMMC_24TO31BITS) >> 24)); - - } - - return HAL_SD_ERROR_NONE; -} - -/** - * @brief Wrap up reading in non-blocking mode. - * @param hsd: pointer to a SD_HandleTypeDef structure that contains - * the configuration information. - * @retval None - */ -static void SD_Read_IT(SD_HandleTypeDef *hsd) -{ - uint32_t count, data, dataremaining; - uint8_t* tmp; - - tmp = hsd->pRxBuffPtr; - dataremaining = hsd->RxXferSize; - - if (dataremaining > 0U) - { - /* Read data from SDIO Rx FIFO */ - for(count = 0U; count < 8U; count++) - { - data = SDIO_ReadFIFO(hsd->Instance); - *tmp = (uint8_t)(data & 0xFFU); - tmp++; - dataremaining--; - *tmp = (uint8_t)((data >> 8U) & 0xFFU); - tmp++; - dataremaining--; - *tmp = (uint8_t)((data >> 16U) & 0xFFU); - tmp++; - dataremaining--; - *tmp = (uint8_t)((data >> 24U) & 0xFFU); - tmp++; - dataremaining--; - } - - hsd->pRxBuffPtr = tmp; - hsd->RxXferSize = dataremaining; - } -} - -/** - * @brief Wrap up writing in non-blocking mode. - * @param hsd: pointer to a SD_HandleTypeDef structure that contains - * the configuration information. - * @retval None - */ -static void SD_Write_IT(SD_HandleTypeDef *hsd) -{ - uint32_t count, data, dataremaining; - uint8_t* tmp; - - tmp = hsd->pTxBuffPtr; - dataremaining = hsd->TxXferSize; - - if (dataremaining > 0U) - { - /* Write data to SDIO Tx FIFO */ - for(count = 0U; count < 8U; count++) - { - data = (uint32_t)(*tmp); - tmp++; - dataremaining--; - data |= ((uint32_t)(*tmp) << 8U); - tmp++; - dataremaining--; - data |= ((uint32_t)(*tmp) << 16U); - tmp++; - dataremaining--; - data |= ((uint32_t)(*tmp) << 24U); - tmp++; - dataremaining--; - (void)SDIO_WriteFIFO(hsd->Instance, &data); - } - - hsd->pTxBuffPtr = tmp; - hsd->TxXferSize = dataremaining; - } -} - -/** - * @} - */ - -#endif /* HAL_SD_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* SDIO */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sdram.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sdram.c deleted file mode 100644 index da34f47a843f045..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sdram.c +++ /dev/null @@ -1,1102 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sdram.c - * @author MCD Application Team - * @brief SDRAM HAL module driver. - * This file provides a generic firmware to drive SDRAM memories mounted - * as external device. - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - This driver is a generic layered driver which contains a set of APIs used to - control SDRAM memories. It uses the FMC layer functions to interface - with SDRAM devices. - The following sequence should be followed to configure the FMC to interface - with SDRAM memories: - - (#) Declare a SDRAM_HandleTypeDef handle structure, for example: - SDRAM_HandleTypeDef hdsram - - (++) Fill the SDRAM_HandleTypeDef handle "Init" field with the allowed - values of the structure member. - - (++) Fill the SDRAM_HandleTypeDef handle "Instance" field with a predefined - base register instance for NOR or SDRAM device - - (#) Declare a FMC_SDRAM_TimingTypeDef structure; for example: - FMC_SDRAM_TimingTypeDef Timing; - and fill its fields with the allowed values of the structure member. - - (#) Initialize the SDRAM Controller by calling the function HAL_SDRAM_Init(). This function - performs the following sequence: - - (##) MSP hardware layer configuration using the function HAL_SDRAM_MspInit() - (##) Control register configuration using the FMC SDRAM interface function - FMC_SDRAM_Init() - (##) Timing register configuration using the FMC SDRAM interface function - FMC_SDRAM_Timing_Init() - (##) Program the SDRAM external device by applying its initialization sequence - according to the device plugged in your hardware. This step is mandatory - for accessing the SDRAM device. - - (#) At this stage you can perform read/write accesses from/to the memory connected - to the SDRAM Bank. You can perform either polling or DMA transfer using the - following APIs: - (++) HAL_SDRAM_Read()/HAL_SDRAM_Write() for polling read/write access - (++) HAL_SDRAM_Read_DMA()/HAL_SDRAM_Write_DMA() for DMA read/write transfer - - (#) You can also control the SDRAM device by calling the control APIs HAL_SDRAM_WriteOperation_Enable()/ - HAL_SDRAM_WriteOperation_Disable() to respectively enable/disable the SDRAM write operation or - the function HAL_SDRAM_SendCommand() to send a specified command to the SDRAM - device. The command to be sent must be configured with the FMC_SDRAM_CommandTypeDef - structure. - - (#) You can continuously monitor the SDRAM device HAL state by calling the function - HAL_SDRAM_GetState() - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_SDRAM_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions @ref HAL_SDRAM_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) MspInitCallback : SDRAM MspInit. - (+) MspDeInitCallback : SDRAM MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function @ref HAL_SDRAM_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) MspInitCallback : SDRAM MspInit. - (+) MspDeInitCallback : SDRAM MspDeInit. - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the @ref HAL_SDRAM_Init and if the state is HAL_SDRAM_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the @ref HAL_SDRAM_Init - and @ref HAL_SDRAM_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the @ref HAL_SDRAM_Init and @ref HAL_SDRAM_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_SDRAM_RegisterCallback before calling @ref HAL_SDRAM_DeInit - or @ref HAL_SDRAM_Init function. - - When The compilation define USE_HAL_SDRAM_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SDRAM SDRAM - * @brief SDRAM driver modules - * @{ - */ -#ifdef HAL_SDRAM_MODULE_ENABLED -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SDRAM_Exported_Functions SDRAM Exported Functions - * @{ - */ - -/** @defgroup SDRAM_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * - @verbatim - ============================================================================== - ##### SDRAM Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to initialize/de-initialize - the SDRAM memory - -@endverbatim - * @{ - */ - -/** - * @brief Performs the SDRAM device initialization sequence. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param Timing Pointer to SDRAM control timing structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Init(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_TimingTypeDef *Timing) -{ - /* Check the SDRAM handle parameter */ - if(hsdram == NULL) - { - return HAL_ERROR; - } - - if(hsdram->State == HAL_SDRAM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hsdram->Lock = HAL_UNLOCKED; -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) - if(hsdram->MspInitCallback == NULL) - { - hsdram->MspInitCallback = HAL_SDRAM_MspInit; - } - hsdram->RefreshErrorCallback = HAL_SDRAM_RefreshErrorCallback; - hsdram->DmaXferCpltCallback = HAL_SDRAM_DMA_XferCpltCallback; - hsdram->DmaXferErrorCallback = HAL_SDRAM_DMA_XferErrorCallback; - - /* Init the low level hardware */ - hsdram->MspInitCallback(hsdram); -#else - /* Initialize the low level hardware (MSP) */ - HAL_SDRAM_MspInit(hsdram); -#endif - } - - /* Initialize the SDRAM controller state */ - hsdram->State = HAL_SDRAM_STATE_BUSY; - - /* Initialize SDRAM control Interface */ - FMC_SDRAM_Init(hsdram->Instance, &(hsdram->Init)); - - /* Initialize SDRAM timing Interface */ - FMC_SDRAM_Timing_Init(hsdram->Instance, Timing, hsdram->Init.SDBank); - - /* Update the SDRAM controller state */ - hsdram->State = HAL_SDRAM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Perform the SDRAM device initialization sequence. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_DeInit(SDRAM_HandleTypeDef *hsdram) -{ -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) - if(hsdram->MspDeInitCallback == NULL) - { - hsdram->MspDeInitCallback = HAL_SDRAM_MspDeInit; - } - - /* DeInit the low level hardware */ - hsdram->MspDeInitCallback(hsdram); -#else - /* Initialize the low level hardware (MSP) */ - HAL_SDRAM_MspDeInit(hsdram); -#endif - - /* Configure the SDRAM registers with their reset values */ - FMC_SDRAM_DeInit(hsdram->Instance, hsdram->Init.SDBank); - - /* Reset the SDRAM controller state */ - hsdram->State = HAL_SDRAM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -/** - * @brief SDRAM MSP Init. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval None - */ -__weak void HAL_SDRAM_MspInit(SDRAM_HandleTypeDef *hsdram) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsdram); - /* NOTE: This function Should not be modified, when the callback is needed, - the HAL_SDRAM_MspInit could be implemented in the user file - */ -} - -/** - * @brief SDRAM MSP DeInit. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval None - */ -__weak void HAL_SDRAM_MspDeInit(SDRAM_HandleTypeDef *hsdram) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsdram); - /* NOTE: This function Should not be modified, when the callback is needed, - the HAL_SDRAM_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief This function handles SDRAM refresh error interrupt request. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval HAL status -*/ -void HAL_SDRAM_IRQHandler(SDRAM_HandleTypeDef *hsdram) -{ - /* Check SDRAM interrupt Rising edge flag */ - if(__FMC_SDRAM_GET_FLAG(hsdram->Instance, FMC_SDRAM_FLAG_REFRESH_IT)) - { - /* SDRAM refresh error interrupt callback */ -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) - hsdram->RefreshErrorCallback(hsdram); -#else - HAL_SDRAM_RefreshErrorCallback(hsdram); -#endif - - /* Clear SDRAM refresh error interrupt pending bit */ - __FMC_SDRAM_CLEAR_FLAG(hsdram->Instance, FMC_SDRAM_FLAG_REFRESH_ERROR); - } -} - -/** - * @brief SDRAM Refresh error callback. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval None - */ -__weak void HAL_SDRAM_RefreshErrorCallback(SDRAM_HandleTypeDef *hsdram) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsdram); - /* NOTE: This function Should not be modified, when the callback is needed, - the HAL_SDRAM_RefreshErrorCallback could be implemented in the user file - */ -} - -/** - * @brief DMA transfer complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -__weak void HAL_SDRAM_DMA_XferCpltCallback(DMA_HandleTypeDef *hdma) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdma); - /* NOTE: This function Should not be modified, when the callback is needed, - the HAL_SDRAM_DMA_XferCpltCallback could be implemented in the user file - */ -} - -/** - * @brief DMA transfer complete error callback. - * @param hdma DMA handle - * @retval None - */ -__weak void HAL_SDRAM_DMA_XferErrorCallback(DMA_HandleTypeDef *hdma) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdma); - /* NOTE: This function Should not be modified, when the callback is needed, - the HAL_SDRAM_DMA_XferErrorCallback could be implemented in the user file - */ -} -/** - * @} - */ - -/** @defgroup SDRAM_Exported_Functions_Group2 Input and Output functions - * @brief Input Output and memory control functions - * - @verbatim - ============================================================================== - ##### SDRAM Input and Output functions ##### - ============================================================================== - [..] - This section provides functions allowing to use and control the SDRAM memory - -@endverbatim - * @{ - */ - -/** - * @brief Reads 8-bit data buffer from the SDRAM memory. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param pAddress Pointer to read start address - * @param pDstBuffer Pointer to destination buffer - * @param BufferSize Size of the buffer to read from memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Read_8b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint8_t *pDstBuffer, uint32_t BufferSize) -{ - __IO uint8_t *pSdramAddress = (uint8_t *)pAddress; - - /* Process Locked */ - __HAL_LOCK(hsdram); - - /* Check the SDRAM controller state */ - if(hsdram->State == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - else if(hsdram->State == HAL_SDRAM_STATE_PRECHARGED) - { - return HAL_ERROR; - } - - /* Read data from source */ - for(; BufferSize != 0U; BufferSize--) - { - *pDstBuffer = *(__IO uint8_t *)pSdramAddress; - pDstBuffer++; - pSdramAddress++; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -/** - * @brief Writes 8-bit data buffer to SDRAM memory. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param pAddress Pointer to write start address - * @param pSrcBuffer Pointer to source buffer to write - * @param BufferSize Size of the buffer to write to memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Write_8b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint8_t *pSrcBuffer, uint32_t BufferSize) -{ - __IO uint8_t *pSdramAddress = (uint8_t *)pAddress; - uint32_t tmp = 0U; - - /* Process Locked */ - __HAL_LOCK(hsdram); - - /* Check the SDRAM controller state */ - tmp = hsdram->State; - - if(tmp == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - else if((tmp == HAL_SDRAM_STATE_PRECHARGED) || (tmp == HAL_SDRAM_STATE_WRITE_PROTECTED)) - { - return HAL_ERROR; - } - - /* Write data to memory */ - for(; BufferSize != 0U; BufferSize--) - { - *(__IO uint8_t *)pSdramAddress = *pSrcBuffer; - pSrcBuffer++; - pSdramAddress++; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -/** - * @brief Reads 16-bit data buffer from the SDRAM memory. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param pAddress Pointer to read start address - * @param pDstBuffer Pointer to destination buffer - * @param BufferSize Size of the buffer to read from memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Read_16b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint16_t *pDstBuffer, uint32_t BufferSize) -{ - __IO uint16_t *pSdramAddress = (uint16_t *)pAddress; - - /* Process Locked */ - __HAL_LOCK(hsdram); - - /* Check the SDRAM controller state */ - if(hsdram->State == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - else if(hsdram->State == HAL_SDRAM_STATE_PRECHARGED) - { - return HAL_ERROR; - } - - /* Read data from source */ - for(; BufferSize != 0U; BufferSize--) - { - *pDstBuffer = *(__IO uint16_t *)pSdramAddress; - pDstBuffer++; - pSdramAddress++; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -/** - * @brief Writes 16-bit data buffer to SDRAM memory. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param pAddress Pointer to write start address - * @param pSrcBuffer Pointer to source buffer to write - * @param BufferSize Size of the buffer to write to memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Write_16b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint16_t *pSrcBuffer, uint32_t BufferSize) -{ - __IO uint16_t *pSdramAddress = (uint16_t *)pAddress; - uint32_t tmp = 0U; - - /* Process Locked */ - __HAL_LOCK(hsdram); - - /* Check the SDRAM controller state */ - tmp = hsdram->State; - - if(tmp == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - else if((tmp == HAL_SDRAM_STATE_PRECHARGED) || (tmp == HAL_SDRAM_STATE_WRITE_PROTECTED)) - { - return HAL_ERROR; - } - - /* Write data to memory */ - for(; BufferSize != 0U; BufferSize--) - { - *(__IO uint16_t *)pSdramAddress = *pSrcBuffer; - pSrcBuffer++; - pSdramAddress++; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -/** - * @brief Reads 32-bit data buffer from the SDRAM memory. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param pAddress Pointer to read start address - * @param pDstBuffer Pointer to destination buffer - * @param BufferSize Size of the buffer to read from memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Read_32b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize) -{ - __IO uint32_t *pSdramAddress = (uint32_t *)pAddress; - - /* Process Locked */ - __HAL_LOCK(hsdram); - - /* Check the SDRAM controller state */ - if(hsdram->State == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - else if(hsdram->State == HAL_SDRAM_STATE_PRECHARGED) - { - return HAL_ERROR; - } - - /* Read data from source */ - for(; BufferSize != 0U; BufferSize--) - { - *pDstBuffer = *(__IO uint32_t *)pSdramAddress; - pDstBuffer++; - pSdramAddress++; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -/** - * @brief Writes 32-bit data buffer to SDRAM memory. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param pAddress Pointer to write start address - * @param pSrcBuffer Pointer to source buffer to write - * @param BufferSize Size of the buffer to write to memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Write_32b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize) -{ - __IO uint32_t *pSdramAddress = (uint32_t *)pAddress; - uint32_t tmp = 0U; - - /* Process Locked */ - __HAL_LOCK(hsdram); - - /* Check the SDRAM controller state */ - tmp = hsdram->State; - - if(tmp == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - else if((tmp == HAL_SDRAM_STATE_PRECHARGED) || (tmp == HAL_SDRAM_STATE_WRITE_PROTECTED)) - { - return HAL_ERROR; - } - - /* Write data to memory */ - for(; BufferSize != 0U; BufferSize--) - { - *(__IO uint32_t *)pSdramAddress = *pSrcBuffer; - pSrcBuffer++; - pSdramAddress++; - } - - /* Process Unlocked */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -/** - * @brief Reads a Words data from the SDRAM memory using DMA transfer. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param pAddress Pointer to read start address - * @param pDstBuffer Pointer to destination buffer - * @param BufferSize Size of the buffer to read from memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Read_DMA(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize) -{ - uint32_t tmp = 0U; - - /* Process Locked */ - __HAL_LOCK(hsdram); - - /* Check the SDRAM controller state */ - tmp = hsdram->State; - - if(tmp == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - else if(tmp == HAL_SDRAM_STATE_PRECHARGED) - { - return HAL_ERROR; - } - - /* Configure DMA user callbacks */ - hsdram->hdma->XferCpltCallback = HAL_SDRAM_DMA_XferCpltCallback; - hsdram->hdma->XferErrorCallback = HAL_SDRAM_DMA_XferErrorCallback; - - /* Enable the DMA Stream */ - HAL_DMA_Start_IT(hsdram->hdma, (uint32_t)pAddress, (uint32_t)pDstBuffer, (uint32_t)BufferSize); - - /* Process Unlocked */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -/** - * @brief Writes a Words data buffer to SDRAM memory using DMA transfer. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param pAddress Pointer to write start address - * @param pSrcBuffer Pointer to source buffer to write - * @param BufferSize Size of the buffer to write to memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_Write_DMA(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize) -{ - uint32_t tmp = 0U; - - /* Process Locked */ - __HAL_LOCK(hsdram); - - /* Check the SDRAM controller state */ - tmp = hsdram->State; - - if(tmp == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - else if((tmp == HAL_SDRAM_STATE_PRECHARGED) || (tmp == HAL_SDRAM_STATE_WRITE_PROTECTED)) - { - return HAL_ERROR; - } - - /* Configure DMA user callbacks */ - hsdram->hdma->XferCpltCallback = HAL_SDRAM_DMA_XferCpltCallback; - hsdram->hdma->XferErrorCallback = HAL_SDRAM_DMA_XferErrorCallback; - - /* Enable the DMA Stream */ - HAL_DMA_Start_IT(hsdram->hdma, (uint32_t)pSrcBuffer, (uint32_t)pAddress, (uint32_t)BufferSize); - - /* Process Unlocked */ - __HAL_UNLOCK(hsdram); - - return HAL_OK; -} - -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User SDRAM Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hsdram : SDRAM handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_SDRAM_MSP_INIT_CB_ID SDRAM MspInit callback ID - * @arg @ref HAL_SDRAM_MSP_DEINIT_CB_ID SDRAM MspDeInit callback ID - * @arg @ref HAL_SDRAM_REFRESH_ERR_CB_ID SDRAM Refresh Error callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_SDRAM_RegisterCallback (SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId, pSDRAM_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_SDRAM_StateTypeDef state; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hsdram); - - state = hsdram->State; - if((state == HAL_SDRAM_STATE_READY) || (state == HAL_SDRAM_STATE_WRITE_PROTECTED)) - { - switch (CallbackId) - { - case HAL_SDRAM_MSP_INIT_CB_ID : - hsdram->MspInitCallback = pCallback; - break; - case HAL_SDRAM_MSP_DEINIT_CB_ID : - hsdram->MspDeInitCallback = pCallback; - break; - case HAL_SDRAM_REFRESH_ERR_CB_ID : - hsdram->RefreshErrorCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(hsdram->State == HAL_SDRAM_STATE_RESET) - { - switch (CallbackId) - { - case HAL_SDRAM_MSP_INIT_CB_ID : - hsdram->MspInitCallback = pCallback; - break; - case HAL_SDRAM_MSP_DEINIT_CB_ID : - hsdram->MspDeInitCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsdram); - return status; -} - -/** - * @brief Unregister a User SDRAM Callback - * SDRAM Callback is redirected to the weak (surcharged) predefined callback - * @param hsdram : SDRAM handle - * @param CallbackId : ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_SDRAM_MSP_INIT_CB_ID SDRAM MspInit callback ID - * @arg @ref HAL_SDRAM_MSP_DEINIT_CB_ID SDRAM MspDeInit callback ID - * @arg @ref HAL_SDRAM_REFRESH_ERR_CB_ID SDRAM Refresh Error callback ID - * @arg @ref HAL_SDRAM_DMA_XFER_CPLT_CB_ID SDRAM DMA Xfer Complete callback ID - * @arg @ref HAL_SDRAM_DMA_XFER_ERR_CB_ID SDRAM DMA Xfer Error callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_SDRAM_UnRegisterCallback (SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_SDRAM_StateTypeDef state; - - /* Process locked */ - __HAL_LOCK(hsdram); - - state = hsdram->State; - if((state == HAL_SDRAM_STATE_READY) || (state == HAL_SDRAM_STATE_WRITE_PROTECTED)) - { - switch (CallbackId) - { - case HAL_SDRAM_MSP_INIT_CB_ID : - hsdram->MspInitCallback = HAL_SDRAM_MspInit; - break; - case HAL_SDRAM_MSP_DEINIT_CB_ID : - hsdram->MspDeInitCallback = HAL_SDRAM_MspDeInit; - break; - case HAL_SDRAM_REFRESH_ERR_CB_ID : - hsdram->RefreshErrorCallback = HAL_SDRAM_RefreshErrorCallback; - break; - case HAL_SDRAM_DMA_XFER_CPLT_CB_ID : - hsdram->DmaXferCpltCallback = HAL_SDRAM_DMA_XferCpltCallback; - break; - case HAL_SDRAM_DMA_XFER_ERR_CB_ID : - hsdram->DmaXferErrorCallback = HAL_SDRAM_DMA_XferErrorCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(hsdram->State == HAL_SDRAM_STATE_RESET) - { - switch (CallbackId) - { - case HAL_SDRAM_MSP_INIT_CB_ID : - hsdram->MspInitCallback = HAL_SDRAM_MspInit; - break; - case HAL_SDRAM_MSP_DEINIT_CB_ID : - hsdram->MspDeInitCallback = HAL_SDRAM_MspDeInit; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsdram); - return status; -} - -/** - * @brief Register a User SDRAM Callback for DMA transfers - * To be used instead of the weak (surcharged) predefined callback - * @param hsdram : SDRAM handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_SDRAM_DMA_XFER_CPLT_CB_ID SDRAM DMA Xfer Complete callback ID - * @arg @ref HAL_SDRAM_DMA_XFER_ERR_CB_ID SDRAM DMA Xfer Error callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_SDRAM_RegisterDmaCallback(SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId, pSDRAM_DmaCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_SDRAM_StateTypeDef state; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hsdram); - - state = hsdram->State; - if((state == HAL_SDRAM_STATE_READY) || (state == HAL_SDRAM_STATE_WRITE_PROTECTED)) - { - switch (CallbackId) - { - case HAL_SDRAM_DMA_XFER_CPLT_CB_ID : - hsdram->DmaXferCpltCallback = pCallback; - break; - case HAL_SDRAM_DMA_XFER_ERR_CB_ID : - hsdram->DmaXferErrorCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsdram); - return status; -} -#endif - -/** - * @} - */ - -/** @defgroup SDRAM_Exported_Functions_Group3 Control functions - * @brief management functions - * -@verbatim - ============================================================================== - ##### SDRAM Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the SDRAM interface. - -@endverbatim - * @{ - */ - -/** - * @brief Enables dynamically SDRAM write protection. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_WriteProtection_Enable(SDRAM_HandleTypeDef *hsdram) -{ - /* Check the SDRAM controller state */ - if(hsdram->State == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_BUSY; - - /* Enable write protection */ - FMC_SDRAM_WriteProtection_Enable(hsdram->Instance, hsdram->Init.SDBank); - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_WRITE_PROTECTED; - - return HAL_OK; -} - -/** - * @brief Disables dynamically SDRAM write protection. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_WriteProtection_Disable(SDRAM_HandleTypeDef *hsdram) -{ - /* Check the SDRAM controller state */ - if(hsdram->State == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_BUSY; - - /* Disable write protection */ - FMC_SDRAM_WriteProtection_Disable(hsdram->Instance, hsdram->Init.SDBank); - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Sends Command to the SDRAM bank. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param Command SDRAM command structure - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_SendCommand(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout) -{ - /* Check the SDRAM controller state */ - if(hsdram->State == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_BUSY; - - /* Send SDRAM command */ - FMC_SDRAM_SendCommand(hsdram->Instance, Command, Timeout); - - /* Update the SDRAM controller state */ - if(Command->CommandMode == FMC_SDRAM_CMD_PALL) - { - hsdram->State = HAL_SDRAM_STATE_PRECHARGED; - } - else - { - hsdram->State = HAL_SDRAM_STATE_READY; - } - - return HAL_OK; -} - -/** - * @brief Programs the SDRAM Memory Refresh rate. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param RefreshRate The SDRAM refresh rate value - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_ProgramRefreshRate(SDRAM_HandleTypeDef *hsdram, uint32_t RefreshRate) -{ - /* Check the SDRAM controller state */ - if(hsdram->State == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_BUSY; - - /* Program the refresh rate */ - FMC_SDRAM_ProgramRefreshRate(hsdram->Instance ,RefreshRate); - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Sets the Number of consecutive SDRAM Memory auto Refresh commands. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @param AutoRefreshNumber The SDRAM auto Refresh number - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SDRAM_SetAutoRefreshNumber(SDRAM_HandleTypeDef *hsdram, uint32_t AutoRefreshNumber) -{ - /* Check the SDRAM controller state */ - if(hsdram->State == HAL_SDRAM_STATE_BUSY) - { - return HAL_BUSY; - } - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_BUSY; - - /* Set the Auto-Refresh number */ - FMC_SDRAM_SetAutoRefreshNumber(hsdram->Instance ,AutoRefreshNumber); - - /* Update the SDRAM state */ - hsdram->State = HAL_SDRAM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Returns the SDRAM memory current mode. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval The SDRAM memory mode. - */ -uint32_t HAL_SDRAM_GetModeStatus(SDRAM_HandleTypeDef *hsdram) -{ - /* Return the SDRAM memory current mode */ - return(FMC_SDRAM_GetModeStatus(hsdram->Instance, hsdram->Init.SDBank)); -} - -/** - * @} - */ - -/** @defgroup SDRAM_Exported_Functions_Group4 State functions - * @brief Peripheral State functions - * -@verbatim - ============================================================================== - ##### SDRAM State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the SDRAM controller - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Returns the SDRAM state. - * @param hsdram pointer to a SDRAM_HandleTypeDef structure that contains - * the configuration information for SDRAM module. - * @retval HAL state - */ -HAL_SDRAM_StateTypeDef HAL_SDRAM_GetState(SDRAM_HandleTypeDef *hsdram) -{ - return hsdram->State; -} - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -#endif /* HAL_SDRAM_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smartcard.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smartcard.c deleted file mode 100644 index 6746744c036c144..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smartcard.c +++ /dev/null @@ -1,2363 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_smartcard.c - * @author MCD Application Team - * @brief SMARTCARD HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the SMARTCARD peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Error functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The SMARTCARD HAL driver can be used as follows: - - (#) Declare a SMARTCARD_HandleTypeDef handle structure. - (#) Initialize the SMARTCARD low level resources by implementing the HAL_SMARTCARD_MspInit() API: - (##) Enable the interface clock of the USARTx associated to the SMARTCARD. - (##) SMARTCARD pins configuration: - (+++) Enable the clock for the SMARTCARD GPIOs. - (+++) Configure SMARTCARD pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_SMARTCARD_Transmit_IT() - and HAL_SMARTCARD_Receive_IT() APIs): - (+++) Configure the USARTx interrupt priority. - (+++) Enable the NVIC USART IRQ handle. - (##) DMA Configuration if you need to use DMA process (HAL_SMARTCARD_Transmit_DMA() - and HAL_SMARTCARD_Receive_DMA() APIs): - (+++) Declare a DMA handle structure for the Tx/Rx stream. - (+++) Enable the DMAx interface clock. - (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. - (+++) Configure the DMA Tx/Rx stream. - (+++) Associate the initialized DMA handle to the SMARTCARD DMA Tx/Rx handle. - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx stream. - (+++) Configure the USARTx interrupt priority and enable the NVIC USART IRQ handle - (used for last byte sending completion detection in DMA non circular mode) - - (#) Program the Baud Rate, Word Length , Stop Bit, Parity, Hardware - flow control and Mode(Receiver/Transmitter) in the SMARTCARD Init structure. - - (#) Initialize the SMARTCARD registers by calling the HAL_SMARTCARD_Init() API: - (++) These APIs configure also the low level Hardware GPIO, CLOCK, CORTEX...etc) - by calling the customized HAL_SMARTCARD_MspInit() API. - [..] - (@) The specific SMARTCARD interrupts (Transmission complete interrupt, - RXNE interrupt and Error Interrupts) will be managed using the macros - __HAL_SMARTCARD_ENABLE_IT() and __HAL_SMARTCARD_DISABLE_IT() inside the transmit and receive process. - - [..] - Three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Send an amount of data in blocking mode using HAL_SMARTCARD_Transmit() - (+) Receive an amount of data in blocking mode using HAL_SMARTCARD_Receive() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Send an amount of data in non blocking mode using HAL_SMARTCARD_Transmit_IT() - (+) At transmission end of transfer HAL_SMARTCARD_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_SMARTCARD_TxCpltCallback - (+) Receive an amount of data in non blocking mode using HAL_SMARTCARD_Receive_IT() - (+) At reception end of transfer HAL_SMARTCARD_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_SMARTCARD_RxCpltCallback - (+) In case of transfer Error, HAL_SMARTCARD_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_SMARTCARD_ErrorCallback - - *** DMA mode IO operation *** - ============================== - [..] - (+) Send an amount of data in non blocking mode (DMA) using HAL_SMARTCARD_Transmit_DMA() - (+) At transmission end of transfer HAL_SMARTCARD_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_SMARTCARD_TxCpltCallback - (+) Receive an amount of data in non blocking mode (DMA) using HAL_SMARTCARD_Receive_DMA() - (+) At reception end of transfer HAL_SMARTCARD_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_SMARTCARD_RxCpltCallback - (+) In case of transfer Error, HAL_SMARTCARD_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_SMARTCARD_ErrorCallback - - *** SMARTCARD HAL driver macros list *** - ======================================== - [..] - Below the list of most used macros in SMARTCARD HAL driver. - - (+) __HAL_SMARTCARD_ENABLE: Enable the SMARTCARD peripheral - (+) __HAL_SMARTCARD_DISABLE: Disable the SMARTCARD peripheral - (+) __HAL_SMARTCARD_GET_FLAG : Check whether the specified SMARTCARD flag is set or not - (+) __HAL_SMARTCARD_CLEAR_FLAG : Clear the specified SMARTCARD pending flag - (+) __HAL_SMARTCARD_ENABLE_IT: Enable the specified SMARTCARD interrupt - (+) __HAL_SMARTCARD_DISABLE_IT: Disable the specified SMARTCARD interrupt - - [..] - (@) You can refer to the SMARTCARD HAL driver header file for more useful macros - - ##### Callback registration ##### - ================================== - - [..] - The compilation define USE_HAL_SMARTCARD_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - [..] - Use Function HAL_SMARTCARD_RegisterCallback() to register a user callback. - Function HAL_SMARTCARD_RegisterCallback() allows to register following callbacks: - (+) TxCpltCallback : Tx Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. - (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. - (+) MspInitCallback : SMARTCARD MspInit. - (+) MspDeInitCallback : SMARTCARD MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_SMARTCARD_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - HAL_SMARTCARD_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxCpltCallback : Tx Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. - (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. - (+) MspInitCallback : SMARTCARD MspInit. - (+) MspDeInitCallback : SMARTCARD MspDeInit. - - [..] - By default, after the HAL_SMARTCARD_Init() and when the state is HAL_SMARTCARD_STATE_RESET - all callbacks are set to the corresponding weak (surcharged) functions: - examples HAL_SMARTCARD_TxCpltCallback(), HAL_SMARTCARD_RxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are respectively - reset to the legacy weak (surcharged) functions in the HAL_SMARTCARD_Init() - and HAL_SMARTCARD_DeInit() only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_SMARTCARD_Init() and HAL_SMARTCARD_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in HAL_SMARTCARD_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_SMARTCARD_STATE_READY or HAL_SMARTCARD_STATE_RESET state, thus registered (user) - MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_SMARTCARD_RegisterCallback() before calling HAL_SMARTCARD_DeInit() - or HAL_SMARTCARD_Init() function. - - [..] - When The compilation define USE_HAL_SMARTCARD_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SMARTCARD SMARTCARD - * @brief HAL SMARTCARD module driver - * @{ - */ -#ifdef HAL_SMARTCARD_MODULE_ENABLED -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup SMARTCARD_Private_Constants - * @{ - */ -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup SMARTCARD_Private_Functions - * @{ - */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -void SMARTCARD_InitCallbacksToDefault(SMARTCARD_HandleTypeDef *hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ -static void SMARTCARD_EndTxTransfer(SMARTCARD_HandleTypeDef *hsc); -static void SMARTCARD_EndRxTransfer(SMARTCARD_HandleTypeDef *hsc); -static void SMARTCARD_SetConfig (SMARTCARD_HandleTypeDef *hsc); -static HAL_StatusTypeDef SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc); -static HAL_StatusTypeDef SMARTCARD_EndTransmit_IT(SMARTCARD_HandleTypeDef *hsc); -static HAL_StatusTypeDef SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc); -static void SMARTCARD_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void SMARTCARD_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void SMARTCARD_DMAError(DMA_HandleTypeDef *hdma); -static void SMARTCARD_DMAAbortOnError(DMA_HandleTypeDef *hdma); -static void SMARTCARD_DMATxAbortCallback(DMA_HandleTypeDef *hdma); -static void SMARTCARD_DMARxAbortCallback(DMA_HandleTypeDef *hdma); -static void SMARTCARD_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma); -static void SMARTCARD_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef SMARTCARD_WaitOnFlagUntilTimeout(SMARTCARD_HandleTypeDef *hsc, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SMARTCARD_Exported_Functions SMARTCARD Exported Functions - * @{ - */ - -/** @defgroup SMARTCARD_Exported_Functions_Group1 SmartCard Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and Configuration functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to initialize the USART - in Smartcard mode. - [..] - The Smartcard interface is designed to support asynchronous protocol Smartcards as - defined in the ISO 7816-3 standard. - [..] - The USART can provide a clock to the smartcard through the SCLK output. - In smartcard mode, SCLK is not associated to the communication but is simply derived - from the internal peripheral input clock through a 5-bit prescaler. - [..] - (+) For the Smartcard mode only these parameters can be configured: - (++) Baud Rate - (++) Word Length => Should be 9 bits (8 bits + parity) - (++) Stop Bit - (++) Parity: => Should be enabled - (++) USART polarity - (++) USART phase - (++) USART LastBit - (++) Receiver/transmitter modes - (++) Prescaler - (++) GuardTime - (++) NACKState: The Smartcard NACK state - - (+) Recommended SmartCard interface configuration to get the Answer to Reset from the Card: - (++) Word Length = 9 Bits - (++) 1.5 Stop Bit - (++) Even parity - (++) BaudRate = 12096 baud - (++) Tx and Rx enabled - [..] - Please refer to the ISO 7816-3 specification for more details. - - [..] - (@) It is also possible to choose 0.5 stop bit for receiving but it is recommended - to use 1.5 stop bits for both transmitting and receiving to avoid switching - between the two configurations. - [..] - The HAL_SMARTCARD_Init() function follows the USART SmartCard configuration - procedures (details for the procedures are available in reference manual - (RM0430 for STM32F4X3xx MCUs and RM0402 for STM32F412xx MCUs - RM0383 for STM32F411xC/E MCUs and RM0401 for STM32F410xx MCUs - RM0090 for STM32F4X5xx/STM32F4X7xx/STM32F429xx/STM32F439xx MCUs - RM0390 for STM32F446xx MCUs and RM0386 for STM32F469xx/STM32F479xx MCUs)). - -@endverbatim - - The SMARTCARD frame format is given in the following table: - +-------------------------------------------------------------+ - | M bit | PCE bit | SMARTCARD frame | - |---------------------|---------------------------------------| - | 1 | 1 | | SB | 8 bit data | PB | STB | | - +-------------------------------------------------------------+ - * @{ - */ - -/** - * @brief Initializes the SmartCard mode according to the specified - * parameters in the SMARTCARD_InitTypeDef and create the associated handle. - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_Init(SMARTCARD_HandleTypeDef *hsc) -{ - /* Check the SMARTCARD handle allocation */ - if(hsc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SMARTCARD_INSTANCE(hsc->Instance)); - assert_param(IS_SMARTCARD_NACK_STATE(hsc->Init.NACKState)); - - if(hsc->gState == HAL_SMARTCARD_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hsc->Lock = HAL_UNLOCKED; - -#if USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1 - SMARTCARD_InitCallbacksToDefault(hsc); - - if (hsc->MspInitCallback == NULL) - { - hsc->MspInitCallback = HAL_SMARTCARD_MspInit; - } - - /* Init the low level hardware */ - hsc->MspInitCallback(hsc); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_SMARTCARD_MspInit(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - } - - hsc->gState = HAL_SMARTCARD_STATE_BUSY; - - /* Set the Prescaler */ - MODIFY_REG(hsc->Instance->GTPR, USART_GTPR_PSC, hsc->Init.Prescaler); - - /* Set the Guard Time */ - MODIFY_REG(hsc->Instance->GTPR, USART_GTPR_GT, ((hsc->Init.GuardTime)<<8U)); - - /* Set the Smartcard Communication parameters */ - SMARTCARD_SetConfig(hsc); - - /* In SmartCard mode, the following bits must be kept cleared: - - LINEN bit in the USART_CR2 register - - HDSEL and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(hsc->Instance->CR2, USART_CR2_LINEN); - CLEAR_BIT(hsc->Instance->CR3, (USART_CR3_IREN | USART_CR3_HDSEL)); - - /* Enable the SMARTCARD Parity Error Interrupt */ - SET_BIT(hsc->Instance->CR1, USART_CR1_PEIE); - - /* Enable the SMARTCARD Framing Error Interrupt */ - SET_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Enable the Peripheral */ - __HAL_SMARTCARD_ENABLE(hsc); - - /* Configure the Smartcard NACK state */ - MODIFY_REG(hsc->Instance->CR3, USART_CR3_NACK, hsc->Init.NACKState); - - /* Enable the SC mode by setting the SCEN bit in the CR3 register */ - hsc->Instance->CR3 |= (USART_CR3_SCEN); - - /* Initialize the SMARTCARD state*/ - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - hsc->gState= HAL_SMARTCARD_STATE_READY; - hsc->RxState= HAL_SMARTCARD_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the USART SmartCard peripheral - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_DeInit(SMARTCARD_HandleTypeDef *hsc) -{ - /* Check the SMARTCARD handle allocation */ - if(hsc == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SMARTCARD_INSTANCE(hsc->Instance)); - - hsc->gState = HAL_SMARTCARD_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_SMARTCARD_DISABLE(hsc); - - /* DeInit the low level hardware */ -#if USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1 - if (hsc->MspDeInitCallback == NULL) - { - hsc->MspDeInitCallback = HAL_SMARTCARD_MspDeInit; - } - /* DeInit the low level hardware */ - hsc->MspDeInitCallback(hsc); -#else - HAL_SMARTCARD_MspDeInit(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - hsc->gState = HAL_SMARTCARD_STATE_RESET; - hsc->RxState = HAL_SMARTCARD_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hsc); - - return HAL_OK; -} - -/** - * @brief SMARTCARD MSP Init - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -__weak void HAL_SMARTCARD_MspInit(SMARTCARD_HandleTypeDef *hsc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMARTCARD_MspInit can be implemented in the user file - */ -} - -/** - * @brief SMARTCARD MSP DeInit - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -__weak void HAL_SMARTCARD_MspDeInit(SMARTCARD_HandleTypeDef *hsc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMARTCARD_MspDeInit can be implemented in the user file - */ -} - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User SMARTCARD Callback - * To be used instead of the weak predefined callback - * @param hsc smartcard handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_SMARTCARD_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_SMARTCARD_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_SMARTCARD_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_SMARTCARD_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID - * @arg @ref HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID - * @arg @ref HAL_SMARTCARD_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_SMARTCARD_MSPDEINIT_CB_ID MspDeInit Callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_RegisterCallback(SMARTCARD_HandleTypeDef *hsc, HAL_SMARTCARD_CallbackIDTypeDef CallbackID, pSMARTCARD_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hsc); - - if (hsc->gState == HAL_SMARTCARD_STATE_READY) - { - switch (CallbackID) - { - - case HAL_SMARTCARD_TX_COMPLETE_CB_ID : - hsc->TxCpltCallback = pCallback; - break; - - case HAL_SMARTCARD_RX_COMPLETE_CB_ID : - hsc->RxCpltCallback = pCallback; - break; - - case HAL_SMARTCARD_ERROR_CB_ID : - hsc->ErrorCallback = pCallback; - break; - - case HAL_SMARTCARD_ABORT_COMPLETE_CB_ID : - hsc->AbortCpltCallback = pCallback; - break; - - case HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID : - hsc->AbortTransmitCpltCallback = pCallback; - break; - - case HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID : - hsc->AbortReceiveCpltCallback = pCallback; - break; - - - case HAL_SMARTCARD_MSPINIT_CB_ID : - hsc->MspInitCallback = pCallback; - break; - - case HAL_SMARTCARD_MSPDEINIT_CB_ID : - hsc->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (hsc->gState == HAL_SMARTCARD_STATE_RESET) - { - switch (CallbackID) - { - case HAL_SMARTCARD_MSPINIT_CB_ID : - hsc->MspInitCallback = pCallback; - break; - - case HAL_SMARTCARD_MSPDEINIT_CB_ID : - hsc->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsc); - - return status; -} - -/** - * @brief Unregister an SMARTCARD callback - * SMARTCARD callback is redirected to the weak predefined callback - * @param hsc smartcard handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_SMARTCARD_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_SMARTCARD_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_SMARTCARD_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_SMARTCARD_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID - * @arg @ref HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID - * @arg @ref HAL_SMARTCARD_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_SMARTCARD_MSPDEINIT_CB_ID MspDeInit Callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_UnRegisterCallback(SMARTCARD_HandleTypeDef *hsc, HAL_SMARTCARD_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hsc); - - if (HAL_SMARTCARD_STATE_READY == hsc->gState) - { - switch (CallbackID) - { - case HAL_SMARTCARD_TX_COMPLETE_CB_ID : - hsc->TxCpltCallback = HAL_SMARTCARD_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_SMARTCARD_RX_COMPLETE_CB_ID : - hsc->RxCpltCallback = HAL_SMARTCARD_RxCpltCallback; /* Legacy weak RxCpltCallback */ - break; - - case HAL_SMARTCARD_ERROR_CB_ID : - hsc->ErrorCallback = HAL_SMARTCARD_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_SMARTCARD_ABORT_COMPLETE_CB_ID : - hsc->AbortCpltCallback = HAL_SMARTCARD_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID : - hsc->AbortTransmitCpltCallback = HAL_SMARTCARD_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ - break; - - case HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID : - hsc->AbortReceiveCpltCallback = HAL_SMARTCARD_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ - break; - - - case HAL_SMARTCARD_MSPINIT_CB_ID : - hsc->MspInitCallback = HAL_SMARTCARD_MspInit; /* Legacy weak MspInitCallback */ - break; - - case HAL_SMARTCARD_MSPDEINIT_CB_ID : - hsc->MspDeInitCallback = HAL_SMARTCARD_MspDeInit; /* Legacy weak MspDeInitCallback */ - break; - - default : - /* Update the error code */ - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SMARTCARD_STATE_RESET == hsc->gState) - { - switch (CallbackID) - { - case HAL_SMARTCARD_MSPINIT_CB_ID : - hsc->MspInitCallback = HAL_SMARTCARD_MspInit; - break; - - case HAL_SMARTCARD_MSPDEINIT_CB_ID : - hsc->MspDeInitCallback = HAL_SMARTCARD_MspDeInit; - break; - - default : - /* Update the error code */ - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsc); - - return status; -} -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup SMARTCARD_Exported_Functions_Group2 IO operation functions - * @brief SMARTCARD Transmit and Receive functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the SMARTCARD data transfers. - - [..] - (#) Smartcard is a single wire half duplex communication protocol. - The Smartcard interface is designed to support asynchronous protocol Smartcards as - defined in the ISO 7816-3 standard. - (#) The USART should be configured as: - (++) 8 bits plus parity: where M=1 and PCE=1 in the USART_CR1 register - (++) 1.5 stop bits when transmitting and receiving: where STOP=11 in the USART_CR2 register. - - (#) There are two modes of transfer: - (++) Blocking mode: The communication is performed in polling mode. - The HAL status of all data processing is returned by the same function - after finishing transfer. - (++) Non Blocking mode: The communication is performed using Interrupts - or DMA, These APIs return the HAL status. - The end of the data processing will be indicated through the - dedicated SMARTCARD IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - The HAL_SMARTCARD_TxCpltCallback(), HAL_SMARTCARD_RxCpltCallback() user callbacks - will be executed respectively at the end of the Transmit or Receive process - The HAL_SMARTCARD_ErrorCallback() user callback will be executed when a communication error is detected - - (#) Blocking mode APIs are : - (++) HAL_SMARTCARD_Transmit() - (++) HAL_SMARTCARD_Receive() - - (#) Non Blocking mode APIs with Interrupt are : - (++) HAL_SMARTCARD_Transmit_IT() - (++) HAL_SMARTCARD_Receive_IT() - (++) HAL_SMARTCARD_IRQHandler() - - (#) Non Blocking mode functions with DMA are : - (++) HAL_SMARTCARD_Transmit_DMA() - (++) HAL_SMARTCARD_Receive_DMA() - - (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: - (++) HAL_SMARTCARD_TxCpltCallback() - (++) HAL_SMARTCARD_RxCpltCallback() - (++) HAL_SMARTCARD_ErrorCallback() - - (#) Non-Blocking mode transfers could be aborted using Abort API's : - (+) HAL_SMARTCARD_Abort() - (+) HAL_SMARTCARD_AbortTransmit() - (+) HAL_SMARTCARD_AbortReceive() - (+) HAL_SMARTCARD_Abort_IT() - (+) HAL_SMARTCARD_AbortTransmit_IT() - (+) HAL_SMARTCARD_AbortReceive_IT() - - (#) For Abort services based on interrupts (HAL_SMARTCARD_Abortxxx_IT), a set of Abort Complete Callbacks are provided: - (+) HAL_SMARTCARD_AbortCpltCallback() - (+) HAL_SMARTCARD_AbortTransmitCpltCallback() - (+) HAL_SMARTCARD_AbortReceiveCpltCallback() - - (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. - Errors are handled as follows : - (+) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is - to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . - Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, - and HAL_SMARTCARD_ErrorCallback() user callback is executed. Transfer is kept ongoing on SMARTCARD side. - If user wants to abort it, Abort services should be called by user. - (+) Error is considered as Blocking : Transfer could not be completed properly and is aborted. - This concerns Frame Error in Interrupt mode transmission, Overrun Error in Interrupt mode reception and all errors in DMA mode. - Error code is set to allow user to identify error type, and HAL_SMARTCARD_ErrorCallback() user callback is executed. - -@endverbatim - * @{ - */ - -/** - * @brief Send an amount of data in blocking mode - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_Transmit(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint8_t *tmp = pData; - uint32_t tickstart = 0U; - - if(hsc->gState == HAL_SMARTCARD_STATE_READY) - { - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsc); - - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - hsc->gState = HAL_SMARTCARD_STATE_BUSY_TX; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - hsc->TxXferSize = Size; - hsc->TxXferCount = Size; - while(hsc->TxXferCount > 0U) - { - hsc->TxXferCount--; - if(SMARTCARD_WaitOnFlagUntilTimeout(hsc, SMARTCARD_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - hsc->Instance->DR = (uint8_t)(*tmp & 0xFFU); - tmp++; - } - - if(SMARTCARD_WaitOnFlagUntilTimeout(hsc, SMARTCARD_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* At end of Tx process, restore hsc->gState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsc); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in blocking mode - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be received - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_Receive(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint8_t *tmp = pData; - uint32_t tickstart = 0U; - - if(hsc->RxState == HAL_SMARTCARD_STATE_READY) - { - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsc); - - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - hsc->RxState = HAL_SMARTCARD_STATE_BUSY_RX; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - hsc->RxXferSize = Size; - hsc->RxXferCount = Size; - - /* Check the remain data to be received */ - while(hsc->RxXferCount > 0U) - { - hsc->RxXferCount--; - if(SMARTCARD_WaitOnFlagUntilTimeout(hsc, SMARTCARD_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - *tmp = (uint8_t)(hsc->Instance->DR & (uint8_t)0xFFU); - tmp++; - } - - /* At end of Rx process, restore hsc->RxState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsc); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Send an amount of data in non blocking mode - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size) -{ - /* Check that a Tx process is not already ongoing */ - if(hsc->gState == HAL_SMARTCARD_STATE_READY) - { - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsc); - - hsc->pTxBuffPtr = pData; - hsc->TxXferSize = Size; - hsc->TxXferCount = Size; - - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - hsc->gState = HAL_SMARTCARD_STATE_BUSY_TX; - - /* Process Unlocked */ - __HAL_UNLOCK(hsc); - - /* Enable the SMARTCARD Parity Error Interrupt */ - SET_BIT(hsc->Instance->CR1, USART_CR1_PEIE); - - /* Disable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Enable the SMARTCARD Transmit data register empty Interrupt */ - SET_BIT(hsc->Instance->CR1, USART_CR1_TXEIE); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in non blocking mode - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size) -{ - /* Check that a Rx process is not already ongoing */ - if(hsc->RxState == HAL_SMARTCARD_STATE_READY) - { - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsc); - - hsc->pRxBuffPtr = pData; - hsc->RxXferSize = Size; - hsc->RxXferCount = Size; - - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - hsc->RxState = HAL_SMARTCARD_STATE_BUSY_RX; - - /* Process Unlocked */ - __HAL_UNLOCK(hsc); - - /* Enable the SMARTCARD Parity Error and Data Register not empty Interrupts */ - SET_BIT(hsc->Instance->CR1, USART_CR1_PEIE| USART_CR1_RXNEIE); - - /* Enable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ - SET_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Send an amount of data in non blocking mode - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_Transmit_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size) -{ - uint32_t *tmp; - - /* Check that a Tx process is not already ongoing */ - if(hsc->gState == HAL_SMARTCARD_STATE_READY) - { - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsc); - - hsc->pTxBuffPtr = pData; - hsc->TxXferSize = Size; - hsc->TxXferCount = Size; - - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - hsc->gState = HAL_SMARTCARD_STATE_BUSY_TX; - - /* Set the SMARTCARD DMA transfer complete callback */ - hsc->hdmatx->XferCpltCallback = SMARTCARD_DMATransmitCplt; - - /* Set the DMA error callback */ - hsc->hdmatx->XferErrorCallback = SMARTCARD_DMAError; - - /* Set the DMA abort callback */ - hsc->hdmatx->XferAbortCallback = NULL; - - /* Enable the SMARTCARD transmit DMA stream */ - tmp = (uint32_t*)&pData; - HAL_DMA_Start_IT(hsc->hdmatx, *(uint32_t*)tmp, (uint32_t)&hsc->Instance->DR, Size); - - /* Clear the TC flag in the SR register by writing 0 to it */ - __HAL_SMARTCARD_CLEAR_FLAG(hsc, SMARTCARD_FLAG_TC); - - /* Process Unlocked */ - __HAL_UNLOCK(hsc); - - /* Enable the DMA transfer for transmit request by setting the DMAT bit - in the SMARTCARD CR3 register */ - SET_BIT(hsc->Instance->CR3, USART_CR3_DMAT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in non blocking mode - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be received - * @note When the SMARTCARD parity is enabled (PCE = 1) the data received contain the parity bit.s - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMARTCARD_Receive_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size) -{ - uint32_t *tmp; - - /* Check that a Rx process is not already ongoing */ - if(hsc->RxState == HAL_SMARTCARD_STATE_READY) - { - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsc); - - hsc->pRxBuffPtr = pData; - hsc->RxXferSize = Size; - - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - hsc->RxState = HAL_SMARTCARD_STATE_BUSY_RX; - - /* Set the SMARTCARD DMA transfer complete callback */ - hsc->hdmarx->XferCpltCallback = SMARTCARD_DMAReceiveCplt; - - /* Set the DMA error callback */ - hsc->hdmarx->XferErrorCallback = SMARTCARD_DMAError; - - /* Set the DMA abort callback */ - hsc->hdmatx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - tmp = (uint32_t*)&pData; - HAL_DMA_Start_IT(hsc->hdmarx, (uint32_t)&hsc->Instance->DR, *(uint32_t*)tmp, Size); - - /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */ - __HAL_SMARTCARD_CLEAR_OREFLAG(hsc); - - /* Process Unlocked */ - __HAL_UNLOCK(hsc); - - /* Enable the SMARTCARD Parity Error Interrupt */ - SET_BIT(hsc->Instance->CR1, USART_CR1_PEIE); - - /* Enable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ - SET_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Enable the DMA transfer for the receiver request by setting the DMAR bit - in the SMARTCARD CR3 register */ - SET_BIT(hsc->Instance->CR3, USART_CR3_DMAR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Abort ongoing transfers (blocking mode). - * @param hsc SMARTCARD handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_SMARTCARD_Abort(SMARTCARD_HandleTypeDef *hsc) -{ - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Disable the SMARTCARD DMA Tx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) - { - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); - - /* Abort the SMARTCARD DMA Tx channel : use blocking DMA Abort API (no callback) */ - if(hsc->hdmatx != NULL) - { - /* Set the SMARTCARD DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - hsc->hdmatx->XferAbortCallback = NULL; - - HAL_DMA_Abort(hsc->hdmatx); - } - } - - /* Disable the SMARTCARD DMA Rx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); - - /* Abort the SMARTCARD DMA Rx channel : use blocking DMA Abort API (no callback) */ - if(hsc->hdmarx != NULL) - { - /* Set the SMARTCARD DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - hsc->hdmarx->XferAbortCallback = NULL; - - HAL_DMA_Abort(hsc->hdmarx); - } - } - - /* Reset Tx and Rx transfer counters */ - hsc->TxXferCount = 0x00U; - hsc->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - - /* Restore hsc->RxState and hsc->gState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - hsc->gState = HAL_SMARTCARD_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Abort ongoing Transmit transfer (blocking mode). - * @param hsc SMARTCARD handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable SMARTCARD Interrupts (Tx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit(SMARTCARD_HandleTypeDef *hsc) -{ - /* Disable TXEIE and TCIE interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* Disable the SMARTCARD DMA Tx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) - { - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); - - /* Abort the SMARTCARD DMA Tx channel : use blocking DMA Abort API (no callback) */ - if(hsc->hdmatx != NULL) - { - /* Set the SMARTCARD DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - hsc->hdmatx->XferAbortCallback = NULL; - - HAL_DMA_Abort(hsc->hdmatx); - } - } - - /* Reset Tx transfer counter */ - hsc->TxXferCount = 0x00U; - - /* Restore hsc->gState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Abort ongoing Receive transfer (blocking mode). - * @param hsc SMARTCARD handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive(SMARTCARD_HandleTypeDef *hsc) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Disable the SMARTCARD DMA Rx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); - - /* Abort the SMARTCARD DMA Rx channel : use blocking DMA Abort API (no callback) */ - if(hsc->hdmarx != NULL) - { - /* Set the SMARTCARD DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - hsc->hdmarx->XferAbortCallback = NULL; - - HAL_DMA_Abort(hsc->hdmarx); - } - } - - /* Reset Rx transfer counter */ - hsc->RxXferCount = 0x00U; - - /* Restore hsc->RxState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Abort ongoing transfers (Interrupt mode). - * @param hsc SMARTCARD handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_SMARTCARD_Abort_IT(SMARTCARD_HandleTypeDef *hsc) -{ - uint32_t AbortCplt = 0x01U; - - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* If DMA Tx and/or DMA Rx Handles are associated to SMARTCARD Handle, DMA Abort complete callbacks should be initialised - before any call to DMA Abort functions */ - /* DMA Tx Handle is valid */ - if(hsc->hdmatx != NULL) - { - /* Set DMA Abort Complete callback if SMARTCARD DMA Tx request if enabled. - Otherwise, set it to NULL */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) - { - hsc->hdmatx->XferAbortCallback = SMARTCARD_DMATxAbortCallback; - } - else - { - hsc->hdmatx->XferAbortCallback = NULL; - } - } - /* DMA Rx Handle is valid */ - if(hsc->hdmarx != NULL) - { - /* Set DMA Abort Complete callback if SMARTCARD DMA Rx request if enabled. - Otherwise, set it to NULL */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) - { - hsc->hdmarx->XferAbortCallback = SMARTCARD_DMARxAbortCallback; - } - else - { - hsc->hdmarx->XferAbortCallback = NULL; - } - } - - /* Disable the SMARTCARD DMA Tx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) - { - /* Disable DMA Tx at SMARTCARD level */ - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); - - /* Abort the SMARTCARD DMA Tx channel : use non blocking DMA Abort API (callback) */ - if(hsc->hdmatx != NULL) - { - /* SMARTCARD Tx DMA Abort callback has already been initialised : - will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA TX */ - if(HAL_DMA_Abort_IT(hsc->hdmatx) != HAL_OK) - { - hsc->hdmatx->XferAbortCallback = NULL; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* Disable the SMARTCARD DMA Rx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); - - /* Abort the SMARTCARD DMA Rx channel : use non blocking DMA Abort API (callback) */ - if(hsc->hdmarx != NULL) - { - /* SMARTCARD Rx DMA Abort callback has already been initialised : - will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA RX */ - if(HAL_DMA_Abort_IT(hsc->hdmarx) != HAL_OK) - { - hsc->hdmarx->XferAbortCallback = NULL; - AbortCplt = 0x01U; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ - if(AbortCplt == 0x01U) - { - /* Reset Tx and Rx transfer counters */ - hsc->TxXferCount = 0x00U; - hsc->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - - /* Restore hsc->gState and hsc->RxState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - hsc->RxState = HAL_SMARTCARD_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - hsc->AbortCpltCallback(hsc); -#else - /* Call legacy weak Abort complete callback */ - HAL_SMARTCARD_AbortCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - } - return HAL_OK; -} - -/** - * @brief Abort ongoing Transmit transfer (Interrupt mode). - * @param hsc SMARTCARD handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable SMARTCARD Interrupts (Tx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit_IT(SMARTCARD_HandleTypeDef *hsc) -{ - /* Disable TXEIE and TCIE interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* Disable the SMARTCARD DMA Tx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT)) - { - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); - - /* Abort the SMARTCARD DMA Tx channel : use blocking DMA Abort API (no callback) */ - if(hsc->hdmatx != NULL) - { - /* Set the SMARTCARD DMA Abort callback : - will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */ - hsc->hdmatx->XferAbortCallback = SMARTCARD_DMATxOnlyAbortCallback; - - /* Abort DMA TX */ - if(HAL_DMA_Abort_IT(hsc->hdmatx) != HAL_OK) - { - /* Call Directly hsc->hdmatx->XferAbortCallback function in case of error */ - hsc->hdmatx->XferAbortCallback(hsc->hdmatx); - } - } - else - { - /* Reset Tx transfer counter */ - hsc->TxXferCount = 0x00U; - - /* Restore hsc->gState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - hsc->AbortTransmitCpltCallback(hsc); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_SMARTCARD_AbortTransmitCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - } - } - else - { - /* Reset Tx transfer counter */ - hsc->TxXferCount = 0x00U; - - /* Restore hsc->gState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - hsc->AbortTransmitCpltCallback(hsc); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_SMARTCARD_AbortTransmitCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing Receive transfer (Interrupt mode). - * @param hsc SMARTCARD handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable SMARTCARD Interrupts (Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status -*/ -HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive_IT(SMARTCARD_HandleTypeDef *hsc) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Disable the SMARTCARD DMA Rx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); - - /* Abort the SMARTCARD DMA Rx channel : use blocking DMA Abort API (no callback) */ - if(hsc->hdmarx != NULL) - { - /* Set the SMARTCARD DMA Abort callback : - will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */ - hsc->hdmarx->XferAbortCallback = SMARTCARD_DMARxOnlyAbortCallback; - - /* Abort DMA RX */ - if(HAL_DMA_Abort_IT(hsc->hdmarx) != HAL_OK) - { - /* Call Directly hsc->hdmarx->XferAbortCallback function in case of error */ - hsc->hdmarx->XferAbortCallback(hsc->hdmarx); - } - } - else - { - /* Reset Rx transfer counter */ - hsc->RxXferCount = 0x00U; - - /* Restore hsc->RxState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - hsc->AbortReceiveCpltCallback(hsc); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_SMARTCARD_AbortReceiveCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - } - } - else - { - /* Reset Rx transfer counter */ - hsc->RxXferCount = 0x00U; - - /* Restore hsc->RxState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - hsc->AbortReceiveCpltCallback(hsc); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_SMARTCARD_AbortReceiveCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - } - - return HAL_OK; -} - -/** - * @brief This function handles SMARTCARD interrupt request. - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -void HAL_SMARTCARD_IRQHandler(SMARTCARD_HandleTypeDef *hsc) -{ - uint32_t isrflags = READ_REG(hsc->Instance->SR); - uint32_t cr1its = READ_REG(hsc->Instance->CR1); - uint32_t cr3its = READ_REG(hsc->Instance->CR3); - uint32_t dmarequest = 0x00U; - uint32_t errorflags = 0x00U; - - /* If no error occurs */ - errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); - if(errorflags == RESET) - { - /* SMARTCARD in mode Receiver -------------------------------------------------*/ - if(((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - SMARTCARD_Receive_IT(hsc); - return; - } - } - - /* If some errors occur */ - if((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) - { - /* SMARTCARD parity error interrupt occurred ---------------------------*/ - if(((isrflags & SMARTCARD_FLAG_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) - { - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_PE; - } - - /* SMARTCARD frame error interrupt occurred ----------------------------*/ - if(((isrflags & SMARTCARD_FLAG_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_FE; - } - - /* SMARTCARD noise error interrupt occurred ----------------------------*/ - if(((isrflags & SMARTCARD_FLAG_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_NE; - } - - /* SMARTCARD Over-Run interrupt occurred -------------------------------*/ - if(((isrflags & SMARTCARD_FLAG_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET))) - { - hsc->ErrorCode |= HAL_SMARTCARD_ERROR_ORE; - } - /* Call the Error call Back in case of Errors --------------------------*/ - if(hsc->ErrorCode != HAL_SMARTCARD_ERROR_NONE) - { - /* SMARTCARD in mode Receiver ----------------------------------------*/ - if(((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - SMARTCARD_Receive_IT(hsc); - } - - /* If Overrun error occurs, or if any error occurs in DMA mode reception, - consider error as blocking */ - dmarequest = HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR); - if(((hsc->ErrorCode & HAL_SMARTCARD_ERROR_ORE) != RESET) || dmarequest) - { - /* Blocking error : transfer is aborted - Set the SMARTCARD state ready to be able to start again the process, - Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ - SMARTCARD_EndRxTransfer(hsc); - /* Disable the SMARTCARD DMA Rx request if enabled */ - if(HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); - - /* Abort the SMARTCARD DMA Rx channel */ - if(hsc->hdmarx != NULL) - { - /* Set the SMARTCARD DMA Abort callback : - will lead to call HAL_SMARTCARD_ErrorCallback() at end of DMA abort procedure */ - hsc->hdmarx->XferAbortCallback = SMARTCARD_DMAAbortOnError; - - if(HAL_DMA_Abort_IT(hsc->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - hsc->hdmarx->XferAbortCallback(hsc->hdmarx); - } - } - else - { -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hsc->ErrorCallback(hsc); -#else - /* Call legacy weak user error callback */ - HAL_SMARTCARD_ErrorCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - } - } - else - { -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hsc->ErrorCallback(hsc); -#else - /* Call legacy weak user error callback */ - HAL_SMARTCARD_ErrorCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - } - } - else - { - /* Non Blocking error : transfer could go on. - Error is notified to user through user error callback */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hsc->ErrorCallback(hsc); -#else - /* Call legacy weak user error callback */ - HAL_SMARTCARD_ErrorCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - } - } - return; - } /* End if some error occurs */ - - /* SMARTCARD in mode Transmitter ------------------------------------------*/ - if(((isrflags & SMARTCARD_FLAG_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) - { - SMARTCARD_Transmit_IT(hsc); - return; - } - - /* SMARTCARD in mode Transmitter (transmission end) -----------------------*/ - if(((isrflags & SMARTCARD_FLAG_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) - { - SMARTCARD_EndTransmit_IT(hsc); - return; - } -} - -/** - * @brief Tx Transfer completed callbacks - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -__weak void HAL_SMARTCARD_TxCpltCallback(SMARTCARD_HandleTypeDef *hsc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMARTCARD_TxCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief Rx Transfer completed callback - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -__weak void HAL_SMARTCARD_RxCpltCallback(SMARTCARD_HandleTypeDef *hsc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMARTCARD_RxCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief SMARTCARD error callback - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -__weak void HAL_SMARTCARD_ErrorCallback(SMARTCARD_HandleTypeDef *hsc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMARTCARD_ErrorCallback can be implemented in the user file. - */ -} - -/** - * @brief SMARTCARD Abort Complete callback. - * @param hsc SMARTCARD handle. - * @retval None - */ -__weak void HAL_SMARTCARD_AbortCpltCallback (SMARTCARD_HandleTypeDef *hsc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMARTCARD_AbortCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief SMARTCARD Abort Transmit Complete callback. - * @param hsc SMARTCARD handle. - * @retval None - */ -__weak void HAL_SMARTCARD_AbortTransmitCpltCallback (SMARTCARD_HandleTypeDef *hsc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMARTCARD_AbortTransmitCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief SMARTCARD Abort Receive Complete callback. - * @param hsc SMARTCARD handle. - * @retval None - */ -__weak void HAL_SMARTCARD_AbortReceiveCpltCallback (SMARTCARD_HandleTypeDef *hsc) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsc); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMARTCARD_AbortReceiveCpltCallback can be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup SMARTCARD_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief SMARTCARD State and Errors functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the SmartCard. - (+) HAL_SMARTCARD_GetState() API can be helpful to check in run-time the state of the SmartCard peripheral. - (+) HAL_SMARTCARD_GetError() check in run-time errors that could be occurred during communication. -@endverbatim - * @{ - */ - -/** - * @brief Return the SMARTCARD handle state - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval HAL state - */ -HAL_SMARTCARD_StateTypeDef HAL_SMARTCARD_GetState(SMARTCARD_HandleTypeDef *hsc) -{ - uint32_t temp1= 0x00U, temp2 = 0x00U; - temp1 = hsc->gState; - temp2 = hsc->RxState; - - return (HAL_SMARTCARD_StateTypeDef)(temp1 | temp2); -} - -/** - * @brief Return the SMARTCARD error code - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for the specified SMARTCARD. - * @retval SMARTCARD Error Code - */ -uint32_t HAL_SMARTCARD_GetError(SMARTCARD_HandleTypeDef *hsc) -{ - return hsc->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup SMARTCARD_Private_Functions SMARTCARD Private Functions - * @{ - */ - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -/** - * @brief Initialize the callbacks to their default values. - * @param hsc SMARTCARD handle. - * @retval none - */ -void SMARTCARD_InitCallbacksToDefault(SMARTCARD_HandleTypeDef *hsc) -{ - /* Init the SMARTCARD Callback settings */ - hsc->TxCpltCallback = HAL_SMARTCARD_TxCpltCallback; /* Legacy weak TxCpltCallback */ - hsc->RxCpltCallback = HAL_SMARTCARD_RxCpltCallback; /* Legacy weak RxCpltCallback */ - hsc->ErrorCallback = HAL_SMARTCARD_ErrorCallback; /* Legacy weak ErrorCallback */ - hsc->AbortCpltCallback = HAL_SMARTCARD_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - hsc->AbortTransmitCpltCallback = HAL_SMARTCARD_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ - hsc->AbortReceiveCpltCallback = HAL_SMARTCARD_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ - -} -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - -/** - * @brief DMA SMARTCARD transmit process complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SMARTCARD_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - hsc->TxXferCount = 0U; - - /* Disable the DMA transfer for transmit request by setting the DMAT bit - in the USART CR3 register */ - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAT); - - /* Enable the SMARTCARD Transmit Complete Interrupt */ - SET_BIT(hsc->Instance->CR1, USART_CR1_TCIE); -} - -/** - * @brief DMA SMARTCARD receive process complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SMARTCARD_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - hsc->RxXferCount = 0U; - - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Disable the DMA transfer for the receiver request by setting the DMAR bit - in the USART CR3 register */ - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_DMAR); - - /* At end of Rx process, restore hsc->RxState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Rx complete callback */ - hsc->RxCpltCallback(hsc); -#else - /* Call legacy weak Rx complete callback */ - HAL_SMARTCARD_RxCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ -} - -/** - * @brief DMA SMARTCARD communication error callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SMARTCARD_DMAError(DMA_HandleTypeDef *hdma) -{ - uint32_t dmarequest = 0x00U; - SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - hsc->RxXferCount = 0U; - hsc->TxXferCount = 0U; - hsc->ErrorCode = HAL_SMARTCARD_ERROR_DMA; - - /* Stop SMARTCARD DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAT); - if((hsc->gState == HAL_SMARTCARD_STATE_BUSY_TX) && dmarequest) - { - SMARTCARD_EndTxTransfer(hsc); - } - - /* Stop SMARTCARD DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(hsc->Instance->CR3, USART_CR3_DMAR); - if((hsc->RxState == HAL_SMARTCARD_STATE_BUSY_RX) && dmarequest) - { - SMARTCARD_EndRxTransfer(hsc); - } - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hsc->ErrorCallback(hsc); -#else - /* Call legacy weak user error callback */ - HAL_SMARTCARD_ErrorCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ -} - -/** - * @brief This function handles SMARTCARD Communication Timeout. - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @param Flag Specifies the SMARTCARD flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SMARTCARD_WaitOnFlagUntilTimeout(SMARTCARD_HandleTypeDef *hsc, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout) -{ - /* Wait until flag is set */ - while((__HAL_SMARTCARD_GET_FLAG(hsc, Flag) ? SET : RESET) == Status) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - Tickstart ) > Timeout)) - { - /* Disable TXE and RXNE interrupts for the interrupt process */ - CLEAR_BIT(hsc->Instance->CR1, USART_CR1_TXEIE); - CLEAR_BIT(hsc->Instance->CR1, USART_CR1_RXNEIE); - - hsc->gState= HAL_SMARTCARD_STATE_READY; - hsc->RxState= HAL_SMARTCARD_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsc); - - return HAL_TIMEOUT; - } - } - } - return HAL_OK; -} - -/** - * @brief End ongoing Tx transfer on SMARTCARD peripheral (following error detection or Transmit completion). - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -static void SMARTCARD_EndTxTransfer(SMARTCARD_HandleTypeDef *hsc) -{ - /* At end of Tx process, restore hsc->gState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - - /* Disable TXEIE and TCIE interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); -} - - -/** - * @brief End ongoing Rx transfer on SMARTCARD peripheral (following error detection or Reception completion). - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -static void SMARTCARD_EndRxTransfer(SMARTCARD_HandleTypeDef *hsc) -{ - /* At end of Rx process, restore hsc->RxState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); -} - -/** - * @brief Send an amount of data in non blocking mode - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval HAL status - */ -static HAL_StatusTypeDef SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc) -{ - - /* Check that a Tx process is ongoing */ - if(hsc->gState == HAL_SMARTCARD_STATE_BUSY_TX) - { - hsc->Instance->DR = (uint8_t)(*hsc->pTxBuffPtr & 0xFFU); - hsc->pTxBuffPtr++; - - if(--hsc->TxXferCount == 0U) - { - /* Disable the SMARTCARD Transmit data register empty Interrupt */ - CLEAR_BIT(hsc->Instance->CR1, USART_CR1_TXEIE); - - /* Enable the SMARTCARD Transmit Complete Interrupt */ - SET_BIT(hsc->Instance->CR1, USART_CR1_TCIE); - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Wraps up transmission in non blocking mode. - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for the specified SMARTCARD module. - * @retval HAL status - */ -static HAL_StatusTypeDef SMARTCARD_EndTransmit_IT(SMARTCARD_HandleTypeDef *hsc) -{ - /* Disable the SMARTCARD Transmit Complete Interrupt */ - CLEAR_BIT(hsc->Instance->CR1, USART_CR1_TCIE); - - /* Disable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Tx process is ended, restore hsc->gState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Tx complete callback */ - hsc->TxCpltCallback(hsc); -#else - /* Call legacy weak Tx complete callback */ - HAL_SMARTCARD_TxCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - - return HAL_OK; -} - -/** - * @brief Receive an amount of data in non blocking mode - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval HAL status - */ -static HAL_StatusTypeDef SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc) -{ - - /* Check that a Rx process is ongoing */ - if(hsc->RxState == HAL_SMARTCARD_STATE_BUSY_RX) - { - *hsc->pRxBuffPtr = (uint8_t)(hsc->Instance->DR & (uint8_t)0xFFU); - hsc->pRxBuffPtr++; - - if(--hsc->RxXferCount == 0U) - { - CLEAR_BIT(hsc->Instance->CR1, USART_CR1_RXNEIE); - - /* Disable the SMARTCARD Parity Error Interrupt */ - CLEAR_BIT(hsc->Instance->CR1, USART_CR1_PEIE); - - /* Disable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(hsc->Instance->CR3, USART_CR3_EIE); - - /* Rx process is completed, restore hsc->RxState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Rx complete callback */ - hsc->RxCpltCallback(hsc); -#else - /* Call legacy weak Rx complete callback */ - HAL_SMARTCARD_RxCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ - - return HAL_OK; - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief DMA SMARTCARD communication abort callback, when initiated by HAL services on Error - * (To be called at end of DMA Abort procedure following error occurrence). - * @param hdma DMA handle. - * @retval None - */ -static void SMARTCARD_DMAAbortOnError(DMA_HandleTypeDef *hdma) -{ - SMARTCARD_HandleTypeDef* hsc = (SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - hsc->RxXferCount = 0x00U; - hsc->TxXferCount = 0x00U; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered user error callback */ - hsc->ErrorCallback(hsc); -#else - /* Call legacy weak user error callback */ - HAL_SMARTCARD_ErrorCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ -} - -/** - * @brief DMA SMARTCARD Tx communication abort callback, when initiated by user - * (To be called at end of DMA Tx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Rx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void SMARTCARD_DMATxAbortCallback(DMA_HandleTypeDef *hdma) -{ - SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - hsc->hdmatx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if(hsc->hdmarx != NULL) - { - if(hsc->hdmarx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - hsc->TxXferCount = 0x00U; - hsc->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - - /* Restore hsc->gState and hsc->RxState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - hsc->RxState = HAL_SMARTCARD_STATE_READY; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - hsc->AbortCpltCallback(hsc); -#else - /* Call legacy weak Abort complete callback */ - HAL_SMARTCARD_AbortCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ -} - -/** - * @brief DMA SMARTCARD Rx communication abort callback, when initiated by user - * (To be called at end of DMA Rx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Tx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void SMARTCARD_DMARxAbortCallback(DMA_HandleTypeDef *hdma) -{ - SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - hsc->hdmarx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if(hsc->hdmatx != NULL) - { - if(hsc->hdmatx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - hsc->TxXferCount = 0x00U; - hsc->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - hsc->ErrorCode = HAL_SMARTCARD_ERROR_NONE; - - /* Restore hsc->gState and hsc->RxState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - hsc->RxState = HAL_SMARTCARD_STATE_READY; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - hsc->AbortCpltCallback(hsc); -#else - /* Call legacy weak Abort complete callback */ - HAL_SMARTCARD_AbortCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ -} - -/** - * @brief DMA SMARTCARD Tx communication abort callback, when initiated by user by a call to - * HAL_SMARTCARD_AbortTransmit_IT API (Abort only Tx transfer) - * (This callback is executed at end of DMA Tx Abort procedure following user abort request, - * and leads to user Tx Abort Complete callback execution). - * @param hdma DMA handle. - * @retval None - */ -static void SMARTCARD_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma) -{ - SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - hsc->TxXferCount = 0x00U; - - /* Restore hsc->gState to Ready */ - hsc->gState = HAL_SMARTCARD_STATE_READY; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - hsc->AbortTransmitCpltCallback(hsc); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_SMARTCARD_AbortTransmitCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ -} - -/** - * @brief DMA SMARTCARD Rx communication abort callback, when initiated by user by a call to - * HAL_SMARTCARD_AbortReceive_IT API (Abort only Rx transfer) - * (This callback is executed at end of DMA Rx Abort procedure following user abort request, - * and leads to user Rx Abort Complete callback execution). - * @param hdma DMA handle. - * @retval None - */ -static void SMARTCARD_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma) -{ - SMARTCARD_HandleTypeDef* hsc = ( SMARTCARD_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - hsc->RxXferCount = 0x00U; - - /* Restore hsc->RxState to Ready */ - hsc->RxState = HAL_SMARTCARD_STATE_READY; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - hsc->AbortReceiveCpltCallback(hsc); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_SMARTCARD_AbortReceiveCpltCallback(hsc); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACK */ -} - -/** - * @brief Configure the SMARTCARD peripheral - * @param hsc Pointer to a SMARTCARD_HandleTypeDef structure that contains - * the configuration information for SMARTCARD module. - * @retval None - */ -static void SMARTCARD_SetConfig(SMARTCARD_HandleTypeDef *hsc) -{ - uint32_t tmpreg = 0x00U; - uint32_t pclk; - - /* Check the parameters */ - assert_param(IS_SMARTCARD_INSTANCE(hsc->Instance)); - assert_param(IS_SMARTCARD_POLARITY(hsc->Init.CLKPolarity)); - assert_param(IS_SMARTCARD_PHASE(hsc->Init.CLKPhase)); - assert_param(IS_SMARTCARD_LASTBIT(hsc->Init.CLKLastBit)); - assert_param(IS_SMARTCARD_BAUDRATE(hsc->Init.BaudRate)); - assert_param(IS_SMARTCARD_WORD_LENGTH(hsc->Init.WordLength)); - assert_param(IS_SMARTCARD_STOPBITS(hsc->Init.StopBits)); - assert_param(IS_SMARTCARD_PARITY(hsc->Init.Parity)); - assert_param(IS_SMARTCARD_MODE(hsc->Init.Mode)); - assert_param(IS_SMARTCARD_NACK_STATE(hsc->Init.NACKState)); - - /* The LBCL, CPOL and CPHA bits have to be selected when both the transmitter and the - receiver are disabled (TE=RE=0) to ensure that the clock pulses function correctly. */ - CLEAR_BIT(hsc->Instance->CR1, (USART_CR1_TE | USART_CR1_RE)); - - /*---------------------------- USART CR2 Configuration ---------------------*/ - tmpreg = hsc->Instance->CR2; - /* Clear CLKEN, CPOL, CPHA and LBCL bits */ - tmpreg &= (uint32_t)~((uint32_t)(USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_CLKEN | USART_CR2_LBCL)); - /* Configure the SMARTCARD Clock, CPOL, CPHA and LastBit -----------------------*/ - /* Set CPOL bit according to hsc->Init.CLKPolarity value */ - /* Set CPHA bit according to hsc->Init.CLKPhase value */ - /* Set LBCL bit according to hsc->Init.CLKLastBit value */ - /* Set Stop Bits: Set STOP[13:12] bits according to hsc->Init.StopBits value */ - tmpreg |= (uint32_t)(USART_CR2_CLKEN | hsc->Init.CLKPolarity | - hsc->Init.CLKPhase| hsc->Init.CLKLastBit | hsc->Init.StopBits); - /* Write to USART CR2 */ - WRITE_REG(hsc->Instance->CR2, (uint32_t)tmpreg); - - tmpreg = hsc->Instance->CR2; - - /* Clear STOP[13:12] bits */ - tmpreg &= (uint32_t)~((uint32_t)USART_CR2_STOP); - - /* Set Stop Bits: Set STOP[13:12] bits according to hsc->Init.StopBits value */ - tmpreg |= (uint32_t)(hsc->Init.StopBits); - - /* Write to USART CR2 */ - WRITE_REG(hsc->Instance->CR2, (uint32_t)tmpreg); - - /*-------------------------- USART CR1 Configuration -----------------------*/ - tmpreg = hsc->Instance->CR1; - - /* Clear M, PCE, PS, TE and RE bits */ - tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | \ - USART_CR1_RE)); - - /* Configure the SMARTCARD Word Length, Parity and mode: - Set the M bits according to hsc->Init.WordLength value - Set PCE and PS bits according to hsc->Init.Parity value - Set TE and RE bits according to hsc->Init.Mode value */ - tmpreg |= (uint32_t)hsc->Init.WordLength | hsc->Init.Parity | hsc->Init.Mode; - - /* Write to USART CR1 */ - WRITE_REG(hsc->Instance->CR1, (uint32_t)tmpreg); - - /*-------------------------- USART CR3 Configuration -----------------------*/ - /* Clear CTSE and RTSE bits */ - CLEAR_BIT(hsc->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE)); - - /*-------------------------- USART BRR Configuration -----------------------*/ -#if defined(USART6) - if((hsc->Instance == USART1) || (hsc->Instance == USART6)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - hsc->Instance->BRR = SMARTCARD_BRR(pclk, hsc->Init.BaudRate); - } -#else - if(hsc->Instance == USART1) - { - pclk = HAL_RCC_GetPCLK2Freq(); - hsc->Instance->BRR = SMARTCARD_BRR(pclk, hsc->Init.BaudRate); - } -#endif /* USART6 */ - else - { - pclk = HAL_RCC_GetPCLK1Freq(); - hsc->Instance->BRR = SMARTCARD_BRR(pclk, hsc->Init.BaudRate); - } -} - -/** - * @} - */ - -#endif /* HAL_SMARTCARD_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smbus.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smbus.c deleted file mode 100644 index 09df379bc93d76c..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_smbus.c +++ /dev/null @@ -1,2786 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_smbus.c - * @author MCD Application Team - * @brief SMBUS HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the System Management Bus (SMBus) peripheral, - * based on SMBUS principals of operation : - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral State, Mode and Error functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The SMBUS HAL driver can be used as follows: - - (#) Declare a SMBUS_HandleTypeDef handle structure, for example: - SMBUS_HandleTypeDef hsmbus; - - (#)Initialize the SMBUS low level resources by implementing the HAL_SMBUS_MspInit() API: - (##) Enable the SMBUSx interface clock - (##) SMBUS pins configuration - (+++) Enable the clock for the SMBUS GPIOs - (+++) Configure SMBUS pins as alternate function open-drain - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the SMBUSx interrupt priority - (+++) Enable the NVIC SMBUS IRQ Channel - - (#) Configure the Communication Speed, Duty cycle, Addressing mode, Own Address1, - Dual Addressing mode, Own Address2, General call and Nostretch mode in the hsmbus Init structure. - - (#) Initialize the SMBUS registers by calling the HAL_SMBUS_Init(), configures also the low level Hardware - (GPIO, CLOCK, NVIC...etc) by calling the customized HAL_SMBUS_MspInit(&hsmbus) API. - - (#) To check if target device is ready for communication, use the function HAL_SMBUS_IsDeviceReady() - - (#) For SMBUS IO operations, only one mode of operations is available within this driver : - - - *** Interrupt mode IO operation *** - =================================== - - [..] - (+) Transmit in master/host SMBUS mode an amount of data in non blocking mode using HAL_SMBUS_Master_Transmit_IT() - (++) At transmission end of transfer HAL_SMBUS_MasterTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SMBUS_MasterTxCpltCallback() - (+) Receive in master/host SMBUS mode an amount of data in non blocking mode using HAL_SMBUS_Master_Receive_IT() - (++) At reception end of transfer HAL_SMBUS_MasterRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SMBUS_MasterRxCpltCallback() - (+) Abort a master/Host SMBUS process communication with Interrupt using HAL_SMBUS_Master_Abort_IT() - (++) End of abort process, HAL_SMBUS_AbortCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SMBUS_AbortCpltCallback() - (+) Enable/disable the Address listen mode in slave/device or host/slave SMBUS mode - using HAL_SMBUS_EnableListen_IT() HAL_SMBUS_DisableListen_IT() - (++) When address slave/device SMBUS match, HAL_SMBUS_AddrCallback() is executed and user can - add his own code to check the Address Match Code and the transmission direction request by master/host (Write/Read). - (++) At Listen mode end HAL_SMBUS_ListenCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SMBUS_ListenCpltCallback() - (+) Transmit in slave/device SMBUS mode an amount of data in non blocking mode using HAL_SMBUS_Slave_Transmit_IT() - (++) At transmission end of transfer HAL_SMBUS_SlaveTxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SMBUS_SlaveTxCpltCallback() - (+) Receive in slave/device SMBUS mode an amount of data in non blocking mode using HAL_SMBUS_Slave_Receive_IT() - (++) At reception end of transfer HAL_SMBUS_SlaveRxCpltCallback() is executed and user can - add his own code by customization of function pointer HAL_SMBUS_SlaveRxCpltCallback() - (+) Enable/Disable the SMBUS alert mode using HAL_SMBUS_EnableAlert_IT() and HAL_SMBUS_DisableAlert_IT() - (++) When SMBUS Alert is generated HAL_SMBUS_ErrorCallback() is executed and user can - add his own code by customization of function pointer HAL_SMBUS_ErrorCallback() - to check the Alert Error Code using function HAL_SMBUS_GetError() - (+) Get HAL state machine or error values using HAL_SMBUS_GetState() or HAL_SMBUS_GetError() - (+) In case of transfer Error, HAL_SMBUS_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_SMBUS_ErrorCallback() - to check the Error Code using function HAL_SMBUS_GetError() - - - *** SMBUS HAL driver macros list *** - ================================== - [..] - Below the list of most used macros in SMBUS HAL driver. - - (+) __HAL_SMBUS_ENABLE : Enable the SMBUS peripheral - (+) __HAL_SMBUS_DISABLE : Disable the SMBUS peripheral - (+) __HAL_SMBUS_GET_FLAG : Checks whether the specified SMBUS flag is set or not - (+) __HAL_SMBUS_CLEAR_FLAG: Clear the specified SMBUS pending flag - (+) __HAL_SMBUS_ENABLE_IT : Enable the specified SMBUS interrupt - (+) __HAL_SMBUS_DISABLE_IT: Disable the specified SMBUS interrupt - - [..] - (@) You can refer to the SMBUS HAL driver header file for more useful macros - - *** Callback registration *** - ============================================= - [..] - The compilation flag USE_HAL_SMBUS_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_SMBUS_RegisterCallback() or HAL_SMBUS_RegisterXXXCallback() - to register an interrupt callback. - - Function HAL_SMBUS_RegisterCallback() allows to register following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) ErrorCallback : callback for error detection. - (+) AbortCpltCallback : callback for abort completion process. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - [..] - For specific callback AddrCallback use dedicated register callbacks : HAL_SMBUS_RegisterAddrCallback(). - [..] - Use function HAL_SMBUS_UnRegisterCallback to reset a callback to the default - weak function. - HAL_SMBUS_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) MasterTxCpltCallback : callback for Master transmission end of transfer. - (+) MasterRxCpltCallback : callback for Master reception end of transfer. - (+) SlaveTxCpltCallback : callback for Slave transmission end of transfer. - (+) SlaveRxCpltCallback : callback for Slave reception end of transfer. - (+) ListenCpltCallback : callback for end of listen mode. - (+) ErrorCallback : callback for error detection. - (+) AbortCpltCallback : callback for abort completion process. - (+) MspInitCallback : callback for Msp Init. - (+) MspDeInitCallback : callback for Msp DeInit. - [..] - For callback AddrCallback use dedicated register callbacks : HAL_SMBUS_UnRegisterAddrCallback(). - [..] - By default, after the HAL_SMBUS_Init() and when the state is HAL_SMBUS_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_SMBUS_MasterTxCpltCallback(), HAL_SMBUS_MasterRxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_SMBUS_Init()/ HAL_SMBUS_DeInit() only when - these callbacks are null (not registered beforehand). - If MspInit or MspDeInit are not null, the HAL_SMBUS_Init()/ HAL_SMBUS_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - [..] - Callbacks can be registered/unregistered in HAL_SMBUS_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_SMBUS_STATE_READY or HAL_SMBUS_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_SMBUS_RegisterCallback() before calling HAL_SMBUS_DeInit() - or HAL_SMBUS_Init() function. - [..] - When the compilation flag USE_HAL_SMBUS_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SMBUS SMBUS - * @brief SMBUS HAL module driver - * @{ - */ - -#ifdef HAL_SMBUS_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup SMBUS_Private_Define - * @{ - */ -#define SMBUS_TIMEOUT_FLAG 35U /*!< Timeout 35 ms */ -#define SMBUS_TIMEOUT_BUSY_FLAG 25U /*!< Timeout 25 ms */ -#define SMBUS_NO_OPTION_FRAME 0xFFFF0000U /*!< XferOptions default value */ - -#define SMBUS_SENDPEC_MODE I2C_CR1_PEC -#define SMBUS_GET_PEC(__HANDLE__) (((__HANDLE__)->Instance->SR2 & I2C_SR2_PEC) >> 8) - -/* Private define for @ref PreviousState usage */ -#define SMBUS_STATE_MSK ((uint32_t)((HAL_SMBUS_STATE_BUSY_TX | HAL_SMBUS_STATE_BUSY_RX) & (~(uint32_t)HAL_SMBUS_STATE_READY))) /*!< Mask State define, keep only RX and TX bits */ -#define SMBUS_STATE_NONE ((uint32_t)(HAL_SMBUS_MODE_NONE)) /*!< Default Value */ -#define SMBUS_STATE_MASTER_BUSY_TX ((uint32_t)((HAL_SMBUS_STATE_BUSY_TX & SMBUS_STATE_MSK) | HAL_SMBUS_MODE_MASTER)) /*!< Master Busy TX, combinaison of State LSB and Mode enum */ -#define SMBUS_STATE_MASTER_BUSY_RX ((uint32_t)((HAL_SMBUS_STATE_BUSY_RX & SMBUS_STATE_MSK) | HAL_SMBUS_MODE_MASTER)) /*!< Master Busy RX, combinaison of State LSB and Mode enum */ -#define SMBUS_STATE_SLAVE_BUSY_TX ((uint32_t)((HAL_SMBUS_STATE_BUSY_TX & SMBUS_STATE_MSK) | HAL_SMBUS_MODE_SLAVE)) /*!< Slave Busy TX, combinaison of State LSB and Mode enum */ -#define SMBUS_STATE_SLAVE_BUSY_RX ((uint32_t)((HAL_SMBUS_STATE_BUSY_RX & SMBUS_STATE_MSK) | HAL_SMBUS_MODE_SLAVE)) /*!< Slave Busy RX, combinaison of State LSB and Mode enum */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - -/** @addtogroup SMBUS_Private_Functions - * @{ - */ - -static HAL_StatusTypeDef SMBUS_WaitOnFlagUntilTimeout(SMBUS_HandleTypeDef *hsmbus, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart); -static void SMBUS_ITError(SMBUS_HandleTypeDef *hsmbus); - -/* Private functions for SMBUS transfer IRQ handler */ -static HAL_StatusTypeDef SMBUS_MasterTransmit_TXE(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_MasterTransmit_BTF(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_MasterReceive_RXNE(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_MasterReceive_BTF(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_Master_SB(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_Master_ADD10(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_Master_ADDR(SMBUS_HandleTypeDef *hsmbus); - -static HAL_StatusTypeDef SMBUS_SlaveTransmit_TXE(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_SlaveTransmit_BTF(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_SlaveReceive_RXNE(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_SlaveReceive_BTF(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_Slave_ADDR(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_Slave_STOPF(SMBUS_HandleTypeDef *hsmbus); -static HAL_StatusTypeDef SMBUS_Slave_AF(SMBUS_HandleTypeDef *hsmbus); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SMBUS_Exported_Functions SMBUS Exported Functions - * @{ - */ - -/** @defgroup SMBUS_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - deinitialize the SMBUSx peripheral: - - (+) User must Implement HAL_SMBUS_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, IT and NVIC). - - (+) Call the function HAL_SMBUS_Init() to configure the selected device with - the selected configuration: - (++) Communication Speed - (++) Addressing mode - (++) Own Address 1 - (++) Dual Addressing mode - (++) Own Address 2 - (++) General call mode - (++) Nostretch mode - (++) Packet Error Check mode - (++) Peripheral mode - - (+) Call the function HAL_SMBUS_DeInit() to restore the default configuration - of the selected SMBUSx peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the SMBUS according to the specified parameters - * in the SMBUS_InitTypeDef and initialize the associated handle. - * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_Init(SMBUS_HandleTypeDef *hsmbus) -{ - uint32_t freqrange = 0U; - uint32_t pclk1 = 0U; - - /* Check the SMBUS handle allocation */ - if (hsmbus == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance)); -#if defined(I2C_FLTR_ANOFF) - assert_param(IS_SMBUS_ANALOG_FILTER(hsmbus->Init.AnalogFilter)); -#endif - assert_param(IS_SMBUS_CLOCK_SPEED(hsmbus->Init.ClockSpeed)); - assert_param(IS_SMBUS_OWN_ADDRESS1(hsmbus->Init.OwnAddress1)); - assert_param(IS_SMBUS_ADDRESSING_MODE(hsmbus->Init.AddressingMode)); - assert_param(IS_SMBUS_DUAL_ADDRESS(hsmbus->Init.DualAddressMode)); - assert_param(IS_SMBUS_OWN_ADDRESS2(hsmbus->Init.OwnAddress2)); - assert_param(IS_SMBUS_GENERAL_CALL(hsmbus->Init.GeneralCallMode)); - assert_param(IS_SMBUS_NO_STRETCH(hsmbus->Init.NoStretchMode)); - assert_param(IS_SMBUS_PEC(hsmbus->Init.PacketErrorCheckMode)); - assert_param(IS_SMBUS_PERIPHERAL_MODE(hsmbus->Init.PeripheralMode)); - - if (hsmbus->State == HAL_SMBUS_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hsmbus->Lock = HAL_UNLOCKED; - /* Init the low level hardware : GPIO, CLOCK, NVIC */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - /* Init the SMBUS Callback settings */ - hsmbus->MasterTxCpltCallback = HAL_SMBUS_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - hsmbus->MasterRxCpltCallback = HAL_SMBUS_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - hsmbus->SlaveTxCpltCallback = HAL_SMBUS_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - hsmbus->SlaveRxCpltCallback = HAL_SMBUS_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - hsmbus->ListenCpltCallback = HAL_SMBUS_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - hsmbus->ErrorCallback = HAL_SMBUS_ErrorCallback; /* Legacy weak ErrorCallback */ - hsmbus->AbortCpltCallback = HAL_SMBUS_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - hsmbus->AddrCallback = HAL_SMBUS_AddrCallback; /* Legacy weak AddrCallback */ - - if (hsmbus->MspInitCallback == NULL) - { - hsmbus->MspInitCallback = HAL_SMBUS_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - hsmbus->MspInitCallback(hsmbus); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - HAL_SMBUS_MspInit(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - - hsmbus->State = HAL_SMBUS_STATE_BUSY; - - /* Disable the selected SMBUS peripheral */ - __HAL_SMBUS_DISABLE(hsmbus); - - /* Get PCLK1 frequency */ - pclk1 = HAL_RCC_GetPCLK1Freq(); - - /* Calculate frequency range */ - freqrange = SMBUS_FREQRANGE(pclk1); - - /*---------------------------- SMBUSx CR2 Configuration ----------------------*/ - /* Configure SMBUSx: Frequency range */ - MODIFY_REG(hsmbus->Instance->CR2, I2C_CR2_FREQ, freqrange); - - /*---------------------------- SMBUSx TRISE Configuration --------------------*/ - /* Configure SMBUSx: Rise Time */ - MODIFY_REG(hsmbus->Instance->TRISE, I2C_TRISE_TRISE, SMBUS_RISE_TIME(freqrange)); - - /*---------------------------- SMBUSx CCR Configuration ----------------------*/ - /* Configure SMBUSx: Speed */ - MODIFY_REG(hsmbus->Instance->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), SMBUS_SPEED_STANDARD(pclk1, hsmbus->Init.ClockSpeed)); - - /*---------------------------- SMBUSx CR1 Configuration ----------------------*/ - /* Configure SMBUSx: Generalcall , PEC , Peripheral mode and NoStretch mode */ - MODIFY_REG(hsmbus->Instance->CR1, (I2C_CR1_NOSTRETCH | I2C_CR1_ENGC | I2C_CR1_ENPEC | I2C_CR1_ENARP | I2C_CR1_SMBTYPE | I2C_CR1_SMBUS), (hsmbus->Init.NoStretchMode | hsmbus->Init.GeneralCallMode | hsmbus->Init.PacketErrorCheckMode | hsmbus->Init.PeripheralMode)); - - /*---------------------------- SMBUSx OAR1 Configuration ---------------------*/ - /* Configure SMBUSx: Own Address1 and addressing mode */ - MODIFY_REG(hsmbus->Instance->OAR1, (I2C_OAR1_ADDMODE | I2C_OAR1_ADD8_9 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD0), (hsmbus->Init.AddressingMode | hsmbus->Init.OwnAddress1)); - - /*---------------------------- SMBUSx OAR2 Configuration ---------------------*/ - /* Configure SMBUSx: Dual mode and Own Address2 */ - MODIFY_REG(hsmbus->Instance->OAR2, (I2C_OAR2_ENDUAL | I2C_OAR2_ADD2), (hsmbus->Init.DualAddressMode | hsmbus->Init.OwnAddress2)); -#if defined(I2C_FLTR_ANOFF) - /*---------------------------- SMBUSx FLTR Configuration ------------------------*/ - /* Configure SMBUSx: Analog noise filter */ - SET_BIT(hsmbus->Instance->FLTR, hsmbus->Init.AnalogFilter); -#endif - - /* Enable the selected SMBUS peripheral */ - __HAL_SMBUS_ENABLE(hsmbus); - - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - hsmbus->XferPEC = 0x00; - - return HAL_OK; -} - -/** - * @brief DeInitializes the SMBUS peripheral. - * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_DeInit(SMBUS_HandleTypeDef *hsmbus) -{ - /* Check the SMBUS handle allocation */ - if (hsmbus == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance)); - - hsmbus->State = HAL_SMBUS_STATE_BUSY; - - /* Disable the SMBUS Peripheral Clock */ - __HAL_SMBUS_DISABLE(hsmbus); - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - if (hsmbus->MspDeInitCallback == NULL) - { - hsmbus->MspDeInitCallback = HAL_SMBUS_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - hsmbus->MspDeInitCallback(hsmbus); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_SMBUS_MspDeInit(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - hsmbus->State = HAL_SMBUS_STATE_RESET; - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - - /* Release Lock */ - __HAL_UNLOCK(hsmbus); - - return HAL_OK; -} - -/** - * @brief Initialize the SMBUS MSP. - * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS - * @retval None - */ -__weak void HAL_SMBUS_MspInit(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SMBUS_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitialize the SMBUS MSP. - * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS - * @retval None - */ -__weak void HAL_SMBUS_MspDeInit(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SMBUS_MspDeInit could be implemented in the user file - */ -} - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/** - * @brief Configures SMBUS Analog noise filter. - * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUSx peripheral. - * @param AnalogFilter new state of the Analog filter. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_ConfigAnalogFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t AnalogFilter) -{ - /* Check the parameters */ - assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance)); - assert_param(IS_SMBUS_ANALOG_FILTER(AnalogFilter)); - - if (hsmbus->State == HAL_SMBUS_STATE_READY) - { - hsmbus->State = HAL_SMBUS_STATE_BUSY; - - /* Disable the selected SMBUS peripheral */ - __HAL_SMBUS_DISABLE(hsmbus); - - /* Reset SMBUSx ANOFF bit */ - hsmbus->Instance->FLTR &= ~(I2C_FLTR_ANOFF); - - /* Disable the analog filter */ - hsmbus->Instance->FLTR |= AnalogFilter; - - __HAL_SMBUS_ENABLE(hsmbus); - - hsmbus->State = HAL_SMBUS_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configures SMBUS Digital noise filter. - * @param hsmbus pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUSx peripheral. - * @param DigitalFilter Coefficient of digital noise filter between 0x00 and 0x0F. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_ConfigDigitalFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t DigitalFilter) -{ - uint16_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_SMBUS_ALL_INSTANCE(hsmbus->Instance)); - assert_param(IS_SMBUS_DIGITAL_FILTER(DigitalFilter)); - - if (hsmbus->State == HAL_SMBUS_STATE_READY) - { - hsmbus->State = HAL_SMBUS_STATE_BUSY; - - /* Disable the selected SMBUS peripheral */ - __HAL_SMBUS_DISABLE(hsmbus); - - /* Get the old register value */ - tmpreg = hsmbus->Instance->FLTR; - - /* Reset SMBUSx DNF bit [3:0] */ - tmpreg &= ~(I2C_FLTR_DNF); - - /* Set SMBUSx DNF coefficient */ - tmpreg |= DigitalFilter; - - /* Store the new register value */ - hsmbus->Instance->FLTR = tmpreg; - - __HAL_SMBUS_ENABLE(hsmbus); - - hsmbus->State = HAL_SMBUS_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} -#endif -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User SMBUS Callback - * To be used instead of the weak predefined callback - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_SMBUS_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_SMBUS_ERROR_CB_ID Error callback ID - * @arg @ref HAL_SMBUS_ABORT_CB_ID Abort callback ID - * @arg @ref HAL_SMBUS_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_SMBUS_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_RegisterCallback(SMBUS_HandleTypeDef *hsmbus, HAL_SMBUS_CallbackIDTypeDef CallbackID, pSMBUS_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hsmbus); - - if (HAL_SMBUS_STATE_READY == hsmbus->State) - { - switch (CallbackID) - { - case HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID : - hsmbus->MasterTxCpltCallback = pCallback; - break; - - case HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID : - hsmbus->MasterRxCpltCallback = pCallback; - break; - - case HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID : - hsmbus->SlaveTxCpltCallback = pCallback; - break; - - case HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID : - hsmbus->SlaveRxCpltCallback = pCallback; - break; - - case HAL_SMBUS_LISTEN_COMPLETE_CB_ID : - hsmbus->ListenCpltCallback = pCallback; - break; - - case HAL_SMBUS_ERROR_CB_ID : - hsmbus->ErrorCallback = pCallback; - break; - - case HAL_SMBUS_ABORT_CB_ID : - hsmbus->AbortCpltCallback = pCallback; - break; - - case HAL_SMBUS_MSPINIT_CB_ID : - hsmbus->MspInitCallback = pCallback; - break; - - case HAL_SMBUS_MSPDEINIT_CB_ID : - hsmbus->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SMBUS_STATE_RESET == hsmbus->State) - { - switch (CallbackID) - { - case HAL_SMBUS_MSPINIT_CB_ID : - hsmbus->MspInitCallback = pCallback; - break; - - case HAL_SMBUS_MSPDEINIT_CB_ID : - hsmbus->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsmbus); - return status; -} - -/** - * @brief Unregister an SMBUS Callback - * SMBUS callback is redirected to the weak predefined callback - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * This parameter can be one of the following values: - * @arg @ref HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID Master Tx Transfer completed callback ID - * @arg @ref HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID Master Rx Transfer completed callback ID - * @arg @ref HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID Slave Tx Transfer completed callback ID - * @arg @ref HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID Slave Rx Transfer completed callback ID - * @arg @ref HAL_SMBUS_LISTEN_COMPLETE_CB_ID Listen Complete callback ID - * @arg @ref HAL_SMBUS_ERROR_CB_ID Error callback ID - * @arg @ref HAL_SMBUS_ABORT_CB_ID Abort callback ID - * @arg @ref HAL_SMBUS_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_SMBUS_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_UnRegisterCallback(SMBUS_HandleTypeDef *hsmbus, HAL_SMBUS_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hsmbus); - - if (HAL_SMBUS_STATE_READY == hsmbus->State) - { - switch (CallbackID) - { - case HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID : - hsmbus->MasterTxCpltCallback = HAL_SMBUS_MasterTxCpltCallback; /* Legacy weak MasterTxCpltCallback */ - break; - - case HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID : - hsmbus->MasterRxCpltCallback = HAL_SMBUS_MasterRxCpltCallback; /* Legacy weak MasterRxCpltCallback */ - break; - - case HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID : - hsmbus->SlaveTxCpltCallback = HAL_SMBUS_SlaveTxCpltCallback; /* Legacy weak SlaveTxCpltCallback */ - break; - - case HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID : - hsmbus->SlaveRxCpltCallback = HAL_SMBUS_SlaveRxCpltCallback; /* Legacy weak SlaveRxCpltCallback */ - break; - - case HAL_SMBUS_LISTEN_COMPLETE_CB_ID : - hsmbus->ListenCpltCallback = HAL_SMBUS_ListenCpltCallback; /* Legacy weak ListenCpltCallback */ - break; - - case HAL_SMBUS_ERROR_CB_ID : - hsmbus->ErrorCallback = HAL_SMBUS_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_SMBUS_ABORT_CB_ID : - hsmbus->AbortCpltCallback = HAL_SMBUS_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_SMBUS_MSPINIT_CB_ID : - hsmbus->MspInitCallback = HAL_SMBUS_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_SMBUS_MSPDEINIT_CB_ID : - hsmbus->MspDeInitCallback = HAL_SMBUS_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SMBUS_STATE_RESET == hsmbus->State) - { - switch (CallbackID) - { - case HAL_SMBUS_MSPINIT_CB_ID : - hsmbus->MspInitCallback = HAL_SMBUS_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_SMBUS_MSPDEINIT_CB_ID : - hsmbus->MspDeInitCallback = HAL_SMBUS_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsmbus); - return status; -} - -/** - * @brief Register the Slave Address Match SMBUS Callback - * To be used instead of the weak HAL_SMBUS_AddrCallback() predefined callback - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param pCallback pointer to the Address Match Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_RegisterAddrCallback(SMBUS_HandleTypeDef *hsmbus, pSMBUS_AddrCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hsmbus); - - if (HAL_SMBUS_STATE_READY == hsmbus->State) - { - hsmbus->AddrCallback = pCallback; - } - else - { - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsmbus); - return status; -} - -/** - * @brief UnRegister the Slave Address Match SMBUS Callback - * Info Ready SMBUS Callback is redirected to the weak HAL_SMBUS_AddrCallback() predefined callback - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_UnRegisterAddrCallback(SMBUS_HandleTypeDef *hsmbus) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hsmbus); - - if (HAL_SMBUS_STATE_READY == hsmbus->State) - { - hsmbus->AddrCallback = HAL_SMBUS_AddrCallback; /* Legacy weak AddrCallback */ - } - else - { - /* Update the error code */ - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsmbus); - return status; -} - -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup SMBUS_Exported_Functions_Group2 Input and Output operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the SMBUS data - transfers. - - (#) Blocking mode function to check if device is ready for usage is : - (++) HAL_SMBUS_IsDeviceReady() - - (#) There is only one mode of transfer: - (++) Non Blocking mode : The communication is performed using Interrupts. - These functions return the status of the transfer startup. - The end of the data processing will be indicated through the - dedicated SMBUS IRQ when using Interrupt mode. - - (#) Non Blocking mode functions with Interrupt are : - (++) HAL_SMBUS_Master_Transmit_IT() - (++) HAL_SMBUS_Master_Receive_IT() - (++) HAL_SMBUS_Master_Abort_IT() - (++) HAL_SMBUS_Slave_Transmit_IT() - (++) HAL_SMBUS_Slave_Receive_IT() - (++) HAL_SMBUS_EnableAlert_IT() - (++) HAL_SMBUS_DisableAlert_IT() - - (#) A set of Transfer Complete Callbacks are provided in No_Blocking mode: - (++) HAL_SMBUS_MasterTxCpltCallback() - (++) HAL_SMBUS_MasterRxCpltCallback() - (++) HAL_SMBUS_SlaveTxCpltCallback() - (++) HAL_SMBUS_SlaveRxCpltCallback() - (++) HAL_SMBUS_AddrCallback() - (++) HAL_SMBUS_ListenCpltCallback() - (++) HAL_SMBUS_ErrorCallback() - (++) HAL_SMBUS_AbortCpltCallback() - -@endverbatim - * @{ - */ - -/** - * @brief Transmits in master mode an amount of data in blocking mode. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param DevAddress Target device address The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_Master_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - uint32_t count = 0x00U; - - /* Check the parameters */ - assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hsmbus->State == HAL_SMBUS_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((XferOptions == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || (XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (XferOptions == SMBUS_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = SMBUS_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - if (count-- == 0U) - { - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->State = HAL_SMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - return HAL_TIMEOUT; - } - } - while (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hsmbus); - - /* Check if the SMBUS is already enabled */ - if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable SMBUS peripheral */ - __HAL_SMBUS_ENABLE(hsmbus); - } - - /* Disable Pos */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); - - hsmbus->State = HAL_SMBUS_STATE_BUSY_TX; - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_MASTER; - - /* Prepare transfer parameters */ - hsmbus->pBuffPtr = pData; - hsmbus->XferCount = Size; - hsmbus->XferOptions = XferOptions; - hsmbus->XferSize = hsmbus->XferCount; - hsmbus->Devaddress = DevAddress; - - /* Generate Start */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - /* Note : The SMBUS interrupts must be enabled after unlocking current process - to avoid the risk of hsmbus interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} -/** - * @brief Receive in master/host SMBUS mode an amount of data in non blocking mode with Interrupt. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param DevAddress Target device address The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_Master_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - __IO uint32_t count = 0U; - - /* Check the parameters */ - assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hsmbus->State == HAL_SMBUS_STATE_READY) - { - /* Check Busy Flag only if FIRST call of Master interface */ - if ((XferOptions == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || (XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (XferOptions == SMBUS_FIRST_FRAME)) - { - /* Wait until BUSY flag is reset */ - count = SMBUS_TIMEOUT_BUSY_FLAG * (SystemCoreClock / 25U / 1000U); - do - { - if (count-- == 0U) - { - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->State = HAL_SMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - return HAL_TIMEOUT; - } - } - while (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_BUSY) != RESET); - } - - /* Process Locked */ - __HAL_LOCK(hsmbus); - - /* Check if the SMBUS is already enabled */ - if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable SMBUS peripheral */ - __HAL_SMBUS_ENABLE(hsmbus); - } - - /* Disable Pos */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); - - hsmbus->State = HAL_SMBUS_STATE_BUSY_RX; - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_MASTER; - - /* Prepare transfer parameters */ - hsmbus->pBuffPtr = pData; - hsmbus->XferCount = Size; - hsmbus->XferOptions = XferOptions; - hsmbus->XferSize = hsmbus->XferCount; - hsmbus->Devaddress = DevAddress; - - if ((hsmbus->PreviousState == SMBUS_STATE_MASTER_BUSY_TX) || (hsmbus->PreviousState == SMBUS_STATE_NONE)) - { - /* Generate Start condition if first transfer */ - if ((XferOptions == SMBUS_NEXT_FRAME) || (XferOptions == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || (XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (XferOptions == SMBUS_FIRST_FRAME) || (XferOptions == SMBUS_NO_OPTION_FRAME)) - { - /* Enable Acknowledge */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); - } - - if ((XferOptions == SMBUS_LAST_FRAME_NO_PEC) || (XferOptions == SMBUS_LAST_FRAME_WITH_PEC)) - { - if (hsmbus->PreviousState == SMBUS_STATE_NONE) - { - /* Enable Acknowledge */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - } - - if (hsmbus->PreviousState == SMBUS_STATE_MASTER_BUSY_TX) - { - /* Enable Acknowledge */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Generate Start */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); - } - } - } - - - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - /* Note : The SMBUS interrupts must be enabled after unlocking current process - to avoid the risk of SMBUS interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Abort a master/host SMBUS process communication with Interrupt. - * @note This abort can be called only if state is ready - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param DevAddress Target device address The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_Master_Abort_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(DevAddress); - if (hsmbus->Init.PeripheralMode == SMBUS_PERIPHERAL_MODE_SMBUS_HOST) - { - /* Process Locked */ - __HAL_LOCK(hsmbus); - - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->State = HAL_SMBUS_STATE_ABORT; - - - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - - hsmbus->XferCount = 0U; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ - SMBUS_ITError(hsmbus); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - - -/** - * @brief Transmit in slave/device SMBUS mode an amount of data in non blocking mode with Interrupt. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_Slave_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hsmbus->State == HAL_SMBUS_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsmbus); - - /* Check if the SMBUS is already enabled */ - if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable SMBUS peripheral */ - __HAL_SMBUS_ENABLE(hsmbus); - } - - /* Disable Pos */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); - - hsmbus->State = HAL_SMBUS_STATE_BUSY_TX_LISTEN; - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_SLAVE; - - /* Prepare transfer parameters */ - hsmbus->pBuffPtr = pData; - hsmbus->XferCount = Size; - hsmbus->XferOptions = XferOptions; - hsmbus->XferSize = hsmbus->XferCount; - - /* Clear ADDR flag after prepare the transfer parameters */ - /* This action will generate an acknowledge to the HOST */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - /* Note : The SMBUS interrupts must be enabled after unlocking current process - to avoid the risk of SMBUS interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Enable the Address listen mode with Interrupt. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param pData Pointer to data buffer - * @param Size Amount of data to be sent - * @param XferOptions Options of Transfer, value of @ref SMBUS_XferOptions_definition - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_Slave_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions) -{ - /* Check the parameters */ - assert_param(IS_SMBUS_TRANSFER_OPTIONS_REQUEST(XferOptions)); - - if (hsmbus->State == HAL_SMBUS_STATE_LISTEN) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsmbus); - - /* Check if the SMBUS is already enabled */ - if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable SMBUS peripheral */ - __HAL_SMBUS_ENABLE(hsmbus); - } - - /* Disable Pos */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); - - hsmbus->State = HAL_SMBUS_STATE_BUSY_RX_LISTEN; - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_SLAVE; - - - - /* Prepare transfer parameters */ - hsmbus->pBuffPtr = pData; - hsmbus->XferCount = Size; - hsmbus->XferOptions = XferOptions; - hsmbus->XferSize = hsmbus->XferCount; - - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - /* Note : The SMBUS interrupts must be enabled after unlocking current process - to avoid the risk of SMBUS interrupt handle execution before current - process unlock */ - - /* Enable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - - -/** - * @brief Enable the Address listen mode with Interrupt. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_EnableListen_IT(SMBUS_HandleTypeDef *hsmbus) -{ - if (hsmbus->State == HAL_SMBUS_STATE_READY) - { - hsmbus->State = HAL_SMBUS_STATE_LISTEN; - - /* Check if the SMBUS is already enabled */ - if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable SMBUS peripheral */ - __HAL_SMBUS_ENABLE(hsmbus); - } - - /* Enable Address Acknowledge */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Enable EVT and ERR interrupt */ - __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Disable the Address listen mode with Interrupt. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_DisableListen_IT(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of tmp to prevent undefined behavior of volatile usage */ - uint32_t tmp; - - /* Disable Address listen mode only if a transfer is not ongoing */ - if (hsmbus->State == HAL_SMBUS_STATE_LISTEN) - { - tmp = (uint32_t)(hsmbus->State) & SMBUS_STATE_MSK; - hsmbus->PreviousState = tmp | (uint32_t)(hsmbus->Mode); - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - - /* Disable Address Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Disable EVT and ERR interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_ERR); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Enable the SMBUS alert mode with Interrupt. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUSx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_EnableAlert_IT(SMBUS_HandleTypeDef *hsmbus) -{ - /* Enable SMBus alert */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ALERT); - - /* Clear ALERT flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_SMBALERT); - - /* Enable Alert Interrupt */ - __HAL_SMBUS_ENABLE_IT(hsmbus, SMBUS_IT_ERR); - - return HAL_OK; -} -/** - * @brief Disable the SMBUS alert mode with Interrupt. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUSx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_DisableAlert_IT(SMBUS_HandleTypeDef *hsmbus) -{ - /* Disable SMBus alert */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ALERT); - - /* Disable Alert Interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_ERR); - - return HAL_OK; -} - - -/** - * @brief Check if target device is ready for communication. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param DevAddress Target device address The device 7 bits address value - * in datasheet must be shifted to the left before calling the interface - * @param Trials Number of trials - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SMBUS_IsDeviceReady(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout) -{ - uint32_t tickstart = 0U, tmp1 = 0U, tmp2 = 0U, tmp3 = 0U, SMBUS_Trials = 1U; - - /* Get tick */ - tickstart = HAL_GetTick(); - - if (hsmbus->State == HAL_SMBUS_STATE_READY) - { - /* Wait until BUSY flag is reset */ - if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_BUSY, SET, SMBUS_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_BUSY; - } - - /* Process Locked */ - __HAL_LOCK(hsmbus); - - /* Check if the SMBUS is already enabled */ - if ((hsmbus->Instance->CR1 & I2C_CR1_PE) != I2C_CR1_PE) - { - /* Enable SMBUS peripheral */ - __HAL_SMBUS_ENABLE(hsmbus); - } - - /* Disable Pos */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); - - hsmbus->State = HAL_SMBUS_STATE_BUSY; - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - hsmbus->XferOptions = SMBUS_NO_OPTION_FRAME; - - do - { - /* Generate Start */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); - - /* Wait until SB flag is set */ - if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_SB, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* Send slave address */ - hsmbus->Instance->DR = SMBUS_7BIT_ADD_WRITE(DevAddress); - - /* Wait until ADDR or AF flag are set */ - /* Get tick */ - tickstart = HAL_GetTick(); - - tmp1 = __HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_ADDR); - tmp2 = __HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_AF); - tmp3 = hsmbus->State; - while ((tmp1 == RESET) && (tmp2 == RESET) && (tmp3 != HAL_SMBUS_STATE_TIMEOUT)) - { - if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout)) - { - hsmbus->State = HAL_SMBUS_STATE_TIMEOUT; - } - tmp1 = __HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_ADDR); - tmp2 = __HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_AF); - tmp3 = hsmbus->State; - } - - hsmbus->State = HAL_SMBUS_STATE_READY; - - /* Check if the ADDR flag has been set */ - if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_ADDR) == SET) - { - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - - /* Clear ADDR Flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - - /* Wait until BUSY flag is reset */ - if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_BUSY, SET, SMBUS_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_TIMEOUT; - } - - hsmbus->State = HAL_SMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - return HAL_OK; - } - else - { - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - - /* Clear AF Flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF); - - /* Wait until BUSY flag is reset */ - if (SMBUS_WaitOnFlagUntilTimeout(hsmbus, SMBUS_FLAG_BUSY, SET, SMBUS_TIMEOUT_BUSY_FLAG, tickstart) != HAL_OK) - { - return HAL_TIMEOUT; - } - } - } - while (SMBUS_Trials++ < Trials); - - hsmbus->State = HAL_SMBUS_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - - return HAL_ERROR; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief This function handles SMBUS event interrupt request. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -void HAL_SMBUS_EV_IRQHandler(SMBUS_HandleTypeDef *hsmbus) -{ - uint32_t sr2itflags = READ_REG(hsmbus->Instance->SR2); - uint32_t sr1itflags = READ_REG(hsmbus->Instance->SR1); - uint32_t itsources = READ_REG(hsmbus->Instance->CR2); - - uint32_t CurrentMode = hsmbus->Mode; - - /* Master mode selected */ - if (CurrentMode == HAL_SMBUS_MODE_MASTER) - { - /* SB Set ----------------------------------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_SB) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_Master_SB(hsmbus); - } - /* ADD10 Set -------------------------------------------------------------*/ - else if (((sr1itflags & SMBUS_FLAG_ADD10) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_Master_ADD10(hsmbus); - } - /* ADDR Set --------------------------------------------------------------*/ - else if (((sr1itflags & SMBUS_FLAG_ADDR) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_Master_ADDR(hsmbus); - } - /* SMBUS in mode Transmitter -----------------------------------------------*/ - if ((sr2itflags & SMBUS_FLAG_TRA) != RESET) - { - /* TXE set and BTF reset -----------------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_TXE) != RESET) && ((itsources & SMBUS_IT_BUF) != RESET) && ((sr1itflags & SMBUS_FLAG_BTF) == RESET)) - { - SMBUS_MasterTransmit_TXE(hsmbus); - } - /* BTF set -------------------------------------------------------------*/ - else if (((sr1itflags & SMBUS_FLAG_BTF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_MasterTransmit_BTF(hsmbus); - } - } - /* SMBUS in mode Receiver --------------------------------------------------*/ - else - { - /* RXNE set and BTF reset -----------------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_RXNE) != RESET) && ((itsources & SMBUS_IT_BUF) != RESET) && ((sr1itflags & SMBUS_FLAG_BTF) == RESET)) - { - SMBUS_MasterReceive_RXNE(hsmbus); - } - /* BTF set -------------------------------------------------------------*/ - else if (((sr1itflags & SMBUS_FLAG_BTF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_MasterReceive_BTF(hsmbus); - } - } - } - /* Slave mode selected */ - else - { - /* ADDR set --------------------------------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_ADDR) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_Slave_ADDR(hsmbus); - } - /* STOPF set --------------------------------------------------------------*/ - else if (((sr1itflags & SMBUS_FLAG_STOPF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_Slave_STOPF(hsmbus); - } - /* SMBUS in mode Transmitter -----------------------------------------------*/ - else if ((sr2itflags & SMBUS_FLAG_TRA) != RESET) - { - /* TXE set and BTF reset -----------------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_TXE) != RESET) && ((itsources & SMBUS_IT_BUF) != RESET) && ((sr1itflags & SMBUS_FLAG_BTF) == RESET)) - { - SMBUS_SlaveTransmit_TXE(hsmbus); - } - /* BTF set -------------------------------------------------------------*/ - else if (((sr1itflags & SMBUS_FLAG_BTF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_SlaveTransmit_BTF(hsmbus); - } - } - /* SMBUS in mode Receiver --------------------------------------------------*/ - else - { - /* RXNE set and BTF reset ----------------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_RXNE) != RESET) && ((itsources & SMBUS_IT_BUF) != RESET) && ((sr1itflags & SMBUS_FLAG_BTF) == RESET)) - { - SMBUS_SlaveReceive_RXNE(hsmbus); - } - /* BTF set -------------------------------------------------------------*/ - else if (((sr1itflags & SMBUS_FLAG_BTF) != RESET) && ((itsources & SMBUS_IT_EVT) != RESET)) - { - SMBUS_SlaveReceive_BTF(hsmbus); - } - } - } -} - -/** - * @brief This function handles SMBUS error interrupt request. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -void HAL_SMBUS_ER_IRQHandler(SMBUS_HandleTypeDef *hsmbus) -{ - uint32_t tmp1 = 0U, tmp2 = 0U, tmp3 = 0U, tmp4 = 0U; - uint32_t sr1itflags = READ_REG(hsmbus->Instance->SR1); - uint32_t itsources = READ_REG(hsmbus->Instance->CR2); - - /* SMBUS Bus error interrupt occurred ------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_BERR) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) - { - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_BERR; - - /* Clear BERR flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_BERR); - - } - - /* SMBUS Over-Run/Under-Run interrupt occurred ----------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_OVR) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) - { - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_OVR; - - /* Clear OVR flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_OVR); - } - - /* SMBUS Arbitration Loss error interrupt occurred ------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_ARLO) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) - { - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_ARLO; - - /* Clear ARLO flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_ARLO); - } - - /* SMBUS Acknowledge failure error interrupt occurred ------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_AF) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) - { - tmp1 = hsmbus->Mode; - tmp2 = hsmbus->XferCount; - tmp3 = hsmbus->State; - tmp4 = hsmbus->PreviousState; - - if ((tmp1 == HAL_SMBUS_MODE_SLAVE) && (tmp2 == 0U) && \ - ((tmp3 == HAL_SMBUS_STATE_BUSY_TX) || (tmp3 == HAL_SMBUS_STATE_BUSY_TX_LISTEN) || \ - ((tmp3 == HAL_SMBUS_STATE_LISTEN) && (tmp4 == SMBUS_STATE_SLAVE_BUSY_TX)))) - { - SMBUS_Slave_AF(hsmbus); - } - else - { - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_AF; - - /* Do not generate a STOP in case of Slave receive non acknowledge during transfer (mean not at the end of transfer) */ - if (hsmbus->Mode == HAL_SMBUS_MODE_MASTER) - { - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - - } - - /* Clear AF flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF); - } - } - - /* SMBUS Timeout error interrupt occurred ---------------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_TIMEOUT) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) - { - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_TIMEOUT; - - /* Clear TIMEOUT flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_TIMEOUT); - - } - - /* SMBUS Alert error interrupt occurred -----------------------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_SMBALERT) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) - { - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_ALERT; - - /* Clear ALERT flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_SMBALERT); - } - - /* SMBUS Packet Error Check error interrupt occurred ----------------------------------*/ - if (((sr1itflags & SMBUS_FLAG_PECERR) != RESET) && ((itsources & SMBUS_IT_ERR) != RESET)) - { - hsmbus->ErrorCode |= HAL_SMBUS_ERROR_PECERR; - - /* Clear PEC error flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_PECERR); - } - - /* Call the Error Callback in case of Error detected -----------------------*/ - if (hsmbus->ErrorCode != HAL_SMBUS_ERROR_NONE) - { - SMBUS_ITError(hsmbus); - } -} - -/** - * @brief Master Tx Transfer completed callback. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -__weak void HAL_SMBUS_MasterTxCpltCallback(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMBUS_MasterTxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief Master Rx Transfer completed callback. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -__weak void HAL_SMBUS_MasterRxCpltCallback(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMBUS_MasterRxCpltCallback can be implemented in the user file - */ -} - -/** @brief Slave Tx Transfer completed callback. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -__weak void HAL_SMBUS_SlaveTxCpltCallback(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMBUS_SlaveTxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief Slave Rx Transfer completed callback. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -__weak void HAL_SMBUS_SlaveRxCpltCallback(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMBUS_SlaveRxCpltCallback can be implemented in the user file - */ -} - -/** - * @brief Slave Address Match callback. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @param TransferDirection Master request Transfer Direction (Write/Read), value of @ref SMBUS_XferOptions_definition - * @param AddrMatchCode Address Match Code - * @retval None - */ -__weak void HAL_SMBUS_AddrCallback(SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - UNUSED(TransferDirection); - UNUSED(AddrMatchCode); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMBUS_AddrCallback can be implemented in the user file - */ -} - -/** - * @brief Listen Complete callback. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -__weak void HAL_SMBUS_ListenCpltCallback(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMBUS_ListenCpltCallback can be implemented in the user file - */ -} - -/** - * @brief SMBUS error callback. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -__weak void HAL_SMBUS_ErrorCallback(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMBUS_ErrorCallback can be implemented in the user file - */ -} - -/** - * @brief SMBUS abort callback. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval None - */ -__weak void HAL_SMBUS_AbortCpltCallback(SMBUS_HandleTypeDef *hsmbus) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsmbus); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SMBUS_AbortCpltCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup SMBUS_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @brief Peripheral State and Errors functions - * -@verbatim - =============================================================================== - ##### Peripheral State, Mode and Error functions ##### - =============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the SMBUS handle state. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval HAL state - */ -HAL_SMBUS_StateTypeDef HAL_SMBUS_GetState(SMBUS_HandleTypeDef *hsmbus) -{ - /* Return SMBUS handle state */ - return hsmbus->State; -} - -/** - * @brief Return the SMBUS Master, Slave or no mode. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL mode - */ -HAL_SMBUS_ModeTypeDef HAL_SMBUS_GetMode(SMBUS_HandleTypeDef *hsmbus) -{ - return hsmbus->Mode; -} - -/** - * @brief Return the SMBUS error code - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for the specified SMBUS. - * @retval SMBUS Error Code - */ -uint32_t HAL_SMBUS_GetError(SMBUS_HandleTypeDef *hsmbus) -{ - return hsmbus->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup SMBUS_Private_Functions - * @{ - */ - -/** - * @brief Handle TXE flag for Master - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_MasterTransmit_TXE(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentState = hsmbus->State; - uint32_t CurrentXferOptions = hsmbus->XferOptions; - - if ((hsmbus->XferSize == 0U) && (CurrentState == HAL_SMBUS_STATE_BUSY_TX)) - { - /* Call TxCpltCallback() directly if no stop mode is set */ - if (((CurrentXferOptions == SMBUS_FIRST_FRAME) || (CurrentXferOptions == SMBUS_NEXT_FRAME)) && (CurrentXferOptions != SMBUS_NO_OPTION_FRAME)) - { - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - hsmbus->PreviousState = SMBUS_STATE_MASTER_BUSY_TX; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - hsmbus->State = HAL_SMBUS_STATE_READY; - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->MasterTxCpltCallback(hsmbus); -#else - HAL_SMBUS_MasterTxCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - else /* Generate Stop condition then Call TxCpltCallback() */ - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - - hsmbus->PreviousState = HAL_SMBUS_STATE_READY; - hsmbus->State = HAL_SMBUS_STATE_READY; - - hsmbus->Mode = HAL_SMBUS_MODE_NONE; -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->MasterTxCpltCallback(hsmbus); -#else - HAL_SMBUS_MasterTxCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - } - else if (CurrentState == HAL_SMBUS_STATE_BUSY_TX) - { - - if ((hsmbus->XferCount == 2U) && (SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) - { - hsmbus->XferCount--; - } - - if (hsmbus->XferCount == 0U) - { - - /* Disable BUF interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); - - if ((SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) - { - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_PEC); - } - - } - else - { - /* Write data to DR */ - hsmbus->Instance->DR = (*hsmbus->pBuffPtr++); - hsmbus->XferCount--; - } - } - return HAL_OK; -} - -/** - * @brief Handle BTF flag for Master transmitter - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_MasterTransmit_BTF(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hsmbus->XferOptions; - - if (hsmbus->State == HAL_SMBUS_STATE_BUSY_TX) - { - if (hsmbus->XferCount != 0U) - { - /* Write data to DR */ - hsmbus->Instance->DR = (*hsmbus->pBuffPtr++); - hsmbus->XferCount--; - } - else - { - /* Call TxCpltCallback() directly if no stop mode is set */ - if (((CurrentXferOptions == SMBUS_FIRST_FRAME) || (CurrentXferOptions == SMBUS_NEXT_FRAME)) && (CurrentXferOptions != SMBUS_NO_OPTION_FRAME)) - { - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - hsmbus->PreviousState = SMBUS_STATE_MASTER_BUSY_TX; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - hsmbus->State = HAL_SMBUS_STATE_READY; - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->MasterTxCpltCallback(hsmbus); -#else - HAL_SMBUS_MasterTxCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - else /* Generate Stop condition then Call TxCpltCallback() */ - { - /* Disable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - - hsmbus->PreviousState = HAL_SMBUS_STATE_READY; - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->MasterTxCpltCallback(hsmbus); -#else - HAL_SMBUS_MasterTxCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - } - } - return HAL_OK; -} - -/** - * @brief Handle RXNE flag for Master - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_MasterReceive_RXNE(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hsmbus->XferOptions; - - if (hsmbus->State == HAL_SMBUS_STATE_BUSY_RX) - { - uint32_t tmp = hsmbus->XferCount; - - if (tmp > 3U) - { - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - - if (hsmbus->XferCount == 3) - { - /* Disable BUF interrupt, this help to treat correctly the last 4 bytes - on BTF subroutine */ - /* Disable BUF interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); - } - } - - else if (tmp == 2U) - { - - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - - if ((CurrentXferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (CurrentXferOptions == SMBUS_LAST_FRAME_WITH_PEC)) - { - /* PEC of slave */ - hsmbus->XferPEC = SMBUS_GET_PEC(hsmbus); - - } - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - } - - else if ((tmp == 1U) || (tmp == 0U)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->MasterRxCpltCallback(hsmbus); -#else - HAL_SMBUS_MasterRxCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - } - - return HAL_OK; -} - -/** - * @brief Handle BTF flag for Master receiver - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_MasterReceive_BTF(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentXferOptions = hsmbus->XferOptions; - - if (hsmbus->XferCount == 4U) - { - /* Disable BUF interrupt, this help to treat correctly the last 2 bytes - on BTF subroutine if there is a reception delay between N-1 and N byte */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); - - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - hsmbus->XferPEC = SMBUS_GET_PEC(hsmbus); - } - else if (hsmbus->XferCount == 3U) - { - /* Disable BUF interrupt, this help to treat correctly the last 2 bytes - on BTF subroutine if there is a reception delay between N-1 and N byte */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); - - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - hsmbus->XferPEC = SMBUS_GET_PEC(hsmbus); - } - else if (hsmbus->XferCount == 2U) - { - /* Prepare next transfer or stop current transfer */ - if ((CurrentXferOptions == SMBUS_NEXT_FRAME) || (CurrentXferOptions == SMBUS_FIRST_FRAME)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Generate ReStart */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); - } - else - { - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - } - - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - - /* Disable EVT and ERR interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_ERR); - - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->MasterRxCpltCallback(hsmbus); -#else - HAL_SMBUS_MasterRxCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - else - { - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - } - return HAL_OK; -} - -/** - * @brief Handle SB flag for Master - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_Master_SB(SMBUS_HandleTypeDef *hsmbus) -{ - if (hsmbus->Init.AddressingMode == SMBUS_ADDRESSINGMODE_7BIT) - { - /* Send slave 7 Bits address */ - if (hsmbus->State == HAL_SMBUS_STATE_BUSY_TX) - { - hsmbus->Instance->DR = SMBUS_7BIT_ADD_WRITE(hsmbus->Devaddress); - } - else - { - hsmbus->Instance->DR = SMBUS_7BIT_ADD_READ(hsmbus->Devaddress); - } - } - else - { - if (hsmbus->EventCount == 0U) - { - /* Send header of slave address */ - hsmbus->Instance->DR = SMBUS_10BIT_HEADER_WRITE(hsmbus->Devaddress); - } - else if (hsmbus->EventCount == 1U) - { - /* Send header of slave address */ - hsmbus->Instance->DR = SMBUS_10BIT_HEADER_READ(hsmbus->Devaddress); - } - } - return HAL_OK; -} - -/** - * @brief Handle ADD10 flag for Master - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_Master_ADD10(SMBUS_HandleTypeDef *hsmbus) -{ - /* Send slave address */ - hsmbus->Instance->DR = SMBUS_10BIT_ADDRESS(hsmbus->Devaddress); - - return HAL_OK; -} - -/** - * @brief Handle ADDR flag for Master - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_Master_ADDR(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - uint32_t Prev_State = hsmbus->PreviousState; - - if (hsmbus->State == HAL_SMBUS_STATE_BUSY_RX) - { - if ((hsmbus->EventCount == 0U) && (hsmbus->Init.AddressingMode == SMBUS_ADDRESSINGMODE_10BIT)) - { - /* Clear ADDR flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - - /* Generate Restart */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_START); - - hsmbus->EventCount++; - } - else - { - /* In the case of the Quick Command, the ADDR flag is cleared and a stop is generated */ - if (hsmbus->XferCount == 0U) - { - /* Clear ADDR flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - } - else if (hsmbus->XferCount == 1U) - { - /* Prepare next transfer or stop current transfer */ - if ((hsmbus->XferOptions == SMBUS_FIRST_FRAME) && (Prev_State != SMBUS_STATE_MASTER_BUSY_RX)) - { - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - } - else if ((hsmbus->XferOptions == SMBUS_NEXT_FRAME) && (Prev_State != SMBUS_STATE_MASTER_BUSY_RX)) - { - /* Enable Acknowledge */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - } - else - { - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - - /* Generate Stop */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_STOP); - } - } - else if (hsmbus->XferCount == 2U) - { - if (hsmbus->XferOptions != SMBUS_NEXT_FRAME) - { - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Enable Pos */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); - - - } - else - { - /* Enable Acknowledge */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - } - - /* Clear ADDR flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - } - else - { - /* Enable Acknowledge */ - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* Clear ADDR flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - } - - /* Reset Event counter */ - hsmbus->EventCount = 0U; - } - } - else - { - /* Clear ADDR flag */ - __HAL_SMBUS_CLEAR_ADDRFLAG(hsmbus); - } - - return HAL_OK; -} - -/** - * @brief Handle TXE flag for Slave - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_SlaveTransmit_TXE(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentState = hsmbus->State; - - if (hsmbus->XferCount != 0U) - { - /* Write data to DR */ - hsmbus->Instance->DR = (*hsmbus->pBuffPtr++); - hsmbus->XferCount--; - - if ((hsmbus->XferCount == 2U) && (SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) - { - hsmbus->XferCount--; - } - - if ((hsmbus->XferCount == 0U) && (CurrentState == (HAL_SMBUS_STATE_BUSY_TX_LISTEN))) - { - /* Last Byte is received, disable Interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); - - /* Set state at HAL_SMBUS_STATE_LISTEN */ - hsmbus->PreviousState = SMBUS_STATE_SLAVE_BUSY_TX; - hsmbus->State = HAL_SMBUS_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->SlaveTxCpltCallback(hsmbus); -#else - HAL_SMBUS_SlaveTxCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - } - return HAL_OK; -} - -/** - * @brief Handle BTF flag for Slave transmitter - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_SlaveTransmit_BTF(SMBUS_HandleTypeDef *hsmbus) -{ - if (hsmbus->XferCount != 0U) - { - /* Write data to DR */ - hsmbus->Instance->DR = (*hsmbus->pBuffPtr++); - hsmbus->XferCount--; - } - - - - else if ((hsmbus->XferCount == 0U) && (SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) - { - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_PEC); - } - return HAL_OK; -} - -/** - * @brief Handle RXNE flag for Slave - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_SlaveReceive_RXNE(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentState = hsmbus->State; - - if (hsmbus->XferCount != 0U) - { - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - - if ((hsmbus->XferCount == 1U) && (SMBUS_GET_PEC_MODE(hsmbus) == SMBUS_PEC_ENABLE) && ((hsmbus->XferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || (hsmbus->XferOptions == SMBUS_LAST_FRAME_WITH_PEC))) - { - SET_BIT(hsmbus->Instance->CR1, I2C_CR1_PEC); - hsmbus->XferPEC = SMBUS_GET_PEC(hsmbus); - } - if ((hsmbus->XferCount == 0U) && (CurrentState == HAL_SMBUS_STATE_BUSY_RX_LISTEN)) - { - /* Last Byte is received, disable Interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_BUF); - - /* Set state at HAL_SMBUS_STATE_LISTEN */ - hsmbus->PreviousState = SMBUS_STATE_SLAVE_BUSY_RX; - hsmbus->State = HAL_SMBUS_STATE_LISTEN; - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->SlaveRxCpltCallback(hsmbus); -#else - HAL_SMBUS_SlaveRxCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - } - return HAL_OK; -} - -/** - * @brief Handle BTF flag for Slave receiver - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_SlaveReceive_BTF(SMBUS_HandleTypeDef *hsmbus) -{ - if (hsmbus->XferCount != 0U) - { - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - hsmbus->XferCount--; - } - - return HAL_OK; -} - -/** - * @brief Handle ADD flag for Slave - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_Slave_ADDR(SMBUS_HandleTypeDef *hsmbus) -{ - uint8_t TransferDirection = SMBUS_DIRECTION_RECEIVE ; - uint16_t SlaveAddrCode = 0U; - - /* Transfer Direction requested by Master */ - if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_TRA) == RESET) - { - TransferDirection = SMBUS_DIRECTION_TRANSMIT; - } - - if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_DUALF) == RESET) - { - SlaveAddrCode = hsmbus->Init.OwnAddress1; - } - else - { - SlaveAddrCode = hsmbus->Init.OwnAddress2; - } - - /* Call Slave Addr callback */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->AddrCallback(hsmbus, TransferDirection, SlaveAddrCode); -#else - HAL_SMBUS_AddrCallback(hsmbus, TransferDirection, SlaveAddrCode); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - - return HAL_OK; -} - -/** - * @brief Handle STOPF flag for Slave - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_Slave_STOPF(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - uint32_t CurrentState = hsmbus->State; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - /* Clear STOPF flag */ - __HAL_SMBUS_CLEAR_STOPFLAG(hsmbus); - - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - /* All data are not transferred, so set error code accordingly */ - if (hsmbus->XferCount != 0U) - { - /* Store Last receive data if any */ - if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_BTF) == SET) - { - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - - if (hsmbus->XferCount > 0) - { - hsmbus->XferSize--; - hsmbus->XferCount--; - } - } - - /* Store Last receive data if any */ - if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) == SET) - { - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - - if (hsmbus->XferCount > 0) - { - hsmbus->XferSize--; - hsmbus->XferCount--; - } - } - } - - if (hsmbus->ErrorCode != HAL_SMBUS_ERROR_NONE) - { - /* Call the corresponding callback to inform upper layer of End of Transfer */ - SMBUS_ITError(hsmbus); - } - else - { - if ((CurrentState == HAL_SMBUS_STATE_LISTEN) || (CurrentState == HAL_SMBUS_STATE_BUSY_RX_LISTEN) || \ - (CurrentState == HAL_SMBUS_STATE_BUSY_TX_LISTEN)) - { - hsmbus->XferOptions = SMBUS_NO_OPTION_FRAME; - hsmbus->PreviousState = HAL_SMBUS_STATE_READY; - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->ListenCpltCallback(hsmbus); -#else - HAL_SMBUS_ListenCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - } - return HAL_OK; -} - -/** - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_Slave_AF(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variables to prevent undefined behavior of volatile usage */ - uint32_t CurrentState = hsmbus->State; - uint32_t CurrentXferOptions = hsmbus->XferOptions; - - if (((CurrentXferOptions == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || (CurrentXferOptions == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || \ - (CurrentXferOptions == SMBUS_LAST_FRAME_NO_PEC) || (CurrentXferOptions == SMBUS_LAST_FRAME_WITH_PEC)) && \ - (CurrentState == HAL_SMBUS_STATE_LISTEN)) - { - hsmbus->XferOptions = SMBUS_NO_OPTION_FRAME; - - /* Disable EVT, BUF and ERR interrupt */ - __HAL_SMBUS_DISABLE_IT(hsmbus, SMBUS_IT_EVT | SMBUS_IT_BUF | SMBUS_IT_ERR); - - /* Clear AF flag */ - __HAL_SMBUS_CLEAR_FLAG(hsmbus, SMBUS_FLAG_AF); - - /* Disable Acknowledge */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_ACK); - - hsmbus->PreviousState = HAL_SMBUS_STATE_READY; - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->ListenCpltCallback(hsmbus); -#else - HAL_SMBUS_ListenCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - return HAL_OK; -} - - - -/** - * @brief SMBUS interrupts error process - * @param hsmbus SMBUS handle. - * @retval None - */ -static void SMBUS_ITError(SMBUS_HandleTypeDef *hsmbus) -{ - /* Declaration of temporary variable to prevent undefined behavior of volatile usage */ - uint32_t CurrentState = hsmbus->State; - - if ((CurrentState == HAL_SMBUS_STATE_BUSY_TX_LISTEN) || (CurrentState == HAL_SMBUS_STATE_BUSY_RX_LISTEN)) - { - /* keep HAL_SMBUS_STATE_LISTEN */ - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->State = HAL_SMBUS_STATE_LISTEN; - } - else - { - /* If state is an abort treatment on going, don't change state */ - /* This change will be done later */ - if (hsmbus->State != HAL_SMBUS_STATE_ABORT) - { - hsmbus->State = HAL_SMBUS_STATE_READY; - } - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - } - - /* Disable Pos bit in SMBUS CR1 when error occurred in Master/Mem Receive IT Process */ - CLEAR_BIT(hsmbus->Instance->CR1, I2C_CR1_POS); - - if (hsmbus->State == HAL_SMBUS_STATE_ABORT) - { - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->ErrorCode = HAL_SMBUS_ERROR_NONE; - - /* Store Last receive data if any */ - if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) == SET) - { - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - } - - /* Disable SMBUS peripheral to prevent dummy data in buffer */ - __HAL_SMBUS_DISABLE(hsmbus); - - /* Call the corresponding callback to inform upper layer of End of Transfer */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->AbortCpltCallback(hsmbus); -#else - HAL_SMBUS_AbortCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - else - { - /* Store Last receive data if any */ - if (__HAL_SMBUS_GET_FLAG(hsmbus, SMBUS_FLAG_RXNE) == SET) - { - /* Read data from DR */ - (*hsmbus->pBuffPtr++) = hsmbus->Instance->DR; - } - - /* Call user error callback */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->ErrorCallback(hsmbus); -#else - HAL_SMBUS_ErrorCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } - /* STOP Flag is not set after a NACK reception */ - /* So may inform upper layer that listen phase is stopped */ - /* during NACK error treatment */ - if ((hsmbus->State == HAL_SMBUS_STATE_LISTEN) && ((hsmbus->ErrorCode & HAL_SMBUS_ERROR_AF) == HAL_SMBUS_ERROR_AF)) - { - hsmbus->XferOptions = SMBUS_NO_OPTION_FRAME; - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - - /* Call the Listen Complete callback, to inform upper layer of the end of Listen usecase */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - hsmbus->ListenCpltCallback(hsmbus); -#else - HAL_SMBUS_ListenCpltCallback(hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - } -} - -/** - * @brief This function handles SMBUS Communication Timeout. - * @param hsmbus Pointer to a SMBUS_HandleTypeDef structure that contains - * the configuration information for SMBUS module - * @param Flag specifies the SMBUS flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Timeout Timeout duration - * @param Tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SMBUS_WaitOnFlagUntilTimeout(SMBUS_HandleTypeDef *hsmbus, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t Tickstart) -{ - /* Wait until flag is set */ - if (Status == RESET) - { - while (__HAL_SMBUS_GET_FLAG(hsmbus, Flag) == RESET) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) - { - hsmbus->PreviousState = SMBUS_STATE_NONE; - hsmbus->State = HAL_SMBUS_STATE_READY; - hsmbus->Mode = HAL_SMBUS_MODE_NONE; - - /* Process Unlocked */ - __HAL_UNLOCK(hsmbus); - return HAL_TIMEOUT; - } - } - } - } - return HAL_OK; -} - -/** - * @} - */ - - -#endif /* HAL_SMBUS_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spdifrx.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spdifrx.c deleted file mode 100644 index 50fac5e027a1332..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spdifrx.c +++ /dev/null @@ -1,1623 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_spdifrx.c - * @author MCD Application Team - * @brief This file provides firmware functions to manage the following - * functionalities of the SPDIFRX audio interface: - * + Initialization and Configuration - * + Data transfers functions - * + DMA transfers management - * + Interrupts and flags management - @verbatim - =============================================================================== - ##### How to use this driver ##### - =============================================================================== - [..] - The SPDIFRX HAL driver can be used as follow: - - (#) Declare SPDIFRX_HandleTypeDef handle structure. - (#) Initialize the SPDIFRX low level resources by implement the HAL_SPDIFRX_MspInit() API: - (##) Enable the SPDIFRX interface clock. - (##) SPDIFRX pins configuration: - (+++) Enable the clock for the SPDIFRX GPIOs. - (+++) Configure these SPDIFRX pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_SPDIFRX_ReceiveControlFlow_IT() and HAL_SPDIFRX_ReceiveDataFlow_IT() API's). - (+++) Configure the SPDIFRX interrupt priority. - (+++) Enable the NVIC SPDIFRX IRQ handle. - (##) DMA Configuration if you need to use DMA process (HAL_SPDIFRX_ReceiveDataFlow_DMA() and HAL_SPDIFRX_ReceiveControlFlow_DMA() API's). - (+++) Declare a DMA handle structure for the reception of the Data Flow channel. - (+++) Declare a DMA handle structure for the reception of the Control Flow channel. - (+++) Enable the DMAx interface clock. - (+++) Configure the declared DMA handle structure CtrlRx/DataRx with the required parameters. - (+++) Configure the DMA Channel. - (+++) Associate the initialized DMA handle to the SPDIFRX DMA CtrlRx/DataRx handle. - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the - DMA CtrlRx/DataRx channel. - - (#) Program the input selection, re-tries number, wait for activity, channel status selection, data format, stereo mode and masking of user bits - using HAL_SPDIFRX_Init() function. - - -@- The specific SPDIFRX interrupts (RXNE/CSRNE and Error Interrupts) will be managed using the macros - __SPDIFRX_ENABLE_IT() and __SPDIFRX_DISABLE_IT() inside the receive process. - -@- Make sure that ck_spdif clock is configured. - - (#) Three operation modes are available within this driver : - - *** Polling mode for reception operation (for debug purpose) *** - ================================================================ - [..] - (+) Receive data flow in blocking mode using HAL_SPDIFRX_ReceiveDataFlow() - (+) Receive control flow of data in blocking mode using HAL_SPDIFRX_ReceiveControlFlow() - - *** Interrupt mode for reception operation *** - ========================================= - [..] - (+) Receive an amount of data (Data Flow) in non blocking mode using HAL_SPDIFRX_ReceiveDataFlow_IT() - (+) Receive an amount of data (Control Flow) in non blocking mode using HAL_SPDIFRX_ReceiveControlFlow_IT() - (+) At reception end of half transfer HAL_SPDIFRX_RxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_SPDIFRX_RxHalfCpltCallback - (+) At reception end of transfer HAL_SPDIFRX_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_SPDIFRX_RxCpltCallback - (+) In case of transfer Error, HAL_SPDIFRX_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_SPDIFRX_ErrorCallback - - *** DMA mode for reception operation *** - ======================================== - [..] - (+) Receive an amount of data (Data Flow) in non blocking mode (DMA) using HAL_SPDIFRX_ReceiveDataFlow_DMA() - (+) Receive an amount of data (Control Flow) in non blocking mode (DMA) using HAL_SPDIFRX_ReceiveControlFlow_DMA() - (+) At reception end of half transfer HAL_SPDIFRX_RxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_SPDIFRX_RxHalfCpltCallback - (+) At reception end of transfer HAL_SPDIFRX_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_SPDIFRX_RxCpltCallback - (+) In case of transfer Error, HAL_SPDIFRX_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_SPDIFRX_ErrorCallback - (+) Stop the DMA Transfer using HAL_SPDIFRX_DMAStop() - - *** SPDIFRX HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in SPDIFRX HAL driver. - (+) __HAL_SPDIFRX_IDLE: Disable the specified SPDIFRX peripheral (IDEL State) - (+) __HAL_SPDIFRX_SYNC: Enable the synchronization state of the specified SPDIFRX peripheral (SYNC State) - (+) __HAL_SPDIFRX_RCV: Enable the receive state of the specified SPDIFRX peripheral (RCV State) - (+) __HAL_SPDIFRX_ENABLE_IT : Enable the specified SPDIFRX interrupts - (+) __HAL_SPDIFRX_DISABLE_IT : Disable the specified SPDIFRX interrupts - (+) __HAL_SPDIFRX_GET_FLAG: Check whether the specified SPDIFRX flag is set or not. - - [..] - (@) You can refer to the SPDIFRX HAL driver header file for more useful macros - - *** Callback registration *** - ============================================= - - The compilation define USE_HAL_SPDIFRX_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - Use HAL_SPDIFRX_RegisterCallback() function to register an interrupt callback. - - The HAL_SPDIFRX_RegisterCallback() function allows to register the following callbacks: - (+) RxHalfCpltCallback : SPDIFRX Data flow half completed callback. - (+) RxCpltCallback : SPDIFRX Data flow completed callback. - (+) CxHalfCpltCallback : SPDIFRX Control flow half completed callback. - (+) CxCpltCallback : SPDIFRX Control flow completed callback. - (+) ErrorCallback : SPDIFRX error callback. - (+) MspInitCallback : SPDIFRX MspInit. - (+) MspDeInitCallback : SPDIFRX MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use HAL_SPDIFRX_UnRegisterCallback() function to reset a callback to the default - weak function. - The HAL_SPDIFRX_UnRegisterCallback() function takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset the following callbacks: - (+) RxHalfCpltCallback : SPDIFRX Data flow half completed callback. - (+) RxCpltCallback : SPDIFRX Data flow completed callback. - (+) CxHalfCpltCallback : SPDIFRX Control flow half completed callback. - (+) CxCpltCallback : SPDIFRX Control flow completed callback. - (+) ErrorCallback : SPDIFRX error callback. - (+) MspInitCallback : SPDIFRX MspInit. - (+) MspDeInitCallback : SPDIFRX MspDeInit. - - By default, after the HAL_SPDIFRX_Init() and when the state is HAL_SPDIFRX_STATE_RESET - all callbacks are set to the corresponding weak functions : - HAL_SPDIFRX_RxHalfCpltCallback() , HAL_SPDIFRX_RxCpltCallback(), HAL_SPDIFRX_CxHalfCpltCallback(), - HAL_SPDIFRX_CxCpltCallback() and HAL_SPDIFRX_ErrorCallback() - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak function in the HAL_SPDIFRX_Init()/ HAL_SPDIFRX_DeInit() only when - these callbacks pointers are NULL (not registered beforehand). - If not, MspInit or MspDeInit callbacks pointers are not null, the HAL_SPDIFRX_Init() / HAL_SPDIFRX_DeInit() - keep and use the user MspInit/MspDeInit functions (registered beforehand) - - Callbacks can be registered/unregistered in HAL_SPDIFRX_STATE_READY state only. - Exception done MspInit/MspDeInit callbacks that can be registered/unregistered - in HAL_SPDIFRX_STATE_READY or HAL_SPDIFRX_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_SPDIFRX_RegisterCallback() before calling HAL_SPDIFRX_DeInit() - or HAL_SPDIFRX_Init() function. - - When The compilation define USE_HAL_SPDIFRX_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SPDIFRX SPDIFRX - * @brief SPDIFRX HAL module driver - * @{ - */ - -#ifdef HAL_SPDIFRX_MODULE_ENABLED -#if defined (SPDIFRX) -#if defined(STM32F446xx) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -#define SPDIFRX_TIMEOUT_VALUE 0xFFFFU - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup SPDIFRX_Private_Functions - * @{ - */ -static void SPDIFRX_DMARxCplt(DMA_HandleTypeDef *hdma); -static void SPDIFRX_DMARxHalfCplt(DMA_HandleTypeDef *hdma); -static void SPDIFRX_DMACxCplt(DMA_HandleTypeDef *hdma); -static void SPDIFRX_DMACxHalfCplt(DMA_HandleTypeDef *hdma); -static void SPDIFRX_DMAError(DMA_HandleTypeDef *hdma); -static void SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef *hspdif); -static void SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef *hspdif); -static HAL_StatusTypeDef SPDIFRX_WaitOnFlagUntilTimeout(SPDIFRX_HandleTypeDef *hspdif, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t tickstart); -/** - * @} - */ -/* Exported functions ---------------------------------------------------------*/ - -/** @defgroup SPDIFRX_Exported_Functions SPDIFRX Exported Functions - * @{ - */ - -/** @defgroup SPDIFRX_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * - @verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - de-initialize the SPDIFRX peripheral: - - (+) User must Implement HAL_SPDIFRX_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). - - (+) Call the function HAL_SPDIFRX_Init() to configure the SPDIFRX peripheral with - the selected configuration: - (++) Input Selection (IN0, IN1,...) - (++) Maximum allowed re-tries during synchronization phase - (++) Wait for activity on SPDIF selected input - (++) Channel status selection (from channel A or B) - (++) Data format (LSB, MSB, ...) - (++) Stereo mode - (++) User bits masking (PT,C,U,V,...) - - (+) Call the function HAL_SPDIFRX_DeInit() to restore the default configuration - of the selected SPDIFRXx peripheral. - @endverbatim - * @{ - */ - -/** - * @brief Initializes the SPDIFRX according to the specified parameters - * in the SPDIFRX_InitTypeDef and create the associated handle. - * @param hspdif SPDIFRX handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_Init(SPDIFRX_HandleTypeDef *hspdif) -{ - uint32_t tmpreg; - - /* Check the SPDIFRX handle allocation */ - if(hspdif == NULL) - { - return HAL_ERROR; - } - - /* Check the SPDIFRX parameters */ - assert_param(IS_STEREO_MODE(hspdif->Init.StereoMode)); - assert_param(IS_SPDIFRX_INPUT_SELECT(hspdif->Init.InputSelection)); - assert_param(IS_SPDIFRX_MAX_RETRIES(hspdif->Init.Retries)); - assert_param(IS_SPDIFRX_WAIT_FOR_ACTIVITY(hspdif->Init.WaitForActivity)); - assert_param(IS_SPDIFRX_CHANNEL(hspdif->Init.ChannelSelection)); - assert_param(IS_SPDIFRX_DATA_FORMAT(hspdif->Init.DataFormat)); - assert_param(IS_PREAMBLE_TYPE_MASK(hspdif->Init.PreambleTypeMask)); - assert_param(IS_CHANNEL_STATUS_MASK(hspdif->Init.ChannelStatusMask)); - assert_param(IS_VALIDITY_MASK(hspdif->Init.ValidityBitMask)); - assert_param(IS_PARITY_ERROR_MASK(hspdif->Init.ParityErrorMask)); - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - if(hspdif->State == HAL_SPDIFRX_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hspdif->Lock = HAL_UNLOCKED; - - hspdif->RxHalfCpltCallback = HAL_SPDIFRX_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - hspdif->RxCpltCallback = HAL_SPDIFRX_RxCpltCallback; /* Legacy weak RxCpltCallback */ - hspdif->CxHalfCpltCallback = HAL_SPDIFRX_CxHalfCpltCallback; /* Legacy weak CxHalfCpltCallback */ - hspdif->CxCpltCallback = HAL_SPDIFRX_CxCpltCallback; /* Legacy weak CxCpltCallback */ - hspdif->ErrorCallback = HAL_SPDIFRX_ErrorCallback; /* Legacy weak ErrorCallback */ - - if(hspdif->MspInitCallback == NULL) - { - hspdif->MspInitCallback = HAL_SPDIFRX_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware */ - hspdif->MspInitCallback(hspdif); - } -#else - if(hspdif->State == HAL_SPDIFRX_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hspdif->Lock = HAL_UNLOCKED; - /* Init the low level hardware : GPIO, CLOCK, CORTEX...etc */ - HAL_SPDIFRX_MspInit(hspdif); - } -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - - /* SPDIFRX peripheral state is BUSY */ - hspdif->State = HAL_SPDIFRX_STATE_BUSY; - - /* Disable SPDIFRX interface (IDLE State) */ - __HAL_SPDIFRX_IDLE(hspdif); - - /* Reset the old SPDIFRX CR configuration */ - tmpreg = hspdif->Instance->CR; - - tmpreg &= ~(SPDIFRX_CR_RXSTEO | SPDIFRX_CR_DRFMT | SPDIFRX_CR_PMSK | - SPDIFRX_CR_VMSK | SPDIFRX_CR_CUMSK | SPDIFRX_CR_PTMSK | - SPDIFRX_CR_CHSEL | SPDIFRX_CR_NBTR | SPDIFRX_CR_WFA | - SPDIFRX_CR_INSEL); - - /* Sets the new configuration of the SPDIFRX peripheral */ - tmpreg |= (hspdif->Init.StereoMode | - hspdif->Init.InputSelection | - hspdif->Init.Retries | - hspdif->Init.WaitForActivity | - hspdif->Init.ChannelSelection | - hspdif->Init.DataFormat | - hspdif->Init.PreambleTypeMask | - hspdif->Init.ChannelStatusMask | - hspdif->Init.ValidityBitMask | - hspdif->Init.ParityErrorMask - ); - - - hspdif->Instance->CR = tmpreg; - - hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; - - /* SPDIFRX peripheral state is READY*/ - hspdif->State = HAL_SPDIFRX_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the SPDIFRX peripheral - * @param hspdif SPDIFRX handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_DeInit(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Check the SPDIFRX handle allocation */ - if(hspdif == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SPDIFRX_ALL_INSTANCE(hspdif->Instance)); - - hspdif->State = HAL_SPDIFRX_STATE_BUSY; - - /* Disable SPDIFRX interface (IDLE state) */ - __HAL_SPDIFRX_IDLE(hspdif); - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - if(hspdif->MspDeInitCallback == NULL) - { - hspdif->MspDeInitCallback = HAL_SPDIFRX_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware */ - hspdif->MspDeInitCallback(hspdif); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ - HAL_SPDIFRX_MspDeInit(hspdif); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - - hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; - - /* SPDIFRX peripheral state is RESET*/ - hspdif->State = HAL_SPDIFRX_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hspdif); - - return HAL_OK; -} - -/** - * @brief SPDIFRX MSP Init - * @param hspdif SPDIFRX handle - * @retval None - */ -__weak void HAL_SPDIFRX_MspInit(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspdif); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SPDIFRX_MspInit could be implemented in the user file - */ -} - -/** - * @brief SPDIFRX MSP DeInit - * @param hspdif SPDIFRX handle - * @retval None - */ -__weak void HAL_SPDIFRX_MspDeInit(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspdif); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SPDIFRX_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User SPDIFRX Callback - * To be used instead of the weak predefined callback - * @param hspdif SPDIFRX handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_SPDIFRX_RX_HALF_CB_ID SPDIFRX Data flow half completed callback ID - * @arg @ref HAL_SPDIFRX_RX_CPLT_CB_ID SPDIFRX Data flow completed callback ID - * @arg @ref HAL_SPDIFRX_CX_HALF_CB_ID SPDIFRX Control flow half completed callback ID - * @arg @ref HAL_SPDIFRX_CX_CPLT_CB_ID SPDIFRX Control flow completed callback ID - * @arg @ref HAL_SPDIFRX_ERROR_CB_ID SPDIFRX error callback ID - * @arg @ref HAL_SPDIFRX_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_SPDIFRX_MSPDEINIT_CB_ID MspDeInit callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_RegisterCallback(SPDIFRX_HandleTypeDef *hspdif, HAL_SPDIFRX_CallbackIDTypeDef CallbackID, pSPDIFRX_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if(pCallback == NULL) - { - /* Update the error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hspdif); - - if(HAL_SPDIFRX_STATE_READY == hspdif->State) - { - switch (CallbackID) - { - case HAL_SPDIFRX_RX_HALF_CB_ID : - hspdif->RxHalfCpltCallback = pCallback; - break; - - case HAL_SPDIFRX_RX_CPLT_CB_ID : - hspdif->RxCpltCallback = pCallback; - break; - - case HAL_SPDIFRX_CX_HALF_CB_ID : - hspdif->CxHalfCpltCallback = pCallback; - break; - - case HAL_SPDIFRX_CX_CPLT_CB_ID : - hspdif->CxCpltCallback = pCallback; - break; - - case HAL_SPDIFRX_ERROR_CB_ID : - hspdif->ErrorCallback = pCallback; - break; - - case HAL_SPDIFRX_MSPINIT_CB_ID : - hspdif->MspInitCallback = pCallback; - break; - - case HAL_SPDIFRX_MSPDEINIT_CB_ID : - hspdif->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if(HAL_SPDIFRX_STATE_RESET == hspdif->State) - { - switch (CallbackID) - { - case HAL_SPDIFRX_MSPINIT_CB_ID : - hspdif->MspInitCallback = pCallback; - break; - - case HAL_SPDIFRX_MSPDEINIT_CB_ID : - hspdif->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hspdif); - return status; -} - -/** - * @brief Unregister a SPDIFRX Callback - * SPDIFRX callabck is redirected to the weak predefined callback - * @param hspdif SPDIFRX handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_SPDIFRX_RX_HALF_CB_ID SPDIFRX Data flow half completed callback ID - * @arg @ref HAL_SPDIFRX_RX_CPLT_CB_ID SPDIFRX Data flow completed callback ID - * @arg @ref HAL_SPDIFRX_CX_HALF_CB_ID SPDIFRX Control flow half completed callback ID - * @arg @ref HAL_SPDIFRX_CX_CPLT_CB_ID SPDIFRX Control flow completed callback ID - * @arg @ref HAL_SPDIFRX_ERROR_CB_ID SPDIFRX error callback ID - * @arg @ref HAL_SPDIFRX_MSPINIT_CB_ID MspInit callback ID - * @arg @ref HAL_SPDIFRX_MSPDEINIT_CB_ID MspDeInit callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_UnRegisterCallback(SPDIFRX_HandleTypeDef *hspdif, HAL_SPDIFRX_CallbackIDTypeDef CallbackID) -{ -HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hspdif); - - if(HAL_SPDIFRX_STATE_READY == hspdif->State) - { - switch (CallbackID) - { - case HAL_SPDIFRX_RX_HALF_CB_ID : - hspdif->RxHalfCpltCallback = HAL_SPDIFRX_RxHalfCpltCallback; - break; - - case HAL_SPDIFRX_RX_CPLT_CB_ID : - hspdif->RxCpltCallback = HAL_SPDIFRX_RxCpltCallback; - break; - - case HAL_SPDIFRX_CX_HALF_CB_ID : - hspdif->CxHalfCpltCallback = HAL_SPDIFRX_CxHalfCpltCallback; - break; - - case HAL_SPDIFRX_CX_CPLT_CB_ID : - hspdif->CxCpltCallback = HAL_SPDIFRX_CxCpltCallback; - break; - - case HAL_SPDIFRX_ERROR_CB_ID : - hspdif->ErrorCallback = HAL_SPDIFRX_ErrorCallback; - break; - - default : - /* Update the error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if(HAL_SPDIFRX_STATE_RESET == hspdif->State) - { - switch (CallbackID) - { - case HAL_SPDIFRX_MSPINIT_CB_ID : - hspdif->MspInitCallback = HAL_SPDIFRX_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_SPDIFRX_MSPDEINIT_CB_ID : - hspdif->MspDeInitCallback = HAL_SPDIFRX_MspDeInit; /* Legacy weak MspInit */ - break; - - default : - /* Update the error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_INVALID_CALLBACK; - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hspdif); - return status; -} - -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - -/** - * @brief Set the SPDIFRX data format according to the specified parameters in the SPDIFRX_InitTypeDef. - * @param hspdif SPDIFRX handle - * @param sDataFormat SPDIFRX data format - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_SetDataFormat(SPDIFRX_HandleTypeDef *hspdif, SPDIFRX_SetDataFormatTypeDef sDataFormat) -{ - uint32_t tmpreg; - - /* Check the SPDIFRX handle allocation */ - if(hspdif == NULL) - { - return HAL_ERROR; - } - - /* Check the SPDIFRX parameters */ - assert_param(IS_STEREO_MODE(sDataFormat.StereoMode)); - assert_param(IS_SPDIFRX_DATA_FORMAT(sDataFormat.DataFormat)); - assert_param(IS_PREAMBLE_TYPE_MASK(sDataFormat.PreambleTypeMask)); - assert_param(IS_CHANNEL_STATUS_MASK(sDataFormat.ChannelStatusMask)); - assert_param(IS_VALIDITY_MASK(sDataFormat.ValidityBitMask)); - assert_param(IS_PARITY_ERROR_MASK(sDataFormat.ParityErrorMask)); - - /* Reset the old SPDIFRX CR configuration */ - tmpreg = hspdif->Instance->CR; - - if(((tmpreg & SPDIFRX_STATE_RCV) == SPDIFRX_STATE_RCV) && - (((tmpreg & SPDIFRX_CR_DRFMT) != sDataFormat.DataFormat) || - ((tmpreg & SPDIFRX_CR_RXSTEO) != sDataFormat.StereoMode))) - { - return HAL_ERROR; - } - - tmpreg &= ~(SPDIFRX_CR_RXSTEO | SPDIFRX_CR_DRFMT | SPDIFRX_CR_PMSK | - SPDIFRX_CR_VMSK | SPDIFRX_CR_CUMSK | SPDIFRX_CR_PTMSK); - - /* Configure the new data format */ - tmpreg |= (sDataFormat.StereoMode | - sDataFormat.DataFormat | - sDataFormat.PreambleTypeMask | - sDataFormat.ChannelStatusMask | - sDataFormat.ValidityBitMask | - sDataFormat.ParityErrorMask); - - hspdif->Instance->CR = tmpreg; - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup SPDIFRX_Exported_Functions_Group2 IO operation functions - * @brief Data transfers functions - * -@verbatim -=============================================================================== - ##### IO operation functions ##### -=============================================================================== - [..] - This subsection provides a set of functions allowing to manage the SPDIFRX data - transfers. - - (#) There is two mode of transfer: - (++) Blocking mode : The communication is performed in the polling mode. - The status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode : The communication is performed using Interrupts - or DMA. These functions return the status of the transfer start-up. - The end of the data processing will be indicated through the - dedicated SPDIFRX IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - - (#) Blocking mode functions are : - (++) HAL_SPDIFRX_ReceiveDataFlow() - (++) HAL_SPDIFRX_ReceiveControlFlow() - (+@) Do not use blocking mode to receive both control and data flow at the same time. - - (#) No-Blocking mode functions with Interrupt are : - (++) HAL_SPDIFRX_ReceiveControlFlow_IT() - (++) HAL_SPDIFRX_ReceiveDataFlow_IT() - - (#) No-Blocking mode functions with DMA are : - (++) HAL_SPDIFRX_ReceiveControlFlow_DMA() - (++) HAL_SPDIFRX_ReceiveDataFlow_DMA() - - (#) A set of Transfer Complete Callbacks are provided in No_Blocking mode: - (++) HAL_SPDIFRX_RxCpltCallback() - (++) HAL_SPDIFRX_CxCpltCallback() - -@endverbatim -* @{ -*/ - -/** - * @brief Receives an amount of data (Data Flow) in blocking mode. - * @param hspdif pointer to SPDIFRX_HandleTypeDef structure that contains - * the configuration information for SPDIFRX module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be received - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart; - uint16_t sizeCounter = Size; - uint32_t *pTmpBuf = pData; - - if((pData == NULL ) || (Size == 0U)) - { - return HAL_ERROR; - } - - if(hspdif->State == HAL_SPDIFRX_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hspdif); - - hspdif->State = HAL_SPDIFRX_STATE_BUSY; - - /* Start synchronisation */ - __HAL_SPDIFRX_SYNC(hspdif); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until SYNCD flag is set */ - if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif, SPDIFRX_FLAG_SYNCD, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* Start reception */ - __HAL_SPDIFRX_RCV(hspdif); - - /* Receive data flow */ - while(sizeCounter > 0U) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until RXNE flag is set */ - if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif, SPDIFRX_FLAG_RXNE, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_TIMEOUT; - } - - (*pTmpBuf) = hspdif->Instance->DR; - pTmpBuf++; - sizeCounter--; - } - - /* SPDIFRX ready */ - hspdif->State = HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives an amount of data (Control Flow) in blocking mode. - * @param hspdif pointer to a SPDIFRX_HandleTypeDef structure that contains - * the configuration information for SPDIFRX module. - * @param pData Pointer to data buffer - * @param Size Amount of data to be received - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart; - uint16_t sizeCounter = Size; - uint32_t *pTmpBuf = pData; - - if((pData == NULL ) || (Size == 0U)) - { - return HAL_ERROR; - } - - if(hspdif->State == HAL_SPDIFRX_STATE_READY) - { - /* Process Locked */ - __HAL_LOCK(hspdif); - - hspdif->State = HAL_SPDIFRX_STATE_BUSY; - - /* Start synchronization */ - __HAL_SPDIFRX_SYNC(hspdif); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until SYNCD flag is set */ - if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif, SPDIFRX_FLAG_SYNCD, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* Start reception */ - __HAL_SPDIFRX_RCV(hspdif); - - /* Receive control flow */ - while(sizeCounter > 0U) - { - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until CSRNE flag is set */ - if(SPDIFRX_WaitOnFlagUntilTimeout(hspdif, SPDIFRX_FLAG_CSRNE, RESET, Timeout, tickstart) != HAL_OK) - { - return HAL_TIMEOUT; - } - - (*pTmpBuf) = hspdif->Instance->CSR; - pTmpBuf++; - sizeCounter--; - } - - /* SPDIFRX ready */ - hspdif->State = HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data (Data Flow) in non-blocking mode with Interrupt - * @param hspdif SPDIFRX handle - * @param pData a 32-bit pointer to the Receive data buffer. - * @param Size number of data sample to be received . - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size) -{ - uint32_t count = SPDIFRX_TIMEOUT_VALUE * (SystemCoreClock / 24U / 1000U); - - const HAL_SPDIFRX_StateTypeDef tempState = hspdif->State; - - if((tempState == HAL_SPDIFRX_STATE_READY) || (tempState == HAL_SPDIFRX_STATE_BUSY_CX)) - { - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hspdif); - - hspdif->pRxBuffPtr = pData; - hspdif->RxXferSize = Size; - hspdif->RxXferCount = Size; - - hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; - - /* Check if a receive process is ongoing or not */ - hspdif->State = HAL_SPDIFRX_STATE_BUSY_RX; - - /* Enable the SPDIFRX PE Error Interrupt */ - __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_PERRIE); - - /* Enable the SPDIFRX OVR Error Interrupt */ - __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_OVRIE); - - /* Enable the SPDIFRX RXNE interrupt */ - __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_RXNE); - - if((SPDIFRX->CR & SPDIFRX_CR_SPDIFEN) != SPDIFRX_STATE_RCV) - { - /* Start synchronization */ - __HAL_SPDIFRX_SYNC(hspdif); - - /* Wait until SYNCD flag is set */ - do - { - if (count == 0U) - { - /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); - - hspdif->State= HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_TIMEOUT; - } - count--; - } while (__HAL_SPDIFRX_GET_FLAG(hspdif, SPDIFRX_FLAG_SYNCD) == RESET); - - /* Start reception */ - __HAL_SPDIFRX_RCV(hspdif); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data (Control Flow) with Interrupt - * @param hspdif SPDIFRX handle - * @param pData a 32-bit pointer to the Receive data buffer. - * @param Size number of data sample (Control Flow) to be received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size) -{ - uint32_t count = SPDIFRX_TIMEOUT_VALUE * (SystemCoreClock / 24U / 1000U); - - const HAL_SPDIFRX_StateTypeDef tempState = hspdif->State; - - if((tempState == HAL_SPDIFRX_STATE_READY) || (tempState == HAL_SPDIFRX_STATE_BUSY_RX)) - { - if((pData == NULL ) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hspdif); - - hspdif->pCsBuffPtr = pData; - hspdif->CsXferSize = Size; - hspdif->CsXferCount = Size; - - hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; - - /* Check if a receive process is ongoing or not */ - hspdif->State = HAL_SPDIFRX_STATE_BUSY_CX; - - /* Enable the SPDIFRX PE Error Interrupt */ - __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_PERRIE); - - /* Enable the SPDIFRX OVR Error Interrupt */ - __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_OVRIE); - - /* Enable the SPDIFRX CSRNE interrupt */ - __HAL_SPDIFRX_ENABLE_IT(hspdif, SPDIFRX_IT_CSRNE); - - if((SPDIFRX->CR & SPDIFRX_CR_SPDIFEN) != SPDIFRX_STATE_RCV) - { - /* Start synchronization */ - __HAL_SPDIFRX_SYNC(hspdif); - - /* Wait until SYNCD flag is set */ - do - { - if (count == 0U) - { - /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); - - hspdif->State= HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_TIMEOUT; - } - count--; - } while (__HAL_SPDIFRX_GET_FLAG(hspdif, SPDIFRX_FLAG_SYNCD) == RESET); - - /* Start reception */ - __HAL_SPDIFRX_RCV(hspdif); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data (Data Flow) mode with DMA - * @param hspdif SPDIFRX handle - * @param pData a 32-bit pointer to the Receive data buffer. - * @param Size number of data sample to be received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow_DMA(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size) -{ - uint32_t count = SPDIFRX_TIMEOUT_VALUE * (SystemCoreClock / 24U / 1000U); - - const HAL_SPDIFRX_StateTypeDef tempState = hspdif->State; - - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - if((tempState == HAL_SPDIFRX_STATE_READY) || (tempState == HAL_SPDIFRX_STATE_BUSY_CX)) - { - /* Process Locked */ - __HAL_LOCK(hspdif); - - hspdif->pRxBuffPtr = pData; - hspdif->RxXferSize = Size; - hspdif->RxXferCount = Size; - - hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; - hspdif->State = HAL_SPDIFRX_STATE_BUSY_RX; - - /* Set the SPDIFRX Rx DMA Half transfer complete callback */ - hspdif->hdmaDrRx->XferHalfCpltCallback = SPDIFRX_DMARxHalfCplt; - - /* Set the SPDIFRX Rx DMA transfer complete callback */ - hspdif->hdmaDrRx->XferCpltCallback = SPDIFRX_DMARxCplt; - - /* Set the DMA error callback */ - hspdif->hdmaDrRx->XferErrorCallback = SPDIFRX_DMAError; - - /* Enable the DMA request */ - if(HAL_DMA_Start_IT(hspdif->hdmaDrRx, (uint32_t)&hspdif->Instance->DR, (uint32_t)hspdif->pRxBuffPtr, Size) != HAL_OK) - { - /* Set SPDIFRX error */ - hspdif->ErrorCode = HAL_SPDIFRX_ERROR_DMA; - - /* Set SPDIFRX state */ - hspdif->State = HAL_SPDIFRX_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_ERROR; - } - - /* Enable RXDMAEN bit in SPDIFRX CR register for data flow reception*/ - hspdif->Instance->CR |= SPDIFRX_CR_RXDMAEN; - - if((SPDIFRX->CR & SPDIFRX_CR_SPDIFEN) != SPDIFRX_STATE_RCV) - { - /* Start synchronization */ - __HAL_SPDIFRX_SYNC(hspdif); - - /* Wait until SYNCD flag is set */ - do - { - if (count == 0U) - { - /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); - - hspdif->State= HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_TIMEOUT; - } - count--; - } while (__HAL_SPDIFRX_GET_FLAG(hspdif, SPDIFRX_FLAG_SYNCD) == RESET); - - /* Start reception */ - __HAL_SPDIFRX_RCV(hspdif); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data (Control Flow) with DMA - * @param hspdif SPDIFRX handle - * @param pData a 32-bit pointer to the Receive data buffer. - * @param Size number of data (Control Flow) sample to be received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow_DMA(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size) -{ - uint32_t count = SPDIFRX_TIMEOUT_VALUE * (SystemCoreClock / 24U / 1000U); - - const HAL_SPDIFRX_StateTypeDef tempState = hspdif->State; - - if((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - if((tempState == HAL_SPDIFRX_STATE_READY) || (tempState == HAL_SPDIFRX_STATE_BUSY_RX)) - { - hspdif->pCsBuffPtr = pData; - hspdif->CsXferSize = Size; - hspdif->CsXferCount = Size; - - /* Process Locked */ - __HAL_LOCK(hspdif); - - hspdif->ErrorCode = HAL_SPDIFRX_ERROR_NONE; - hspdif->State = HAL_SPDIFRX_STATE_BUSY_CX; - - /* Set the SPDIFRX Rx DMA Half transfer complete callback */ - hspdif->hdmaCsRx->XferHalfCpltCallback = SPDIFRX_DMACxHalfCplt; - - /* Set the SPDIFRX Rx DMA transfer complete callback */ - hspdif->hdmaCsRx->XferCpltCallback = SPDIFRX_DMACxCplt; - - /* Set the DMA error callback */ - hspdif->hdmaCsRx->XferErrorCallback = SPDIFRX_DMAError; - - /* Enable the DMA request */ - if(HAL_DMA_Start_IT(hspdif->hdmaCsRx, (uint32_t)&hspdif->Instance->CSR, (uint32_t)hspdif->pCsBuffPtr, Size) != HAL_OK) - { - /* Set SPDIFRX error */ - hspdif->ErrorCode = HAL_SPDIFRX_ERROR_DMA; - - /* Set SPDIFRX state */ - hspdif->State = HAL_SPDIFRX_STATE_ERROR; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_ERROR; - } - - /* Enable CBDMAEN bit in SPDIFRX CR register for control flow reception*/ - hspdif->Instance->CR |= SPDIFRX_CR_CBDMAEN; - - if((SPDIFRX->CR & SPDIFRX_CR_SPDIFEN) != SPDIFRX_STATE_RCV) - { - /* Start synchronization */ - __HAL_SPDIFRX_SYNC(hspdif); - - /* Wait until SYNCD flag is set */ - do - { - if (count == 0U) - { - /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); - - hspdif->State= HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_TIMEOUT; - } - count--; - } while (__HAL_SPDIFRX_GET_FLAG(hspdif, SPDIFRX_FLAG_SYNCD) == RESET); - - /* Start reception */ - __HAL_SPDIFRX_RCV(hspdif); - } - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief stop the audio stream receive from the Media. - * @param hspdif SPDIFRX handle - * @retval None - */ -HAL_StatusTypeDef HAL_SPDIFRX_DMAStop(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Process Locked */ - __HAL_LOCK(hspdif); - - /* Disable the SPDIFRX DMA requests */ - hspdif->Instance->CR &= (uint16_t)(~SPDIFRX_CR_RXDMAEN); - hspdif->Instance->CR &= (uint16_t)(~SPDIFRX_CR_CBDMAEN); - - /* Disable the SPDIFRX DMA channel */ - __HAL_DMA_DISABLE(hspdif->hdmaDrRx); - __HAL_DMA_DISABLE(hspdif->hdmaCsRx); - - /* Disable SPDIFRX peripheral */ - __HAL_SPDIFRX_IDLE(hspdif); - - hspdif->State = HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_OK; -} - -/** - * @brief This function handles SPDIFRX interrupt request. - * @param hspdif SPDIFRX handle - * @retval HAL status - */ -void HAL_SPDIFRX_IRQHandler(SPDIFRX_HandleTypeDef *hspdif) -{ - uint32_t itFlag = hspdif->Instance->SR; - uint32_t itSource = hspdif->Instance->IMR; - - /* SPDIFRX in mode Data Flow Reception */ - if(((itFlag & SPDIFRX_FLAG_RXNE) == SPDIFRX_FLAG_RXNE) && ((itSource & SPDIFRX_IT_RXNE) == SPDIFRX_IT_RXNE)) - { - __HAL_SPDIFRX_CLEAR_IT(hspdif, SPDIFRX_IT_RXNE); - SPDIFRX_ReceiveDataFlow_IT(hspdif); - } - - /* SPDIFRX in mode Control Flow Reception */ - if(((itFlag & SPDIFRX_FLAG_CSRNE) == SPDIFRX_FLAG_CSRNE) && ((itSource & SPDIFRX_IT_CSRNE) == SPDIFRX_IT_CSRNE)) - { - __HAL_SPDIFRX_CLEAR_IT(hspdif, SPDIFRX_IT_CSRNE); - SPDIFRX_ReceiveControlFlow_IT(hspdif); - } - - /* SPDIFRX Overrun error interrupt occurred */ - if(((itFlag & SPDIFRX_FLAG_OVR) == SPDIFRX_FLAG_OVR) && ((itSource & SPDIFRX_IT_OVRIE) == SPDIFRX_IT_OVRIE)) - { - __HAL_SPDIFRX_CLEAR_IT(hspdif, SPDIFRX_IT_OVRIE); - - /* Change the SPDIFRX error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_OVR; - - /* the transfer is not stopped */ - HAL_SPDIFRX_ErrorCallback(hspdif); - } - - /* SPDIFRX Parity error interrupt occurred */ - if(((itFlag & SPDIFRX_FLAG_PERR) == SPDIFRX_FLAG_PERR) && ((itSource & SPDIFRX_IT_PERRIE) == SPDIFRX_IT_PERRIE)) - { - __HAL_SPDIFRX_CLEAR_IT(hspdif, SPDIFRX_IT_PERRIE); - - /* Change the SPDIFRX error code */ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_PE; - - /* the transfer is not stopped */ - HAL_SPDIFRX_ErrorCallback(hspdif); - } -} - -/** - * @brief Rx Transfer (Data flow) half completed callbacks - * @param hspdif SPDIFRX handle - * @retval None - */ -__weak void HAL_SPDIFRX_RxHalfCpltCallback(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspdif); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer (Data flow) completed callbacks - * @param hspdif SPDIFRX handle - * @retval None - */ -__weak void HAL_SPDIFRX_RxCpltCallback(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspdif); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx (Control flow) Transfer half completed callbacks - * @param hspdif SPDIFRX handle - * @retval None - */ -__weak void HAL_SPDIFRX_CxHalfCpltCallback(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspdif); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer (Control flow) completed callbacks - * @param hspdif SPDIFRX handle - * @retval None - */ -__weak void HAL_SPDIFRX_CxCpltCallback(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspdif); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SPDIFRX_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief SPDIFRX error callbacks - * @param hspdif SPDIFRX handle - * @retval None - */ -__weak void HAL_SPDIFRX_ErrorCallback(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspdif); - - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SPDIFRX_ErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup SPDIFRX_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief Peripheral State functions - * -@verbatim -=============================================================================== -##### Peripheral State and Errors functions ##### -=============================================================================== -[..] -This subsection permit to get in run-time the status of the peripheral -and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the SPDIFRX state - * @param hspdif SPDIFRX handle - * @retval HAL state - */ -HAL_SPDIFRX_StateTypeDef HAL_SPDIFRX_GetState(SPDIFRX_HandleTypeDef const * const hspdif) -{ - return hspdif->State; -} - -/** - * @brief Return the SPDIFRX error code - * @param hspdif SPDIFRX handle - * @retval SPDIFRX Error Code - */ -uint32_t HAL_SPDIFRX_GetError(SPDIFRX_HandleTypeDef const * const hspdif) -{ - return hspdif->ErrorCode; -} - -/** - * @} - */ - -/** - * @brief DMA SPDIFRX receive process (Data flow) complete callback - * @param hdma DMA handle - * @retval None - */ -static void SPDIFRX_DMARxCplt(DMA_HandleTypeDef *hdma) -{ - SPDIFRX_HandleTypeDef* hspdif = ( SPDIFRX_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - /* Disable Rx DMA Request */ - if(hdma->Init.Mode != DMA_CIRCULAR) - { - hspdif->Instance->CR &= (uint16_t)(~SPDIFRX_CR_RXDMAEN); - hspdif->RxXferCount = 0; - hspdif->State = HAL_SPDIFRX_STATE_READY; - } -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - hspdif->RxCpltCallback(hspdif); -#else - HAL_SPDIFRX_RxCpltCallback(hspdif); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPDIFRX receive process (Data flow) half complete callback - * @param hdma DMA handle - * @retval None - */ -static void SPDIFRX_DMARxHalfCplt(DMA_HandleTypeDef *hdma) -{ - SPDIFRX_HandleTypeDef* hspdif = (SPDIFRX_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent; - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - hspdif->RxHalfCpltCallback(hspdif); -#else - HAL_SPDIFRX_RxHalfCpltCallback(hspdif); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -} - - -/** - * @brief DMA SPDIFRX receive process (Control flow) complete callback - * @param hdma DMA handle - * @retval None - */ -static void SPDIFRX_DMACxCplt(DMA_HandleTypeDef *hdma) -{ - SPDIFRX_HandleTypeDef* hspdif = ( SPDIFRX_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - /* Disable Cb DMA Request */ - hspdif->Instance->CR &= (uint16_t)(~SPDIFRX_CR_CBDMAEN); - hspdif->CsXferCount = 0; - - hspdif->State = HAL_SPDIFRX_STATE_READY; -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - hspdif->CxCpltCallback(hspdif); -#else - HAL_SPDIFRX_CxCpltCallback(hspdif); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPDIFRX receive process (Control flow) half complete callback - * @param hdma DMA handle - * @retval None - */ -static void SPDIFRX_DMACxHalfCplt(DMA_HandleTypeDef *hdma) -{ - SPDIFRX_HandleTypeDef* hspdif = (SPDIFRX_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent; - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - hspdif->CxHalfCpltCallback(hspdif); -#else - HAL_SPDIFRX_CxHalfCpltCallback(hspdif); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPDIFRX communication error callback - * @param hdma DMA handle - * @retval None - */ -static void SPDIFRX_DMAError(DMA_HandleTypeDef *hdma) -{ - SPDIFRX_HandleTypeDef* hspdif = ( SPDIFRX_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent; - - /* Disable Rx and Cb DMA Request */ - hspdif->Instance->CR &= (uint16_t)(~(SPDIFRX_CR_RXDMAEN | SPDIFRX_CR_CBDMAEN)); - hspdif->RxXferCount = 0; - - hspdif->State= HAL_SPDIFRX_STATE_READY; - - /* Set the error code and execute error callback*/ - hspdif->ErrorCode |= HAL_SPDIFRX_ERROR_DMA; - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - /* The transfer is not stopped */ - hspdif->ErrorCallback(hspdif); -#else - /* The transfer is not stopped */ - HAL_SPDIFRX_ErrorCallback(hspdif); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -} - -/** - * @brief Receive an amount of data (Data Flow) with Interrupt - * @param hspdif SPDIFRX handle - * @retval None - */ -static void SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Receive data */ - (*hspdif->pRxBuffPtr) = hspdif->Instance->DR; - hspdif->pRxBuffPtr++; - hspdif->RxXferCount--; - - if(hspdif->RxXferCount == 0U) - { - /* Disable RXNE/PE and OVR interrupts */ - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE | SPDIFRX_IT_PERRIE | SPDIFRX_IT_RXNE); - - hspdif->State = HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - hspdif->RxCpltCallback(hspdif); -#else - HAL_SPDIFRX_RxCpltCallback(hspdif); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Receive an amount of data (Control Flow) with Interrupt - * @param hspdif SPDIFRX handle - * @retval None - */ -static void SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef *hspdif) -{ - /* Receive data */ - (*hspdif->pCsBuffPtr) = hspdif->Instance->CSR; - hspdif->pCsBuffPtr++; - hspdif->CsXferCount--; - - if(hspdif->CsXferCount == 0U) - { - /* Disable CSRNE interrupt */ - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); - - hspdif->State = HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - hspdif->CxCpltCallback(hspdif); -#else - HAL_SPDIFRX_CxCpltCallback(hspdif); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - } -} - -/** - * @brief This function handles SPDIFRX Communication Timeout. - * @param hspdif SPDIFRX handle - * @param Flag Flag checked - * @param Status Value of the flag expected - * @param Timeout Duration of the timeout - * @param tickstart Tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SPDIFRX_WaitOnFlagUntilTimeout(SPDIFRX_HandleTypeDef *hspdif, uint32_t Flag, FlagStatus Status, uint32_t Timeout, uint32_t tickstart) -{ - /* Wait until flag is set */ - while(__HAL_SPDIFRX_GET_FLAG(hspdif, Flag) == Status) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if(((HAL_GetTick() - tickstart ) > Timeout) || (Timeout == 0U)) - { - /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_RXNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_CSRNE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_PERRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_OVRIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SBLKIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_SYNCDIE); - __HAL_SPDIFRX_DISABLE_IT(hspdif, SPDIFRX_IT_IFEIE); - - hspdif->State= HAL_SPDIFRX_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspdif); - - return HAL_TIMEOUT; - } - } - } - - return HAL_OK; -} - -/** - * @} - */ -#endif /* STM32F446xx */ - -#endif /* SPDIFRX */ -#endif /* HAL_SPDIFRX_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c deleted file mode 100644 index e15ffcd7ca98c86..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c +++ /dev/null @@ -1,3918 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_spi.c - * @author MCD Application Team - * @brief SPI HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Serial Peripheral Interface (SPI) peripheral: - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The SPI HAL driver can be used as follows: - - (#) Declare a SPI_HandleTypeDef handle structure, for example: - SPI_HandleTypeDef hspi; - - (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API: - (##) Enable the SPIx interface clock - (##) SPI pins configuration - (+++) Enable the clock for the SPI GPIOs - (+++) Configure these SPI pins as alternate function push-pull - (##) NVIC configuration if you need to use interrupt process - (+++) Configure the SPIx interrupt priority - (+++) Enable the NVIC SPI IRQ handle - (##) DMA Configuration if you need to use DMA process - (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive Stream/Channel - (+++) Enable the DMAx clock - (+++) Configure the DMA handle parameters - (+++) Configure the DMA Tx or Rx Stream/Channel - (+++) Associate the initialized hdma_tx(or _rx) handle to the hspi DMA Tx or Rx handle - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx Stream/Channel - - (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS - management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure. - - (#) Initialize the SPI registers by calling the HAL_SPI_Init() API: - (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) - by calling the customized HAL_SPI_MspInit() API. - [..] - Circular mode restriction: - (#) The DMA circular mode cannot be used when the SPI is configured in these modes: - (##) Master 2Lines RxOnly - (##) Master 1Line Rx - (#) The CRC feature is not managed when the DMA circular mode is enabled - (#) When the SPI DMA Pause/Stop features are used, we must use the following APIs - the HAL_SPI_DMAPause()/ HAL_SPI_DMAStop() only under the SPI callbacks - [..] - Master Receive mode restriction: - (#) In Master unidirectional receive-only mode (MSTR =1, BIDIMODE=0, RXONLY=1) or - bidirectional receive mode (MSTR=1, BIDIMODE=1, BIDIOE=0), to ensure that the SPI - does not initiate a new transfer the following procedure has to be respected: - (##) HAL_SPI_DeInit() - (##) HAL_SPI_Init() - [..] - Callback registration: - - (#) The compilation flag USE_HAL_SPI_REGISTER_CALLBACKS when set to 1U - allows the user to configure dynamically the driver callbacks. - Use Functions HAL_SPI_RegisterCallback() to register an interrupt callback. - - Function HAL_SPI_RegisterCallback() allows to register following callbacks: - (++) TxCpltCallback : SPI Tx Completed callback - (++) RxCpltCallback : SPI Rx Completed callback - (++) TxRxCpltCallback : SPI TxRx Completed callback - (++) TxHalfCpltCallback : SPI Tx Half Completed callback - (++) RxHalfCpltCallback : SPI Rx Half Completed callback - (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback - (++) ErrorCallback : SPI Error callback - (++) AbortCpltCallback : SPI Abort callback - (++) MspInitCallback : SPI Msp Init callback - (++) MspDeInitCallback : SPI Msp DeInit callback - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - - (#) Use function HAL_SPI_UnRegisterCallback to reset a callback to the default - weak function. - HAL_SPI_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (++) TxCpltCallback : SPI Tx Completed callback - (++) RxCpltCallback : SPI Rx Completed callback - (++) TxRxCpltCallback : SPI TxRx Completed callback - (++) TxHalfCpltCallback : SPI Tx Half Completed callback - (++) RxHalfCpltCallback : SPI Rx Half Completed callback - (++) TxRxHalfCpltCallback : SPI TxRx Half Completed callback - (++) ErrorCallback : SPI Error callback - (++) AbortCpltCallback : SPI Abort callback - (++) MspInitCallback : SPI Msp Init callback - (++) MspDeInitCallback : SPI Msp DeInit callback - - [..] - By default, after the HAL_SPI_Init() and when the state is HAL_SPI_STATE_RESET - all callbacks are set to the corresponding weak functions: - examples HAL_SPI_MasterTxCpltCallback(), HAL_SPI_MasterRxCpltCallback(). - Exception done for MspInit and MspDeInit functions that are - reset to the legacy weak functions in the HAL_SPI_Init()/ HAL_SPI_DeInit() only when - these callbacks are null (not registered beforehand). - If MspInit or MspDeInit are not null, the HAL_SPI_Init()/ HAL_SPI_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state. - - [..] - Callbacks can be registered/unregistered in HAL_SPI_STATE_READY state only. - Exception done MspInit/MspDeInit functions that can be registered/unregistered - in HAL_SPI_STATE_READY or HAL_SPI_STATE_RESET state, - thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit. - Then, the user first registers the MspInit/MspDeInit user callbacks - using HAL_SPI_RegisterCallback() before calling HAL_SPI_DeInit() - or HAL_SPI_Init() function. - - [..] - When the compilation define USE_HAL_PPP_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - [..] - Using the HAL it is not possible to reach all supported SPI frequency with the different SPI Modes, - the following table resume the max SPI frequency reached with data size 8bits/16bits, - according to frequency of the APBx Peripheral Clock (fPCLK) used by the SPI instance. - - @endverbatim - - Additional table : - - DataSize = SPI_DATASIZE_8BIT: - +----------------------------------------------------------------------------------------------+ - | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line | - | Process | Transfer mode |---------------------|----------------------|----------------------| - | | | Master | Slave | Master | Slave | Master | Slave | - |==============================================================================================| - | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | / | Interrupt | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA | - | R |----------------|----------|----------|-----------|----------|-----------|----------| - | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | - |=========|================|==========|==========|===========|==========|===========|==========| - | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | - | |----------------|----------|----------|-----------|----------|-----------|----------| - | R | Interrupt | Fpclk/8 | Fpclk/8 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 | - |=========|================|==========|==========|===========|==========|===========|==========| - | | Polling | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 | - | |----------------|----------|----------|-----------|----------|-----------|----------| - | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128| - +----------------------------------------------------------------------------------------------+ - - DataSize = SPI_DATASIZE_16BIT: - +----------------------------------------------------------------------------------------------+ - | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line | - | Process | Transfer mode |---------------------|----------------------|----------------------| - | | | Master | Slave | Master | Slave | Master | Slave | - |==============================================================================================| - | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | / | Interrupt | Fpclk/4 | Fpclk/4 | NA | NA | NA | NA | - | R |----------------|----------|----------|-----------|----------|-----------|----------| - | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA | - |=========|================|==========|==========|===========|==========|===========|==========| - | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/32 | Fpclk/2 | - | |----------------|----------|----------|-----------|----------|-----------|----------| - | R | Interrupt | Fpclk/4 | Fpclk/4 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 | - |=========|================|==========|==========|===========|==========|===========|==========| - | | Polling | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/32 | - | |----------------|----------|----------|-----------|----------|-----------|----------| - | T | Interrupt | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/64 | - | X |----------------|----------|----------|-----------|----------|-----------|----------| - | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128| - +----------------------------------------------------------------------------------------------+ - @note The max SPI frequency depend on SPI data size (8bits, 16bits), - SPI mode(2 Lines fullduplex, 2 lines RxOnly, 1 line TX/RX) and Process mode (Polling, IT, DMA). - @note - (#) TX/RX processes are HAL_SPI_TransmitReceive(), HAL_SPI_TransmitReceive_IT() and HAL_SPI_TransmitReceive_DMA() - (#) RX processes are HAL_SPI_Receive(), HAL_SPI_Receive_IT() and HAL_SPI_Receive_DMA() - (#) TX processes are HAL_SPI_Transmit(), HAL_SPI_Transmit_IT() and HAL_SPI_Transmit_DMA() - - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SPI SPI - * @brief SPI HAL module driver - * @{ - */ -#ifdef HAL_SPI_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private defines -----------------------------------------------------------*/ -/** @defgroup SPI_Private_Constants SPI Private Constants - * @{ - */ -#define SPI_DEFAULT_TIMEOUT 100U -#define SPI_BSY_FLAG_WORKAROUND_TIMEOUT 1000U /*!< Timeout 1000 µs */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup SPI_Private_Functions SPI Private Functions - * @{ - */ -static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma); -static void SPI_DMAError(DMA_HandleTypeDef *hdma); -static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma); -static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma); -static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State, - uint32_t Timeout, uint32_t Tickstart); -static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi); -#if (USE_SPI_CRC != 0U) -static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi); -static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi); -static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi); -#endif /* USE_SPI_CRC */ -static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi); -static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi); -static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi); -static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi); -static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi); -static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart); -static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SPI_Exported_Functions SPI Exported Functions - * @{ - */ - -/** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and de-initialization functions ##### - =============================================================================== - [..] This subsection provides a set of functions allowing to initialize and - de-initialize the SPIx peripheral: - - (+) User must implement HAL_SPI_MspInit() function in which he configures - all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ). - - (+) Call the function HAL_SPI_Init() to configure the selected device with - the selected configuration: - (++) Mode - (++) Direction - (++) Data Size - (++) Clock Polarity and Phase - (++) NSS Management - (++) BaudRate Prescaler - (++) FirstBit - (++) TIMode - (++) CRC Calculation - (++) CRC Polynomial if CRC enabled - - (+) Call the function HAL_SPI_DeInit() to restore the default configuration - of the selected SPIx peripheral. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the SPI according to the specified parameters - * in the SPI_InitTypeDef and initialize the associated handle. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi) -{ - /* Check the SPI handle allocation */ - if (hspi == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance)); - assert_param(IS_SPI_MODE(hspi->Init.Mode)); - assert_param(IS_SPI_DIRECTION(hspi->Init.Direction)); - assert_param(IS_SPI_DATASIZE(hspi->Init.DataSize)); - assert_param(IS_SPI_NSS(hspi->Init.NSS)); - assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); - assert_param(IS_SPI_FIRST_BIT(hspi->Init.FirstBit)); - assert_param(IS_SPI_TIMODE(hspi->Init.TIMode)); - if (hspi->Init.TIMode == SPI_TIMODE_DISABLE) - { - assert_param(IS_SPI_CPOL(hspi->Init.CLKPolarity)); - assert_param(IS_SPI_CPHA(hspi->Init.CLKPhase)); - - if (hspi->Init.Mode == SPI_MODE_MASTER) - { - assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); - } - else - { - /* Baudrate prescaler not use in Motoraola Slave mode. force to default value */ - hspi->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; - } - } - else - { - assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler)); - - /* Force polarity and phase to TI protocaol requirements */ - hspi->Init.CLKPolarity = SPI_POLARITY_LOW; - hspi->Init.CLKPhase = SPI_PHASE_1EDGE; - } -#if (USE_SPI_CRC != 0U) - assert_param(IS_SPI_CRC_CALCULATION(hspi->Init.CRCCalculation)); - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - assert_param(IS_SPI_CRC_POLYNOMIAL(hspi->Init.CRCPolynomial)); - } -#else - hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; -#endif /* USE_SPI_CRC */ - - if (hspi->State == HAL_SPI_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hspi->Lock = HAL_UNLOCKED; - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - /* Init the SPI Callback settings */ - hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */ - hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */ - hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ - hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ - hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */ - hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - - if (hspi->MspInitCallback == NULL) - { - hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ - } - - /* Init the low level hardware : GPIO, CLOCK, NVIC... */ - hspi->MspInitCallback(hspi); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC... */ - HAL_SPI_MspInit(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - - hspi->State = HAL_SPI_STATE_BUSY; - - /* Disable the selected SPI peripheral */ - __HAL_SPI_DISABLE(hspi); - - /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/ - /* Configure : SPI Mode, Communication Mode, Data size, Clock polarity and phase, NSS management, - Communication speed, First bit and CRC calculation state */ - WRITE_REG(hspi->Instance->CR1, ((hspi->Init.Mode & (SPI_CR1_MSTR | SPI_CR1_SSI)) | - (hspi->Init.Direction & (SPI_CR1_RXONLY | SPI_CR1_BIDIMODE)) | - (hspi->Init.DataSize & SPI_CR1_DFF) | - (hspi->Init.CLKPolarity & SPI_CR1_CPOL) | - (hspi->Init.CLKPhase & SPI_CR1_CPHA) | - (hspi->Init.NSS & SPI_CR1_SSM) | - (hspi->Init.BaudRatePrescaler & SPI_CR1_BR_Msk) | - (hspi->Init.FirstBit & SPI_CR1_LSBFIRST) | - (hspi->Init.CRCCalculation & SPI_CR1_CRCEN))); - - /* Configure : NSS management, TI Mode */ - WRITE_REG(hspi->Instance->CR2, (((hspi->Init.NSS >> 16U) & SPI_CR2_SSOE) | (hspi->Init.TIMode & SPI_CR2_FRF))); - -#if (USE_SPI_CRC != 0U) - /*---------------------------- SPIx CRCPOLY Configuration ------------------*/ - /* Configure : CRC Polynomial */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - WRITE_REG(hspi->Instance->CRCPR, (hspi->Init.CRCPolynomial & SPI_CRCPR_CRCPOLY_Msk)); - } -#endif /* USE_SPI_CRC */ - -#if defined(SPI_I2SCFGR_I2SMOD) - /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */ - CLEAR_BIT(hspi->Instance->I2SCFGR, SPI_I2SCFGR_I2SMOD); -#endif /* SPI_I2SCFGR_I2SMOD */ - - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->State = HAL_SPI_STATE_READY; - - return HAL_OK; -} - -/** - * @brief De-Initialize the SPI peripheral. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi) -{ - /* Check the SPI handle allocation */ - if (hspi == NULL) - { - return HAL_ERROR; - } - - /* Check SPI Instance parameter */ - assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance)); - - hspi->State = HAL_SPI_STATE_BUSY; - - /* Disable the SPI Peripheral Clock */ - __HAL_SPI_DISABLE(hspi); - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - if (hspi->MspDeInitCallback == NULL) - { - hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ - } - - /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ - hspi->MspDeInitCallback(hspi); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */ - HAL_SPI_MspDeInit(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->State = HAL_SPI_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hspi); - - return HAL_OK; -} - -/** - * @brief Initialize the SPI MSP. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_MspInit should be implemented in the user file - */ -} - -/** - * @brief De-Initialize the SPI MSP. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_MspDeInit should be implemented in the user file - */ -} - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -/** - * @brief Register a User SPI Callback - * To be used instead of the weak predefined callback - * @param hspi Pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI. - * @param CallbackID ID of the callback to be registered - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, - pSPI_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - hspi->ErrorCode |= HAL_SPI_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(hspi); - - if (HAL_SPI_STATE_READY == hspi->State) - { - switch (CallbackID) - { - case HAL_SPI_TX_COMPLETE_CB_ID : - hspi->TxCpltCallback = pCallback; - break; - - case HAL_SPI_RX_COMPLETE_CB_ID : - hspi->RxCpltCallback = pCallback; - break; - - case HAL_SPI_TX_RX_COMPLETE_CB_ID : - hspi->TxRxCpltCallback = pCallback; - break; - - case HAL_SPI_TX_HALF_COMPLETE_CB_ID : - hspi->TxHalfCpltCallback = pCallback; - break; - - case HAL_SPI_RX_HALF_COMPLETE_CB_ID : - hspi->RxHalfCpltCallback = pCallback; - break; - - case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID : - hspi->TxRxHalfCpltCallback = pCallback; - break; - - case HAL_SPI_ERROR_CB_ID : - hspi->ErrorCallback = pCallback; - break; - - case HAL_SPI_ABORT_CB_ID : - hspi->AbortCpltCallback = pCallback; - break; - - case HAL_SPI_MSPINIT_CB_ID : - hspi->MspInitCallback = pCallback; - break; - - case HAL_SPI_MSPDEINIT_CB_ID : - hspi->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SPI_STATE_RESET == hspi->State) - { - switch (CallbackID) - { - case HAL_SPI_MSPINIT_CB_ID : - hspi->MspInitCallback = pCallback; - break; - - case HAL_SPI_MSPDEINIT_CB_ID : - hspi->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hspi); - return status; -} - -/** - * @brief Unregister an SPI Callback - * SPI callback is redirected to the weak predefined callback - * @param hspi Pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI. - * @param CallbackID ID of the callback to be unregistered - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(hspi); - - if (HAL_SPI_STATE_READY == hspi->State) - { - switch (CallbackID) - { - case HAL_SPI_TX_COMPLETE_CB_ID : - hspi->TxCpltCallback = HAL_SPI_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_SPI_RX_COMPLETE_CB_ID : - hspi->RxCpltCallback = HAL_SPI_RxCpltCallback; /* Legacy weak RxCpltCallback */ - break; - - case HAL_SPI_TX_RX_COMPLETE_CB_ID : - hspi->TxRxCpltCallback = HAL_SPI_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ - break; - - case HAL_SPI_TX_HALF_COMPLETE_CB_ID : - hspi->TxHalfCpltCallback = HAL_SPI_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - break; - - case HAL_SPI_RX_HALF_COMPLETE_CB_ID : - hspi->RxHalfCpltCallback = HAL_SPI_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - break; - - case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID : - hspi->TxRxHalfCpltCallback = HAL_SPI_TxRxHalfCpltCallback; /* Legacy weak TxRxHalfCpltCallback */ - break; - - case HAL_SPI_ERROR_CB_ID : - hspi->ErrorCallback = HAL_SPI_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_SPI_ABORT_CB_ID : - hspi->AbortCpltCallback = HAL_SPI_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_SPI_MSPINIT_CB_ID : - hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_SPI_MSPDEINIT_CB_ID : - hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_SPI_STATE_RESET == hspi->State) - { - switch (CallbackID) - { - case HAL_SPI_MSPINIT_CB_ID : - hspi->MspInitCallback = HAL_SPI_MspInit; /* Legacy weak MspInit */ - break; - - case HAL_SPI_MSPDEINIT_CB_ID : - hspi->MspDeInitCallback = HAL_SPI_MspDeInit; /* Legacy weak MspDeInit */ - break; - - default : - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_INVALID_CALLBACK); - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hspi); - return status; -} -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SPI_Exported_Functions_Group2 IO operation functions - * @brief Data transfers functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the SPI - data transfers. - - [..] The SPI supports master and slave mode : - - (#) There are two modes of transfer: - (++) Blocking mode: The communication is performed in polling mode. - The HAL status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode: The communication is performed using Interrupts - or DMA, These APIs return the HAL status. - The end of the data processing will be indicated through the - dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks - will be executed respectively at the end of the transmit or Receive process - The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected - - (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA) - exist for 1Line (simplex) and 2Lines (full duplex) modes. - -@endverbatim - * @{ - */ - -/** - * @brief Transmit an amount of data in blocking mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint32_t tickstart; - HAL_StatusTypeDef errorcode = HAL_OK; - uint16_t initial_TxXferCount; - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); - - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - initial_TxXferCount = Size; - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_TX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - - /*Init field not used in handle to zero */ - hspi->pRxBuffPtr = (uint8_t *)NULL; - hspi->RxXferSize = 0U; - hspi->RxXferCount = 0U; - hspi->TxISR = NULL; - hspi->RxISR = NULL; - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_TX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Transmit data in 16 Bit mode */ - if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) - { - if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) - { - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - } - /* Transmit data in 16 Bit mode */ - while (hspi->TxXferCount > 0U) - { - /* Wait until TXE flag is set to send data */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) - { - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - } - else - { - /* Timeout management */ - if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - } - /* Transmit data in 8 Bit mode */ - else - { - if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) - { - *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint8_t); - hspi->TxXferCount--; - } - while (hspi->TxXferCount > 0U) - { - /* Wait until TXE flag is set to send data */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) - { - *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint8_t); - hspi->TxXferCount--; - } - else - { - /* Timeout management */ - if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - } -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_FLAG; - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - errorcode = HAL_ERROR; - } - -error: - hspi->State = HAL_SPI_STATE_READY; - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Receive an amount of data in blocking mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be received - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ -#if (USE_SPI_CRC != 0U) - __IO uint32_t tmpreg = 0U; -#endif /* USE_SPI_CRC */ - uint32_t tickstart; - HAL_StatusTypeDef errorcode = HAL_OK; - - if ((hspi->Init.Mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES)) - { - hspi->State = HAL_SPI_STATE_BUSY_RX; - /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ - return HAL_SPI_TransmitReceive(hspi, pData, pData, Size, Timeout); - } - - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_RX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pRxBuffPtr = (uint8_t *)pData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /*Init field not used in handle to zero */ - hspi->pTxBuffPtr = (uint8_t *)NULL; - hspi->TxXferSize = 0U; - hspi->TxXferCount = 0U; - hspi->RxISR = NULL; - hspi->TxISR = NULL; - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - /* this is done to handle the CRCNEXT before the latest data */ - hspi->RxXferCount--; - } -#endif /* USE_SPI_CRC */ - - /* Configure communication direction: 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_RX(hspi); - } - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Receive data in 8 Bit mode */ - if (hspi->Init.DataSize == SPI_DATASIZE_8BIT) - { - /* Transfer loop */ - while (hspi->RxXferCount > 0U) - { - /* Check the RXNE flag */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) - { - /* read the received data */ - (* (uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR; - hspi->pRxBuffPtr += sizeof(uint8_t); - hspi->RxXferCount--; - } - else - { - /* Timeout management */ - if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - } - else - { - /* Transfer loop */ - while (hspi->RxXferCount > 0U) - { - /* Check the RXNE flag */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) - { - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; - hspi->pRxBuffPtr += sizeof(uint16_t); - hspi->RxXferCount--; - } - else - { - /* Timeout management */ - if ((((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - } - -#if (USE_SPI_CRC != 0U) - /* Handle the CRC Transmission */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* freeze the CRC before the latest data */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - - /* Read the latest data */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) - { - /* the latest data has not been received */ - errorcode = HAL_TIMEOUT; - goto error; - } - - /* Receive last data in 16 Bit mode */ - if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) - { - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; - } - /* Receive last data in 8 Bit mode */ - else - { - (*(uint8_t *)hspi->pRxBuffPtr) = *(__IO uint8_t *)&hspi->Instance->DR; - } - - /* Wait the CRC data */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - errorcode = HAL_TIMEOUT; - goto error; - } - - /* Read CRC to Flush DR and RXNE flag */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - } -#endif /* USE_SPI_CRC */ - - /* Check the end of the transaction */ - if (SPI_EndRxTransaction(hspi, Timeout, tickstart) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_FLAG; - } - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - } -#endif /* USE_SPI_CRC */ - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - errorcode = HAL_ERROR; - } - -error : - hspi->State = HAL_SPI_STATE_READY; - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit and Receive an amount of data in blocking mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pTxData pointer to transmission data buffer - * @param pRxData pointer to reception data buffer - * @param Size amount of data to be sent and received - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, - uint32_t Timeout) -{ - uint16_t initial_TxXferCount; - uint32_t tmp_mode; - HAL_SPI_StateTypeDef tmp_state; - uint32_t tickstart; -#if (USE_SPI_CRC != 0U) - __IO uint32_t tmpreg = 0U; -#endif /* USE_SPI_CRC */ - - /* Variable used to alternate Rx and Tx during transfer */ - uint32_t txallowed = 1U; - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); - - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* Init temporary variables */ - tmp_state = hspi->State; - tmp_mode = hspi->Init.Mode; - initial_TxXferCount = Size; - - if (!((tmp_state == HAL_SPI_STATE_READY) || \ - ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ - if (hspi->State != HAL_SPI_STATE_BUSY_RX) - { - hspi->State = HAL_SPI_STATE_BUSY_TX_RX; - } - - /* Set the transaction information */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pRxBuffPtr = (uint8_t *)pRxData; - hspi->RxXferCount = Size; - hspi->RxXferSize = Size; - hspi->pTxBuffPtr = (uint8_t *)pTxData; - hspi->TxXferCount = Size; - hspi->TxXferSize = Size; - - /*Init field not used in handle to zero */ - hspi->RxISR = NULL; - hspi->TxISR = NULL; - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Transmit and Receive data in 16 Bit mode */ - if (hspi->Init.DataSize == SPI_DATASIZE_16BIT) - { - if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) - { - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - } - while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U)) - { - /* Check TXE flag */ - if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U)) - { - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - /* Next Data is a reception (Rx). Tx not allowed */ - txallowed = 0U; - -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - } - - /* Check RXNE flag */ - if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U)) - { - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)hspi->Instance->DR; - hspi->pRxBuffPtr += sizeof(uint16_t); - hspi->RxXferCount--; - /* Next Data is a Transmission (Tx). Tx is allowed */ - txallowed = 1U; - } - if (((HAL_GetTick() - tickstart) >= Timeout) && (Timeout != HAL_MAX_DELAY)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - /* Transmit and Receive data in 8 Bit mode */ - else - { - if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (initial_TxXferCount == 0x01U)) - { - *((__IO uint8_t *)&hspi->Instance->DR) = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint8_t); - hspi->TxXferCount--; - } - while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U)) - { - /* Check TXE flag */ - if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)) && (hspi->TxXferCount > 0U) && (txallowed == 1U)) - { - *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr++; - hspi->TxXferCount--; - /* Next Data is a reception (Rx). Tx not allowed */ - txallowed = 0U; - -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - } - - /* Wait until RXNE flag is reset */ - if ((__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)) && (hspi->RxXferCount > 0U)) - { - (*(uint8_t *)hspi->pRxBuffPtr) = hspi->Instance->DR; - hspi->pRxBuffPtr++; - hspi->RxXferCount--; - /* Next Data is a Transmission (Tx). Tx is allowed */ - txallowed = 1U; - } - if ((((HAL_GetTick() - tickstart) >= Timeout) && ((Timeout != HAL_MAX_DELAY))) || (Timeout == 0U)) - { - errorcode = HAL_TIMEOUT; - goto error; - } - } - } - -#if (USE_SPI_CRC != 0U) - /* Read CRC from DR to close CRC calculation process */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Wait until TXE flag */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK) - { - /* Error on the CRC reception */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - errorcode = HAL_TIMEOUT; - goto error; - } - /* Read CRC */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - } - - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - /* Clear CRC Flag */ - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - - errorcode = HAL_ERROR; - } -#endif /* USE_SPI_CRC */ - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK) - { - errorcode = HAL_ERROR; - hspi->ErrorCode = HAL_SPI_ERROR_FLAG; - goto error; - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - -error : - hspi->State = HAL_SPI_STATE_READY; - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit an amount of data in non-blocking mode with Interrupt. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); - - /* Process Locked */ - __HAL_LOCK(hspi); - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_TX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - - /* Init field not used in handle to zero */ - hspi->pRxBuffPtr = (uint8_t *)NULL; - hspi->RxXferSize = 0U; - hspi->RxXferCount = 0U; - hspi->RxISR = NULL; - - /* Set the function for IT treatment */ - if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) - { - hspi->TxISR = SPI_TxISR_16BIT; - } - else - { - hspi->TxISR = SPI_TxISR_8BIT; - } - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_TX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Enable TXE and ERR interrupt */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR)); - - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - -error : - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Receive an amount of data in non-blocking mode with Interrupt. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - - if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) - { - hspi->State = HAL_SPI_STATE_BUSY_RX; - /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ - return HAL_SPI_TransmitReceive_IT(hspi, pData, pData, Size); - } - - /* Process Locked */ - __HAL_LOCK(hspi); - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_RX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pRxBuffPtr = (uint8_t *)pData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /* Init field not used in handle to zero */ - hspi->pTxBuffPtr = (uint8_t *)NULL; - hspi->TxXferSize = 0U; - hspi->TxXferCount = 0U; - hspi->TxISR = NULL; - - /* Set the function for IT treatment */ - if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) - { - hspi->RxISR = SPI_RxISR_16BIT; - } - else - { - hspi->RxISR = SPI_RxISR_8BIT; - } - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_RX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Enable TXE and ERR interrupt */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - /* Note : The SPI must be enabled after unlocking current process - to avoid the risk of SPI interrupt handle execution before current - process unlock */ - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - -error : - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pTxData pointer to transmission data buffer - * @param pRxData pointer to reception data buffer - * @param Size amount of data to be sent and received - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size) -{ - uint32_t tmp_mode; - HAL_SPI_StateTypeDef tmp_state; - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); - - /* Process locked */ - __HAL_LOCK(hspi); - - /* Init temporary variables */ - tmp_state = hspi->State; - tmp_mode = hspi->Init.Mode; - - if (!((tmp_state == HAL_SPI_STATE_READY) || \ - ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ - if (hspi->State != HAL_SPI_STATE_BUSY_RX) - { - hspi->State = HAL_SPI_STATE_BUSY_TX_RX; - } - - /* Set the transaction information */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pTxData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - hspi->pRxBuffPtr = (uint8_t *)pRxData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /* Set the function for IT treatment */ - if (hspi->Init.DataSize > SPI_DATASIZE_8BIT) - { - hspi->RxISR = SPI_2linesRxISR_16BIT; - hspi->TxISR = SPI_2linesTxISR_16BIT; - } - else - { - hspi->RxISR = SPI_2linesRxISR_8BIT; - hspi->TxISR = SPI_2linesTxISR_8BIT; - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Enable TXE, RXNE and ERR interrupt */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR)); - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - -error : - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit an amount of data in non-blocking mode with DMA. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check tx dma handle */ - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction)); - - /* Process Locked */ - __HAL_LOCK(hspi); - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_TX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - - /* Init field not used in handle to zero */ - hspi->pRxBuffPtr = (uint8_t *)NULL; - hspi->TxISR = NULL; - hspi->RxISR = NULL; - hspi->RxXferSize = 0U; - hspi->RxXferCount = 0U; - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_TX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Set the SPI TxDMA Half transfer complete callback */ - hspi->hdmatx->XferHalfCpltCallback = SPI_DMAHalfTransmitCplt; - - /* Set the SPI TxDMA transfer complete callback */ - hspi->hdmatx->XferCpltCallback = SPI_DMATransmitCplt; - - /* Set the DMA error callback */ - hspi->hdmatx->XferErrorCallback = SPI_DMAError; - - /* Set the DMA AbortCpltCallback */ - hspi->hdmatx->XferAbortCallback = NULL; - - /* Enable the Tx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, - hspi->TxXferCount)) - { - /* Update SPI error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - - hspi->State = HAL_SPI_STATE_READY; - goto error; - } - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Enable the SPI Error Interrupt Bit */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); - - /* Enable Tx DMA Request */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); - -error : - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Receive an amount of data in non-blocking mode with DMA. - * @note In case of MASTER mode and SPI_DIRECTION_2LINES direction, hdmatx shall be defined. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pData pointer to data buffer - * @note When the CRC feature is enabled the pData Length must be Size + 1. - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check rx dma handle */ - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx)); - - if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) - { - hspi->State = HAL_SPI_STATE_BUSY_RX; - - /* Check tx dma handle */ - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); - - /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */ - return HAL_SPI_TransmitReceive_DMA(hspi, pData, pData, Size); - } - - /* Process Locked */ - __HAL_LOCK(hspi); - - if (hspi->State != HAL_SPI_STATE_READY) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Set the transaction information */ - hspi->State = HAL_SPI_STATE_BUSY_RX; - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pRxBuffPtr = (uint8_t *)pData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /*Init field not used in handle to zero */ - hspi->RxISR = NULL; - hspi->TxISR = NULL; - hspi->TxXferSize = 0U; - hspi->TxXferCount = 0U; - - /* Configure communication direction : 1Line */ - if (hspi->Init.Direction == SPI_DIRECTION_1LINE) - { - /* Disable SPI Peripheral before set 1Line direction (BIDIOE bit) */ - __HAL_SPI_DISABLE(hspi); - SPI_1LINE_RX(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Set the SPI RxDMA Half transfer complete callback */ - hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt; - - /* Set the SPI Rx DMA transfer complete callback */ - hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt; - - /* Set the DMA error callback */ - hspi->hdmarx->XferErrorCallback = SPI_DMAError; - - /* Set the DMA AbortCpltCallback */ - hspi->hdmarx->XferAbortCallback = NULL; - - /* Enable the Rx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, - hspi->RxXferCount)) - { - /* Update SPI error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - - hspi->State = HAL_SPI_STATE_READY; - goto error; - } - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - - /* Enable the SPI Error Interrupt Bit */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); - - /* Enable Rx DMA Request */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); - -error: - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Transmit and Receive an amount of data in non-blocking mode with DMA. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param pTxData pointer to transmission data buffer - * @param pRxData pointer to reception data buffer - * @note When the CRC feature is enabled the pRxData Length must be Size + 1 - * @param Size amount of data to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size) -{ - uint32_t tmp_mode; - HAL_SPI_StateTypeDef tmp_state; - HAL_StatusTypeDef errorcode = HAL_OK; - - /* Check rx & tx dma handles */ - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx)); - assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx)); - - /* Check Direction parameter */ - assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction)); - - /* Process locked */ - __HAL_LOCK(hspi); - - /* Init temporary variables */ - tmp_state = hspi->State; - tmp_mode = hspi->Init.Mode; - - if (!((tmp_state == HAL_SPI_STATE_READY) || - ((tmp_mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp_state == HAL_SPI_STATE_BUSY_RX)))) - { - errorcode = HAL_BUSY; - goto error; - } - - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U)) - { - errorcode = HAL_ERROR; - goto error; - } - - /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */ - if (hspi->State != HAL_SPI_STATE_BUSY_RX) - { - hspi->State = HAL_SPI_STATE_BUSY_TX_RX; - } - - /* Set the transaction information */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - hspi->pTxBuffPtr = (uint8_t *)pTxData; - hspi->TxXferSize = Size; - hspi->TxXferCount = Size; - hspi->pRxBuffPtr = (uint8_t *)pRxData; - hspi->RxXferSize = Size; - hspi->RxXferCount = Size; - - /* Init field not used in handle to zero */ - hspi->RxISR = NULL; - hspi->TxISR = NULL; - -#if (USE_SPI_CRC != 0U) - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } -#endif /* USE_SPI_CRC */ - - /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */ - if (hspi->State == HAL_SPI_STATE_BUSY_RX) - { - /* Set the SPI Rx DMA Half transfer complete callback */ - hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt; - hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt; - } - else - { - /* Set the SPI Tx/Rx DMA Half transfer complete callback */ - hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfTransmitReceiveCplt; - hspi->hdmarx->XferCpltCallback = SPI_DMATransmitReceiveCplt; - } - - /* Set the DMA error callback */ - hspi->hdmarx->XferErrorCallback = SPI_DMAError; - - /* Set the DMA AbortCpltCallback */ - hspi->hdmarx->XferAbortCallback = NULL; - - /* Enable the Rx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, - hspi->RxXferCount)) - { - /* Update SPI error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - - hspi->State = HAL_SPI_STATE_READY; - goto error; - } - - /* Enable Rx DMA Request */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); - - /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing - is performed in DMA reception complete callback */ - hspi->hdmatx->XferHalfCpltCallback = NULL; - hspi->hdmatx->XferCpltCallback = NULL; - hspi->hdmatx->XferErrorCallback = NULL; - hspi->hdmatx->XferAbortCallback = NULL; - - /* Enable the Tx DMA Stream/Channel */ - if (HAL_OK != HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, - hspi->TxXferCount)) - { - /* Update SPI error code */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - - hspi->State = HAL_SPI_STATE_READY; - goto error; - } - - /* Check if the SPI is already enabled */ - if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE) - { - /* Enable SPI peripheral */ - __HAL_SPI_ENABLE(hspi); - } - /* Enable the SPI Error Interrupt Bit */ - __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR)); - - /* Enable Tx DMA Request */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); - -error : - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - return errorcode; -} - -/** - * @brief Abort ongoing transfer (blocking mode). - * @param hspi SPI handle. - * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx), - * started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable SPI Interrupts (depending of transfer direction) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi) -{ - HAL_StatusTypeDef errorcode; - __IO uint32_t count; - __IO uint32_t resetcount; - - /* Initialized local variable */ - errorcode = HAL_OK; - resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - count = resetcount; - - /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE); - - /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE)) - { - hspi->TxISR = SPI_AbortTx_ISR; - /* Wait HAL_SPI_STATE_ABORT state */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while (hspi->State != HAL_SPI_STATE_ABORT); - /* Reset Timeout Counter */ - count = resetcount; - } - - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE)) - { - hspi->RxISR = SPI_AbortRx_ISR; - /* Wait HAL_SPI_STATE_ABORT state */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while (hspi->State != HAL_SPI_STATE_ABORT); - /* Reset Timeout Counter */ - count = resetcount; - } - - /* Disable the SPI DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) - { - /* Abort the SPI DMA Tx Stream/Channel : use blocking DMA Abort API (no callback) */ - if (hspi->hdmatx != NULL) - { - /* Set the SPI DMA Abort callback : - will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */ - hspi->hdmatx->XferAbortCallback = NULL; - - /* Abort DMA Tx Handle linked to SPI Peripheral */ - if (HAL_DMA_Abort(hspi->hdmatx) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_ABORT; - } - - /* Disable Tx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN)); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - } - } - - /* Disable the SPI DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) - { - /* Abort the SPI DMA Rx Stream/Channel : use blocking DMA Abort API (no callback) */ - if (hspi->hdmarx != NULL) - { - /* Set the SPI DMA Abort callback : - will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */ - hspi->hdmarx->XferAbortCallback = NULL; - - /* Abort DMA Rx Handle linked to SPI Peripheral */ - if (HAL_DMA_Abort(hspi->hdmarx) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_ABORT; - } - - /* Disable peripheral */ - __HAL_SPI_DISABLE(hspi); - - /* Disable Rx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXDMAEN)); - } - } - /* Reset Tx and Rx transfer counters */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Check error during Abort procedure */ - if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT) - { - /* return HAL_Error in case of error during Abort procedure */ - errorcode = HAL_ERROR; - } - else - { - /* Reset errorCode */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - } - - /* Clear the Error flags in the SR register */ - __HAL_SPI_CLEAR_OVRFLAG(hspi); - __HAL_SPI_CLEAR_FREFLAG(hspi); - - /* Restore hspi->state to ready */ - hspi->State = HAL_SPI_STATE_READY; - - return errorcode; -} - -/** - * @brief Abort ongoing transfer (Interrupt mode). - * @param hspi SPI handle. - * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx), - * started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable SPI Interrupts (depending of transfer direction) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi) -{ - HAL_StatusTypeDef errorcode; - uint32_t abortcplt ; - __IO uint32_t count; - __IO uint32_t resetcount; - - /* Initialized local variable */ - errorcode = HAL_OK; - abortcplt = 1U; - resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - count = resetcount; - - /* Clear ERRIE interrupt to avoid error interrupts generation during Abort procedure */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE); - - /* Change Rx and Tx Irq Handler to Disable TXEIE, RXNEIE and ERRIE interrupts */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE)) - { - hspi->TxISR = SPI_AbortTx_ISR; - /* Wait HAL_SPI_STATE_ABORT state */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while (hspi->State != HAL_SPI_STATE_ABORT); - /* Reset Timeout Counter */ - count = resetcount; - } - - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE)) - { - hspi->RxISR = SPI_AbortRx_ISR; - /* Wait HAL_SPI_STATE_ABORT state */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while (hspi->State != HAL_SPI_STATE_ABORT); - /* Reset Timeout Counter */ - count = resetcount; - } - - /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialised - before any call to DMA Abort functions */ - /* DMA Tx Handle is valid */ - if (hspi->hdmatx != NULL) - { - /* Set DMA Abort Complete callback if UART DMA Tx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) - { - hspi->hdmatx->XferAbortCallback = SPI_DMATxAbortCallback; - } - else - { - hspi->hdmatx->XferAbortCallback = NULL; - } - } - /* DMA Rx Handle is valid */ - if (hspi->hdmarx != NULL) - { - /* Set DMA Abort Complete callback if UART DMA Rx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) - { - hspi->hdmarx->XferAbortCallback = SPI_DMARxAbortCallback; - } - else - { - hspi->hdmarx->XferAbortCallback = NULL; - } - } - - /* Disable the SPI DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) - { - /* Abort the SPI DMA Tx Stream/Channel */ - if (hspi->hdmatx != NULL) - { - /* Abort DMA Tx Handle linked to SPI Peripheral */ - if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK) - { - hspi->hdmatx->XferAbortCallback = NULL; - hspi->ErrorCode = HAL_SPI_ERROR_ABORT; - } - else - { - abortcplt = 0U; - } - } - } - /* Disable the SPI DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)) - { - /* Abort the SPI DMA Rx Stream/Channel */ - if (hspi->hdmarx != NULL) - { - /* Abort DMA Rx Handle linked to SPI Peripheral */ - if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK) - { - hspi->hdmarx->XferAbortCallback = NULL; - hspi->ErrorCode = HAL_SPI_ERROR_ABORT; - } - else - { - abortcplt = 0U; - } - } - } - - if (abortcplt == 1U) - { - /* Reset Tx and Rx transfer counters */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Check error during Abort procedure */ - if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT) - { - /* return HAL_Error in case of error during Abort procedure */ - errorcode = HAL_ERROR; - } - else - { - /* Reset errorCode */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - } - - /* Clear the Error flags in the SR register */ - __HAL_SPI_CLEAR_OVRFLAG(hspi); - __HAL_SPI_CLEAR_FREFLAG(hspi); - - /* Restore hspi->State to Ready */ - hspi->State = HAL_SPI_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->AbortCpltCallback(hspi); -#else - HAL_SPI_AbortCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - - return errorcode; -} - -/** - * @brief Pause the DMA Transfer. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi) -{ - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Disable the SPI DMA Tx & Rx requests */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - - return HAL_OK; -} - -/** - * @brief Resume the DMA Transfer. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi) -{ - /* Process Locked */ - __HAL_LOCK(hspi); - - /* Enable the SPI DMA Tx & Rx requests */ - SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - - return HAL_OK; -} - -/** - * @brief Stop the DMA Transfer. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi) -{ - HAL_StatusTypeDef errorcode = HAL_OK; - /* The Lock is not implemented on this API to allow the user application - to call the HAL SPI API under callbacks HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback(): - when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated - and the correspond call back is executed HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback() - */ - - /* Abort the SPI DMA tx Stream/Channel */ - if (hspi->hdmatx != NULL) - { - if (HAL_OK != HAL_DMA_Abort(hspi->hdmatx)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - } - } - /* Abort the SPI DMA rx Stream/Channel */ - if (hspi->hdmarx != NULL) - { - if (HAL_OK != HAL_DMA_Abort(hspi->hdmarx)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - errorcode = HAL_ERROR; - } - } - - /* Disable the SPI DMA Tx & Rx requests */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - hspi->State = HAL_SPI_STATE_READY; - return errorcode; -} - -/** - * @brief Handle SPI interrupt request. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for the specified SPI module. - * @retval None - */ -void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi) -{ - uint32_t itsource = hspi->Instance->CR2; - uint32_t itflag = hspi->Instance->SR; - - /* SPI in mode Receiver ----------------------------------------------------*/ - if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) == RESET) && - (SPI_CHECK_FLAG(itflag, SPI_FLAG_RXNE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_RXNE) != RESET)) - { - hspi->RxISR(hspi); - return; - } - - /* SPI in mode Transmitter -------------------------------------------------*/ - if ((SPI_CHECK_FLAG(itflag, SPI_FLAG_TXE) != RESET) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_TXE) != RESET)) - { - hspi->TxISR(hspi); - return; - } - - /* SPI in Error Treatment --------------------------------------------------*/ - if (((SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) || (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET) - || (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET)) && (SPI_CHECK_IT_SOURCE(itsource, SPI_IT_ERR) != RESET)) - { - /* SPI Overrun error interrupt occurred ----------------------------------*/ - if (SPI_CHECK_FLAG(itflag, SPI_FLAG_OVR) != RESET) - { - if (hspi->State != HAL_SPI_STATE_BUSY_TX) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_OVR); - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - else - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - return; - } - } - - /* SPI Mode Fault error interrupt occurred -------------------------------*/ - if (SPI_CHECK_FLAG(itflag, SPI_FLAG_MODF) != RESET) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_MODF); - __HAL_SPI_CLEAR_MODFFLAG(hspi); - } - - /* SPI Frame error interrupt occurred ------------------------------------*/ - if (SPI_CHECK_FLAG(itflag, SPI_FLAG_FRE) != RESET) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FRE); - __HAL_SPI_CLEAR_FREFLAG(hspi); - } - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Disable all interrupts */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE | SPI_IT_TXE | SPI_IT_ERR); - - hspi->State = HAL_SPI_STATE_READY; - /* Disable the SPI DMA requests if enabled */ - if ((HAL_IS_BIT_SET(itsource, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(itsource, SPI_CR2_RXDMAEN))) - { - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN)); - - /* Abort the SPI DMA Rx channel */ - if (hspi->hdmarx != NULL) - { - /* Set the SPI DMA Abort callback : - will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */ - hspi->hdmarx->XferAbortCallback = SPI_DMAAbortOnError; - if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmarx)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - } - } - /* Abort the SPI DMA Tx channel */ - if (hspi->hdmatx != NULL) - { - /* Set the SPI DMA Abort callback : - will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */ - hspi->hdmatx->XferAbortCallback = SPI_DMAAbortOnError; - if (HAL_OK != HAL_DMA_Abort_IT(hspi->hdmatx)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - } - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - } - return; - } -} - -/** - * @brief Tx Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_TxCpltCallback should be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_RxCpltCallback should be implemented in the user file - */ -} - -/** - * @brief Tx and Rx Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_TxRxCpltCallback should be implemented in the user file - */ -} - -/** - * @brief Tx Half Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_TxHalfCpltCallback should be implemented in the user file - */ -} - -/** - * @brief Rx Half Transfer completed callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file - */ -} - -/** - * @brief Tx and Rx Half Transfer callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file - */ -} - -/** - * @brief SPI error callback. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -__weak void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_ErrorCallback should be implemented in the user file - */ - /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes - and user can use HAL_SPI_GetError() API to check the latest error occurred - */ -} - -/** - * @brief SPI Abort Complete callback. - * @param hspi SPI handle. - * @retval None - */ -__weak void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hspi); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_SPI_AbortCpltCallback can be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief SPI control functions - * -@verbatim - =============================================================================== - ##### Peripheral State and Errors functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the SPI. - (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral - (+) HAL_SPI_GetError() check in run-time Errors occurring during communication -@endverbatim - * @{ - */ - -/** - * @brief Return the SPI handle state. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval SPI state - */ -HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi) -{ - /* Return SPI handle state */ - return hspi->State; -} - -/** - * @brief Return the SPI error code. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval SPI error code in bitmap format - */ -uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi) -{ - /* Return SPI ErrorCode */ - return hspi->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup SPI_Private_Functions - * @brief Private functions - * @{ - */ - -/** - * @brief DMA SPI transmit process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - uint32_t tickstart; - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* DMA Normal Mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) - { - /* Disable ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); - - /* Disable Tx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Clear overrun flag in 2 Lines communication mode because received data is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - - hspi->TxXferCount = 0U; - hspi->State = HAL_SPI_STATE_READY; - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - return; - } - } - /* Call user Tx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxCpltCallback(hspi); -#else - HAL_SPI_TxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI receive process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - uint32_t tickstart; -#if (USE_SPI_CRC != 0U) - __IO uint32_t tmpreg = 0U; -#endif /* USE_SPI_CRC */ - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* DMA Normal Mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) - { - /* Disable ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); - -#if (USE_SPI_CRC != 0U) - /* CRC handling */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Wait until RXNE flag */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - /* Error on the CRC reception */ - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - } - /* Read CRC */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - } -#endif /* USE_SPI_CRC */ - - /* Check if we are in Master RX 2 line mode */ - if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER)) - { - /* Disable Rx/Tx DMA Request (done by default to handle the case master rx direction 2 lines) */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - } - else - { - /* Normal case */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); - } - - /* Check the end of the transaction */ - if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - hspi->ErrorCode = HAL_SPI_ERROR_FLAG; - } - - hspi->RxXferCount = 0U; - hspi->State = HAL_SPI_STATE_READY; - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - } -#endif /* USE_SPI_CRC */ - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - return; - } - } - /* Call user Rx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->RxCpltCallback(hspi); -#else - HAL_SPI_RxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI transmit receive process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - uint32_t tickstart; -#if (USE_SPI_CRC != 0U) - __IO uint32_t tmpreg = 0U; -#endif /* USE_SPI_CRC */ - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* DMA Normal Mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC) - { - /* Disable ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); - -#if (USE_SPI_CRC != 0U) - /* CRC handling */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Wait the CRC data */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - } - /* Read CRC to Flush DR and RXNE flag */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - } -#endif /* USE_SPI_CRC */ - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Disable Rx/Tx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - - hspi->TxXferCount = 0U; - hspi->RxXferCount = 0U; - hspi->State = HAL_SPI_STATE_READY; - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR)) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - } -#endif /* USE_SPI_CRC */ - - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - return; - } - } - /* Call user TxRx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxRxCpltCallback(hspi); -#else - HAL_SPI_TxRxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI half transmit process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Call user Tx half complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxHalfCpltCallback(hspi); -#else - HAL_SPI_TxHalfCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI half receive process complete callback - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Call user Rx half complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->RxHalfCpltCallback(hspi); -#else - HAL_SPI_RxHalfCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI half transmit receive process complete callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Call user TxRx half complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxRxHalfCpltCallback(hspi); -#else - HAL_SPI_TxRxHalfCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI communication error callback. - * @param hdma pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void SPI_DMAError(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Stop the disable DMA transfer on SPI side */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN); - - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA); - hspi->State = HAL_SPI_STATE_READY; - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI communication abort callback, when initiated by HAL services on Error - * (To be called at end of DMA Abort procedure following error occurrence). - * @param hdma DMA handle. - * @retval None - */ -static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI Tx communication abort callback, when initiated by user - * (To be called at end of DMA Tx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Rx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - __IO uint32_t count; - - hspi->hdmatx->XferAbortCallback = NULL; - count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - - /* Disable Tx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - - /* Check if an Abort process is still ongoing */ - if (hspi->hdmarx != NULL) - { - if (hspi->hdmarx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Check no error during Abort procedure */ - if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT) - { - /* Reset errorCode */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - } - - /* Clear the Error flags in the SR register */ - __HAL_SPI_CLEAR_OVRFLAG(hspi); - __HAL_SPI_CLEAR_FREFLAG(hspi); - - /* Restore hspi->State to Ready */ - hspi->State = HAL_SPI_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->AbortCpltCallback(hspi); -#else - HAL_SPI_AbortCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA SPI Rx communication abort callback, when initiated by user - * (To be called at end of DMA Rx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Tx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma) -{ - SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)(((DMA_HandleTypeDef *)hdma)->Parent); /* Derogation MISRAC2012-Rule-11.5 */ - - /* Disable SPI Peripheral */ - __HAL_SPI_DISABLE(hspi); - - hspi->hdmarx->XferAbortCallback = NULL; - - /* Disable Rx DMA Request */ - CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN); - - /* Check Busy flag */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - } - - /* Check if an Abort process is still ongoing */ - if (hspi->hdmatx != NULL) - { - if (hspi->hdmatx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */ - hspi->RxXferCount = 0U; - hspi->TxXferCount = 0U; - - /* Check no error during Abort procedure */ - if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT) - { - /* Reset errorCode */ - hspi->ErrorCode = HAL_SPI_ERROR_NONE; - } - - /* Clear the Error flags in the SR register */ - __HAL_SPI_CLEAR_OVRFLAG(hspi); - __HAL_SPI_CLEAR_FREFLAG(hspi); - - /* Restore hspi->State to Ready */ - hspi->State = HAL_SPI_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->AbortCpltCallback(hspi); -#else - HAL_SPI_AbortCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} - -/** - * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi) -{ - /* Receive data in 8bit mode */ - *hspi->pRxBuffPtr = *((__IO uint8_t *)&hspi->Instance->DR); - hspi->pRxBuffPtr++; - hspi->RxXferCount--; - - /* Check end of the reception */ - if (hspi->RxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - hspi->RxISR = SPI_2linesRxISR_8BITCRC; - return; - } -#endif /* USE_SPI_CRC */ - - /* Disable RXNE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - if (hspi->TxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } - } -} - -#if (USE_SPI_CRC != 0U) -/** - * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi) -{ - __IO uint8_t * ptmpreg8; - __IO uint8_t tmpreg8 = 0; - - /* Initialize the 8bit temporary pointer */ - ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR; - /* Read 8bit CRC to flush Data Register */ - tmpreg8 = *ptmpreg8; - /* To avoid GCC warning */ - UNUSED(tmpreg8); - - /* Disable RXNE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - if (hspi->TxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } -} -#endif /* USE_SPI_CRC */ - -/** - * @brief Tx 8-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi) -{ - *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr++; - hspi->TxXferCount--; - - /* Check the end of the transmission */ - if (hspi->TxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Set CRC Next Bit to send CRC */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - /* Disable TXE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); - return; - } -#endif /* USE_SPI_CRC */ - - /* Disable TXE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); - - if (hspi->RxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } - } -} - -/** - * @brief Rx 16-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi) -{ - /* Receive data in 16 Bit mode */ - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR); - hspi->pRxBuffPtr += sizeof(uint16_t); - hspi->RxXferCount--; - - if (hspi->RxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - hspi->RxISR = SPI_2linesRxISR_16BITCRC; - return; - } -#endif /* USE_SPI_CRC */ - - /* Disable RXNE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE); - - if (hspi->TxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } - } -} - -#if (USE_SPI_CRC != 0U) -/** - * @brief Manage the CRC 16-bit receive for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi) -{ - __IO uint32_t tmpreg = 0U; - - /* Read 16bit CRC to flush Data Register */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - - /* Disable RXNE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE); - - SPI_CloseRxTx_ISR(hspi); -} -#endif /* USE_SPI_CRC */ - -/** - * @brief Tx 16-bit handler for Transmit and Receive in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi) -{ - /* Transmit data in 16 Bit mode */ - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - - /* Enable CRC Transmission */ - if (hspi->TxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Set CRC Next Bit to send CRC */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - /* Disable TXE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); - return; - } -#endif /* USE_SPI_CRC */ - - /* Disable TXE interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE); - - if (hspi->RxXferCount == 0U) - { - SPI_CloseRxTx_ISR(hspi); - } - } -} - -#if (USE_SPI_CRC != 0U) -/** - * @brief Manage the CRC 8-bit receive in Interrupt context. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi) -{ - __IO uint8_t * ptmpreg8; - __IO uint8_t tmpreg8 = 0; - - /* Initialize the 8bit temporary pointer */ - ptmpreg8 = (__IO uint8_t *)&hspi->Instance->DR; - /* Read 8bit CRC to flush Data Register */ - tmpreg8 = *ptmpreg8; - /* To avoid GCC warning */ - UNUSED(tmpreg8); - - SPI_CloseRx_ISR(hspi); -} -#endif /* USE_SPI_CRC */ - -/** - * @brief Manage the receive 8-bit in Interrupt context. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi) -{ - *hspi->pRxBuffPtr = (*(__IO uint8_t *)&hspi->Instance->DR); - hspi->pRxBuffPtr++; - hspi->RxXferCount--; - -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - - if (hspi->RxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - hspi->RxISR = SPI_RxISR_8BITCRC; - return; - } -#endif /* USE_SPI_CRC */ - SPI_CloseRx_ISR(hspi); - } -} - -#if (USE_SPI_CRC != 0U) -/** - * @brief Manage the CRC 16-bit receive in Interrupt context. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi) -{ - __IO uint32_t tmpreg = 0U; - - /* Read 16bit CRC to flush Data Register */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - - /* Disable RXNE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - SPI_CloseRx_ISR(hspi); -} -#endif /* USE_SPI_CRC */ - -/** - * @brief Manage the 16-bit receive in Interrupt context. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi) -{ - *((uint16_t *)hspi->pRxBuffPtr) = (uint16_t)(hspi->Instance->DR); - hspi->pRxBuffPtr += sizeof(uint16_t); - hspi->RxXferCount--; - -#if (USE_SPI_CRC != 0U) - /* Enable CRC Transmission */ - if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)) - { - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - - if (hspi->RxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - hspi->RxISR = SPI_RxISR_16BITCRC; - return; - } -#endif /* USE_SPI_CRC */ - SPI_CloseRx_ISR(hspi); - } -} - -/** - * @brief Handle the data 8-bit transmit in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi) -{ - *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr); - hspi->pTxBuffPtr++; - hspi->TxXferCount--; - - if (hspi->TxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Enable CRC Transmission */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - SPI_CloseTx_ISR(hspi); - } -} - -/** - * @brief Handle the data 16-bit transmit in Interrupt mode. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi) -{ - /* Transmit data in 16 Bit mode */ - hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr); - hspi->pTxBuffPtr += sizeof(uint16_t); - hspi->TxXferCount--; - - if (hspi->TxXferCount == 0U) - { -#if (USE_SPI_CRC != 0U) - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - /* Enable CRC Transmission */ - SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT); - } -#endif /* USE_SPI_CRC */ - SPI_CloseTx_ISR(hspi); - } -} - -/** - * @brief Handle SPI Communication Timeout. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param Flag SPI flag to check - * @param State flag state to check - * @param Timeout Timeout duration - * @param Tickstart tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, FlagStatus State, - uint32_t Timeout, uint32_t Tickstart) -{ - __IO uint32_t count; - uint32_t tmp_timeout; - uint32_t tmp_tickstart; - - /* Adjust Timeout value in case of end of transfer */ - tmp_timeout = Timeout - (HAL_GetTick() - Tickstart); - tmp_tickstart = HAL_GetTick(); - - /* Calculate Timeout based on a software loop to avoid blocking issue if Systick is disabled */ - count = tmp_timeout * ((SystemCoreClock * 32U) >> 20U); - - while ((__HAL_SPI_GET_FLAG(hspi, Flag) ? SET : RESET) != State) - { - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tmp_tickstart) >= tmp_timeout) || (tmp_timeout == 0U)) - { - /* Disable the SPI and reset the CRC: the CRC value should be cleared - on both master and slave sides in order to resynchronize the master - and slave for their respective CRC calculation */ - - /* Disable TXE, RXNE and ERR interrupts for the interrupt process */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR)); - - if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE) - || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY))) - { - /* Disable SPI peripheral */ - __HAL_SPI_DISABLE(hspi); - } - - /* Reset CRC Calculation */ - if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE) - { - SPI_RESET_CRC(hspi); - } - - hspi->State = HAL_SPI_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(hspi); - - return HAL_TIMEOUT; - } - /* If Systick is disabled or not incremented, deactivate timeout to go in disable loop procedure */ - if(count == 0U) - { - tmp_timeout = 0U; - } - count--; - } - } - - return HAL_OK; -} - -/** - * @brief Handle the check of the RX transaction complete. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @param Timeout Timeout duration - * @param Tickstart tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart) -{ - if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE) - || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY))) - { - /* Disable SPI peripheral */ - __HAL_SPI_DISABLE(hspi); - } - - /* Erratasheet: BSY bit may stay high at the end of a data transfer in Slave mode */ - if (hspi->Init.Mode == SPI_MODE_MASTER) - { - if (hspi->Init.Direction != SPI_DIRECTION_2LINES_RXONLY) - { - /* Control the BSY flag */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - return HAL_TIMEOUT; - } - } - else - { - /* Wait the RXNE reset */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, RESET, Timeout, Tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - return HAL_TIMEOUT; - } - } - } - else - { - /* Wait the RXNE reset */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, RESET, Timeout, Tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - return HAL_TIMEOUT; - } - } - return HAL_OK; -} - -/** - * @brief Handle the check of the RXTX or TX transaction complete. - * @param hspi SPI handle - * @param Timeout Timeout duration - * @param Tickstart tick start value - * @retval HAL status - */ -static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart) -{ - /* Timeout in µs */ - __IO uint32_t count = SPI_BSY_FLAG_WORKAROUND_TIMEOUT * (SystemCoreClock / 24U / 1000000U); - /* Erratasheet: BSY bit may stay high at the end of a data transfer in Slave mode */ - if (hspi->Init.Mode == SPI_MODE_MASTER) - { - /* Control the BSY flag */ - if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - return HAL_TIMEOUT; - } - } - else - { - /* Wait BSY flag during 1 Byte time transfer in case of Full-Duplex and Tx transfer - * If Timeout is reached, the transfer is considered as finish. - * User have to calculate the timeout value to fit with the time of 1 byte transfer. - * This time is directly link with the SPI clock from Master device. - */ - do - { - if (count == 0U) - { - break; - } - count--; - } while (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_BSY) != RESET); - } - - return HAL_OK; -} - -/** - * @brief Handle the end of the RXTX transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi) -{ - uint32_t tickstart; - __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - /* Disable ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET) - { - hspi->State = HAL_SPI_STATE_READY; - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { -#endif /* USE_SPI_CRC */ - if (hspi->ErrorCode == HAL_SPI_ERROR_NONE) - { - if (hspi->State == HAL_SPI_STATE_BUSY_RX) - { - hspi->State = HAL_SPI_STATE_READY; - /* Call user Rx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->RxCpltCallback(hspi); -#else - HAL_SPI_RxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { - hspi->State = HAL_SPI_STATE_READY; - /* Call user TxRx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxRxCpltCallback(hspi); -#else - HAL_SPI_TxRxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - } - else - { - hspi->State = HAL_SPI_STATE_READY; - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } -#if (USE_SPI_CRC != 0U) - } -#endif /* USE_SPI_CRC */ -} - -/** - * @brief Handle the end of the RX transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi) -{ - /* Disable RXNE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR)); - - /* Check the end of the transaction */ - if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - hspi->State = HAL_SPI_STATE_READY; - -#if (USE_SPI_CRC != 0U) - /* Check if CRC error occurred */ - if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC); - __HAL_SPI_CLEAR_CRCERRFLAG(hspi); - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { -#endif /* USE_SPI_CRC */ - if (hspi->ErrorCode == HAL_SPI_ERROR_NONE) - { - /* Call user Rx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->RxCpltCallback(hspi); -#else - HAL_SPI_RxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } -#if (USE_SPI_CRC != 0U) - } -#endif /* USE_SPI_CRC */ -} - -/** - * @brief Handle the end of the TX transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi) -{ - uint32_t tickstart; - __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - - /* Init tickstart for timeout management*/ - tickstart = HAL_GetTick(); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - - /* Disable TXE and ERR interrupt */ - __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR)); - - /* Check the end of the transaction */ - if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG); - } - - /* Clear overrun flag in 2 Lines communication mode because received is not read */ - if (hspi->Init.Direction == SPI_DIRECTION_2LINES) - { - __HAL_SPI_CLEAR_OVRFLAG(hspi); - } - - hspi->State = HAL_SPI_STATE_READY; - if (hspi->ErrorCode != HAL_SPI_ERROR_NONE) - { - /* Call user error callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->ErrorCallback(hspi); -#else - HAL_SPI_ErrorCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } - else - { - /* Call user Rx complete callback */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - hspi->TxCpltCallback(hspi); -#else - HAL_SPI_TxCpltCallback(hspi); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - } -} - -/** - * @brief Handle abort a Rx transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi) -{ - __IO uint32_t tmpreg = 0U; - __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U); - - /* Wait until TXE flag is set */ - do - { - if (count == 0U) - { - SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT); - break; - } - count--; - } while ((hspi->Instance->SR & SPI_FLAG_TXE) == RESET); - - /* Disable SPI Peripheral */ - __HAL_SPI_DISABLE(hspi); - - /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */ - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE)); - - /* Flush Data Register by a blank read */ - tmpreg = READ_REG(hspi->Instance->DR); - /* To avoid GCC warning */ - UNUSED(tmpreg); - - hspi->State = HAL_SPI_STATE_ABORT; -} - -/** - * @brief Handle abort a Tx or Rx/Tx transaction. - * @param hspi pointer to a SPI_HandleTypeDef structure that contains - * the configuration information for SPI module. - * @retval None - */ -static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi) -{ - /* Disable TXEIE interrupt */ - CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE)); - - /* Disable SPI Peripheral */ - __HAL_SPI_DISABLE(hspi); - - hspi->State = HAL_SPI_STATE_ABORT; -} - -/** - * @} - */ - -#endif /* HAL_SPI_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sram.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sram.c deleted file mode 100644 index 752056982b7efe9..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_sram.c +++ /dev/null @@ -1,912 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sram.c - * @author MCD Application Team - * @brief SRAM HAL module driver. - * This file provides a generic firmware to drive SRAM memories - * mounted as external device. - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - This driver is a generic layered driver which contains a set of APIs used to - control SRAM memories. It uses the FMC layer functions to interface - with SRAM devices. - The following sequence should be followed to configure the FMC/FSMC to interface - with SRAM/PSRAM memories: - - (#) Declare a SRAM_HandleTypeDef handle structure, for example: - SRAM_HandleTypeDef hsram; and: - - (++) Fill the SRAM_HandleTypeDef handle "Init" field with the allowed - values of the structure member. - - (++) Fill the SRAM_HandleTypeDef handle "Instance" field with a predefined - base register instance for NOR or SRAM device - - (++) Fill the SRAM_HandleTypeDef handle "Extended" field with a predefined - base register instance for NOR or SRAM extended mode - - (#) Declare two FMC_NORSRAM_TimingTypeDef structures, for both normal and extended - mode timings; for example: - FMC_NORSRAM_TimingTypeDef Timing and FMC_NORSRAM_TimingTypeDef ExTiming; - and fill its fields with the allowed values of the structure member. - - (#) Initialize the SRAM Controller by calling the function HAL_SRAM_Init(). This function - performs the following sequence: - - (##) MSP hardware layer configuration using the function HAL_SRAM_MspInit() - (##) Control register configuration using the FMC NORSRAM interface function - FMC_NORSRAM_Init() - (##) Timing register configuration using the FMC NORSRAM interface function - FMC_NORSRAM_Timing_Init() - (##) Extended mode Timing register configuration using the FMC NORSRAM interface function - FMC_NORSRAM_Extended_Timing_Init() - (##) Enable the SRAM device using the macro __FMC_NORSRAM_ENABLE() - - (#) At this stage you can perform read/write accesses from/to the memory connected - to the NOR/SRAM Bank. You can perform either polling or DMA transfer using the - following APIs: - (++) HAL_SRAM_Read()/HAL_SRAM_Write() for polling read/write access - (++) HAL_SRAM_Read_DMA()/HAL_SRAM_Write_DMA() for DMA read/write transfer - - (#) You can also control the SRAM device by calling the control APIs HAL_SRAM_WriteOperation_Enable()/ - HAL_SRAM_WriteOperation_Disable() to respectively enable/disable the SRAM write operation - - (#) You can continuously monitor the SRAM device HAL state by calling the function - HAL_SRAM_GetState() - - *** Callback registration *** - ============================================= - [..] - The compilation define USE_HAL_SRAM_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - Use Functions @ref HAL_SRAM_RegisterCallback() to register a user callback, - it allows to register following callbacks: - (+) MspInitCallback : SRAM MspInit. - (+) MspDeInitCallback : SRAM MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - Use function @ref HAL_SRAM_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. It allows to reset following callbacks: - (+) MspInitCallback : SRAM MspInit. - (+) MspDeInitCallback : SRAM MspDeInit. - This function) takes as parameters the HAL peripheral handle and the Callback ID. - - By default, after the @ref HAL_SRAM_Init and if the state is HAL_SRAM_STATE_RESET - all callbacks are reset to the corresponding legacy weak (surcharged) functions. - Exception done for MspInit and MspDeInit callbacks that are respectively - reset to the legacy weak (surcharged) functions in the @ref HAL_SRAM_Init - and @ref HAL_SRAM_DeInit only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the @ref HAL_SRAM_Init and @ref HAL_SRAM_DeInit - keep and use the user MspInit/MspDeInit callbacks (registered beforehand) - - Callbacks can be registered/unregistered in READY state only. - Exception done for MspInit/MspDeInit callbacks that can be registered/unregistered - in READY or RESET state, thus registered (user) MspInit/DeInit callbacks can be used - during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_SRAM_RegisterCallback before calling @ref HAL_SRAM_DeInit - or @ref HAL_SRAM_Init function. - - When The compilation define USE_HAL_SRAM_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SRAM SRAM - * @brief SRAM driver modules - * @{ - */ -#ifdef HAL_SRAM_MODULE_ENABLED - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SRAM_Exported_Functions SRAM Exported Functions - * @{ - */ -/** @defgroup SRAM_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * - @verbatim - ============================================================================== - ##### SRAM Initialization and de_initialization functions ##### - ============================================================================== - [..] This section provides functions allowing to initialize/de-initialize - the SRAM memory - -@endverbatim - * @{ - */ - -/** - * @brief Performs the SRAM device initialization sequence - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param Timing Pointer to SRAM control timing structure - * @param ExtTiming Pointer to SRAM extended mode timing structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Init(SRAM_HandleTypeDef *hsram, FMC_NORSRAM_TimingTypeDef *Timing, FMC_NORSRAM_TimingTypeDef *ExtTiming) -{ - /* Check the SRAM handle parameter */ - if(hsram == NULL) - { - return HAL_ERROR; - } - - if(hsram->State == HAL_SRAM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - hsram->Lock = HAL_UNLOCKED; - -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) - if(hsram->MspInitCallback == NULL) - { - hsram->MspInitCallback = HAL_SRAM_MspInit; - } - hsram->DmaXferCpltCallback = HAL_SRAM_DMA_XferCpltCallback; - hsram->DmaXferErrorCallback = HAL_SRAM_DMA_XferErrorCallback; - - /* Init the low level hardware */ - hsram->MspInitCallback(hsram); -#else - /* Initialize the low level hardware (MSP) */ - HAL_SRAM_MspInit(hsram); -#endif - } - - /* Initialize SRAM control Interface */ - FMC_NORSRAM_Init(hsram->Instance, &(hsram->Init)); - - /* Initialize SRAM timing Interface */ - FMC_NORSRAM_Timing_Init(hsram->Instance, Timing, hsram->Init.NSBank); - - /* Initialize SRAM extended mode timing Interface */ - FMC_NORSRAM_Extended_Timing_Init(hsram->Extended, ExtTiming, hsram->Init.NSBank, hsram->Init.ExtendedMode); - - /* Enable the NORSRAM device */ - __FMC_NORSRAM_ENABLE(hsram->Instance, hsram->Init.NSBank); - - return HAL_OK; -} - -/** - * @brief Performs the SRAM device De-initialization sequence. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_DeInit(SRAM_HandleTypeDef *hsram) -{ -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) - if(hsram->MspDeInitCallback == NULL) - { - hsram->MspDeInitCallback = HAL_SRAM_MspDeInit; - } - - /* DeInit the low level hardware */ - hsram->MspDeInitCallback(hsram); -#else - /* De-Initialize the low level hardware (MSP) */ - HAL_SRAM_MspDeInit(hsram); -#endif - - /* Configure the SRAM registers with their reset values */ - FMC_NORSRAM_DeInit(hsram->Instance, hsram->Extended, hsram->Init.NSBank); - - hsram->State = HAL_SRAM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief SRAM MSP Init. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @retval None - */ -__weak void HAL_SRAM_MspInit(SRAM_HandleTypeDef *hsram) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsram); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SRAM_MspInit could be implemented in the user file - */ -} - -/** - * @brief SRAM MSP DeInit. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @retval None - */ -__weak void HAL_SRAM_MspDeInit(SRAM_HandleTypeDef *hsram) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hsram); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SRAM_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief DMA transfer complete callback. - * @param hdma pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @retval None - */ -__weak void HAL_SRAM_DMA_XferCpltCallback(DMA_HandleTypeDef *hdma) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdma); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SRAM_DMA_XferCpltCallback could be implemented in the user file - */ -} - -/** - * @brief DMA transfer complete error callback. - * @param hdma pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @retval None - */ -__weak void HAL_SRAM_DMA_XferErrorCallback(DMA_HandleTypeDef *hdma) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hdma); - /* NOTE : This function Should not be modified, when the callback is needed, - the HAL_SRAM_DMA_XferErrorCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** @defgroup SRAM_Exported_Functions_Group2 Input and Output functions - * @brief Input Output and memory control functions - * - @verbatim - ============================================================================== - ##### SRAM Input and Output functions ##### - ============================================================================== - [..] - This section provides functions allowing to use and control the SRAM memory - -@endverbatim - * @{ - */ - -/** - * @brief Reads 8-bit buffer from SRAM memory. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param pAddress Pointer to read start address - * @param pDstBuffer Pointer to destination buffer - * @param BufferSize Size of the buffer to read from memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Read_8b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint8_t *pDstBuffer, uint32_t BufferSize) -{ - __IO uint8_t * pSramAddress = (uint8_t *)pAddress; - - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Read data from memory */ - for(; BufferSize != 0U; BufferSize--) - { - *pDstBuffer = *(__IO uint8_t *)pSramAddress; - pDstBuffer++; - pSramAddress++; - } - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief Writes 8-bit buffer to SRAM memory. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param pAddress Pointer to write start address - * @param pSrcBuffer Pointer to source buffer to write - * @param BufferSize Size of the buffer to write to memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Write_8b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint8_t *pSrcBuffer, uint32_t BufferSize) -{ - __IO uint8_t * pSramAddress = (uint8_t *)pAddress; - - /* Check the SRAM controller state */ - if(hsram->State == HAL_SRAM_STATE_PROTECTED) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Write data to memory */ - for(; BufferSize != 0U; BufferSize--) - { - *(__IO uint8_t *)pSramAddress = *pSrcBuffer; - pSrcBuffer++; - pSramAddress++; - } - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief Reads 16-bit buffer from SRAM memory. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param pAddress Pointer to read start address - * @param pDstBuffer Pointer to destination buffer - * @param BufferSize Size of the buffer to read from memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Read_16b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint16_t *pDstBuffer, uint32_t BufferSize) -{ - __IO uint16_t * pSramAddress = (uint16_t *)pAddress; - - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Read data from memory */ - for(; BufferSize != 0U; BufferSize--) - { - *pDstBuffer = *(__IO uint16_t *)pSramAddress; - pDstBuffer++; - pSramAddress++; - } - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief Writes 16-bit buffer to SRAM memory. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param pAddress Pointer to write start address - * @param pSrcBuffer Pointer to source buffer to write - * @param BufferSize Size of the buffer to write to memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Write_16b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint16_t *pSrcBuffer, uint32_t BufferSize) -{ - __IO uint16_t * pSramAddress = (uint16_t *)pAddress; - - /* Check the SRAM controller state */ - if(hsram->State == HAL_SRAM_STATE_PROTECTED) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Write data to memory */ - for(; BufferSize != 0U; BufferSize--) - { - *(__IO uint16_t *)pSramAddress = *pSrcBuffer; - pSrcBuffer++; - pSramAddress++; - } - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief Reads 32-bit buffer from SRAM memory. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param pAddress Pointer to read start address - * @param pDstBuffer Pointer to destination buffer - * @param BufferSize Size of the buffer to read from memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Read_32b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize) -{ - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Read data from memory */ - for(; BufferSize != 0U; BufferSize--) - { - *pDstBuffer = *(__IO uint32_t *)pAddress; - pDstBuffer++; - pAddress++; - } - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief Writes 32-bit buffer to SRAM memory. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param pAddress Pointer to write start address - * @param pSrcBuffer Pointer to source buffer to write - * @param BufferSize Size of the buffer to write to memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Write_32b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize) -{ - /* Check the SRAM controller state */ - if(hsram->State == HAL_SRAM_STATE_PROTECTED) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Write data to memory */ - for(; BufferSize != 0U; BufferSize--) - { - *(__IO uint32_t *)pAddress = *pSrcBuffer; - pSrcBuffer++; - pAddress++; - } - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief Reads a Words data from the SRAM memory using DMA transfer. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param pAddress Pointer to read start address - * @param pDstBuffer Pointer to destination buffer - * @param BufferSize Size of the buffer to read from memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Read_DMA(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize) -{ - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Configure DMA user callbacks */ - hsram->hdma->XferCpltCallback = HAL_SRAM_DMA_XferCpltCallback; - hsram->hdma->XferErrorCallback = HAL_SRAM_DMA_XferErrorCallback; - - /* Enable the DMA Stream */ - HAL_DMA_Start_IT(hsram->hdma, (uint32_t)pAddress, (uint32_t)pDstBuffer, (uint32_t)BufferSize); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief Writes a Words data buffer to SRAM memory using DMA transfer. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @param pAddress Pointer to write start address - * @param pSrcBuffer Pointer to source buffer to write - * @param BufferSize Size of the buffer to write to memory - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_Write_DMA(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize) -{ - /* Check the SRAM controller state */ - if(hsram->State == HAL_SRAM_STATE_PROTECTED) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Configure DMA user callbacks */ - hsram->hdma->XferCpltCallback = HAL_SRAM_DMA_XferCpltCallback; - hsram->hdma->XferErrorCallback = HAL_SRAM_DMA_XferErrorCallback; - - /* Enable the DMA Stream */ - HAL_DMA_Start_IT(hsram->hdma, (uint32_t)pSrcBuffer, (uint32_t)pAddress, (uint32_t)BufferSize); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User SRAM Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hsram : SRAM handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_SRAM_MSP_INIT_CB_ID SRAM MspInit callback ID - * @arg @ref HAL_SRAM_MSP_DEINIT_CB_ID SRAM MspDeInit callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_SRAM_RegisterCallback (SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId, pSRAM_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_SRAM_StateTypeDef state; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hsram); - - state = hsram->State; - if((state == HAL_SRAM_STATE_READY) || (state == HAL_SRAM_STATE_RESET) || (state == HAL_SRAM_STATE_PROTECTED)) - { - switch (CallbackId) - { - case HAL_SRAM_MSP_INIT_CB_ID : - hsram->MspInitCallback = pCallback; - break; - case HAL_SRAM_MSP_DEINIT_CB_ID : - hsram->MspDeInitCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsram); - return status; -} - -/** - * @brief Unregister a User SRAM Callback - * SRAM Callback is redirected to the weak (surcharged) predefined callback - * @param hsram : SRAM handle - * @param CallbackId : ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_SRAM_MSP_INIT_CB_ID SRAM MspInit callback ID - * @arg @ref HAL_SRAM_MSP_DEINIT_CB_ID SRAM MspDeInit callback ID - * @arg @ref HAL_SRAM_DMA_XFER_CPLT_CB_ID SRAM DMA Xfer Complete callback ID - * @arg @ref HAL_SRAM_DMA_XFER_ERR_CB_ID SRAM DMA Xfer Error callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_SRAM_UnRegisterCallback (SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_SRAM_StateTypeDef state; - - /* Process locked */ - __HAL_LOCK(hsram); - - state = hsram->State; - if((state == HAL_SRAM_STATE_READY) || (state == HAL_SRAM_STATE_PROTECTED)) - { - switch (CallbackId) - { - case HAL_SRAM_MSP_INIT_CB_ID : - hsram->MspInitCallback = HAL_SRAM_MspInit; - break; - case HAL_SRAM_MSP_DEINIT_CB_ID : - hsram->MspDeInitCallback = HAL_SRAM_MspDeInit; - break; - case HAL_SRAM_DMA_XFER_CPLT_CB_ID : - hsram->DmaXferCpltCallback = HAL_SRAM_DMA_XferCpltCallback; - break; - case HAL_SRAM_DMA_XFER_ERR_CB_ID : - hsram->DmaXferErrorCallback = HAL_SRAM_DMA_XferErrorCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else if(state == HAL_SRAM_STATE_RESET) - { - switch (CallbackId) - { - case HAL_SRAM_MSP_INIT_CB_ID : - hsram->MspInitCallback = HAL_SRAM_MspInit; - break; - case HAL_SRAM_MSP_DEINIT_CB_ID : - hsram->MspDeInitCallback = HAL_SRAM_MspDeInit; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsram); - return status; -} - -/** - * @brief Register a User SRAM Callback for DMA transfers - * To be used instead of the weak (surcharged) predefined callback - * @param hsram : SRAM handle - * @param CallbackId : ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_SRAM_DMA_XFER_CPLT_CB_ID SRAM DMA Xfer Complete callback ID - * @arg @ref HAL_SRAM_DMA_XFER_ERR_CB_ID SRAM DMA Xfer Error callback ID - * @param pCallback : pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_SRAM_RegisterDmaCallback(SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId, pSRAM_DmaCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - HAL_SRAM_StateTypeDef state; - - if(pCallback == NULL) - { - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(hsram); - - state = hsram->State; - if((state == HAL_SRAM_STATE_READY) || (state == HAL_SRAM_STATE_PROTECTED)) - { - switch (CallbackId) - { - case HAL_SRAM_DMA_XFER_CPLT_CB_ID : - hsram->DmaXferCpltCallback = pCallback; - break; - case HAL_SRAM_DMA_XFER_ERR_CB_ID : - hsram->DmaXferErrorCallback = pCallback; - break; - default : - /* update return status */ - status = HAL_ERROR; - break; - } - } - else - { - /* update return status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(hsram); - return status; -} -#endif -/** - * @} - */ - -/** @defgroup SRAM_Exported_Functions_Group3 Control functions - * @brief management functions - * -@verbatim - ============================================================================== - ##### SRAM Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the SRAM interface. - -@endverbatim - * @{ - */ - -/** - * @brief Enables dynamically SRAM write operation. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_WriteOperation_Enable(SRAM_HandleTypeDef *hsram) -{ - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Enable write operation */ - FMC_NORSRAM_WriteOperation_Enable(hsram->Instance, hsram->Init.NSBank); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_READY; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @brief Disables dynamically SRAM write operation. - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_SRAM_WriteOperation_Disable(SRAM_HandleTypeDef *hsram) -{ - /* Process Locked */ - __HAL_LOCK(hsram); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_BUSY; - - /* Disable write operation */ - FMC_NORSRAM_WriteOperation_Disable(hsram->Instance, hsram->Init.NSBank); - - /* Update the SRAM controller state */ - hsram->State = HAL_SRAM_STATE_PROTECTED; - - /* Process unlocked */ - __HAL_UNLOCK(hsram); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup SRAM_Exported_Functions_Group4 State functions - * @brief Peripheral State functions - * -@verbatim - ============================================================================== - ##### SRAM State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the SRAM controller - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Returns the SRAM controller state - * @param hsram pointer to a SRAM_HandleTypeDef structure that contains - * the configuration information for SRAM module. - * @retval HAL state - */ -HAL_SRAM_StateTypeDef HAL_SRAM_GetState(SRAM_HandleTypeDef *hsram) -{ - return hsram->State; -} -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -#endif /* HAL_SRAM_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c deleted file mode 100644 index f3d46cdd3467861..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c +++ /dev/null @@ -1,7626 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim.c - * @author MCD Application Team - * @brief TIM HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Timer (TIM) peripheral: - * + TIM Time Base Initialization - * + TIM Time Base Start - * + TIM Time Base Start Interruption - * + TIM Time Base Start DMA - * + TIM Output Compare/PWM Initialization - * + TIM Output Compare/PWM Channel Configuration - * + TIM Output Compare/PWM Start - * + TIM Output Compare/PWM Start Interruption - * + TIM Output Compare/PWM Start DMA - * + TIM Input Capture Initialization - * + TIM Input Capture Channel Configuration - * + TIM Input Capture Start - * + TIM Input Capture Start Interruption - * + TIM Input Capture Start DMA - * + TIM One Pulse Initialization - * + TIM One Pulse Channel Configuration - * + TIM One Pulse Start - * + TIM Encoder Interface Initialization - * + TIM Encoder Interface Start - * + TIM Encoder Interface Start Interruption - * + TIM Encoder Interface Start DMA - * + Commutation Event configuration with Interruption and DMA - * + TIM OCRef clear configuration - * + TIM External Clock configuration - @verbatim - ============================================================================== - ##### TIMER Generic features ##### - ============================================================================== - [..] The Timer features include: - (#) 16-bit up, down, up/down auto-reload counter. - (#) 16-bit programmable prescaler allowing dividing (also on the fly) the - counter clock frequency either by any factor between 1 and 65536. - (#) Up to 4 independent channels for: - (++) Input Capture - (++) Output Compare - (++) PWM generation (Edge and Center-aligned Mode) - (++) One-pulse mode output - (#) Synchronization circuit to control the timer with external signals and to interconnect - several timers together. - (#) Supports incremental encoder for positioning purposes - - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Initialize the TIM low level resources by implementing the following functions - depending on the selected feature: - (++) Time Base : HAL_TIM_Base_MspInit() - (++) Input Capture : HAL_TIM_IC_MspInit() - (++) Output Compare : HAL_TIM_OC_MspInit() - (++) PWM generation : HAL_TIM_PWM_MspInit() - (++) One-pulse mode output : HAL_TIM_OnePulse_MspInit() - (++) Encoder mode output : HAL_TIM_Encoder_MspInit() - - (#) Initialize the TIM low level resources : - (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE(); - (##) TIM pins configuration - (+++) Enable the clock for the TIM GPIOs using the following function: - __HAL_RCC_GPIOx_CLK_ENABLE(); - (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init(); - - (#) The external Clock can be configured, if needed (the default clock is the - internal clock from the APBx), using the following function: - HAL_TIM_ConfigClockSource, the clock configuration should be done before - any start function. - - (#) Configure the TIM in the desired functioning mode using one of the - Initialization function of this driver: - (++) HAL_TIM_Base_Init: to use the Timer to generate a simple time base - (++) HAL_TIM_OC_Init and HAL_TIM_OC_ConfigChannel: to use the Timer to generate an - Output Compare signal. - (++) HAL_TIM_PWM_Init and HAL_TIM_PWM_ConfigChannel: to use the Timer to generate a - PWM signal. - (++) HAL_TIM_IC_Init and HAL_TIM_IC_ConfigChannel: to use the Timer to measure an - external signal. - (++) HAL_TIM_OnePulse_Init and HAL_TIM_OnePulse_ConfigChannel: to use the Timer - in One Pulse Mode. - (++) HAL_TIM_Encoder_Init: to use the Timer Encoder Interface. - - (#) Activate the TIM peripheral using one of the start functions depending from the feature used: - (++) Time Base : HAL_TIM_Base_Start(), HAL_TIM_Base_Start_DMA(), HAL_TIM_Base_Start_IT() - (++) Input Capture : HAL_TIM_IC_Start(), HAL_TIM_IC_Start_DMA(), HAL_TIM_IC_Start_IT() - (++) Output Compare : HAL_TIM_OC_Start(), HAL_TIM_OC_Start_DMA(), HAL_TIM_OC_Start_IT() - (++) PWM generation : HAL_TIM_PWM_Start(), HAL_TIM_PWM_Start_DMA(), HAL_TIM_PWM_Start_IT() - (++) One-pulse mode output : HAL_TIM_OnePulse_Start(), HAL_TIM_OnePulse_Start_IT() - (++) Encoder mode output : HAL_TIM_Encoder_Start(), HAL_TIM_Encoder_Start_DMA(), HAL_TIM_Encoder_Start_IT(). - - (#) The DMA Burst is managed with the two following functions: - HAL_TIM_DMABurst_WriteStart() - HAL_TIM_DMABurst_ReadStart() - - *** Callback registration *** - ============================================= - - [..] - The compilation define USE_HAL_TIM_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - [..] - Use Function HAL_TIM_RegisterCallback() to register a callback. - HAL_TIM_RegisterCallback() takes as parameters the HAL peripheral handle, - the Callback ID and a pointer to the user callback function. - - [..] - Use function HAL_TIM_UnRegisterCallback() to reset a callback to the default - weak function. - HAL_TIM_UnRegisterCallback takes as parameters the HAL peripheral handle, - and the Callback ID. - - [..] - These functions allow to register/unregister following callbacks: - (+) Base_MspInitCallback : TIM Base Msp Init Callback. - (+) Base_MspDeInitCallback : TIM Base Msp DeInit Callback. - (+) IC_MspInitCallback : TIM IC Msp Init Callback. - (+) IC_MspDeInitCallback : TIM IC Msp DeInit Callback. - (+) OC_MspInitCallback : TIM OC Msp Init Callback. - (+) OC_MspDeInitCallback : TIM OC Msp DeInit Callback. - (+) PWM_MspInitCallback : TIM PWM Msp Init Callback. - (+) PWM_MspDeInitCallback : TIM PWM Msp DeInit Callback. - (+) OnePulse_MspInitCallback : TIM One Pulse Msp Init Callback. - (+) OnePulse_MspDeInitCallback : TIM One Pulse Msp DeInit Callback. - (+) Encoder_MspInitCallback : TIM Encoder Msp Init Callback. - (+) Encoder_MspDeInitCallback : TIM Encoder Msp DeInit Callback. - (+) HallSensor_MspInitCallback : TIM Hall Sensor Msp Init Callback. - (+) HallSensor_MspDeInitCallback : TIM Hall Sensor Msp DeInit Callback. - (+) PeriodElapsedCallback : TIM Period Elapsed Callback. - (+) PeriodElapsedHalfCpltCallback : TIM Period Elapsed half complete Callback. - (+) TriggerCallback : TIM Trigger Callback. - (+) TriggerHalfCpltCallback : TIM Trigger half complete Callback. - (+) IC_CaptureCallback : TIM Input Capture Callback. - (+) IC_CaptureHalfCpltCallback : TIM Input Capture half complete Callback. - (+) OC_DelayElapsedCallback : TIM Output Compare Delay Elapsed Callback. - (+) PWM_PulseFinishedCallback : TIM PWM Pulse Finished Callback. - (+) PWM_PulseFinishedHalfCpltCallback : TIM PWM Pulse Finished half complete Callback. - (+) ErrorCallback : TIM Error Callback. - (+) CommutationCallback : TIM Commutation Callback. - (+) CommutationHalfCpltCallback : TIM Commutation half complete Callback. - (+) BreakCallback : TIM Break Callback. - - [..] -By default, after the Init and when the state is HAL_TIM_STATE_RESET -all interrupt callbacks are set to the corresponding weak functions: - examples HAL_TIM_TriggerCallback(), HAL_TIM_ErrorCallback(). - - [..] - Exception done for MspInit and MspDeInit functions that are reset to the legacy weak - functionalities in the Init / DeInit only when these callbacks are null - (not registered beforehand). If not, MspInit or MspDeInit are not null, the Init / DeInit - keep and use the user MspInit / MspDeInit callbacks(registered beforehand) - - [..] - Callbacks can be registered / unregistered in HAL_TIM_STATE_READY state only. - Exception done MspInit / MspDeInit that can be registered / unregistered - in HAL_TIM_STATE_READY or HAL_TIM_STATE_RESET state, - thus registered(user) MspInit / DeInit callbacks can be used during the Init / DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_TIM_RegisterCallback() before calling DeInit or Init function. - - [..] - When The compilation define USE_HAL_TIM_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available and all callbacks - are set to the corresponding weak functions. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup TIM TIM - * @brief TIM HAL module driver - * @{ - */ - -#ifdef HAL_TIM_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup TIM_Private_Functions - * @{ - */ -static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter); -static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter); -static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter); -static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter); -static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter); -static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource); -static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim, - TIM_SlaveConfigTypeDef *sSlaveConfig); -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup TIM_Exported_Functions TIM Exported Functions - * @{ - */ - -/** @defgroup TIM_Exported_Functions_Group1 TIM Time Base functions - * @brief Time Base functions - * -@verbatim - ============================================================================== - ##### Time Base functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM base. - (+) De-initialize the TIM base. - (+) Start the Time Base. - (+) Stop the Time Base. - (+) Start the Time Base and enable interrupt. - (+) Stop the Time Base and disable interrupt. - (+) Start the Time Base and enable DMA transfer. - (+) Stop the Time Base and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Time base Unit according to the specified - * parameters in the TIM_HandleTypeDef and initialize the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_Base_DeInit() before HAL_TIM_Base_Init() - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->Base_MspInitCallback == NULL) - { - htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->Base_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - HAL_TIM_Base_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Set the Time Base configuration */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM Base peripheral - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->Base_MspDeInitCallback == NULL) - { - htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; - } - /* DeInit the low level hardware */ - htim->Base_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_TIM_Base_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Base MSP. - * @param htim TIM Base handle - * @retval None - */ -__weak void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_Base_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Base MSP. - * @param htim TIM Base handle - * @retval None - */ -__weak void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_Base_MspDeInit could be implemented in the user file - */ -} - - -/** - * @brief Starts the TIM Base generation. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - /* Check the TIM state */ - if (htim->State != HAL_TIM_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Base generation. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Base generation in interrupt mode. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - /* Check the TIM state */ - if (htim->State != HAL_TIM_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Enable the TIM Update interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_UPDATE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Base generation in interrupt mode. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - /* Disable the TIM Update interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_UPDATE); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Base generation in DMA mode. - * @param htim TIM Base handle - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_DMA_INSTANCE(htim->Instance)); - - /* Set the TIM state */ - if (htim->State == HAL_TIM_STATE_BUSY) - { - return HAL_BUSY; - } - else if (htim->State == HAL_TIM_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - htim->State = HAL_TIM_STATE_BUSY; - } - } - else - { - return HAL_ERROR; - } - - /* Set the DMA Period elapsed callbacks */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; - htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)pData, (uint32_t)&htim->Instance->ARR, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Update DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_UPDATE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Base generation in DMA mode. - * @param htim TIM Base handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_DMA_INSTANCE(htim->Instance)); - - /* Disable the TIM Update DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_UPDATE); - - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_READY; - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group2 TIM Output Compare functions - * @brief TIM Output Compare functions - * -@verbatim - ============================================================================== - ##### TIM Output Compare functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM Output Compare. - (+) De-initialize the TIM Output Compare. - (+) Start the TIM Output Compare. - (+) Stop the TIM Output Compare. - (+) Start the TIM Output Compare and enable interrupt. - (+) Stop the TIM Output Compare and disable interrupt. - (+) Start the TIM Output Compare and enable DMA transfer. - (+) Stop the TIM Output Compare and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Output Compare according to the specified - * parameters in the TIM_HandleTypeDef and initializes the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_OC_DeInit() before HAL_TIM_OC_Init() - * @param htim TIM Output Compare handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->OC_MspInitCallback == NULL) - { - htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->OC_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_OC_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Init the base time for the Output Compare */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM peripheral - * @param htim TIM Output Compare handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->OC_MspDeInitCallback == NULL) - { - htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; - } - /* DeInit the low level hardware */ - htim->OC_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_OC_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Output Compare MSP. - * @param htim TIM Output Compare handle - * @retval None - */ -__weak void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OC_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Output Compare MSP. - * @param htim TIM Output Compare handle - * @retval None - */ -__weak void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OC_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM Output Compare signal generation. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Output Compare signal generation. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Disable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Output Compare signal generation in interrupt mode. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Enable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Output Compare signal generation in interrupt mode. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM Output Compare signal generation in DMA mode. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to TIM peripheral - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Set the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) - { - return HAL_BUSY; - } - else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 4 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Output Compare signal generation in DMA mode. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Output compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group3 TIM PWM functions - * @brief TIM PWM functions - * -@verbatim - ============================================================================== - ##### TIM PWM functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM PWM. - (+) De-initialize the TIM PWM. - (+) Start the TIM PWM. - (+) Stop the TIM PWM. - (+) Start the TIM PWM and enable interrupt. - (+) Stop the TIM PWM and disable interrupt. - (+) Start the TIM PWM and enable DMA transfer. - (+) Stop the TIM PWM and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM PWM Time Base according to the specified - * parameters in the TIM_HandleTypeDef and initializes the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_PWM_DeInit() before HAL_TIM_PWM_Init() - * @param htim TIM PWM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->PWM_MspInitCallback == NULL) - { - htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->PWM_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_PWM_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Init the base time for the PWM */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM peripheral - * @param htim TIM PWM handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->PWM_MspDeInitCallback == NULL) - { - htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; - } - /* DeInit the low level hardware */ - htim->PWM_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_PWM_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM PWM MSP. - * @param htim TIM PWM handle - * @retval None - */ -__weak void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PWM_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM PWM MSP. - * @param htim TIM PWM handle - * @retval None - */ -__weak void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PWM_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the PWM signal generation. - * @param htim TIM handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the PWM signal generation. - * @param htim TIM PWM handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Disable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the PWM signal generation in interrupt mode. - * @param htim TIM PWM handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Enable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the PWM signal generation in interrupt mode. - * @param htim TIM PWM handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM PWM signal generation in DMA mode. - * @param htim TIM PWM handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to TIM peripheral - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Set the TIM channel state */ - if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) - { - return HAL_BUSY; - } - else if (TIM_CHANNEL_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Output Capture/Compare 3 request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 4 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM PWM signal generation in DMA mode. - * @param htim TIM PWM handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group4 TIM Input Capture functions - * @brief TIM Input Capture functions - * -@verbatim - ============================================================================== - ##### TIM Input Capture functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM Input Capture. - (+) De-initialize the TIM Input Capture. - (+) Start the TIM Input Capture. - (+) Stop the TIM Input Capture. - (+) Start the TIM Input Capture and enable interrupt. - (+) Stop the TIM Input Capture and disable interrupt. - (+) Start the TIM Input Capture and enable DMA transfer. - (+) Stop the TIM Input Capture and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Input Capture Time base according to the specified - * parameters in the TIM_HandleTypeDef and initializes the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_IC_DeInit() before HAL_TIM_IC_Init() - * @param htim TIM Input Capture handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->IC_MspInitCallback == NULL) - { - htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->IC_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_IC_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Init the base time for the input capture */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM peripheral - * @param htim TIM Input Capture handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->IC_MspDeInitCallback == NULL) - { - htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; - } - /* DeInit the low level hardware */ - htim->IC_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_IC_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET_ALL(htim, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Input Capture MSP. - * @param htim TIM Input Capture handle - * @retval None - */ -__weak void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_IC_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Input Capture MSP. - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_IC_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM Input Capture measurement. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); - HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if ((channel_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Input Capture measurement. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Disable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Input Capture measurement in interrupt mode. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); - HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM channel state */ - if ((channel_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Enable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Input Capture measurement in interrupt mode. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM Input Capture measurement in DMA mode. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param pData The destination Buffer address. - * @param Length The length of data to be transferred from TIM peripheral to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - HAL_TIM_ChannelStateTypeDef channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); - HAL_TIM_ChannelStateTypeDef complementary_channel_state = TIM_CHANNEL_N_STATE_GET(htim, Channel); - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance)); - - /* Set the TIM channel state */ - if ((channel_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - /* Enable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_ENABLE); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->CCR3, (uint32_t)pData, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - case TIM_CHANNEL_4: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->CCR4, (uint32_t)pData, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 4 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); - break; - } - - default: - status = HAL_ERROR; - break; - } - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Input Capture measurement in DMA mode. - * @param htim TIM Input Capture handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - assert_param(IS_TIM_DMA_CC_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channel */ - TIM_CCxChannelCmd(htim->Instance, Channel, TIM_CCx_DISABLE); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - case TIM_CHANNEL_4: - { - /* Disable the TIM Capture/Compare 4 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group5 TIM One Pulse functions - * @brief TIM One Pulse functions - * -@verbatim - ============================================================================== - ##### TIM One Pulse functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM One Pulse. - (+) De-initialize the TIM One Pulse. - (+) Start the TIM One Pulse. - (+) Stop the TIM One Pulse. - (+) Start the TIM One Pulse and enable interrupt. - (+) Stop the TIM One Pulse and disable interrupt. - (+) Start the TIM One Pulse and enable DMA transfer. - (+) Stop the TIM One Pulse and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM One Pulse Time Base according to the specified - * parameters in the TIM_HandleTypeDef and initializes the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_OnePulse_DeInit() before HAL_TIM_OnePulse_Init() - * @note When the timer instance is initialized in One Pulse mode, timer - * channels 1 and channel 2 are reserved and cannot be used for other - * purpose. - * @param htim TIM One Pulse handle - * @param OnePulseMode Select the One pulse mode. - * This parameter can be one of the following values: - * @arg TIM_OPMODE_SINGLE: Only one pulse will be generated. - * @arg TIM_OPMODE_REPETITIVE: Repetitive pulses will be generated. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode) -{ - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_OPM_MODE(OnePulseMode)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->OnePulse_MspInitCallback == NULL) - { - htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->OnePulse_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_OnePulse_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Configure the Time base in the One Pulse Mode */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Reset the OPM Bit */ - htim->Instance->CR1 &= ~TIM_CR1_OPM; - - /* Configure the OPM Mode */ - htim->Instance->CR1 |= OnePulseMode; - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM One Pulse - * @param htim TIM One Pulse handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->OnePulse_MspDeInitCallback == NULL) - { - htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; - } - /* DeInit the low level hardware */ - htim->OnePulse_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_TIM_OnePulse_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM One Pulse MSP. - * @param htim TIM One Pulse handle - * @retval None - */ -__weak void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OnePulse_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM One Pulse MSP. - * @param htim TIM One Pulse handle - * @retval None - */ -__weak void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OnePulse_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM One Pulse signal generation. - * @note Though OutputChannel parameter is deprecated and ignored by the function - * it has been kept to avoid HAL_TIM API compatibility break. - * @note The pulse output channel is determined when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel See note above - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Prevent unused argument(s) compilation warning */ - UNUSED(OutputChannel); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Capture compare and the Input Capture channels - (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) - if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and - if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output - whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together - - No need to enable the counter, it's enabled automatically by hardware - (the counter starts in response to a stimulus and generate a pulse */ - - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM One Pulse signal generation. - * @note Though OutputChannel parameter is deprecated and ignored by the function - * it has been kept to avoid HAL_TIM API compatibility break. - * @note The pulse output channel is determined when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel See note above - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(OutputChannel); - - /* Disable the Capture compare and the Input Capture channels - (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) - if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and - if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output - whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ - - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM One Pulse signal generation in interrupt mode. - * @note Though OutputChannel parameter is deprecated and ignored by the function - * it has been kept to avoid HAL_TIM API compatibility break. - * @note The pulse output channel is determined when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel See note above - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Prevent unused argument(s) compilation warning */ - UNUSED(OutputChannel); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Capture compare and the Input Capture channels - (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) - if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and - if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output - whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be enabled together - - No need to enable the counter, it's enabled automatically by hardware - (the counter starts in response to a stimulus and generate a pulse */ - - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Enable the main output */ - __HAL_TIM_MOE_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM One Pulse signal generation in interrupt mode. - * @note Though OutputChannel parameter is deprecated and ignored by the function - * it has been kept to avoid HAL_TIM API compatibility break. - * @note The pulse output channel is determined when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel See note above - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(OutputChannel); - - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - - /* Disable the Capture compare and the Input Capture channels - (in the OPM Mode the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) - if TIM_CHANNEL_1 is used as output, the TIM_CHANNEL_2 will be used as input and - if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output - whatever the combination, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - if (IS_TIM_BREAK_INSTANCE(htim->Instance) != RESET) - { - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group6 TIM Encoder functions - * @brief TIM Encoder functions - * -@verbatim - ============================================================================== - ##### TIM Encoder functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the TIM Encoder. - (+) De-initialize the TIM Encoder. - (+) Start the TIM Encoder. - (+) Stop the TIM Encoder. - (+) Start the TIM Encoder and enable interrupt. - (+) Stop the TIM Encoder and disable interrupt. - (+) Start the TIM Encoder and enable DMA transfer. - (+) Stop the TIM Encoder and disable DMA transfer. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Encoder Interface and initialize the associated handle. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * Ex: call @ref HAL_TIM_Encoder_DeInit() before HAL_TIM_Encoder_Init() - * @note Encoder mode and External clock mode 2 are not compatible and must not be selected together - * Ex: A call for @ref HAL_TIM_Encoder_Init will erase the settings of @ref HAL_TIM_ConfigClockSource - * using TIM_CLOCKSOURCE_ETRMODE2 and vice versa - * @note When the timer instance is initialized in Encoder mode, timer - * channels 1 and channel 2 are reserved and cannot be used for other - * purpose. - * @param htim TIM Encoder Interface handle - * @param sConfig TIM Encoder Interface configuration structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig) -{ - uint32_t tmpsmcr; - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - assert_param(IS_TIM_ENCODER_MODE(sConfig->EncoderMode)); - assert_param(IS_TIM_IC_SELECTION(sConfig->IC1Selection)); - assert_param(IS_TIM_IC_SELECTION(sConfig->IC2Selection)); - assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC1Polarity)); - assert_param(IS_TIM_ENCODERINPUT_POLARITY(sConfig->IC2Polarity)); - assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); - assert_param(IS_TIM_IC_PRESCALER(sConfig->IC2Prescaler)); - assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); - assert_param(IS_TIM_IC_FILTER(sConfig->IC2Filter)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy weak callbacks */ - TIM_ResetCallback(htim); - - if (htim->Encoder_MspInitCallback == NULL) - { - htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->Encoder_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIM_Encoder_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Reset the SMS and ECE bits */ - htim->Instance->SMCR &= ~(TIM_SMCR_SMS | TIM_SMCR_ECE); - - /* Configure the Time base in the Encoder Mode */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Get the TIMx SMCR register value */ - tmpsmcr = htim->Instance->SMCR; - - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = htim->Instance->CCMR1; - - /* Get the TIMx CCER register value */ - tmpccer = htim->Instance->CCER; - - /* Set the encoder Mode */ - tmpsmcr |= sConfig->EncoderMode; - - /* Select the Capture Compare 1 and the Capture Compare 2 as input */ - tmpccmr1 &= ~(TIM_CCMR1_CC1S | TIM_CCMR1_CC2S); - tmpccmr1 |= (sConfig->IC1Selection | (sConfig->IC2Selection << 8U)); - - /* Set the Capture Compare 1 and the Capture Compare 2 prescalers and filters */ - tmpccmr1 &= ~(TIM_CCMR1_IC1PSC | TIM_CCMR1_IC2PSC); - tmpccmr1 &= ~(TIM_CCMR1_IC1F | TIM_CCMR1_IC2F); - tmpccmr1 |= sConfig->IC1Prescaler | (sConfig->IC2Prescaler << 8U); - tmpccmr1 |= (sConfig->IC1Filter << 4U) | (sConfig->IC2Filter << 12U); - - /* Set the TI1 and the TI2 Polarities */ - tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC2P); - tmpccer &= ~(TIM_CCER_CC1NP | TIM_CCER_CC2NP); - tmpccer |= sConfig->IC1Polarity | (sConfig->IC2Polarity << 4U); - - /* Write to TIMx SMCR */ - htim->Instance->SMCR = tmpsmcr; - - /* Write to TIMx CCMR1 */ - htim->Instance->CCMR1 = tmpccmr1; - - /* Write to TIMx CCER */ - htim->Instance->CCER = tmpccer; - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - - -/** - * @brief DeInitializes the TIM Encoder interface - * @param htim TIM Encoder Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->Encoder_MspDeInitCallback == NULL) - { - htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; - } - /* DeInit the low level hardware */ - htim->Encoder_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_TIM_Encoder_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Encoder Interface MSP. - * @param htim TIM Encoder Interface handle - * @retval None - */ -__weak void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_Encoder_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Encoder Interface MSP. - * @param htim TIM Encoder Interface handle - * @retval None - */ -__weak void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_Encoder_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM Encoder Interface. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Set the TIM channel(s) state */ - if (Channel == TIM_CHANNEL_1) - { - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else if (Channel == TIM_CHANNEL_2) - { - if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - - /* Enable the encoder interface channels */ - switch (Channel) - { - case TIM_CHANNEL_1: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - break; - } - - case TIM_CHANNEL_2: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - break; - } - - default : - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - break; - } - } - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Encoder Interface. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channels 1 and 2 - (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ - switch (Channel) - { - case TIM_CHANNEL_1: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - break; - } - - case TIM_CHANNEL_2: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - break; - } - - default : - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - break; - } - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel(s) state */ - if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Encoder Interface in interrupt mode. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Set the TIM channel(s) state */ - if (Channel == TIM_CHANNEL_1) - { - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else if (Channel == TIM_CHANNEL_2) - { - if ((channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - - /* Enable the encoder interface channels */ - /* Enable the capture compare Interrupts 1 and/or 2 */ - switch (Channel) - { - case TIM_CHANNEL_1: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - default : - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - } - - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Encoder Interface in interrupt mode. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channels 1 and 2 - (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ - if (Channel == TIM_CHANNEL_1) - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - /* Disable the capture compare Interrupts 1 */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - } - else if (Channel == TIM_CHANNEL_2) - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - /* Disable the capture compare Interrupts 2 */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - } - else - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - /* Disable the capture compare Interrupts 1 and 2 */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel(s) state */ - if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Encoder Interface in DMA mode. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @param pData1 The destination Buffer address for IC1. - * @param pData2 The destination Buffer address for IC2. - * @param Length The length of data to be transferred from TIM peripheral to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1, - uint32_t *pData2, uint16_t Length) -{ - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Set the TIM channel(s) state */ - if (Channel == TIM_CHANNEL_1) - { - if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((pData1 == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - } - else if (Channel == TIM_CHANNEL_2) - { - if ((channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_2_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((pData2 == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - } - else - { - if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) - && (channel_2_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_2_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((((pData1 == NULL) || (pData2 == NULL))) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Input Capture DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError; - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Input Capture DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - break; - } - - default: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->CCR2, (uint32_t)pData2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - - /* Enable the TIM Input Capture DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - /* Enable the TIM Input Capture DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - - /* Enable the Capture compare channel */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); - - /* Enable the Peripheral */ - __HAL_TIM_ENABLE(htim); - - break; - } - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Encoder Interface in DMA mode. - * @param htim TIM Encoder Interface handle - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_ALL: TIM Channel 1 and TIM Channel 2 are selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channels 1 and 2 - (in the EncoderInterface the two possible channels that can be used are TIM_CHANNEL_1 and TIM_CHANNEL_2) */ - if (Channel == TIM_CHANNEL_1) - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - /* Disable the capture compare DMA Request 1 */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - } - else if (Channel == TIM_CHANNEL_2) - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - /* Disable the capture compare DMA Request 2 */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - } - else - { - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); - - /* Disable the capture compare DMA Request 1 and 2 */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - } - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel(s) state */ - if ((Channel == TIM_CHANNEL_1) || (Channel == TIM_CHANNEL_2)) - { - TIM_CHANNEL_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ -/** @defgroup TIM_Exported_Functions_Group7 TIM IRQ handler management - * @brief TIM IRQ handler management - * -@verbatim - ============================================================================== - ##### IRQ handler management ##### - ============================================================================== - [..] - This section provides Timer IRQ handler function. - -@endverbatim - * @{ - */ -/** - * @brief This function handles TIM interrupts requests. - * @param htim TIM handle - * @retval None - */ -void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim) -{ - /* Capture compare 1 event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET) - { - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1); - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - - /* Input capture event */ - if ((htim->Instance->CCMR1 & TIM_CCMR1_CC1S) != 0x00U) - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - /* Output compare event */ - else - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->OC_DelayElapsedCallback(htim); - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_OC_DelayElapsedCallback(htim); - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - } - } - } - /* Capture compare 2 event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2); - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - /* Input capture event */ - if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U) - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - /* Output compare event */ - else - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->OC_DelayElapsedCallback(htim); - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_OC_DelayElapsedCallback(htim); - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - } - } - /* Capture compare 3 event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3); - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - /* Input capture event */ - if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U) - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - /* Output compare event */ - else - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->OC_DelayElapsedCallback(htim); - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_OC_DelayElapsedCallback(htim); - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - } - } - /* Capture compare 4 event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4); - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - /* Input capture event */ - if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U) - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - /* Output compare event */ - else - { -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->OC_DelayElapsedCallback(htim); - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_OC_DelayElapsedCallback(htim); - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; - } - } - /* TIM Update event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PeriodElapsedCallback(htim); -#else - HAL_TIM_PeriodElapsedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - } - /* TIM Break input event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK); -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->BreakCallback(htim); -#else - HAL_TIMEx_BreakCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - } - /* TIM Trigger detection event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER); -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->TriggerCallback(htim); -#else - HAL_TIM_TriggerCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - } - /* TIM commutation event */ - if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET) - { - if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET) - { - __HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM); -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->CommutationCallback(htim); -#else - HAL_TIMEx_CommutCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - } -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions - * @brief TIM Peripheral Control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Configure The Input Output channels for OC, PWM, IC or One Pulse mode. - (+) Configure External Clock source. - (+) Configure Complementary channels, break features and dead time. - (+) Configure Master and the Slave synchronization. - (+) Configure the DMA Burst Mode. - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the TIM Output Compare Channels according to the specified - * parameters in the TIM_OC_InitTypeDef. - * @param htim TIM Output Compare handle - * @param sConfig TIM Output Compare configuration structure - * @param Channel TIM Channels to configure - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, - TIM_OC_InitTypeDef *sConfig, - uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CHANNELS(Channel)); - assert_param(IS_TIM_OC_MODE(sConfig->OCMode)); - assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); - - /* Process Locked */ - __HAL_LOCK(htim); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - /* Configure the TIM Channel 1 in Output Compare */ - TIM_OC1_SetConfig(htim->Instance, sConfig); - break; - } - - case TIM_CHANNEL_2: - { - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - /* Configure the TIM Channel 2 in Output Compare */ - TIM_OC2_SetConfig(htim->Instance, sConfig); - break; - } - - case TIM_CHANNEL_3: - { - /* Check the parameters */ - assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); - - /* Configure the TIM Channel 3 in Output Compare */ - TIM_OC3_SetConfig(htim->Instance, sConfig); - break; - } - - case TIM_CHANNEL_4: - { - /* Check the parameters */ - assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); - - /* Configure the TIM Channel 4 in Output Compare */ - TIM_OC4_SetConfig(htim->Instance, sConfig); - break; - } - - default: - status = HAL_ERROR; - break; - } - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Initializes the TIM Input Capture Channels according to the specified - * parameters in the TIM_IC_InitTypeDef. - * @param htim TIM IC handle - * @param sConfig TIM Input Capture configuration structure - * @param Channel TIM Channel to configure - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - assert_param(IS_TIM_IC_POLARITY(sConfig->ICPolarity)); - assert_param(IS_TIM_IC_SELECTION(sConfig->ICSelection)); - assert_param(IS_TIM_IC_PRESCALER(sConfig->ICPrescaler)); - assert_param(IS_TIM_IC_FILTER(sConfig->ICFilter)); - - /* Process Locked */ - __HAL_LOCK(htim); - - if (Channel == TIM_CHANNEL_1) - { - /* TI1 Configuration */ - TIM_TI1_SetConfig(htim->Instance, - sConfig->ICPolarity, - sConfig->ICSelection, - sConfig->ICFilter); - - /* Reset the IC1PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; - - /* Set the IC1PSC value */ - htim->Instance->CCMR1 |= sConfig->ICPrescaler; - } - else if (Channel == TIM_CHANNEL_2) - { - /* TI2 Configuration */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - TIM_TI2_SetConfig(htim->Instance, - sConfig->ICPolarity, - sConfig->ICSelection, - sConfig->ICFilter); - - /* Reset the IC2PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC; - - /* Set the IC2PSC value */ - htim->Instance->CCMR1 |= (sConfig->ICPrescaler << 8U); - } - else if (Channel == TIM_CHANNEL_3) - { - /* TI3 Configuration */ - assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); - - TIM_TI3_SetConfig(htim->Instance, - sConfig->ICPolarity, - sConfig->ICSelection, - sConfig->ICFilter); - - /* Reset the IC3PSC Bits */ - htim->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC; - - /* Set the IC3PSC value */ - htim->Instance->CCMR2 |= sConfig->ICPrescaler; - } - else if (Channel == TIM_CHANNEL_4) - { - /* TI4 Configuration */ - assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); - - TIM_TI4_SetConfig(htim->Instance, - sConfig->ICPolarity, - sConfig->ICSelection, - sConfig->ICFilter); - - /* Reset the IC4PSC Bits */ - htim->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC; - - /* Set the IC4PSC value */ - htim->Instance->CCMR2 |= (sConfig->ICPrescaler << 8U); - } - else - { - status = HAL_ERROR; - } - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Initializes the TIM PWM channels according to the specified - * parameters in the TIM_OC_InitTypeDef. - * @param htim TIM PWM handle - * @param sConfig TIM PWM configuration structure - * @param Channel TIM Channels to be configured - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, - TIM_OC_InitTypeDef *sConfig, - uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CHANNELS(Channel)); - assert_param(IS_TIM_PWM_MODE(sConfig->OCMode)); - assert_param(IS_TIM_OC_POLARITY(sConfig->OCPolarity)); - assert_param(IS_TIM_FAST_STATE(sConfig->OCFastMode)); - - /* Process Locked */ - __HAL_LOCK(htim); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - /* Configure the Channel 1 in PWM mode */ - TIM_OC1_SetConfig(htim->Instance, sConfig); - - /* Set the Preload enable bit for channel1 */ - htim->Instance->CCMR1 |= TIM_CCMR1_OC1PE; - - /* Configure the Output Fast mode */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE; - htim->Instance->CCMR1 |= sConfig->OCFastMode; - break; - } - - case TIM_CHANNEL_2: - { - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - /* Configure the Channel 2 in PWM mode */ - TIM_OC2_SetConfig(htim->Instance, sConfig); - - /* Set the Preload enable bit for channel2 */ - htim->Instance->CCMR1 |= TIM_CCMR1_OC2PE; - - /* Configure the Output Fast mode */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE; - htim->Instance->CCMR1 |= sConfig->OCFastMode << 8U; - break; - } - - case TIM_CHANNEL_3: - { - /* Check the parameters */ - assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); - - /* Configure the Channel 3 in PWM mode */ - TIM_OC3_SetConfig(htim->Instance, sConfig); - - /* Set the Preload enable bit for channel3 */ - htim->Instance->CCMR2 |= TIM_CCMR2_OC3PE; - - /* Configure the Output Fast mode */ - htim->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE; - htim->Instance->CCMR2 |= sConfig->OCFastMode; - break; - } - - case TIM_CHANNEL_4: - { - /* Check the parameters */ - assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); - - /* Configure the Channel 4 in PWM mode */ - TIM_OC4_SetConfig(htim->Instance, sConfig); - - /* Set the Preload enable bit for channel4 */ - htim->Instance->CCMR2 |= TIM_CCMR2_OC4PE; - - /* Configure the Output Fast mode */ - htim->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE; - htim->Instance->CCMR2 |= sConfig->OCFastMode << 8U; - break; - } - - default: - status = HAL_ERROR; - break; - } - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Initializes the TIM One Pulse Channels according to the specified - * parameters in the TIM_OnePulse_InitTypeDef. - * @param htim TIM One Pulse handle - * @param sConfig TIM One Pulse configuration structure - * @param OutputChannel TIM output channel to configure - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @param InputChannel TIM input Channel to configure - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @note To output a waveform with a minimum delay user can enable the fast - * mode by calling the @ref __HAL_TIM_ENABLE_OCxFAST macro. Then CCx - * output is forced in response to the edge detection on TIx input, - * without taking in account the comparison. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig, - uint32_t OutputChannel, uint32_t InputChannel) -{ - HAL_StatusTypeDef status = HAL_OK; - TIM_OC_InitTypeDef temp1; - - /* Check the parameters */ - assert_param(IS_TIM_OPM_CHANNELS(OutputChannel)); - assert_param(IS_TIM_OPM_CHANNELS(InputChannel)); - - if (OutputChannel != InputChannel) - { - /* Process Locked */ - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Extract the Output compare configuration from sConfig structure */ - temp1.OCMode = sConfig->OCMode; - temp1.Pulse = sConfig->Pulse; - temp1.OCPolarity = sConfig->OCPolarity; - temp1.OCNPolarity = sConfig->OCNPolarity; - temp1.OCIdleState = sConfig->OCIdleState; - temp1.OCNIdleState = sConfig->OCNIdleState; - - switch (OutputChannel) - { - case TIM_CHANNEL_1: - { - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - TIM_OC1_SetConfig(htim->Instance, &temp1); - break; - } - - case TIM_CHANNEL_2: - { - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - TIM_OC2_SetConfig(htim->Instance, &temp1); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - switch (InputChannel) - { - case TIM_CHANNEL_1: - { - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - TIM_TI1_SetConfig(htim->Instance, sConfig->ICPolarity, - sConfig->ICSelection, sConfig->ICFilter); - - /* Reset the IC1PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; - - /* Select the Trigger source */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= TIM_TS_TI1FP1; - - /* Select the Slave Mode */ - htim->Instance->SMCR &= ~TIM_SMCR_SMS; - htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER; - break; - } - - case TIM_CHANNEL_2: - { - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - TIM_TI2_SetConfig(htim->Instance, sConfig->ICPolarity, - sConfig->ICSelection, sConfig->ICFilter); - - /* Reset the IC2PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC; - - /* Select the Trigger source */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= TIM_TS_TI2FP2; - - /* Select the Slave Mode */ - htim->Instance->SMCR &= ~TIM_SMCR_SMS; - htim->Instance->SMCR |= TIM_SLAVEMODE_TRIGGER; - break; - } - - default: - status = HAL_ERROR; - break; - } - } - - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return status; - } - else - { - return HAL_ERROR; - } -} - -/** - * @brief Configure the DMA Burst to transfer Data from the memory to the TIM peripheral - * @param htim TIM handle - * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write - * This parameter can be one of the following values: - * @arg TIM_DMABASE_CR1 - * @arg TIM_DMABASE_CR2 - * @arg TIM_DMABASE_SMCR - * @arg TIM_DMABASE_DIER - * @arg TIM_DMABASE_SR - * @arg TIM_DMABASE_EGR - * @arg TIM_DMABASE_CCMR1 - * @arg TIM_DMABASE_CCMR2 - * @arg TIM_DMABASE_CCER - * @arg TIM_DMABASE_CNT - * @arg TIM_DMABASE_PSC - * @arg TIM_DMABASE_ARR - * @arg TIM_DMABASE_RCR - * @arg TIM_DMABASE_CCR1 - * @arg TIM_DMABASE_CCR2 - * @arg TIM_DMABASE_CCR3 - * @arg TIM_DMABASE_CCR4 - * @arg TIM_DMABASE_BDTR - * @param BurstRequestSrc TIM DMA Request sources - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source - * @param BurstBuffer The Buffer address. - * @param BurstLength DMA Burst length. This parameter can be one value - * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. - * @note This function should be used only when BurstLength is equal to DMA data transfer length. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (status == HAL_OK) - { - status = HAL_TIM_DMABurst_MultiWriteStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength, - ((BurstLength) >> 8U) + 1U); - } - - - return status; -} - -/** - * @brief Configure the DMA Burst to transfer multiple Data from the memory to the TIM peripheral - * @param htim TIM handle - * @param BurstBaseAddress TIM Base address from where the DMA will start the Data write - * This parameter can be one of the following values: - * @arg TIM_DMABASE_CR1 - * @arg TIM_DMABASE_CR2 - * @arg TIM_DMABASE_SMCR - * @arg TIM_DMABASE_DIER - * @arg TIM_DMABASE_SR - * @arg TIM_DMABASE_EGR - * @arg TIM_DMABASE_CCMR1 - * @arg TIM_DMABASE_CCMR2 - * @arg TIM_DMABASE_CCER - * @arg TIM_DMABASE_CNT - * @arg TIM_DMABASE_PSC - * @arg TIM_DMABASE_ARR - * @arg TIM_DMABASE_RCR - * @arg TIM_DMABASE_CCR1 - * @arg TIM_DMABASE_CCR2 - * @arg TIM_DMABASE_CCR3 - * @arg TIM_DMABASE_CCR4 - * @arg TIM_DMABASE_BDTR - * @param BurstRequestSrc TIM DMA Request sources - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source - * @param BurstBuffer The Buffer address. - * @param BurstLength DMA Burst length. This parameter can be one value - * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. - * @param DataLength Data length. This parameter can be one value - * between 1 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); - assert_param(IS_TIM_DMA_BASE(BurstBaseAddress)); - assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); - assert_param(IS_TIM_DMA_LENGTH(BurstLength)); - assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength)); - - if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY) - { - return HAL_BUSY; - } - else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY) - { - if ((BurstBuffer == NULL) && (BurstLength > 0U)) - { - return HAL_ERROR; - } - else - { - htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY; - } - } - else - { - /* nothing to do */ - } - - switch (BurstRequestSrc) - { - case TIM_DMA_UPDATE: - { - /* Set the DMA Period elapsed callbacks */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; - htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC4: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMADelayPulseCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_COM: - { - /* Set the DMA commutation callbacks */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_TRIGGER: - { - /* Set the DMA trigger callbacks */ - htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt; - htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)BurstBuffer, - (uint32_t)&htim->Instance->DMAR, DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Configure the DMA Burst Mode */ - htim->Instance->DCR = (BurstBaseAddress | BurstLength); - /* Enable the TIM DMA Request */ - __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM DMA Burst mode - * @param htim TIM handle - * @param BurstRequestSrc TIM DMA Request sources to disable - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); - - /* Abort the DMA transfer (at least disable the DMA stream) */ - switch (BurstRequestSrc) - { - case TIM_DMA_UPDATE: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); - break; - } - case TIM_DMA_CC1: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - case TIM_DMA_CC2: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - case TIM_DMA_CC3: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - case TIM_DMA_CC4: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - case TIM_DMA_COM: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]); - break; - } - case TIM_DMA_TRIGGER: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]); - break; - } - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the TIM Update DMA request */ - __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc); - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - } - - /* Return function status */ - return status; -} - -/** - * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory - * @param htim TIM handle - * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read - * This parameter can be one of the following values: - * @arg TIM_DMABASE_CR1 - * @arg TIM_DMABASE_CR2 - * @arg TIM_DMABASE_SMCR - * @arg TIM_DMABASE_DIER - * @arg TIM_DMABASE_SR - * @arg TIM_DMABASE_EGR - * @arg TIM_DMABASE_CCMR1 - * @arg TIM_DMABASE_CCMR2 - * @arg TIM_DMABASE_CCER - * @arg TIM_DMABASE_CNT - * @arg TIM_DMABASE_PSC - * @arg TIM_DMABASE_ARR - * @arg TIM_DMABASE_RCR - * @arg TIM_DMABASE_CCR1 - * @arg TIM_DMABASE_CCR2 - * @arg TIM_DMABASE_CCR3 - * @arg TIM_DMABASE_CCR4 - * @arg TIM_DMABASE_BDTR - * @param BurstRequestSrc TIM DMA Request sources - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source - * @param BurstBuffer The Buffer address. - * @param BurstLength DMA Burst length. This parameter can be one value - * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. - * @note This function should be used only when BurstLength is equal to DMA data transfer length. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (status == HAL_OK) - { - status = HAL_TIM_DMABurst_MultiReadStart(htim, BurstBaseAddress, BurstRequestSrc, BurstBuffer, BurstLength, - ((BurstLength) >> 8U) + 1U); - } - - return status; -} - -/** - * @brief Configure the DMA Burst to transfer Data from the TIM peripheral to the memory - * @param htim TIM handle - * @param BurstBaseAddress TIM Base address from where the DMA will start the Data read - * This parameter can be one of the following values: - * @arg TIM_DMABASE_CR1 - * @arg TIM_DMABASE_CR2 - * @arg TIM_DMABASE_SMCR - * @arg TIM_DMABASE_DIER - * @arg TIM_DMABASE_SR - * @arg TIM_DMABASE_EGR - * @arg TIM_DMABASE_CCMR1 - * @arg TIM_DMABASE_CCMR2 - * @arg TIM_DMABASE_CCER - * @arg TIM_DMABASE_CNT - * @arg TIM_DMABASE_PSC - * @arg TIM_DMABASE_ARR - * @arg TIM_DMABASE_RCR - * @arg TIM_DMABASE_CCR1 - * @arg TIM_DMABASE_CCR2 - * @arg TIM_DMABASE_CCR3 - * @arg TIM_DMABASE_CCR4 - * @arg TIM_DMABASE_BDTR - * @param BurstRequestSrc TIM DMA Request sources - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_TRIGGER: TIM Trigger DMA source - * @param BurstBuffer The Buffer address. - * @param BurstLength DMA Burst length. This parameter can be one value - * between: TIM_DMABURSTLENGTH_1TRANSFER and TIM_DMABURSTLENGTH_18TRANSFERS. - * @param DataLength Data length. This parameter can be one value - * between 1 and 0xFFFF. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); - assert_param(IS_TIM_DMA_BASE(BurstBaseAddress)); - assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); - assert_param(IS_TIM_DMA_LENGTH(BurstLength)); - assert_param(IS_TIM_DMA_DATA_LENGTH(DataLength)); - - if (htim->DMABurstState == HAL_DMA_BURST_STATE_BUSY) - { - return HAL_BUSY; - } - else if (htim->DMABurstState == HAL_DMA_BURST_STATE_READY) - { - if ((BurstBuffer == NULL) && (BurstLength > 0U)) - { - return HAL_ERROR; - } - else - { - htim->DMABurstState = HAL_DMA_BURST_STATE_BUSY; - } - } - else - { - /* nothing to do */ - } - switch (BurstRequestSrc) - { - case TIM_DMA_UPDATE: - { - /* Set the DMA Period elapsed callbacks */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferCpltCallback = TIM_DMAPeriodElapsedCplt; - htim->hdma[TIM_DMA_ID_UPDATE]->XferHalfCpltCallback = TIM_DMAPeriodElapsedHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_UPDATE]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC1: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC2: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC3: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_CC4: - { - /* Set the DMA capture callbacks */ - htim->hdma[TIM_DMA_ID_CC4]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC4]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC4]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_COM: - { - /* Set the DMA commutation callbacks */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_COMMUTATION], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - case TIM_DMA_TRIGGER: - { - /* Set the DMA trigger callbacks */ - htim->hdma[TIM_DMA_ID_TRIGGER]->XferCpltCallback = TIM_DMATriggerCplt; - htim->hdma[TIM_DMA_ID_TRIGGER]->XferHalfCpltCallback = TIM_DMATriggerHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_TRIGGER]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_TRIGGER], (uint32_t)&htim->Instance->DMAR, (uint32_t)BurstBuffer, - DataLength) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - break; - } - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Configure the DMA Burst Mode */ - htim->Instance->DCR = (BurstBaseAddress | BurstLength); - - /* Enable the TIM DMA Request */ - __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); - } - - /* Return function status */ - return status; -} - -/** - * @brief Stop the DMA burst reading - * @param htim TIM handle - * @param BurstRequestSrc TIM DMA Request sources to disable. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_DMA_SOURCE(BurstRequestSrc)); - - /* Abort the DMA transfer (at least disable the DMA stream) */ - switch (BurstRequestSrc) - { - case TIM_DMA_UPDATE: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_UPDATE]); - break; - } - case TIM_DMA_CC1: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - case TIM_DMA_CC2: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - case TIM_DMA_CC3: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - case TIM_DMA_CC4: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC4]); - break; - } - case TIM_DMA_COM: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_COMMUTATION]); - break; - } - case TIM_DMA_TRIGGER: - { - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_TRIGGER]); - break; - } - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the TIM Update DMA request */ - __HAL_TIM_DISABLE_DMA(htim, BurstRequestSrc); - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - } - - /* Return function status */ - return status; -} - -/** - * @brief Generate a software event - * @param htim TIM handle - * @param EventSource specifies the event source. - * This parameter can be one of the following values: - * @arg TIM_EVENTSOURCE_UPDATE: Timer update Event source - * @arg TIM_EVENTSOURCE_CC1: Timer Capture Compare 1 Event source - * @arg TIM_EVENTSOURCE_CC2: Timer Capture Compare 2 Event source - * @arg TIM_EVENTSOURCE_CC3: Timer Capture Compare 3 Event source - * @arg TIM_EVENTSOURCE_CC4: Timer Capture Compare 4 Event source - * @arg TIM_EVENTSOURCE_COM: Timer COM event source - * @arg TIM_EVENTSOURCE_TRIGGER: Timer Trigger Event source - * @arg TIM_EVENTSOURCE_BREAK: Timer Break event source - * @note Basic timers can only generate an update event. - * @note TIM_EVENTSOURCE_COM is relevant only with advanced timer instances. - * @note TIM_EVENTSOURCE_BREAK are relevant only for timer instances - * supporting a break input. - * @retval HAL status - */ - -HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - assert_param(IS_TIM_EVENT_SOURCE(EventSource)); - - /* Process Locked */ - __HAL_LOCK(htim); - - /* Change the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Set the event sources */ - htim->Instance->EGR = EventSource; - - /* Change the TIM state */ - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Configures the OCRef clear feature - * @param htim TIM handle - * @param sClearInputConfig pointer to a TIM_ClearInputConfigTypeDef structure that - * contains the OCREF clear feature and parameters for the TIM peripheral. - * @param Channel specifies the TIM Channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @arg TIM_CHANNEL_4: TIM Channel 4 - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, - TIM_ClearInputConfigTypeDef *sClearInputConfig, - uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_OCXREF_CLEAR_INSTANCE(htim->Instance)); - assert_param(IS_TIM_CLEARINPUT_SOURCE(sClearInputConfig->ClearInputSource)); - - /* Process Locked */ - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - switch (sClearInputConfig->ClearInputSource) - { - case TIM_CLEARINPUTSOURCE_NONE: - { - /* Clear the OCREF clear selection bit and the the ETR Bits */ - CLEAR_BIT(htim->Instance->SMCR, (TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP)); - break; - } - - case TIM_CLEARINPUTSOURCE_ETR: - { - /* Check the parameters */ - assert_param(IS_TIM_CLEARINPUT_POLARITY(sClearInputConfig->ClearInputPolarity)); - assert_param(IS_TIM_CLEARINPUT_PRESCALER(sClearInputConfig->ClearInputPrescaler)); - assert_param(IS_TIM_CLEARINPUT_FILTER(sClearInputConfig->ClearInputFilter)); - - /* When OCRef clear feature is used with ETR source, ETR prescaler must be off */ - if (sClearInputConfig->ClearInputPrescaler != TIM_CLEARINPUTPRESCALER_DIV1) - { - htim->State = HAL_TIM_STATE_READY; - __HAL_UNLOCK(htim); - return HAL_ERROR; - } - - TIM_ETR_SetConfig(htim->Instance, - sClearInputConfig->ClearInputPrescaler, - sClearInputConfig->ClearInputPolarity, - sClearInputConfig->ClearInputFilter); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - switch (Channel) - { - case TIM_CHANNEL_1: - { - if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) - { - /* Enable the OCREF clear feature for Channel 1 */ - SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE); - } - else - { - /* Disable the OCREF clear feature for Channel 1 */ - CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC1CE); - } - break; - } - case TIM_CHANNEL_2: - { - if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) - { - /* Enable the OCREF clear feature for Channel 2 */ - SET_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE); - } - else - { - /* Disable the OCREF clear feature for Channel 2 */ - CLEAR_BIT(htim->Instance->CCMR1, TIM_CCMR1_OC2CE); - } - break; - } - case TIM_CHANNEL_3: - { - if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) - { - /* Enable the OCREF clear feature for Channel 3 */ - SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE); - } - else - { - /* Disable the OCREF clear feature for Channel 3 */ - CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC3CE); - } - break; - } - case TIM_CHANNEL_4: - { - if (sClearInputConfig->ClearInputState != (uint32_t)DISABLE) - { - /* Enable the OCREF clear feature for Channel 4 */ - SET_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE); - } - else - { - /* Disable the OCREF clear feature for Channel 4 */ - CLEAR_BIT(htim->Instance->CCMR2, TIM_CCMR2_OC4CE); - } - break; - } - default: - break; - } - } - - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Configures the clock source to be used - * @param htim TIM handle - * @param sClockSourceConfig pointer to a TIM_ClockConfigTypeDef structure that - * contains the clock source information for the TIM peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Process Locked */ - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Check the parameters */ - assert_param(IS_TIM_CLOCKSOURCE(sClockSourceConfig->ClockSource)); - - /* Reset the SMS, TS, ECE, ETPS and ETRF bits */ - tmpsmcr = htim->Instance->SMCR; - tmpsmcr &= ~(TIM_SMCR_SMS | TIM_SMCR_TS); - tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); - htim->Instance->SMCR = tmpsmcr; - - switch (sClockSourceConfig->ClockSource) - { - case TIM_CLOCKSOURCE_INTERNAL: - { - assert_param(IS_TIM_INSTANCE(htim->Instance)); - break; - } - - case TIM_CLOCKSOURCE_ETRMODE1: - { - /* Check whether or not the timer instance supports external trigger input mode 1 (ETRF)*/ - assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance)); - - /* Check ETR input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler)); - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - /* Configure the ETR Clock source */ - TIM_ETR_SetConfig(htim->Instance, - sClockSourceConfig->ClockPrescaler, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - - /* Select the External clock mode1 and the ETRF trigger */ - tmpsmcr = htim->Instance->SMCR; - tmpsmcr |= (TIM_SLAVEMODE_EXTERNAL1 | TIM_CLOCKSOURCE_ETRMODE1); - /* Write to TIMx SMCR */ - htim->Instance->SMCR = tmpsmcr; - break; - } - - case TIM_CLOCKSOURCE_ETRMODE2: - { - /* Check whether or not the timer instance supports external trigger input mode 2 (ETRF)*/ - assert_param(IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(htim->Instance)); - - /* Check ETR input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPRESCALER(sClockSourceConfig->ClockPrescaler)); - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - /* Configure the ETR Clock source */ - TIM_ETR_SetConfig(htim->Instance, - sClockSourceConfig->ClockPrescaler, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - /* Enable the External clock mode2 */ - htim->Instance->SMCR |= TIM_SMCR_ECE; - break; - } - - case TIM_CLOCKSOURCE_TI1: - { - /* Check whether or not the timer instance supports external clock mode 1 */ - assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); - - /* Check TI1 input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - TIM_TI1_ConfigInputStage(htim->Instance, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1); - break; - } - - case TIM_CLOCKSOURCE_TI2: - { - /* Check whether or not the timer instance supports external clock mode 1 (ETRF)*/ - assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); - - /* Check TI2 input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - TIM_TI2_ConfigInputStage(htim->Instance, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI2); - break; - } - - case TIM_CLOCKSOURCE_TI1ED: - { - /* Check whether or not the timer instance supports external clock mode 1 */ - assert_param(IS_TIM_CLOCKSOURCE_TIX_INSTANCE(htim->Instance)); - - /* Check TI1 input conditioning related parameters */ - assert_param(IS_TIM_CLOCKPOLARITY(sClockSourceConfig->ClockPolarity)); - assert_param(IS_TIM_CLOCKFILTER(sClockSourceConfig->ClockFilter)); - - TIM_TI1_ConfigInputStage(htim->Instance, - sClockSourceConfig->ClockPolarity, - sClockSourceConfig->ClockFilter); - TIM_ITRx_SetConfig(htim->Instance, TIM_CLOCKSOURCE_TI1ED); - break; - } - - case TIM_CLOCKSOURCE_ITR0: - case TIM_CLOCKSOURCE_ITR1: - case TIM_CLOCKSOURCE_ITR2: - case TIM_CLOCKSOURCE_ITR3: - { - /* Check whether or not the timer instance supports internal trigger input */ - assert_param(IS_TIM_CLOCKSOURCE_ITRX_INSTANCE(htim->Instance)); - - TIM_ITRx_SetConfig(htim->Instance, sClockSourceConfig->ClockSource); - break; - } - - default: - status = HAL_ERROR; - break; - } - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Selects the signal connected to the TI1 input: direct from CH1_input - * or a XOR combination between CH1_input, CH2_input & CH3_input - * @param htim TIM handle. - * @param TI1_Selection Indicate whether or not channel 1 is connected to the - * output of a XOR gate. - * This parameter can be one of the following values: - * @arg TIM_TI1SELECTION_CH1: The TIMx_CH1 pin is connected to TI1 input - * @arg TIM_TI1SELECTION_XORCOMBINATION: The TIMx_CH1, CH2 and CH3 - * pins are connected to the TI1 input (XOR combination) - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection) -{ - uint32_t tmpcr2; - - /* Check the parameters */ - assert_param(IS_TIM_XOR_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TI1SELECTION(TI1_Selection)); - - /* Get the TIMx CR2 register value */ - tmpcr2 = htim->Instance->CR2; - - /* Reset the TI1 selection */ - tmpcr2 &= ~TIM_CR2_TI1S; - - /* Set the TI1 selection */ - tmpcr2 |= TI1_Selection; - - /* Write to TIMxCR2 */ - htim->Instance->CR2 = tmpcr2; - - return HAL_OK; -} - -/** - * @brief Configures the TIM in Slave mode - * @param htim TIM handle. - * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that - * contains the selected trigger (internal trigger input, filtered - * timer input or external trigger input) and the Slave mode - * (Disable, Reset, Gated, Trigger, External clock mode 1). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig) -{ - /* Check the parameters */ - assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance)); - assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode)); - assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger)); - - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK) - { - htim->State = HAL_TIM_STATE_READY; - __HAL_UNLOCK(htim); - return HAL_ERROR; - } - - /* Disable Trigger Interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_TRIGGER); - - /* Disable Trigger DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER); - - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configures the TIM in Slave mode in interrupt mode - * @param htim TIM handle. - * @param sSlaveConfig pointer to a TIM_SlaveConfigTypeDef structure that - * contains the selected trigger (internal trigger input, filtered - * timer input or external trigger input) and the Slave mode - * (Disable, Reset, Gated, Trigger, External clock mode 1). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, - TIM_SlaveConfigTypeDef *sSlaveConfig) -{ - /* Check the parameters */ - assert_param(IS_TIM_SLAVE_INSTANCE(htim->Instance)); - assert_param(IS_TIM_SLAVE_MODE(sSlaveConfig->SlaveMode)); - assert_param(IS_TIM_TRIGGER_SELECTION(sSlaveConfig->InputTrigger)); - - __HAL_LOCK(htim); - - htim->State = HAL_TIM_STATE_BUSY; - - if (TIM_SlaveTimer_SetConfig(htim, sSlaveConfig) != HAL_OK) - { - htim->State = HAL_TIM_STATE_READY; - __HAL_UNLOCK(htim); - return HAL_ERROR; - } - - /* Enable Trigger Interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_TRIGGER); - - /* Disable Trigger DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_TRIGGER); - - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Read the captured value from Capture Compare unit - * @param htim TIM handle. - * @param Channel TIM Channels to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval Captured value - */ -uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpreg = 0U; - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - - /* Return the capture 1 value */ - tmpreg = htim->Instance->CCR1; - - break; - } - case TIM_CHANNEL_2: - { - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - - /* Return the capture 2 value */ - tmpreg = htim->Instance->CCR2; - - break; - } - - case TIM_CHANNEL_3: - { - /* Check the parameters */ - assert_param(IS_TIM_CC3_INSTANCE(htim->Instance)); - - /* Return the capture 3 value */ - tmpreg = htim->Instance->CCR3; - - break; - } - - case TIM_CHANNEL_4: - { - /* Check the parameters */ - assert_param(IS_TIM_CC4_INSTANCE(htim->Instance)); - - /* Return the capture 4 value */ - tmpreg = htim->Instance->CCR4; - - break; - } - - default: - break; - } - - return tmpreg; -} - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions - * @brief TIM Callbacks functions - * -@verbatim - ============================================================================== - ##### TIM Callbacks functions ##### - ============================================================================== - [..] - This section provides TIM callback functions: - (+) TIM Period elapsed callback - (+) TIM Output Compare callback - (+) TIM Input capture callback - (+) TIM Trigger callback - (+) TIM Error callback - -@endverbatim - * @{ - */ - -/** - * @brief Period elapsed callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PeriodElapsedCallback could be implemented in the user file - */ -} - -/** - * @brief Period elapsed half complete callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PeriodElapsedHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Output Compare callback in non-blocking mode - * @param htim TIM OC handle - * @retval None - */ -__weak void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_OC_DelayElapsedCallback could be implemented in the user file - */ -} - -/** - * @brief Input Capture callback in non-blocking mode - * @param htim TIM IC handle - * @retval None - */ -__weak void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_IC_CaptureCallback could be implemented in the user file - */ -} - -/** - * @brief Input Capture half complete callback in non-blocking mode - * @param htim TIM IC handle - * @retval None - */ -__weak void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_IC_CaptureHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief PWM Pulse finished callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PWM_PulseFinishedCallback could be implemented in the user file - */ -} - -/** - * @brief PWM Pulse finished half complete callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_PWM_PulseFinishedHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Hall Trigger detection callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_TriggerCallback could be implemented in the user file - */ -} - -/** - * @brief Hall Trigger detection half complete callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_TriggerHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Timer error callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIM_ErrorCallback could be implemented in the user file - */ -} - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User TIM callback to be used instead of the weak predefined callback - * @param htim tim handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID - * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID - * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID - * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID - * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID - * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID - * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID - * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID - * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID - * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID - * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID - * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID - * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID - * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID - * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID - * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID - * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID - * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID - * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID - * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID - * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID - * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID - * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID - * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID - * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID - * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID - * @param pCallback pointer to the callback function - * @retval status - */ -HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID, - pTIM_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(htim); - - if (htim->State == HAL_TIM_STATE_READY) - { - switch (CallbackID) - { - case HAL_TIM_BASE_MSPINIT_CB_ID : - htim->Base_MspInitCallback = pCallback; - break; - - case HAL_TIM_BASE_MSPDEINIT_CB_ID : - htim->Base_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_IC_MSPINIT_CB_ID : - htim->IC_MspInitCallback = pCallback; - break; - - case HAL_TIM_IC_MSPDEINIT_CB_ID : - htim->IC_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_OC_MSPINIT_CB_ID : - htim->OC_MspInitCallback = pCallback; - break; - - case HAL_TIM_OC_MSPDEINIT_CB_ID : - htim->OC_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_PWM_MSPINIT_CB_ID : - htim->PWM_MspInitCallback = pCallback; - break; - - case HAL_TIM_PWM_MSPDEINIT_CB_ID : - htim->PWM_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : - htim->OnePulse_MspInitCallback = pCallback; - break; - - case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : - htim->OnePulse_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_ENCODER_MSPINIT_CB_ID : - htim->Encoder_MspInitCallback = pCallback; - break; - - case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : - htim->Encoder_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : - htim->HallSensor_MspInitCallback = pCallback; - break; - - case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : - htim->HallSensor_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_PERIOD_ELAPSED_CB_ID : - htim->PeriodElapsedCallback = pCallback; - break; - - case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID : - htim->PeriodElapsedHalfCpltCallback = pCallback; - break; - - case HAL_TIM_TRIGGER_CB_ID : - htim->TriggerCallback = pCallback; - break; - - case HAL_TIM_TRIGGER_HALF_CB_ID : - htim->TriggerHalfCpltCallback = pCallback; - break; - - case HAL_TIM_IC_CAPTURE_CB_ID : - htim->IC_CaptureCallback = pCallback; - break; - - case HAL_TIM_IC_CAPTURE_HALF_CB_ID : - htim->IC_CaptureHalfCpltCallback = pCallback; - break; - - case HAL_TIM_OC_DELAY_ELAPSED_CB_ID : - htim->OC_DelayElapsedCallback = pCallback; - break; - - case HAL_TIM_PWM_PULSE_FINISHED_CB_ID : - htim->PWM_PulseFinishedCallback = pCallback; - break; - - case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID : - htim->PWM_PulseFinishedHalfCpltCallback = pCallback; - break; - - case HAL_TIM_ERROR_CB_ID : - htim->ErrorCallback = pCallback; - break; - - case HAL_TIM_COMMUTATION_CB_ID : - htim->CommutationCallback = pCallback; - break; - - case HAL_TIM_COMMUTATION_HALF_CB_ID : - htim->CommutationHalfCpltCallback = pCallback; - break; - - case HAL_TIM_BREAK_CB_ID : - htim->BreakCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (htim->State == HAL_TIM_STATE_RESET) - { - switch (CallbackID) - { - case HAL_TIM_BASE_MSPINIT_CB_ID : - htim->Base_MspInitCallback = pCallback; - break; - - case HAL_TIM_BASE_MSPDEINIT_CB_ID : - htim->Base_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_IC_MSPINIT_CB_ID : - htim->IC_MspInitCallback = pCallback; - break; - - case HAL_TIM_IC_MSPDEINIT_CB_ID : - htim->IC_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_OC_MSPINIT_CB_ID : - htim->OC_MspInitCallback = pCallback; - break; - - case HAL_TIM_OC_MSPDEINIT_CB_ID : - htim->OC_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_PWM_MSPINIT_CB_ID : - htim->PWM_MspInitCallback = pCallback; - break; - - case HAL_TIM_PWM_MSPDEINIT_CB_ID : - htim->PWM_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : - htim->OnePulse_MspInitCallback = pCallback; - break; - - case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : - htim->OnePulse_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_ENCODER_MSPINIT_CB_ID : - htim->Encoder_MspInitCallback = pCallback; - break; - - case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : - htim->Encoder_MspDeInitCallback = pCallback; - break; - - case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : - htim->HallSensor_MspInitCallback = pCallback; - break; - - case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : - htim->HallSensor_MspDeInitCallback = pCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return status; -} - -/** - * @brief Unregister a TIM callback - * TIM callback is redirected to the weak predefined callback - * @param htim tim handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_TIM_BASE_MSPINIT_CB_ID Base MspInit Callback ID - * @arg @ref HAL_TIM_BASE_MSPDEINIT_CB_ID Base MspDeInit Callback ID - * @arg @ref HAL_TIM_IC_MSPINIT_CB_ID IC MspInit Callback ID - * @arg @ref HAL_TIM_IC_MSPDEINIT_CB_ID IC MspDeInit Callback ID - * @arg @ref HAL_TIM_OC_MSPINIT_CB_ID OC MspInit Callback ID - * @arg @ref HAL_TIM_OC_MSPDEINIT_CB_ID OC MspDeInit Callback ID - * @arg @ref HAL_TIM_PWM_MSPINIT_CB_ID PWM MspInit Callback ID - * @arg @ref HAL_TIM_PWM_MSPDEINIT_CB_ID PWM MspDeInit Callback ID - * @arg @ref HAL_TIM_ONE_PULSE_MSPINIT_CB_ID One Pulse MspInit Callback ID - * @arg @ref HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID One Pulse MspDeInit Callback ID - * @arg @ref HAL_TIM_ENCODER_MSPINIT_CB_ID Encoder MspInit Callback ID - * @arg @ref HAL_TIM_ENCODER_MSPDEINIT_CB_ID Encoder MspDeInit Callback ID - * @arg @ref HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID Hall Sensor MspInit Callback ID - * @arg @ref HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID Hall Sensor MspDeInit Callback ID - * @arg @ref HAL_TIM_PERIOD_ELAPSED_CB_ID Period Elapsed Callback ID - * @arg @ref HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID Period Elapsed half complete Callback ID - * @arg @ref HAL_TIM_TRIGGER_CB_ID Trigger Callback ID - * @arg @ref HAL_TIM_TRIGGER_HALF_CB_ID Trigger half complete Callback ID - * @arg @ref HAL_TIM_IC_CAPTURE_CB_ID Input Capture Callback ID - * @arg @ref HAL_TIM_IC_CAPTURE_HALF_CB_ID Input Capture half complete Callback ID - * @arg @ref HAL_TIM_OC_DELAY_ELAPSED_CB_ID Output Compare Delay Elapsed Callback ID - * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_CB_ID PWM Pulse Finished Callback ID - * @arg @ref HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID PWM Pulse Finished half complete Callback ID - * @arg @ref HAL_TIM_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_TIM_COMMUTATION_CB_ID Commutation Callback ID - * @arg @ref HAL_TIM_COMMUTATION_HALF_CB_ID Commutation half complete Callback ID - * @arg @ref HAL_TIM_BREAK_CB_ID Break Callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(htim); - - if (htim->State == HAL_TIM_STATE_READY) - { - switch (CallbackID) - { - case HAL_TIM_BASE_MSPINIT_CB_ID : - /* Legacy weak Base MspInit Callback */ - htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; - break; - - case HAL_TIM_BASE_MSPDEINIT_CB_ID : - /* Legacy weak Base Msp DeInit Callback */ - htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; - break; - - case HAL_TIM_IC_MSPINIT_CB_ID : - /* Legacy weak IC Msp Init Callback */ - htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; - break; - - case HAL_TIM_IC_MSPDEINIT_CB_ID : - /* Legacy weak IC Msp DeInit Callback */ - htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; - break; - - case HAL_TIM_OC_MSPINIT_CB_ID : - /* Legacy weak OC Msp Init Callback */ - htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; - break; - - case HAL_TIM_OC_MSPDEINIT_CB_ID : - /* Legacy weak OC Msp DeInit Callback */ - htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; - break; - - case HAL_TIM_PWM_MSPINIT_CB_ID : - /* Legacy weak PWM Msp Init Callback */ - htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; - break; - - case HAL_TIM_PWM_MSPDEINIT_CB_ID : - /* Legacy weak PWM Msp DeInit Callback */ - htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; - break; - - case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : - /* Legacy weak One Pulse Msp Init Callback */ - htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; - break; - - case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : - /* Legacy weak One Pulse Msp DeInit Callback */ - htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; - break; - - case HAL_TIM_ENCODER_MSPINIT_CB_ID : - /* Legacy weak Encoder Msp Init Callback */ - htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; - break; - - case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : - /* Legacy weak Encoder Msp DeInit Callback */ - htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; - break; - - case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : - /* Legacy weak Hall Sensor Msp Init Callback */ - htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; - break; - - case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : - /* Legacy weak Hall Sensor Msp DeInit Callback */ - htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; - break; - - case HAL_TIM_PERIOD_ELAPSED_CB_ID : - /* Legacy weak Period Elapsed Callback */ - htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback; - break; - - case HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID : - /* Legacy weak Period Elapsed half complete Callback */ - htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback; - break; - - case HAL_TIM_TRIGGER_CB_ID : - /* Legacy weak Trigger Callback */ - htim->TriggerCallback = HAL_TIM_TriggerCallback; - break; - - case HAL_TIM_TRIGGER_HALF_CB_ID : - /* Legacy weak Trigger half complete Callback */ - htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback; - break; - - case HAL_TIM_IC_CAPTURE_CB_ID : - /* Legacy weak IC Capture Callback */ - htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback; - break; - - case HAL_TIM_IC_CAPTURE_HALF_CB_ID : - /* Legacy weak IC Capture half complete Callback */ - htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback; - break; - - case HAL_TIM_OC_DELAY_ELAPSED_CB_ID : - /* Legacy weak OC Delay Elapsed Callback */ - htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback; - break; - - case HAL_TIM_PWM_PULSE_FINISHED_CB_ID : - /* Legacy weak PWM Pulse Finished Callback */ - htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback; - break; - - case HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID : - /* Legacy weak PWM Pulse Finished half complete Callback */ - htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback; - break; - - case HAL_TIM_ERROR_CB_ID : - /* Legacy weak Error Callback */ - htim->ErrorCallback = HAL_TIM_ErrorCallback; - break; - - case HAL_TIM_COMMUTATION_CB_ID : - /* Legacy weak Commutation Callback */ - htim->CommutationCallback = HAL_TIMEx_CommutCallback; - break; - - case HAL_TIM_COMMUTATION_HALF_CB_ID : - /* Legacy weak Commutation half complete Callback */ - htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback; - break; - - case HAL_TIM_BREAK_CB_ID : - /* Legacy weak Break Callback */ - htim->BreakCallback = HAL_TIMEx_BreakCallback; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (htim->State == HAL_TIM_STATE_RESET) - { - switch (CallbackID) - { - case HAL_TIM_BASE_MSPINIT_CB_ID : - /* Legacy weak Base MspInit Callback */ - htim->Base_MspInitCallback = HAL_TIM_Base_MspInit; - break; - - case HAL_TIM_BASE_MSPDEINIT_CB_ID : - /* Legacy weak Base Msp DeInit Callback */ - htim->Base_MspDeInitCallback = HAL_TIM_Base_MspDeInit; - break; - - case HAL_TIM_IC_MSPINIT_CB_ID : - /* Legacy weak IC Msp Init Callback */ - htim->IC_MspInitCallback = HAL_TIM_IC_MspInit; - break; - - case HAL_TIM_IC_MSPDEINIT_CB_ID : - /* Legacy weak IC Msp DeInit Callback */ - htim->IC_MspDeInitCallback = HAL_TIM_IC_MspDeInit; - break; - - case HAL_TIM_OC_MSPINIT_CB_ID : - /* Legacy weak OC Msp Init Callback */ - htim->OC_MspInitCallback = HAL_TIM_OC_MspInit; - break; - - case HAL_TIM_OC_MSPDEINIT_CB_ID : - /* Legacy weak OC Msp DeInit Callback */ - htim->OC_MspDeInitCallback = HAL_TIM_OC_MspDeInit; - break; - - case HAL_TIM_PWM_MSPINIT_CB_ID : - /* Legacy weak PWM Msp Init Callback */ - htim->PWM_MspInitCallback = HAL_TIM_PWM_MspInit; - break; - - case HAL_TIM_PWM_MSPDEINIT_CB_ID : - /* Legacy weak PWM Msp DeInit Callback */ - htim->PWM_MspDeInitCallback = HAL_TIM_PWM_MspDeInit; - break; - - case HAL_TIM_ONE_PULSE_MSPINIT_CB_ID : - /* Legacy weak One Pulse Msp Init Callback */ - htim->OnePulse_MspInitCallback = HAL_TIM_OnePulse_MspInit; - break; - - case HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID : - /* Legacy weak One Pulse Msp DeInit Callback */ - htim->OnePulse_MspDeInitCallback = HAL_TIM_OnePulse_MspDeInit; - break; - - case HAL_TIM_ENCODER_MSPINIT_CB_ID : - /* Legacy weak Encoder Msp Init Callback */ - htim->Encoder_MspInitCallback = HAL_TIM_Encoder_MspInit; - break; - - case HAL_TIM_ENCODER_MSPDEINIT_CB_ID : - /* Legacy weak Encoder Msp DeInit Callback */ - htim->Encoder_MspDeInitCallback = HAL_TIM_Encoder_MspDeInit; - break; - - case HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID : - /* Legacy weak Hall Sensor Msp Init Callback */ - htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; - break; - - case HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID : - /* Legacy weak Hall Sensor Msp DeInit Callback */ - htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; - break; - - default : - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return status; -} -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions - * @brief TIM Peripheral State functions - * -@verbatim - ============================================================================== - ##### Peripheral State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the TIM Base handle state. - * @param htim TIM Base handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM OC handle state. - * @param htim TIM Output Compare handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM PWM handle state. - * @param htim TIM handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM Input Capture handle state. - * @param htim TIM IC handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM One Pulse Mode handle state. - * @param htim TIM OPM handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM Encoder Mode handle state. - * @param htim TIM Encoder Interface handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return the TIM Encoder Mode handle state. - * @param htim TIM handle - * @retval Active channel - */ -HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim) -{ - return htim->Channel; -} - -/** - * @brief Return actual state of the TIM channel. - * @param htim TIM handle - * @param Channel TIM Channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @arg TIM_CHANNEL_4: TIM Channel 4 - * @arg TIM_CHANNEL_5: TIM Channel 5 - * @arg TIM_CHANNEL_6: TIM Channel 6 - * @retval TIM Channel state - */ -HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_TIM_ChannelStateTypeDef channel_state; - - /* Check the parameters */ - assert_param(IS_TIM_CCX_INSTANCE(htim->Instance, Channel)); - - channel_state = TIM_CHANNEL_STATE_GET(htim, Channel); - - return channel_state; -} - -/** - * @brief Return actual state of a DMA burst operation. - * @param htim TIM handle - * @retval DMA burst state - */ -HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_DMABURST_INSTANCE(htim->Instance)); - - return htim->DMABurstState; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup TIM_Private_Functions TIM Private Functions - * @{ - */ - -/** - * @brief TIM DMA error callback - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIM_DMAError(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - htim->State = HAL_TIM_STATE_READY; - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->ErrorCallback(htim); -#else - HAL_TIM_ErrorCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Delay Pulse complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMADelayPulseCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - } - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Delay Pulse half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PWM_PulseFinishedHalfCpltCallback(htim); -#else - HAL_TIM_PWM_PulseFinishedHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Capture complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - } - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureCallback(htim); -#else - HAL_TIM_IC_CaptureCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Capture half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->IC_CaptureHalfCpltCallback(htim); -#else - HAL_TIM_IC_CaptureHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA Period Elapse complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMAPeriodElapsedCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (htim->hdma[TIM_DMA_ID_UPDATE]->Init.Mode == DMA_NORMAL) - { - htim->State = HAL_TIM_STATE_READY; - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PeriodElapsedCallback(htim); -#else - HAL_TIM_PeriodElapsedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief TIM DMA Period Elapse half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMAPeriodElapsedHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PeriodElapsedHalfCpltCallback(htim); -#else - HAL_TIM_PeriodElapsedHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief TIM DMA Trigger callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMATriggerCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (htim->hdma[TIM_DMA_ID_TRIGGER]->Init.Mode == DMA_NORMAL) - { - htim->State = HAL_TIM_STATE_READY; - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->TriggerCallback(htim); -#else - HAL_TIM_TriggerCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief TIM DMA Trigger half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMATriggerHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->TriggerHalfCpltCallback(htim); -#else - HAL_TIM_TriggerHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief Time Base configuration - * @param TIMx TIM peripheral - * @param Structure TIM Base configuration structure - * @retval None - */ -void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure) -{ - uint32_t tmpcr1; - tmpcr1 = TIMx->CR1; - - /* Set TIM Time Base Unit parameters ---------------------------------------*/ - if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) - { - /* Select the Counter Mode */ - tmpcr1 &= ~(TIM_CR1_DIR | TIM_CR1_CMS); - tmpcr1 |= Structure->CounterMode; - } - - if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) - { - /* Set the clock division */ - tmpcr1 &= ~TIM_CR1_CKD; - tmpcr1 |= (uint32_t)Structure->ClockDivision; - } - - /* Set the auto-reload preload */ - MODIFY_REG(tmpcr1, TIM_CR1_ARPE, Structure->AutoReloadPreload); - - TIMx->CR1 = tmpcr1; - - /* Set the Autoreload value */ - TIMx->ARR = (uint32_t)Structure->Period ; - - /* Set the Prescaler value */ - TIMx->PSC = Structure->Prescaler; - - if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) - { - /* Set the Repetition Counter value */ - TIMx->RCR = Structure->RepetitionCounter; - } - - /* Generate an update event to reload the Prescaler - and the repetition counter (only for advanced timer) value immediately */ - TIMx->EGR = TIM_EGR_UG; -} - -/** - * @brief Timer Output Compare 1 configuration - * @param TIMx to select the TIM peripheral - * @param OC_Config The output configuration structure - * @retval None - */ -static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) -{ - uint32_t tmpccmrx; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Disable the Channel 1: Reset the CC1E Bit */ - TIMx->CCER &= ~TIM_CCER_CC1E; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR1 register value */ - tmpccmrx = TIMx->CCMR1; - - /* Reset the Output Compare Mode Bits */ - tmpccmrx &= ~TIM_CCMR1_OC1M; - tmpccmrx &= ~TIM_CCMR1_CC1S; - /* Select the Output Compare Mode */ - tmpccmrx |= OC_Config->OCMode; - - /* Reset the Output Polarity level */ - tmpccer &= ~TIM_CCER_CC1P; - /* Set the Output Compare Polarity */ - tmpccer |= OC_Config->OCPolarity; - - if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_1)) - { - /* Check parameters */ - assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); - - /* Reset the Output N Polarity level */ - tmpccer &= ~TIM_CCER_CC1NP; - /* Set the Output N Polarity */ - tmpccer |= OC_Config->OCNPolarity; - /* Reset the Output N State */ - tmpccer &= ~TIM_CCER_CC1NE; - } - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - /* Check parameters */ - assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); - - /* Reset the Output Compare and Output Compare N IDLE State */ - tmpcr2 &= ~TIM_CR2_OIS1; - tmpcr2 &= ~TIM_CR2_OIS1N; - /* Set the Output Idle state */ - tmpcr2 |= OC_Config->OCIdleState; - /* Set the Output N Idle state */ - tmpcr2 |= OC_Config->OCNIdleState; - } - - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR1 = OC_Config->Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Timer Output Compare 2 configuration - * @param TIMx to select the TIM peripheral - * @param OC_Config The output configuration structure - * @retval None - */ -void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) -{ - uint32_t tmpccmrx; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= ~TIM_CCER_CC2E; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR1 register value */ - tmpccmrx = TIMx->CCMR1; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= ~TIM_CCMR1_OC2M; - tmpccmrx &= ~TIM_CCMR1_CC2S; - - /* Select the Output Compare Mode */ - tmpccmrx |= (OC_Config->OCMode << 8U); - - /* Reset the Output Polarity level */ - tmpccer &= ~TIM_CCER_CC2P; - /* Set the Output Compare Polarity */ - tmpccer |= (OC_Config->OCPolarity << 4U); - - if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_2)) - { - assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); - - /* Reset the Output N Polarity level */ - tmpccer &= ~TIM_CCER_CC2NP; - /* Set the Output N Polarity */ - tmpccer |= (OC_Config->OCNPolarity << 4U); - /* Reset the Output N State */ - tmpccer &= ~TIM_CCER_CC2NE; - - } - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - /* Check parameters */ - assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); - - /* Reset the Output Compare and Output Compare N IDLE State */ - tmpcr2 &= ~TIM_CR2_OIS2; - tmpcr2 &= ~TIM_CR2_OIS2N; - /* Set the Output Idle state */ - tmpcr2 |= (OC_Config->OCIdleState << 2U); - /* Set the Output N Idle state */ - tmpcr2 |= (OC_Config->OCNIdleState << 2U); - } - - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR2 = OC_Config->Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Timer Output Compare 3 configuration - * @param TIMx to select the TIM peripheral - * @param OC_Config The output configuration structure - * @retval None - */ -static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) -{ - uint32_t tmpccmrx; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Disable the Channel 3: Reset the CC2E Bit */ - TIMx->CCER &= ~TIM_CCER_CC3E; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR2 register value */ - tmpccmrx = TIMx->CCMR2; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= ~TIM_CCMR2_OC3M; - tmpccmrx &= ~TIM_CCMR2_CC3S; - /* Select the Output Compare Mode */ - tmpccmrx |= OC_Config->OCMode; - - /* Reset the Output Polarity level */ - tmpccer &= ~TIM_CCER_CC3P; - /* Set the Output Compare Polarity */ - tmpccer |= (OC_Config->OCPolarity << 8U); - - if (IS_TIM_CCXN_INSTANCE(TIMx, TIM_CHANNEL_3)) - { - assert_param(IS_TIM_OCN_POLARITY(OC_Config->OCNPolarity)); - - /* Reset the Output N Polarity level */ - tmpccer &= ~TIM_CCER_CC3NP; - /* Set the Output N Polarity */ - tmpccer |= (OC_Config->OCNPolarity << 8U); - /* Reset the Output N State */ - tmpccer &= ~TIM_CCER_CC3NE; - } - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - /* Check parameters */ - assert_param(IS_TIM_OCNIDLE_STATE(OC_Config->OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); - - /* Reset the Output Compare and Output Compare N IDLE State */ - tmpcr2 &= ~TIM_CR2_OIS3; - tmpcr2 &= ~TIM_CR2_OIS3N; - /* Set the Output Idle state */ - tmpcr2 |= (OC_Config->OCIdleState << 4U); - /* Set the Output N Idle state */ - tmpcr2 |= (OC_Config->OCNIdleState << 4U); - } - - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR2 */ - TIMx->CCMR2 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR3 = OC_Config->Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Timer Output Compare 4 configuration - * @param TIMx to select the TIM peripheral - * @param OC_Config The output configuration structure - * @retval None - */ -static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config) -{ - uint32_t tmpccmrx; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Disable the Channel 4: Reset the CC4E Bit */ - TIMx->CCER &= ~TIM_CCER_CC4E; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR2 register value */ - tmpccmrx = TIMx->CCMR2; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= ~TIM_CCMR2_OC4M; - tmpccmrx &= ~TIM_CCMR2_CC4S; - - /* Select the Output Compare Mode */ - tmpccmrx |= (OC_Config->OCMode << 8U); - - /* Reset the Output Polarity level */ - tmpccer &= ~TIM_CCER_CC4P; - /* Set the Output Compare Polarity */ - tmpccer |= (OC_Config->OCPolarity << 12U); - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - /* Check parameters */ - assert_param(IS_TIM_OCIDLE_STATE(OC_Config->OCIdleState)); - - /* Reset the Output Compare IDLE State */ - tmpcr2 &= ~TIM_CR2_OIS4; - - /* Set the Output Idle state */ - tmpcr2 |= (OC_Config->OCIdleState << 6U); - } - - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR2 */ - TIMx->CCMR2 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR4 = OC_Config->Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Slave Timer configuration function - * @param htim TIM handle - * @param sSlaveConfig Slave timer configuration - * @retval None - */ -static HAL_StatusTypeDef TIM_SlaveTimer_SetConfig(TIM_HandleTypeDef *htim, - TIM_SlaveConfigTypeDef *sSlaveConfig) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Get the TIMx SMCR register value */ - tmpsmcr = htim->Instance->SMCR; - - /* Reset the Trigger Selection Bits */ - tmpsmcr &= ~TIM_SMCR_TS; - /* Set the Input Trigger source */ - tmpsmcr |= sSlaveConfig->InputTrigger; - - /* Reset the slave mode Bits */ - tmpsmcr &= ~TIM_SMCR_SMS; - /* Set the slave mode */ - tmpsmcr |= sSlaveConfig->SlaveMode; - - /* Write to TIMx SMCR */ - htim->Instance->SMCR = tmpsmcr; - - /* Configure the trigger prescaler, filter, and polarity */ - switch (sSlaveConfig->InputTrigger) - { - case TIM_TS_ETRF: - { - /* Check the parameters */ - assert_param(IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRIGGERPRESCALER(sSlaveConfig->TriggerPrescaler)); - assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); - assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); - /* Configure the ETR Trigger source */ - TIM_ETR_SetConfig(htim->Instance, - sSlaveConfig->TriggerPrescaler, - sSlaveConfig->TriggerPolarity, - sSlaveConfig->TriggerFilter); - break; - } - - case TIM_TS_TI1F_ED: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); - - if (sSlaveConfig->SlaveMode == TIM_SLAVEMODE_GATED) - { - return HAL_ERROR; - } - - /* Disable the Channel 1: Reset the CC1E Bit */ - tmpccer = htim->Instance->CCER; - htim->Instance->CCER &= ~TIM_CCER_CC1E; - tmpccmr1 = htim->Instance->CCMR1; - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC1F; - tmpccmr1 |= ((sSlaveConfig->TriggerFilter) << 4U); - - /* Write to TIMx CCMR1 and CCER registers */ - htim->Instance->CCMR1 = tmpccmr1; - htim->Instance->CCER = tmpccer; - break; - } - - case TIM_TS_TI1FP1: - { - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); - assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); - - /* Configure TI1 Filter and Polarity */ - TIM_TI1_ConfigInputStage(htim->Instance, - sSlaveConfig->TriggerPolarity, - sSlaveConfig->TriggerFilter); - break; - } - - case TIM_TS_TI2FP2: - { - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRIGGERPOLARITY(sSlaveConfig->TriggerPolarity)); - assert_param(IS_TIM_TRIGGERFILTER(sSlaveConfig->TriggerFilter)); - - /* Configure TI2 Filter and Polarity */ - TIM_TI2_ConfigInputStage(htim->Instance, - sSlaveConfig->TriggerPolarity, - sSlaveConfig->TriggerFilter); - break; - } - - case TIM_TS_ITR0: - case TIM_TS_ITR1: - case TIM_TS_ITR2: - case TIM_TS_ITR3: - { - /* Check the parameter */ - assert_param(IS_TIM_CC2_INSTANCE(htim->Instance)); - break; - } - - default: - status = HAL_ERROR; - break; - } - - return status; -} - -/** - * @brief Configure the TI1 as Input. - * @param TIMx to select the TIM peripheral. - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICSelection specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 1 is selected to be connected to IC1. - * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 1 is selected to be connected to IC2. - * @arg TIM_ICSELECTION_TRC: TIM Input 1 is selected to be connected to TRC. - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI2FP1 - * (on channel2 path) is used as the input signal. Therefore CCMR1 must be - * protected against un-initialized filter and polarity values. - */ -void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Disable the Channel 1: Reset the CC1E Bit */ - TIMx->CCER &= ~TIM_CCER_CC1E; - tmpccmr1 = TIMx->CCMR1; - tmpccer = TIMx->CCER; - - /* Select the Input */ - if (IS_TIM_CC2_INSTANCE(TIMx) != RESET) - { - tmpccmr1 &= ~TIM_CCMR1_CC1S; - tmpccmr1 |= TIM_ICSelection; - } - else - { - tmpccmr1 |= TIM_CCMR1_CC1S_0; - } - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC1F; - tmpccmr1 |= ((TIM_ICFilter << 4U) & TIM_CCMR1_IC1F); - - /* Select the Polarity and set the CC1E Bit */ - tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); - tmpccer |= (TIM_ICPolarity & (TIM_CCER_CC1P | TIM_CCER_CC1NP)); - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the Polarity and Filter for TI1. - * @param TIMx to select the TIM peripheral. - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - */ -static void TIM_TI1_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Disable the Channel 1: Reset the CC1E Bit */ - tmpccer = TIMx->CCER; - TIMx->CCER &= ~TIM_CCER_CC1E; - tmpccmr1 = TIMx->CCMR1; - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC1F; - tmpccmr1 |= (TIM_ICFilter << 4U); - - /* Select the Polarity and set the CC1E Bit */ - tmpccer &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP); - tmpccer |= TIM_ICPolarity; - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI2 as Input. - * @param TIMx to select the TIM peripheral - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICSelection specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 2 is selected to be connected to IC2. - * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 2 is selected to be connected to IC1. - * @arg TIM_ICSELECTION_TRC: TIM Input 2 is selected to be connected to TRC. - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI1FP2 - * (on channel1 path) is used as the input signal. Therefore CCMR1 must be - * protected against un-initialized filter and polarity values. - */ -static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= ~TIM_CCER_CC2E; - tmpccmr1 = TIMx->CCMR1; - tmpccer = TIMx->CCER; - - /* Select the Input */ - tmpccmr1 &= ~TIM_CCMR1_CC2S; - tmpccmr1 |= (TIM_ICSelection << 8U); - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC2F; - tmpccmr1 |= ((TIM_ICFilter << 12U) & TIM_CCMR1_IC2F); - - /* Select the Polarity and set the CC2E Bit */ - tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); - tmpccer |= ((TIM_ICPolarity << 4U) & (TIM_CCER_CC2P | TIM_CCER_CC2NP)); - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1 ; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the Polarity and Filter for TI2. - * @param TIMx to select the TIM peripheral. - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - */ -static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= ~TIM_CCER_CC2E; - tmpccmr1 = TIMx->CCMR1; - tmpccer = TIMx->CCER; - - /* Set the filter */ - tmpccmr1 &= ~TIM_CCMR1_IC2F; - tmpccmr1 |= (TIM_ICFilter << 12U); - - /* Select the Polarity and set the CC2E Bit */ - tmpccer &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP); - tmpccer |= (TIM_ICPolarity << 4U); - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1 ; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI3 as Input. - * @param TIMx to select the TIM peripheral - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICSelection specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 3 is selected to be connected to IC3. - * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 3 is selected to be connected to IC4. - * @arg TIM_ICSELECTION_TRC: TIM Input 3 is selected to be connected to TRC. - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI3FP4 - * (on channel1 path) is used as the input signal. Therefore CCMR2 must be - * protected against un-initialized filter and polarity values. - */ -static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr2; - uint32_t tmpccer; - - /* Disable the Channel 3: Reset the CC3E Bit */ - TIMx->CCER &= ~TIM_CCER_CC3E; - tmpccmr2 = TIMx->CCMR2; - tmpccer = TIMx->CCER; - - /* Select the Input */ - tmpccmr2 &= ~TIM_CCMR2_CC3S; - tmpccmr2 |= TIM_ICSelection; - - /* Set the filter */ - tmpccmr2 &= ~TIM_CCMR2_IC3F; - tmpccmr2 |= ((TIM_ICFilter << 4U) & TIM_CCMR2_IC3F); - - /* Select the Polarity and set the CC3E Bit */ - tmpccer &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP); - tmpccer |= ((TIM_ICPolarity << 8U) & (TIM_CCER_CC3P | TIM_CCER_CC3NP)); - - /* Write to TIMx CCMR2 and CCER registers */ - TIMx->CCMR2 = tmpccmr2; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI4 as Input. - * @param TIMx to select the TIM peripheral - * @param TIM_ICPolarity The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPOLARITY_RISING - * @arg TIM_ICPOLARITY_FALLING - * @arg TIM_ICPOLARITY_BOTHEDGE - * @param TIM_ICSelection specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSELECTION_DIRECTTI: TIM Input 4 is selected to be connected to IC4. - * @arg TIM_ICSELECTION_INDIRECTTI: TIM Input 4 is selected to be connected to IC3. - * @arg TIM_ICSELECTION_TRC: TIM Input 4 is selected to be connected to TRC. - * @param TIM_ICFilter Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @note TIM_ICFilter and TIM_ICPolarity are not used in INDIRECT mode as TI4FP3 - * (on channel1 path) is used as the input signal. Therefore CCMR2 must be - * protected against un-initialized filter and polarity values. - * @retval None - */ -static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, - uint32_t TIM_ICFilter) -{ - uint32_t tmpccmr2; - uint32_t tmpccer; - - /* Disable the Channel 4: Reset the CC4E Bit */ - TIMx->CCER &= ~TIM_CCER_CC4E; - tmpccmr2 = TIMx->CCMR2; - tmpccer = TIMx->CCER; - - /* Select the Input */ - tmpccmr2 &= ~TIM_CCMR2_CC4S; - tmpccmr2 |= (TIM_ICSelection << 8U); - - /* Set the filter */ - tmpccmr2 &= ~TIM_CCMR2_IC4F; - tmpccmr2 |= ((TIM_ICFilter << 12U) & TIM_CCMR2_IC4F); - - /* Select the Polarity and set the CC4E Bit */ - tmpccer &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP); - tmpccer |= ((TIM_ICPolarity << 12U) & (TIM_CCER_CC4P | TIM_CCER_CC4NP)); - - /* Write to TIMx CCMR2 and CCER registers */ - TIMx->CCMR2 = tmpccmr2; - TIMx->CCER = tmpccer ; -} - -/** - * @brief Selects the Input Trigger source - * @param TIMx to select the TIM peripheral - * @param InputTriggerSource The Input Trigger source. - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal Trigger 0 - * @arg TIM_TS_ITR1: Internal Trigger 1 - * @arg TIM_TS_ITR2: Internal Trigger 2 - * @arg TIM_TS_ITR3: Internal Trigger 3 - * @arg TIM_TS_TI1F_ED: TI1 Edge Detector - * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 - * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 - * @arg TIM_TS_ETRF: External Trigger input - * @retval None - */ -static void TIM_ITRx_SetConfig(TIM_TypeDef *TIMx, uint32_t InputTriggerSource) -{ - uint32_t tmpsmcr; - - /* Get the TIMx SMCR register value */ - tmpsmcr = TIMx->SMCR; - /* Reset the TS Bits */ - tmpsmcr &= ~TIM_SMCR_TS; - /* Set the Input Trigger source and the slave mode*/ - tmpsmcr |= (InputTriggerSource | TIM_SLAVEMODE_EXTERNAL1); - /* Write to TIMx SMCR */ - TIMx->SMCR = tmpsmcr; -} -/** - * @brief Configures the TIMx External Trigger (ETR). - * @param TIMx to select the TIM peripheral - * @param TIM_ExtTRGPrescaler The external Trigger Prescaler. - * This parameter can be one of the following values: - * @arg TIM_ETRPRESCALER_DIV1: ETRP Prescaler OFF. - * @arg TIM_ETRPRESCALER_DIV2: ETRP frequency divided by 2. - * @arg TIM_ETRPRESCALER_DIV4: ETRP frequency divided by 4. - * @arg TIM_ETRPRESCALER_DIV8: ETRP frequency divided by 8. - * @param TIM_ExtTRGPolarity The external Trigger Polarity. - * This parameter can be one of the following values: - * @arg TIM_ETRPOLARITY_INVERTED: active low or falling edge active. - * @arg TIM_ETRPOLARITY_NONINVERTED: active high or rising edge active. - * @param ExtTRGFilter External Trigger Filter. - * This parameter must be a value between 0x00 and 0x0F - * @retval None - */ -void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, - uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter) -{ - uint32_t tmpsmcr; - - tmpsmcr = TIMx->SMCR; - - /* Reset the ETR Bits */ - tmpsmcr &= ~(TIM_SMCR_ETF | TIM_SMCR_ETPS | TIM_SMCR_ECE | TIM_SMCR_ETP); - - /* Set the Prescaler, the Filter value and the Polarity */ - tmpsmcr |= (uint32_t)(TIM_ExtTRGPrescaler | (TIM_ExtTRGPolarity | (ExtTRGFilter << 8U))); - - /* Write to TIMx SMCR */ - TIMx->SMCR = tmpsmcr; -} - -/** - * @brief Enables or disables the TIM Capture Compare Channel x. - * @param TIMx to select the TIM peripheral - * @param Channel specifies the TIM Channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @arg TIM_CHANNEL_4: TIM Channel 4 - * @param ChannelState specifies the TIM Channel CCxE bit new state. - * This parameter can be: TIM_CCx_ENABLE or TIM_CCx_DISABLE. - * @retval None - */ -void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState) -{ - uint32_t tmp; - - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(TIMx)); - assert_param(IS_TIM_CHANNELS(Channel)); - - tmp = TIM_CCER_CC1E << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ - - /* Reset the CCxE Bit */ - TIMx->CCER &= ~tmp; - - /* Set or reset the CCxE Bit */ - TIMx->CCER |= (uint32_t)(ChannelState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ -} - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -/** - * @brief Reset interrupt callbacks to the legacy weak callbacks. - * @param htim pointer to a TIM_HandleTypeDef structure that contains - * the configuration information for TIM module. - * @retval None - */ -void TIM_ResetCallback(TIM_HandleTypeDef *htim) -{ - /* Reset the TIM callback to the legacy weak callbacks */ - htim->PeriodElapsedCallback = HAL_TIM_PeriodElapsedCallback; - htim->PeriodElapsedHalfCpltCallback = HAL_TIM_PeriodElapsedHalfCpltCallback; - htim->TriggerCallback = HAL_TIM_TriggerCallback; - htim->TriggerHalfCpltCallback = HAL_TIM_TriggerHalfCpltCallback; - htim->IC_CaptureCallback = HAL_TIM_IC_CaptureCallback; - htim->IC_CaptureHalfCpltCallback = HAL_TIM_IC_CaptureHalfCpltCallback; - htim->OC_DelayElapsedCallback = HAL_TIM_OC_DelayElapsedCallback; - htim->PWM_PulseFinishedCallback = HAL_TIM_PWM_PulseFinishedCallback; - htim->PWM_PulseFinishedHalfCpltCallback = HAL_TIM_PWM_PulseFinishedHalfCpltCallback; - htim->ErrorCallback = HAL_TIM_ErrorCallback; - htim->CommutationCallback = HAL_TIMEx_CommutCallback; - htim->CommutationHalfCpltCallback = HAL_TIMEx_CommutHalfCpltCallback; - htim->BreakCallback = HAL_TIMEx_BreakCallback; -} -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ - -#endif /* HAL_TIM_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c deleted file mode 100644 index bba44f15c661207..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c +++ /dev/null @@ -1,2429 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim_ex.c - * @author MCD Application Team - * @brief TIM HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Timer Extended peripheral: - * + Time Hall Sensor Interface Initialization - * + Time Hall Sensor Interface Start - * + Time Complementary signal break and dead time configuration - * + Time Master and Slave synchronization configuration - * + Timer remapping capabilities configuration - @verbatim - ============================================================================== - ##### TIMER Extended features ##### - ============================================================================== - [..] - The Timer Extended features include: - (#) Complementary outputs with programmable dead-time for : - (++) Output Compare - (++) PWM generation (Edge and Center-aligned Mode) - (++) One-pulse mode output - (#) Synchronization circuit to control the timer with external signals and to - interconnect several timers together. - (#) Break input to put the timer output signals in reset state or in a known state. - (#) Supports incremental (quadrature) encoder and hall-sensor circuitry for - positioning purposes - - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Initialize the TIM low level resources by implementing the following functions - depending on the selected feature: - (++) Hall Sensor output : HAL_TIMEx_HallSensor_MspInit() - - (#) Initialize the TIM low level resources : - (##) Enable the TIM interface clock using __HAL_RCC_TIMx_CLK_ENABLE(); - (##) TIM pins configuration - (+++) Enable the clock for the TIM GPIOs using the following function: - __HAL_RCC_GPIOx_CLK_ENABLE(); - (+++) Configure these TIM pins in Alternate function mode using HAL_GPIO_Init(); - - (#) The external Clock can be configured, if needed (the default clock is the - internal clock from the APBx), using the following function: - HAL_TIM_ConfigClockSource, the clock configuration should be done before - any start function. - - (#) Configure the TIM in the desired functioning mode using one of the - initialization function of this driver: - (++) HAL_TIMEx_HallSensor_Init() and HAL_TIMEx_ConfigCommutEvent(): to use the - Timer Hall Sensor Interface and the commutation event with the corresponding - Interrupt and DMA request if needed (Note that One Timer is used to interface - with the Hall sensor Interface and another Timer should be used to use - the commutation event). - - (#) Activate the TIM peripheral using one of the start functions: - (++) Complementary Output Compare : HAL_TIMEx_OCN_Start(), HAL_TIMEx_OCN_Start_DMA(), - HAL_TIMEx_OCN_Start_IT() - (++) Complementary PWM generation : HAL_TIMEx_PWMN_Start(), HAL_TIMEx_PWMN_Start_DMA(), - HAL_TIMEx_PWMN_Start_IT() - (++) Complementary One-pulse mode output : HAL_TIMEx_OnePulseN_Start(), HAL_TIMEx_OnePulseN_Start_IT() - (++) Hall Sensor output : HAL_TIMEx_HallSensor_Start(), HAL_TIMEx_HallSensor_Start_DMA(), - HAL_TIMEx_HallSensor_Start_IT(). - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup TIMEx TIMEx - * @brief TIM Extended HAL module driver - * @{ - */ - -#ifdef HAL_TIM_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma); -static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma); -static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState); - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Functions TIM Extended Exported Functions - * @{ - */ - -/** @defgroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions - * @brief Timer Hall Sensor functions - * -@verbatim - ============================================================================== - ##### Timer Hall Sensor functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure TIM HAL Sensor. - (+) De-initialize TIM HAL Sensor. - (+) Start the Hall Sensor Interface. - (+) Stop the Hall Sensor Interface. - (+) Start the Hall Sensor Interface and enable interrupts. - (+) Stop the Hall Sensor Interface and disable interrupts. - (+) Start the Hall Sensor Interface and enable DMA transfers. - (+) Stop the Hall Sensor Interface and disable DMA transfers. - -@endverbatim - * @{ - */ -/** - * @brief Initializes the TIM Hall Sensor Interface and initialize the associated handle. - * @note When the timer instance is initialized in Hall Sensor Interface mode, - * timer channels 1 and channel 2 are reserved and cannot be used for - * other purpose. - * @param htim TIM Hall Sensor Interface handle - * @param sConfig TIM Hall Sensor configuration structure - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig) -{ - TIM_OC_InitTypeDef OC_Config; - - /* Check the TIM handle allocation */ - if (htim == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - assert_param(IS_TIM_COUNTER_MODE(htim->Init.CounterMode)); - assert_param(IS_TIM_CLOCKDIVISION_DIV(htim->Init.ClockDivision)); - assert_param(IS_TIM_AUTORELOAD_PRELOAD(htim->Init.AutoReloadPreload)); - assert_param(IS_TIM_IC_POLARITY(sConfig->IC1Polarity)); - assert_param(IS_TIM_IC_PRESCALER(sConfig->IC1Prescaler)); - assert_param(IS_TIM_IC_FILTER(sConfig->IC1Filter)); - - if (htim->State == HAL_TIM_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - htim->Lock = HAL_UNLOCKED; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - /* Reset interrupt callbacks to legacy week callbacks */ - TIM_ResetCallback(htim); - - if (htim->HallSensor_MspInitCallback == NULL) - { - htim->HallSensor_MspInitCallback = HAL_TIMEx_HallSensor_MspInit; - } - /* Init the low level hardware : GPIO, CLOCK, NVIC */ - htim->HallSensor_MspInitCallback(htim); -#else - /* Init the low level hardware : GPIO, CLOCK, NVIC and DMA */ - HAL_TIMEx_HallSensor_MspInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - } - - /* Set the TIM state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Configure the Time base in the Encoder Mode */ - TIM_Base_SetConfig(htim->Instance, &htim->Init); - - /* Configure the Channel 1 as Input Channel to interface with the three Outputs of the Hall sensor */ - TIM_TI1_SetConfig(htim->Instance, sConfig->IC1Polarity, TIM_ICSELECTION_TRC, sConfig->IC1Filter); - - /* Reset the IC1PSC Bits */ - htim->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC; - /* Set the IC1PSC value */ - htim->Instance->CCMR1 |= sConfig->IC1Prescaler; - - /* Enable the Hall sensor interface (XOR function of the three inputs) */ - htim->Instance->CR2 |= TIM_CR2_TI1S; - - /* Select the TIM_TS_TI1F_ED signal as Input trigger for the TIM */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= TIM_TS_TI1F_ED; - - /* Use the TIM_TS_TI1F_ED signal to reset the TIM counter each edge detection */ - htim->Instance->SMCR &= ~TIM_SMCR_SMS; - htim->Instance->SMCR |= TIM_SLAVEMODE_RESET; - - /* Program channel 2 in PWM 2 mode with the desired Commutation_Delay*/ - OC_Config.OCFastMode = TIM_OCFAST_DISABLE; - OC_Config.OCIdleState = TIM_OCIDLESTATE_RESET; - OC_Config.OCMode = TIM_OCMODE_PWM2; - OC_Config.OCNIdleState = TIM_OCNIDLESTATE_RESET; - OC_Config.OCNPolarity = TIM_OCNPOLARITY_HIGH; - OC_Config.OCPolarity = TIM_OCPOLARITY_HIGH; - OC_Config.Pulse = sConfig->Commutation_Delay; - - TIM_OC2_SetConfig(htim->Instance, &OC_Config); - - /* Select OC2REF as trigger output on TRGO: write the MMS bits in the TIMx_CR2 - register to 101 */ - htim->Instance->CR2 &= ~TIM_CR2_MMS; - htim->Instance->CR2 |= TIM_TRGO_OC2REF; - - /* Initialize the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_READY; - - /* Initialize the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Initialize the TIM state*/ - htim->State = HAL_TIM_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the TIM Hall Sensor interface - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(htim->Instance)); - - htim->State = HAL_TIM_STATE_BUSY; - - /* Disable the TIM Peripheral Clock */ - __HAL_TIM_DISABLE(htim); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - if (htim->HallSensor_MspDeInitCallback == NULL) - { - htim->HallSensor_MspDeInitCallback = HAL_TIMEx_HallSensor_MspDeInit; - } - /* DeInit the low level hardware */ - htim->HallSensor_MspDeInitCallback(htim); -#else - /* DeInit the low level hardware: GPIO, CLOCK, NVIC */ - HAL_TIMEx_HallSensor_MspDeInit(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - /* Change the DMA burst operation state */ - htim->DMABurstState = HAL_DMA_BURST_STATE_RESET; - - /* Change the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_RESET); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_RESET); - - /* Change TIM state */ - htim->State = HAL_TIM_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Initializes the TIM Hall Sensor MSP. - * @param htim TIM Hall Sensor Interface handle - * @retval None - */ -__weak void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_HallSensor_MspInit could be implemented in the user file - */ -} - -/** - * @brief DeInitializes TIM Hall Sensor MSP. - * @param htim TIM Hall Sensor Interface handle - * @retval None - */ -__weak void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_HallSensor_MspDeInit could be implemented in the user file - */ -} - -/** - * @brief Starts the TIM Hall Sensor Interface. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim) -{ - uint32_t tmpsmcr; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Hall sensor Interface. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channels 1, 2 and 3 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Hall Sensor Interface in interrupt mode. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim) -{ - uint32_t tmpsmcr; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the capture compare Interrupts 1 event */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - - /* Enable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Hall Sensor Interface in interrupt mode. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - /* Disable the capture compare Interrupts event */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Hall Sensor Interface in DMA mode. - * @param htim TIM Hall Sensor Interface handle - * @param pData The destination Buffer address. - * @param Length The length of data to be transferred from TIM peripheral to memory. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length) -{ - uint32_t tmpsmcr; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Set the TIM channel state */ - if ((channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY) - || (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_BUSY)) - { - return HAL_BUSY; - } - else if ((channel_1_state == HAL_TIM_CHANNEL_STATE_READY) - && (complementary_channel_1_state == HAL_TIM_CHANNEL_STATE_READY)) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - /* Enable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); - - /* Set the DMA Input Capture 1 Callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMACaptureCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMACaptureHalfCplt; - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAError ; - - /* Enable the DMA stream for Capture 1*/ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)&htim->Instance->CCR1, (uint32_t)pData, Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the capture compare 1 Interrupt */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Hall Sensor Interface in DMA mode. - * @param htim TIM Hall Sensor Interface handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim) -{ - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(htim->Instance)); - - /* Disable the Input Capture channel 1 - (in the Hall Sensor Interface the three possible channels that can be used are TIM_CHANNEL_1, - TIM_CHANNEL_2 and TIM_CHANNEL_3) */ - TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); - - - /* Disable the capture compare Interrupts 1 event */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channel state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions - * @brief Timer Complementary Output Compare functions - * -@verbatim - ============================================================================== - ##### Timer Complementary Output Compare functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Start the Complementary Output Compare/PWM. - (+) Stop the Complementary Output Compare/PWM. - (+) Start the Complementary Output Compare/PWM and enable interrupts. - (+) Stop the Complementary Output Compare/PWM and disable interrupts. - (+) Start the Complementary Output Compare/PWM and enable DMA transfers. - (+) Stop the Complementary Output Compare/PWM and disable DMA transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Starts the TIM Output Compare signal generation on the complementary - * output. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM Output Compare signal generation on the complementary - * output. - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Disable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM Output Compare signal generation in interrupt mode - * on the complementary output. - * @param htim TIM OC handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Output Compare interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Output Compare interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Output Compare interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the TIM Break interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK); - - /* Enable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Output Compare signal generation in interrupt mode - * on the complementary output. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpccer; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Output Compare interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Output Compare interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Output Compare interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the TIM Break interrupt (only if no more channel is active) */ - tmpccer = htim->Instance->CCER; - if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) - { - __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); - } - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM Output Compare signal generation in DMA mode - * on the complementary output. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to TIM peripheral - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Set the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) - { - return HAL_BUSY; - } - else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Output Compare DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Output Compare DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Output Compare DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM Output Compare signal generation in DMA mode - * on the complementary output. - * @param htim TIM Output Compare handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Output Compare DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Output Compare DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Output Compare DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the Capture compare channel N */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions - * @brief Timer Complementary PWM functions - * -@verbatim - ============================================================================== - ##### Timer Complementary PWM functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Start the Complementary PWM. - (+) Stop the Complementary PWM. - (+) Start the Complementary PWM and enable interrupts. - (+) Stop the Complementary PWM and disable interrupts. - (+) Start the Complementary PWM and enable DMA transfers. - (+) Stop the Complementary PWM and disable DMA transfers. - (+) Start the Complementary Input Capture measurement. - (+) Stop the Complementary Input Capture. - (+) Start the Complementary Input Capture and enable interrupts. - (+) Stop the Complementary Input Capture and disable interrupts. - (+) Start the Complementary Input Capture and enable DMA transfers. - (+) Stop the Complementary Input Capture and disable DMA transfers. - (+) Start the Complementary One Pulse generation. - (+) Stop the Complementary One Pulse. - (+) Start the Complementary One Pulse and enable interrupts. - (+) Stop the Complementary One Pulse and disable interrupts. - -@endverbatim - * @{ - */ - -/** - * @brief Starts the PWM signal generation on the complementary output. - * @param htim TIM handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the PWM signal generation on the complementary output. - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Disable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the PWM signal generation in interrupt mode on the - * complementary output. - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Check the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) != HAL_TIM_CHANNEL_STATE_READY) - { - return HAL_ERROR; - } - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Enable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the TIM Break interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_BREAK); - - /* Enable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the PWM signal generation in interrupt mode on the - * complementary output. - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpccer; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the TIM Break interrupt (only if no more channel is active) */ - tmpccer = htim->Instance->CCER; - if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) - { - __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); - } - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @brief Starts the TIM PWM signal generation in DMA mode on the - * complementary output - * @param htim TIM handle - * @param Channel TIM Channel to be enabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @param pData The source Buffer address. - * @param Length The length of data to be transferred from memory to TIM peripheral - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) -{ - HAL_StatusTypeDef status = HAL_OK; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - /* Set the TIM complementary channel state */ - if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_BUSY) - { - return HAL_BUSY; - } - else if (TIM_CHANNEL_N_STATE_GET(htim, Channel) == HAL_TIM_CHANNEL_STATE_READY) - { - if ((pData == NULL) && (Length > 0U)) - { - return HAL_ERROR; - } - else - { - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_BUSY); - } - } - else - { - return HAL_ERROR; - } - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC1]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC1]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC1]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); - break; - } - - case TIM_CHANNEL_2: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC2]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC2]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC2]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); - break; - } - - case TIM_CHANNEL_3: - { - /* Set the DMA compare callbacks */ - htim->hdma[TIM_DMA_ID_CC3]->XferCpltCallback = TIM_DMADelayPulseNCplt; - htim->hdma[TIM_DMA_ID_CC3]->XferHalfCpltCallback = TIM_DMADelayPulseHalfCplt; - - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_CC3]->XferErrorCallback = TIM_DMAErrorCCxN ; - - /* Enable the DMA stream */ - if (HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3, - Length) != HAL_OK) - { - /* Return error status */ - return HAL_ERROR; - } - /* Enable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Enable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Enable the Peripheral, except in trigger mode where enable is automatically done with trigger */ - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - tmpsmcr = htim->Instance->SMCR & TIM_SMCR_SMS; - if (!IS_TIM_SLAVEMODE_TRIGGER_ENABLED(tmpsmcr)) - { - __HAL_TIM_ENABLE(htim); - } - } - else - { - __HAL_TIM_ENABLE(htim); - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Stops the TIM PWM signal generation in DMA mode on the complementary - * output - * @param htim TIM handle - * @param Channel TIM Channel to be disabled - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, Channel)); - - switch (Channel) - { - case TIM_CHANNEL_1: - { - /* Disable the TIM Capture/Compare 1 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC1]); - break; - } - - case TIM_CHANNEL_2: - { - /* Disable the TIM Capture/Compare 2 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC2]); - break; - } - - case TIM_CHANNEL_3: - { - /* Disable the TIM Capture/Compare 3 DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); - (void)HAL_DMA_Abort_IT(htim->hdma[TIM_DMA_ID_CC3]); - break; - } - - default: - status = HAL_ERROR; - break; - } - - if (status == HAL_OK) - { - /* Disable the complementary PWM output */ - TIM_CCxNChannelCmd(htim->Instance, Channel, TIM_CCxN_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM complementary channel state */ - TIM_CHANNEL_N_STATE_SET(htim, Channel, HAL_TIM_CHANNEL_STATE_READY); - } - - /* Return function status */ - return status; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions - * @brief Timer Complementary One Pulse functions - * -@verbatim - ============================================================================== - ##### Timer Complementary One Pulse functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Start the Complementary One Pulse generation. - (+) Stop the Complementary One Pulse. - (+) Start the Complementary One Pulse and enable interrupts. - (+) Stop the Complementary One Pulse and disable interrupts. - -@endverbatim - * @{ - */ - -/** - * @brief Starts the TIM One Pulse signal generation on the complementary - * output. - * @note OutputChannel must match the pulse output channel chosen when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel pulse output channel to enable - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the complementary One Pulse output channel and the Input Capture channel */ - TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE); - TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM One Pulse signal generation on the complementary - * output. - * @note OutputChannel must match the pulse output channel chosen when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel pulse output channel to disable - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); - - /* Disable the complementary One Pulse output channel and the Input Capture channel */ - TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE); - TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Starts the TIM One Pulse signal generation in interrupt mode on the - * complementary channel. - * @note OutputChannel must match the pulse output channel chosen when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel pulse output channel to enable - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; - HAL_TIM_ChannelStateTypeDef channel_1_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef channel_2_state = TIM_CHANNEL_STATE_GET(htim, TIM_CHANNEL_2); - HAL_TIM_ChannelStateTypeDef complementary_channel_1_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_1); - HAL_TIM_ChannelStateTypeDef complementary_channel_2_state = TIM_CHANNEL_N_STATE_GET(htim, TIM_CHANNEL_2); - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); - - /* Check the TIM channels state */ - if ((channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (channel_2_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_1_state != HAL_TIM_CHANNEL_STATE_READY) - || (complementary_channel_2_state != HAL_TIM_CHANNEL_STATE_READY)) - { - return HAL_ERROR; - } - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_BUSY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_BUSY); - - /* Enable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); - - /* Enable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC2); - - /* Enable the complementary One Pulse output channel and the Input Capture channel */ - TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_ENABLE); - TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_ENABLE); - - /* Enable the Main Output */ - __HAL_TIM_MOE_ENABLE(htim); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Stops the TIM One Pulse signal generation in interrupt mode on the - * complementary channel. - * @note OutputChannel must match the pulse output channel chosen when calling - * @ref HAL_TIM_OnePulse_ConfigChannel(). - * @param htim TIM One Pulse handle - * @param OutputChannel pulse output channel to disable - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) -{ - uint32_t input_channel = (OutputChannel == TIM_CHANNEL_1) ? TIM_CHANNEL_2 : TIM_CHANNEL_1; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, OutputChannel)); - - /* Disable the TIM Capture/Compare 1 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); - - /* Disable the TIM Capture/Compare 2 interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC2); - - /* Disable the complementary One Pulse output channel and the Input Capture channel */ - TIM_CCxNChannelCmd(htim->Instance, OutputChannel, TIM_CCxN_DISABLE); - TIM_CCxChannelCmd(htim->Instance, input_channel, TIM_CCx_DISABLE); - - /* Disable the Main Output */ - __HAL_TIM_MOE_DISABLE(htim); - - /* Disable the Peripheral */ - __HAL_TIM_DISABLE(htim); - - /* Set the TIM channels state */ - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - - /* Return function status */ - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions - * @brief Peripheral Control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Configure the commutation event in case of use of the Hall sensor interface. - (+) Configure Output channels for OC and PWM mode. - - (+) Configure Complementary channels, break features and dead time. - (+) Configure Master synchronization. - (+) Configure timer remapping capabilities. - -@endverbatim - * @{ - */ - -/** - * @brief Configure the TIM commutation event sequence. - * @note This function is mandatory to use the commutation event in order to - * update the configuration at each commutation detection on the TRGI input of the Timer, - * the typical use of this feature is with the use of another Timer(interface Timer) - * configured in Hall sensor interface, this interface Timer will generate the - * commutation at its TRGO output (connected to Timer used in this function) each time - * the TI1 of the Interface Timer detect a commutation at its input TI1. - * @param htim TIM handle - * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal trigger 0 selected - * @arg TIM_TS_ITR1: Internal trigger 1 selected - * @arg TIM_TS_ITR2: Internal trigger 2 selected - * @arg TIM_TS_ITR3: Internal trigger 3 selected - * @arg TIM_TS_NONE: No trigger is needed - * @param CommutationSource the Commutation Event source - * This parameter can be one of the following values: - * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer - * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); - assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); - - __HAL_LOCK(htim); - - if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || - (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) - { - /* Select the Input trigger */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= InputTrigger; - } - - /* Select the Capture Compare preload feature */ - htim->Instance->CR2 |= TIM_CR2_CCPC; - /* Select the Commutation event source */ - htim->Instance->CR2 &= ~TIM_CR2_CCUS; - htim->Instance->CR2 |= CommutationSource; - - /* Disable Commutation Interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM); - - /* Disable Commutation DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM); - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configure the TIM commutation event sequence with interrupt. - * @note This function is mandatory to use the commutation event in order to - * update the configuration at each commutation detection on the TRGI input of the Timer, - * the typical use of this feature is with the use of another Timer(interface Timer) - * configured in Hall sensor interface, this interface Timer will generate the - * commutation at its TRGO output (connected to Timer used in this function) each time - * the TI1 of the Interface Timer detect a commutation at its input TI1. - * @param htim TIM handle - * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal trigger 0 selected - * @arg TIM_TS_ITR1: Internal trigger 1 selected - * @arg TIM_TS_ITR2: Internal trigger 2 selected - * @arg TIM_TS_ITR3: Internal trigger 3 selected - * @arg TIM_TS_NONE: No trigger is needed - * @param CommutationSource the Commutation Event source - * This parameter can be one of the following values: - * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer - * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); - assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); - - __HAL_LOCK(htim); - - if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || - (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) - { - /* Select the Input trigger */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= InputTrigger; - } - - /* Select the Capture Compare preload feature */ - htim->Instance->CR2 |= TIM_CR2_CCPC; - /* Select the Commutation event source */ - htim->Instance->CR2 &= ~TIM_CR2_CCUS; - htim->Instance->CR2 |= CommutationSource; - - /* Disable Commutation DMA request */ - __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_COM); - - /* Enable the Commutation Interrupt */ - __HAL_TIM_ENABLE_IT(htim, TIM_IT_COM); - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configure the TIM commutation event sequence with DMA. - * @note This function is mandatory to use the commutation event in order to - * update the configuration at each commutation detection on the TRGI input of the Timer, - * the typical use of this feature is with the use of another Timer(interface Timer) - * configured in Hall sensor interface, this interface Timer will generate the - * commutation at its TRGO output (connected to Timer used in this function) each time - * the TI1 of the Interface Timer detect a commutation at its input TI1. - * @note The user should configure the DMA in his own software, in This function only the COMDE bit is set - * @param htim TIM handle - * @param InputTrigger the Internal trigger corresponding to the Timer Interfacing with the Hall sensor - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal trigger 0 selected - * @arg TIM_TS_ITR1: Internal trigger 1 selected - * @arg TIM_TS_ITR2: Internal trigger 2 selected - * @arg TIM_TS_ITR3: Internal trigger 3 selected - * @arg TIM_TS_NONE: No trigger is needed - * @param CommutationSource the Commutation Event source - * This parameter can be one of the following values: - * @arg TIM_COMMUTATION_TRGI: Commutation source is the TRGI of the Interface Timer - * @arg TIM_COMMUTATION_SOFTWARE: Commutation source is set by software using the COMG bit - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_COMMUTATION_EVENT_INSTANCE(htim->Instance)); - assert_param(IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(InputTrigger)); - - __HAL_LOCK(htim); - - if ((InputTrigger == TIM_TS_ITR0) || (InputTrigger == TIM_TS_ITR1) || - (InputTrigger == TIM_TS_ITR2) || (InputTrigger == TIM_TS_ITR3)) - { - /* Select the Input trigger */ - htim->Instance->SMCR &= ~TIM_SMCR_TS; - htim->Instance->SMCR |= InputTrigger; - } - - /* Select the Capture Compare preload feature */ - htim->Instance->CR2 |= TIM_CR2_CCPC; - /* Select the Commutation event source */ - htim->Instance->CR2 &= ~TIM_CR2_CCUS; - htim->Instance->CR2 |= CommutationSource; - - /* Enable the Commutation DMA Request */ - /* Set the DMA Commutation Callback */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferCpltCallback = TIMEx_DMACommutationCplt; - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferHalfCpltCallback = TIMEx_DMACommutationHalfCplt; - /* Set the DMA error callback */ - htim->hdma[TIM_DMA_ID_COMMUTATION]->XferErrorCallback = TIM_DMAError; - - /* Disable Commutation Interrupt */ - __HAL_TIM_DISABLE_IT(htim, TIM_IT_COM); - - /* Enable the Commutation DMA Request */ - __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_COM); - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configures the TIM in master mode. - * @param htim TIM handle. - * @param sMasterConfig pointer to a TIM_MasterConfigTypeDef structure that - * contains the selected trigger output (TRGO) and the Master/Slave - * mode. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, - TIM_MasterConfigTypeDef *sMasterConfig) -{ - uint32_t tmpcr2; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_MASTER_INSTANCE(htim->Instance)); - assert_param(IS_TIM_TRGO_SOURCE(sMasterConfig->MasterOutputTrigger)); - assert_param(IS_TIM_MSM_STATE(sMasterConfig->MasterSlaveMode)); - - /* Check input state */ - __HAL_LOCK(htim); - - /* Change the handler state */ - htim->State = HAL_TIM_STATE_BUSY; - - /* Get the TIMx CR2 register value */ - tmpcr2 = htim->Instance->CR2; - - /* Get the TIMx SMCR register value */ - tmpsmcr = htim->Instance->SMCR; - - /* Reset the MMS Bits */ - tmpcr2 &= ~TIM_CR2_MMS; - /* Select the TRGO source */ - tmpcr2 |= sMasterConfig->MasterOutputTrigger; - - /* Update TIMx CR2 */ - htim->Instance->CR2 = tmpcr2; - - if (IS_TIM_SLAVE_INSTANCE(htim->Instance)) - { - /* Reset the MSM Bit */ - tmpsmcr &= ~TIM_SMCR_MSM; - /* Set master mode */ - tmpsmcr |= sMasterConfig->MasterSlaveMode; - - /* Update TIMx SMCR */ - htim->Instance->SMCR = tmpsmcr; - } - - /* Change the htim state */ - htim->State = HAL_TIM_STATE_READY; - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configures the Break feature, dead time, Lock level, OSSI/OSSR State - * and the AOE(automatic output enable). - * @param htim TIM handle - * @param sBreakDeadTimeConfig pointer to a TIM_ConfigBreakDeadConfigTypeDef structure that - * contains the BDTR Register configuration information for the TIM peripheral. - * @note Interrupts can be generated when an active level is detected on the - * break input, the break 2 input or the system break input. Break - * interrupt can be enabled by calling the @ref __HAL_TIM_ENABLE_IT macro. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim, - TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig) -{ - /* Keep this variable initialized to 0 as it is used to configure BDTR register */ - uint32_t tmpbdtr = 0U; - - /* Check the parameters */ - assert_param(IS_TIM_BREAK_INSTANCE(htim->Instance)); - assert_param(IS_TIM_OSSR_STATE(sBreakDeadTimeConfig->OffStateRunMode)); - assert_param(IS_TIM_OSSI_STATE(sBreakDeadTimeConfig->OffStateIDLEMode)); - assert_param(IS_TIM_LOCK_LEVEL(sBreakDeadTimeConfig->LockLevel)); - assert_param(IS_TIM_DEADTIME(sBreakDeadTimeConfig->DeadTime)); - assert_param(IS_TIM_BREAK_STATE(sBreakDeadTimeConfig->BreakState)); - assert_param(IS_TIM_BREAK_POLARITY(sBreakDeadTimeConfig->BreakPolarity)); - assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(sBreakDeadTimeConfig->AutomaticOutput)); - - /* Check input state */ - __HAL_LOCK(htim); - - /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State, - the OSSI State, the dead time value and the Automatic Output Enable Bit */ - - /* Set the BDTR bits */ - MODIFY_REG(tmpbdtr, TIM_BDTR_DTG, sBreakDeadTimeConfig->DeadTime); - MODIFY_REG(tmpbdtr, TIM_BDTR_LOCK, sBreakDeadTimeConfig->LockLevel); - MODIFY_REG(tmpbdtr, TIM_BDTR_OSSI, sBreakDeadTimeConfig->OffStateIDLEMode); - MODIFY_REG(tmpbdtr, TIM_BDTR_OSSR, sBreakDeadTimeConfig->OffStateRunMode); - MODIFY_REG(tmpbdtr, TIM_BDTR_BKE, sBreakDeadTimeConfig->BreakState); - MODIFY_REG(tmpbdtr, TIM_BDTR_BKP, sBreakDeadTimeConfig->BreakPolarity); - MODIFY_REG(tmpbdtr, TIM_BDTR_AOE, sBreakDeadTimeConfig->AutomaticOutput); - - - /* Set TIMx_BDTR */ - htim->Instance->BDTR = tmpbdtr; - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @brief Configures the TIMx Remapping input capabilities. - * @param htim TIM handle. - * @param Remap specifies the TIM remapping source. - * For TIM1, the parameter can have the following values: (**) - * @arg TIM_TIM1_TIM3_TRGO: TIM1 ITR2 is connected to TIM3 TRGO - * @arg TIM_TIM1_LPTIM: TIM1 ITR2 is connected to LPTIM1 output - * - * For TIM2, the parameter can have the following values: (**) - * @arg TIM_TIM2_TIM8_TRGO: TIM2 ITR1 is connected to TIM8 TRGO (*) - * @arg TIM_TIM2_ETH_PTP: TIM2 ITR1 is connected to PTP trigger output (*) - * @arg TIM_TIM2_USBFS_SOF: TIM2 ITR1 is connected to OTG FS SOF - * @arg TIM_TIM2_USBHS_SOF: TIM2 ITR1 is connected to OTG FS SOF - * - * For TIM5, the parameter can have the following values: - * @arg TIM_TIM5_GPIO: TIM5 TI4 is connected to GPIO - * @arg TIM_TIM5_LSI: TIM5 TI4 is connected to LSI - * @arg TIM_TIM5_LSE: TIM5 TI4 is connected to LSE - * @arg TIM_TIM5_RTC: TIM5 TI4 is connected to the RTC wakeup interrupt - * @arg TIM_TIM5_TIM3_TRGO: TIM5 ITR1 is connected to TIM3 TRGO (*) - * @arg TIM_TIM5_LPTIM: TIM5 ITR1 is connected to LPTIM1 output (*) - * - * For TIM9, the parameter can have the following values: (**) - * @arg TIM_TIM9_TIM3_TRGO: TIM9 ITR1 is connected to TIM3 TRGO - * @arg TIM_TIM9_LPTIM: TIM9 ITR1 is connected to LPTIM1 output - * - * For TIM11, the parameter can have the following values: - * @arg TIM_TIM11_GPIO: TIM11 TI1 is connected to GPIO - * @arg TIM_TIM11_HSE: TIM11 TI1 is connected to HSE_RTC clock - * @arg TIM_TIM11_SPDIFRX: TIM11 TI1 is connected to SPDIFRX_FRAME_SYNC (*) - * - * (*) Value not defined in all devices. \n - * (**) Register not available in all devices. - * - * @retval HAL status - */ -HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap) -{ - __HAL_LOCK(htim); - - /* Check parameters */ - assert_param(IS_TIM_REMAP(htim->Instance, Remap)); - -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM9_ITR1_RMP) - if ((Remap & LPTIM_REMAP_MASK) == LPTIM_REMAP_MASK) - { - /* Connect TIMx internal trigger to LPTIM1 output */ - __HAL_RCC_LPTIM1_CLK_ENABLE(); - MODIFY_REG(LPTIM1->OR, - (LPTIM_OR_TIM1_ITR2_RMP | LPTIM_OR_TIM5_ITR1_RMP | LPTIM_OR_TIM9_ITR1_RMP), - Remap & ~(LPTIM_REMAP_MASK)); - } - else - { - /* Set the Timer remapping configuration */ - WRITE_REG(htim->Instance->OR, Remap); - } -#else - /* Set the Timer remapping configuration */ - WRITE_REG(htim->Instance->OR, Remap); -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM9_ITR1_RMP */ - - __HAL_UNLOCK(htim); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions - * @brief Extended Callbacks functions - * -@verbatim - ============================================================================== - ##### Extended Callbacks functions ##### - ============================================================================== - [..] - This section provides Extended TIM callback functions: - (+) Timer Commutation callback - (+) Timer Break callback - -@endverbatim - * @{ - */ - -/** - * @brief Hall commutation changed callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_CommutCallback could be implemented in the user file - */ -} -/** - * @brief Hall commutation changed half complete callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_CommutHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Hall Break detection callback in non-blocking mode - * @param htim TIM handle - * @retval None - */ -__weak void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(htim); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_TIMEx_BreakCallback could be implemented in the user file - */ -} -/** - * @} - */ - -/** @defgroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions - * @brief Extended Peripheral State functions - * -@verbatim - ============================================================================== - ##### Extended Peripheral State functions ##### - ============================================================================== - [..] - This subsection permits to get in run-time the status of the peripheral - and the data flow. - -@endverbatim - * @{ - */ - -/** - * @brief Return the TIM Hall Sensor interface handle state. - * @param htim TIM Hall Sensor handle - * @retval HAL state - */ -HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim) -{ - return htim->State; -} - -/** - * @brief Return actual state of the TIM complementary channel. - * @param htim TIM handle - * @param ChannelN TIM Complementary channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @retval TIM Complementary channel state - */ -HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN) -{ - HAL_TIM_ChannelStateTypeDef channel_state; - - /* Check the parameters */ - assert_param(IS_TIM_CCXN_INSTANCE(htim->Instance, ChannelN)); - - channel_state = TIM_CHANNEL_N_STATE_GET(htim, ChannelN); - - return channel_state; -} -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup TIMEx_Private_Functions TIMEx Private Functions - * @{ - */ - -/** - * @brief TIM DMA Commutation callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Change the htim state */ - htim->State = HAL_TIM_STATE_READY; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->CommutationCallback(htim); -#else - HAL_TIMEx_CommutCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - -/** - * @brief TIM DMA Commutation half complete callback. - * @param hdma pointer to DMA handle. - * @retval None - */ -void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Change the htim state */ - htim->State = HAL_TIM_STATE_READY; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->CommutationHalfCpltCallback(htim); -#else - HAL_TIMEx_CommutHalfCpltCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} - - -/** - * @brief TIM DMA Delay Pulse complete callback (complementary channel). - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC4]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; - - if (hdma->Init.Mode == DMA_NORMAL) - { - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY); - } - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->PWM_PulseFinishedCallback(htim); -#else - HAL_TIM_PWM_PulseFinishedCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief TIM DMA error callback (complementary channel) - * @param hdma pointer to DMA handle. - * @retval None - */ -static void TIM_DMAErrorCCxN(DMA_HandleTypeDef *hdma) -{ - TIM_HandleTypeDef *htim = (TIM_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - if (hdma == htim->hdma[TIM_DMA_ID_CC1]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_1, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC2]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_2, HAL_TIM_CHANNEL_STATE_READY); - } - else if (hdma == htim->hdma[TIM_DMA_ID_CC3]) - { - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; - TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); - } - else - { - /* nothing to do */ - } - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - htim->ErrorCallback(htim); -#else - HAL_TIM_ErrorCallback(htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - - htim->Channel = HAL_TIM_ACTIVE_CHANNEL_CLEARED; -} - -/** - * @brief Enables or disables the TIM Capture Compare Channel xN. - * @param TIMx to select the TIM peripheral - * @param Channel specifies the TIM Channel - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 - * @arg TIM_CHANNEL_2: TIM Channel 2 - * @arg TIM_CHANNEL_3: TIM Channel 3 - * @param ChannelNState specifies the TIM Channel CCxNE bit new state. - * This parameter can be: TIM_CCxN_ENABLE or TIM_CCxN_Disable. - * @retval None - */ -static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelNState) -{ - uint32_t tmp; - - tmp = TIM_CCER_CC1NE << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ - - /* Reset the CCxNE Bit */ - TIMx->CCER &= ~tmp; - - /* Set or reset the CCxNE Bit */ - TIMx->CCER |= (uint32_t)(ChannelNState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ -} -/** - * @} - */ - -#endif /* HAL_TIM_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_alarm_template.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_alarm_template.c deleted file mode 100644 index ddd78a529690c27..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_alarm_template.c +++ /dev/null @@ -1,317 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_timebase_rtc_alarm_template.c - * @author MCD Application Team - * @brief HAL time base based on the hardware RTC_ALARM Template. - * - * This file override the native HAL time base functions (defined as weak) - * to use the RTC ALARM for time base generation: - * + Intializes the RTC peripheral to increment the seconds registers each 1ms - * + The alarm is configured to assert an interrupt when the RTC reaches 1ms - * + HAL_IncTick is called at each Alarm event and the time is reset to 00:00:00 - * + HSE (default), LSE or LSI can be selected as RTC clock source - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - This file must be copied to the application folder and modified as follows: - (#) Rename it to 'stm32f4xx_hal_timebase_rtc_alarm.c' - (#) Add this file and the RTC HAL drivers to your project and uncomment - HAL_RTC_MODULE_ENABLED define in stm32f4xx_hal_conf.h - - [..] - (@) HAL RTC alarm and HAL RTC wakeup drivers cant be used with low power modes: - The wake up capability of the RTC may be intrusive in case of prior low power mode - configuration requiring different wake up sources. - Application/Example behavior is no more guaranteed - (@) The stm32f4xx_hal_timebase_tim use is recommended for the Applications/Examples - requiring low power modes - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup HAL_TimeBase_RTC_Alarm_Template HAL TimeBase RTC Alarm Template - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ - -/* Uncomment the line below to select the appropriate RTC Clock source for your application: - + RTC_CLOCK_SOURCE_HSE: can be selected for applications requiring timing precision. - + RTC_CLOCK_SOURCE_LSE: can be selected for applications with low constraint on timing - precision. - + RTC_CLOCK_SOURCE_LSI: can be selected for applications with low constraint on timing - precision. - */ -#define RTC_CLOCK_SOURCE_HSE -/* #define RTC_CLOCK_SOURCE_LSE */ -/* #define RTC_CLOCK_SOURCE_LSI */ - -#ifdef RTC_CLOCK_SOURCE_HSE - #define RTC_ASYNCH_PREDIV 99U - #define RTC_SYNCH_PREDIV 9U - #define RCC_RTCCLKSOURCE_1MHZ ((uint32_t)((uint32_t)RCC_BDCR_RTCSEL | (uint32_t)((HSE_VALUE/1000000U) << 16U))) -#else /* RTC_CLOCK_SOURCE_LSE || RTC_CLOCK_SOURCE_LSI */ - #define RTC_ASYNCH_PREDIV 0U - #define RTC_SYNCH_PREDIV 31U -#endif /* RTC_CLOCK_SOURCE_HSE */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -RTC_HandleTypeDef hRTC_Handle; -/* Private function prototypes -----------------------------------------------*/ -void RTC_Alarm_IRQHandler(void); -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief This function configures the RTC_ALARMA as a time base source. - * The time source is configured to have 1ms time base with a dedicated - * Tick interrupt priority. - * @note This function is called automatically at the beginning of program after - * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig(). - * @param TickPriority Tick interrupt priority. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) -{ - __IO uint32_t counter = 0U; - - RCC_OscInitTypeDef RCC_OscInitStruct; - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; - HAL_StatusTypeDef status; - -#ifdef RTC_CLOCK_SOURCE_LSE - /* Configue LSE as RTC clock soucre */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - RCC_OscInitStruct.LSEState = RCC_LSE_ON; - PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE; -#elif defined (RTC_CLOCK_SOURCE_LSI) - /* Configue LSI as RTC clock soucre */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - RCC_OscInitStruct.LSIState = RCC_LSI_ON; - PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSI; -#elif defined (RTC_CLOCK_SOURCE_HSE) - /* Configue HSE as RTC clock soucre */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - /* Ensure that RTC is clocked by 1MHz */ - PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_1MHZ; -#else -#error Please select the RTC Clock source -#endif /* RTC_CLOCK_SOURCE_LSE */ - - status = HAL_RCC_OscConfig(&RCC_OscInitStruct); - if (status == HAL_OK) - { - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC; - status = HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); - } - if (status == HAL_OK) - { - /* Enable RTC Clock */ - __HAL_RCC_RTC_ENABLE(); - /* The time base should be 1ms - Time base = ((RTC_ASYNCH_PREDIV + 1) * (RTC_SYNCH_PREDIV + 1)) / RTC_CLOCK - HSE as RTC clock - Time base = ((99 + 1) * (9 + 1)) / 1MHz - = 1ms - LSE as RTC clock - Time base = ((31 + 1) * (0 + 1)) / 32.768KHz - = ~1ms - LSI as RTC clock - Time base = ((31 + 1) * (0 + 1)) / 32KHz - = 1ms - */ - hRTC_Handle.Instance = RTC; - hRTC_Handle.Init.HourFormat = RTC_HOURFORMAT_24; - hRTC_Handle.Init.AsynchPrediv = RTC_ASYNCH_PREDIV; - hRTC_Handle.Init.SynchPrediv = RTC_SYNCH_PREDIV; - hRTC_Handle.Init.OutPut = RTC_OUTPUT_DISABLE; - hRTC_Handle.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH; - hRTC_Handle.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN; - status = HAL_RTC_Init(&hRTC_Handle); - } - if (status == HAL_OK) - { - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); - - /* Disable the Alarm A interrupt */ - __HAL_RTC_ALARMA_DISABLE(&hRTC_Handle); - - /* Clear flag alarm A */ - __HAL_RTC_ALARM_CLEAR_FLAG(&hRTC_Handle, RTC_FLAG_ALRAF); - - counter = 0U; - /* Wait till RTC ALRAWF flag is set and if Time out is reached exit */ - while (__HAL_RTC_ALARM_GET_FLAG(&hRTC_Handle, RTC_FLAG_ALRAWF) == RESET) - { - if (counter++ == (SystemCoreClock / 48U)) /* Timeout = ~ 1s */ - { - status = HAL_ERROR; - } - } - } - if (status == HAL_OK) - { - hRTC_Handle.Instance->ALRMAR = (uint32_t)0x01U; - - /* Configure the Alarm state: Enable Alarm */ - __HAL_RTC_ALARMA_ENABLE(&hRTC_Handle); - /* Configure the Alarm interrupt */ - __HAL_RTC_ALARM_ENABLE_IT(&hRTC_Handle, RTC_IT_ALRA); - - /* RTC Alarm Interrupt Configuration: EXTI configuration */ - __HAL_RTC_ALARM_EXTI_ENABLE_IT(); - __HAL_RTC_ALARM_EXTI_ENABLE_RISING_EDGE(); - - /* Check if the Initialization mode is set */ - if ((hRTC_Handle.Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) - { - /* Set the Initialization mode */ - hRTC_Handle.Instance->ISR = (uint32_t)RTC_INIT_MASK; - counter = 0U; - while ((hRTC_Handle.Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) - { - if (counter++ == (SystemCoreClock / 48U)) /* Timeout = ~ 1s */ - { - status = HAL_ERROR; - } - } - } - } - if (status == HAL_OK) - { - hRTC_Handle.Instance->DR = 0U; - hRTC_Handle.Instance->TR = 0U; - - hRTC_Handle.Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); - - /* Enable the RTC Alarm Interrupt */ - HAL_NVIC_EnableIRQ(RTC_Alarm_IRQn); - - /* Configure the SysTick IRQ priority */ - if (TickPriority < (1UL << __NVIC_PRIO_BITS)) - { - HAL_NVIC_SetPriority(RTC_Alarm_IRQn, TickPriority, 0U); - uwTickPrio = TickPriority; - } - else - { - status = HAL_ERROR; - } - - } - return status; -} - -/** - * @brief Suspend Tick increment. - * @note Disable the tick increment by disabling RTC ALARM interrupt. - * @retval None - */ -void HAL_SuspendTick(void) -{ - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); - /* Disable RTC ALARM update Interrupt */ - __HAL_RTC_ALARM_DISABLE_IT(&hRTC_Handle, RTC_IT_ALRA); - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); -} - -/** - * @brief Resume Tick increment. - * @note Enable the tick increment by Enabling RTC ALARM interrupt. - * @retval None - */ -void HAL_ResumeTick(void) -{ - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); - /* Enable RTC ALARM Update interrupt */ - __HAL_RTC_ALARM_ENABLE_IT(&hRTC_Handle, RTC_IT_ALRA); - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); -} - -/** - * @brief ALARM A Event Callback in non blocking mode - * @note This function is called when RTC_ALARM interrupt took place, inside - * RTC_ALARM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment - * a global variable "uwTick" used as application time base. - * @param hrtc RTC handle - * @retval None - */ -void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc) -{ - __IO uint32_t counter = 0U; - - HAL_IncTick(); - - __HAL_RTC_WRITEPROTECTION_DISABLE(hrtc); - - /* Set the Initialization mode */ - hrtc->Instance->ISR = (uint32_t)RTC_INIT_MASK; - - while((hrtc->Instance->ISR & RTC_ISR_INITF) == (uint32_t)RESET) - { - if(counter++ == (SystemCoreClock /48U)) /* Timeout = ~ 1s */ - { - break; - } - } - - hrtc->Instance->DR = 0U; - hrtc->Instance->TR = 0U; - - hrtc->Instance->ISR &= (uint32_t)~RTC_ISR_INIT; - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(hrtc); -} - -/** - * @brief This function handles RTC ALARM interrupt request. - * @retval None - */ -void RTC_Alarm_IRQHandler(void) -{ - HAL_RTC_AlarmIRQHandler(&hRTC_Handle); -} - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_wakeup_template.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_wakeup_template.c deleted file mode 100644 index 01663e75d76a9dc..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_rtc_wakeup_template.c +++ /dev/null @@ -1,292 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_timebase_rtc_wakeup_template.c - * @author MCD Application Team - * @brief HAL time base based on the hardware RTC_WAKEUP Template. - * - * This file overrides the native HAL time base functions (defined as weak) - * to use the RTC WAKEUP for the time base generation: - * + Intializes the RTC peripheral and configures the wakeup timer to be - * incremented each 1ms - * + The wakeup feature is configured to assert an interrupt each 1ms - * + HAL_IncTick is called inside the HAL_RTCEx_WakeUpTimerEventCallback - * + HSE (default), LSE or LSI can be selected as RTC clock source - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - This file must be copied to the application folder and modified as follows: - (#) Rename it to 'stm32f4xx_hal_timebase_rtc_wakeup.c' - (#) Add this file and the RTC HAL drivers to your project and uncomment - HAL_RTC_MODULE_ENABLED define in stm32f4xx_hal_conf.h - - [..] - (@) HAL RTC alarm and HAL RTC wakeup drivers cant be used with low power modes: - The wake up capability of the RTC may be intrusive in case of prior low power mode - configuration requiring different wake up sources. - Application/Example behavior is no more guaranteed - (@) The stm32f4xx_hal_timebase_tim use is recommended for the Applications/Examples - requiring low power modes - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup HAL_TimeBase_RTC_WakeUp_Template HAL TimeBase RTC WakeUp Template - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ - -/* Uncomment the line below to select the appropriate RTC Clock source for your application: - + RTC_CLOCK_SOURCE_HSE: can be selected for applications requiring timing precision. - + RTC_CLOCK_SOURCE_LSE: can be selected for applications with low constraint on timing - precision. - + RTC_CLOCK_SOURCE_LSI: can be selected for applications with low constraint on timing - precision. - */ -#define RTC_CLOCK_SOURCE_HSE -/* #define RTC_CLOCK_SOURCE_LSE */ -/* #define RTC_CLOCK_SOURCE_LSI */ - -#ifdef RTC_CLOCK_SOURCE_HSE - #define RTC_ASYNCH_PREDIV 99U - #define RTC_SYNCH_PREDIV 9U - #define RCC_RTCCLKSOURCE_1MHZ ((uint32_t)((uint32_t)RCC_BDCR_RTCSEL | (uint32_t)((HSE_VALUE/1000000U) << 16U))) -#else /* RTC_CLOCK_SOURCE_LSE || RTC_CLOCK_SOURCE_LSI */ - #define RTC_ASYNCH_PREDIV 0U - #define RTC_SYNCH_PREDIV 31U -#endif /* RTC_CLOCK_SOURCE_HSE */ - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -RTC_HandleTypeDef hRTC_Handle; - -/* Private function prototypes -----------------------------------------------*/ -void RTC_WKUP_IRQHandler(void); - -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief This function configures the RTC_WKUP as a time base source. - * The time source is configured to have 1ms time base with a dedicated - * Tick interrupt priority. - * Wakeup Time base = ((RTC_ASYNCH_PREDIV + 1) * (RTC_SYNCH_PREDIV + 1)) / RTC_CLOCK - = 1ms - * Wakeup Time = WakeupTimebase * WakeUpCounter (0 + 1) - = 1 ms - * @note This function is called automatically at the beginning of program after - * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig(). - * @param TickPriority Tick interrupt priority. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority) -{ - __IO uint32_t counter = 0U; - - RCC_OscInitTypeDef RCC_OscInitStruct; - RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; - HAL_StatusTypeDef status; - -#ifdef RTC_CLOCK_SOURCE_LSE - /* Configue LSE as RTC clock soucre */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - RCC_OscInitStruct.LSEState = RCC_LSE_ON; - PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE; -#elif defined (RTC_CLOCK_SOURCE_LSI) - /* Configue LSI as RTC clock soucre */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - RCC_OscInitStruct.LSIState = RCC_LSI_ON; - PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSI; -#elif defined (RTC_CLOCK_SOURCE_HSE) - /* Configue HSE as RTC clock soucre */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - RCC_OscInitStruct.HSEState = RCC_HSE_ON; - /* Ensure that RTC is clocked by 1MHz */ - PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_1MHZ; -#else -#error Please select the RTC Clock source -#endif /* RTC_CLOCK_SOURCE_LSE */ - - status = HAL_RCC_OscConfig(&RCC_OscInitStruct); - if (status == HAL_OK) - { - PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC; - status = HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); - } - if (status == HAL_OK) - { - /* Enable RTC Clock */ - __HAL_RCC_RTC_ENABLE(); - /* The time base should be 1ms - Time base = ((RTC_ASYNCH_PREDIV + 1) * (RTC_SYNCH_PREDIV + 1)) / RTC_CLOCK - HSE as RTC clock - Time base = ((99 + 1) * (9 + 1)) / 1Mhz - = 1ms - LSE as RTC clock - Time base = ((31 + 1) * (0 + 1)) / 32.768Khz - = ~1ms - LSI as RTC clock - Time base = ((31 + 1) * (0 + 1)) / 32Khz - = 1ms - */ - hRTC_Handle.Instance = RTC; - hRTC_Handle.Init.HourFormat = RTC_HOURFORMAT_24; - hRTC_Handle.Init.AsynchPrediv = RTC_ASYNCH_PREDIV; - hRTC_Handle.Init.SynchPrediv = RTC_SYNCH_PREDIV; - hRTC_Handle.Init.OutPut = RTC_OUTPUT_DISABLE; - hRTC_Handle.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH; - hRTC_Handle.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN; - status = HAL_RTC_Init(&hRTC_Handle); - } - if (status == HAL_OK) - { - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); - - /* Disable the Wake-up Timer */ - __HAL_RTC_WAKEUPTIMER_DISABLE(&hRTC_Handle); - - /* In case of interrupt mode is used, the interrupt source must disabled */ - __HAL_RTC_WAKEUPTIMER_DISABLE_IT(&hRTC_Handle, RTC_IT_WUT); - - /* Wait till RTC WUTWF flag is set */ - while (__HAL_RTC_WAKEUPTIMER_GET_FLAG(&hRTC_Handle, RTC_FLAG_WUTWF) == RESET) - { - if (counter++ == (SystemCoreClock / 48U)) - { - status = HAL_ERROR; - } - } - } - if (status == HAL_OK) - { - /* Clear PWR wake up Flag */ - __HAL_PWR_CLEAR_FLAG(PWR_FLAG_WU); - - /* Clear RTC Wake Up timer Flag */ - __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(&hRTC_Handle, RTC_FLAG_WUTF); - - /* Configure the Wake-up Timer counter */ - hRTC_Handle.Instance->WUTR = 0U; - - /* Clear the Wake-up Timer clock source bits in CR register */ - hRTC_Handle.Instance->CR &= (uint32_t)~RTC_CR_WUCKSEL; - - /* Configure the clock source */ - hRTC_Handle.Instance->CR |= (uint32_t)RTC_WAKEUPCLOCK_CK_SPRE_16BITS; - - /* RTC WakeUpTimer Interrupt Configuration: EXTI configuration */ - __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT(); - - __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE(); - - /* Configure the Interrupt in the RTC_CR register */ - __HAL_RTC_WAKEUPTIMER_ENABLE_IT(&hRTC_Handle,RTC_IT_WUT); - - /* Enable the Wake-up Timer */ - __HAL_RTC_WAKEUPTIMER_ENABLE(&hRTC_Handle); - - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); - - /* Enable the RTC global Interrupt */ - HAL_NVIC_EnableIRQ(RTC_WKUP_IRQn); - - /* Configure the SysTick IRQ priority */ - if (TickPriority < (1UL << __NVIC_PRIO_BITS)) - { - HAL_NVIC_SetPriority(RTC_WKUP_IRQn, TickPriority, 0U); - uwTickPrio = TickPriority; - } - else - { - status = HAL_ERROR; - } - } - return status; -} - -/** - * @brief Suspend Tick increment. - * @note Disable the tick increment by disabling RTC_WKUP interrupt. - * @retval None - */ -void HAL_SuspendTick(void) -{ - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); - /* Disable WAKE UP TIMER Interrupt */ - __HAL_RTC_WAKEUPTIMER_DISABLE_IT(&hRTC_Handle, RTC_IT_WUT); - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); -} - -/** - * @brief Resume Tick increment. - * @note Enable the tick increment by Enabling RTC_WKUP interrupt. - * @retval None - */ -void HAL_ResumeTick(void) -{ - /* Disable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_DISABLE(&hRTC_Handle); - /* Enable WAKE UP TIMER interrupt */ - __HAL_RTC_WAKEUPTIMER_ENABLE_IT(&hRTC_Handle, RTC_IT_WUT); - /* Enable the write protection for RTC registers */ - __HAL_RTC_WRITEPROTECTION_ENABLE(&hRTC_Handle); -} - -/** - * @brief Wake Up Timer Event Callback in non blocking mode - * @note This function is called when RTC_WKUP interrupt took place, inside - * RTC_WKUP_IRQHandler(). It makes a direct call to HAL_IncTick() to increment - * a global variable "uwTick" used as application time base. - * @param hrtc RTC handle - * @retval None - */ -void HAL_RTCEx_WakeUpTimerEventCallback(RTC_HandleTypeDef *hrtc) -{ - HAL_IncTick(); -} - -/** - * @brief This function handles WAKE UP TIMER interrupt request. - * @retval None - */ -void RTC_WKUP_IRQHandler(void) -{ - HAL_RTCEx_WakeUpTimerIRQHandler(&hRTC_Handle); -} - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_tim_template.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_tim_template.c deleted file mode 100644 index da61e9ccbc05797..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_timebase_tim_template.c +++ /dev/null @@ -1,178 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_timebase_tim_template.c - * @author MCD Application Team - * @brief HAL time base based on the hardware TIM Template. - * - * This file overrides the native HAL time base functions (defined as weak) - * the TIM time base: - * + Intializes the TIM peripheral generate a Period elapsed Event each 1ms - * + HAL_IncTick is called inside HAL_TIM_PeriodElapsedCallback ie each 1ms - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup HAL_TimeBase_TIM - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -TIM_HandleTypeDef TimHandle; -/* Private function prototypes -----------------------------------------------*/ -void TIM6_DAC_IRQHandler(void); -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief This function configures the TIM6 as a time base source. - * The time source is configured to have 1ms time base with a dedicated - * Tick interrupt priority. - * @note This function is called automatically at the beginning of program after - * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig(). - * @param TickPriority Tick interrupt priority. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority) -{ - RCC_ClkInitTypeDef clkconfig; - uint32_t uwTimclock, uwAPB1Prescaler = 0U; - uint32_t uwPrescalerValue = 0U; - uint32_t pFLatency; - HAL_StatusTypeDef status; - - /* Enable TIM6 clock */ - __HAL_RCC_TIM6_CLK_ENABLE(); - - /* Get clock configuration */ - HAL_RCC_GetClockConfig(&clkconfig, &pFLatency); - - /* Get APB1 prescaler */ - uwAPB1Prescaler = clkconfig.APB1CLKDivider; - - /* Compute TIM6 clock */ - if (uwAPB1Prescaler == RCC_HCLK_DIV1) - { - uwTimclock = HAL_RCC_GetPCLK1Freq(); - } - else - { - uwTimclock = 2 * HAL_RCC_GetPCLK1Freq(); - } - - /* Compute the prescaler value to have TIM6 counter clock equal to 1MHz */ - uwPrescalerValue = (uint32_t) ((uwTimclock / 1000000U) - 1U); - - /* Initialize TIM6 */ - TimHandle.Instance = TIM6; - - /* Initialize TIMx peripheral as follow: - + Period = [(TIM6CLK/1000) - 1]. to have a (1/1000) s time base. - + Prescaler = (uwTimclock/1000000 - 1) to have a 1MHz counter clock. - + ClockDivision = 0 - + Counter direction = Up - */ - TimHandle.Init.Period = (1000000U / 1000U) - 1U; - TimHandle.Init.Prescaler = uwPrescalerValue; - TimHandle.Init.ClockDivision = 0U; - TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; - TimHandle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - status = HAL_TIM_Base_Init(&TimHandle); - if (status == HAL_OK) - { - /* Start the TIM time Base generation in interrupt mode */ - status = HAL_TIM_Base_Start_IT(&TimHandle); - if (status == HAL_OK) - { - /* Enable the TIM6 global Interrupt */ - HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn); - - if (TickPriority < (1UL << __NVIC_PRIO_BITS)) - { - /* Enable the TIM6 global Interrupt */ - HAL_NVIC_SetPriority(TIM6_DAC_IRQn, TickPriority, 0); - uwTickPrio = TickPriority; - } - else - { - status = HAL_ERROR; - } - } - } - - /* Return function status */ - return status; -} - -/** - * @brief Suspend Tick increment. - * @note Disable the tick increment by disabling TIM6 update interrupt. - * @retval None - */ -void HAL_SuspendTick(void) -{ - /* Disable TIM6 update Interrupt */ - __HAL_TIM_DISABLE_IT(&TimHandle, TIM_IT_UPDATE); -} - -/** - * @brief Resume Tick increment. - * @note Enable the tick increment by Enabling TIM6 update interrupt. - * @retval None - */ -void HAL_ResumeTick(void) -{ - /* Enable TIM6 Update interrupt */ - __HAL_TIM_ENABLE_IT(&TimHandle, TIM_IT_UPDATE); -} - -/** - * @brief Period elapsed callback in non blocking mode - * @note This function is called when TIM6 interrupt took place, inside - * HAL_TIM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment - * a global variable "uwTick" used as application time base. - * @param htim TIM handle - * @retval None - */ -void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) -{ - HAL_IncTick(); -} - -/** - * @brief This function handles TIM interrupt request. - * @retval None - */ -void TIM6_DAC_IRQHandler(void) -{ - HAL_TIM_IRQHandler(&TimHandle); -} - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c deleted file mode 100644 index 5e53813c8663025..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c +++ /dev/null @@ -1,3741 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_uart.c - * @author MCD Application Team - * @brief UART HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Universal Asynchronous Receiver Transmitter Peripheral (UART). - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - * + Peripheral State and Errors functions - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The UART HAL driver can be used as follows: - - (#) Declare a UART_HandleTypeDef handle structure (eg. UART_HandleTypeDef huart). - (#) Initialize the UART low level resources by implementing the HAL_UART_MspInit() API: - (##) Enable the USARTx interface clock. - (##) UART pins configuration: - (+++) Enable the clock for the UART GPIOs. - (+++) Configure the UART TX/RX pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_UART_Transmit_IT() - and HAL_UART_Receive_IT() APIs): - (+++) Configure the USARTx interrupt priority. - (+++) Enable the NVIC USART IRQ handle. - (##) DMA Configuration if you need to use DMA process (HAL_UART_Transmit_DMA() - and HAL_UART_Receive_DMA() APIs): - (+++) Declare a DMA handle structure for the Tx/Rx stream. - (+++) Enable the DMAx interface clock. - (+++) Configure the declared DMA handle structure with the required - Tx/Rx parameters. - (+++) Configure the DMA Tx/Rx stream. - (+++) Associate the initialized DMA handle to the UART DMA Tx/Rx handle. - (+++) Configure the priority and enable the NVIC for the transfer complete - interrupt on the DMA Tx/Rx stream. - (+++) Configure the USARTx interrupt priority and enable the NVIC USART IRQ handle - (used for last byte sending completion detection in DMA non circular mode) - - (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware - flow control and Mode(Receiver/Transmitter) in the huart Init structure. - - (#) For the UART asynchronous mode, initialize the UART registers by calling - the HAL_UART_Init() API. - - (#) For the UART Half duplex mode, initialize the UART registers by calling - the HAL_HalfDuplex_Init() API. - - (#) For the LIN mode, initialize the UART registers by calling the HAL_LIN_Init() API. - - (#) For the Multi-Processor mode, initialize the UART registers by calling - the HAL_MultiProcessor_Init() API. - - [..] - (@) The specific UART interrupts (Transmission complete interrupt, - RXNE interrupt and Error Interrupts) will be managed using the macros - __HAL_UART_ENABLE_IT() and __HAL_UART_DISABLE_IT() inside the transmit - and receive process. - - [..] - (@) These APIs (HAL_UART_Init() and HAL_HalfDuplex_Init()) configure also the - low level Hardware GPIO, CLOCK, CORTEX...etc) by calling the customized - HAL_UART_MspInit() API. - - ##### Callback registration ##### - ================================== - - [..] - The compilation define USE_HAL_UART_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - [..] - Use Function HAL_UART_RegisterCallback() to register a user callback. - Function HAL_UART_RegisterCallback() allows to register following callbacks: - (+) TxHalfCpltCallback : Tx Half Complete Callback. - (+) TxCpltCallback : Tx Complete Callback. - (+) RxHalfCpltCallback : Rx Half Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. - (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. - (+) MspInitCallback : UART MspInit. - (+) MspDeInitCallback : UART MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - Use function HAL_UART_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - HAL_UART_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxHalfCpltCallback : Tx Half Complete Callback. - (+) TxCpltCallback : Tx Complete Callback. - (+) RxHalfCpltCallback : Rx Half Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) AbortTransmitCpltCallback : Abort Transmit Complete Callback. - (+) AbortReceiveCpltCallback : Abort Receive Complete Callback. - (+) MspInitCallback : UART MspInit. - (+) MspDeInitCallback : UART MspDeInit. - - [..] - For specific callback RxEventCallback, use dedicated registration/reset functions: - respectively HAL_UART_RegisterRxEventCallback() , HAL_UART_UnRegisterRxEventCallback(). - - [..] - By default, after the HAL_UART_Init() and when the state is HAL_UART_STATE_RESET - all callbacks are set to the corresponding weak (surcharged) functions: - examples HAL_UART_TxCpltCallback(), HAL_UART_RxHalfCpltCallback(). - Exception done for MspInit and MspDeInit functions that are respectively - reset to the legacy weak (surcharged) functions in the HAL_UART_Init() - and HAL_UART_DeInit() only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the HAL_UART_Init() and HAL_UART_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in HAL_UART_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_UART_STATE_READY or HAL_UART_STATE_RESET state, thus registered (user) - MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using HAL_UART_RegisterCallback() before calling HAL_UART_DeInit() - or HAL_UART_Init() function. - - [..] - When The compilation define USE_HAL_UART_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available - and weak (surcharged) callbacks are used. - - [..] - Three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Send an amount of data in blocking mode using HAL_UART_Transmit() - (+) Receive an amount of data in blocking mode using HAL_UART_Receive() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Send an amount of data in non blocking mode using HAL_UART_Transmit_IT() - (+) At transmission end of transfer HAL_UART_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_TxCpltCallback - (+) Receive an amount of data in non blocking mode using HAL_UART_Receive_IT() - (+) At reception end of transfer HAL_UART_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_RxCpltCallback - (+) In case of transfer Error, HAL_UART_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_UART_ErrorCallback - - *** DMA mode IO operation *** - ============================== - [..] - (+) Send an amount of data in non blocking mode (DMA) using HAL_UART_Transmit_DMA() - (+) At transmission end of half transfer HAL_UART_TxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_TxHalfCpltCallback - (+) At transmission end of transfer HAL_UART_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_TxCpltCallback - (+) Receive an amount of data in non blocking mode (DMA) using HAL_UART_Receive_DMA() - (+) At reception end of half transfer HAL_UART_RxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_RxHalfCpltCallback - (+) At reception end of transfer HAL_UART_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_UART_RxCpltCallback - (+) In case of transfer Error, HAL_UART_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_UART_ErrorCallback - (+) Pause the DMA Transfer using HAL_UART_DMAPause() - (+) Resume the DMA Transfer using HAL_UART_DMAResume() - (+) Stop the DMA Transfer using HAL_UART_DMAStop() - - - [..] This subsection also provides a set of additional functions providing enhanced reception - services to user. (For example, these functions allow application to handle use cases - where number of data to be received is unknown). - - (#) Compared to standard reception services which only consider number of received - data elements as reception completion criteria, these functions also consider additional events - as triggers for updating reception status to caller : - (+) Detection of inactivity period (RX line has not been active for a given period). - (++) RX inactivity detected by IDLE event, i.e. RX line has been in idle state (normally high state) - for 1 frame time, after last received byte. - - (#) There are two mode of transfer: - (+) Blocking mode: The reception is performed in polling mode, until either expected number of data is received, - or till IDLE event occurs. Reception is handled only during function execution. - When function exits, no data reception could occur. HAL status and number of actually received data elements, - are returned by function after finishing transfer. - (+) Non-Blocking mode: The reception is performed using Interrupts or DMA. - These API's return the HAL status. - The end of the data processing will be indicated through the - dedicated UART IRQ when using Interrupt mode or the DMA IRQ when using DMA mode. - The HAL_UARTEx_RxEventCallback() user callback will be executed during Receive process - The HAL_UART_ErrorCallback()user callback will be executed when a reception error is detected. - - (#) Blocking mode API: - (+) HAL_UARTEx_ReceiveToIdle() - - (#) Non-Blocking mode API with Interrupt: - (+) HAL_UARTEx_ReceiveToIdle_IT() - - (#) Non-Blocking mode API with DMA: - (+) HAL_UARTEx_ReceiveToIdle_DMA() - - - *** UART HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in UART HAL driver. - - (+) __HAL_UART_ENABLE: Enable the UART peripheral - (+) __HAL_UART_DISABLE: Disable the UART peripheral - (+) __HAL_UART_GET_FLAG : Check whether the specified UART flag is set or not - (+) __HAL_UART_CLEAR_FLAG : Clear the specified UART pending flag - (+) __HAL_UART_ENABLE_IT: Enable the specified UART interrupt - (+) __HAL_UART_DISABLE_IT: Disable the specified UART interrupt - (+) __HAL_UART_GET_IT_SOURCE: Check whether the specified UART interrupt has occurred or not - - [..] - (@) You can refer to the UART HAL driver header file for more useful macros - - @endverbatim - [..] - (@) Additional remark: If the parity is enabled, then the MSB bit of the data written - in the data register is transmitted but is changed by the parity bit. - Depending on the frame length defined by the M bit (8-bits or 9-bits), - the possible UART frame formats are as listed in the following table: - +-------------------------------------------------------------+ - | M bit | PCE bit | UART frame | - |---------------------|---------------------------------------| - | 0 | 0 | | SB | 8 bit data | STB | | - |---------|-----------|---------------------------------------| - | 0 | 1 | | SB | 7 bit data | PB | STB | | - |---------|-----------|---------------------------------------| - | 1 | 0 | | SB | 9 bit data | STB | | - |---------|-----------|---------------------------------------| - | 1 | 1 | | SB | 8 bit data | PB | STB | | - +-------------------------------------------------------------+ - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup UART UART - * @brief HAL UART module driver - * @{ - */ -#ifdef HAL_UART_MODULE_ENABLED - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup UART_Private_Constants - * @{ - */ -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/** @addtogroup UART_Private_Functions UART Private Functions - * @{ - */ - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -void UART_InitCallbacksToDefault(UART_HandleTypeDef *huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -static void UART_EndTxTransfer(UART_HandleTypeDef *huart); -static void UART_EndRxTransfer(UART_HandleTypeDef *huart); -static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void UART_DMATxHalfCplt(DMA_HandleTypeDef *hdma); -static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma); -static void UART_DMAError(DMA_HandleTypeDef *hdma); -static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma); -static void UART_DMATxAbortCallback(DMA_HandleTypeDef *hdma); -static void UART_DMARxAbortCallback(DMA_HandleTypeDef *hdma); -static void UART_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma); -static void UART_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma); -static HAL_StatusTypeDef UART_Transmit_IT(UART_HandleTypeDef *huart); -static HAL_StatusTypeDef UART_EndTransmit_IT(UART_HandleTypeDef *huart); -static HAL_StatusTypeDef UART_Receive_IT(UART_HandleTypeDef *huart); -static HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, - uint32_t Tickstart, uint32_t Timeout); -static void UART_SetConfig(UART_HandleTypeDef *huart); - -/** - * @} - */ - -/* Exported functions ---------------------------------------------------------*/ -/** @defgroup UART_Exported_Functions UART Exported Functions - * @{ - */ - -/** @defgroup UART_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization and Configuration functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to initialize the USARTx or the UARTy - in asynchronous mode. - (+) For the asynchronous mode only these parameters can be configured: - (++) Baud Rate - (++) Word Length - (++) Stop Bit - (++) Parity: If the parity is enabled, then the MSB bit of the data written - in the data register is transmitted but is changed by the parity bit. - Depending on the frame length defined by the M bit (8-bits or 9-bits), - please refer to Reference manual for possible UART frame formats. - (++) Hardware flow control - (++) Receiver/transmitter modes - (++) Over Sampling Method - [..] - The HAL_UART_Init(), HAL_HalfDuplex_Init(), HAL_LIN_Init() and HAL_MultiProcessor_Init() APIs - follow respectively the UART asynchronous, UART Half duplex, LIN and Multi-Processor configuration - procedures (details for the procedures are available in reference manual - (RM0430 for STM32F4X3xx MCUs and RM0402 for STM32F412xx MCUs - RM0383 for STM32F411xC/E MCUs and RM0401 for STM32F410xx MCUs - RM0090 for STM32F4X5xx/STM32F4X7xx/STM32F429xx/STM32F439xx MCUs - RM0390 for STM32F446xx MCUs and RM0386 for STM32F469xx/STM32F479xx MCUs)). - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the UART mode according to the specified parameters in - * the UART_InitTypeDef and create the associated handle. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - if (huart->Init.HwFlowCtl != UART_HWCONTROL_NONE) - { - /* The hardware flow control is available only for USART1, USART2, USART3 and USART6. - Except for STM32F446xx devices, that is available for USART1, USART2, USART3, USART6, UART4 and UART5. - */ - assert_param(IS_UART_HWFLOW_INSTANCE(huart->Instance)); - assert_param(IS_UART_HARDWARE_FLOW_CONTROL(huart->Init.HwFlowCtl)); - } - else - { - assert_param(IS_UART_INSTANCE(huart->Instance)); - } - assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); - assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); - - if (huart->gState == HAL_UART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - huart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - UART_InitCallbacksToDefault(huart); - - if (huart->MspInitCallback == NULL) - { - huart->MspInitCallback = HAL_UART_MspInit; - } - - /* Init the low level hardware */ - huart->MspInitCallback(huart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_UART_MspInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - } - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the peripheral */ - __HAL_UART_DISABLE(huart); - - /* Set the UART Communication parameters */ - UART_SetConfig(huart); - - /* In asynchronous mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); - - /* Enable the peripheral */ - __HAL_UART_ENABLE(huart); - - /* Initialize the UART state */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initializes the half-duplex mode according to the specified - * parameters in the UART_InitTypeDef and create the associated handle. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_UART_HALFDUPLEX_INSTANCE(huart->Instance)); - assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); - assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); - - if (huart->gState == HAL_UART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - huart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - UART_InitCallbacksToDefault(huart); - - if (huart->MspInitCallback == NULL) - { - huart->MspInitCallback = HAL_UART_MspInit; - } - - /* Init the low level hardware */ - huart->MspInitCallback(huart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_UART_MspInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - } - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the peripheral */ - __HAL_UART_DISABLE(huart); - - /* Set the UART Communication parameters */ - UART_SetConfig(huart); - - /* In half-duplex mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(huart->Instance->CR3, (USART_CR3_IREN | USART_CR3_SCEN)); - - /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ - SET_BIT(huart->Instance->CR3, USART_CR3_HDSEL); - - /* Enable the peripheral */ - __HAL_UART_ENABLE(huart); - - /* Initialize the UART state*/ - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initializes the LIN mode according to the specified - * parameters in the UART_InitTypeDef and create the associated handle. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param BreakDetectLength Specifies the LIN break detection length. - * This parameter can be one of the following values: - * @arg UART_LINBREAKDETECTLENGTH_10B: 10-bit break detection - * @arg UART_LINBREAKDETECTLENGTH_11B: 11-bit break detection - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the LIN UART instance */ - assert_param(IS_UART_LIN_INSTANCE(huart->Instance)); - - /* Check the Break detection length parameter */ - assert_param(IS_UART_LIN_BREAK_DETECT_LENGTH(BreakDetectLength)); - assert_param(IS_UART_LIN_WORD_LENGTH(huart->Init.WordLength)); - assert_param(IS_UART_LIN_OVERSAMPLING(huart->Init.OverSampling)); - - if (huart->gState == HAL_UART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - huart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - UART_InitCallbacksToDefault(huart); - - if (huart->MspInitCallback == NULL) - { - huart->MspInitCallback = HAL_UART_MspInit; - } - - /* Init the low level hardware */ - huart->MspInitCallback(huart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_UART_MspInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - } - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the peripheral */ - __HAL_UART_DISABLE(huart); - - /* Set the UART Communication parameters */ - UART_SetConfig(huart); - - /* In LIN mode, the following bits must be kept cleared: - - CLKEN bits in the USART_CR2 register, - - SCEN, HDSEL and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(huart->Instance->CR2, (USART_CR2_CLKEN)); - CLEAR_BIT(huart->Instance->CR3, (USART_CR3_HDSEL | USART_CR3_IREN | USART_CR3_SCEN)); - - /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ - SET_BIT(huart->Instance->CR2, USART_CR2_LINEN); - - /* Set the USART LIN Break detection length. */ - CLEAR_BIT(huart->Instance->CR2, USART_CR2_LBDL); - SET_BIT(huart->Instance->CR2, BreakDetectLength); - - /* Enable the peripheral */ - __HAL_UART_ENABLE(huart); - - /* Initialize the UART state*/ - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Initializes the Multi-Processor mode according to the specified - * parameters in the UART_InitTypeDef and create the associated handle. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param Address USART address - * @param WakeUpMethod specifies the USART wake-up method. - * This parameter can be one of the following values: - * @arg UART_WAKEUPMETHOD_IDLELINE: Wake-up by an idle line detection - * @arg UART_WAKEUPMETHOD_ADDRESSMARK: Wake-up by an address mark - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - /* Check the Address & wake up method parameters */ - assert_param(IS_UART_WAKEUPMETHOD(WakeUpMethod)); - assert_param(IS_UART_ADDRESS(Address)); - assert_param(IS_UART_WORD_LENGTH(huart->Init.WordLength)); - assert_param(IS_UART_OVERSAMPLING(huart->Init.OverSampling)); - - if (huart->gState == HAL_UART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - huart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - UART_InitCallbacksToDefault(huart); - - if (huart->MspInitCallback == NULL) - { - huart->MspInitCallback = HAL_UART_MspInit; - } - - /* Init the low level hardware */ - huart->MspInitCallback(huart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_UART_MspInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - } - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the peripheral */ - __HAL_UART_DISABLE(huart); - - /* Set the UART Communication parameters */ - UART_SetConfig(huart); - - /* In Multi-Processor mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN, HDSEL and IREN bits in the USART_CR3 register */ - CLEAR_BIT(huart->Instance->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(huart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); - - /* Set the USART address node */ - CLEAR_BIT(huart->Instance->CR2, USART_CR2_ADD); - SET_BIT(huart->Instance->CR2, Address); - - /* Set the wake up method by setting the WAKE bit in the CR1 register */ - CLEAR_BIT(huart->Instance->CR1, USART_CR1_WAKE); - SET_BIT(huart->Instance->CR1, WakeUpMethod); - - /* Enable the peripheral */ - __HAL_UART_ENABLE(huart); - - /* Initialize the UART state */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the UART peripheral. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_DeInit(UART_HandleTypeDef *huart) -{ - /* Check the UART handle allocation */ - if (huart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_UART_DISABLE(huart); - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - if (huart->MspDeInitCallback == NULL) - { - huart->MspDeInitCallback = HAL_UART_MspDeInit; - } - /* DeInit the low level hardware */ - huart->MspDeInitCallback(huart); -#else - /* DeInit the low level hardware */ - HAL_UART_MspDeInit(huart); -#endif /* (USE_HAL_UART_REGISTER_CALLBACKS) */ - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_RESET; - huart->RxState = HAL_UART_STATE_RESET; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Process Unlock */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief UART MSP Init. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_MspInit(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_MspInit could be implemented in the user file - */ -} - -/** - * @brief UART MSP DeInit. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_MspDeInit(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User UART Callback - * To be used instead of the weak predefined callback - * @param huart uart handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_UART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID - * @arg @ref HAL_UART_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_UART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID - * @arg @ref HAL_UART_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_UART_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_UART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID - * @arg @ref HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID - * @arg @ref HAL_UART_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_UART_MSPDEINIT_CB_ID MspDeInit Callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_RegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID, - pUART_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(huart); - - if (huart->gState == HAL_UART_STATE_READY) - { - switch (CallbackID) - { - case HAL_UART_TX_HALFCOMPLETE_CB_ID : - huart->TxHalfCpltCallback = pCallback; - break; - - case HAL_UART_TX_COMPLETE_CB_ID : - huart->TxCpltCallback = pCallback; - break; - - case HAL_UART_RX_HALFCOMPLETE_CB_ID : - huart->RxHalfCpltCallback = pCallback; - break; - - case HAL_UART_RX_COMPLETE_CB_ID : - huart->RxCpltCallback = pCallback; - break; - - case HAL_UART_ERROR_CB_ID : - huart->ErrorCallback = pCallback; - break; - - case HAL_UART_ABORT_COMPLETE_CB_ID : - huart->AbortCpltCallback = pCallback; - break; - - case HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID : - huart->AbortTransmitCpltCallback = pCallback; - break; - - case HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID : - huart->AbortReceiveCpltCallback = pCallback; - break; - - case HAL_UART_MSPINIT_CB_ID : - huart->MspInitCallback = pCallback; - break; - - case HAL_UART_MSPDEINIT_CB_ID : - huart->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (huart->gState == HAL_UART_STATE_RESET) - { - switch (CallbackID) - { - case HAL_UART_MSPINIT_CB_ID : - huart->MspInitCallback = pCallback; - break; - - case HAL_UART_MSPDEINIT_CB_ID : - huart->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(huart); - - return status; -} - -/** - * @brief Unregister an UART Callback - * UART callaback is redirected to the weak predefined callback - * @param huart uart handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_UART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID - * @arg @ref HAL_UART_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_UART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID - * @arg @ref HAL_UART_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_UART_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_UART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID Abort Transmit Complete Callback ID - * @arg @ref HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID Abort Receive Complete Callback ID - * @arg @ref HAL_UART_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_UART_MSPDEINIT_CB_ID MspDeInit Callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_UnRegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(huart); - - if (HAL_UART_STATE_READY == huart->gState) - { - switch (CallbackID) - { - case HAL_UART_TX_HALFCOMPLETE_CB_ID : - huart->TxHalfCpltCallback = HAL_UART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - break; - - case HAL_UART_TX_COMPLETE_CB_ID : - huart->TxCpltCallback = HAL_UART_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_UART_RX_HALFCOMPLETE_CB_ID : - huart->RxHalfCpltCallback = HAL_UART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - break; - - case HAL_UART_RX_COMPLETE_CB_ID : - huart->RxCpltCallback = HAL_UART_RxCpltCallback; /* Legacy weak RxCpltCallback */ - break; - - case HAL_UART_ERROR_CB_ID : - huart->ErrorCallback = HAL_UART_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_UART_ABORT_COMPLETE_CB_ID : - huart->AbortCpltCallback = HAL_UART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID : - huart->AbortTransmitCpltCallback = HAL_UART_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ - break; - - case HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID : - huart->AbortReceiveCpltCallback = HAL_UART_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ - break; - - case HAL_UART_MSPINIT_CB_ID : - huart->MspInitCallback = HAL_UART_MspInit; /* Legacy weak MspInitCallback */ - break; - - case HAL_UART_MSPDEINIT_CB_ID : - huart->MspDeInitCallback = HAL_UART_MspDeInit; /* Legacy weak MspDeInitCallback */ - break; - - default : - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (HAL_UART_STATE_RESET == huart->gState) - { - switch (CallbackID) - { - case HAL_UART_MSPINIT_CB_ID : - huart->MspInitCallback = HAL_UART_MspInit; - break; - - case HAL_UART_MSPDEINIT_CB_ID : - huart->MspDeInitCallback = HAL_UART_MspDeInit; - break; - - default : - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(huart); - - return status; -} - -/** - * @brief Register a User UART Rx Event Callback - * To be used instead of the weak predefined callback - * @param huart Uart handle - * @param pCallback Pointer to the Rx Event Callback function - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pUART_RxEventCallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - - /* Process locked */ - __HAL_LOCK(huart); - - if (huart->gState == HAL_UART_STATE_READY) - { - huart->RxEventCallback = pCallback; - } - else - { - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(huart); - - return status; -} - -/** - * @brief UnRegister the UART Rx Event Callback - * UART Rx Event Callback is redirected to the weak HAL_UARTEx_RxEventCallback() predefined callback - * @param huart Uart handle - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(huart); - - if (huart->gState == HAL_UART_STATE_READY) - { - huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak UART Rx Event Callback */ - } - else - { - huart->ErrorCode |= HAL_UART_ERROR_INVALID_CALLBACK; - - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(huart); - return status; -} -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup UART_Exported_Functions_Group2 IO operation functions - * @brief UART Transmit and Receive functions - * -@verbatim - =============================================================================== - ##### IO operation functions ##### - =============================================================================== - This subsection provides a set of functions allowing to manage the UART asynchronous - and Half duplex data transfers. - - (#) There are two modes of transfer: - (+) Blocking mode: The communication is performed in polling mode. - The HAL status of all data processing is returned by the same function - after finishing transfer. - (+) Non-Blocking mode: The communication is performed using Interrupts - or DMA, these API's return the HAL status. - The end of the data processing will be indicated through the - dedicated UART IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - The HAL_UART_TxCpltCallback(), HAL_UART_RxCpltCallback() user callbacks - will be executed respectively at the end of the transmit or receive process - The HAL_UART_ErrorCallback()user callback will be executed when a communication error is detected. - - (#) Blocking mode API's are : - (+) HAL_UART_Transmit() - (+) HAL_UART_Receive() - - (#) Non-Blocking mode API's with Interrupt are : - (+) HAL_UART_Transmit_IT() - (+) HAL_UART_Receive_IT() - (+) HAL_UART_IRQHandler() - - (#) Non-Blocking mode API's with DMA are : - (+) HAL_UART_Transmit_DMA() - (+) HAL_UART_Receive_DMA() - (+) HAL_UART_DMAPause() - (+) HAL_UART_DMAResume() - (+) HAL_UART_DMAStop() - - (#) A set of Transfer Complete Callbacks are provided in Non_Blocking mode: - (+) HAL_UART_TxHalfCpltCallback() - (+) HAL_UART_TxCpltCallback() - (+) HAL_UART_RxHalfCpltCallback() - (+) HAL_UART_RxCpltCallback() - (+) HAL_UART_ErrorCallback() - - (#) Non-Blocking mode transfers could be aborted using Abort API's : - (+) HAL_UART_Abort() - (+) HAL_UART_AbortTransmit() - (+) HAL_UART_AbortReceive() - (+) HAL_UART_Abort_IT() - (+) HAL_UART_AbortTransmit_IT() - (+) HAL_UART_AbortReceive_IT() - - (#) For Abort services based on interrupts (HAL_UART_Abortxxx_IT), a set of Abort Complete Callbacks are provided: - (+) HAL_UART_AbortCpltCallback() - (+) HAL_UART_AbortTransmitCpltCallback() - (+) HAL_UART_AbortReceiveCpltCallback() - - (#) A Rx Event Reception Callback (Rx event notification) is available for Non_Blocking modes of enhanced reception services: - (+) HAL_UARTEx_RxEventCallback() - - (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. - Errors are handled as follows : - (+) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is - to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . - Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, - and HAL_UART_ErrorCallback() user callback is executed. Transfer is kept ongoing on UART side. - If user wants to abort it, Abort services should be called by user. - (+) Error is considered as Blocking : Transfer could not be completed properly and is aborted. - This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode. - Error code is set to allow user to identify error type, and HAL_UART_ErrorCallback() user callback is executed. - - -@- In the Half duplex communication, it is forbidden to run the transmit - and receive process in parallel, the UART state HAL_UART_STATE_BUSY_TX_RX can't be useful. - -@endverbatim - * @{ - */ - -/** - * @brief Sends an amount of data in blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - uint32_t tickstart = 0U; - - /* Check that a Tx process is not already ongoing */ - if (huart->gState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_BUSY_TX; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - huart->TxXferSize = Size; - huart->TxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pData needs to be handled as a uint16_t pointer */ - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) pData; - } - else - { - pdata8bits = pData; - pdata16bits = NULL; - } - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - while (huart->TxXferCount > 0U) - { - if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - if (pdata8bits == NULL) - { - huart->Instance->DR = (uint16_t)(*pdata16bits & 0x01FFU); - pdata16bits++; - } - else - { - huart->Instance->DR = (uint8_t)(*pdata8bits & 0xFFU); - pdata8bits++; - } - huart->TxXferCount--; - } - - if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - /* At end of Tx process, restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives an amount of data in blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - uint32_t tickstart = 0U; - - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->RxState = HAL_UART_STATE_BUSY_RX; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - huart->RxXferSize = Size; - huart->RxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) pData; - } - else - { - pdata8bits = pData; - pdata16bits = NULL; - } - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - /* Check the remain data to be received */ - while (huart->RxXferCount > 0U) - { - if (UART_WaitOnFlagUntilTimeout(huart, UART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - if (pdata8bits == NULL) - { - *pdata16bits = (uint16_t)(huart->Instance->DR & 0x01FF); - pdata16bits++; - } - else - { - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); - } - pdata8bits++; - } - huart->RxXferCount--; - } - - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sends an amount of data in non blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - /* Check that a Tx process is not already ongoing */ - if (huart->gState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->pTxBuffPtr = pData; - huart->TxXferSize = Size; - huart->TxXferCount = Size; - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_BUSY_TX; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - /* Enable the UART Transmit data register empty Interrupt */ - __HAL_UART_ENABLE_IT(huart, UART_IT_TXE); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives an amount of data in non blocking mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - /* Set Reception type to Standard reception */ - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - return (UART_Start_Receive_IT(huart, pData, Size)); - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Sends an amount of data in DMA mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - uint32_t *tmp; - - /* Check that a Tx process is not already ongoing */ - if (huart->gState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->pTxBuffPtr = pData; - huart->TxXferSize = Size; - huart->TxXferCount = Size; - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->gState = HAL_UART_STATE_BUSY_TX; - - /* Set the UART DMA transfer complete callback */ - huart->hdmatx->XferCpltCallback = UART_DMATransmitCplt; - - /* Set the UART DMA Half transfer complete callback */ - huart->hdmatx->XferHalfCpltCallback = UART_DMATxHalfCplt; - - /* Set the DMA error callback */ - huart->hdmatx->XferErrorCallback = UART_DMAError; - - /* Set the DMA abort callback */ - huart->hdmatx->XferAbortCallback = NULL; - - /* Enable the UART transmit DMA stream */ - tmp = (uint32_t *)&pData; - HAL_DMA_Start_IT(huart->hdmatx, *(uint32_t *)tmp, (uint32_t)&huart->Instance->DR, Size); - - /* Clear the TC flag in the SR register by writing 0 to it */ - __HAL_UART_CLEAR_FLAG(huart, UART_FLAG_TC); - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - /* Enable the DMA transfer for transmit request by setting the DMAT bit - in the UART CR3 register */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receives an amount of data in DMA mode. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pData. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @note When the UART parity is enabled (PCE = 1) the received data contains the parity bit. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(huart); - - /* Set Reception type to Standard reception */ - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - return (UART_Start_Receive_DMA(huart, pData, Size)); - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Pauses the DMA Transfer. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart) -{ - uint32_t dmarequest = 0x00U; - - /* Process Locked */ - __HAL_LOCK(huart); - - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); - if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) - { - /* Disable the UART DMA Tx request */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - } - - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); - if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) - { - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Disable the UART DMA Rx request */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Resumes the DMA Transfer. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart) -{ - /* Process Locked */ - __HAL_LOCK(huart); - - if (huart->gState == HAL_UART_STATE_BUSY_TX) - { - /* Enable the UART DMA Tx request */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAT); - } - - if (huart->RxState == HAL_UART_STATE_BUSY_RX) - { - /* Clear the Overrun flag before resuming the Rx transfer*/ - __HAL_UART_CLEAR_OREFLAG(huart); - - /* Re-enable PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_PEIE); - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Enable the UART DMA Rx request */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAR); - } - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Stops the DMA Transfer. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart) -{ - uint32_t dmarequest = 0x00U; - /* The Lock is not implemented on this API to allow the user application - to call the HAL UART API under callbacks HAL_UART_TxCpltCallback() / HAL_UART_RxCpltCallback(): - when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated - and the correspond call back is executed HAL_UART_TxCpltCallback() / HAL_UART_RxCpltCallback() - */ - - /* Stop UART DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); - if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream */ - if (huart->hdmatx != NULL) - { - HAL_DMA_Abort(huart->hdmatx); - } - UART_EndTxTransfer(huart); - } - - /* Stop UART DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); - if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream */ - if (huart->hdmarx != NULL) - { - HAL_DMA_Abort(huart->hdmarx); - } - UART_EndRxTransfer(huart); - } - - return HAL_OK; -} - -/** - * @brief Receive an amount of data in blocking mode till either the expected number of data is received or an IDLE event occurs. - * @note HAL_OK is returned if reception is completed (expected number of data has been received) - * or if reception is stopped after IDLE event (less than the expected number of data has been received) - * In this case, RxLen output parameter indicates number of data available in reception buffer. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), - * the received data is handled as a set of uint16_t. In this case, Size must indicate the number - * of uint16_t available through pData. - * @param huart UART handle. - * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). - * @param Size Amount of data elements (uint8_t or uint16_t) to be received. - * @param RxLen Number of data elements finally received (could be lower than Size, in case reception ends on IDLE event) - * @param Timeout Timeout duration expressed in ms (covers the whole reception sequence). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen, - uint32_t Timeout) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - uint32_t tickstart; - - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - __HAL_LOCK(huart); - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->RxState = HAL_UART_STATE_BUSY_RX; - huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - huart->RxXferSize = Size; - huart->RxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) pData; - } - else - { - pdata8bits = pData; - pdata16bits = NULL; - } - - __HAL_UNLOCK(huart); - - /* Initialize output number of received elements */ - *RxLen = 0U; - - /* as long as data have to be received */ - while (huart->RxXferCount > 0U) - { - /* Check if IDLE flag is set */ - if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE)) - { - /* Clear IDLE flag in ISR */ - __HAL_UART_CLEAR_IDLEFLAG(huart); - - /* If Set, but no data ever received, clear flag without exiting loop */ - /* If Set, and data has already been received, this means Idle Event is valid : End reception */ - if (*RxLen > 0U) - { - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; - } - } - - /* Check if RXNE flag is set */ - if (__HAL_UART_GET_FLAG(huart, UART_FLAG_RXNE)) - { - if (pdata8bits == NULL) - { - *pdata16bits = (uint16_t)(huart->Instance->DR & (uint16_t)0x01FF); - pdata16bits++; - } - else - { - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); - } - - pdata8bits++; - } - /* Increment number of received elements */ - *RxLen += 1U; - huart->RxXferCount--; - } - - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0U)) - { - huart->RxState = HAL_UART_STATE_READY; - - return HAL_TIMEOUT; - } - } - } - - /* Set number of received elements in output parameter : RxLen */ - *RxLen = huart->RxXferSize - huart->RxXferCount; - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in interrupt mode till either the expected number of data is received or an IDLE event occurs. - * @note Reception is initiated by this function call. Further progress of reception is achieved thanks - * to UART interrupts raised by RXNE and IDLE events. Callback is called at end of reception indicating - * number of received data elements. - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), - * the received data is handled as a set of uint16_t. In this case, Size must indicate the number - * of uint16_t available through pData. - * @param huart UART handle. - * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). - * @param Size Amount of data elements (uint8_t or uint16_t) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef status; - - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - __HAL_LOCK(huart); - - /* Set Reception type to reception till IDLE Event*/ - huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; - - status = UART_Start_Receive_IT(huart, pData, Size); - - /* Check Rx process has been successfully started */ - if (status == HAL_OK) - { - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - __HAL_UART_CLEAR_IDLEFLAG(huart); - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - } - else - { - /* In case of errors already pending when reception is started, - Interrupts may have already been raised and lead to reception abortion. - (Overrun error for instance). - In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */ - status = HAL_ERROR; - } - } - - return status; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Receive an amount of data in DMA mode till either the expected number of data is received or an IDLE event occurs. - * @note Reception is initiated by this function call. Further progress of reception is achieved thanks - * to DMA services, transferring automatically received data elements in user reception buffer and - * calling registered callbacks at half/end of reception. UART IDLE events are also used to consider - * reception phase as ended. In all cases, callback execution will indicate number of received data elements. - * @note When the UART parity is enabled (PCE = 1), the received data contain - * the parity bit (MSB position). - * @note When UART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M = 01), - * the received data is handled as a set of uint16_t. In this case, Size must indicate the number - * of uint16_t available through pData. - * @param huart UART handle. - * @param pData Pointer to data buffer (uint8_t or uint16_t data elements). - * @param Size Amount of data elements (uint8_t or uint16_t) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - HAL_StatusTypeDef status; - - /* Check that a Rx process is not already ongoing */ - if (huart->RxState == HAL_UART_STATE_READY) - { - if ((pData == NULL) || (Size == 0U)) - { - return HAL_ERROR; - } - - __HAL_LOCK(huart); - - /* Set Reception type to reception till IDLE Event*/ - huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; - - status = UART_Start_Receive_DMA(huart, pData, Size); - - /* Check Rx process has been successfully started */ - if (status == HAL_OK) - { - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - __HAL_UART_CLEAR_IDLEFLAG(huart); - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - } - else - { - /* In case of errors already pending when reception is started, - Interrupts may have already been raised and lead to reception abortion. - (Overrun error for instance). - In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */ - status = HAL_ERROR; - } - } - - return status; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Abort ongoing transfers (blocking mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Tx and Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Abort(UART_HandleTypeDef *huart) -{ - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); - } - - /* Disable the UART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream: use blocking DMA Abort API (no callback) */ - if (huart->hdmatx != NULL) - { - /* Set the UART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - huart->hdmatx->XferAbortCallback = NULL; - - if (HAL_DMA_Abort(huart->hdmatx) != HAL_OK) - { - if (HAL_DMA_GetError(huart->hdmatx) == HAL_DMA_ERROR_TIMEOUT) - { - /* Set error code to DMA */ - huart->ErrorCode = HAL_UART_ERROR_DMA; - - return HAL_TIMEOUT; - } - } - } - } - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream: use blocking DMA Abort API (no callback) */ - if (huart->hdmarx != NULL) - { - /* Set the UART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - huart->hdmarx->XferAbortCallback = NULL; - - if (HAL_DMA_Abort(huart->hdmarx) != HAL_OK) - { - if (HAL_DMA_GetError(huart->hdmarx) == HAL_DMA_ERROR_TIMEOUT) - { - /* Set error code to DMA */ - huart->ErrorCode = HAL_UART_ERROR_DMA; - - return HAL_TIMEOUT; - } - } - } - } - - /* Reset Tx and Rx transfer counters */ - huart->TxXferCount = 0x00U; - huart->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - - /* Restore huart->RxState and huart->gState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->gState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - return HAL_OK; -} - -/** - * @brief Abort ongoing Transmit transfer (blocking mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Tx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_AbortTransmit(UART_HandleTypeDef *huart) -{ - /* Disable TXEIE and TCIE interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* Disable the UART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream : use blocking DMA Abort API (no callback) */ - if (huart->hdmatx != NULL) - { - /* Set the UART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - huart->hdmatx->XferAbortCallback = NULL; - - if (HAL_DMA_Abort(huart->hdmatx) != HAL_OK) - { - if (HAL_DMA_GetError(huart->hdmatx) == HAL_DMA_ERROR_TIMEOUT) - { - /* Set error code to DMA */ - huart->ErrorCode = HAL_UART_ERROR_DMA; - - return HAL_TIMEOUT; - } - } - } - } - - /* Reset Tx transfer counter */ - huart->TxXferCount = 0x00U; - - /* Restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief Abort ongoing Receive transfer (blocking mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_AbortReceive(UART_HandleTypeDef *huart) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); - } - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream : use blocking DMA Abort API (no callback) */ - if (huart->hdmarx != NULL) - { - /* Set the UART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - huart->hdmarx->XferAbortCallback = NULL; - - if (HAL_DMA_Abort(huart->hdmarx) != HAL_OK) - { - if (HAL_DMA_GetError(huart->hdmarx) == HAL_DMA_ERROR_TIMEOUT) - { - /* Set error code to DMA */ - huart->ErrorCode = HAL_UART_ERROR_DMA; - - return HAL_TIMEOUT; - } - } - } - } - - /* Reset Rx transfer counter */ - huart->RxXferCount = 0x00U; - - /* Restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - return HAL_OK; -} - -/** - * @brief Abort ongoing transfers (Interrupt mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Tx and Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_Abort_IT(UART_HandleTypeDef *huart) -{ - uint32_t AbortCplt = 0x01U; - - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); - } - - /* If DMA Tx and/or DMA Rx Handles are associated to UART Handle, DMA Abort complete callbacks should be initialised - before any call to DMA Abort functions */ - /* DMA Tx Handle is valid */ - if (huart->hdmatx != NULL) - { - /* Set DMA Abort Complete callback if UART DMA Tx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - huart->hdmatx->XferAbortCallback = UART_DMATxAbortCallback; - } - else - { - huart->hdmatx->XferAbortCallback = NULL; - } - } - /* DMA Rx Handle is valid */ - if (huart->hdmarx != NULL) - { - /* Set DMA Abort Complete callback if UART DMA Rx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - huart->hdmarx->XferAbortCallback = UART_DMARxAbortCallback; - } - else - { - huart->hdmarx->XferAbortCallback = NULL; - } - } - - /* Disable the UART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - /* Disable DMA Tx at UART level */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream : use non blocking DMA Abort API (callback) */ - if (huart->hdmatx != NULL) - { - /* UART Tx DMA Abort callback has already been initialised : - will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(huart->hdmatx) != HAL_OK) - { - huart->hdmatx->XferAbortCallback = NULL; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream : use non blocking DMA Abort API (callback) */ - if (huart->hdmarx != NULL) - { - /* UART Rx DMA Abort callback has already been initialised : - will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) - { - huart->hdmarx->XferAbortCallback = NULL; - AbortCplt = 0x01U; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ - if (AbortCplt == 0x01U) - { - /* Reset Tx and Rx transfer counters */ - huart->TxXferCount = 0x00U; - huart->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - - /* Restore huart->gState and huart->RxState to Ready */ - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - huart->AbortCpltCallback(huart); -#else - /* Call legacy weak Abort complete callback */ - HAL_UART_AbortCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing Transmit transfer (Interrupt mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Tx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_AbortTransmit_IT(UART_HandleTypeDef *huart) -{ - /* Disable TXEIE and TCIE interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* Disable the UART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the UART DMA Tx stream : use blocking DMA Abort API (no callback) */ - if (huart->hdmatx != NULL) - { - /* Set the UART DMA Abort callback : - will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ - huart->hdmatx->XferAbortCallback = UART_DMATxOnlyAbortCallback; - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(huart->hdmatx) != HAL_OK) - { - /* Call Directly huart->hdmatx->XferAbortCallback function in case of error */ - huart->hdmatx->XferAbortCallback(huart->hdmatx); - } - } - else - { - /* Reset Tx transfer counter */ - huart->TxXferCount = 0x00U; - - /* Restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - huart->AbortTransmitCpltCallback(huart); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_UART_AbortTransmitCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - } - else - { - /* Reset Tx transfer counter */ - huart->TxXferCount = 0x00U; - - /* Restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - huart->AbortTransmitCpltCallback(huart); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_UART_AbortTransmitCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing Receive transfer (Interrupt mode). - * @param huart UART handle. - * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable UART Interrupts (Rx) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_UART_AbortReceive_IT(UART_HandleTypeDef *huart) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* If Reception till IDLE event was ongoing, disable IDLEIE interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_IDLEIE)); - } - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream : use blocking DMA Abort API (no callback) */ - if (huart->hdmarx != NULL) - { - /* Set the UART DMA Abort callback : - will lead to call HAL_UART_AbortCpltCallback() at end of DMA abort procedure */ - huart->hdmarx->XferAbortCallback = UART_DMARxOnlyAbortCallback; - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) - { - /* Call Directly huart->hdmarx->XferAbortCallback function in case of error */ - huart->hdmarx->XferAbortCallback(huart->hdmarx); - } - } - else - { - /* Reset Rx transfer counter */ - huart->RxXferCount = 0x00U; - - /* Restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - huart->AbortReceiveCpltCallback(huart); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_UART_AbortReceiveCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - } - else - { - /* Reset Rx transfer counter */ - huart->RxXferCount = 0x00U; - - /* Restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - huart->AbortReceiveCpltCallback(huart); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_UART_AbortReceiveCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - - return HAL_OK; -} - -/** - * @brief This function handles UART interrupt request. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -void HAL_UART_IRQHandler(UART_HandleTypeDef *huart) -{ - uint32_t isrflags = READ_REG(huart->Instance->SR); - uint32_t cr1its = READ_REG(huart->Instance->CR1); - uint32_t cr3its = READ_REG(huart->Instance->CR3); - uint32_t errorflags = 0x00U; - uint32_t dmarequest = 0x00U; - - /* If no error occurs */ - errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); - if (errorflags == RESET) - { - /* UART in mode Receiver -------------------------------------------------*/ - if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - UART_Receive_IT(huart); - return; - } - } - - /* If some errors occur */ - if ((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) - || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) - { - /* UART parity error interrupt occurred ----------------------------------*/ - if (((isrflags & USART_SR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) - { - huart->ErrorCode |= HAL_UART_ERROR_PE; - } - - /* UART noise error interrupt occurred -----------------------------------*/ - if (((isrflags & USART_SR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - huart->ErrorCode |= HAL_UART_ERROR_NE; - } - - /* UART frame error interrupt occurred -----------------------------------*/ - if (((isrflags & USART_SR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - huart->ErrorCode |= HAL_UART_ERROR_FE; - } - - /* UART Over-Run interrupt occurred --------------------------------------*/ - if (((isrflags & USART_SR_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) - || ((cr3its & USART_CR3_EIE) != RESET))) - { - huart->ErrorCode |= HAL_UART_ERROR_ORE; - } - - /* Call UART Error Call back function if need be --------------------------*/ - if (huart->ErrorCode != HAL_UART_ERROR_NONE) - { - /* UART in mode Receiver -----------------------------------------------*/ - if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - UART_Receive_IT(huart); - } - - /* If Overrun error occurs, or if any error occurs in DMA mode reception, - consider error as blocking */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); - if (((huart->ErrorCode & HAL_UART_ERROR_ORE) != RESET) || dmarequest) - { - /* Blocking error : transfer is aborted - Set the UART state ready to be able to start again the process, - Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ - UART_EndRxTransfer(huart); - - /* Disable the UART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the UART DMA Rx stream */ - if (huart->hdmarx != NULL) - { - /* Set the UART DMA Abort callback : - will lead to call HAL_UART_ErrorCallback() at end of DMA abort procedure */ - huart->hdmarx->XferAbortCallback = UART_DMAAbortOnError; - if (HAL_DMA_Abort_IT(huart->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - huart->hdmarx->XferAbortCallback(huart->hdmarx); - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - } - else - { - /* Non Blocking error : transfer could go on. - Error is notified to user through user error callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - - huart->ErrorCode = HAL_UART_ERROR_NONE; - } - } - return; - } /* End if some error occurs */ - - /* Check current reception Mode : - If Reception till IDLE event has been selected : */ - if ((huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - && ((isrflags & USART_SR_IDLE) != 0U) - && ((cr1its & USART_SR_IDLE) != 0U)) - { - __HAL_UART_CLEAR_IDLEFLAG(huart); - - /* Check if DMA mode is enabled in UART */ - if (HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR)) - { - /* DMA mode enabled */ - /* Check received length : If all expected data are received, do nothing, - (DMA cplt callback will be called). - Otherwise, if at least one data has already been received, IDLE event is to be notified to user */ - uint16_t nb_remaining_rx_data = (uint16_t) __HAL_DMA_GET_COUNTER(huart->hdmarx); - if ((nb_remaining_rx_data > 0U) - && (nb_remaining_rx_data < huart->RxXferSize)) - { - /* Reception is not complete */ - huart->RxXferCount = nb_remaining_rx_data; - - /* In Normal mode, end DMA xfer and HAL UART Rx process*/ - if (huart->hdmarx->Init.Mode != DMA_CIRCULAR) - { - /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Disable the DMA transfer for the receiver request by resetting the DMAR bit - in the UART CR3 register */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - - /* Last bytes received, so no need as the abort is immediate */ - (void)HAL_DMA_Abort(huart->hdmarx); - } -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Event callback*/ - huart->RxEventCallback(huart, (huart->RxXferSize - huart->RxXferCount)); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, (huart->RxXferSize - huart->RxXferCount)); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - return; - } - else - { - /* DMA mode not enabled */ - /* Check received length : If all expected data are received, do nothing. - Otherwise, if at least one data has already been received, IDLE event is to be notified to user */ - uint16_t nb_rx_data = huart->RxXferSize - huart->RxXferCount; - if ((huart->RxXferCount > 0U) - && (nb_rx_data > 0U)) - { - /* Disable the UART Parity Error Interrupt and RXNE interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - - /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Rx process is completed, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx complete callback*/ - huart->RxEventCallback(huart, nb_rx_data); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, nb_rx_data); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - return; - } - } - - /* UART in mode Transmitter ------------------------------------------------*/ - if (((isrflags & USART_SR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) - { - UART_Transmit_IT(huart); - return; - } - - /* UART in mode Transmitter end --------------------------------------------*/ - if (((isrflags & USART_SR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) - { - UART_EndTransmit_IT(huart); - return; - } -} - -/** - * @brief Tx Transfer completed callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx Half Transfer completed callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_TxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Half Transfer completed callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_RxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief UART error callbacks. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -__weak void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_UART_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief UART Abort Complete callback. - * @param huart UART handle. - * @retval None - */ -__weak void HAL_UART_AbortCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_UART_AbortCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief UART Abort Complete callback. - * @param huart UART handle. - * @retval None - */ -__weak void HAL_UART_AbortTransmitCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_UART_AbortTransmitCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief UART Abort Receive Complete callback. - * @param huart UART handle. - * @retval None - */ -__weak void HAL_UART_AbortReceiveCpltCallback(UART_HandleTypeDef *huart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_UART_AbortReceiveCpltCallback can be implemented in the user file. - */ -} - -/** - * @brief Reception Event Callback (Rx event notification called after use of advanced reception service). - * @param huart UART handle - * @param Size Number of data available in application reception buffer (indicates a position in - * reception buffer until which, data are available) - * @retval None - */ -__weak void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(huart); - UNUSED(Size); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_UARTEx_RxEventCallback can be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup UART_Exported_Functions_Group3 Peripheral Control functions - * @brief UART control functions - * -@verbatim - ============================================================================== - ##### Peripheral Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control the UART: - (+) HAL_LIN_SendBreak() API can be helpful to transmit the break character. - (+) HAL_MultiProcessor_EnterMuteMode() API can be helpful to enter the UART in mute mode. - (+) HAL_MultiProcessor_ExitMuteMode() API can be helpful to exit the UART mute mode by software. - (+) HAL_HalfDuplex_EnableTransmitter() API to enable the UART transmitter and disables the UART receiver in Half Duplex mode - (+) HAL_HalfDuplex_EnableReceiver() API to enable the UART receiver and disables the UART transmitter in Half Duplex mode - -@endverbatim - * @{ - */ - -/** - * @brief Transmits break characters. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart) -{ - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /* Send break characters */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_SBK); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Enters the UART in mute mode. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart) -{ - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_RWU); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Exits the UART mute mode: wake up software. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart) -{ - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(huart->Instance)); - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_RWU); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Enables the UART transmitter and disables the UART receiver. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart) -{ - uint32_t tmpreg = 0x00U; - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /*-------------------------- USART CR1 Configuration -----------------------*/ - tmpreg = huart->Instance->CR1; - - /* Clear TE and RE bits */ - tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_TE | USART_CR1_RE)); - - /* Enable the USART's transmit interface by setting the TE bit in the USART CR1 register */ - tmpreg |= (uint32_t)USART_CR1_TE; - - /* Write to USART CR1 */ - WRITE_REG(huart->Instance->CR1, (uint32_t)tmpreg); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @brief Enables the UART receiver and disables the UART transmitter. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart) -{ - uint32_t tmpreg = 0x00U; - - /* Process Locked */ - __HAL_LOCK(huart); - - huart->gState = HAL_UART_STATE_BUSY; - - /*-------------------------- USART CR1 Configuration -----------------------*/ - tmpreg = huart->Instance->CR1; - - /* Clear TE and RE bits */ - tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_TE | USART_CR1_RE)); - - /* Enable the USART's receive interface by setting the RE bit in the USART CR1 register */ - tmpreg |= (uint32_t)USART_CR1_RE; - - /* Write to USART CR1 */ - WRITE_REG(huart->Instance->CR1, (uint32_t)tmpreg); - - huart->gState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup UART_Exported_Functions_Group4 Peripheral State and Errors functions - * @brief UART State and Errors functions - * -@verbatim - ============================================================================== - ##### Peripheral State and Errors functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to return the State of - UART communication process, return Peripheral Errors occurred during communication - process - (+) HAL_UART_GetState() API can be helpful to check in run-time the state of the UART peripheral. - (+) HAL_UART_GetError() check in run-time errors that could be occurred during communication. - -@endverbatim - * @{ - */ - -/** - * @brief Returns the UART state. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL state - */ -HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart) -{ - uint32_t temp1 = 0x00U, temp2 = 0x00U; - temp1 = huart->gState; - temp2 = huart->RxState; - - return (HAL_UART_StateTypeDef)(temp1 | temp2); -} - -/** - * @brief Return the UART error code - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART. - * @retval UART Error Code - */ -uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart) -{ - return huart->ErrorCode; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup UART_Private_Functions UART Private Functions - * @{ - */ - -/** - * @brief Initialize the callbacks to their default values. - * @param huart UART handle. - * @retval none - */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -void UART_InitCallbacksToDefault(UART_HandleTypeDef *huart) -{ - /* Init the UART Callback settings */ - huart->TxHalfCpltCallback = HAL_UART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - huart->TxCpltCallback = HAL_UART_TxCpltCallback; /* Legacy weak TxCpltCallback */ - huart->RxHalfCpltCallback = HAL_UART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - huart->RxCpltCallback = HAL_UART_RxCpltCallback; /* Legacy weak RxCpltCallback */ - huart->ErrorCallback = HAL_UART_ErrorCallback; /* Legacy weak ErrorCallback */ - huart->AbortCpltCallback = HAL_UART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - huart->AbortTransmitCpltCallback = HAL_UART_AbortTransmitCpltCallback; /* Legacy weak AbortTransmitCpltCallback */ - huart->AbortReceiveCpltCallback = HAL_UART_AbortReceiveCpltCallback; /* Legacy weak AbortReceiveCpltCallback */ - huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak RxEventCallback */ - -} -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @brief DMA UART transmit process complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* DMA Normal mode*/ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) - { - huart->TxXferCount = 0x00U; - - /* Disable the DMA transfer for transmit request by setting the DMAT bit - in the UART CR3 register */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAT); - - /* Enable the UART Transmit Complete Interrupt */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_TCIE); - - } - /* DMA Circular mode */ - else - { -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Tx complete callback*/ - huart->TxCpltCallback(huart); -#else - /*Call legacy weak Tx complete callback*/ - HAL_UART_TxCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA UART transmit process half complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMATxHalfCplt(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Tx complete callback*/ - huart->TxHalfCpltCallback(huart); -#else - /*Call legacy weak Tx complete callback*/ - HAL_UART_TxHalfCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART receive process complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* DMA Normal mode*/ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) - { - huart->RxXferCount = 0U; - - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_PEIE); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Disable the DMA transfer for the receiver request by setting the DMAR bit - in the UART CR3 register */ - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - - /* If Reception till IDLE event has been selected, Disable IDLE Interrupt */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - } - } - - /* Check current reception Mode : - If Reception till IDLE event has been selected : use Rx Event callback */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Event callback*/ - huart->RxEventCallback(huart, huart->RxXferSize); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - else - { - /* In other cases : use Rx Complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx complete callback*/ - huart->RxCpltCallback(huart); -#else - /*Call legacy weak Rx complete callback*/ - HAL_UART_RxCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA UART receive process half complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Check current reception Mode : - If Reception till IDLE event has been selected : use Rx Event callback */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Event callback*/ - huart->RxEventCallback(huart, huart->RxXferSize / 2U); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize / 2U); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - else - { - /* In other cases : use Rx Half Complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Half complete callback*/ - huart->RxHalfCpltCallback(huart); -#else - /*Call legacy weak Rx Half complete callback*/ - HAL_UART_RxHalfCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } -} - -/** - * @brief DMA UART communication error callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMAError(DMA_HandleTypeDef *hdma) -{ - uint32_t dmarequest = 0x00U; - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - /* Stop UART DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAT); - if ((huart->gState == HAL_UART_STATE_BUSY_TX) && dmarequest) - { - huart->TxXferCount = 0x00U; - UART_EndTxTransfer(huart); - } - - /* Stop UART DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(huart->Instance->CR3, USART_CR3_DMAR); - if ((huart->RxState == HAL_UART_STATE_BUSY_RX) && dmarequest) - { - huart->RxXferCount = 0x00U; - UART_EndRxTransfer(huart); - } - - huart->ErrorCode |= HAL_UART_ERROR_DMA; -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief This function handles UART Communication Timeout. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @param Flag specifies the UART flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Tickstart Tick start value - * @param Timeout Timeout duration - * @retval HAL status - */ -static HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_t Flag, FlagStatus Status, - uint32_t Tickstart, uint32_t Timeout) -{ - /* Wait until flag is set */ - while ((__HAL_UART_GET_FLAG(huart, Flag) ? SET : RESET) == Status) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) - { - /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - return HAL_TIMEOUT; - } - } - } - return HAL_OK; -} - -/** - * @brief Start Receive operation in interrupt mode. - * @note This function could be called by all HAL UART API providing reception in Interrupt mode. - * @note When calling this function, parameters validity is considered as already checked, - * i.e. Rx State, buffer address, ... - * UART Handle is assumed as Locked. - * @param huart UART handle. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef UART_Start_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - huart->pRxBuffPtr = pData; - huart->RxXferSize = Size; - huart->RxXferCount = Size; - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->RxState = HAL_UART_STATE_BUSY_RX; - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - /* Enable the UART Parity Error Interrupt */ - __HAL_UART_ENABLE_IT(huart, UART_IT_PE); - - /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ - __HAL_UART_ENABLE_IT(huart, UART_IT_ERR); - - /* Enable the UART Data Register not empty Interrupt */ - __HAL_UART_ENABLE_IT(huart, UART_IT_RXNE); - - return HAL_OK; -} - -/** - * @brief Start Receive operation in DMA mode. - * @note This function could be called by all HAL UART API providing reception in DMA mode. - * @note When calling this function, parameters validity is considered as already checked, - * i.e. Rx State, buffer address, ... - * UART Handle is assumed as Locked. - * @param huart UART handle. - * @param pData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef UART_Start_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) -{ - uint32_t *tmp; - - huart->pRxBuffPtr = pData; - huart->RxXferSize = Size; - - huart->ErrorCode = HAL_UART_ERROR_NONE; - huart->RxState = HAL_UART_STATE_BUSY_RX; - - /* Set the UART DMA transfer complete callback */ - huart->hdmarx->XferCpltCallback = UART_DMAReceiveCplt; - - /* Set the UART DMA Half transfer complete callback */ - huart->hdmarx->XferHalfCpltCallback = UART_DMARxHalfCplt; - - /* Set the DMA error callback */ - huart->hdmarx->XferErrorCallback = UART_DMAError; - - /* Set the DMA abort callback */ - huart->hdmarx->XferAbortCallback = NULL; - - /* Enable the DMA stream */ - tmp = (uint32_t *)&pData; - HAL_DMA_Start_IT(huart->hdmarx, (uint32_t)&huart->Instance->DR, *(uint32_t *)tmp, Size); - - /* Clear the Overrun flag just before enabling the DMA Rx request: can be mandatory for the second transfer */ - __HAL_UART_CLEAR_OREFLAG(huart); - - /* Process Unlocked */ - __HAL_UNLOCK(huart); - - /* Enable the UART Parity Error Interrupt */ - ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_PEIE); - - /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* Enable the DMA transfer for the receiver request by setting the DMAR bit - in the UART CR3 register */ - ATOMIC_SET_BIT(huart->Instance->CR3, USART_CR3_DMAR); - - return HAL_OK; -} - -/** - * @brief End ongoing Tx transfer on UART peripheral (following error detection or Transmit completion). - * @param huart UART handle. - * @retval None - */ -static void UART_EndTxTransfer(UART_HandleTypeDef *huart) -{ - /* Disable TXEIE and TCIE interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* At end of Tx process, restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; -} - -/** - * @brief End ongoing Rx transfer on UART peripheral (following error detection or Reception completion). - * @param huart UART handle. - * @retval None - */ -static void UART_EndRxTransfer(UART_HandleTypeDef *huart) -{ - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - ATOMIC_CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE); - - /* In case of reception waiting for IDLE event, disable also the IDLE IE interrupt source */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - } - - /* At end of Rx process, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; -} - -/** - * @brief DMA UART communication abort callback, when initiated by HAL services on Error - * (To be called at end of DMA Abort procedure following error occurrence). - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMAAbortOnError(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - huart->RxXferCount = 0x00U; - huart->TxXferCount = 0x00U; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered error callback*/ - huart->ErrorCallback(huart); -#else - /*Call legacy weak error callback*/ - HAL_UART_ErrorCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART Tx communication abort callback, when initiated by user - * (To be called at end of DMA Tx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Rx DMA Handle. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMATxAbortCallback(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - huart->hdmatx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if (huart->hdmarx != NULL) - { - if (huart->hdmarx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - huart->TxXferCount = 0x00U; - huart->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - - /* Restore huart->gState and huart->RxState to Ready */ - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Call user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - huart->AbortCpltCallback(huart); -#else - /* Call legacy weak Abort complete callback */ - HAL_UART_AbortCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART Rx communication abort callback, when initiated by user - * (To be called at end of DMA Rx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Tx DMA Handle. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMARxAbortCallback(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - huart->hdmarx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if (huart->hdmatx != NULL) - { - if (huart->hdmatx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - huart->TxXferCount = 0x00U; - huart->RxXferCount = 0x00U; - - /* Reset ErrorCode */ - huart->ErrorCode = HAL_UART_ERROR_NONE; - - /* Restore huart->gState and huart->RxState to Ready */ - huart->gState = HAL_UART_STATE_READY; - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Call user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort complete callback */ - huart->AbortCpltCallback(huart); -#else - /* Call legacy weak Abort complete callback */ - HAL_UART_AbortCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART Tx communication abort callback, when initiated by user by a call to - * HAL_UART_AbortTransmit_IT API (Abort only Tx transfer) - * (This callback is executed at end of DMA Tx Abort procedure following user abort request, - * and leads to user Tx Abort Complete callback execution). - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - huart->TxXferCount = 0x00U; - - /* Restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Transmit Complete Callback */ - huart->AbortTransmitCpltCallback(huart); -#else - /* Call legacy weak Abort Transmit Complete Callback */ - HAL_UART_AbortTransmitCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA UART Rx communication abort callback, when initiated by user by a call to - * HAL_UART_AbortReceive_IT API (Abort only Rx transfer) - * (This callback is executed at end of DMA Rx Abort procedure following user abort request, - * and leads to user Rx Abort Complete callback execution). - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void UART_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma) -{ - UART_HandleTypeDef *huart = (UART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - huart->RxXferCount = 0x00U; - - /* Restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Call user Abort complete callback */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Receive Complete Callback */ - huart->AbortReceiveCpltCallback(huart); -#else - /* Call legacy weak Abort Receive Complete Callback */ - HAL_UART_AbortReceiveCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -} - -/** - * @brief Sends an amount of data in non blocking mode. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -static HAL_StatusTypeDef UART_Transmit_IT(UART_HandleTypeDef *huart) -{ - uint16_t *tmp; - - /* Check that a Tx process is ongoing */ - if (huart->gState == HAL_UART_STATE_BUSY_TX) - { - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - tmp = (uint16_t *) huart->pTxBuffPtr; - huart->Instance->DR = (uint16_t)(*tmp & (uint16_t)0x01FF); - huart->pTxBuffPtr += 2U; - } - else - { - huart->Instance->DR = (uint8_t)(*huart->pTxBuffPtr++ & (uint8_t)0x00FF); - } - - if (--huart->TxXferCount == 0U) - { - /* Disable the UART Transmit Complete Interrupt */ - __HAL_UART_DISABLE_IT(huart, UART_IT_TXE); - - /* Enable the UART Transmit Complete Interrupt */ - __HAL_UART_ENABLE_IT(huart, UART_IT_TC); - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Wraps up transmission in non blocking mode. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -static HAL_StatusTypeDef UART_EndTransmit_IT(UART_HandleTypeDef *huart) -{ - /* Disable the UART Transmit Complete Interrupt */ - __HAL_UART_DISABLE_IT(huart, UART_IT_TC); - - /* Tx process is ended, restore huart->gState to Ready */ - huart->gState = HAL_UART_STATE_READY; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Tx complete callback*/ - huart->TxCpltCallback(huart); -#else - /*Call legacy weak Tx complete callback*/ - HAL_UART_TxCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - - return HAL_OK; -} - -/** - * @brief Receives an amount of data in non blocking mode - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval HAL status - */ -static HAL_StatusTypeDef UART_Receive_IT(UART_HandleTypeDef *huart) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - - /* Check that a Rx process is ongoing */ - if (huart->RxState == HAL_UART_STATE_BUSY_RX) - { - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) huart->pRxBuffPtr; - *pdata16bits = (uint16_t)(huart->Instance->DR & (uint16_t)0x01FF); - huart->pRxBuffPtr += 2U; - } - else - { - pdata8bits = (uint8_t *) huart->pRxBuffPtr; - pdata16bits = NULL; - - if ((huart->Init.WordLength == UART_WORDLENGTH_9B) || ((huart->Init.WordLength == UART_WORDLENGTH_8B) && (huart->Init.Parity == UART_PARITY_NONE))) - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pdata8bits = (uint8_t)(huart->Instance->DR & (uint8_t)0x007F); - } - huart->pRxBuffPtr += 1U; - } - - if (--huart->RxXferCount == 0U) - { - /* Disable the UART Data Register not empty Interrupt */ - __HAL_UART_DISABLE_IT(huart, UART_IT_RXNE); - - /* Disable the UART Parity Error Interrupt */ - __HAL_UART_DISABLE_IT(huart, UART_IT_PE); - - /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */ - __HAL_UART_DISABLE_IT(huart, UART_IT_ERR); - - /* Rx process is completed, restore huart->RxState to Ready */ - huart->RxState = HAL_UART_STATE_READY; - - /* Check current reception Mode : - If Reception till IDLE event has been selected : */ - if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) - { - /* Set reception type to Standard */ - huart->ReceptionType = HAL_UART_RECEPTION_STANDARD; - - /* Disable IDLE interrupt */ - ATOMIC_CLEAR_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); - - /* Check if IDLE flag is set */ - if (__HAL_UART_GET_FLAG(huart, UART_FLAG_IDLE)) - { - /* Clear IDLE flag in ISR */ - __HAL_UART_CLEAR_IDLEFLAG(huart); - } - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx Event callback*/ - huart->RxEventCallback(huart, huart->RxXferSize); -#else - /*Call legacy weak Rx Event callback*/ - HAL_UARTEx_RxEventCallback(huart, huart->RxXferSize); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - else - { - /* Standard reception API called */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - /*Call registered Rx complete callback*/ - huart->RxCpltCallback(huart); -#else - /*Call legacy weak Rx complete callback*/ - HAL_UART_RxCpltCallback(huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - } - - return HAL_OK; - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configures the UART peripheral. - * @param huart Pointer to a UART_HandleTypeDef structure that contains - * the configuration information for the specified UART module. - * @retval None - */ -static void UART_SetConfig(UART_HandleTypeDef *huart) -{ - uint32_t tmpreg; - uint32_t pclk; - - /* Check the parameters */ - assert_param(IS_UART_BAUDRATE(huart->Init.BaudRate)); - assert_param(IS_UART_STOPBITS(huart->Init.StopBits)); - assert_param(IS_UART_PARITY(huart->Init.Parity)); - assert_param(IS_UART_MODE(huart->Init.Mode)); - - /*-------------------------- USART CR2 Configuration -----------------------*/ - /* Configure the UART Stop Bits: Set STOP[13:12] bits - according to huart->Init.StopBits value */ - MODIFY_REG(huart->Instance->CR2, USART_CR2_STOP, huart->Init.StopBits); - - /*-------------------------- USART CR1 Configuration -----------------------*/ - /* Configure the UART Word Length, Parity and mode: - Set the M bits according to huart->Init.WordLength value - Set PCE and PS bits according to huart->Init.Parity value - Set TE and RE bits according to huart->Init.Mode value - Set OVER8 bit according to huart->Init.OverSampling value */ - - tmpreg = (uint32_t)huart->Init.WordLength | huart->Init.Parity | huart->Init.Mode | huart->Init.OverSampling; - MODIFY_REG(huart->Instance->CR1, - (uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8), - tmpreg); - - /*-------------------------- USART CR3 Configuration -----------------------*/ - /* Configure the UART HFC: Set CTSE and RTSE bits according to huart->Init.HwFlowCtl value */ - MODIFY_REG(huart->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE), huart->Init.HwFlowCtl); - - -#if defined(USART6) && defined(UART9) && defined(UART10) - if ((huart->Instance == USART1) || (huart->Instance == USART6) || (huart->Instance == UART9) || (huart->Instance == UART10)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - } -#elif defined(USART6) - if ((huart->Instance == USART1) || (huart->Instance == USART6)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - } -#else - if (huart->Instance == USART1) - { - pclk = HAL_RCC_GetPCLK2Freq(); - } -#endif /* USART6 */ - else - { - pclk = HAL_RCC_GetPCLK1Freq(); - } - /*-------------------------- USART BRR Configuration ---------------------*/ - if (huart->Init.OverSampling == UART_OVERSAMPLING_8) - { - huart->Instance->BRR = UART_BRR_SAMPLING8(pclk, huart->Init.BaudRate); - } - else - { - huart->Instance->BRR = UART_BRR_SAMPLING16(pclk, huart->Init.BaudRate); - } -} - -/** - * @} - */ - -#endif /* HAL_UART_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_usart.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_usart.c deleted file mode 100644 index 0af05821f141187..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_usart.c +++ /dev/null @@ -1,2824 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_usart.c - * @author MCD Application Team - * @brief USART HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Universal Synchronous/Asynchronous Receiver Transmitter - * Peripheral (USART). - * + Initialization and de-initialization functions - * + IO operation functions - * + Peripheral Control functions - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The USART HAL driver can be used as follows: - - (#) Declare a USART_HandleTypeDef handle structure (eg. USART_HandleTypeDef husart). - (#) Initialize the USART low level resources by implementing the HAL_USART_MspInit() API: - (##) Enable the USARTx interface clock. - (##) USART pins configuration: - (+++) Enable the clock for the USART GPIOs. - (+++) Configure the USART pins as alternate function pull-up. - (##) NVIC configuration if you need to use interrupt process (HAL_USART_Transmit_IT(), - HAL_USART_Receive_IT() and HAL_USART_TransmitReceive_IT() APIs): - (+++) Configure the USARTx interrupt priority. - (+++) Enable the NVIC USART IRQ handle. - (##) DMA Configuration if you need to use DMA process (HAL_USART_Transmit_DMA() - HAL_USART_Receive_DMA() and HAL_USART_TransmitReceive_DMA() APIs): - (+++) Declare a DMA handle structure for the Tx/Rx stream. - (+++) Enable the DMAx interface clock. - (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters. - (+++) Configure the DMA Tx/Rx stream. - (+++) Associate the initialized DMA handle to the USART DMA Tx/Rx handle. - (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx stream. - (+++) Configure the USARTx interrupt priority and enable the NVIC USART IRQ handle - (used for last byte sending completion detection in DMA non circular mode) - - (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware - flow control and Mode(Receiver/Transmitter) in the husart Init structure. - - (#) Initialize the USART registers by calling the HAL_USART_Init() API: - (++) These APIs configures also the low level Hardware GPIO, CLOCK, CORTEX...etc) - by calling the customized HAL_USART_MspInit(&husart) API. - - -@@- The specific USART interrupts (Transmission complete interrupt, - RXNE interrupt and Error Interrupts) will be managed using the macros - __HAL_USART_ENABLE_IT() and __HAL_USART_DISABLE_IT() inside the transmit and receive process. - - (#) Three operation modes are available within this driver : - - *** Polling mode IO operation *** - ================================= - [..] - (+) Send an amount of data in blocking mode using HAL_USART_Transmit() - (+) Receive an amount of data in blocking mode using HAL_USART_Receive() - - *** Interrupt mode IO operation *** - =================================== - [..] - (+) Send an amount of data in non blocking mode using HAL_USART_Transmit_IT() - (+) At transmission end of transfer HAL_USART_TxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_USART_TxCpltCallback - (+) Receive an amount of data in non blocking mode using HAL_USART_Receive_IT() - (+) At reception end of transfer HAL_USART_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_USART_RxCpltCallback - (+) In case of transfer Error, HAL_USART_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_USART_ErrorCallback - - *** DMA mode IO operation *** - ============================== - [..] - (+) Send an amount of data in non blocking mode (DMA) using HAL_USART_Transmit_DMA() - (+) At transmission end of half transfer HAL_USART_TxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_USART_TxHalfCpltCallback - (+) At transmission end of transfer HAL_USART_TxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_USART_TxCpltCallback - (+) Receive an amount of data in non blocking mode (DMA) using HAL_USART_Receive_DMA() - (+) At reception end of half transfer HAL_USART_RxHalfCpltCallback is executed and user can - add his own code by customization of function pointer HAL_USART_RxHalfCpltCallback - (+) At reception end of transfer HAL_USART_RxCpltCallback is executed and user can - add his own code by customization of function pointer HAL_USART_RxCpltCallback - (+) In case of transfer Error, HAL_USART_ErrorCallback() function is executed and user can - add his own code by customization of function pointer HAL_USART_ErrorCallback - (+) Pause the DMA Transfer using HAL_USART_DMAPause() - (+) Resume the DMA Transfer using HAL_USART_DMAResume() - (+) Stop the DMA Transfer using HAL_USART_DMAStop() - - *** USART HAL driver macros list *** - ============================================= - [..] - Below the list of most used macros in USART HAL driver. - - (+) __HAL_USART_ENABLE: Enable the USART peripheral - (+) __HAL_USART_DISABLE: Disable the USART peripheral - (+) __HAL_USART_GET_FLAG : Check whether the specified USART flag is set or not - (+) __HAL_USART_CLEAR_FLAG : Clear the specified USART pending flag - (+) __HAL_USART_ENABLE_IT: Enable the specified USART interrupt - (+) __HAL_USART_DISABLE_IT: Disable the specified USART interrupt - - [..] - (@) You can refer to the USART HAL driver header file for more useful macros - - ##### Callback registration ##### - ================================== - - [..] - The compilation define USE_HAL_USART_REGISTER_CALLBACKS when set to 1 - allows the user to configure dynamically the driver callbacks. - - [..] - Use Function @ref HAL_USART_RegisterCallback() to register a user callback. - Function @ref HAL_USART_RegisterCallback() allows to register following callbacks: - (+) TxHalfCpltCallback : Tx Half Complete Callback. - (+) TxCpltCallback : Tx Complete Callback. - (+) RxHalfCpltCallback : Rx Half Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) TxRxCpltCallback : Tx Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) MspInitCallback : USART MspInit. - (+) MspDeInitCallback : USART MspDeInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - [..] - Use function @ref HAL_USART_UnRegisterCallback() to reset a callback to the default - weak (surcharged) function. - @ref HAL_USART_UnRegisterCallback() takes as parameters the HAL peripheral handle, - and the Callback ID. - This function allows to reset following callbacks: - (+) TxHalfCpltCallback : Tx Half Complete Callback. - (+) TxCpltCallback : Tx Complete Callback. - (+) RxHalfCpltCallback : Rx Half Complete Callback. - (+) RxCpltCallback : Rx Complete Callback. - (+) TxRxCpltCallback : Tx Rx Complete Callback. - (+) ErrorCallback : Error Callback. - (+) AbortCpltCallback : Abort Complete Callback. - (+) MspInitCallback : USART MspInit. - (+) MspDeInitCallback : USART MspDeInit. - - [..] - By default, after the @ref HAL_USART_Init() and when the state is HAL_USART_STATE_RESET - all callbacks are set to the corresponding weak (surcharged) functions: - examples @ref HAL_USART_TxCpltCallback(), @ref HAL_USART_RxHalfCpltCallback(). - Exception done for MspInit and MspDeInit functions that are respectively - reset to the legacy weak (surcharged) functions in the @ref HAL_USART_Init() - and @ref HAL_USART_DeInit() only when these callbacks are null (not registered beforehand). - If not, MspInit or MspDeInit are not null, the @ref HAL_USART_Init() and @ref HAL_USART_DeInit() - keep and use the user MspInit/MspDeInit callbacks (registered beforehand). - - [..] - Callbacks can be registered/unregistered in HAL_USART_STATE_READY state only. - Exception done MspInit/MspDeInit that can be registered/unregistered - in HAL_USART_STATE_READY or HAL_USART_STATE_RESET state, thus registered (user) - MspInit/DeInit callbacks can be used during the Init/DeInit. - In that case first register the MspInit/MspDeInit user callbacks - using @ref HAL_USART_RegisterCallback() before calling @ref HAL_USART_DeInit() - or @ref HAL_USART_Init() function. - - [..] - When The compilation define USE_HAL_USART_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registration feature is not available - and weak (surcharged) callbacks are used. - - @endverbatim - [..] - (@) Additional remark: If the parity is enabled, then the MSB bit of the data written - in the data register is transmitted but is changed by the parity bit. - Depending on the frame length defined by the M bit (8-bits or 9-bits), - the possible USART frame formats are as listed in the following table: - +-------------------------------------------------------------+ - | M bit | PCE bit | USART frame | - |---------------------|---------------------------------------| - | 0 | 0 | | SB | 8 bit data | STB | | - |---------|-----------|---------------------------------------| - | 0 | 1 | | SB | 7 bit data | PB | STB | | - |---------|-----------|---------------------------------------| - | 1 | 0 | | SB | 9 bit data | STB | | - |---------|-----------|---------------------------------------| - | 1 | 1 | | SB | 8 bit data | PB | STB | | - +-------------------------------------------------------------+ - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup USART USART - * @brief HAL USART Synchronous module driver - * @{ - */ -#ifdef HAL_USART_MODULE_ENABLED -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/** @addtogroup USART_Private_Constants - * @{ - */ -#define DUMMY_DATA 0xFFFFU -#define USART_TIMEOUT_VALUE 22000U -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup USART_Private_Functions - * @{ - */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -void USART_InitCallbacksToDefault(USART_HandleTypeDef *husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -static void USART_EndTxTransfer(USART_HandleTypeDef *husart); -static void USART_EndRxTransfer(USART_HandleTypeDef *husart); -static HAL_StatusTypeDef USART_Transmit_IT(USART_HandleTypeDef *husart); -static HAL_StatusTypeDef USART_EndTransmit_IT(USART_HandleTypeDef *husart); -static HAL_StatusTypeDef USART_Receive_IT(USART_HandleTypeDef *husart); -static HAL_StatusTypeDef USART_TransmitReceive_IT(USART_HandleTypeDef *husart); -static void USART_SetConfig(USART_HandleTypeDef *husart); -static void USART_DMATransmitCplt(DMA_HandleTypeDef *hdma); -static void USART_DMATxHalfCplt(DMA_HandleTypeDef *hdma); -static void USART_DMAReceiveCplt(DMA_HandleTypeDef *hdma); -static void USART_DMARxHalfCplt(DMA_HandleTypeDef *hdma); -static void USART_DMAError(DMA_HandleTypeDef *hdma); -static void USART_DMAAbortOnError(DMA_HandleTypeDef *hdma); -static void USART_DMATxAbortCallback(DMA_HandleTypeDef *hdma); -static void USART_DMARxAbortCallback(DMA_HandleTypeDef *hdma); - -static HAL_StatusTypeDef USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef *husart, uint32_t Flag, FlagStatus Status, - uint32_t Tickstart, uint32_t Timeout); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup USART_Exported_Functions USART Exported Functions - * @{ - */ - -/** @defgroup USART_Exported_Functions_Group1 USART Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and Configuration functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to initialize the USART - in asynchronous and in synchronous modes. - (+) For the asynchronous mode only these parameters can be configured: - (++) Baud Rate - (++) Word Length - (++) Stop Bit - (++) Parity: If the parity is enabled, then the MSB bit of the data written - in the data register is transmitted but is changed by the parity bit. - Depending on the frame length defined by the M bit (8-bits or 9-bits), - please refer to Reference manual for possible USART frame formats. - (++) USART polarity - (++) USART phase - (++) USART LastBit - (++) Receiver/transmitter modes - - [..] - The HAL_USART_Init() function follows the USART synchronous configuration - procedures (details for the procedures are available in reference manual - (RM0430 for STM32F4X3xx MCUs and RM0402 for STM32F412xx MCUs - RM0383 for STM32F411xC/E MCUs and RM0401 for STM32F410xx MCUs - RM0090 for STM32F4X5xx/STM32F4X7xx/STM32F429xx/STM32F439xx MCUs - RM0390 for STM32F446xx MCUs and RM0386 for STM32F469xx/STM32F479xx MCUs)). - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the USART mode according to the specified - * parameters in the USART_InitTypeDef and initialize the associated handle. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_Init(USART_HandleTypeDef *husart) -{ - /* Check the USART handle allocation */ - if (husart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_USART_INSTANCE(husart->Instance)); - - if (husart->State == HAL_USART_STATE_RESET) - { - /* Allocate lock resource and initialize it */ - husart->Lock = HAL_UNLOCKED; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - USART_InitCallbacksToDefault(husart); - - if (husart->MspInitCallback == NULL) - { - husart->MspInitCallback = HAL_USART_MspInit; - } - - /* Init the low level hardware */ - husart->MspInitCallback(husart); -#else - /* Init the low level hardware : GPIO, CLOCK */ - HAL_USART_MspInit(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - - husart->State = HAL_USART_STATE_BUSY; - - /* Set the USART Communication parameters */ - USART_SetConfig(husart); - - /* In USART mode, the following bits must be kept cleared: - - LINEN bit in the USART_CR2 register - - HDSEL, SCEN and IREN bits in the USART_CR3 register */ - CLEAR_BIT(husart->Instance->CR2, USART_CR2_LINEN); - CLEAR_BIT(husart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); - - /* Enable the Peripheral */ - __HAL_USART_ENABLE(husart); - - /* Initialize the USART state */ - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_READY; - - return HAL_OK; -} - -/** - * @brief DeInitializes the USART peripheral. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_DeInit(USART_HandleTypeDef *husart) -{ - /* Check the USART handle allocation */ - if (husart == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_USART_INSTANCE(husart->Instance)); - - husart->State = HAL_USART_STATE_BUSY; - - /* Disable the Peripheral */ - __HAL_USART_DISABLE(husart); - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - if (husart->MspDeInitCallback == NULL) - { - husart->MspDeInitCallback = HAL_USART_MspDeInit; - } - /* DeInit the low level hardware */ - husart->MspDeInitCallback(husart); -#else - /* DeInit the low level hardware */ - HAL_USART_MspDeInit(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_RESET; - - /* Release Lock */ - __HAL_UNLOCK(husart); - - return HAL_OK; -} - -/** - * @brief USART MSP Init. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_USART_MspInit(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_USART_MspInit could be implemented in the user file - */ -} - -/** - * @brief USART MSP DeInit. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_USART_MspDeInit(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_USART_MspDeInit could be implemented in the user file - */ -} - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User USART Callback - * To be used instead of the weak predefined callback - * @param husart usart handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_USART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID - * @arg @ref HAL_USART_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_USART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID - * @arg @ref HAL_USART_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_USART_TX_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_USART_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_USART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_USART_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_USART_MSPDEINIT_CB_ID MspDeInit Callback ID - * @param pCallback pointer to the Callback function - * @retval HAL status -+ */ -HAL_StatusTypeDef HAL_USART_RegisterCallback(USART_HandleTypeDef *husart, HAL_USART_CallbackIDTypeDef CallbackID, - pUSART_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - /* Update the error code */ - husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; - - return HAL_ERROR; - } - /* Process locked */ - __HAL_LOCK(husart); - - if (husart->State == HAL_USART_STATE_READY) - { - switch (CallbackID) - { - case HAL_USART_TX_HALFCOMPLETE_CB_ID : - husart->TxHalfCpltCallback = pCallback; - break; - - case HAL_USART_TX_COMPLETE_CB_ID : - husart->TxCpltCallback = pCallback; - break; - - case HAL_USART_RX_HALFCOMPLETE_CB_ID : - husart->RxHalfCpltCallback = pCallback; - break; - - case HAL_USART_RX_COMPLETE_CB_ID : - husart->RxCpltCallback = pCallback; - break; - - case HAL_USART_TX_RX_COMPLETE_CB_ID : - husart->TxRxCpltCallback = pCallback; - break; - - case HAL_USART_ERROR_CB_ID : - husart->ErrorCallback = pCallback; - break; - - case HAL_USART_ABORT_COMPLETE_CB_ID : - husart->AbortCpltCallback = pCallback; - break; - - case HAL_USART_MSPINIT_CB_ID : - husart->MspInitCallback = pCallback; - break; - - case HAL_USART_MSPDEINIT_CB_ID : - husart->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (husart->State == HAL_USART_STATE_RESET) - { - switch (CallbackID) - { - case HAL_USART_MSPINIT_CB_ID : - husart->MspInitCallback = pCallback; - break; - - case HAL_USART_MSPDEINIT_CB_ID : - husart->MspDeInitCallback = pCallback; - break; - - default : - /* Update the error code */ - husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(husart); - - return status; -} - -/** - * @brief Unregister an USART Callback - * USART callaback is redirected to the weak predefined callback - * @param husart usart handle - * @param CallbackID ID of the callback to be unregistered - * This parameter can be one of the following values: - * @arg @ref HAL_USART_TX_HALFCOMPLETE_CB_ID Tx Half Complete Callback ID - * @arg @ref HAL_USART_TX_COMPLETE_CB_ID Tx Complete Callback ID - * @arg @ref HAL_USART_RX_HALFCOMPLETE_CB_ID Rx Half Complete Callback ID - * @arg @ref HAL_USART_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_USART_TX_RX_COMPLETE_CB_ID Rx Complete Callback ID - * @arg @ref HAL_USART_ERROR_CB_ID Error Callback ID - * @arg @ref HAL_USART_ABORT_COMPLETE_CB_ID Abort Complete Callback ID - * @arg @ref HAL_USART_MSPINIT_CB_ID MspInit Callback ID - * @arg @ref HAL_USART_MSPDEINIT_CB_ID MspDeInit Callback ID - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_UnRegisterCallback(USART_HandleTypeDef *husart, HAL_USART_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - /* Process locked */ - __HAL_LOCK(husart); - - if (husart->State == HAL_USART_STATE_READY) - { - switch (CallbackID) - { - case HAL_USART_TX_HALFCOMPLETE_CB_ID : - husart->TxHalfCpltCallback = HAL_USART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - break; - - case HAL_USART_TX_COMPLETE_CB_ID : - husart->TxCpltCallback = HAL_USART_TxCpltCallback; /* Legacy weak TxCpltCallback */ - break; - - case HAL_USART_RX_HALFCOMPLETE_CB_ID : - husart->RxHalfCpltCallback = HAL_USART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - break; - - case HAL_USART_RX_COMPLETE_CB_ID : - husart->RxCpltCallback = HAL_USART_RxCpltCallback; /* Legacy weak RxCpltCallback */ - break; - - case HAL_USART_TX_RX_COMPLETE_CB_ID : - husart->TxRxCpltCallback = HAL_USART_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ - break; - - case HAL_USART_ERROR_CB_ID : - husart->ErrorCallback = HAL_USART_ErrorCallback; /* Legacy weak ErrorCallback */ - break; - - case HAL_USART_ABORT_COMPLETE_CB_ID : - husart->AbortCpltCallback = HAL_USART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ - break; - - case HAL_USART_MSPINIT_CB_ID : - husart->MspInitCallback = HAL_USART_MspInit; /* Legacy weak MspInitCallback */ - break; - - case HAL_USART_MSPDEINIT_CB_ID : - husart->MspDeInitCallback = HAL_USART_MspDeInit; /* Legacy weak MspDeInitCallback */ - break; - - default : - /* Update the error code */ - husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else if (husart->State == HAL_USART_STATE_RESET) - { - switch (CallbackID) - { - case HAL_USART_MSPINIT_CB_ID : - husart->MspInitCallback = HAL_USART_MspInit; - break; - - case HAL_USART_MSPDEINIT_CB_ID : - husart->MspDeInitCallback = HAL_USART_MspDeInit; - break; - - default : - /* Update the error code */ - husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - break; - } - } - else - { - /* Update the error code */ - husart->ErrorCode |= HAL_USART_ERROR_INVALID_CALLBACK; - - /* Return error status */ - status = HAL_ERROR; - } - - /* Release Lock */ - __HAL_UNLOCK(husart); - - return status; -} -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup USART_Exported_Functions_Group2 IO operation functions - * @brief USART Transmit and Receive functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to manage the USART synchronous - data transfers. - - [..] - The USART supports master mode only: it cannot receive or send data related to an input - clock (SCLK is always an output). - - (#) There are two modes of transfer: - (++) Blocking mode: The communication is performed in polling mode. - The HAL status of all data processing is returned by the same function - after finishing transfer. - (++) No-Blocking mode: The communication is performed using Interrupts - or DMA, These API's return the HAL status. - The end of the data processing will be indicated through the - dedicated USART IRQ when using Interrupt mode or the DMA IRQ when - using DMA mode. - The HAL_USART_TxCpltCallback(), HAL_USART_RxCpltCallback() and HAL_USART_TxRxCpltCallback() - user callbacks - will be executed respectively at the end of the transmit or Receive process - The HAL_USART_ErrorCallback() user callback will be executed when a communication - error is detected - - (#) Blocking mode APIs are : - (++) HAL_USART_Transmit() in simplex mode - (++) HAL_USART_Receive() in full duplex receive only - (++) HAL_USART_TransmitReceive() in full duplex mode - - (#) Non Blocking mode APIs with Interrupt are : - (++) HAL_USART_Transmit_IT()in simplex mode - (++) HAL_USART_Receive_IT() in full duplex receive only - (++) HAL_USART_TransmitReceive_IT() in full duplex mode - (++) HAL_USART_IRQHandler() - - (#) Non Blocking mode functions with DMA are : - (++) HAL_USART_Transmit_DMA()in simplex mode - (++) HAL_USART_Receive_DMA() in full duplex receive only - (++) HAL_USART_TransmitReceive_DMA() in full duplex mode - (++) HAL_USART_DMAPause() - (++) HAL_USART_DMAResume() - (++) HAL_USART_DMAStop() - - (#) A set of Transfer Complete Callbacks are provided in non Blocking mode: - (++) HAL_USART_TxHalfCpltCallback() - (++) HAL_USART_TxCpltCallback() - (++) HAL_USART_RxHalfCpltCallback() - (++) HAL_USART_RxCpltCallback() - (++) HAL_USART_ErrorCallback() - (++) HAL_USART_TxRxCpltCallback() - - (#) Non-Blocking mode transfers could be aborted using Abort API's : - (++) HAL_USART_Abort() - (++) HAL_USART_Abort_IT() - - (#) For Abort services based on interrupts (HAL_USART_Abort_IT), a Abort Complete Callbacks is provided: - (++) HAL_USART_AbortCpltCallback() - - (#) In Non-Blocking mode transfers, possible errors are split into 2 categories. - Errors are handled as follows : - (++) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is - to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception . - Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type, - and HAL_USART_ErrorCallback() user callback is executed. Transfer is kept ongoing on USART side. - If user wants to abort it, Abort services should be called by user. - (++) Error is considered as Blocking : Transfer could not be completed properly and is aborted. - This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode. - Error code is set to allow user to identify error type, and HAL_USART_ErrorCallback() user callback is executed. - -@endverbatim - * @{ - */ - -/** - * @brief Simplex Send an amount of data in blocking mode. - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pTxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pTxData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent. - * @param Timeout Timeout duration. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_Transmit(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size, uint32_t Timeout) -{ - uint8_t *ptxdata8bits; - uint16_t *ptxdata16bits; - uint32_t tickstart; - - if (husart->State == HAL_USART_STATE_READY) - { - if ((pTxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(husart); - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_TX; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - husart->TxXferSize = Size; - husart->TxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pTxData needs to be handled as a uint16_t pointer */ - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) - { - ptxdata8bits = NULL; - ptxdata16bits = (uint16_t *) pTxData; - } - else - { - ptxdata8bits = pTxData; - ptxdata16bits = NULL; - } - - while (husart->TxXferCount > 0U) - { - /* Wait for TXE flag in order to write data in DR */ - if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - if (ptxdata8bits == NULL) - { - husart->Instance->DR = (uint16_t)(*ptxdata16bits & (uint16_t)0x01FF); - ptxdata16bits++; - } - else - { - husart->Instance->DR = (uint8_t)(*ptxdata8bits & (uint8_t)0xFF); - ptxdata8bits++; - } - - husart->TxXferCount--; - } - - if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - husart->State = HAL_USART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Full-Duplex Receive an amount of data in blocking mode. - * @note To receive synchronous data, dummy data are simultaneously transmitted. - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pRxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pRxData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @param Timeout Timeout duration. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_Receive(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size, uint32_t Timeout) -{ - uint8_t *prxdata8bits; - uint16_t *prxdata16bits; - uint32_t tickstart; - - if (husart->State == HAL_USART_STATE_READY) - { - if ((pRxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(husart); - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_RX; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - husart->RxXferSize = Size; - husart->RxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) - { - prxdata8bits = NULL; - prxdata16bits = (uint16_t *) pRxData; - } - else - { - prxdata8bits = pRxData; - prxdata16bits = NULL; - } - - /* Check the remain data to be received */ - while (husart->RxXferCount > 0U) - { - /* Wait until TXE flag is set to send dummy byte in order to generate the - * clock for the slave to send data. - * Whatever the frame length (7, 8 or 9-bit long), the same dummy value - * can be written for all the cases. */ - if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - husart->Instance->DR = (DUMMY_DATA & (uint16_t)0x0FF); - - /* Wait until RXNE flag is set to receive the byte */ - if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - if (prxdata8bits == NULL) - { - *prxdata16bits = (uint16_t)(husart->Instance->DR & (uint16_t)0x01FF); - prxdata16bits++; - } - else - { - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) || ((husart->Init.WordLength == USART_WORDLENGTH_8B) && (husart->Init.Parity == USART_PARITY_NONE))) - { - *prxdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x0FF); - } - else - { - *prxdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x07F); - } - prxdata8bits++; - } - husart->RxXferCount--; - } - - husart->State = HAL_USART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Full-Duplex Send and Receive an amount of data in full-duplex mode (blocking mode). - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data and the received data are handled as sets of u16. In this case, Size must indicate the number - * of u16 available through pTxData and through pRxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pTxData Pointer to TX data buffer (u8 or u16 data elements). - * @param pRxData Pointer to RX data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent (same amount to be received). - * @param Timeout Timeout duration - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_TransmitReceive(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size, uint32_t Timeout) -{ - uint8_t *prxdata8bits; - uint16_t *prxdata16bits; - uint8_t *ptxdata8bits; - uint16_t *ptxdata16bits; - uint16_t rxdatacount; - uint32_t tickstart; - - if (husart->State == HAL_USART_STATE_READY) - { - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - /* In case of 9bits/No Parity transfer, pTxData and pRxData buffers provided as input parameter - should be aligned on a u16 frontier, as data to be filled into TDR/retrieved from RDR will be - handled through a u16 cast. */ - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) - { - if (((((uint32_t)pTxData) & 1U) != 0U) || ((((uint32_t)pRxData) & 1U) != 0U)) - { - return HAL_ERROR; - } - } - /* Process Locked */ - __HAL_LOCK(husart); - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_RX; - - /* Init tickstart for timeout management */ - tickstart = HAL_GetTick(); - - husart->RxXferSize = Size; - husart->TxXferSize = Size; - husart->TxXferCount = Size; - husart->RxXferCount = Size; - - /* In case of 9bits/No Parity transfer, pRxData needs to be handled as a uint16_t pointer */ - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) - { - prxdata8bits = NULL; - ptxdata8bits = NULL; - ptxdata16bits = (uint16_t *) pTxData; - prxdata16bits = (uint16_t *) pRxData; - } - else - { - prxdata8bits = pRxData; - ptxdata8bits = pTxData; - ptxdata16bits = NULL; - prxdata16bits = NULL; - } - - /* Check the remain data to be received */ - /* rxdatacount is a temporary variable for MISRAC2012-Rule-13.5 */ - rxdatacount = husart->RxXferCount; - while ((husart->TxXferCount > 0U) || (rxdatacount > 0U)) - { - if (husart->TxXferCount > 0U) - { - /* Wait for TXE flag in order to write data in DR */ - if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - - if (ptxdata8bits == NULL) - { - husart->Instance->DR = (uint16_t)(*ptxdata16bits & (uint16_t)0x01FF); - ptxdata16bits++; - } - else - { - husart->Instance->DR = (uint8_t)(*ptxdata8bits & (uint8_t)0xFF); - ptxdata8bits++; - } - - husart->TxXferCount--; - } - - if (husart->RxXferCount > 0U) - { - /* Wait for RXNE Flag */ - if (USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK) - { - return HAL_TIMEOUT; - } - if (prxdata8bits == NULL) - { - *prxdata16bits = (uint16_t)(husart->Instance->DR & (uint16_t)0x01FF); - prxdata16bits++; - } - else - { - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) || ((husart->Init.WordLength == USART_WORDLENGTH_8B) && (husart->Init.Parity == USART_PARITY_NONE))) - { - *prxdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x0FF); - } - else - { - *prxdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x07F); - } - - prxdata8bits++; - } - - husart->RxXferCount--; - } - rxdatacount = husart->RxXferCount; - } - - husart->State = HAL_USART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Simplex Send an amount of data in non-blocking mode. - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pTxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pTxData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent. - * @retval HAL status - * @note The USART errors are not managed to avoid the overrun error. - */ -HAL_StatusTypeDef HAL_USART_Transmit_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size) -{ - if (husart->State == HAL_USART_STATE_READY) - { - if ((pTxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(husart); - - husart->pTxBuffPtr = pTxData; - husart->TxXferSize = Size; - husart->TxXferCount = Size; - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_TX; - - /* The USART Error Interrupts: (Frame error, Noise error, Overrun error) - are not managed by the USART transmit process to avoid the overrun interrupt - when the USART mode is configured for transmit and receive "USART_MODE_TX_RX" - to benefit for the frame error and noise interrupts the USART mode should be - configured only for transmit "USART_MODE_TX" - The __HAL_USART_ENABLE_IT(husart, USART_IT_ERR) can be used to enable the Frame error, - Noise error interrupt */ - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - /* Enable the USART Transmit Data Register Empty Interrupt */ - SET_BIT(husart->Instance->CR1, USART_CR1_TXEIE); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Simplex Receive an amount of data in non-blocking mode. - * @note To receive synchronous data, dummy data are simultaneously transmitted. - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pRxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pRxData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_Receive_IT(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size) -{ - if (husart->State == HAL_USART_STATE_READY) - { - if ((pRxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(husart); - - husart->pRxBuffPtr = pRxData; - husart->RxXferSize = Size; - husart->RxXferCount = Size; - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_RX; - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - /* Enable the USART Parity Error and Data Register not empty Interrupts */ - SET_BIT(husart->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE); - - /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */ - SET_BIT(husart->Instance->CR3, USART_CR3_EIE); - - /* Send dummy byte in order to generate the clock for the slave to send data */ - husart->Instance->DR = (DUMMY_DATA & (uint16_t)0x01FF); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Full-Duplex Send and Receive an amount of data in full-duplex mode (non-blocking). - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data and the received data are handled as sets of u16. In this case, Size must indicate the number - * of u16 available through pTxData and through pRxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pTxData Pointer to TX data buffer (u8 or u16 data elements). - * @param pRxData Pointer to RX data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent (same amount to be received). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_TransmitReceive_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size) -{ - if (husart->State == HAL_USART_STATE_READY) - { - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(husart); - - husart->pRxBuffPtr = pRxData; - husart->RxXferSize = Size; - husart->RxXferCount = Size; - husart->pTxBuffPtr = pTxData; - husart->TxXferSize = Size; - husart->TxXferCount = Size; - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_TX_RX; - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - /* Enable the USART Data Register not empty Interrupt */ - SET_BIT(husart->Instance->CR1, USART_CR1_RXNEIE); - - /* Enable the USART Parity Error Interrupt */ - SET_BIT(husart->Instance->CR1, USART_CR1_PEIE); - - /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */ - SET_BIT(husart->Instance->CR3, USART_CR3_EIE); - - /* Enable the USART Transmit Data Register Empty Interrupt */ - SET_BIT(husart->Instance->CR1, USART_CR1_TXEIE); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Simplex Send an amount of data in DMA mode. - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data is handled as a set of u16. In this case, Size must indicate the number - * of u16 provided through pTxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pTxData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be sent. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_Transmit_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size) -{ - uint32_t *tmp; - - if (husart->State == HAL_USART_STATE_READY) - { - if ((pTxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(husart); - - husart->pTxBuffPtr = pTxData; - husart->TxXferSize = Size; - husart->TxXferCount = Size; - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_TX; - - /* Set the USART DMA transfer complete callback */ - husart->hdmatx->XferCpltCallback = USART_DMATransmitCplt; - - /* Set the USART DMA Half transfer complete callback */ - husart->hdmatx->XferHalfCpltCallback = USART_DMATxHalfCplt; - - /* Set the DMA error callback */ - husart->hdmatx->XferErrorCallback = USART_DMAError; - - /* Set the DMA abort callback */ - husart->hdmatx->XferAbortCallback = NULL; - - /* Enable the USART transmit DMA stream */ - tmp = (uint32_t *)&pTxData; - HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t *)tmp, (uint32_t)&husart->Instance->DR, Size); - - /* Clear the TC flag in the SR register by writing 0 to it */ - __HAL_USART_CLEAR_FLAG(husart, USART_FLAG_TC); - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - /* Enable the DMA transfer for transmit request by setting the DMAT bit - in the USART CR3 register */ - SET_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Full-Duplex Receive an amount of data in DMA mode. - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the received data is handled as a set of u16. In this case, Size must indicate the number - * of u16 available through pRxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pRxData Pointer to data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received. - * @retval HAL status - * @note The USART DMA transmit stream must be configured in order to generate the clock for the slave. - * @note When the USART parity is enabled (PCE = 1) the data received contain the parity bit. - */ -HAL_StatusTypeDef HAL_USART_Receive_DMA(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size) -{ - uint32_t *tmp; - - if (husart->State == HAL_USART_STATE_READY) - { - if ((pRxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - - /* Process Locked */ - __HAL_LOCK(husart); - - husart->pRxBuffPtr = pRxData; - husart->RxXferSize = Size; - husart->pTxBuffPtr = pRxData; - husart->TxXferSize = Size; - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_RX; - - /* Set the USART DMA Rx transfer complete callback */ - husart->hdmarx->XferCpltCallback = USART_DMAReceiveCplt; - - /* Set the USART DMA Half transfer complete callback */ - husart->hdmarx->XferHalfCpltCallback = USART_DMARxHalfCplt; - - /* Set the USART DMA Rx transfer error callback */ - husart->hdmarx->XferErrorCallback = USART_DMAError; - - /* Set the DMA abort callback */ - husart->hdmarx->XferAbortCallback = NULL; - - /* Set the USART Tx DMA transfer complete callback as NULL because the communication closing - is performed in DMA reception complete callback */ - husart->hdmatx->XferHalfCpltCallback = NULL; - husart->hdmatx->XferCpltCallback = NULL; - - /* Set the DMA error callback */ - husart->hdmatx->XferErrorCallback = USART_DMAError; - - /* Set the DMA AbortCpltCallback */ - husart->hdmatx->XferAbortCallback = NULL; - - /* Enable the USART receive DMA stream */ - tmp = (uint32_t *)&pRxData; - HAL_DMA_Start_IT(husart->hdmarx, (uint32_t)&husart->Instance->DR, *(uint32_t *)tmp, Size); - - /* Enable the USART transmit DMA stream: the transmit stream is used in order - to generate in the non-blocking mode the clock to the slave device, - this mode isn't a simplex receive mode but a full-duplex receive one */ - HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t *)tmp, (uint32_t)&husart->Instance->DR, Size); - - /* Clear the Overrun flag just before enabling the DMA Rx request: mandatory for the second transfer */ - __HAL_USART_CLEAR_OREFLAG(husart); - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - /* Enable the USART Parity Error Interrupt */ - SET_BIT(husart->Instance->CR1, USART_CR1_PEIE); - - /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */ - SET_BIT(husart->Instance->CR3, USART_CR3_EIE); - - /* Enable the DMA transfer for the receiver request by setting the DMAR bit - in the USART CR3 register */ - SET_BIT(husart->Instance->CR3, USART_CR3_DMAR); - - /* Enable the DMA transfer for transmit request by setting the DMAT bit - in the USART CR3 register */ - SET_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Full-Duplex Transmit Receive an amount of data in DMA mode. - * @note When USART parity is not enabled (PCE = 0), and Word Length is configured to 9 bits (M1-M0 = 01), - * the sent data and the received data are handled as sets of u16. In this case, Size must indicate the number - * of u16 available through pTxData and through pRxData. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param pTxData Pointer to TX data buffer (u8 or u16 data elements). - * @param pRxData Pointer to RX data buffer (u8 or u16 data elements). - * @param Size Amount of data elements (u8 or u16) to be received/sent. - * @note When the USART parity is enabled (PCE = 1) the data received contain the parity bit. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_TransmitReceive_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size) -{ - uint32_t *tmp; - - if (husart->State == HAL_USART_STATE_READY) - { - if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0)) - { - return HAL_ERROR; - } - /* Process Locked */ - __HAL_LOCK(husart); - - husart->pRxBuffPtr = pRxData; - husart->RxXferSize = Size; - husart->pTxBuffPtr = pTxData; - husart->TxXferSize = Size; - - husart->ErrorCode = HAL_USART_ERROR_NONE; - husart->State = HAL_USART_STATE_BUSY_TX_RX; - - /* Set the USART DMA Rx transfer complete callback */ - husart->hdmarx->XferCpltCallback = USART_DMAReceiveCplt; - - /* Set the USART DMA Half transfer complete callback */ - husart->hdmarx->XferHalfCpltCallback = USART_DMARxHalfCplt; - - /* Set the USART DMA Tx transfer complete callback */ - husart->hdmatx->XferCpltCallback = USART_DMATransmitCplt; - - /* Set the USART DMA Half transfer complete callback */ - husart->hdmatx->XferHalfCpltCallback = USART_DMATxHalfCplt; - - /* Set the USART DMA Tx transfer error callback */ - husart->hdmatx->XferErrorCallback = USART_DMAError; - - /* Set the USART DMA Rx transfer error callback */ - husart->hdmarx->XferErrorCallback = USART_DMAError; - - /* Set the DMA abort callback */ - husart->hdmarx->XferAbortCallback = NULL; - - /* Enable the USART receive DMA stream */ - tmp = (uint32_t *)&pRxData; - HAL_DMA_Start_IT(husart->hdmarx, (uint32_t)&husart->Instance->DR, *(uint32_t *)tmp, Size); - - /* Enable the USART transmit DMA stream */ - tmp = (uint32_t *)&pTxData; - HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t *)tmp, (uint32_t)&husart->Instance->DR, Size); - - /* Clear the TC flag in the SR register by writing 0 to it */ - __HAL_USART_CLEAR_FLAG(husart, USART_FLAG_TC); - - /* Clear the Overrun flag: mandatory for the second transfer in circular mode */ - __HAL_USART_CLEAR_OREFLAG(husart); - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - /* Enable the USART Parity Error Interrupt */ - SET_BIT(husart->Instance->CR1, USART_CR1_PEIE); - - /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */ - SET_BIT(husart->Instance->CR3, USART_CR3_EIE); - - /* Enable the DMA transfer for the receiver request by setting the DMAR bit - in the USART CR3 register */ - SET_BIT(husart->Instance->CR3, USART_CR3_DMAR); - - /* Enable the DMA transfer for transmit request by setting the DMAT bit - in the USART CR3 register */ - SET_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Pauses the DMA Transfer. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_DMAPause(USART_HandleTypeDef *husart) -{ - /* Process Locked */ - __HAL_LOCK(husart); - - /* Disable the USART DMA Tx request */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - return HAL_OK; -} - -/** - * @brief Resumes the DMA Transfer. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_DMAResume(USART_HandleTypeDef *husart) -{ - /* Process Locked */ - __HAL_LOCK(husart); - - /* Enable the USART DMA Tx request */ - SET_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - return HAL_OK; -} - -/** - * @brief Stops the DMA Transfer. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_DMAStop(USART_HandleTypeDef *husart) -{ - uint32_t dmarequest = 0x00U; - /* The Lock is not implemented on this API to allow the user application - to call the HAL USART API under callbacks HAL_USART_TxCpltCallback() / HAL_USART_RxCpltCallback(): - when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated - and the correspond call back is executed HAL_USART_TxCpltCallback() / HAL_USART_RxCpltCallback() - */ - - /* Stop USART DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT); - if ((husart->State == HAL_USART_STATE_BUSY_TX) && dmarequest) - { - USART_EndTxTransfer(husart); - - /* Abort the USART DMA Tx channel */ - if (husart->hdmatx != NULL) - { - HAL_DMA_Abort(husart->hdmatx); - } - - /* Disable the USART Tx DMA request */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); - } - - /* Stop USART DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR); - if ((husart->State == HAL_USART_STATE_BUSY_RX) && dmarequest) - { - USART_EndRxTransfer(husart); - - /* Abort the USART DMA Rx channel */ - if (husart->hdmarx != NULL) - { - HAL_DMA_Abort(husart->hdmarx); - } - - /* Disable the USART Rx DMA request */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); - } - - return HAL_OK; -} - -/** - * @brief Abort ongoing transfer (blocking mode). - * @param husart USART handle. - * @note This procedure could be used for aborting any ongoing transfer (either Tx or Rx, - * as described by TransferType parameter) started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts (depending of transfer direction) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode) - * - Set handle State to READY - * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_Abort(USART_HandleTypeDef *husart) -{ - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); - - /* Disable the USART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)) - { - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the USART DMA Tx channel : use blocking DMA Abort API (no callback) */ - if (husart->hdmatx != NULL) - { - /* Set the USART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - husart->hdmatx->XferAbortCallback = NULL; - - HAL_DMA_Abort(husart->hdmatx); - } - } - - /* Disable the USART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the USART DMA Rx channel : use blocking DMA Abort API (no callback) */ - if (husart->hdmarx != NULL) - { - /* Set the USART DMA Abort callback to Null. - No call back execution at end of DMA abort procedure */ - husart->hdmarx->XferAbortCallback = NULL; - - HAL_DMA_Abort(husart->hdmarx); - } - } - - /* Reset Tx and Rx transfer counters */ - husart->TxXferCount = 0x00U; - husart->RxXferCount = 0x00U; - - /* Restore husart->State to Ready */ - husart->State = HAL_USART_STATE_READY; - - /* Reset Handle ErrorCode to No Error */ - husart->ErrorCode = HAL_USART_ERROR_NONE; - - return HAL_OK; -} - -/** - * @brief Abort ongoing transfer (Interrupt mode). - * @param husart USART handle. - * @note This procedure could be used for aborting any ongoing transfer (either Tx or Rx, - * as described by TransferType parameter) started in Interrupt or DMA mode. - * This procedure performs following operations : - * - Disable PPP Interrupts (depending of transfer direction) - * - Disable the DMA transfer in the peripheral register (if enabled) - * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode) - * - Set handle State to READY - * - At abort completion, call user abort complete callback - * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be - * considered as completed only when user abort complete callback is executed (not when exiting function). - * @retval HAL status - */ -HAL_StatusTypeDef HAL_USART_Abort_IT(USART_HandleTypeDef *husart) -{ - uint32_t AbortCplt = 0x01U; - - /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE)); - CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); - - /* If DMA Tx and/or DMA Rx Handles are associated to USART Handle, DMA Abort complete callbacks should be initialised - before any call to DMA Abort functions */ - /* DMA Tx Handle is valid */ - if (husart->hdmatx != NULL) - { - /* Set DMA Abort Complete callback if USART DMA Tx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)) - { - husart->hdmatx->XferAbortCallback = USART_DMATxAbortCallback; - } - else - { - husart->hdmatx->XferAbortCallback = NULL; - } - } - /* DMA Rx Handle is valid */ - if (husart->hdmarx != NULL) - { - /* Set DMA Abort Complete callback if USART DMA Rx request if enabled. - Otherwise, set it to NULL */ - if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)) - { - husart->hdmarx->XferAbortCallback = USART_DMARxAbortCallback; - } - else - { - husart->hdmarx->XferAbortCallback = NULL; - } - } - - /* Disable the USART DMA Tx request if enabled */ - if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)) - { - /* Disable DMA Tx at USART level */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - /* Abort the USART DMA Tx channel : use non blocking DMA Abort API (callback) */ - if (husart->hdmatx != NULL) - { - /* USART Tx DMA Abort callback has already been initialised : - will lead to call HAL_USART_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA TX */ - if (HAL_DMA_Abort_IT(husart->hdmatx) != HAL_OK) - { - husart->hdmatx->XferAbortCallback = NULL; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* Disable the USART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the USART DMA Rx channel : use non blocking DMA Abort API (callback) */ - if (husart->hdmarx != NULL) - { - /* USART Rx DMA Abort callback has already been initialised : - will lead to call HAL_USART_AbortCpltCallback() at end of DMA abort procedure */ - - /* Abort DMA RX */ - if (HAL_DMA_Abort_IT(husart->hdmarx) != HAL_OK) - { - husart->hdmarx->XferAbortCallback = NULL; - AbortCplt = 0x01U; - } - else - { - AbortCplt = 0x00U; - } - } - } - - /* if no DMA abort complete callback execution is required => call user Abort Complete callback */ - if (AbortCplt == 0x01U) - { - /* Reset Tx and Rx transfer counters */ - husart->TxXferCount = 0x00U; - husart->RxXferCount = 0x00U; - - /* Reset errorCode */ - husart->ErrorCode = HAL_USART_ERROR_NONE; - - /* Restore husart->State to Ready */ - husart->State = HAL_USART_STATE_READY; - - /* As no DMA to be aborted, call directly user Abort complete callback */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Complete Callback */ - husart->AbortCpltCallback(husart); -#else - /* Call legacy weak Abort Complete Callback */ - HAL_USART_AbortCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - - return HAL_OK; -} - -/** - * @brief This function handles USART interrupt request. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -void HAL_USART_IRQHandler(USART_HandleTypeDef *husart) -{ - uint32_t isrflags = READ_REG(husart->Instance->SR); - uint32_t cr1its = READ_REG(husart->Instance->CR1); - uint32_t cr3its = READ_REG(husart->Instance->CR3); - uint32_t errorflags = 0x00U; - uint32_t dmarequest = 0x00U; - - /* If no error occurs */ - errorflags = (isrflags & (uint32_t)(USART_SR_PE | USART_SR_FE | USART_SR_ORE | USART_SR_NE)); - if (errorflags == RESET) - { - /* USART in mode Receiver -------------------------------------------------*/ - if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - if (husart->State == HAL_USART_STATE_BUSY_RX) - { - USART_Receive_IT(husart); - } - else - { - USART_TransmitReceive_IT(husart); - } - return; - } - } - /* If some errors occur */ - if ((errorflags != RESET) && (((cr3its & USART_CR3_EIE) != RESET) || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET))) - { - /* USART parity error interrupt occurred ----------------------------------*/ - if (((isrflags & USART_SR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET)) - { - husart->ErrorCode |= HAL_USART_ERROR_PE; - } - - /* USART noise error interrupt occurred --------------------------------*/ - if (((isrflags & USART_SR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - husart->ErrorCode |= HAL_USART_ERROR_NE; - } - - /* USART frame error interrupt occurred --------------------------------*/ - if (((isrflags & USART_SR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET)) - { - husart->ErrorCode |= HAL_USART_ERROR_FE; - } - - /* USART Over-Run interrupt occurred -----------------------------------*/ - if (((isrflags & USART_SR_ORE) != RESET) && (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET))) - { - husart->ErrorCode |= HAL_USART_ERROR_ORE; - } - - if (husart->ErrorCode != HAL_USART_ERROR_NONE) - { - /* USART in mode Receiver -----------------------------------------------*/ - if (((isrflags & USART_SR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET)) - { - if (husart->State == HAL_USART_STATE_BUSY_RX) - { - USART_Receive_IT(husart); - } - else - { - USART_TransmitReceive_IT(husart); - } - } - /* If Overrun error occurs, or if any error occurs in DMA mode reception, - consider error as blocking */ - dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR); - if (((husart->ErrorCode & HAL_USART_ERROR_ORE) != RESET) || dmarequest) - { - /* Set the USART state ready to be able to start again the process, - Disable Rx Interrupts, and disable Rx DMA request, if ongoing */ - USART_EndRxTransfer(husart); - - /* Disable the USART DMA Rx request if enabled */ - if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)) - { - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); - - /* Abort the USART DMA Rx channel */ - if (husart->hdmarx != NULL) - { - /* Set the USART DMA Abort callback : - will lead to call HAL_USART_ErrorCallback() at end of DMA abort procedure */ - husart->hdmarx->XferAbortCallback = USART_DMAAbortOnError; - - if (HAL_DMA_Abort_IT(husart->hdmarx) != HAL_OK) - { - /* Call Directly XferAbortCallback function in case of error */ - husart->hdmarx->XferAbortCallback(husart->hdmarx); - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Error Callback */ - husart->ErrorCallback(husart); -#else - /* Call legacy weak Error Callback */ - HAL_USART_ErrorCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Error Callback */ - husart->ErrorCallback(husart); -#else - /* Call legacy weak Error Callback */ - HAL_USART_ErrorCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - } - else - { - /* Call user error callback */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Error Callback */ - husart->ErrorCallback(husart); -#else - /* Call legacy weak Error Callback */ - HAL_USART_ErrorCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - husart->ErrorCode = HAL_USART_ERROR_NONE; - } - } - return; - } - - /* USART in mode Transmitter -----------------------------------------------*/ - if (((isrflags & USART_SR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET)) - { - if (husart->State == HAL_USART_STATE_BUSY_TX) - { - USART_Transmit_IT(husart); - } - else - { - USART_TransmitReceive_IT(husart); - } - return; - } - - /* USART in mode Transmitter (transmission end) ----------------------------*/ - if (((isrflags & USART_SR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET)) - { - USART_EndTransmit_IT(husart); - return; - } -} - -/** - * @brief Tx Transfer completed callbacks. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_USART_TxCpltCallback(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_USART_TxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx Half Transfer completed callbacks. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_USART_TxHalfCpltCallback(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_USART_TxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Transfer completed callbacks. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_USART_RxCpltCallback(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_USART_RxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Rx Half Transfer completed callbacks. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_USART_RxHalfCpltCallback(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_USART_RxHalfCpltCallback could be implemented in the user file - */ -} - -/** - * @brief Tx/Rx Transfers completed callback for the non-blocking process. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_USART_TxRxCpltCallback(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_USART_TxRxCpltCallback could be implemented in the user file - */ -} - -/** - * @brief USART error callbacks. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -__weak void HAL_USART_ErrorCallback(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_USART_ErrorCallback could be implemented in the user file - */ -} - -/** - * @brief USART Abort Complete callback. - * @param husart USART handle. - * @retval None - */ -__weak void HAL_USART_AbortCpltCallback(USART_HandleTypeDef *husart) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(husart); - - /* NOTE : This function should not be modified, when the callback is needed, - the HAL_USART_AbortCpltCallback can be implemented in the user file. - */ -} - -/** - * @} - */ - -/** @defgroup USART_Exported_Functions_Group3 Peripheral State and Errors functions - * @brief USART State and Errors functions - * -@verbatim - ============================================================================== - ##### Peripheral State and Errors functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to return the State of - USART communication - process, return Peripheral Errors occurred during communication process - (+) HAL_USART_GetState() API can be helpful to check in run-time the state - of the USART peripheral. - (+) HAL_USART_GetError() check in run-time errors that could be occurred during - communication. -@endverbatim - * @{ - */ - -/** - * @brief Returns the USART state. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL state - */ -HAL_USART_StateTypeDef HAL_USART_GetState(USART_HandleTypeDef *husart) -{ - return husart->State; -} - -/** - * @brief Return the USART error code - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART. - * @retval USART Error Code - */ -uint32_t HAL_USART_GetError(USART_HandleTypeDef *husart) -{ - return husart->ErrorCode; -} - -/** - * @} - */ - -/** @defgroup USART_Private_Functions USART Private Functions - * @{ - */ - -/** - * @brief Initialize the callbacks to their default values. - * @param husart USART handle. - * @retval none - */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -void USART_InitCallbacksToDefault(USART_HandleTypeDef *husart) -{ - /* Init the USART Callback settings */ - husart->TxHalfCpltCallback = HAL_USART_TxHalfCpltCallback; /* Legacy weak TxHalfCpltCallback */ - husart->TxCpltCallback = HAL_USART_TxCpltCallback; /* Legacy weak TxCpltCallback */ - husart->RxHalfCpltCallback = HAL_USART_RxHalfCpltCallback; /* Legacy weak RxHalfCpltCallback */ - husart->RxCpltCallback = HAL_USART_RxCpltCallback; /* Legacy weak RxCpltCallback */ - husart->TxRxCpltCallback = HAL_USART_TxRxCpltCallback; /* Legacy weak TxRxCpltCallback */ - husart->ErrorCallback = HAL_USART_ErrorCallback; /* Legacy weak ErrorCallback */ - husart->AbortCpltCallback = HAL_USART_AbortCpltCallback; /* Legacy weak AbortCpltCallback */ -} -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -/** - * @brief DMA USART transmit process complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void USART_DMATransmitCplt(DMA_HandleTypeDef *hdma) -{ - USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* DMA Normal mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) - { - husart->TxXferCount = 0U; - if (husart->State == HAL_USART_STATE_BUSY_TX) - { - /* Disable the DMA transfer for transmit request by resetting the DMAT bit - in the USART CR3 register */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - /* Enable the USART Transmit Complete Interrupt */ - SET_BIT(husart->Instance->CR1, USART_CR1_TCIE); - } - } - /* DMA Circular mode */ - else - { - if (husart->State == HAL_USART_STATE_BUSY_TX) - { -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Tx Complete Callback */ - husart->TxCpltCallback(husart); -#else - /* Call legacy weak Tx Complete Callback */ - HAL_USART_TxCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief DMA USART transmit process half complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void USART_DMATxHalfCplt(DMA_HandleTypeDef *hdma) -{ - USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Tx Half Complete Callback */ - husart->TxHalfCpltCallback(husart); -#else - /* Call legacy weak Tx Half Complete Callback */ - HAL_USART_TxHalfCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA USART receive process complete callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void USART_DMAReceiveCplt(DMA_HandleTypeDef *hdma) -{ - USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - /* DMA Normal mode */ - if ((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U) - { - husart->RxXferCount = 0x00U; - - /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE); - CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); - - /* Disable the DMA transfer for the Transmit/receiver request by clearing the DMAT/DMAR bit - in the USART CR3 register */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR); - CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT); - - /* The USART state is HAL_USART_STATE_BUSY_RX */ - if (husart->State == HAL_USART_STATE_BUSY_RX) - { -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Rx Complete Callback */ - husart->RxCpltCallback(husart); -#else - /* Call legacy weak Rx Complete Callback */ - HAL_USART_RxCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - /* The USART state is HAL_USART_STATE_BUSY_TX_RX */ - else - { -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Tx Rx Complete Callback */ - husart->TxRxCpltCallback(husart); -#else - /* Call legacy weak Tx Rx Complete Callback */ - HAL_USART_TxRxCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - husart->State = HAL_USART_STATE_READY; - } - /* DMA circular mode */ - else - { - if (husart->State == HAL_USART_STATE_BUSY_RX) - { -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Rx Complete Callback */ - husart->RxCpltCallback(husart); -#else - /* Call legacy weak Rx Complete Callback */ - HAL_USART_RxCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - /* The USART state is HAL_USART_STATE_BUSY_TX_RX */ - else - { -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Tx Rx Complete Callback */ - husart->TxRxCpltCallback(husart); -#else - /* Call legacy weak Tx Rx Complete Callback */ - HAL_USART_TxRxCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - } - } -} - -/** - * @brief DMA USART receive process half complete callback - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void USART_DMARxHalfCplt(DMA_HandleTypeDef *hdma) -{ - USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Rx Half Complete Callback */ - husart->RxHalfCpltCallback(husart); -#else - /* Call legacy weak Rx Half Complete Callback */ - HAL_USART_RxHalfCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA USART communication error callback. - * @param hdma Pointer to a DMA_HandleTypeDef structure that contains - * the configuration information for the specified DMA module. - * @retval None - */ -static void USART_DMAError(DMA_HandleTypeDef *hdma) -{ - uint32_t dmarequest = 0x00U; - USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - husart->RxXferCount = 0x00U; - husart->TxXferCount = 0x00U; - - /* Stop USART DMA Tx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT); - if ((husart->State == HAL_USART_STATE_BUSY_TX) && dmarequest) - { - USART_EndTxTransfer(husart); - } - - /* Stop USART DMA Rx request if ongoing */ - dmarequest = HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR); - if ((husart->State == HAL_USART_STATE_BUSY_RX) && dmarequest) - { - USART_EndRxTransfer(husart); - } - - husart->ErrorCode |= HAL_USART_ERROR_DMA; - husart->State = HAL_USART_STATE_READY; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Error Callback */ - husart->ErrorCallback(husart); -#else - /* Call legacy weak Error Callback */ - HAL_USART_ErrorCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -} - -/** - * @brief This function handles USART Communication Timeout. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @param Flag specifies the USART flag to check. - * @param Status The new Flag status (SET or RESET). - * @param Tickstart Tick start value. - * @param Timeout Timeout duration. - * @retval HAL status - */ -static HAL_StatusTypeDef USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef *husart, uint32_t Flag, FlagStatus Status, - uint32_t Tickstart, uint32_t Timeout) -{ - /* Wait until flag is set */ - while ((__HAL_USART_GET_FLAG(husart, Flag) ? SET : RESET) == Status) - { - /* Check for the Timeout */ - if (Timeout != HAL_MAX_DELAY) - { - if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) > Timeout)) - { - /* Disable the USART Transmit Complete Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_TXEIE); - - /* Disable the USART RXNE Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE); - - /* Disable the USART Parity Error Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE); - - /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); - - husart->State = HAL_USART_STATE_READY; - - /* Process Unlocked */ - __HAL_UNLOCK(husart); - - return HAL_TIMEOUT; - } - } - } - return HAL_OK; -} - -/** - * @brief End ongoing Tx transfer on USART peripheral (following error detection or Transmit completion). - * @param husart USART handle. - * @retval None - */ -static void USART_EndTxTransfer(USART_HandleTypeDef *husart) -{ - /* Disable TXEIE and TCIE interrupts */ - CLEAR_BIT(husart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE)); - - /* At end of Tx process, restore husart->State to Ready */ - husart->State = HAL_USART_STATE_READY; -} - -/** - * @brief End ongoing Rx transfer on USART peripheral (following error detection or Reception completion). - * @param husart USART handle. - * @retval None - */ -static void USART_EndRxTransfer(USART_HandleTypeDef *husart) -{ - /* Disable RXNE, PE and ERR interrupts */ - CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE)); - CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); - - /* At end of Rx process, restore husart->State to Ready */ - husart->State = HAL_USART_STATE_READY; -} - -/** - * @brief DMA USART communication abort callback, when initiated by HAL services on Error - * (To be called at end of DMA Abort procedure following error occurrence). - * @param hdma DMA handle. - * @retval None - */ -static void USART_DMAAbortOnError(DMA_HandleTypeDef *hdma) -{ - USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - husart->RxXferCount = 0x00U; - husart->TxXferCount = 0x00U; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Error Callback */ - husart->ErrorCallback(husart); -#else - /* Call legacy weak Error Callback */ - HAL_USART_ErrorCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA USART Tx communication abort callback, when initiated by user - * (To be called at end of DMA Tx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Rx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void USART_DMATxAbortCallback(DMA_HandleTypeDef *hdma) -{ - USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - husart->hdmatx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if (husart->hdmarx != NULL) - { - if (husart->hdmarx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - husart->TxXferCount = 0x00U; - husart->RxXferCount = 0x00U; - - /* Reset errorCode */ - husart->ErrorCode = HAL_USART_ERROR_NONE; - - /* Restore husart->State to Ready */ - husart->State = HAL_USART_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Complete Callback */ - husart->AbortCpltCallback(husart); -#else - /* Call legacy weak Abort Complete Callback */ - HAL_USART_AbortCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -} - -/** - * @brief DMA USART Rx communication abort callback, when initiated by user - * (To be called at end of DMA Rx Abort procedure following user abort request). - * @note When this callback is executed, User Abort complete call back is called only if no - * Abort still ongoing for Tx DMA Handle. - * @param hdma DMA handle. - * @retval None - */ -static void USART_DMARxAbortCallback(DMA_HandleTypeDef *hdma) -{ - USART_HandleTypeDef *husart = (USART_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent; - - husart->hdmarx->XferAbortCallback = NULL; - - /* Check if an Abort process is still ongoing */ - if (husart->hdmatx != NULL) - { - if (husart->hdmatx->XferAbortCallback != NULL) - { - return; - } - } - - /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */ - husart->TxXferCount = 0x00U; - husart->RxXferCount = 0x00U; - - /* Reset errorCode */ - husart->ErrorCode = HAL_USART_ERROR_NONE; - - /* Restore husart->State to Ready */ - husart->State = HAL_USART_STATE_READY; - - /* Call user Abort complete callback */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Abort Complete Callback */ - husart->AbortCpltCallback(husart); -#else - /* Call legacy weak Abort Complete Callback */ - HAL_USART_AbortCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -} - -/** - * @brief Simplex Send an amount of data in non-blocking mode. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - * @note The USART errors are not managed to avoid the overrun error. - */ -static HAL_StatusTypeDef USART_Transmit_IT(USART_HandleTypeDef *husart) -{ - uint16_t *tmp; - - if (husart->State == HAL_USART_STATE_BUSY_TX) - { - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) - { - tmp = (uint16_t *) husart->pTxBuffPtr; - husart->Instance->DR = (uint16_t)(*tmp & (uint16_t)0x01FF); - husart->pTxBuffPtr += 2U; - } - else - { - husart->Instance->DR = (uint8_t)(*husart->pTxBuffPtr++ & (uint8_t)0x00FF); - } - - if (--husart->TxXferCount == 0U) - { - /* Disable the USART Transmit data register empty Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_TXEIE); - - /* Enable the USART Transmit Complete Interrupt */ - SET_BIT(husart->Instance->CR1, USART_CR1_TCIE); - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Wraps up transmission in non blocking mode. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - */ -static HAL_StatusTypeDef USART_EndTransmit_IT(USART_HandleTypeDef *husart) -{ - /* Disable the USART Transmit Complete Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_TCIE); - - /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); - - husart->State = HAL_USART_STATE_READY; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Tx Complete Callback */ - husart->TxCpltCallback(husart); -#else - /* Call legacy weak Tx Complete Callback */ - HAL_USART_TxCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - - return HAL_OK; -} - -/** - * @brief Simplex Receive an amount of data in non-blocking mode. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - */ -static HAL_StatusTypeDef USART_Receive_IT(USART_HandleTypeDef *husart) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - - if (husart->State == HAL_USART_STATE_BUSY_RX) - { - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) husart->pRxBuffPtr; - *pdata16bits = (uint16_t)(husart->Instance->DR & (uint16_t)0x01FF); - husart->pRxBuffPtr += 2U; - } - else - { - pdata8bits = (uint8_t *) husart->pRxBuffPtr; - pdata16bits = NULL; - - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) || ((husart->Init.WordLength == USART_WORDLENGTH_8B) && (husart->Init.Parity == USART_PARITY_NONE))) - { - *pdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x007F); - } - - husart->pRxBuffPtr += 1U; - } - - husart->RxXferCount--; - - if (husart->RxXferCount == 0U) - { - /* Disable the USART RXNE Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE); - - /* Disable the USART Parity Error Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE); - - /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); - - husart->State = HAL_USART_STATE_READY; -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Rx Complete Callback */ - husart->RxCpltCallback(husart); -#else - /* Call legacy weak Rx Complete Callback */ - HAL_USART_RxCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - - return HAL_OK; - } - else - { - /* Send dummy byte in order to generate the clock for the slave to send the next data. - * Whatever the frame length (7, 8 or 9-bit long), the same dummy value - * can be written for all the cases. */ - husart->Instance->DR = (DUMMY_DATA & (uint16_t)0x0FF); - } - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Full-Duplex Send receive an amount of data in full-duplex mode (non-blocking). - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval HAL status - */ -static HAL_StatusTypeDef USART_TransmitReceive_IT(USART_HandleTypeDef *husart) -{ - uint8_t *pdata8bits; - uint16_t *pdata16bits; - - if (husart->State == HAL_USART_STATE_BUSY_TX_RX) - { - if (husart->TxXferCount != 0x00U) - { - if (__HAL_USART_GET_FLAG(husart, USART_FLAG_TXE) != RESET) - { - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) husart->pTxBuffPtr; - husart->Instance->DR = (uint16_t)(*pdata16bits & (uint16_t)0x01FF); - husart->pTxBuffPtr += 2U; - } - else - { - husart->Instance->DR = (uint8_t)(*husart->pTxBuffPtr++ & (uint8_t)0x00FF); - } - - husart->TxXferCount--; - - /* Check the latest data transmitted */ - if (husart->TxXferCount == 0U) - { - CLEAR_BIT(husart->Instance->CR1, USART_CR1_TXEIE); - } - } - } - - if (husart->RxXferCount != 0x00U) - { - if (__HAL_USART_GET_FLAG(husart, USART_FLAG_RXNE) != RESET) - { - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE)) - { - pdata8bits = NULL; - pdata16bits = (uint16_t *) husart->pRxBuffPtr; - *pdata16bits = (uint16_t)(husart->Instance->DR & (uint16_t)0x01FF); - husart->pRxBuffPtr += 2U; - } - else - { - pdata8bits = (uint8_t *) husart->pRxBuffPtr; - pdata16bits = NULL; - if ((husart->Init.WordLength == USART_WORDLENGTH_9B) || ((husart->Init.WordLength == USART_WORDLENGTH_8B) && (husart->Init.Parity == USART_PARITY_NONE))) - { - *pdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x00FF); - } - else - { - *pdata8bits = (uint8_t)(husart->Instance->DR & (uint8_t)0x007F); - } - husart->pRxBuffPtr += 1U; - } - - husart->RxXferCount--; - } - } - - /* Check the latest data received */ - if (husart->RxXferCount == 0U) - { - /* Disable the USART RXNE Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE); - - /* Disable the USART Parity Error Interrupt */ - CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE); - - /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */ - CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE); - - husart->State = HAL_USART_STATE_READY; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - /* Call registered Tx Rx Complete Callback */ - husart->TxRxCpltCallback(husart); -#else - /* Call legacy weak Tx Rx Complete Callback */ - HAL_USART_TxRxCpltCallback(husart); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - - return HAL_OK; - } - - return HAL_OK; - } - else - { - return HAL_BUSY; - } -} - -/** - * @brief Configures the USART peripheral. - * @param husart Pointer to a USART_HandleTypeDef structure that contains - * the configuration information for the specified USART module. - * @retval None - */ -static void USART_SetConfig(USART_HandleTypeDef *husart) -{ - uint32_t tmpreg = 0x00U; - uint32_t pclk; - - /* Check the parameters */ - assert_param(IS_USART_INSTANCE(husart->Instance)); - assert_param(IS_USART_POLARITY(husart->Init.CLKPolarity)); - assert_param(IS_USART_PHASE(husart->Init.CLKPhase)); - assert_param(IS_USART_LASTBIT(husart->Init.CLKLastBit)); - assert_param(IS_USART_BAUDRATE(husart->Init.BaudRate)); - assert_param(IS_USART_WORD_LENGTH(husart->Init.WordLength)); - assert_param(IS_USART_STOPBITS(husart->Init.StopBits)); - assert_param(IS_USART_PARITY(husart->Init.Parity)); - assert_param(IS_USART_MODE(husart->Init.Mode)); - - /* The LBCL, CPOL and CPHA bits have to be selected when both the transmitter and the - receiver are disabled (TE=RE=0) to ensure that the clock pulses function correctly. */ - CLEAR_BIT(husart->Instance->CR1, (USART_CR1_TE | USART_CR1_RE)); - - /*---------------------------- USART CR2 Configuration ---------------------*/ - tmpreg = husart->Instance->CR2; - /* Clear CLKEN, CPOL, CPHA and LBCL bits */ - tmpreg &= (uint32_t)~((uint32_t)(USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_CLKEN | USART_CR2_LBCL | USART_CR2_STOP)); - /* Configure the USART Clock, CPOL, CPHA and LastBit -----------------------*/ - /* Set CPOL bit according to husart->Init.CLKPolarity value */ - /* Set CPHA bit according to husart->Init.CLKPhase value */ - /* Set LBCL bit according to husart->Init.CLKLastBit value */ - /* Set Stop Bits: Set STOP[13:12] bits according to husart->Init.StopBits value */ - tmpreg |= (uint32_t)(USART_CLOCK_ENABLE | husart->Init.CLKPolarity | - husart->Init.CLKPhase | husart->Init.CLKLastBit | husart->Init.StopBits); - /* Write to USART CR2 */ - WRITE_REG(husart->Instance->CR2, (uint32_t)tmpreg); - - /*-------------------------- USART CR1 Configuration -----------------------*/ - tmpreg = husart->Instance->CR1; - - /* Clear M, PCE, PS, TE, RE and OVER8 bits */ - tmpreg &= (uint32_t)~((uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_TE | \ - USART_CR1_RE | USART_CR1_OVER8)); - - /* Configure the USART Word Length, Parity and mode: - Set the M bits according to husart->Init.WordLength value - Set PCE and PS bits according to husart->Init.Parity value - Set TE and RE bits according to husart->Init.Mode value - Force OVER8 bit to 1 in order to reach the max USART frequencies */ - tmpreg |= (uint32_t)husart->Init.WordLength | husart->Init.Parity | husart->Init.Mode | USART_CR1_OVER8; - - /* Write to USART CR1 */ - WRITE_REG(husart->Instance->CR1, (uint32_t)tmpreg); - - /*-------------------------- USART CR3 Configuration -----------------------*/ - /* Clear CTSE and RTSE bits */ - CLEAR_BIT(husart->Instance->CR3, (USART_CR3_RTSE | USART_CR3_CTSE)); - - /*-------------------------- USART BRR Configuration -----------------------*/ -#if defined(USART6) && defined(UART9) && defined(UART10) - if ((husart->Instance == USART1) || (husart->Instance == USART6) || (husart->Instance == UART9) || (husart->Instance == UART10)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - husart->Instance->BRR = USART_BRR(pclk, husart->Init.BaudRate); - } -#elif defined(USART6) - if((husart->Instance == USART1) || (husart->Instance == USART6)) - { - pclk = HAL_RCC_GetPCLK2Freq(); - husart->Instance->BRR = USART_BRR(pclk, husart->Init.BaudRate); - } -#else - if(husart->Instance == USART1) - { - pclk = HAL_RCC_GetPCLK2Freq(); - husart->Instance->BRR = USART_BRR(pclk, husart->Init.BaudRate); - } -#endif /* USART6 || UART9 || UART10 */ - else - { - pclk = HAL_RCC_GetPCLK1Freq(); - husart->Instance->BRR = USART_BRR(pclk, husart->Init.BaudRate); - } -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_USART_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_wwdg.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_wwdg.c deleted file mode 100644 index d1e2fa071e88928..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_wwdg.c +++ /dev/null @@ -1,422 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_wwdg.c - * @author MCD Application Team - * @brief WWDG HAL module driver. - * This file provides firmware functions to manage the following - * functionalities of the Window Watchdog (WWDG) peripheral: - * + Initialization and Configuration functions - * + IO operation functions - @verbatim - ============================================================================== - ##### WWDG Specific features ##### - ============================================================================== - [..] - Once enabled the WWDG generates a system reset on expiry of a programmed - time period, unless the program refreshes the counter (T[6;0] downcounter) - before reaching 0x3F value (i.e. a reset is generated when the counter - value rolls down from 0x40 to 0x3F). - - (+) An MCU reset is also generated if the counter value is refreshed - before the counter has reached the refresh window value. This - implies that the counter must be refreshed in a limited window. - (+) Once enabled the WWDG cannot be disabled except by a system reset. - (+) If required by application, an Early Wakeup Interrupt can be triggered - in order to be warned before WWDG expiration. The Early Wakeup Interrupt - (EWI) can be used if specific safety operations or data logging must - be performed before the actual reset is generated. When the downcounter - reaches 0x40, interrupt occurs. This mechanism requires WWDG interrupt - line to be enabled in NVIC. Once enabled, EWI interrupt cannot be - disabled except by a system reset. - (+) WWDGRST flag in RCC CSR register can be used to inform when a WWDG - reset occurs. - (+) The WWDG counter input clock is derived from the APB clock divided - by a programmable prescaler. - (+) WWDG clock (Hz) = PCLK1 / (4096 * Prescaler) - (+) WWDG timeout (mS) = 1000 * (T[5;0] + 1) / WWDG clock (Hz) - where T[5;0] are the lowest 6 bits of Counter. - (+) WWDG Counter refresh is allowed between the following limits : - (++) min time (mS) = 1000 * (Counter - Window) / WWDG clock - (++) max time (mS) = 1000 * (Counter - 0x40) / WWDG clock - (+) Typical values: - (++) Counter min (T[5;0] = 0x00) at 42MHz (PCLK1) with zero prescaler: - max timeout before reset: approximately 97.52s - (++) Counter max (T[5;0] = 0x3F) at 42MHz (PCLK1) with prescaler - dividing by 8: - max timeout before reset: approximately 49.93ms - - ##### How to use this driver ##### - ============================================================================== - - *** Common driver usage *** - =========================== - - [..] - (+) Enable WWDG APB1 clock using __HAL_RCC_WWDG_CLK_ENABLE(). - (+) Configure the WWDG prescaler, refresh window value, counter value and early - interrupt status using HAL_WWDG_Init() function. This will automatically - enable WWDG and start its downcounter. Time reference can be taken from - function exit. Care must be taken to provide a counter value - greater than 0x40 to prevent generation of immediate reset. - (+) If the Early Wakeup Interrupt (EWI) feature is enabled, an interrupt is - generated when the counter reaches 0x40. When HAL_WWDG_IRQHandler is - triggered by the interrupt service routine, flag will be automatically - cleared and HAL_WWDG_WakeupCallback user callback will be executed. User - can add his own code by customization of callback HAL_WWDG_WakeupCallback. - (+) Then the application program must refresh the WWDG counter at regular - intervals during normal operation to prevent an MCU reset, using - HAL_WWDG_Refresh() function. This operation must occur only when - the counter is lower than the refresh window value already programmed. - - *** Callback registration *** - ============================= - - [..] - The compilation define USE_HAL_WWDG_REGISTER_CALLBACKS when set to 1 allows - the user to configure dynamically the driver callbacks. Use Functions - HAL_WWDG_RegisterCallback() to register a user callback. - - (+) Function HAL_WWDG_RegisterCallback() allows to register following - callbacks: - (++) EwiCallback : callback for Early WakeUp Interrupt. - (++) MspInitCallback : WWDG MspInit. - This function takes as parameters the HAL peripheral handle, the Callback ID - and a pointer to the user callback function. - - (+) Use function HAL_WWDG_UnRegisterCallback() to reset a callback to - the default weak (surcharged) function. HAL_WWDG_UnRegisterCallback() - takes as parameters the HAL peripheral handle and the Callback ID. - This function allows to reset following callbacks: - (++) EwiCallback : callback for Early WakeUp Interrupt. - (++) MspInitCallback : WWDG MspInit. - - [..] - When calling HAL_WWDG_Init function, callbacks are reset to the - corresponding legacy weak (surcharged) functions: - HAL_WWDG_EarlyWakeupCallback() and HAL_WWDG_MspInit() only if they have - not been registered before. - - [..] - When compilation define USE_HAL_WWDG_REGISTER_CALLBACKS is set to 0 or - not defined, the callback registering feature is not available - and weak (surcharged) callbacks are used. - - *** WWDG HAL driver macros list *** - =================================== - [..] - Below the list of available macros in WWDG HAL driver. - (+) __HAL_WWDG_ENABLE: Enable the WWDG peripheral - (+) __HAL_WWDG_GET_FLAG: Get the selected WWDG's flag status - (+) __HAL_WWDG_CLEAR_FLAG: Clear the WWDG's pending flags - (+) __HAL_WWDG_ENABLE_IT: Enable the WWDG early wakeup interrupt - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#ifdef HAL_WWDG_MODULE_ENABLED -/** @defgroup WWDG WWDG - * @brief WWDG HAL module driver. - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup WWDG_Exported_Functions WWDG Exported Functions - * @{ - */ - -/** @defgroup WWDG_Exported_Functions_Group1 Initialization and Configuration functions - * @brief Initialization and Configuration functions. - * -@verbatim - ============================================================================== - ##### Initialization and Configuration functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and start the WWDG according to the specified parameters - in the WWDG_InitTypeDef of associated handle. - (+) Initialize the WWDG MSP. - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the WWDG according to the specified. - * parameters in the WWDG_InitTypeDef of associated handle. - * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains - * the configuration information for the specified WWDG module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_WWDG_Init(WWDG_HandleTypeDef *hwwdg) -{ - /* Check the WWDG handle allocation */ - if (hwwdg == NULL) - { - return HAL_ERROR; - } - - /* Check the parameters */ - assert_param(IS_WWDG_ALL_INSTANCE(hwwdg->Instance)); - assert_param(IS_WWDG_PRESCALER(hwwdg->Init.Prescaler)); - assert_param(IS_WWDG_WINDOW(hwwdg->Init.Window)); - assert_param(IS_WWDG_COUNTER(hwwdg->Init.Counter)); - assert_param(IS_WWDG_EWI_MODE(hwwdg->Init.EWIMode)); - -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) - /* Reset Callback pointers */ - if (hwwdg->EwiCallback == NULL) - { - hwwdg->EwiCallback = HAL_WWDG_EarlyWakeupCallback; - } - - if (hwwdg->MspInitCallback == NULL) - { - hwwdg->MspInitCallback = HAL_WWDG_MspInit; - } - - /* Init the low level hardware */ - hwwdg->MspInitCallback(hwwdg); -#else - /* Init the low level hardware */ - HAL_WWDG_MspInit(hwwdg); -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ - - /* Set WWDG Counter */ - WRITE_REG(hwwdg->Instance->CR, (WWDG_CR_WDGA | hwwdg->Init.Counter)); - - /* Set WWDG Prescaler and Window */ - WRITE_REG(hwwdg->Instance->CFR, (hwwdg->Init.EWIMode | hwwdg->Init.Prescaler | hwwdg->Init.Window)); - - /* Return function status */ - return HAL_OK; -} - - -/** - * @brief Initialize the WWDG MSP. - * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains - * the configuration information for the specified WWDG module. - * @note When rewriting this function in user file, mechanism may be added - * to avoid multiple initialize when HAL_WWDG_Init function is called - * again to change parameters. - * @retval None - */ -__weak void HAL_WWDG_MspInit(WWDG_HandleTypeDef *hwwdg) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hwwdg); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_WWDG_MspInit could be implemented in the user file - */ -} - - -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) -/** - * @brief Register a User WWDG Callback - * To be used instead of the weak (surcharged) predefined callback - * @param hwwdg WWDG handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_WWDG_EWI_CB_ID Early WakeUp Interrupt Callback ID - * @arg @ref HAL_WWDG_MSPINIT_CB_ID MspInit callback ID - * @param pCallback pointer to the Callback function - * @retval status - */ -HAL_StatusTypeDef HAL_WWDG_RegisterCallback(WWDG_HandleTypeDef *hwwdg, HAL_WWDG_CallbackIDTypeDef CallbackID, - pWWDG_CallbackTypeDef pCallback) -{ - HAL_StatusTypeDef status = HAL_OK; - - if (pCallback == NULL) - { - status = HAL_ERROR; - } - else - { - switch (CallbackID) - { - case HAL_WWDG_EWI_CB_ID: - hwwdg->EwiCallback = pCallback; - break; - - case HAL_WWDG_MSPINIT_CB_ID: - hwwdg->MspInitCallback = pCallback; - break; - - default: - status = HAL_ERROR; - break; - } - } - - return status; -} - - -/** - * @brief Unregister a WWDG Callback - * WWDG Callback is redirected to the weak (surcharged) predefined callback - * @param hwwdg WWDG handle - * @param CallbackID ID of the callback to be registered - * This parameter can be one of the following values: - * @arg @ref HAL_WWDG_EWI_CB_ID Early WakeUp Interrupt Callback ID - * @arg @ref HAL_WWDG_MSPINIT_CB_ID MspInit callback ID - * @retval status - */ -HAL_StatusTypeDef HAL_WWDG_UnRegisterCallback(WWDG_HandleTypeDef *hwwdg, HAL_WWDG_CallbackIDTypeDef CallbackID) -{ - HAL_StatusTypeDef status = HAL_OK; - - switch (CallbackID) - { - case HAL_WWDG_EWI_CB_ID: - hwwdg->EwiCallback = HAL_WWDG_EarlyWakeupCallback; - break; - - case HAL_WWDG_MSPINIT_CB_ID: - hwwdg->MspInitCallback = HAL_WWDG_MspInit; - break; - - default: - status = HAL_ERROR; - break; - } - - return status; -} -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup WWDG_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * -@verbatim - ============================================================================== - ##### IO operation functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Refresh the WWDG. - (+) Handle WWDG interrupt request and associated function callback. - -@endverbatim - * @{ - */ - -/** - * @brief Refresh the WWDG. - * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains - * the configuration information for the specified WWDG module. - * @retval HAL status - */ -HAL_StatusTypeDef HAL_WWDG_Refresh(WWDG_HandleTypeDef *hwwdg) -{ - /* Write to WWDG CR the WWDG Counter value to refresh with */ - WRITE_REG(hwwdg->Instance->CR, (hwwdg->Init.Counter)); - - /* Return function status */ - return HAL_OK; -} - -/** - * @brief Handle WWDG interrupt request. - * @note The Early Wakeup Interrupt (EWI) can be used if specific safety operations - * or data logging must be performed before the actual reset is generated. - * The EWI interrupt is enabled by calling HAL_WWDG_Init function with - * EWIMode set to WWDG_EWI_ENABLE. - * When the downcounter reaches the value 0x40, and EWI interrupt is - * generated and the corresponding Interrupt Service Routine (ISR) can - * be used to trigger specific actions (such as communications or data - * logging), before resetting the device. - * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains - * the configuration information for the specified WWDG module. - * @retval None - */ -void HAL_WWDG_IRQHandler(WWDG_HandleTypeDef *hwwdg) -{ - /* Check if Early Wakeup Interrupt is enable */ - if (__HAL_WWDG_GET_IT_SOURCE(hwwdg, WWDG_IT_EWI) != RESET) - { - /* Check if WWDG Early Wakeup Interrupt occurred */ - if (__HAL_WWDG_GET_FLAG(hwwdg, WWDG_FLAG_EWIF) != RESET) - { - /* Clear the WWDG Early Wakeup flag */ - __HAL_WWDG_CLEAR_FLAG(hwwdg, WWDG_FLAG_EWIF); - -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) - /* Early Wakeup registered callback */ - hwwdg->EwiCallback(hwwdg); -#else - /* Early Wakeup callback */ - HAL_WWDG_EarlyWakeupCallback(hwwdg); -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ - } - } -} - - -/** - * @brief WWDG Early Wakeup callback. - * @param hwwdg pointer to a WWDG_HandleTypeDef structure that contains - * the configuration information for the specified WWDG module. - * @retval None - */ -__weak void HAL_WWDG_EarlyWakeupCallback(WWDG_HandleTypeDef *hwwdg) -{ - /* Prevent unused argument(s) compilation warning */ - UNUSED(hwwdg); - - /* NOTE: This function should not be modified, when the callback is needed, - the HAL_WWDG_EarlyWakeupCallback could be implemented in the user file - */ -} - -/** - * @} - */ - -/** - * @} - */ - -#endif /* HAL_WWDG_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c deleted file mode 100644 index 5710e2664e0cc68..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_adc.c +++ /dev/null @@ -1,924 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_adc.c - * @author MCD Application Team - * @brief ADC LL module driver - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_adc.h" -#include "stm32f4xx_ll_bus.h" - -#ifdef USE_FULL_ASSERT - #include "stm32_assert.h" -#else - #define assert_param(expr) ((void)0U) -#endif - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (ADC1) || defined (ADC2) || defined (ADC3) - -/** @addtogroup ADC_LL ADC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/** @addtogroup ADC_LL_Private_Macros - * @{ - */ - -/* Check of parameters for configuration of ADC hierarchical scope: */ -/* common to several ADC instances. */ -#define IS_LL_ADC_COMMON_CLOCK(__CLOCK__) \ - ( ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV2) \ - || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV4) \ - || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV6) \ - || ((__CLOCK__) == LL_ADC_CLOCK_SYNC_PCLK_DIV8) \ - ) - -/* Check of parameters for configuration of ADC hierarchical scope: */ -/* ADC instance. */ -#define IS_LL_ADC_RESOLUTION(__RESOLUTION__) \ - ( ((__RESOLUTION__) == LL_ADC_RESOLUTION_12B) \ - || ((__RESOLUTION__) == LL_ADC_RESOLUTION_10B) \ - || ((__RESOLUTION__) == LL_ADC_RESOLUTION_8B) \ - || ((__RESOLUTION__) == LL_ADC_RESOLUTION_6B) \ - ) - -#define IS_LL_ADC_DATA_ALIGN(__DATA_ALIGN__) \ - ( ((__DATA_ALIGN__) == LL_ADC_DATA_ALIGN_RIGHT) \ - || ((__DATA_ALIGN__) == LL_ADC_DATA_ALIGN_LEFT) \ - ) - -#define IS_LL_ADC_SCAN_SELECTION(__SCAN_SELECTION__) \ - ( ((__SCAN_SELECTION__) == LL_ADC_SEQ_SCAN_DISABLE) \ - || ((__SCAN_SELECTION__) == LL_ADC_SEQ_SCAN_ENABLE) \ - ) - -#define IS_LL_ADC_SEQ_SCAN_MODE(__SEQ_SCAN_MODE__) \ - ( ((__SCAN_MODE__) == LL_ADC_SEQ_SCAN_DISABLE) \ - || ((__SCAN_MODE__) == LL_ADC_SEQ_SCAN_ENABLE) \ - ) - -/* Check of parameters for configuration of ADC hierarchical scope: */ -/* ADC group regular */ -#define IS_LL_ADC_REG_TRIG_SOURCE(__REG_TRIG_SOURCE__) \ - ( ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_SOFTWARE) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH1) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH2) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM1_CH3) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH2) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH3) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_CH4) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM2_TRGO) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM3_CH1) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM3_TRGO) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM4_CH4) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH1) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH2) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM5_CH3) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM8_CH1) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_TIM8_TRGO) \ - || ((__REG_TRIG_SOURCE__) == LL_ADC_REG_TRIG_EXT_EXTI_LINE11) \ - ) -#define IS_LL_ADC_REG_CONTINUOUS_MODE(__REG_CONTINUOUS_MODE__) \ - ( ((__REG_CONTINUOUS_MODE__) == LL_ADC_REG_CONV_SINGLE) \ - || ((__REG_CONTINUOUS_MODE__) == LL_ADC_REG_CONV_CONTINUOUS) \ - ) - -#define IS_LL_ADC_REG_DMA_TRANSFER(__REG_DMA_TRANSFER__) \ - ( ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_NONE) \ - || ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_LIMITED) \ - || ((__REG_DMA_TRANSFER__) == LL_ADC_REG_DMA_TRANSFER_UNLIMITED) \ - ) - -#define IS_LL_ADC_REG_FLAG_EOC_SELECTION(__REG_FLAG_EOC_SELECTION__) \ - ( ((__REG_FLAG_EOC_SELECTION__) == LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV) \ - || ((__REG_FLAG_EOC_SELECTION__) == LL_ADC_REG_FLAG_EOC_UNITARY_CONV) \ - ) - -#define IS_LL_ADC_REG_SEQ_SCAN_LENGTH(__REG_SEQ_SCAN_LENGTH__) \ - ( ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_DISABLE) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS) \ - || ((__REG_SEQ_SCAN_LENGTH__) == LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS) \ - ) - -#define IS_LL_ADC_REG_SEQ_SCAN_DISCONT_MODE(__REG_SEQ_DISCONT_MODE__) \ - ( ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_DISABLE) \ - || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_1RANK) \ - || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_2RANKS) \ - || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_3RANKS) \ - || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_4RANKS) \ - || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_5RANKS) \ - || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_6RANKS) \ - || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_7RANKS) \ - || ((__REG_SEQ_DISCONT_MODE__) == LL_ADC_REG_SEQ_DISCONT_8RANKS) \ - ) - -/* Check of parameters for configuration of ADC hierarchical scope: */ -/* ADC group injected */ -#define IS_LL_ADC_INJ_TRIG_SOURCE(__INJ_TRIG_SOURCE__) \ - ( ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_SOFTWARE) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM1_CH4) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM1_TRGO) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM2_CH1) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM2_TRGO) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM3_CH2) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM3_CH4) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH1) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH2) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_CH3) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM4_TRGO) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM5_CH4) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM5_TRGO) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH2) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH3) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_TIM8_CH4) \ - || ((__INJ_TRIG_SOURCE__) == LL_ADC_INJ_TRIG_EXT_EXTI_LINE15) \ - ) - -#define IS_LL_ADC_INJ_TRIG_EXT_EDGE(__INJ_TRIG_EXT_EDGE__) \ - ( ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_RISING) \ - || ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_FALLING) \ - || ((__INJ_TRIG_EXT_EDGE__) == LL_ADC_INJ_TRIG_EXT_RISINGFALLING) \ - ) - -#define IS_LL_ADC_INJ_TRIG_AUTO(__INJ_TRIG_AUTO__) \ - ( ((__INJ_TRIG_AUTO__) == LL_ADC_INJ_TRIG_INDEPENDENT) \ - || ((__INJ_TRIG_AUTO__) == LL_ADC_INJ_TRIG_FROM_GRP_REGULAR) \ - ) - -#define IS_LL_ADC_INJ_SEQ_SCAN_LENGTH(__INJ_SEQ_SCAN_LENGTH__) \ - ( ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_DISABLE) \ - || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS) \ - || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS) \ - || ((__INJ_SEQ_SCAN_LENGTH__) == LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS) \ - ) - -#define IS_LL_ADC_INJ_SEQ_SCAN_DISCONT_MODE(__INJ_SEQ_DISCONT_MODE__) \ - ( ((__INJ_SEQ_DISCONT_MODE__) == LL_ADC_INJ_SEQ_DISCONT_DISABLE) \ - || ((__INJ_SEQ_DISCONT_MODE__) == LL_ADC_INJ_SEQ_DISCONT_1RANK) \ - ) - -#if defined(ADC_MULTIMODE_SUPPORT) -/* Check of parameters for configuration of ADC hierarchical scope: */ -/* multimode. */ -#if defined(ADC3) -#define IS_LL_ADC_MULTI_MODE(__MULTI_MODE__) \ - ( ((__MULTI_MODE__) == LL_ADC_MULTI_INDEPENDENT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIMULT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INTERL) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_SIMULT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_ALTERN) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_INJ_SIMULT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_SIMULT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_REG_INTERL) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_TRIPLE_INJ_ALTERN) \ - ) -#else -#define IS_LL_ADC_MULTI_MODE(__MULTI_MODE__) \ - ( ((__MULTI_MODE__) == LL_ADC_MULTI_INDEPENDENT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIMULT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INTERL) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_SIMULT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_INJ_ALTERN) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT) \ - || ((__MULTI_MODE__) == LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM) \ - ) -#endif - -#define IS_LL_ADC_MULTI_DMA_TRANSFER(__MULTI_DMA_TRANSFER__) \ - ( ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_EACH_ADC) \ - || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_1) \ - || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_2) \ - || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_LIMIT_3) \ - || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_1) \ - || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_2) \ - || ((__MULTI_DMA_TRANSFER__) == LL_ADC_MULTI_REG_DMA_UNLMT_3) \ - ) - -#define IS_LL_ADC_MULTI_TWOSMP_DELAY(__MULTI_TWOSMP_DELAY__) \ - ( ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES) \ - || ((__MULTI_TWOSMP_DELAY__) == LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES) \ - ) - -#define IS_LL_ADC_MULTI_MASTER_SLAVE(__MULTI_MASTER_SLAVE__) \ - ( ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_MASTER) \ - || ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_SLAVE) \ - || ((__MULTI_MASTER_SLAVE__) == LL_ADC_MULTI_MASTER_SLAVE) \ - ) - -#endif /* ADC_MULTIMODE_SUPPORT */ -/** - * @} - */ - - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup ADC_LL_Exported_Functions - * @{ - */ - -/** @addtogroup ADC_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize registers of all ADC instances belonging to - * the same ADC common instance to their default reset values. - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval An ErrorStatus enumeration value: - * - SUCCESS: ADC common registers are de-initialized - * - ERROR: not applicable - */ -ErrorStatus LL_ADC_CommonDeInit(ADC_Common_TypeDef *ADCxy_COMMON) -{ - /* Check the parameters */ - assert_param(IS_ADC_COMMON_INSTANCE(ADCxy_COMMON)); - - - /* Force reset of ADC clock (core clock) */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_ADC); - - /* Release reset of ADC clock (core clock) */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_ADC); - - return SUCCESS; -} - -/** - * @brief Initialize some features of ADC common parameters - * (all ADC instances belonging to the same ADC common instance) - * and multimode (for devices with several ADC instances available). - * @note The setting of ADC common parameters is conditioned to - * ADC instances state: - * All ADC instances belonging to the same ADC common instance - * must be disabled. - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param ADC_CommonInitStruct Pointer to a @ref LL_ADC_CommonInitTypeDef structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: ADC common registers are initialized - * - ERROR: ADC common registers are not initialized - */ -ErrorStatus LL_ADC_CommonInit(ADC_Common_TypeDef *ADCxy_COMMON, LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_ADC_COMMON_INSTANCE(ADCxy_COMMON)); - assert_param(IS_LL_ADC_COMMON_CLOCK(ADC_CommonInitStruct->CommonClock)); - -#if defined(ADC_MULTIMODE_SUPPORT) - assert_param(IS_LL_ADC_MULTI_MODE(ADC_CommonInitStruct->Multimode)); - if(ADC_CommonInitStruct->Multimode != LL_ADC_MULTI_INDEPENDENT) - { - assert_param(IS_LL_ADC_MULTI_DMA_TRANSFER(ADC_CommonInitStruct->MultiDMATransfer)); - assert_param(IS_LL_ADC_MULTI_TWOSMP_DELAY(ADC_CommonInitStruct->MultiTwoSamplingDelay)); - } -#endif /* ADC_MULTIMODE_SUPPORT */ - - /* Note: Hardware constraint (refer to description of functions */ - /* "LL_ADC_SetCommonXXX()" and "LL_ADC_SetMultiXXX()"): */ - /* On this STM32 series, setting of these features is conditioned to */ - /* ADC state: */ - /* All ADC instances of the ADC common group must be disabled. */ - if(__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(ADCxy_COMMON) == 0UL) - { - /* Configuration of ADC hierarchical scope: */ - /* - common to several ADC */ - /* (all ADC instances belonging to the same ADC common instance) */ - /* - Set ADC clock (conversion clock) */ - /* - multimode (if several ADC instances available on the */ - /* selected device) */ - /* - Set ADC multimode configuration */ - /* - Set ADC multimode DMA transfer */ - /* - Set ADC multimode: delay between 2 sampling phases */ -#if defined(ADC_MULTIMODE_SUPPORT) - if(ADC_CommonInitStruct->Multimode != LL_ADC_MULTI_INDEPENDENT) - { - MODIFY_REG(ADCxy_COMMON->CCR, - ADC_CCR_ADCPRE - | ADC_CCR_MULTI - | ADC_CCR_DMA - | ADC_CCR_DDS - | ADC_CCR_DELAY - , - ADC_CommonInitStruct->CommonClock - | ADC_CommonInitStruct->Multimode - | ADC_CommonInitStruct->MultiDMATransfer - | ADC_CommonInitStruct->MultiTwoSamplingDelay - ); - } - else - { - MODIFY_REG(ADCxy_COMMON->CCR, - ADC_CCR_ADCPRE - | ADC_CCR_MULTI - | ADC_CCR_DMA - | ADC_CCR_DDS - | ADC_CCR_DELAY - , - ADC_CommonInitStruct->CommonClock - | LL_ADC_MULTI_INDEPENDENT - ); - } -#else - LL_ADC_SetCommonClock(ADCxy_COMMON, ADC_CommonInitStruct->CommonClock); -#endif - } - else - { - /* Initialization error: One or several ADC instances belonging to */ - /* the same ADC common instance are not disabled. */ - status = ERROR; - } - - return status; -} - -/** - * @brief Set each @ref LL_ADC_CommonInitTypeDef field to default value. - * @param ADC_CommonInitStruct Pointer to a @ref LL_ADC_CommonInitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_ADC_CommonStructInit(LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct) -{ - /* Set ADC_CommonInitStruct fields to default values */ - /* Set fields of ADC common */ - /* (all ADC instances belonging to the same ADC common instance) */ - ADC_CommonInitStruct->CommonClock = LL_ADC_CLOCK_SYNC_PCLK_DIV2; - -#if defined(ADC_MULTIMODE_SUPPORT) - /* Set fields of ADC multimode */ - ADC_CommonInitStruct->Multimode = LL_ADC_MULTI_INDEPENDENT; - ADC_CommonInitStruct->MultiDMATransfer = LL_ADC_MULTI_REG_DMA_EACH_ADC; - ADC_CommonInitStruct->MultiTwoSamplingDelay = LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES; -#endif /* ADC_MULTIMODE_SUPPORT */ -} - -/** - * @brief De-initialize registers of the selected ADC instance - * to their default reset values. - * @note To reset all ADC instances quickly (perform a hard reset), - * use function @ref LL_ADC_CommonDeInit(). - * @param ADCx ADC instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: ADC registers are de-initialized - * - ERROR: ADC registers are not de-initialized - */ -ErrorStatus LL_ADC_DeInit(ADC_TypeDef *ADCx) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(ADCx)); - - /* Disable ADC instance if not already disabled. */ - if(LL_ADC_IsEnabled(ADCx) == 1UL) - { - /* Set ADC group regular trigger source to SW start to ensure to not */ - /* have an external trigger event occurring during the conversion stop */ - /* ADC disable process. */ - LL_ADC_REG_SetTriggerSource(ADCx, LL_ADC_REG_TRIG_SOFTWARE); - - /* Set ADC group injected trigger source to SW start to ensure to not */ - /* have an external trigger event occurring during the conversion stop */ - /* ADC disable process. */ - LL_ADC_INJ_SetTriggerSource(ADCx, LL_ADC_INJ_TRIG_SOFTWARE); - - /* Disable the ADC instance */ - LL_ADC_Disable(ADCx); - } - - /* Check whether ADC state is compliant with expected state */ - /* (hardware requirements of bits state to reset registers below) */ - if(READ_BIT(ADCx->CR2, ADC_CR2_ADON) == 0UL) - { - /* ========== Reset ADC registers ========== */ - /* Reset register SR */ - CLEAR_BIT(ADCx->SR, - ( LL_ADC_FLAG_STRT - | LL_ADC_FLAG_JSTRT - | LL_ADC_FLAG_EOCS - | LL_ADC_FLAG_OVR - | LL_ADC_FLAG_JEOS - | LL_ADC_FLAG_AWD1 ) - ); - - /* Reset register CR1 */ - CLEAR_BIT(ADCx->CR1, - ( ADC_CR1_OVRIE | ADC_CR1_RES | ADC_CR1_AWDEN - | ADC_CR1_JAWDEN - | ADC_CR1_DISCNUM | ADC_CR1_JDISCEN | ADC_CR1_DISCEN - | ADC_CR1_JAUTO | ADC_CR1_AWDSGL | ADC_CR1_SCAN - | ADC_CR1_JEOCIE | ADC_CR1_AWDIE | ADC_CR1_EOCIE - | ADC_CR1_AWDCH ) - ); - - /* Reset register CR2 */ - CLEAR_BIT(ADCx->CR2, - ( ADC_CR2_SWSTART | ADC_CR2_EXTEN | ADC_CR2_EXTSEL - | ADC_CR2_JSWSTART | ADC_CR2_JEXTEN | ADC_CR2_JEXTSEL - | ADC_CR2_ALIGN | ADC_CR2_EOCS - | ADC_CR2_DDS | ADC_CR2_DMA - | ADC_CR2_CONT | ADC_CR2_ADON ) - ); - - /* Reset register SMPR1 */ - CLEAR_BIT(ADCx->SMPR1, - ( ADC_SMPR1_SMP18 | ADC_SMPR1_SMP17 | ADC_SMPR1_SMP16 - | ADC_SMPR1_SMP15 | ADC_SMPR1_SMP14 | ADC_SMPR1_SMP13 - | ADC_SMPR1_SMP12 | ADC_SMPR1_SMP11 | ADC_SMPR1_SMP10) - ); - - /* Reset register SMPR2 */ - CLEAR_BIT(ADCx->SMPR2, - ( ADC_SMPR2_SMP9 - | ADC_SMPR2_SMP8 | ADC_SMPR2_SMP7 | ADC_SMPR2_SMP6 - | ADC_SMPR2_SMP5 | ADC_SMPR2_SMP4 | ADC_SMPR2_SMP3 - | ADC_SMPR2_SMP2 | ADC_SMPR2_SMP1 | ADC_SMPR2_SMP0) - ); - - /* Reset register JOFR1 */ - CLEAR_BIT(ADCx->JOFR1, ADC_JOFR1_JOFFSET1); - /* Reset register JOFR2 */ - CLEAR_BIT(ADCx->JOFR2, ADC_JOFR2_JOFFSET2); - /* Reset register JOFR3 */ - CLEAR_BIT(ADCx->JOFR3, ADC_JOFR3_JOFFSET3); - /* Reset register JOFR4 */ - CLEAR_BIT(ADCx->JOFR4, ADC_JOFR4_JOFFSET4); - - /* Reset register HTR */ - SET_BIT(ADCx->HTR, ADC_HTR_HT); - /* Reset register LTR */ - CLEAR_BIT(ADCx->LTR, ADC_LTR_LT); - - /* Reset register SQR1 */ - CLEAR_BIT(ADCx->SQR1, - ( ADC_SQR1_L - | ADC_SQR1_SQ16 - | ADC_SQR1_SQ15 | ADC_SQR1_SQ14 | ADC_SQR1_SQ13) - ); - - /* Reset register SQR2 */ - CLEAR_BIT(ADCx->SQR2, - ( ADC_SQR2_SQ12 | ADC_SQR2_SQ11 | ADC_SQR2_SQ10 - | ADC_SQR2_SQ9 | ADC_SQR2_SQ8 | ADC_SQR2_SQ7) - ); - - /* Reset register SQR3 */ - CLEAR_BIT(ADCx->SQR3, - ( ADC_SQR3_SQ6 | ADC_SQR3_SQ5 | ADC_SQR3_SQ4 - | ADC_SQR3_SQ3 | ADC_SQR3_SQ2 | ADC_SQR3_SQ1) - ); - - /* Reset register JSQR */ - CLEAR_BIT(ADCx->JSQR, - ( ADC_JSQR_JL - | ADC_JSQR_JSQ4 | ADC_JSQR_JSQ3 - | ADC_JSQR_JSQ2 | ADC_JSQR_JSQ1 ) - ); - - /* Reset register DR */ - /* bits in access mode read only, no direct reset applicable */ - - /* Reset registers JDR1, JDR2, JDR3, JDR4 */ - /* bits in access mode read only, no direct reset applicable */ - - /* Reset register CCR */ - CLEAR_BIT(ADC->CCR, ADC_CCR_TSVREFE | ADC_CCR_ADCPRE); - } - - return status; -} - -/** - * @brief Initialize some features of ADC instance. - * @note These parameters have an impact on ADC scope: ADC instance. - * Affects both group regular and group injected (availability - * of ADC group injected depends on STM32 families). - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Instance . - * @note The setting of these parameters by function @ref LL_ADC_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - * @note After using this function, some other features must be configured - * using LL unitary functions. - * The minimum configuration remaining to be done is: - * - Set ADC group regular or group injected sequencer: - * map channel on the selected sequencer rank. - * Refer to function @ref LL_ADC_REG_SetSequencerRanks(). - * - Set ADC channel sampling time - * Refer to function LL_ADC_SetChannelSamplingTime(); - * @param ADCx ADC instance - * @param ADC_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: ADC registers are initialized - * - ERROR: ADC registers are not initialized - */ -ErrorStatus LL_ADC_Init(ADC_TypeDef *ADCx, LL_ADC_InitTypeDef *ADC_InitStruct) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(ADCx)); - - assert_param(IS_LL_ADC_RESOLUTION(ADC_InitStruct->Resolution)); - assert_param(IS_LL_ADC_DATA_ALIGN(ADC_InitStruct->DataAlignment)); - assert_param(IS_LL_ADC_SCAN_SELECTION(ADC_InitStruct->SequencersScanMode)); - - /* Note: Hardware constraint (refer to description of this function): */ - /* ADC instance must be disabled. */ - if(LL_ADC_IsEnabled(ADCx) == 0UL) - { - /* Configuration of ADC hierarchical scope: */ - /* - ADC instance */ - /* - Set ADC data resolution */ - /* - Set ADC conversion data alignment */ - MODIFY_REG(ADCx->CR1, - ADC_CR1_RES - | ADC_CR1_SCAN - , - ADC_InitStruct->Resolution - | ADC_InitStruct->SequencersScanMode - ); - - MODIFY_REG(ADCx->CR2, - ADC_CR2_ALIGN - , - ADC_InitStruct->DataAlignment - ); - - } - else - { - /* Initialization error: ADC instance is not disabled. */ - status = ERROR; - } - return status; -} - -/** - * @brief Set each @ref LL_ADC_InitTypeDef field to default value. - * @param ADC_InitStruct Pointer to a @ref LL_ADC_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_ADC_StructInit(LL_ADC_InitTypeDef *ADC_InitStruct) -{ - /* Set ADC_InitStruct fields to default values */ - /* Set fields of ADC instance */ - ADC_InitStruct->Resolution = LL_ADC_RESOLUTION_12B; - ADC_InitStruct->DataAlignment = LL_ADC_DATA_ALIGN_RIGHT; - - /* Enable scan mode to have a generic behavior with ADC of other */ - /* STM32 families, without this setting available: */ - /* ADC group regular sequencer and ADC group injected sequencer depend */ - /* only of their own configuration. */ - ADC_InitStruct->SequencersScanMode = LL_ADC_SEQ_SCAN_ENABLE; - -} - -/** - * @brief Initialize some features of ADC group regular. - * @note These parameters have an impact on ADC scope: ADC group regular. - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Group_Regular - * (functions with prefix "REG"). - * @note The setting of these parameters by function @ref LL_ADC_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - * @note After using this function, other features must be configured - * using LL unitary functions. - * The minimum configuration remaining to be done is: - * - Set ADC group regular or group injected sequencer: - * map channel on the selected sequencer rank. - * Refer to function @ref LL_ADC_REG_SetSequencerRanks(). - * - Set ADC channel sampling time - * Refer to function LL_ADC_SetChannelSamplingTime(); - * @param ADCx ADC instance - * @param ADC_REG_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: ADC registers are initialized - * - ERROR: ADC registers are not initialized - */ -ErrorStatus LL_ADC_REG_Init(ADC_TypeDef *ADCx, LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(ADCx)); - assert_param(IS_LL_ADC_REG_TRIG_SOURCE(ADC_REG_InitStruct->TriggerSource)); - assert_param(IS_LL_ADC_REG_SEQ_SCAN_LENGTH(ADC_REG_InitStruct->SequencerLength)); - if(ADC_REG_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) - { - assert_param(IS_LL_ADC_REG_SEQ_SCAN_DISCONT_MODE(ADC_REG_InitStruct->SequencerDiscont)); - } - assert_param(IS_LL_ADC_REG_CONTINUOUS_MODE(ADC_REG_InitStruct->ContinuousMode)); - assert_param(IS_LL_ADC_REG_DMA_TRANSFER(ADC_REG_InitStruct->DMATransfer)); - - /* ADC group regular continuous mode and discontinuous mode */ - /* can not be enabled simultenaeously */ - assert_param((ADC_REG_InitStruct->ContinuousMode == LL_ADC_REG_CONV_SINGLE) - || (ADC_REG_InitStruct->SequencerDiscont == LL_ADC_REG_SEQ_DISCONT_DISABLE)); - - /* Note: Hardware constraint (refer to description of this function): */ - /* ADC instance must be disabled. */ - if(LL_ADC_IsEnabled(ADCx) == 0UL) - { - /* Configuration of ADC hierarchical scope: */ - /* - ADC group regular */ - /* - Set ADC group regular trigger source */ - /* - Set ADC group regular sequencer length */ - /* - Set ADC group regular sequencer discontinuous mode */ - /* - Set ADC group regular continuous mode */ - /* - Set ADC group regular conversion data transfer: no transfer or */ - /* transfer by DMA, and DMA requests mode */ - /* Note: On this STM32 series, ADC trigger edge is set when starting */ - /* ADC conversion. */ - /* Refer to function @ref LL_ADC_REG_StartConversionExtTrig(). */ - if(ADC_REG_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) - { - MODIFY_REG(ADCx->CR1, - ADC_CR1_DISCEN - | ADC_CR1_DISCNUM - , - ADC_REG_InitStruct->SequencerDiscont - ); - } - else - { - MODIFY_REG(ADCx->CR1, - ADC_CR1_DISCEN - | ADC_CR1_DISCNUM - , - LL_ADC_REG_SEQ_DISCONT_DISABLE - ); - } - - MODIFY_REG(ADCx->CR2, - ADC_CR2_EXTSEL - | ADC_CR2_EXTEN - | ADC_CR2_CONT - | ADC_CR2_DMA - | ADC_CR2_DDS - , - (ADC_REG_InitStruct->TriggerSource & ADC_CR2_EXTSEL) - | ADC_REG_InitStruct->ContinuousMode - | ADC_REG_InitStruct->DMATransfer - ); - - /* Set ADC group regular sequencer length and scan direction */ - /* Note: Hardware constraint (refer to description of this function): */ - /* Note: If ADC instance feature scan mode is disabled */ - /* (refer to ADC instance initialization structure */ - /* parameter @ref SequencersScanMode */ - /* or function @ref LL_ADC_SetSequencersScanMode() ), */ - /* this parameter is discarded. */ - LL_ADC_REG_SetSequencerLength(ADCx, ADC_REG_InitStruct->SequencerLength); - } - else - { - /* Initialization error: ADC instance is not disabled. */ - status = ERROR; - } - return status; -} - -/** - * @brief Set each @ref LL_ADC_REG_InitTypeDef field to default value. - * @param ADC_REG_InitStruct Pointer to a @ref LL_ADC_REG_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_ADC_REG_StructInit(LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct) -{ - /* Set ADC_REG_InitStruct fields to default values */ - /* Set fields of ADC group regular */ - /* Note: On this STM32 series, ADC trigger edge is set when starting */ - /* ADC conversion. */ - /* Refer to function @ref LL_ADC_REG_StartConversionExtTrig(). */ - ADC_REG_InitStruct->TriggerSource = LL_ADC_REG_TRIG_SOFTWARE; - ADC_REG_InitStruct->SequencerLength = LL_ADC_REG_SEQ_SCAN_DISABLE; - ADC_REG_InitStruct->SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE; - ADC_REG_InitStruct->ContinuousMode = LL_ADC_REG_CONV_SINGLE; - ADC_REG_InitStruct->DMATransfer = LL_ADC_REG_DMA_TRANSFER_NONE; -} - -/** - * @brief Initialize some features of ADC group injected. - * @note These parameters have an impact on ADC scope: ADC group injected. - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Group_Regular - * (functions with prefix "INJ"). - * @note The setting of these parameters by function @ref LL_ADC_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - * @note After using this function, other features must be configured - * using LL unitary functions. - * The minimum configuration remaining to be done is: - * - Set ADC group injected sequencer: - * map channel on the selected sequencer rank. - * Refer to function @ref LL_ADC_INJ_SetSequencerRanks(). - * - Set ADC channel sampling time - * Refer to function LL_ADC_SetChannelSamplingTime(); - * @param ADCx ADC instance - * @param ADC_INJ_InitStruct Pointer to a @ref LL_ADC_INJ_InitTypeDef structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: ADC registers are initialized - * - ERROR: ADC registers are not initialized - */ -ErrorStatus LL_ADC_INJ_Init(ADC_TypeDef *ADCx, LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_INSTANCE(ADCx)); - assert_param(IS_LL_ADC_INJ_TRIG_SOURCE(ADC_INJ_InitStruct->TriggerSource)); - assert_param(IS_LL_ADC_INJ_SEQ_SCAN_LENGTH(ADC_INJ_InitStruct->SequencerLength)); - if(ADC_INJ_InitStruct->SequencerLength != LL_ADC_INJ_SEQ_SCAN_DISABLE) - { - assert_param(IS_LL_ADC_INJ_SEQ_SCAN_DISCONT_MODE(ADC_INJ_InitStruct->SequencerDiscont)); - } - assert_param(IS_LL_ADC_INJ_TRIG_AUTO(ADC_INJ_InitStruct->TrigAuto)); - - /* Note: Hardware constraint (refer to description of this function): */ - /* ADC instance must be disabled. */ - if(LL_ADC_IsEnabled(ADCx) == 0UL) - { - /* Configuration of ADC hierarchical scope: */ - /* - ADC group injected */ - /* - Set ADC group injected trigger source */ - /* - Set ADC group injected sequencer length */ - /* - Set ADC group injected sequencer discontinuous mode */ - /* - Set ADC group injected conversion trigger: independent or */ - /* from ADC group regular */ - /* Note: On this STM32 series, ADC trigger edge is set when starting */ - /* ADC conversion. */ - /* Refer to function @ref LL_ADC_INJ_StartConversionExtTrig(). */ - if(ADC_INJ_InitStruct->SequencerLength != LL_ADC_REG_SEQ_SCAN_DISABLE) - { - MODIFY_REG(ADCx->CR1, - ADC_CR1_JDISCEN - | ADC_CR1_JAUTO - , - ADC_INJ_InitStruct->SequencerDiscont - | ADC_INJ_InitStruct->TrigAuto - ); - } - else - { - MODIFY_REG(ADCx->CR1, - ADC_CR1_JDISCEN - | ADC_CR1_JAUTO - , - LL_ADC_REG_SEQ_DISCONT_DISABLE - | ADC_INJ_InitStruct->TrigAuto - ); - } - - MODIFY_REG(ADCx->CR2, - ADC_CR2_JEXTSEL - | ADC_CR2_JEXTEN - , - (ADC_INJ_InitStruct->TriggerSource & ADC_CR2_JEXTSEL) - ); - - /* Note: Hardware constraint (refer to description of this function): */ - /* Note: If ADC instance feature scan mode is disabled */ - /* (refer to ADC instance initialization structure */ - /* parameter @ref SequencersScanMode */ - /* or function @ref LL_ADC_SetSequencersScanMode() ), */ - /* this parameter is discarded. */ - LL_ADC_INJ_SetSequencerLength(ADCx, ADC_INJ_InitStruct->SequencerLength); - } - else - { - /* Initialization error: ADC instance is not disabled. */ - status = ERROR; - } - return status; -} - -/** - * @brief Set each @ref LL_ADC_INJ_InitTypeDef field to default value. - * @param ADC_INJ_InitStruct Pointer to a @ref LL_ADC_INJ_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_ADC_INJ_StructInit(LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct) -{ - /* Set ADC_INJ_InitStruct fields to default values */ - /* Set fields of ADC group injected */ - ADC_INJ_InitStruct->TriggerSource = LL_ADC_INJ_TRIG_SOFTWARE; - ADC_INJ_InitStruct->SequencerLength = LL_ADC_INJ_SEQ_SCAN_DISABLE; - ADC_INJ_InitStruct->SequencerDiscont = LL_ADC_INJ_SEQ_DISCONT_DISABLE; - ADC_INJ_InitStruct->TrigAuto = LL_ADC_INJ_TRIG_INDEPENDENT; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* ADC1 || ADC2 || ADC3 */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_crc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_crc.c deleted file mode 100644 index 372e2f2723d74ca..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_crc.c +++ /dev/null @@ -1,107 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_crc.c - * @author MCD Application Team - * @brief CRC LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_crc.h" -#include "stm32f4xx_ll_bus.h" - -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif/* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (CRC) - -/** @addtogroup CRC_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CRC_LL_Exported_Functions - * @{ - */ - -/** @addtogroup CRC_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize CRC registers (Registers restored to their default values). - * @param CRCx CRC Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: CRC registers are de-initialized - * - ERROR: CRC registers are not de-initialized - */ -ErrorStatus LL_CRC_DeInit(CRC_TypeDef *CRCx) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_CRC_ALL_INSTANCE(CRCx)); - - if (CRCx == CRC) - { - /* Force CRC reset */ - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_CRC); - - /* Release CRC reset */ - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_CRC); - } - else - { - status = ERROR; - } - - return (status); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (CRC) */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dac.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dac.c deleted file mode 100644 index 1316504b4fc4e11..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dac.c +++ /dev/null @@ -1,282 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dac.c - * @author MCD Application Team - * @brief DAC LL module driver - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_dac.h" -#include "stm32f4xx_ll_bus.h" - -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(DAC) - -/** @addtogroup DAC_LL DAC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/** @addtogroup DAC_LL_Private_Macros - * @{ - */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define IS_LL_DAC_CHANNEL(__DACX__, __DAC_CHANNEL__) \ - ( \ - ((__DAC_CHANNEL__) == LL_DAC_CHANNEL_1) \ - || ((__DAC_CHANNEL__) == LL_DAC_CHANNEL_2) \ - ) -#else -#define IS_LL_DAC_CHANNEL(__DACX__, __DAC_CHANNEL__) \ - ( \ - ((__DAC_CHANNEL__) == LL_DAC_CHANNEL_1) \ - ) -#endif /* DAC_CHANNEL2_SUPPORT */ - -#define IS_LL_DAC_TRIGGER_SOURCE(__TRIGGER_SOURCE__) \ - ( ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_SOFTWARE) \ - || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM2_TRGO) \ - || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM4_TRGO) \ - || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM5_TRGO) \ - || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM6_TRGO) \ - || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM7_TRGO) \ - || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_TIM8_TRGO) \ - || ((__TRIGGER_SOURCE__) == LL_DAC_TRIG_EXT_EXTI_LINE9) \ - ) - -#define IS_LL_DAC_WAVE_AUTO_GENER_MODE(__WAVE_AUTO_GENERATION_MODE__) \ - ( ((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_NONE) \ - || ((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_NOISE) \ - || ((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE) \ - ) - -#define IS_LL_DAC_WAVE_AUTO_GENER_CONFIG(__WAVE_AUTO_GENERATION_MODE__, __WAVE_AUTO_GENERATION_CONFIG__) \ - ( (((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_NOISE) \ - && ( ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BIT0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS1_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS2_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS3_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS4_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS5_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS6_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS7_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS8_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS9_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS10_0) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_NOISE_LFSR_UNMASK_BITS11_0)) \ - ) \ - ||(((__WAVE_AUTO_GENERATION_MODE__) == LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE) \ - && ( ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_1) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_3) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_7) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_15) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_31) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_63) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_127) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_255) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_511) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_1023) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_2047) \ - || ((__WAVE_AUTO_GENERATION_CONFIG__) == LL_DAC_TRIANGLE_AMPLITUDE_4095)) \ - ) \ - ) - -#define IS_LL_DAC_OUTPUT_BUFFER(__OUTPUT_BUFFER__) \ - ( ((__OUTPUT_BUFFER__) == LL_DAC_OUTPUT_BUFFER_ENABLE) \ - || ((__OUTPUT_BUFFER__) == LL_DAC_OUTPUT_BUFFER_DISABLE) \ - ) - -/** - * @} - */ - - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DAC_LL_Exported_Functions - * @{ - */ - -/** @addtogroup DAC_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize registers of the selected DAC instance - * to their default reset values. - * @param DACx DAC instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: DAC registers are de-initialized - * - ERROR: not applicable - */ -ErrorStatus LL_DAC_DeInit(DAC_TypeDef *DACx) -{ - /* Check the parameters */ - assert_param(IS_DAC_ALL_INSTANCE(DACx)); - - /* Force reset of DAC clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_DAC1); - - /* Release reset of DAC clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_DAC1); - - return SUCCESS; -} - -/** - * @brief Initialize some features of DAC channel. - * @note @ref LL_DAC_Init() aims to ease basic configuration of a DAC channel. - * Leaving it ready to be enabled and output: - * a level by calling one of - * @ref LL_DAC_ConvertData12RightAligned - * @ref LL_DAC_ConvertData12LeftAligned - * @ref LL_DAC_ConvertData8RightAligned - * or one of the supported autogenerated wave. - * @note This function allows configuration of: - * - Output mode - * - Trigger - * - Wave generation - * @note The setting of these parameters by function @ref LL_DAC_Init() - * is conditioned to DAC state: - * DAC channel must be disabled. - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param DAC_InitStruct Pointer to a @ref LL_DAC_InitTypeDef structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: DAC registers are initialized - * - ERROR: DAC registers are not initialized - */ -ErrorStatus LL_DAC_Init(DAC_TypeDef *DACx, uint32_t DAC_Channel, LL_DAC_InitTypeDef *DAC_InitStruct) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_DAC_ALL_INSTANCE(DACx)); - assert_param(IS_LL_DAC_CHANNEL(DACx, DAC_Channel)); - assert_param(IS_LL_DAC_TRIGGER_SOURCE(DAC_InitStruct->TriggerSource)); - assert_param(IS_LL_DAC_OUTPUT_BUFFER(DAC_InitStruct->OutputBuffer)); - assert_param(IS_LL_DAC_WAVE_AUTO_GENER_MODE(DAC_InitStruct->WaveAutoGeneration)); - if (DAC_InitStruct->WaveAutoGeneration != LL_DAC_WAVE_AUTO_GENERATION_NONE) - { - assert_param(IS_LL_DAC_WAVE_AUTO_GENER_CONFIG(DAC_InitStruct->WaveAutoGeneration, - DAC_InitStruct->WaveAutoGenerationConfig)); - } - - /* Note: Hardware constraint (refer to description of this function) */ - /* DAC instance must be disabled. */ - if (LL_DAC_IsEnabled(DACx, DAC_Channel) == 0UL) - { - /* Configuration of DAC channel: */ - /* - TriggerSource */ - /* - WaveAutoGeneration */ - /* - OutputBuffer */ - /* - OutputMode */ - if (DAC_InitStruct->WaveAutoGeneration != LL_DAC_WAVE_AUTO_GENERATION_NONE) - { - MODIFY_REG(DACx->CR, - (DAC_CR_TSEL1 - | DAC_CR_WAVE1 - | DAC_CR_MAMP1 - | DAC_CR_BOFF1 - ) << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - , - (DAC_InitStruct->TriggerSource - | DAC_InitStruct->WaveAutoGeneration - | DAC_InitStruct->WaveAutoGenerationConfig - | DAC_InitStruct->OutputBuffer - ) << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); - } - else - { - MODIFY_REG(DACx->CR, - (DAC_CR_TSEL1 - | DAC_CR_WAVE1 - | DAC_CR_BOFF1 - ) << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - , - (DAC_InitStruct->TriggerSource - | LL_DAC_WAVE_AUTO_GENERATION_NONE - | DAC_InitStruct->OutputBuffer - ) << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); - } - } - else - { - /* Initialization error: DAC instance is not disabled. */ - status = ERROR; - } - return status; -} - -/** - * @brief Set each @ref LL_DAC_InitTypeDef field to default value. - * @param DAC_InitStruct pointer to a @ref LL_DAC_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_DAC_StructInit(LL_DAC_InitTypeDef *DAC_InitStruct) -{ - /* Set DAC_InitStruct fields to default values */ - DAC_InitStruct->TriggerSource = LL_DAC_TRIG_SOFTWARE; - DAC_InitStruct->WaveAutoGeneration = LL_DAC_WAVE_AUTO_GENERATION_NONE; - /* Note: Parameter discarded if wave auto generation is disabled, */ - /* set anyway to its default value. */ - DAC_InitStruct->WaveAutoGenerationConfig = LL_DAC_NOISE_LFSR_UNMASK_BIT0; - DAC_InitStruct->OutputBuffer = LL_DAC_OUTPUT_BUFFER_ENABLE; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma.c deleted file mode 100644 index e4cbae4c98b0a4c..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma.c +++ /dev/null @@ -1,425 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dma.c - * @author MCD Application Team - * @brief DMA LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_dma.h" -#include "stm32f4xx_ll_bus.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (DMA1) || defined (DMA2) - -/** @defgroup DMA_LL DMA - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup DMA_LL_Private_Macros - * @{ - */ -#define IS_LL_DMA_DIRECTION(__VALUE__) (((__VALUE__) == LL_DMA_DIRECTION_PERIPH_TO_MEMORY) || \ - ((__VALUE__) == LL_DMA_DIRECTION_MEMORY_TO_PERIPH) || \ - ((__VALUE__) == LL_DMA_DIRECTION_MEMORY_TO_MEMORY)) - -#define IS_LL_DMA_MODE(__VALUE__) (((__VALUE__) == LL_DMA_MODE_NORMAL) || \ - ((__VALUE__) == LL_DMA_MODE_CIRCULAR) || \ - ((__VALUE__) == LL_DMA_MODE_PFCTRL)) - -#define IS_LL_DMA_PERIPHINCMODE(__VALUE__) (((__VALUE__) == LL_DMA_PERIPH_INCREMENT) || \ - ((__VALUE__) == LL_DMA_PERIPH_NOINCREMENT)) - -#define IS_LL_DMA_MEMORYINCMODE(__VALUE__) (((__VALUE__) == LL_DMA_MEMORY_INCREMENT) || \ - ((__VALUE__) == LL_DMA_MEMORY_NOINCREMENT)) - -#define IS_LL_DMA_PERIPHDATASIZE(__VALUE__) (((__VALUE__) == LL_DMA_PDATAALIGN_BYTE) || \ - ((__VALUE__) == LL_DMA_PDATAALIGN_HALFWORD) || \ - ((__VALUE__) == LL_DMA_PDATAALIGN_WORD)) - -#define IS_LL_DMA_MEMORYDATASIZE(__VALUE__) (((__VALUE__) == LL_DMA_MDATAALIGN_BYTE) || \ - ((__VALUE__) == LL_DMA_MDATAALIGN_HALFWORD) || \ - ((__VALUE__) == LL_DMA_MDATAALIGN_WORD)) - -#define IS_LL_DMA_NBDATA(__VALUE__) ((__VALUE__) <= 0x0000FFFFU) - -#define IS_LL_DMA_CHANNEL(__VALUE__) (((__VALUE__) == LL_DMA_CHANNEL_0) || \ - ((__VALUE__) == LL_DMA_CHANNEL_1) || \ - ((__VALUE__) == LL_DMA_CHANNEL_2) || \ - ((__VALUE__) == LL_DMA_CHANNEL_3) || \ - ((__VALUE__) == LL_DMA_CHANNEL_4) || \ - ((__VALUE__) == LL_DMA_CHANNEL_5) || \ - ((__VALUE__) == LL_DMA_CHANNEL_6) || \ - ((__VALUE__) == LL_DMA_CHANNEL_7)) - -#define IS_LL_DMA_PRIORITY(__VALUE__) (((__VALUE__) == LL_DMA_PRIORITY_LOW) || \ - ((__VALUE__) == LL_DMA_PRIORITY_MEDIUM) || \ - ((__VALUE__) == LL_DMA_PRIORITY_HIGH) || \ - ((__VALUE__) == LL_DMA_PRIORITY_VERYHIGH)) - -#define IS_LL_DMA_ALL_STREAM_INSTANCE(INSTANCE, STREAM) ((((INSTANCE) == DMA1) && \ - (((STREAM) == LL_DMA_STREAM_0) || \ - ((STREAM) == LL_DMA_STREAM_1) || \ - ((STREAM) == LL_DMA_STREAM_2) || \ - ((STREAM) == LL_DMA_STREAM_3) || \ - ((STREAM) == LL_DMA_STREAM_4) || \ - ((STREAM) == LL_DMA_STREAM_5) || \ - ((STREAM) == LL_DMA_STREAM_6) || \ - ((STREAM) == LL_DMA_STREAM_7) || \ - ((STREAM) == LL_DMA_STREAM_ALL))) ||\ - (((INSTANCE) == DMA2) && \ - (((STREAM) == LL_DMA_STREAM_0) || \ - ((STREAM) == LL_DMA_STREAM_1) || \ - ((STREAM) == LL_DMA_STREAM_2) || \ - ((STREAM) == LL_DMA_STREAM_3) || \ - ((STREAM) == LL_DMA_STREAM_4) || \ - ((STREAM) == LL_DMA_STREAM_5) || \ - ((STREAM) == LL_DMA_STREAM_6) || \ - ((STREAM) == LL_DMA_STREAM_7) || \ - ((STREAM) == LL_DMA_STREAM_ALL)))) - -#define IS_LL_DMA_FIFO_MODE_STATE(STATE) (((STATE) == LL_DMA_FIFOMODE_DISABLE ) || \ - ((STATE) == LL_DMA_FIFOMODE_ENABLE)) - -#define IS_LL_DMA_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == LL_DMA_FIFOTHRESHOLD_1_4) || \ - ((THRESHOLD) == LL_DMA_FIFOTHRESHOLD_1_2) || \ - ((THRESHOLD) == LL_DMA_FIFOTHRESHOLD_3_4) || \ - ((THRESHOLD) == LL_DMA_FIFOTHRESHOLD_FULL)) - -#define IS_LL_DMA_MEMORY_BURST(BURST) (((BURST) == LL_DMA_MBURST_SINGLE) || \ - ((BURST) == LL_DMA_MBURST_INC4) || \ - ((BURST) == LL_DMA_MBURST_INC8) || \ - ((BURST) == LL_DMA_MBURST_INC16)) - -#define IS_LL_DMA_PERIPHERAL_BURST(BURST) (((BURST) == LL_DMA_PBURST_SINGLE) || \ - ((BURST) == LL_DMA_PBURST_INC4) || \ - ((BURST) == LL_DMA_PBURST_INC8) || \ - ((BURST) == LL_DMA_PBURST_INC16)) - -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DMA_LL_Exported_Functions - * @{ - */ - -/** @addtogroup DMA_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize the DMA registers to their default reset values. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @arg @ref LL_DMA_STREAM_ALL - * @retval An ErrorStatus enumeration value: - * - SUCCESS: DMA registers are de-initialized - * - ERROR: DMA registers are not de-initialized - */ -uint32_t LL_DMA_DeInit(DMA_TypeDef *DMAx, uint32_t Stream) -{ - DMA_Stream_TypeDef *tmp = (DMA_Stream_TypeDef *)DMA1_Stream0; - ErrorStatus status = SUCCESS; - - /* Check the DMA Instance DMAx and Stream parameters*/ - assert_param(IS_LL_DMA_ALL_STREAM_INSTANCE(DMAx, Stream)); - - if (Stream == LL_DMA_STREAM_ALL) - { - if (DMAx == DMA1) - { - /* Force reset of DMA clock */ - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_DMA1); - - /* Release reset of DMA clock */ - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_DMA1); - } - else if (DMAx == DMA2) - { - /* Force reset of DMA clock */ - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_DMA2); - - /* Release reset of DMA clock */ - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_DMA2); - } - else - { - status = ERROR; - } - } - else - { - /* Disable the selected Stream */ - LL_DMA_DisableStream(DMAx,Stream); - - /* Get the DMA Stream Instance */ - tmp = (DMA_Stream_TypeDef *)(__LL_DMA_GET_STREAM_INSTANCE(DMAx, Stream)); - - /* Reset DMAx_Streamy configuration register */ - LL_DMA_WriteReg(tmp, CR, 0U); - - /* Reset DMAx_Streamy remaining bytes register */ - LL_DMA_WriteReg(tmp, NDTR, 0U); - - /* Reset DMAx_Streamy peripheral address register */ - LL_DMA_WriteReg(tmp, PAR, 0U); - - /* Reset DMAx_Streamy memory address register */ - LL_DMA_WriteReg(tmp, M0AR, 0U); - - /* Reset DMAx_Streamy memory address register */ - LL_DMA_WriteReg(tmp, M1AR, 0U); - - /* Reset DMAx_Streamy FIFO control register */ - LL_DMA_WriteReg(tmp, FCR, 0x00000021U); - - /* Reset Channel register field for DMAx Stream*/ - LL_DMA_SetChannelSelection(DMAx, Stream, LL_DMA_CHANNEL_0); - - if(Stream == LL_DMA_STREAM_0) - { - /* Reset the Stream0 pending flags */ - DMAx->LIFCR = 0x0000003FU; - } - else if(Stream == LL_DMA_STREAM_1) - { - /* Reset the Stream1 pending flags */ - DMAx->LIFCR = 0x00000F40U; - } - else if(Stream == LL_DMA_STREAM_2) - { - /* Reset the Stream2 pending flags */ - DMAx->LIFCR = 0x003F0000U; - } - else if(Stream == LL_DMA_STREAM_3) - { - /* Reset the Stream3 pending flags */ - DMAx->LIFCR = 0x0F400000U; - } - else if(Stream == LL_DMA_STREAM_4) - { - /* Reset the Stream4 pending flags */ - DMAx->HIFCR = 0x0000003FU; - } - else if(Stream == LL_DMA_STREAM_5) - { - /* Reset the Stream5 pending flags */ - DMAx->HIFCR = 0x00000F40U; - } - else if(Stream == LL_DMA_STREAM_6) - { - /* Reset the Stream6 pending flags */ - DMAx->HIFCR = 0x003F0000U; - } - else if(Stream == LL_DMA_STREAM_7) - { - /* Reset the Stream7 pending flags */ - DMAx->HIFCR = 0x0F400000U; - } - else - { - status = ERROR; - } - } - - return status; -} - -/** - * @brief Initialize the DMA registers according to the specified parameters in DMA_InitStruct. - * @note To convert DMAx_Streamy Instance to DMAx Instance and Streamy, use helper macros : - * @arg @ref __LL_DMA_GET_INSTANCE - * @arg @ref __LL_DMA_GET_STREAM - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param DMA_InitStruct pointer to a @ref LL_DMA_InitTypeDef structure. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: DMA registers are initialized - * - ERROR: Not applicable - */ -uint32_t LL_DMA_Init(DMA_TypeDef *DMAx, uint32_t Stream, LL_DMA_InitTypeDef *DMA_InitStruct) -{ - /* Check the DMA Instance DMAx and Stream parameters*/ - assert_param(IS_LL_DMA_ALL_STREAM_INSTANCE(DMAx, Stream)); - - /* Check the DMA parameters from DMA_InitStruct */ - assert_param(IS_LL_DMA_DIRECTION(DMA_InitStruct->Direction)); - assert_param(IS_LL_DMA_MODE(DMA_InitStruct->Mode)); - assert_param(IS_LL_DMA_PERIPHINCMODE(DMA_InitStruct->PeriphOrM2MSrcIncMode)); - assert_param(IS_LL_DMA_MEMORYINCMODE(DMA_InitStruct->MemoryOrM2MDstIncMode)); - assert_param(IS_LL_DMA_PERIPHDATASIZE(DMA_InitStruct->PeriphOrM2MSrcDataSize)); - assert_param(IS_LL_DMA_MEMORYDATASIZE(DMA_InitStruct->MemoryOrM2MDstDataSize)); - assert_param(IS_LL_DMA_NBDATA(DMA_InitStruct->NbData)); - assert_param(IS_LL_DMA_CHANNEL(DMA_InitStruct->Channel)); - assert_param(IS_LL_DMA_PRIORITY(DMA_InitStruct->Priority)); - assert_param(IS_LL_DMA_FIFO_MODE_STATE(DMA_InitStruct->FIFOMode)); - /* Check the memory burst, peripheral burst and FIFO threshold parameters only - when FIFO mode is enabled */ - if(DMA_InitStruct->FIFOMode != LL_DMA_FIFOMODE_DISABLE) - { - assert_param(IS_LL_DMA_FIFO_THRESHOLD(DMA_InitStruct->FIFOThreshold)); - assert_param(IS_LL_DMA_MEMORY_BURST(DMA_InitStruct->MemBurst)); - assert_param(IS_LL_DMA_PERIPHERAL_BURST(DMA_InitStruct->PeriphBurst)); - } - - /*---------------------------- DMAx SxCR Configuration ------------------------ - * Configure DMAx_Streamy: data transfer direction, data transfer mode, - * peripheral and memory increment mode, - * data size alignment and priority level with parameters : - * - Direction: DMA_SxCR_DIR[1:0] bits - * - Mode: DMA_SxCR_CIRC bit - * - PeriphOrM2MSrcIncMode: DMA_SxCR_PINC bit - * - MemoryOrM2MDstIncMode: DMA_SxCR_MINC bit - * - PeriphOrM2MSrcDataSize: DMA_SxCR_PSIZE[1:0] bits - * - MemoryOrM2MDstDataSize: DMA_SxCR_MSIZE[1:0] bits - * - Priority: DMA_SxCR_PL[1:0] bits - */ - LL_DMA_ConfigTransfer(DMAx, Stream, DMA_InitStruct->Direction | \ - DMA_InitStruct->Mode | \ - DMA_InitStruct->PeriphOrM2MSrcIncMode | \ - DMA_InitStruct->MemoryOrM2MDstIncMode | \ - DMA_InitStruct->PeriphOrM2MSrcDataSize | \ - DMA_InitStruct->MemoryOrM2MDstDataSize | \ - DMA_InitStruct->Priority - ); - - if(DMA_InitStruct->FIFOMode != LL_DMA_FIFOMODE_DISABLE) - { - /*---------------------------- DMAx SxFCR Configuration ------------------------ - * Configure DMAx_Streamy: fifo mode and fifo threshold with parameters : - * - FIFOMode: DMA_SxFCR_DMDIS bit - * - FIFOThreshold: DMA_SxFCR_FTH[1:0] bits - */ - LL_DMA_ConfigFifo(DMAx, Stream, DMA_InitStruct->FIFOMode, DMA_InitStruct->FIFOThreshold); - - /*---------------------------- DMAx SxCR Configuration -------------------------- - * Configure DMAx_Streamy: memory burst transfer with parameters : - * - MemBurst: DMA_SxCR_MBURST[1:0] bits - */ - LL_DMA_SetMemoryBurstxfer(DMAx,Stream,DMA_InitStruct->MemBurst); - - /*---------------------------- DMAx SxCR Configuration -------------------------- - * Configure DMAx_Streamy: peripheral burst transfer with parameters : - * - PeriphBurst: DMA_SxCR_PBURST[1:0] bits - */ - LL_DMA_SetPeriphBurstxfer(DMAx,Stream,DMA_InitStruct->PeriphBurst); - } - - /*-------------------------- DMAx SxM0AR Configuration -------------------------- - * Configure the memory or destination base address with parameter : - * - MemoryOrM2MDstAddress: DMA_SxM0AR_M0A[31:0] bits - */ - LL_DMA_SetMemoryAddress(DMAx, Stream, DMA_InitStruct->MemoryOrM2MDstAddress); - - /*-------------------------- DMAx SxPAR Configuration --------------------------- - * Configure the peripheral or source base address with parameter : - * - PeriphOrM2MSrcAddress: DMA_SxPAR_PA[31:0] bits - */ - LL_DMA_SetPeriphAddress(DMAx, Stream, DMA_InitStruct->PeriphOrM2MSrcAddress); - - /*--------------------------- DMAx SxNDTR Configuration ------------------------- - * Configure the peripheral base address with parameter : - * - NbData: DMA_SxNDT[15:0] bits - */ - LL_DMA_SetDataLength(DMAx, Stream, DMA_InitStruct->NbData); - - /*--------------------------- DMA SxCR_CHSEL Configuration ---------------------- - * Configure the peripheral base address with parameter : - * - PeriphRequest: DMA_SxCR_CHSEL[2:0] bits - */ - LL_DMA_SetChannelSelection(DMAx, Stream, DMA_InitStruct->Channel); - - return SUCCESS; -} - -/** - * @brief Set each @ref LL_DMA_InitTypeDef field to default value. - * @param DMA_InitStruct Pointer to a @ref LL_DMA_InitTypeDef structure. - * @retval None - */ -void LL_DMA_StructInit(LL_DMA_InitTypeDef *DMA_InitStruct) -{ - /* Set DMA_InitStruct fields to default values */ - DMA_InitStruct->PeriphOrM2MSrcAddress = 0x00000000U; - DMA_InitStruct->MemoryOrM2MDstAddress = 0x00000000U; - DMA_InitStruct->Direction = LL_DMA_DIRECTION_PERIPH_TO_MEMORY; - DMA_InitStruct->Mode = LL_DMA_MODE_NORMAL; - DMA_InitStruct->PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT; - DMA_InitStruct->MemoryOrM2MDstIncMode = LL_DMA_MEMORY_NOINCREMENT; - DMA_InitStruct->PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_BYTE; - DMA_InitStruct->MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_BYTE; - DMA_InitStruct->NbData = 0x00000000U; - DMA_InitStruct->Channel = LL_DMA_CHANNEL_0; - DMA_InitStruct->Priority = LL_DMA_PRIORITY_LOW; - DMA_InitStruct->FIFOMode = LL_DMA_FIFOMODE_DISABLE; - DMA_InitStruct->FIFOThreshold = LL_DMA_FIFOTHRESHOLD_1_4; - DMA_InitStruct->MemBurst = LL_DMA_MBURST_SINGLE; - DMA_InitStruct->PeriphBurst = LL_DMA_PBURST_SINGLE; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DMA1 || DMA2 */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma2d.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma2d.c deleted file mode 100644 index 92941c4fb632c54..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_dma2d.c +++ /dev/null @@ -1,598 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dma2d.c - * @author MCD Application Team - * @brief DMA2D LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_dma2d.h" -#include "stm32f4xx_ll_bus.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (DMA2D) - -/** @addtogroup DMA2D_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @addtogroup DMA2D_LL_Private_Constants DMA2D Private Constants - * @{ - */ -#define LL_DMA2D_COLOR 0xFFU /*!< Maximum output color setting */ -#define LL_DMA2D_NUMBEROFLINES DMA2D_NLR_NL /*!< Maximum number of lines */ -#define LL_DMA2D_NUMBEROFPIXELS (DMA2D_NLR_PL >> DMA2D_NLR_PL_Pos) /*!< Maximum number of pixels per lines */ -#define LL_DMA2D_OFFSET_MAX 0x3FFFU /*!< Maximum output line offset expressed in pixels */ -#define LL_DMA2D_CLUTSIZE_MAX 0xFFU /*!< Maximum CLUT size */ -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup DMA2D_LL_Private_Macros - * @{ - */ -#define IS_LL_DMA2D_MODE(MODE) (((MODE) == LL_DMA2D_MODE_M2M) || \ - ((MODE) == LL_DMA2D_MODE_M2M_PFC) || \ - ((MODE) == LL_DMA2D_MODE_M2M_BLEND) || \ - ((MODE) == LL_DMA2D_MODE_R2M)) - -#define IS_LL_DMA2D_OCMODE(MODE_ARGB) (((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_ARGB8888) || \ - ((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_RGB888) || \ - ((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_RGB565) || \ - ((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_ARGB1555) || \ - ((MODE_ARGB) == LL_DMA2D_OUTPUT_MODE_ARGB4444)) - -#define IS_LL_DMA2D_GREEN(GREEN) ((GREEN) <= LL_DMA2D_COLOR) -#define IS_LL_DMA2D_RED(RED) ((RED) <= LL_DMA2D_COLOR) -#define IS_LL_DMA2D_BLUE(BLUE) ((BLUE) <= LL_DMA2D_COLOR) -#define IS_LL_DMA2D_ALPHA(ALPHA) ((ALPHA) <= LL_DMA2D_COLOR) - - -#define IS_LL_DMA2D_OFFSET(OFFSET) ((OFFSET) <= LL_DMA2D_OFFSET_MAX) - -#define IS_LL_DMA2D_LINE(LINES) ((LINES) <= LL_DMA2D_NUMBEROFLINES) -#define IS_LL_DMA2D_PIXEL(PIXELS) ((PIXELS) <= LL_DMA2D_NUMBEROFPIXELS) - - - -#define IS_LL_DMA2D_LCMODE(MODE_ARGB) (((MODE_ARGB) == LL_DMA2D_INPUT_MODE_ARGB8888) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_RGB888) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_RGB565) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_ARGB1555) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_ARGB4444) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_L8) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_AL44) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_AL88) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_L4) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_A8) || \ - ((MODE_ARGB) == LL_DMA2D_INPUT_MODE_A4)) - -#define IS_LL_DMA2D_CLUTCMODE(CLUTCMODE) (((CLUTCMODE) == LL_DMA2D_CLUT_COLOR_MODE_ARGB8888) || \ - ((CLUTCMODE) == LL_DMA2D_CLUT_COLOR_MODE_RGB888)) - -#define IS_LL_DMA2D_CLUTSIZE(SIZE) ((SIZE) <= LL_DMA2D_CLUTSIZE_MAX) - -#define IS_LL_DMA2D_ALPHAMODE(MODE) (((MODE) == LL_DMA2D_ALPHA_MODE_NO_MODIF) || \ - ((MODE) == LL_DMA2D_ALPHA_MODE_REPLACE) || \ - ((MODE) == LL_DMA2D_ALPHA_MODE_COMBINE)) - - -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DMA2D_LL_Exported_Functions - * @{ - */ - -/** @addtogroup DMA2D_LL_EF_Init_Functions Initialization and De-initialization Functions - * @{ - */ - -/** - * @brief De-initialize DMA2D registers (registers restored to their default values). - * @param DMA2Dx DMA2D Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: DMA2D registers are de-initialized - * - ERROR: DMA2D registers are not de-initialized - */ -ErrorStatus LL_DMA2D_DeInit(DMA2D_TypeDef *DMA2Dx) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); - - if (DMA2Dx == DMA2D) - { - /* Force reset of DMA2D clock */ - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_DMA2D); - - /* Release reset of DMA2D clock */ - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_DMA2D); - } - else - { - status = ERROR; - } - - return (status); -} - -/** - * @brief Initialize DMA2D registers according to the specified parameters in DMA2D_InitStruct. - * @note DMA2D transfers must be disabled to set initialization bits in configuration registers, - * otherwise ERROR result is returned. - * @param DMA2Dx DMA2D Instance - * @param DMA2D_InitStruct pointer to a LL_DMA2D_InitTypeDef structure - * that contains the configuration information for the specified DMA2D peripheral. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: DMA2D registers are initialized according to DMA2D_InitStruct content - * - ERROR: Issue occurred during DMA2D registers initialization - */ -ErrorStatus LL_DMA2D_Init(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_InitTypeDef *DMA2D_InitStruct) -{ - ErrorStatus status = ERROR; - LL_DMA2D_ColorTypeDef dma2d_colorstruct; - uint32_t tmp; - uint32_t tmp1; - uint32_t tmp2; - uint32_t regMask; - uint32_t regValue; - - /* Check the parameters */ - assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); - assert_param(IS_LL_DMA2D_MODE(DMA2D_InitStruct->Mode)); - assert_param(IS_LL_DMA2D_OCMODE(DMA2D_InitStruct->ColorMode)); - assert_param(IS_LL_DMA2D_LINE(DMA2D_InitStruct->NbrOfLines)); - assert_param(IS_LL_DMA2D_PIXEL(DMA2D_InitStruct->NbrOfPixelsPerLines)); - assert_param(IS_LL_DMA2D_GREEN(DMA2D_InitStruct->OutputGreen)); - assert_param(IS_LL_DMA2D_RED(DMA2D_InitStruct->OutputRed)); - assert_param(IS_LL_DMA2D_BLUE(DMA2D_InitStruct->OutputBlue)); - assert_param(IS_LL_DMA2D_ALPHA(DMA2D_InitStruct->OutputAlpha)); - assert_param(IS_LL_DMA2D_OFFSET(DMA2D_InitStruct->LineOffset)); - - /* DMA2D transfers must be disabled to configure bits in initialization registers */ - tmp = LL_DMA2D_IsTransferOngoing(DMA2Dx); - tmp1 = LL_DMA2D_FGND_IsEnabledCLUTLoad(DMA2Dx); - tmp2 = LL_DMA2D_BGND_IsEnabledCLUTLoad(DMA2Dx); - if ((tmp == 0U) && (tmp1 == 0U) && (tmp2 == 0U)) - { - /* DMA2D CR register configuration -------------------------------------------*/ - LL_DMA2D_SetMode(DMA2Dx, DMA2D_InitStruct->Mode); - - /* DMA2D OPFCCR register configuration ---------------------------------------*/ - regMask = DMA2D_OPFCCR_CM; - regValue = DMA2D_InitStruct->ColorMode; - - - - - MODIFY_REG(DMA2Dx->OPFCCR, regMask, regValue); - - /* DMA2D OOR register configuration ------------------------------------------*/ - LL_DMA2D_SetLineOffset(DMA2Dx, DMA2D_InitStruct->LineOffset); - - /* DMA2D NLR register configuration ------------------------------------------*/ - LL_DMA2D_ConfigSize(DMA2Dx, DMA2D_InitStruct->NbrOfLines, DMA2D_InitStruct->NbrOfPixelsPerLines); - - /* DMA2D OMAR register configuration ------------------------------------------*/ - LL_DMA2D_SetOutputMemAddr(DMA2Dx, DMA2D_InitStruct->OutputMemoryAddress); - - /* DMA2D OCOLR register configuration ------------------------------------------*/ - dma2d_colorstruct.ColorMode = DMA2D_InitStruct->ColorMode; - dma2d_colorstruct.OutputBlue = DMA2D_InitStruct->OutputBlue; - dma2d_colorstruct.OutputGreen = DMA2D_InitStruct->OutputGreen; - dma2d_colorstruct.OutputRed = DMA2D_InitStruct->OutputRed; - dma2d_colorstruct.OutputAlpha = DMA2D_InitStruct->OutputAlpha; - LL_DMA2D_ConfigOutputColor(DMA2Dx, &dma2d_colorstruct); - - status = SUCCESS; - } - /* If DMA2D transfers are not disabled, return ERROR */ - - return (status); -} - -/** - * @brief Set each @ref LL_DMA2D_InitTypeDef field to default value. - * @param DMA2D_InitStruct pointer to a @ref LL_DMA2D_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_DMA2D_StructInit(LL_DMA2D_InitTypeDef *DMA2D_InitStruct) -{ - /* Set DMA2D_InitStruct fields to default values */ - DMA2D_InitStruct->Mode = LL_DMA2D_MODE_M2M; - DMA2D_InitStruct->ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB8888; - DMA2D_InitStruct->NbrOfLines = 0x0U; - DMA2D_InitStruct->NbrOfPixelsPerLines = 0x0U; - DMA2D_InitStruct->LineOffset = 0x0U; - DMA2D_InitStruct->OutputBlue = 0x0U; - DMA2D_InitStruct->OutputGreen = 0x0U; - DMA2D_InitStruct->OutputRed = 0x0U; - DMA2D_InitStruct->OutputAlpha = 0x0U; - DMA2D_InitStruct->OutputMemoryAddress = 0x0U; -} - -/** - * @brief Configure the foreground or background according to the specified parameters - * in the LL_DMA2D_LayerCfgTypeDef structure. - * @param DMA2Dx DMA2D Instance - * @param DMA2D_LayerCfg pointer to a LL_DMA2D_LayerCfgTypeDef structure that contains - * the configuration information for the specified layer. - * @param LayerIdx DMA2D Layer index. - * This parameter can be one of the following values: - * 0(background) / 1(foreground) - * @retval None - */ -void LL_DMA2D_ConfigLayer(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_LayerCfgTypeDef *DMA2D_LayerCfg, uint32_t LayerIdx) -{ - /* Check the parameters */ - assert_param(IS_LL_DMA2D_OFFSET(DMA2D_LayerCfg->LineOffset)); - assert_param(IS_LL_DMA2D_LCMODE(DMA2D_LayerCfg->ColorMode)); - assert_param(IS_LL_DMA2D_CLUTCMODE(DMA2D_LayerCfg->CLUTColorMode)); - assert_param(IS_LL_DMA2D_CLUTSIZE(DMA2D_LayerCfg->CLUTSize)); - assert_param(IS_LL_DMA2D_ALPHAMODE(DMA2D_LayerCfg->AlphaMode)); - assert_param(IS_LL_DMA2D_GREEN(DMA2D_LayerCfg->Green)); - assert_param(IS_LL_DMA2D_RED(DMA2D_LayerCfg->Red)); - assert_param(IS_LL_DMA2D_BLUE(DMA2D_LayerCfg->Blue)); - assert_param(IS_LL_DMA2D_ALPHA(DMA2D_LayerCfg->Alpha)); - - - if (LayerIdx == 0U) - { - /* Configure the background memory address */ - LL_DMA2D_BGND_SetMemAddr(DMA2Dx, DMA2D_LayerCfg->MemoryAddress); - - /* Configure the background line offset */ - LL_DMA2D_BGND_SetLineOffset(DMA2Dx, DMA2D_LayerCfg->LineOffset); - - /* Configure the background Alpha value, Alpha mode, CLUT size, CLUT Color mode and Color mode */ - MODIFY_REG(DMA2Dx->BGPFCCR, \ - (DMA2D_BGPFCCR_ALPHA | DMA2D_BGPFCCR_AM | DMA2D_BGPFCCR_CS | DMA2D_BGPFCCR_CCM | DMA2D_BGPFCCR_CM), \ - ((DMA2D_LayerCfg->Alpha << DMA2D_BGPFCCR_ALPHA_Pos) | DMA2D_LayerCfg->AlphaMode | \ - (DMA2D_LayerCfg->CLUTSize << DMA2D_BGPFCCR_CS_Pos) | DMA2D_LayerCfg->CLUTColorMode | \ - DMA2D_LayerCfg->ColorMode)); - - /* Configure the background color */ - LL_DMA2D_BGND_SetColor(DMA2Dx, DMA2D_LayerCfg->Red, DMA2D_LayerCfg->Green, DMA2D_LayerCfg->Blue); - - /* Configure the background CLUT memory address */ - LL_DMA2D_BGND_SetCLUTMemAddr(DMA2Dx, DMA2D_LayerCfg->CLUTMemoryAddress); - } - else - { - /* Configure the foreground memory address */ - LL_DMA2D_FGND_SetMemAddr(DMA2Dx, DMA2D_LayerCfg->MemoryAddress); - - /* Configure the foreground line offset */ - LL_DMA2D_FGND_SetLineOffset(DMA2Dx, DMA2D_LayerCfg->LineOffset); - - /* Configure the foreground Alpha value, Alpha mode, CLUT size, CLUT Color mode and Color mode */ - MODIFY_REG(DMA2Dx->FGPFCCR, \ - (DMA2D_FGPFCCR_ALPHA | DMA2D_FGPFCCR_AM | DMA2D_FGPFCCR_CS | DMA2D_FGPFCCR_CCM | DMA2D_FGPFCCR_CM), \ - ((DMA2D_LayerCfg->Alpha << DMA2D_FGPFCCR_ALPHA_Pos) | DMA2D_LayerCfg->AlphaMode | \ - (DMA2D_LayerCfg->CLUTSize << DMA2D_FGPFCCR_CS_Pos) | DMA2D_LayerCfg->CLUTColorMode | \ - DMA2D_LayerCfg->ColorMode)); - - /* Configure the foreground color */ - LL_DMA2D_FGND_SetColor(DMA2Dx, DMA2D_LayerCfg->Red, DMA2D_LayerCfg->Green, DMA2D_LayerCfg->Blue); - - /* Configure the foreground CLUT memory address */ - LL_DMA2D_FGND_SetCLUTMemAddr(DMA2Dx, DMA2D_LayerCfg->CLUTMemoryAddress); - } -} - -/** - * @brief Set each @ref LL_DMA2D_LayerCfgTypeDef field to default value. - * @param DMA2D_LayerCfg pointer to a @ref LL_DMA2D_LayerCfgTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_DMA2D_LayerCfgStructInit(LL_DMA2D_LayerCfgTypeDef *DMA2D_LayerCfg) -{ - /* Set DMA2D_LayerCfg fields to default values */ - DMA2D_LayerCfg->MemoryAddress = 0x0U; - DMA2D_LayerCfg->ColorMode = LL_DMA2D_INPUT_MODE_ARGB8888; - DMA2D_LayerCfg->LineOffset = 0x0U; - DMA2D_LayerCfg->CLUTColorMode = LL_DMA2D_CLUT_COLOR_MODE_ARGB8888; - DMA2D_LayerCfg->CLUTSize = 0x0U; - DMA2D_LayerCfg->AlphaMode = LL_DMA2D_ALPHA_MODE_NO_MODIF; - DMA2D_LayerCfg->Alpha = 0x0U; - DMA2D_LayerCfg->Blue = 0x0U; - DMA2D_LayerCfg->Green = 0x0U; - DMA2D_LayerCfg->Red = 0x0U; - DMA2D_LayerCfg->CLUTMemoryAddress = 0x0U; -} - -/** - * @brief Initialize DMA2D output color register according to the specified parameters - * in DMA2D_ColorStruct. - * @param DMA2Dx DMA2D Instance - * @param DMA2D_ColorStruct pointer to a LL_DMA2D_ColorTypeDef structure that contains - * the color configuration information for the specified DMA2D peripheral. - * @retval None - */ -void LL_DMA2D_ConfigOutputColor(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_ColorTypeDef *DMA2D_ColorStruct) -{ - uint32_t outgreen; - uint32_t outred; - uint32_t outalpha; - - /* Check the parameters */ - assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); - assert_param(IS_LL_DMA2D_OCMODE(DMA2D_ColorStruct->ColorMode)); - assert_param(IS_LL_DMA2D_GREEN(DMA2D_ColorStruct->OutputGreen)); - assert_param(IS_LL_DMA2D_RED(DMA2D_ColorStruct->OutputRed)); - assert_param(IS_LL_DMA2D_BLUE(DMA2D_ColorStruct->OutputBlue)); - assert_param(IS_LL_DMA2D_ALPHA(DMA2D_ColorStruct->OutputAlpha)); - - /* DMA2D OCOLR register configuration ------------------------------------------*/ - if (DMA2D_ColorStruct->ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) - { - outgreen = DMA2D_ColorStruct->OutputGreen << 8U; - outred = DMA2D_ColorStruct->OutputRed << 16U; - outalpha = DMA2D_ColorStruct->OutputAlpha << 24U; - } - else if (DMA2D_ColorStruct->ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) - { - outgreen = DMA2D_ColorStruct->OutputGreen << 8U; - outred = DMA2D_ColorStruct->OutputRed << 16U; - outalpha = 0x00000000U; - } - else if (DMA2D_ColorStruct->ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565) - { - outgreen = DMA2D_ColorStruct->OutputGreen << 5U; - outred = DMA2D_ColorStruct->OutputRed << 11U; - outalpha = 0x00000000U; - } - else if (DMA2D_ColorStruct->ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) - { - outgreen = DMA2D_ColorStruct->OutputGreen << 5U; - outred = DMA2D_ColorStruct->OutputRed << 10U; - outalpha = DMA2D_ColorStruct->OutputAlpha << 15U; - } - else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ - { - outgreen = DMA2D_ColorStruct->OutputGreen << 4U; - outred = DMA2D_ColorStruct->OutputRed << 8U; - outalpha = DMA2D_ColorStruct->OutputAlpha << 12U; - } - LL_DMA2D_SetOutputColor(DMA2Dx, (outgreen | outred | DMA2D_ColorStruct->OutputBlue | outalpha)); -} - -/** - * @brief Return DMA2D output Blue color. - * @param DMA2Dx DMA2D Instance. - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 - * @retval Output Blue color value between Min_Data=0 and Max_Data=0xFF - */ -uint32_t LL_DMA2D_GetOutputBlueColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - uint32_t color; - - /* Check the parameters */ - assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); - assert_param(IS_LL_DMA2D_OCMODE(ColorMode)); - - /* DMA2D OCOLR register reading ------------------------------------------*/ - if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFFU)); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFFU)); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x1FU)); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x1FU)); - } - else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFU)); - } - - return color; -} - -/** - * @brief Return DMA2D output Green color. - * @param DMA2Dx DMA2D Instance. - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 - * @retval Output Green color value between Min_Data=0 and Max_Data=0xFF - */ -uint32_t LL_DMA2D_GetOutputGreenColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - uint32_t color; - - /* Check the parameters */ - assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); - assert_param(IS_LL_DMA2D_OCMODE(ColorMode)); - - /* DMA2D OCOLR register reading ------------------------------------------*/ - if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF00U) >> 8U); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF00U) >> 8U); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x7E0U) >> 5U); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x3E0U) >> 5U); - } - else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xF0U) >> 4U); - } - - return color; -} - -/** - * @brief Return DMA2D output Red color. - * @param DMA2Dx DMA2D Instance. - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 - * @retval Output Red color value between Min_Data=0 and Max_Data=0xFF - */ -uint32_t LL_DMA2D_GetOutputRedColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - uint32_t color; - - /* Check the parameters */ - assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); - assert_param(IS_LL_DMA2D_OCMODE(ColorMode)); - - /* DMA2D OCOLR register reading ------------------------------------------*/ - if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF0000U) >> 16U); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF0000U) >> 16U); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xF800U) >> 11U); - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x7C00U) >> 10U); - } - else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xF00U) >> 8U); - } - - return color; -} - -/** - * @brief Return DMA2D output Alpha color. - * @param DMA2Dx DMA2D Instance. - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 - * @retval Output Alpha color value between Min_Data=0 and Max_Data=0xFF - */ -uint32_t LL_DMA2D_GetOutputAlphaColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - uint32_t color; - - /* Check the parameters */ - assert_param(IS_DMA2D_ALL_INSTANCE(DMA2Dx)); - assert_param(IS_LL_DMA2D_OCMODE(ColorMode)); - - /* DMA2D OCOLR register reading ------------------------------------------*/ - if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB8888) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xFF000000U) >> 24U); - } - else if ((ColorMode == LL_DMA2D_OUTPUT_MODE_RGB888) || (ColorMode == LL_DMA2D_OUTPUT_MODE_RGB565)) - { - color = 0x0U; - } - else if (ColorMode == LL_DMA2D_OUTPUT_MODE_ARGB1555) - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0x8000U) >> 15U); - } - else /* ColorMode = LL_DMA2D_OUTPUT_MODE_ARGB4444 */ - { - color = (uint32_t)(READ_BIT(DMA2Dx->OCOLR, 0xF000U) >> 12U); - } - - return color; -} - -/** - * @brief Configure DMA2D transfer size. - * @param DMA2Dx DMA2D Instance - * @param NbrOfLines Value between Min_Data=0 and Max_Data=0xFFFF - * @param NbrOfPixelsPerLines Value between Min_Data=0 and Max_Data=0x3FFF - * @retval None - */ -void LL_DMA2D_ConfigSize(DMA2D_TypeDef *DMA2Dx, uint32_t NbrOfLines, uint32_t NbrOfPixelsPerLines) -{ - MODIFY_REG(DMA2Dx->NLR, (DMA2D_NLR_PL | DMA2D_NLR_NL), \ - ((NbrOfPixelsPerLines << DMA2D_NLR_PL_Pos) | NbrOfLines)); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (DMA2D) */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_exti.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_exti.c deleted file mode 100644 index 31d70ac68196c6b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_exti.c +++ /dev/null @@ -1,214 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_exti.c - * @author MCD Application Team - * @brief EXTI LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_exti.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (EXTI) - -/** @defgroup EXTI_LL EXTI - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup EXTI_LL_Private_Macros - * @{ - */ - -#define IS_LL_EXTI_LINE_0_31(__VALUE__) (((__VALUE__) & ~LL_EXTI_LINE_ALL_0_31) == 0x00000000U) - -#define IS_LL_EXTI_MODE(__VALUE__) (((__VALUE__) == LL_EXTI_MODE_IT) \ - || ((__VALUE__) == LL_EXTI_MODE_EVENT) \ - || ((__VALUE__) == LL_EXTI_MODE_IT_EVENT)) - - -#define IS_LL_EXTI_TRIGGER(__VALUE__) (((__VALUE__) == LL_EXTI_TRIGGER_NONE) \ - || ((__VALUE__) == LL_EXTI_TRIGGER_RISING) \ - || ((__VALUE__) == LL_EXTI_TRIGGER_FALLING) \ - || ((__VALUE__) == LL_EXTI_TRIGGER_RISING_FALLING)) - -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup EXTI_LL_Exported_Functions - * @{ - */ - -/** @addtogroup EXTI_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize the EXTI registers to their default reset values. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: EXTI registers are de-initialized - * - ERROR: not applicable - */ -uint32_t LL_EXTI_DeInit(void) -{ - /* Interrupt mask register set to default reset values */ - LL_EXTI_WriteReg(IMR, 0x00000000U); - /* Event mask register set to default reset values */ - LL_EXTI_WriteReg(EMR, 0x00000000U); - /* Rising Trigger selection register set to default reset values */ - LL_EXTI_WriteReg(RTSR, 0x00000000U); - /* Falling Trigger selection register set to default reset values */ - LL_EXTI_WriteReg(FTSR, 0x00000000U); - /* Software interrupt event register set to default reset values */ - LL_EXTI_WriteReg(SWIER, 0x00000000U); - /* Pending register set to default reset values */ - LL_EXTI_WriteReg(PR, 0x00FFFFFFU); - - return SUCCESS; -} - -/** - * @brief Initialize the EXTI registers according to the specified parameters in EXTI_InitStruct. - * @param EXTI_InitStruct pointer to a @ref LL_EXTI_InitTypeDef structure. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: EXTI registers are initialized - * - ERROR: not applicable - */ -uint32_t LL_EXTI_Init(LL_EXTI_InitTypeDef *EXTI_InitStruct) -{ - ErrorStatus status = SUCCESS; - /* Check the parameters */ - assert_param(IS_LL_EXTI_LINE_0_31(EXTI_InitStruct->Line_0_31)); - assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->LineCommand)); - assert_param(IS_LL_EXTI_MODE(EXTI_InitStruct->Mode)); - - /* ENABLE LineCommand */ - if (EXTI_InitStruct->LineCommand != DISABLE) - { - assert_param(IS_LL_EXTI_TRIGGER(EXTI_InitStruct->Trigger)); - - /* Configure EXTI Lines in range from 0 to 31 */ - if (EXTI_InitStruct->Line_0_31 != LL_EXTI_LINE_NONE) - { - switch (EXTI_InitStruct->Mode) - { - case LL_EXTI_MODE_IT: - /* First Disable Event on provided Lines */ - LL_EXTI_DisableEvent_0_31(EXTI_InitStruct->Line_0_31); - /* Then Enable IT on provided Lines */ - LL_EXTI_EnableIT_0_31(EXTI_InitStruct->Line_0_31); - break; - case LL_EXTI_MODE_EVENT: - /* First Disable IT on provided Lines */ - LL_EXTI_DisableIT_0_31(EXTI_InitStruct->Line_0_31); - /* Then Enable Event on provided Lines */ - LL_EXTI_EnableEvent_0_31(EXTI_InitStruct->Line_0_31); - break; - case LL_EXTI_MODE_IT_EVENT: - /* Directly Enable IT & Event on provided Lines */ - LL_EXTI_EnableIT_0_31(EXTI_InitStruct->Line_0_31); - LL_EXTI_EnableEvent_0_31(EXTI_InitStruct->Line_0_31); - break; - default: - status = ERROR; - break; - } - if (EXTI_InitStruct->Trigger != LL_EXTI_TRIGGER_NONE) - { - switch (EXTI_InitStruct->Trigger) - { - case LL_EXTI_TRIGGER_RISING: - /* First Disable Falling Trigger on provided Lines */ - LL_EXTI_DisableFallingTrig_0_31(EXTI_InitStruct->Line_0_31); - /* Then Enable Rising Trigger on provided Lines */ - LL_EXTI_EnableRisingTrig_0_31(EXTI_InitStruct->Line_0_31); - break; - case LL_EXTI_TRIGGER_FALLING: - /* First Disable Rising Trigger on provided Lines */ - LL_EXTI_DisableRisingTrig_0_31(EXTI_InitStruct->Line_0_31); - /* Then Enable Falling Trigger on provided Lines */ - LL_EXTI_EnableFallingTrig_0_31(EXTI_InitStruct->Line_0_31); - break; - case LL_EXTI_TRIGGER_RISING_FALLING: - LL_EXTI_EnableRisingTrig_0_31(EXTI_InitStruct->Line_0_31); - LL_EXTI_EnableFallingTrig_0_31(EXTI_InitStruct->Line_0_31); - break; - default: - status = ERROR; - break; - } - } - } - } - /* DISABLE LineCommand */ - else - { - /* De-configure EXTI Lines in range from 0 to 31 */ - LL_EXTI_DisableIT_0_31(EXTI_InitStruct->Line_0_31); - LL_EXTI_DisableEvent_0_31(EXTI_InitStruct->Line_0_31); - } - return status; -} - -/** - * @brief Set each @ref LL_EXTI_InitTypeDef field to default value. - * @param EXTI_InitStruct Pointer to a @ref LL_EXTI_InitTypeDef structure. - * @retval None - */ -void LL_EXTI_StructInit(LL_EXTI_InitTypeDef *EXTI_InitStruct) -{ - EXTI_InitStruct->Line_0_31 = LL_EXTI_LINE_NONE; - EXTI_InitStruct->LineCommand = DISABLE; - EXTI_InitStruct->Mode = LL_EXTI_MODE_IT; - EXTI_InitStruct->Trigger = LL_EXTI_TRIGGER_FALLING; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (EXTI) */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmc.c deleted file mode 100644 index 2e4dadb32e674a3..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmc.c +++ /dev/null @@ -1,1692 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fmc.c - * @author MCD Application Team - * @brief FMC Low Layer HAL module driver. - * - * This file provides firmware functions to manage the following - * functionalities of the Flexible Memory Controller (FMC) peripheral memories: - * + Initialization/de-initialization functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### FMC peripheral features ##### - ============================================================================== - [..] The Flexible memory controller (FMC) includes three memory controllers: - (+) The NOR/PSRAM memory controller - (+) The NAND/PC Card memory controller - (+) The Synchronous DRAM (SDRAM) controller - - [..] The FMC functional block makes the interface with synchronous and asynchronous static - memories, SDRAM memories, and 16-bit PC memory cards. Its main purposes are: - (+) to translate AHB transactions into the appropriate external device protocol - (+) to meet the access time requirements of the external memory devices - - [..] All external memories share the addresses, data and control signals with the controller. - Each external device is accessed by means of a unique Chip Select. The FMC performs - only one access at a time to an external device. - The main features of the FMC controller are the following: - (+) Interface with static-memory mapped devices including: - (++) Static random access memory (SRAM) - (++) Read-only memory (ROM) - (++) NOR Flash memory/OneNAND Flash memory - (++) PSRAM (4 memory banks) - (++) 16-bit PC Card compatible devices - (++) Two banks of NAND Flash memory with ECC hardware to check up to 8 Kbytes of - data - (+) Interface with synchronous DRAM (SDRAM) memories - (+) Independent Chip Select control for each memory bank - (+) Independent configuration for each memory bank - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FMC_LL FMC Low Layer - * @brief FMC driver modules - * @{ - */ - -#if defined (HAL_SRAM_MODULE_ENABLED) || defined(HAL_NOR_MODULE_ENABLED) || defined(HAL_NAND_MODULE_ENABLED) || defined(HAL_PCCARD_MODULE_ENABLED) || defined(HAL_SDRAM_MODULE_ENABLED) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup FMC_LL_Private_Functions - * @{ - */ - -/** @addtogroup FMC_LL_NORSRAM - * @brief NORSRAM Controller functions - * - @verbatim - ============================================================================== - ##### How to use NORSRAM device driver ##### - ============================================================================== - - [..] - This driver contains a set of APIs to interface with the FMC NORSRAM banks in order - to run the NORSRAM external devices. - - (+) FMC NORSRAM bank reset using the function FMC_NORSRAM_DeInit() - (+) FMC NORSRAM bank control configuration using the function FMC_NORSRAM_Init() - (+) FMC NORSRAM bank timing configuration using the function FMC_NORSRAM_Timing_Init() - (+) FMC NORSRAM bank extended timing configuration using the function - FMC_NORSRAM_Extended_Timing_Init() - (+) FMC NORSRAM bank enable/disable write operation using the functions - FMC_NORSRAM_WriteOperation_Enable()/FMC_NORSRAM_WriteOperation_Disable() - - -@endverbatim - * @{ - */ - -/** @addtogroup FMC_LL_NORSRAM_Private_Functions_Group1 - * @brief Initialization and Configuration functions - * - @verbatim - ============================================================================== - ##### Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the FMC NORSRAM interface - (+) De-initialize the FMC NORSRAM interface - (+) Configure the FMC clock and associated GPIOs - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the FMC_NORSRAM device according to the specified - * control parameters in the FMC_NORSRAM_InitTypeDef - * @param Device Pointer to NORSRAM device instance - * @param Init Pointer to NORSRAM Initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NORSRAM_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_InitTypeDef* Init) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FMC_NORSRAM_BANK(Init->NSBank)); - assert_param(IS_FMC_MUX(Init->DataAddressMux)); - assert_param(IS_FMC_MEMORY(Init->MemoryType)); - assert_param(IS_FMC_NORSRAM_MEMORY_WIDTH(Init->MemoryDataWidth)); - assert_param(IS_FMC_BURSTMODE(Init->BurstAccessMode)); - assert_param(IS_FMC_WAIT_POLARITY(Init->WaitSignalPolarity)); -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) - assert_param(IS_FMC_WRAP_MODE(Init->WrapMode)); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - assert_param(IS_FMC_WAIT_SIGNAL_ACTIVE(Init->WaitSignalActive)); - assert_param(IS_FMC_WRITE_OPERATION(Init->WriteOperation)); - assert_param(IS_FMC_WAITE_SIGNAL(Init->WaitSignal)); - assert_param(IS_FMC_EXTENDED_MODE(Init->ExtendedMode)); - assert_param(IS_FMC_ASYNWAIT(Init->AsynchronousWait)); - assert_param(IS_FMC_WRITE_BURST(Init->WriteBurst)); - assert_param(IS_FMC_CONTINOUS_CLOCK(Init->ContinuousClock)); - assert_param(IS_FMC_PAGESIZE(Init->PageSize)); -#if defined (STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - assert_param(IS_FMC_WRITE_FIFO(Init->WriteFifo)); -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - - /* Get the BTCR register value */ - tmpr = Device->BTCR[Init->NSBank]; - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) - /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, WRAPMOD, WAITCFG, WREN, - WAITEN, EXTMOD, ASYNCWAIT, CPSIZE, CBURSTRW and CCLKEN bits */ - tmpr &= ((uint32_t)~(FMC_BCR1_MBKEN | FMC_BCR1_MUXEN | FMC_BCR1_MTYP | \ - FMC_BCR1_MWID | FMC_BCR1_FACCEN | FMC_BCR1_BURSTEN | \ - FMC_BCR1_WAITPOL | FMC_BCR1_WRAPMOD | FMC_BCR1_WAITCFG | \ - FMC_BCR1_WREN | FMC_BCR1_WAITEN | FMC_BCR1_EXTMOD | \ - FMC_BCR1_ASYNCWAIT | FMC_BCR1_CPSIZE | FMC_BCR1_CBURSTRW | \ - FMC_BCR1_CCLKEN)); - - /* Set NORSRAM device control parameters */ - tmpr |= (uint32_t)(Init->DataAddressMux |\ - Init->MemoryType |\ - Init->MemoryDataWidth |\ - Init->BurstAccessMode |\ - Init->WaitSignalPolarity |\ - Init->WrapMode |\ - Init->WaitSignalActive |\ - Init->WriteOperation |\ - Init->WaitSignal |\ - Init->ExtendedMode |\ - Init->AsynchronousWait |\ - Init->PageSize |\ - Init->WriteBurst |\ - Init->ContinuousClock); -#else /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */ - /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, CPSIZE, WAITCFG, WREN, - WAITEN, EXTMOD, ASYNCWAIT, CBURSTRW, CCLKEN and WFDIS bits */ - tmpr &= ((uint32_t)~(FMC_BCR1_MBKEN | FMC_BCR1_MUXEN | FMC_BCR1_MTYP | \ - FMC_BCR1_MWID | FMC_BCR1_FACCEN | FMC_BCR1_BURSTEN | \ - FMC_BCR1_WAITPOL | FMC_BCR1_WAITCFG | FMC_BCR1_CPSIZE | \ - FMC_BCR1_WREN | FMC_BCR1_WAITEN | FMC_BCR1_EXTMOD | \ - FMC_BCR1_ASYNCWAIT | FMC_BCR1_CBURSTRW | FMC_BCR1_CCLKEN | \ - FMC_BCR1_WFDIS)); - - /* Set NORSRAM device control parameters */ - tmpr |= (uint32_t)(Init->DataAddressMux |\ - Init->MemoryType |\ - Init->MemoryDataWidth |\ - Init->BurstAccessMode |\ - Init->WaitSignalPolarity |\ - Init->WaitSignalActive |\ - Init->WriteOperation |\ - Init->WaitSignal |\ - Init->ExtendedMode |\ - Init->AsynchronousWait |\ - Init->WriteBurst |\ - Init->ContinuousClock |\ - Init->PageSize |\ - Init->WriteFifo); -#endif /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ - - if(Init->MemoryType == FMC_MEMORY_TYPE_NOR) - { - tmpr |= (uint32_t)FMC_NORSRAM_FLASH_ACCESS_ENABLE; - } - - Device->BTCR[Init->NSBank] = tmpr; - - /* Configure synchronous mode when Continuous clock is enabled for bank2..4 */ - if((Init->ContinuousClock == FMC_CONTINUOUS_CLOCK_SYNC_ASYNC) && (Init->NSBank != FMC_NORSRAM_BANK1)) - { - Device->BTCR[FMC_NORSRAM_BANK1] |= (uint32_t)(Init->ContinuousClock); - } - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - if(Init->NSBank != FMC_NORSRAM_BANK1) - { - Device->BTCR[FMC_NORSRAM_BANK1] |= (uint32_t)(Init->WriteFifo); - } -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - - return HAL_OK; -} - -/** - * @brief DeInitialize the FMC_NORSRAM peripheral - * @param Device Pointer to NORSRAM device instance - * @param ExDevice Pointer to NORSRAM extended mode device instance - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NORSRAM_DeInit(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(ExDevice)); - assert_param(IS_FMC_NORSRAM_BANK(Bank)); - - /* Disable the FMC_NORSRAM device */ - __FMC_NORSRAM_DISABLE(Device, Bank); - - /* De-initialize the FMC_NORSRAM device */ - /* FMC_NORSRAM_BANK1 */ - if(Bank == FMC_NORSRAM_BANK1) - { - Device->BTCR[Bank] = 0x000030DBU; - } - /* FMC_NORSRAM_BANK2, FMC_NORSRAM_BANK3 or FMC_NORSRAM_BANK4 */ - else - { - Device->BTCR[Bank] = 0x000030D2U; - } - - Device->BTCR[Bank + 1U] = 0x0FFFFFFFU; - ExDevice->BWTR[Bank] = 0x0FFFFFFFU; - - return HAL_OK; -} - -/** - * @brief Initialize the FMC_NORSRAM Timing according to the specified - * parameters in the FMC_NORSRAM_TimingTypeDef - * @param Device Pointer to NORSRAM device instance - * @param Timing Pointer to NORSRAM Timing structure - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NORSRAM_Timing_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime)); - assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime)); - assert_param(IS_FMC_DATASETUP_TIME(Timing->DataSetupTime)); - assert_param(IS_FMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration)); - assert_param(IS_FMC_CLK_DIV(Timing->CLKDivision)); - assert_param(IS_FMC_DATA_LATENCY(Timing->DataLatency)); - assert_param(IS_FMC_ACCESS_MODE(Timing->AccessMode)); - assert_param(IS_FMC_NORSRAM_BANK(Bank)); - - /* Get the BTCR register value */ - tmpr = Device->BTCR[Bank + 1U]; - - /* Clear ADDSET, ADDHLD, DATAST, BUSTURN, CLKDIV, DATLAT and ACCMOD bits */ - tmpr &= ((uint32_t)~(FMC_BTR1_ADDSET | FMC_BTR1_ADDHLD | FMC_BTR1_DATAST | \ - FMC_BTR1_BUSTURN | FMC_BTR1_CLKDIV | FMC_BTR1_DATLAT | \ - FMC_BTR1_ACCMOD)); - - /* Set FMC_NORSRAM device timing parameters */ - tmpr |= (uint32_t)(Timing->AddressSetupTime |\ - ((Timing->AddressHoldTime) << 4U) |\ - ((Timing->DataSetupTime) << 8U) |\ - ((Timing->BusTurnAroundDuration) << 16U) |\ - (((Timing->CLKDivision) - 1U) << 20U) |\ - (((Timing->DataLatency) - 2U) << 24U) |\ - (Timing->AccessMode)); - - Device->BTCR[Bank + 1U] = tmpr; - - /* Configure Clock division value (in NORSRAM bank 1) when continuous clock is enabled */ - if(HAL_IS_BIT_SET(Device->BTCR[FMC_NORSRAM_BANK1], FMC_BCR1_CCLKEN)) - { - tmpr = (uint32_t)(Device->BTCR[FMC_NORSRAM_BANK1 + 1U] & ~(0x0FU << 20U)); - tmpr |= (uint32_t)(((Timing->CLKDivision) - 1U) << 20U); - Device->BTCR[FMC_NORSRAM_BANK1 + 1U] = tmpr; - } - - return HAL_OK; -} - -/** - * @brief Initialize the FMC_NORSRAM Extended mode Timing according to the specified - * parameters in the FMC_NORSRAM_TimingTypeDef - * @param Device Pointer to NORSRAM device instance - * @param Timing Pointer to NORSRAM Timing structure - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NORSRAM_Extended_Timing_Init(FMC_NORSRAM_EXTENDED_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_EXTENDED_MODE(ExtendedMode)); - - /* Set NORSRAM device timing register for write configuration, if extended mode is used */ - if(ExtendedMode == FMC_EXTENDED_MODE_ENABLE) - { - /* Check the parameters */ - assert_param(IS_FMC_NORSRAM_EXTENDED_DEVICE(Device)); - assert_param(IS_FMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime)); - assert_param(IS_FMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime)); - assert_param(IS_FMC_DATASETUP_TIME(Timing->DataSetupTime)); - assert_param(IS_FMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration)); - assert_param(IS_FMC_ACCESS_MODE(Timing->AccessMode)); - assert_param(IS_FMC_NORSRAM_BANK(Bank)); - - /* Get the BWTR register value */ - tmpr = Device->BWTR[Bank]; - - /* Clear ADDSET, ADDHLD, DATAST, BUSTURN and ACCMOD bits */ - tmpr &= ((uint32_t)~(FMC_BWTR1_ADDSET | FMC_BWTR1_ADDHLD | FMC_BWTR1_DATAST | \ - FMC_BWTR1_BUSTURN | FMC_BWTR1_ACCMOD)); - - tmpr |= (uint32_t)(Timing->AddressSetupTime |\ - ((Timing->AddressHoldTime) << 4U) |\ - ((Timing->DataSetupTime) << 8U) |\ - ((Timing->BusTurnAroundDuration) << 16U) |\ - (Timing->AccessMode)); - - Device->BWTR[Bank] = tmpr; - } - else - { - Device->BWTR[Bank] = 0x0FFFFFFFU; - } - - return HAL_OK; -} -/** - * @} - */ - -/** @addtogroup FMC_LL_NORSRAM_Private_Functions_Group2 - * @brief management functions - * -@verbatim - ============================================================================== - ##### FMC_NORSRAM Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the FMC NORSRAM interface. - -@endverbatim - * @{ - */ -/** - * @brief Enables dynamically FMC_NORSRAM write operation. - * @param Device Pointer to NORSRAM device instance - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Enable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FMC_NORSRAM_BANK(Bank)); - - /* Enable write operation */ - Device->BTCR[Bank] |= FMC_WRITE_OPERATION_ENABLE; - - return HAL_OK; -} - -/** - * @brief Disables dynamically FMC_NORSRAM write operation. - * @param Device Pointer to NORSRAM device instance - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Disable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FMC_NORSRAM_BANK(Bank)); - - /* Disable write operation */ - Device->BTCR[Bank] &= ~FMC_WRITE_OPERATION_ENABLE; - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup FMC_LL_NAND - * @brief NAND Controller functions - * - @verbatim - ============================================================================== - ##### How to use NAND device driver ##### - ============================================================================== - [..] - This driver contains a set of APIs to interface with the FMC NAND banks in order - to run the NAND external devices. - - (+) FMC NAND bank reset using the function FMC_NAND_DeInit() - (+) FMC NAND bank control configuration using the function FMC_NAND_Init() - (+) FMC NAND bank common space timing configuration using the function - FMC_NAND_CommonSpace_Timing_Init() - (+) FMC NAND bank attribute space timing configuration using the function - FMC_NAND_AttributeSpace_Timing_Init() - (+) FMC NAND bank enable/disable ECC correction feature using the functions - FMC_NAND_ECC_Enable()/FMC_NAND_ECC_Disable() - (+) FMC NAND bank get ECC correction code using the function FMC_NAND_GetECC() - -@endverbatim - * @{ - */ - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup HAL_FMC_NAND_Group1 Initialization/de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the FMC NAND interface - (+) De-initialize the FMC NAND interface - (+) Configure the FMC clock and associated GPIOs - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the FMC_NAND device according to the specified - * control parameters in the FMC_NAND_HandleTypeDef - * @param Device Pointer to NAND device instance - * @param Init Pointer to NAND Initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_Init(FMC_NAND_TypeDef *Device, FMC_NAND_InitTypeDef *Init) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Init->NandBank)); - assert_param(IS_FMC_WAIT_FEATURE(Init->Waitfeature)); - assert_param(IS_FMC_NAND_MEMORY_WIDTH(Init->MemoryDataWidth)); - assert_param(IS_FMC_ECC_STATE(Init->EccComputation)); - assert_param(IS_FMC_ECCPAGE_SIZE(Init->ECCPageSize)); - assert_param(IS_FMC_TCLR_TIME(Init->TCLRSetupTime)); - assert_param(IS_FMC_TAR_TIME(Init->TARSetupTime)); - - /* Get the NAND bank register value */ - tmpr = Device->PCR; - - /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */ - tmpr &= ((uint32_t)~(FMC_PCR_PWAITEN | FMC_PCR_PBKEN | FMC_PCR_PTYP | \ - FMC_PCR_PWID | FMC_PCR_ECCEN | FMC_PCR_TCLR | \ - FMC_PCR_TAR | FMC_PCR_ECCPS)); - - /* Set NAND device control parameters */ - tmpr |= (uint32_t)(Init->Waitfeature |\ - FMC_PCR_MEMORY_TYPE_NAND |\ - Init->MemoryDataWidth |\ - Init->EccComputation |\ - Init->ECCPageSize |\ - ((Init->TCLRSetupTime) << 9U) |\ - ((Init->TARSetupTime) << 13U)); - - /* NAND bank registers configuration */ - Device->PCR = tmpr; - - return HAL_OK; -} - -/** - * @brief Initializes the FMC_NAND Common space Timing according to the specified - * parameters in the FMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to NAND device instance - * @param Timing Pointer to NAND timing structure - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Get the NAND bank 2 register value */ - tmpr = Device->PMEM; - - - /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ - tmpr &= ((uint32_t)~(FMC_PMEM_MEMSET2 | FMC_PMEM_MEMWAIT2 | FMC_PMEM_MEMHOLD2 | \ - FMC_PMEM_MEMHIZ2)); - - /* Set FMC_NAND device timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U) - ); - - /* NAND bank registers configuration */ - Device->PMEM = tmpr; - - return HAL_OK; -} - -/** - * @brief Initializes the FMC_NAND Attribute space Timing according to the specified - * parameters in the FMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to NAND device instance - * @param Timing Pointer to NAND timing structure - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Get the NAND bank register value */ - tmpr = Device->PATT; - - /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ - tmpr &= ((uint32_t)~(FMC_PATT_ATTSET2 | FMC_PATT_ATTWAIT2 | FMC_PATT_ATTHOLD2 | \ - FMC_PATT_ATTHIZ2)); - - /* Set FMC_NAND device timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U)); - - /* NAND bank registers configuration */ - Device->PATT = tmpr; - - return HAL_OK; -} - - -/** - * @brief DeInitializes the FMC_NAND device - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_DeInit(FMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Disable the NAND Bank */ - __FMC_NAND_DISABLE(Device, Bank); - - /* De-initialize the NAND Bank */ - /* Set the FMC_NAND_BANK registers to their reset values */ - Device->PCR = 0x00000018U; - Device->SR = 0x00000040U; - Device->PMEM = 0xFCFCFCFCU; - Device->PATT = 0xFCFCFCFCU; - - return HAL_OK; -} - -/** - * @} - */ - - -/** @defgroup HAL_FMC_NAND_Group2 Control functions - * @brief management functions - * -@verbatim - ============================================================================== - ##### FMC_NAND Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the FMC NAND interface. - -@endverbatim - * @{ - */ - - -/** - * @brief Enables dynamically FMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_ECC_Enable(FMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Enable ECC feature */ - Device->PCR |= FMC_PCR_ECCEN; - - return HAL_OK; -} - - -/** - * @brief Disables dynamically FMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_ECC_Disable(FMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Disable ECC feature */ - Device->PCR &= ~FMC_PCR_ECCEN; - - return HAL_OK; -} - -/** - * @brief Disables dynamically FMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param ECCval Pointer to ECC value - * @param Bank NAND bank number - * @param Timeout Timeout wait value - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_GetECC(FMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until FIFO is empty */ - while(__FMC_NAND_GET_FLAG(Device, Bank, FMC_FLAG_FEMPT) == RESET) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - return HAL_TIMEOUT; - } - } - } - - /* Get the ECCR register value */ - *ECCval = (uint32_t)Device->ECCR; - - return HAL_OK; -} - -/** - * @} - */ - -#else /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ -/** @defgroup HAL_FMC_NAND_Group1 Initialization/de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the FMC NAND interface - (+) De-initialize the FMC NAND interface - (+) Configure the FMC clock and associated GPIOs - -@endverbatim - * @{ - */ -/** - * @brief Initializes the FMC_NAND device according to the specified - * control parameters in the FMC_NAND_HandleTypeDef - * @param Device Pointer to NAND device instance - * @param Init Pointer to NAND Initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_Init(FMC_NAND_TypeDef *Device, FMC_NAND_InitTypeDef *Init) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Init->NandBank)); - assert_param(IS_FMC_WAIT_FEATURE(Init->Waitfeature)); - assert_param(IS_FMC_NAND_MEMORY_WIDTH(Init->MemoryDataWidth)); - assert_param(IS_FMC_ECC_STATE(Init->EccComputation)); - assert_param(IS_FMC_ECCPAGE_SIZE(Init->ECCPageSize)); - assert_param(IS_FMC_TCLR_TIME(Init->TCLRSetupTime)); - assert_param(IS_FMC_TAR_TIME(Init->TARSetupTime)); - - if(Init->NandBank == FMC_NAND_BANK2) - { - /* Get the NAND bank 2 register value */ - tmpr = Device->PCR2; - } - else - { - /* Get the NAND bank 3 register value */ - tmpr = Device->PCR3; - } - - /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */ - tmpr &= ((uint32_t)~(FMC_PCR2_PWAITEN | FMC_PCR2_PBKEN | FMC_PCR2_PTYP | \ - FMC_PCR2_PWID | FMC_PCR2_ECCEN | FMC_PCR2_TCLR | \ - FMC_PCR2_TAR | FMC_PCR2_ECCPS)); - - /* Set NAND device control parameters */ - tmpr |= (uint32_t)(Init->Waitfeature |\ - FMC_PCR_MEMORY_TYPE_NAND |\ - Init->MemoryDataWidth |\ - Init->EccComputation |\ - Init->ECCPageSize |\ - ((Init->TCLRSetupTime) << 9U) |\ - ((Init->TARSetupTime) << 13U)); - - if(Init->NandBank == FMC_NAND_BANK2) - { - /* NAND bank 2 registers configuration */ - Device->PCR2 = tmpr; - } - else - { - /* NAND bank 3 registers configuration */ - Device->PCR3 = tmpr; - } - - return HAL_OK; - -} - -/** - * @brief Initializes the FMC_NAND Common space Timing according to the specified - * parameters in the FMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to NAND device instance - * @param Timing Pointer to NAND timing structure - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - if(Bank == FMC_NAND_BANK2) - { - /* Get the NAND bank 2 register value */ - tmpr = Device->PMEM2; - } - else - { - /* Get the NAND bank 3 register value */ - tmpr = Device->PMEM3; - } - - /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ - tmpr &= ((uint32_t)~(FMC_PMEM2_MEMSET2 | FMC_PMEM2_MEMWAIT2 | FMC_PMEM2_MEMHOLD2 | \ - FMC_PMEM2_MEMHIZ2)); - - /* Set FMC_NAND device timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U) - ); - - if(Bank == FMC_NAND_BANK2) - { - /* NAND bank 2 registers configuration */ - Device->PMEM2 = tmpr; - } - else - { - /* NAND bank 3 registers configuration */ - Device->PMEM3 = tmpr; - } - - return HAL_OK; -} - -/** - * @brief Initializes the FMC_NAND Attribute space Timing according to the specified - * parameters in the FMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to NAND device instance - * @param Timing Pointer to NAND timing structure - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - if(Bank == FMC_NAND_BANK2) - { - /* Get the NAND bank 2 register value */ - tmpr = Device->PATT2; - } - else - { - /* Get the NAND bank 3 register value */ - tmpr = Device->PATT3; - } - - /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ - tmpr &= ((uint32_t)~(FMC_PATT2_ATTSET2 | FMC_PATT2_ATTWAIT2 | FMC_PATT2_ATTHOLD2 | \ - FMC_PATT2_ATTHIZ2)); - - /* Set FMC_NAND device timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U)); - - if(Bank == FMC_NAND_BANK2) - { - /* NAND bank 2 registers configuration */ - Device->PATT2 = tmpr; - } - else - { - /* NAND bank 3 registers configuration */ - Device->PATT3 = tmpr; - } - - return HAL_OK; -} - -/** - * @brief DeInitializes the FMC_NAND device - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_DeInit(FMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Disable the NAND Bank */ - __FMC_NAND_DISABLE(Device, Bank); - - /* De-initialize the NAND Bank */ - if(Bank == FMC_NAND_BANK2) - { - /* Set the FMC_NAND_BANK2 registers to their reset values */ - Device->PCR2 = 0x00000018U; - Device->SR2 = 0x00000040U; - Device->PMEM2 = 0xFCFCFCFCU; - Device->PATT2 = 0xFCFCFCFCU; - } - /* FMC_Bank3_NAND */ - else - { - /* Set the FMC_NAND_BANK3 registers to their reset values */ - Device->PCR3 = 0x00000018U; - Device->SR3 = 0x00000040U; - Device->PMEM3 = 0xFCFCFCFCU; - Device->PATT3 = 0xFCFCFCFCU; - } - - return HAL_OK; -} - -/** - * @} - */ - -/** @addtogroup FMC_LL_NAND_Private_Functions_Group2 - * @brief management functions - * -@verbatim - ============================================================================== - ##### FMC_NAND Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the FMC NAND interface. - -@endverbatim - * @{ - */ -/** - * @brief Enables dynamically FMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_ECC_Enable(FMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Enable ECC feature */ - if(Bank == FMC_NAND_BANK2) - { - Device->PCR2 |= FMC_PCR2_ECCEN; - } - else - { - Device->PCR3 |= FMC_PCR3_ECCEN; - } - - return HAL_OK; -} - -/** - * @brief Disables dynamically FMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_ECC_Disable(FMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Disable ECC feature */ - if(Bank == FMC_NAND_BANK2) - { - Device->PCR2 &= ~FMC_PCR2_ECCEN; - } - else - { - Device->PCR3 &= ~FMC_PCR3_ECCEN; - } - - return HAL_OK; -} - -/** - * @brief Disables dynamically FMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param ECCval Pointer to ECC value - * @param Bank NAND bank number - * @param Timeout Timeout wait value - * @retval HAL status - */ -HAL_StatusTypeDef FMC_NAND_GetECC(FMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_NAND_DEVICE(Device)); - assert_param(IS_FMC_NAND_BANK(Bank)); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until FIFO is empty */ - while(__FMC_NAND_GET_FLAG(Device, Bank, FMC_FLAG_FEMPT) == RESET) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - return HAL_TIMEOUT; - } - } - } - - if(Bank == FMC_NAND_BANK2) - { - /* Get the ECCR2 register value */ - *ECCval = (uint32_t)Device->ECCR2; - } - else - { - /* Get the ECCR3 register value */ - *ECCval = (uint32_t)Device->ECCR3; - } - - return HAL_OK; -} - -/** - * @} - */ - -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */ -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @addtogroup FMC_LL_PCCARD - * @brief PCCARD Controller functions - * - @verbatim - ============================================================================== - ##### How to use PCCARD device driver ##### - ============================================================================== - [..] - This driver contains a set of APIs to interface with the FMC PCCARD bank in order - to run the PCCARD/compact flash external devices. - - (+) FMC PCCARD bank reset using the function FMC_PCCARD_DeInit() - (+) FMC PCCARD bank control configuration using the function FMC_PCCARD_Init() - (+) FMC PCCARD bank common space timing configuration using the function - FMC_PCCARD_CommonSpace_Timing_Init() - (+) FMC PCCARD bank attribute space timing configuration using the function - FMC_PCCARD_AttributeSpace_Timing_Init() - (+) FMC PCCARD bank IO space timing configuration using the function - FMC_PCCARD_IOSpace_Timing_Init() -@endverbatim - * @{ - */ - -/** @addtogroup FMC_LL_PCCARD_Private_Functions_Group1 - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the FMC PCCARD interface - (+) De-initialize the FMC PCCARD interface - (+) Configure the FMC clock and associated GPIOs - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the FMC_PCCARD device according to the specified - * control parameters in the FMC_PCCARD_HandleTypeDef - * @param Device Pointer to PCCARD device instance - * @param Init Pointer to PCCARD Initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef FMC_PCCARD_Init(FMC_PCCARD_TypeDef *Device, FMC_PCCARD_InitTypeDef *Init) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_PCCARD_DEVICE(Device)); - assert_param(IS_FMC_WAIT_FEATURE(Init->Waitfeature)); - assert_param(IS_FMC_TCLR_TIME(Init->TCLRSetupTime)); - assert_param(IS_FMC_TAR_TIME(Init->TARSetupTime)); - - /* Get PCCARD control register value */ - tmpr = Device->PCR4; - - /* Clear TAR, TCLR, PWAITEN and PWID bits */ - tmpr &= ((uint32_t)~(FMC_PCR4_TAR | FMC_PCR4_TCLR | FMC_PCR4_PWAITEN | \ - FMC_PCR4_PWID | FMC_PCR4_PTYP)); - - /* Set FMC_PCCARD device control parameters */ - tmpr |= (uint32_t)(Init->Waitfeature |\ - FMC_NAND_PCC_MEM_BUS_WIDTH_16 |\ - (Init->TCLRSetupTime << 9U) |\ - (Init->TARSetupTime << 13U)); - - Device->PCR4 = tmpr; - - return HAL_OK; -} - -/** - * @brief Initializes the FMC_PCCARD Common space Timing according to the specified - * parameters in the FMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to PCCARD device instance - * @param Timing Pointer to PCCARD timing structure - * @retval HAL status - */ -HAL_StatusTypeDef FMC_PCCARD_CommonSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_PCCARD_DEVICE(Device)); - assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); - - /* Get PCCARD common space timing register value */ - tmpr = Device->PMEM4; - - /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ - tmpr &= ((uint32_t)~(FMC_PMEM4_MEMSET4 | FMC_PMEM4_MEMWAIT4 | FMC_PMEM4_MEMHOLD4 | \ - FMC_PMEM4_MEMHIZ4)); - /* Set PCCARD timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U)); - - Device->PMEM4 = tmpr; - - return HAL_OK; -} - -/** - * @brief Initializes the FMC_PCCARD Attribute space Timing according to the specified - * parameters in the FMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to PCCARD device instance - * @param Timing Pointer to PCCARD timing structure - * @retval HAL status - */ -HAL_StatusTypeDef FMC_PCCARD_AttributeSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_PCCARD_DEVICE(Device)); - assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); - - /* Get PCCARD timing parameters */ - tmpr = Device->PATT4; - - /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ - tmpr &= ((uint32_t)~(FMC_PATT4_ATTSET4 | FMC_PATT4_ATTWAIT4 | FMC_PATT4_ATTHOLD4 | \ - FMC_PATT4_ATTHIZ4)); - - /* Set PCCARD timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U)); - Device->PATT4 = tmpr; - - return HAL_OK; -} - -/** - * @brief Initializes the FMC_PCCARD IO space Timing according to the specified - * parameters in the FMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to PCCARD device instance - * @param Timing Pointer to PCCARD timing structure - * @retval HAL status - */ -HAL_StatusTypeDef FMC_PCCARD_IOSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing) -{ - uint32_t tmpr = 0; - - /* Check the parameters */ - assert_param(IS_FMC_PCCARD_DEVICE(Device)); - assert_param(IS_FMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FMC_HIZ_TIME(Timing->HiZSetupTime)); - - /* Get FMC_PCCARD device timing parameters */ - tmpr = Device->PIO4; - - /* Clear IOSET4, IOWAIT4, IOHOLD4 and IOHIZ4 bits */ - tmpr &= ((uint32_t)~(FMC_PIO4_IOSET4 | FMC_PIO4_IOWAIT4 | FMC_PIO4_IOHOLD4 | \ - FMC_PIO4_IOHIZ4)); - - /* Set FMC_PCCARD device timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U)); - - Device->PIO4 = tmpr; - - return HAL_OK; -} - -/** - * @brief DeInitializes the FMC_PCCARD device - * @param Device Pointer to PCCARD device instance - * @retval HAL status - */ -HAL_StatusTypeDef FMC_PCCARD_DeInit(FMC_PCCARD_TypeDef *Device) -{ - /* Check the parameters */ - assert_param(IS_FMC_PCCARD_DEVICE(Device)); - - /* Disable the FMC_PCCARD device */ - __FMC_PCCARD_DISABLE(Device); - - /* De-initialize the FMC_PCCARD device */ - Device->PCR4 = 0x00000018U; - Device->SR4 = 0x00000000U; - Device->PMEM4 = 0xFCFCFCFCU; - Device->PATT4 = 0xFCFCFCFCU; - Device->PIO4 = 0xFCFCFCFCU; - - return HAL_OK; -} - -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - - -/** @addtogroup FMC_LL_SDRAM - * @brief SDRAM Controller functions - * - @verbatim - ============================================================================== - ##### How to use SDRAM device driver ##### - ============================================================================== - [..] - This driver contains a set of APIs to interface with the FMC SDRAM banks in order - to run the SDRAM external devices. - - (+) FMC SDRAM bank reset using the function FMC_SDRAM_DeInit() - (+) FMC SDRAM bank control configuration using the function FMC_SDRAM_Init() - (+) FMC SDRAM bank timing configuration using the function FMC_SDRAM_Timing_Init() - (+) FMC SDRAM bank enable/disable write operation using the functions - FMC_SDRAM_WriteOperation_Enable()/FMC_SDRAM_WriteOperation_Disable() - (+) FMC SDRAM bank send command using the function FMC_SDRAM_SendCommand() - -@endverbatim - * @{ - */ - -/** @addtogroup FMC_LL_SDRAM_Private_Functions_Group1 - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the FMC SDRAM interface - (+) De-initialize the FMC SDRAM interface - (+) Configure the FMC clock and associated GPIOs - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the FMC_SDRAM device according to the specified - * control parameters in the FMC_SDRAM_InitTypeDef - * @param Device Pointer to SDRAM device instance - * @param Init Pointer to SDRAM Initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef FMC_SDRAM_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_InitTypeDef *Init) -{ - uint32_t tmpr1 = 0U; - uint32_t tmpr2 = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_SDRAM_BANK(Init->SDBank)); - assert_param(IS_FMC_COLUMNBITS_NUMBER(Init->ColumnBitsNumber)); - assert_param(IS_FMC_ROWBITS_NUMBER(Init->RowBitsNumber)); - assert_param(IS_FMC_SDMEMORY_WIDTH(Init->MemoryDataWidth)); - assert_param(IS_FMC_INTERNALBANK_NUMBER(Init->InternalBankNumber)); - assert_param(IS_FMC_CAS_LATENCY(Init->CASLatency)); - assert_param(IS_FMC_WRITE_PROTECTION(Init->WriteProtection)); - assert_param(IS_FMC_SDCLOCK_PERIOD(Init->SDClockPeriod)); - assert_param(IS_FMC_READ_BURST(Init->ReadBurst)); - assert_param(IS_FMC_READPIPE_DELAY(Init->ReadPipeDelay)); - - /* Set SDRAM bank configuration parameters */ - if (Init->SDBank != FMC_SDRAM_BANK2) - { - tmpr1 = Device->SDCR[FMC_SDRAM_BANK1]; - - /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */ - tmpr1 &= ((uint32_t)~(FMC_SDCR1_NC | FMC_SDCR1_NR | FMC_SDCR1_MWID | \ - FMC_SDCR1_NB | FMC_SDCR1_CAS | FMC_SDCR1_WP | \ - FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE)); - - - tmpr1 |= (uint32_t)(Init->ColumnBitsNumber |\ - Init->RowBitsNumber |\ - Init->MemoryDataWidth |\ - Init->InternalBankNumber |\ - Init->CASLatency |\ - Init->WriteProtection |\ - Init->SDClockPeriod |\ - Init->ReadBurst |\ - Init->ReadPipeDelay - ); - Device->SDCR[FMC_SDRAM_BANK1] = tmpr1; - } - else /* FMC_Bank2_SDRAM */ - { - tmpr1 = Device->SDCR[FMC_SDRAM_BANK1]; - - /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */ - tmpr1 &= ((uint32_t)~(FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE)); - - tmpr1 |= (uint32_t)(Init->SDClockPeriod |\ - Init->ReadBurst |\ - Init->ReadPipeDelay); - - tmpr2 = Device->SDCR[FMC_SDRAM_BANK2]; - - /* Clear NC, NR, MWID, NB, CAS, WP, SDCLK, RBURST, and RPIPE bits */ - tmpr2 &= ((uint32_t)~(FMC_SDCR1_NC | FMC_SDCR1_NR | FMC_SDCR1_MWID | \ - FMC_SDCR1_NB | FMC_SDCR1_CAS | FMC_SDCR1_WP | \ - FMC_SDCR1_SDCLK | FMC_SDCR1_RBURST | FMC_SDCR1_RPIPE)); - - tmpr2 |= (uint32_t)(Init->ColumnBitsNumber |\ - Init->RowBitsNumber |\ - Init->MemoryDataWidth |\ - Init->InternalBankNumber |\ - Init->CASLatency |\ - Init->WriteProtection); - - Device->SDCR[FMC_SDRAM_BANK1] = tmpr1; - Device->SDCR[FMC_SDRAM_BANK2] = tmpr2; - } - - return HAL_OK; -} - -/** - * @brief Initializes the FMC_SDRAM device timing according to the specified - * parameters in the FMC_SDRAM_TimingTypeDef - * @param Device Pointer to SDRAM device instance - * @param Timing Pointer to SDRAM Timing structure - * @param Bank SDRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_SDRAM_Timing_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr1 = 0U; - uint32_t tmpr2 = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_LOADTOACTIVE_DELAY(Timing->LoadToActiveDelay)); - assert_param(IS_FMC_EXITSELFREFRESH_DELAY(Timing->ExitSelfRefreshDelay)); - assert_param(IS_FMC_SELFREFRESH_TIME(Timing->SelfRefreshTime)); - assert_param(IS_FMC_ROWCYCLE_DELAY(Timing->RowCycleDelay)); - assert_param(IS_FMC_WRITE_RECOVERY_TIME(Timing->WriteRecoveryTime)); - assert_param(IS_FMC_RP_DELAY(Timing->RPDelay)); - assert_param(IS_FMC_RCD_DELAY(Timing->RCDDelay)); - assert_param(IS_FMC_SDRAM_BANK(Bank)); - - /* Set SDRAM device timing parameters */ - if (Bank != FMC_SDRAM_BANK2) - { - tmpr1 = Device->SDTR[FMC_SDRAM_BANK1]; - - /* Clear TMRD, TXSR, TRAS, TRC, TWR, TRP and TRCD bits */ - tmpr1 &= ((uint32_t)~(FMC_SDTR1_TMRD | FMC_SDTR1_TXSR | FMC_SDTR1_TRAS | \ - FMC_SDTR1_TRC | FMC_SDTR1_TWR | FMC_SDTR1_TRP | \ - FMC_SDTR1_TRCD)); - - tmpr1 |= (uint32_t)(((Timing->LoadToActiveDelay)-1U) |\ - (((Timing->ExitSelfRefreshDelay)-1U) << 4U) |\ - (((Timing->SelfRefreshTime)-1U) << 8U) |\ - (((Timing->RowCycleDelay)-1U) << 12U) |\ - (((Timing->WriteRecoveryTime)-1U) <<16U) |\ - (((Timing->RPDelay)-1U) << 20U) |\ - (((Timing->RCDDelay)-1U) << 24U)); - Device->SDTR[FMC_SDRAM_BANK1] = tmpr1; - } - else /* FMC_Bank2_SDRAM */ - { - tmpr1 = Device->SDTR[FMC_SDRAM_BANK1]; - - /* Clear TRC and TRP bits */ - tmpr1 &= ((uint32_t)~(FMC_SDTR1_TRC | FMC_SDTR1_TRP)); - - tmpr1 |= (uint32_t)((((Timing->RowCycleDelay)-1U) << 12U) |\ - (((Timing->RPDelay)-1U) << 20U)); - - tmpr2 = Device->SDTR[FMC_SDRAM_BANK2]; - - /* Clear TMRD, TXSR, TRAS, TRC, TWR, TRP and TRCD bits */ - tmpr2 &= ((uint32_t)~(FMC_SDTR1_TMRD | FMC_SDTR1_TXSR | FMC_SDTR1_TRAS | \ - FMC_SDTR1_TRC | FMC_SDTR1_TWR | FMC_SDTR1_TRP | \ - FMC_SDTR1_TRCD)); - - tmpr2 |= (uint32_t)((((Timing->LoadToActiveDelay)-1U) |\ - (((Timing->ExitSelfRefreshDelay)-1U) << 4U) |\ - (((Timing->SelfRefreshTime)-1U) << 8U) |\ - (((Timing->WriteRecoveryTime)-1U) <<16U) |\ - (((Timing->RCDDelay)-1U) << 24U))); - - Device->SDTR[FMC_SDRAM_BANK1] = tmpr1; - Device->SDTR[FMC_SDRAM_BANK2] = tmpr2; - } - return HAL_OK; -} - -/** - * @brief DeInitializes the FMC_SDRAM peripheral - * @param Device Pointer to SDRAM device instance - * @retval HAL status - */ -HAL_StatusTypeDef FMC_SDRAM_DeInit(FMC_SDRAM_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_SDRAM_BANK(Bank)); - - /* De-initialize the SDRAM device */ - Device->SDCR[Bank] = 0x000002D0U; - Device->SDTR[Bank] = 0x0FFFFFFFU; - Device->SDCMR = 0x00000000U; - Device->SDRTR = 0x00000000U; - Device->SDSR = 0x00000000U; - - return HAL_OK; -} - -/** - * @} - */ - -/** @addtogroup FMC_LL_SDRAMPrivate_Functions_Group2 - * @brief management functions - * -@verbatim - ============================================================================== - ##### FMC_SDRAM Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the FMC SDRAM interface. - -@endverbatim - * @{ - */ -/** - * @brief Enables dynamically FMC_SDRAM write protection. - * @param Device Pointer to SDRAM device instance - * @param Bank SDRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Enable(FMC_SDRAM_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_SDRAM_BANK(Bank)); - - /* Enable write protection */ - Device->SDCR[Bank] |= FMC_SDRAM_WRITE_PROTECTION_ENABLE; - - return HAL_OK; -} - -/** - * @brief Disables dynamically FMC_SDRAM write protection. - * @param hsdram FMC_SDRAM handle - * @retval HAL status - */ -HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Disable(FMC_SDRAM_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_SDRAM_BANK(Bank)); - - /* Disable write protection */ - Device->SDCR[Bank] &= ~FMC_SDRAM_WRITE_PROTECTION_ENABLE; - - return HAL_OK; -} - -/** - * @brief Send Command to the FMC SDRAM bank - * @param Device Pointer to SDRAM device instance - * @param Command Pointer to SDRAM command structure - * @param Timing Pointer to SDRAM Timing structure - * @param Timeout Timeout wait value - * @retval HAL state - */ -HAL_StatusTypeDef FMC_SDRAM_SendCommand(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout) -{ - __IO uint32_t tmpr = 0U; - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_COMMAND_MODE(Command->CommandMode)); - assert_param(IS_FMC_COMMAND_TARGET(Command->CommandTarget)); - assert_param(IS_FMC_AUTOREFRESH_NUMBER(Command->AutoRefreshNumber)); - assert_param(IS_FMC_MODE_REGISTER(Command->ModeRegisterDefinition)); - - /* Set command register */ - tmpr = (uint32_t)((Command->CommandMode) |\ - (Command->CommandTarget) |\ - (((Command->AutoRefreshNumber)-1U) << 5U) |\ - ((Command->ModeRegisterDefinition) << 9U) - ); - - Device->SDCMR = tmpr; - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until command is send */ - while(HAL_IS_BIT_SET(Device->SDSR, FMC_SDSR_BUSY)) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - return HAL_TIMEOUT; - } - } - } - - return HAL_OK; -} - -/** - * @brief Program the SDRAM Memory Refresh rate. - * @param Device Pointer to SDRAM device instance - * @param RefreshRate The SDRAM refresh rate value. - * @retval HAL state - */ -HAL_StatusTypeDef FMC_SDRAM_ProgramRefreshRate(FMC_SDRAM_TypeDef *Device, uint32_t RefreshRate) -{ - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_REFRESH_RATE(RefreshRate)); - - /* Set the refresh rate in command register */ - Device->SDRTR |= (RefreshRate<<1U); - - return HAL_OK; -} - -/** - * @brief Set the Number of consecutive SDRAM Memory auto Refresh commands. - * @param Device Pointer to SDRAM device instance - * @param AutoRefreshNumber Specifies the auto Refresh number. - * @retval None - */ -HAL_StatusTypeDef FMC_SDRAM_SetAutoRefreshNumber(FMC_SDRAM_TypeDef *Device, uint32_t AutoRefreshNumber) -{ - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_AUTOREFRESH_NUMBER(AutoRefreshNumber)); - - /* Set the Auto-refresh number in command register */ - Device->SDCMR |= (AutoRefreshNumber << 5U); - - return HAL_OK; -} - -/** - * @brief Returns the indicated FMC SDRAM bank mode status. - * @param Device Pointer to SDRAM device instance - * @param Bank Defines the FMC SDRAM bank. This parameter can be - * FMC_Bank1_SDRAM or FMC_Bank2_SDRAM. - * @retval The FMC SDRAM bank mode status, could be on of the following values: - * FMC_SDRAM_NORMAL_MODE, FMC_SDRAM_SELF_REFRESH_MODE or - * FMC_SDRAM_POWER_DOWN_MODE. - */ -uint32_t FMC_SDRAM_GetModeStatus(FMC_SDRAM_TypeDef *Device, uint32_t Bank) -{ - uint32_t tmpreg = 0U; - - /* Check the parameters */ - assert_param(IS_FMC_SDRAM_DEVICE(Device)); - assert_param(IS_FMC_SDRAM_BANK(Bank)); - - /* Get the corresponding bank mode */ - if(Bank == FMC_SDRAM_BANK1) - { - tmpreg = (uint32_t)(Device->SDSR & FMC_SDSR_MODES1); - } - else - { - tmpreg = ((uint32_t)(Device->SDSR & FMC_SDSR_MODES2) >> 2U); - } - - /* Return the mode status */ - return tmpreg; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -#endif /* HAL_SRAM_MODULE_ENABLED || HAL_NOR_MODULE_ENABLED || HAL_NAND_MODULE_ENABLED || HAL_PCCARD_MODULE_ENABLED || HAL_SDRAM_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmpi2c.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmpi2c.c deleted file mode 100644 index 8fcb2a1580e9f28..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fmpi2c.c +++ /dev/null @@ -1,220 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fmpi2c.c - * @author MCD Application Team - * @brief FMPI2C LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_fmpi2c.h" -#include "stm32f4xx_ll_bus.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (FMPI2C1) - -/** @defgroup FMPI2C_LL FMPI2C - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup FMPI2C_LL_Private_Macros - * @{ - */ - -#define IS_LL_FMPI2C_PERIPHERAL_MODE(__VALUE__) (((__VALUE__) == LL_FMPI2C_MODE_I2C) || \ - ((__VALUE__) == LL_FMPI2C_MODE_SMBUS_HOST) || \ - ((__VALUE__) == LL_FMPI2C_MODE_SMBUS_DEVICE) || \ - ((__VALUE__) == LL_FMPI2C_MODE_SMBUS_DEVICE_ARP)) - -#define IS_LL_FMPI2C_ANALOG_FILTER(__VALUE__) (((__VALUE__) == LL_FMPI2C_ANALOGFILTER_ENABLE) || \ - ((__VALUE__) == LL_FMPI2C_ANALOGFILTER_DISABLE)) - -#define IS_LL_FMPI2C_DIGITAL_FILTER(__VALUE__) ((__VALUE__) <= 0x0000000FU) - -#define IS_LL_FMPI2C_OWN_ADDRESS1(__VALUE__) ((__VALUE__) <= 0x000003FFU) - -#define IS_LL_FMPI2C_TYPE_ACKNOWLEDGE(__VALUE__) (((__VALUE__) == LL_FMPI2C_ACK) || \ - ((__VALUE__) == LL_FMPI2C_NACK)) - -#define IS_LL_FMPI2C_OWN_ADDRSIZE(__VALUE__) (((__VALUE__) == LL_FMPI2C_OWNADDRESS1_7BIT) || \ - ((__VALUE__) == LL_FMPI2C_OWNADDRESS1_10BIT)) -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPI2C_LL_Exported_Functions - * @{ - */ - -/** @addtogroup FMPI2C_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize the FMPI2C registers to their default reset values. - * @param FMPI2Cx FMPI2C Instance. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: FMPI2C registers are de-initialized - * - ERROR: FMPI2C registers are not de-initialized - */ -ErrorStatus LL_FMPI2C_DeInit(FMPI2C_TypeDef *FMPI2Cx) -{ - ErrorStatus status = SUCCESS; - - /* Check the FMPI2C Instance FMPI2Cx */ - assert_param(IS_FMPI2C_ALL_INSTANCE(FMPI2Cx)); - - if (FMPI2Cx == FMPI2C1) - { - /* Force reset of FMPI2C clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_FMPI2C1); - - /* Release reset of FMPI2C clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_FMPI2C1); - } - else - { - status = ERROR; - } - - return status; -} - -/** - * @brief Initialize the FMPI2C registers according to the specified parameters in FMPI2C_InitStruct. - * @param FMPI2Cx FMPI2C Instance. - * @param FMPI2C_InitStruct pointer to a @ref LL_FMPI2C_InitTypeDef structure. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: FMPI2C registers are initialized - * - ERROR: Not applicable - */ -ErrorStatus LL_FMPI2C_Init(FMPI2C_TypeDef *FMPI2Cx, LL_FMPI2C_InitTypeDef *FMPI2C_InitStruct) -{ - /* Check the FMPI2C Instance FMPI2Cx */ - assert_param(IS_FMPI2C_ALL_INSTANCE(FMPI2Cx)); - - /* Check the FMPI2C parameters from FMPI2C_InitStruct */ - assert_param(IS_LL_FMPI2C_PERIPHERAL_MODE(FMPI2C_InitStruct->PeripheralMode)); - assert_param(IS_LL_FMPI2C_ANALOG_FILTER(FMPI2C_InitStruct->AnalogFilter)); - assert_param(IS_LL_FMPI2C_DIGITAL_FILTER(FMPI2C_InitStruct->DigitalFilter)); - assert_param(IS_LL_FMPI2C_OWN_ADDRESS1(FMPI2C_InitStruct->OwnAddress1)); - assert_param(IS_LL_FMPI2C_TYPE_ACKNOWLEDGE(FMPI2C_InitStruct->TypeAcknowledge)); - assert_param(IS_LL_FMPI2C_OWN_ADDRSIZE(FMPI2C_InitStruct->OwnAddrSize)); - - /* Disable the selected FMPI2Cx Peripheral */ - LL_FMPI2C_Disable(FMPI2Cx); - - /*---------------------------- FMPI2Cx CR1 Configuration ------------------------ - * Configure the analog and digital noise filters with parameters : - * - AnalogFilter: FMPI2C_CR1_ANFOFF bit - * - DigitalFilter: FMPI2C_CR1_DNF[3:0] bits - */ - LL_FMPI2C_ConfigFilters(FMPI2Cx, FMPI2C_InitStruct->AnalogFilter, FMPI2C_InitStruct->DigitalFilter); - - /*---------------------------- FMPI2Cx TIMINGR Configuration -------------------- - * Configure the SDA setup, hold time and the SCL high, low period with parameter : - * - Timing: FMPI2C_TIMINGR_PRESC[3:0], FMPI2C_TIMINGR_SCLDEL[3:0], FMPI2C_TIMINGR_SDADEL[3:0], - * FMPI2C_TIMINGR_SCLH[7:0] and FMPI2C_TIMINGR_SCLL[7:0] bits - */ - LL_FMPI2C_SetTiming(FMPI2Cx, FMPI2C_InitStruct->Timing); - - /* Enable the selected FMPI2Cx Peripheral */ - LL_FMPI2C_Enable(FMPI2Cx); - - /*---------------------------- FMPI2Cx OAR1 Configuration ----------------------- - * Disable, Configure and Enable FMPI2Cx device own address 1 with parameters : - * - OwnAddress1: FMPI2C_OAR1_OA1[9:0] bits - * - OwnAddrSize: FMPI2C_OAR1_OA1MODE bit - */ - LL_FMPI2C_DisableOwnAddress1(FMPI2Cx); - LL_FMPI2C_SetOwnAddress1(FMPI2Cx, FMPI2C_InitStruct->OwnAddress1, FMPI2C_InitStruct->OwnAddrSize); - - /* OwnAdress1 == 0 is reserved for General Call address */ - if (FMPI2C_InitStruct->OwnAddress1 != 0U) - { - LL_FMPI2C_EnableOwnAddress1(FMPI2Cx); - } - - /*---------------------------- FMPI2Cx MODE Configuration ----------------------- - * Configure FMPI2Cx peripheral mode with parameter : - * - PeripheralMode: FMPI2C_CR1_SMBDEN and FMPI2C_CR1_SMBHEN bits - */ - LL_FMPI2C_SetMode(FMPI2Cx, FMPI2C_InitStruct->PeripheralMode); - - /*---------------------------- FMPI2Cx CR2 Configuration ------------------------ - * Configure the ACKnowledge or Non ACKnowledge condition - * after the address receive match code or next received byte with parameter : - * - TypeAcknowledge: FMPI2C_CR2_NACK bit - */ - LL_FMPI2C_AcknowledgeNextData(FMPI2Cx, FMPI2C_InitStruct->TypeAcknowledge); - - return SUCCESS; -} - -/** - * @brief Set each @ref LL_FMPI2C_InitTypeDef field to default value. - * @param FMPI2C_InitStruct Pointer to a @ref LL_FMPI2C_InitTypeDef structure. - * @retval None - */ -void LL_FMPI2C_StructInit(LL_FMPI2C_InitTypeDef *FMPI2C_InitStruct) -{ - /* Set FMPI2C_InitStruct fields to default values */ - FMPI2C_InitStruct->PeripheralMode = LL_FMPI2C_MODE_I2C; - FMPI2C_InitStruct->Timing = 0U; - FMPI2C_InitStruct->AnalogFilter = LL_FMPI2C_ANALOGFILTER_ENABLE; - FMPI2C_InitStruct->DigitalFilter = 0U; - FMPI2C_InitStruct->OwnAddress1 = 0U; - FMPI2C_InitStruct->TypeAcknowledge = LL_FMPI2C_NACK; - FMPI2C_InitStruct->OwnAddrSize = LL_FMPI2C_OWNADDRESS1_7BIT; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C1 */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fsmc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fsmc.c deleted file mode 100644 index 986813744482505..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_fsmc.c +++ /dev/null @@ -1,1009 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fsmc.c - * @author MCD Application Team - * @brief FSMC Low Layer HAL module driver. - * - * This file provides firmware functions to manage the following - * functionalities of the Flexible Static Memory Controller (FSMC) peripheral memories: - * + Initialization/de-initialization functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### FSMC peripheral features ##### - ============================================================================== - [..] The Flexible static memory controller (FSMC) includes two memory controllers: - (+) The NOR/PSRAM memory controller - (+) The NAND/PC Card memory controller - - [..] The FSMC functional block makes the interface with synchronous and asynchronous static - memories, SDRAM memories, and 16-bit PC memory cards. Its main purposes are: - (+) to translate AHB transactions into the appropriate external device protocol. - (+) to meet the access time requirements of the external memory devices. - - [..] All external memories share the addresses, data and control signals with the controller. - Each external device is accessed by means of a unique Chip Select. The FSMC performs - only one access at a time to an external device. - The main features of the FSMC controller are the following: - (+) Interface with static-memory mapped devices including: - (++) Static random access memory (SRAM). - (++) Read-only memory (ROM). - (++) NOR Flash memory/OneNAND Flash memory. - (++) PSRAM (4 memory banks). - (++) 16-bit PC Card compatible devices. - (++) Two banks of NAND Flash memory with ECC hardware to check up to 8 Kbytes of - data. - (+) Independent Chip Select control for each memory bank. - (+) Independent configuration for each memory bank. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup FSMC_LL FSMC Low Layer - * @brief FSMC driver modules - * @{ - */ - -#if defined (HAL_SRAM_MODULE_ENABLED) || defined(HAL_NOR_MODULE_ENABLED) || defined(HAL_NAND_MODULE_ENABLED) || defined(HAL_PCCARD_MODULE_ENABLED) -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup FSMC_LL_Private_Functions - * @{ - */ - -/** @addtogroup FSMC_LL_NORSRAM - * @brief NORSRAM Controller functions - * - @verbatim - ============================================================================== - ##### How to use NORSRAM device driver ##### - ============================================================================== - - [..] - This driver contains a set of APIs to interface with the FSMC NORSRAM banks in order - to run the NORSRAM external devices. - - (+) FSMC NORSRAM bank reset using the function FSMC_NORSRAM_DeInit() - (+) FSMC NORSRAM bank control configuration using the function FSMC_NORSRAM_Init() - (+) FSMC NORSRAM bank timing configuration using the function FSMC_NORSRAM_Timing_Init() - (+) FSMC NORSRAM bank extended timing configuration using the function - FSMC_NORSRAM_Extended_Timing_Init() - (+) FSMC NORSRAM bank enable/disable write operation using the functions - FSMC_NORSRAM_WriteOperation_Enable()/FSMC_NORSRAM_WriteOperation_Disable() - -@endverbatim - * @{ - */ - -/** @addtogroup FSMC_LL_NORSRAM_Private_Functions_Group1 - * @brief Initialization and Configuration functions - * - @verbatim - ============================================================================== - ##### Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the FSMC NORSRAM interface - (+) De-initialize the FSMC NORSRAM interface - (+) Configure the FSMC clock and associated GPIOs - -@endverbatim - * @{ - */ - -/** - * @brief Initialize the FSMC_NORSRAM device according to the specified - * control parameters in the FSMC_NORSRAM_InitTypeDef - * @param Device Pointer to NORSRAM device instance - * @param Init Pointer to NORSRAM Initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NORSRAM_Init(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_InitTypeDef* Init) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FSMC_NORSRAM_BANK(Init->NSBank)); - assert_param(IS_FSMC_MUX(Init->DataAddressMux)); - assert_param(IS_FSMC_MEMORY(Init->MemoryType)); - assert_param(IS_FSMC_NORSRAM_MEMORY_WIDTH(Init->MemoryDataWidth)); - assert_param(IS_FSMC_BURSTMODE(Init->BurstAccessMode)); - assert_param(IS_FSMC_WAIT_POLARITY(Init->WaitSignalPolarity)); -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) - assert_param(IS_FSMC_WRAP_MODE(Init->WrapMode)); -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(Init->WaitSignalActive)); - assert_param(IS_FSMC_WRITE_OPERATION(Init->WriteOperation)); - assert_param(IS_FSMC_WAITE_SIGNAL(Init->WaitSignal)); - assert_param(IS_FSMC_EXTENDED_MODE(Init->ExtendedMode)); - assert_param(IS_FSMC_ASYNWAIT(Init->AsynchronousWait)); - assert_param(IS_FSMC_WRITE_BURST(Init->WriteBurst)); - assert_param(IS_FSMC_PAGESIZE(Init->PageSize)); -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - assert_param(IS_FSMC_WRITE_FIFO(Init->WriteFifo)); - assert_param(IS_FSMC_CONTINOUS_CLOCK(Init->ContinuousClock)); -#endif /* STM32F412Zx || STM32F412Vx || STM32F413xx || STM32F423xx */ - - /* Get the BTCR register value */ - tmpr = Device->BTCR[Init->NSBank]; - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) - /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, WRAPMOD, WAITCFG, WREN, - WAITEN, EXTMOD, ASYNCWAIT, CPSIZE and CBURSTRW bits */ - tmpr &= ((uint32_t)~(FSMC_BCR1_MBKEN | FSMC_BCR1_MUXEN | FSMC_BCR1_MTYP | \ - FSMC_BCR1_MWID | FSMC_BCR1_FACCEN | FSMC_BCR1_BURSTEN | \ - FSMC_BCR1_WAITPOL | FSMC_BCR1_WRAPMOD | FSMC_BCR1_WAITCFG | \ - FSMC_BCR1_WREN | FSMC_BCR1_WAITEN | FSMC_BCR1_EXTMOD | \ - FSMC_BCR1_ASYNCWAIT | FSMC_BCR1_CPSIZE | FSMC_BCR1_CBURSTRW)); - /* Set NORSRAM device control parameters */ - tmpr |= (uint32_t)(Init->DataAddressMux |\ - Init->MemoryType |\ - Init->MemoryDataWidth |\ - Init->BurstAccessMode |\ - Init->WaitSignalPolarity |\ - Init->WrapMode |\ - Init->WaitSignalActive |\ - Init->WriteOperation |\ - Init->WaitSignal |\ - Init->ExtendedMode |\ - Init->AsynchronousWait |\ - Init->PageSize |\ - Init->WriteBurst - ); -#else /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - /* Clear MBKEN, MUXEN, MTYP, MWID, FACCEN, BURSTEN, WAITPOL, WAITCFG, WREN, - WAITEN, EXTMOD, ASYNCWAIT,CPSIZE, CBURSTRW, CCLKEN and WFDIS bits */ - tmpr &= ((uint32_t)~(FSMC_BCR1_MBKEN | FSMC_BCR1_MUXEN | FSMC_BCR1_MTYP | \ - FSMC_BCR1_MWID | FSMC_BCR1_FACCEN | FSMC_BCR1_BURSTEN | \ - FSMC_BCR1_WAITPOL | FSMC_BCR1_WAITCFG | FSMC_BCR1_WREN | \ - FSMC_BCR1_WAITEN | FSMC_BCR1_EXTMOD | FSMC_BCR1_ASYNCWAIT | \ - FSMC_BCR1_CPSIZE | FSMC_BCR1_CBURSTRW | FSMC_BCR1_CCLKEN | \ - FSMC_BCR1_WFDIS)); - /* Set NORSRAM device control parameters */ - tmpr |= (uint32_t)(Init->DataAddressMux |\ - Init->MemoryType |\ - Init->MemoryDataWidth |\ - Init->BurstAccessMode |\ - Init->WaitSignalPolarity |\ - Init->WaitSignalActive |\ - Init->WriteOperation |\ - Init->WaitSignal |\ - Init->ExtendedMode |\ - Init->AsynchronousWait |\ - Init->WriteBurst |\ - Init->ContinuousClock |\ - Init->PageSize |\ - Init->WriteFifo); -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - - if(Init->MemoryType == FSMC_MEMORY_TYPE_NOR) - { - tmpr |= (uint32_t)FSMC_NORSRAM_FLASH_ACCESS_ENABLE; - } - - Device->BTCR[Init->NSBank] = tmpr; - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Configure synchronous mode when Continuous clock is enabled for bank2..4 */ - if((Init->ContinuousClock == FSMC_CONTINUOUS_CLOCK_SYNC_ASYNC) && (Init->NSBank != FSMC_NORSRAM_BANK1)) - { - Device->BTCR[FSMC_NORSRAM_BANK1] |= (uint32_t)(Init->ContinuousClock); - } - - if(Init->NSBank != FSMC_NORSRAM_BANK1) - { - Device->BTCR[FSMC_NORSRAM_BANK1] |= (uint32_t)(Init->WriteFifo); - } -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - - return HAL_OK; -} - -/** - * @brief DeInitialize the FSMC_NORSRAM peripheral - * @param Device Pointer to NORSRAM device instance - * @param ExDevice Pointer to NORSRAM extended mode device instance - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NORSRAM_DeInit(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FSMC_NORSRAM_EXTENDED_DEVICE(ExDevice)); - assert_param(IS_FSMC_NORSRAM_BANK(Bank)); - - /* Disable the FSMC_NORSRAM device */ - __FSMC_NORSRAM_DISABLE(Device, Bank); - - /* De-initialize the FSMC_NORSRAM device */ - /* FSMC_NORSRAM_BANK1 */ - if(Bank == FSMC_NORSRAM_BANK1) - { - Device->BTCR[Bank] = 0x000030DBU; - } - /* FSMC_NORSRAM_BANK2, FSMC_NORSRAM_BANK3 or FSMC_NORSRAM_BANK4 */ - else - { - Device->BTCR[Bank] = 0x000030D2U; - } - - Device->BTCR[Bank + 1U] = 0x0FFFFFFFU; - ExDevice->BWTR[Bank] = 0x0FFFFFFFU; - - return HAL_OK; -} - - -/** - * @brief Initialize the FSMC_NORSRAM Timing according to the specified - * parameters in the FSMC_NORSRAM_TimingTypeDef - * @param Device Pointer to NORSRAM device instance - * @param Timing Pointer to NORSRAM Timing structure - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NORSRAM_Timing_Init(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FSMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime)); - assert_param(IS_FSMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime)); - assert_param(IS_FSMC_DATASETUP_TIME(Timing->DataSetupTime)); - assert_param(IS_FSMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration)); - assert_param(IS_FSMC_CLK_DIV(Timing->CLKDivision)); - assert_param(IS_FSMC_DATA_LATENCY(Timing->DataLatency)); - assert_param(IS_FSMC_ACCESS_MODE(Timing->AccessMode)); - assert_param(IS_FSMC_NORSRAM_BANK(Bank)); - - /* Get the BTCR register value */ - tmpr = Device->BTCR[Bank + 1U]; - - /* Clear ADDSET, ADDHLD, DATAST, BUSTURN, CLKDIV, DATLAT and ACCMOD bits */ - tmpr &= ((uint32_t)~(FSMC_BTR1_ADDSET | FSMC_BTR1_ADDHLD | FSMC_BTR1_DATAST | \ - FSMC_BTR1_BUSTURN | FSMC_BTR1_CLKDIV | FSMC_BTR1_DATLAT | \ - FSMC_BTR1_ACCMOD)); - - /* Set FSMC_NORSRAM device timing parameters */ - tmpr |= (uint32_t)(Timing->AddressSetupTime |\ - ((Timing->AddressHoldTime) << 4U) |\ - ((Timing->DataSetupTime) << 8U) |\ - ((Timing->BusTurnAroundDuration) << 16U) |\ - (((Timing->CLKDivision)-1U) << 20U) |\ - (((Timing->DataLatency)-2U) << 24U) |\ - (Timing->AccessMode)); - - Device->BTCR[Bank + 1] = tmpr; - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Configure Clock division value (in NORSRAM bank 1) when continuous clock is enabled */ - if(HAL_IS_BIT_SET(Device->BTCR[FSMC_NORSRAM_BANK1], FSMC_BCR1_CCLKEN)) - { - tmpr = (uint32_t)(Device->BTCR[FSMC_NORSRAM_BANK1 + 1U] & ~(0x0FU << 20U)); - tmpr |= (uint32_t)(((Timing->CLKDivision)-1U) << 20U); - Device->BTCR[FSMC_NORSRAM_BANK1 + 1U] = tmpr; - } -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - - return HAL_OK; -} - -/** - * @brief Initialize the FSMC_NORSRAM Extended mode Timing according to the specified - * parameters in the FSMC_NORSRAM_TimingTypeDef - * @param Device Pointer to NORSRAM device instance - * @param Timing Pointer to NORSRAM Timing structure - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NORSRAM_Extended_Timing_Init(FSMC_NORSRAM_EXTENDED_TypeDef *Device, FSMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_EXTENDED_MODE(ExtendedMode)); - - /* Set NORSRAM device timing register for write configuration, if extended mode is used */ - if(ExtendedMode == FSMC_EXTENDED_MODE_ENABLE) - { - /* Check the parameters */ - assert_param(IS_FSMC_NORSRAM_EXTENDED_DEVICE(Device)); - assert_param(IS_FSMC_ADDRESS_SETUP_TIME(Timing->AddressSetupTime)); - assert_param(IS_FSMC_ADDRESS_HOLD_TIME(Timing->AddressHoldTime)); - assert_param(IS_FSMC_DATASETUP_TIME(Timing->DataSetupTime)); - assert_param(IS_FSMC_TURNAROUND_TIME(Timing->BusTurnAroundDuration)); - assert_param(IS_FSMC_ACCESS_MODE(Timing->AccessMode)); - assert_param(IS_FSMC_NORSRAM_BANK(Bank)); - - /* Get the BWTR register value */ - tmpr = Device->BWTR[Bank]; - - /* Clear ADDSET, ADDHLD, DATAST, BUSTURN and ACCMOD bits */ - tmpr &= ((uint32_t)~(FSMC_BWTR1_ADDSET | FSMC_BWTR1_ADDHLD | FSMC_BWTR1_DATAST | \ - FSMC_BWTR1_BUSTURN | FSMC_BWTR1_ACCMOD)); - - tmpr |= (uint32_t)(Timing->AddressSetupTime |\ - ((Timing->AddressHoldTime) << 4U) |\ - ((Timing->DataSetupTime) << 8U) |\ - ((Timing->BusTurnAroundDuration) << 16U) |\ - (Timing->AccessMode)); - - Device->BWTR[Bank] = tmpr; - } - else - { - Device->BWTR[Bank] = 0x0FFFFFFFU; - } - - return HAL_OK; -} -/** - * @} - */ - -/** @addtogroup FSMC_LL_NORSRAM_Private_Functions_Group2 - * @brief management functions - * -@verbatim - ============================================================================== - ##### FSMC_NORSRAM Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the FSMC NORSRAM interface. - -@endverbatim - * @{ - */ - -/** - * @brief Enables dynamically FSMC_NORSRAM write operation. - * @param Device Pointer to NORSRAM device instance - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NORSRAM_WriteOperation_Enable(FSMC_NORSRAM_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FSMC_NORSRAM_BANK(Bank)); - - /* Enable write operation */ - Device->BTCR[Bank] |= FSMC_WRITE_OPERATION_ENABLE; - - return HAL_OK; -} - -/** - * @brief Disables dynamically FSMC_NORSRAM write operation. - * @param Device Pointer to NORSRAM device instance - * @param Bank NORSRAM bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NORSRAM_WriteOperation_Disable(FSMC_NORSRAM_TypeDef *Device, uint32_t Bank) -{ - /* Check the parameters */ - assert_param(IS_FSMC_NORSRAM_DEVICE(Device)); - assert_param(IS_FSMC_NORSRAM_BANK(Bank)); - - /* Disable write operation */ - Device->BTCR[Bank] &= ~FSMC_WRITE_OPERATION_ENABLE; - - return HAL_OK; -} -/** - * @} - */ - -/** - * @} - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** @addtogroup FSMC_LL_NAND - * @brief NAND Controller functions - * - @verbatim - ============================================================================== - ##### How to use NAND device driver ##### - ============================================================================== - [..] - This driver contains a set of APIs to interface with the FSMC NAND banks in order - to run the NAND external devices. - - (+) FSMC NAND bank reset using the function FSMC_NAND_DeInit() - (+) FSMC NAND bank control configuration using the function FSMC_NAND_Init() - (+) FSMC NAND bank common space timing configuration using the function - FSMC_NAND_CommonSpace_Timing_Init() - (+) FSMC NAND bank attribute space timing configuration using the function - FSMC_NAND_AttributeSpace_Timing_Init() - (+) FSMC NAND bank enable/disable ECC correction feature using the functions - FSMC_NAND_ECC_Enable()/FSMC_NAND_ECC_Disable() - (+) FSMC NAND bank get ECC correction code using the function FSMC_NAND_GetECC() - -@endverbatim - * @{ - */ - -/** @addtogroup FSMC_LL_NAND_Private_Functions_Group1 - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the FSMC NAND interface - (+) De-initialize the FSMC NAND interface - (+) Configure the FSMC clock and associated GPIOs - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the FSMC_NAND device according to the specified - * control parameters in the FSMC_NAND_HandleTypeDef - * @param Device Pointer to NAND device instance - * @param Init Pointer to NAND Initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NAND_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_InitTypeDef *Init) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_NAND_BANK(Init->NandBank)); - assert_param(IS_FSMC_WAIT_FEATURE(Init->Waitfeature)); - assert_param(IS_FSMC_NAND_MEMORY_WIDTH(Init->MemoryDataWidth)); - assert_param(IS_FSMC_ECC_STATE(Init->EccComputation)); - assert_param(IS_FSMC_ECCPAGE_SIZE(Init->ECCPageSize)); - assert_param(IS_FSMC_TCLR_TIME(Init->TCLRSetupTime)); - assert_param(IS_FSMC_TAR_TIME(Init->TARSetupTime)); - - if(Init->NandBank == FSMC_NAND_BANK2) - { - /* Get the NAND bank 2 register value */ - tmpr = Device->PCR2; - } - else - { - /* Get the NAND bank 3 register value */ - tmpr = Device->PCR3; - } - - /* Clear PWAITEN, PBKEN, PTYP, PWID, ECCEN, TCLR, TAR and ECCPS bits */ - tmpr &= ((uint32_t)~(FSMC_PCR2_PWAITEN | FSMC_PCR2_PBKEN | FSMC_PCR2_PTYP | \ - FSMC_PCR2_PWID | FSMC_PCR2_ECCEN | FSMC_PCR2_TCLR | \ - FSMC_PCR2_TAR | FSMC_PCR2_ECCPS)); - - /* Set NAND device control parameters */ - tmpr |= (uint32_t)(Init->Waitfeature |\ - FSMC_PCR_MEMORY_TYPE_NAND |\ - Init->MemoryDataWidth |\ - Init->EccComputation |\ - Init->ECCPageSize |\ - ((Init->TCLRSetupTime) << 9U) |\ - ((Init->TARSetupTime) << 13U)); - - if(Init->NandBank == FSMC_NAND_BANK2) - { - /* NAND bank 2 registers configuration */ - Device->PCR2 = tmpr; - } - else - { - /* NAND bank 3 registers configuration */ - Device->PCR3 = tmpr; - } - - return HAL_OK; -} - -/** - * @brief Initializes the FSMC_NAND Common space Timing according to the specified - * parameters in the FSMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to NAND device instance - * @param Timing Pointer to NAND timing structure - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NAND_CommonSpace_Timing_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); - - if(Bank == FSMC_NAND_BANK2) - { - /* Get the NAND bank 2 register value */ - tmpr = Device->PMEM2; - } - else - { - /* Get the NAND bank 3 register value */ - tmpr = Device->PMEM3; - } - - /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ - tmpr &= ((uint32_t)~(FSMC_PMEM2_MEMSET2 | FSMC_PMEM2_MEMWAIT2 | FSMC_PMEM2_MEMHOLD2 | \ - FSMC_PMEM2_MEMHIZ2)); - - /* Set FSMC_NAND device timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U) - ); - - if(Bank == FSMC_NAND_BANK2) - { - /* NAND bank 2 registers configuration */ - Device->PMEM2 = tmpr; - } - else - { - /* NAND bank 3 registers configuration */ - Device->PMEM3 = tmpr; - } - - return HAL_OK; -} - -/** - * @brief Initializes the FSMC_NAND Attribute space Timing according to the specified - * parameters in the FSMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to NAND device instance - * @param Timing Pointer to NAND timing structure - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NAND_AttributeSpace_Timing_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); - - if(Bank == FSMC_NAND_BANK2) - { - /* Get the NAND bank 2 register value */ - tmpr = Device->PATT2; - } - else - { - /* Get the NAND bank 3 register value */ - tmpr = Device->PATT3; - } - - /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ - tmpr &= ((uint32_t)~(FSMC_PATT2_ATTSET2 | FSMC_PATT2_ATTWAIT2 | FSMC_PATT2_ATTHOLD2 | \ - FSMC_PATT2_ATTHIZ2)); - - /* Set FSMC_NAND device timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U) - ); - - if(Bank == FSMC_NAND_BANK2) - { - /* NAND bank 2 registers configuration */ - Device->PATT2 = tmpr; - } - else - { - /* NAND bank 3 registers configuration */ - Device->PATT3 = tmpr; - } - - return HAL_OK; -} - -/** - * @brief DeInitializes the FSMC_NAND device - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NAND_DeInit(FSMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Disable the NAND Bank */ - __FSMC_NAND_DISABLE(Device, Bank); - - /* De-initialize the NAND Bank */ - if(Bank == FSMC_NAND_BANK2) - { - /* Set the FSMC_NAND_BANK2 registers to their reset values */ - Device->PCR2 = 0x00000018U; - Device->SR2 = 0x00000040U; - Device->PMEM2 = 0xFCFCFCFCU; - Device->PATT2 = 0xFCFCFCFCU; - } - /* FSMC_Bank3_NAND */ - else - { - /* Set the FSMC_NAND_BANK3 registers to their reset values */ - Device->PCR3 = 0x00000018U; - Device->SR3 = 0x00000040U; - Device->PMEM3 = 0xFCFCFCFCU; - Device->PATT3 = 0xFCFCFCFCU; - } - - return HAL_OK; -} -/** - * @} - */ - -/** @addtogroup FSMC_LL_NAND_Private_Functions_Group2 - * @brief management functions - * -@verbatim - ============================================================================== - ##### FSMC_NAND Control functions ##### - ============================================================================== - [..] - This subsection provides a set of functions allowing to control dynamically - the FSMC NAND interface. - -@endverbatim - * @{ - */ - -/** - * @brief Enables dynamically FSMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NAND_ECC_Enable(FSMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Enable ECC feature */ - if(Bank == FSMC_NAND_BANK2) - { - Device->PCR2 |= FSMC_PCR2_ECCEN; - } - else - { - Device->PCR3 |= FSMC_PCR3_ECCEN; - } - - return HAL_OK; -} - -/** - * @brief Disables dynamically FSMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param Bank NAND bank number - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NAND_ECC_Disable(FSMC_NAND_TypeDef *Device, uint32_t Bank) -{ - /* Disable ECC feature */ - if(Bank == FSMC_NAND_BANK2) - { - Device->PCR2 &= ~FSMC_PCR2_ECCEN; - } - else - { - Device->PCR3 &= ~FSMC_PCR3_ECCEN; - } - - return HAL_OK; -} - -/** - * @brief Disables dynamically FSMC_NAND ECC feature. - * @param Device Pointer to NAND device instance - * @param ECCval Pointer to ECC value - * @param Bank NAND bank number - * @param Timeout Timeout wait value - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_NAND_GetECC(FSMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout) -{ - uint32_t tickstart = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_NAND_DEVICE(Device)); - assert_param(IS_FSMC_NAND_BANK(Bank)); - - /* Get tick */ - tickstart = HAL_GetTick(); - - /* Wait until FIFO is empty */ - while(__FSMC_NAND_GET_FLAG(Device, Bank, FSMC_FLAG_FEMPT) == RESET) - { - /* Check for the Timeout */ - if(Timeout != HAL_MAX_DELAY) - { - if((Timeout == 0U)||((HAL_GetTick() - tickstart ) > Timeout)) - { - return HAL_TIMEOUT; - } - } - } - - if(Bank == FSMC_NAND_BANK2) - { - /* Get the ECCR2 register value */ - *ECCval = (uint32_t)Device->ECCR2; - } - else - { - /* Get the ECCR3 register value */ - *ECCval = (uint32_t)Device->ECCR3; - } - - return HAL_OK; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup FSMC_LL_PCCARD - * @brief PCCARD Controller functions - * - @verbatim - ============================================================================== - ##### How to use PCCARD device driver ##### - ============================================================================== - [..] - This driver contains a set of APIs to interface with the FSMC PCCARD bank in order - to run the PCCARD/compact flash external devices. - - (+) FSMC PCCARD bank reset using the function FSMC_PCCARD_DeInit() - (+) FSMC PCCARD bank control configuration using the function FSMC_PCCARD_Init() - (+) FSMC PCCARD bank common space timing configuration using the function - FSMC_PCCARD_CommonSpace_Timing_Init() - (+) FSMC PCCARD bank attribute space timing configuration using the function - FSMC_PCCARD_AttributeSpace_Timing_Init() - (+) FSMC PCCARD bank IO space timing configuration using the function - FSMC_PCCARD_IOSpace_Timing_Init() - -@endverbatim - * @{ - */ - -/** @addtogroup FSMC_LL_PCCARD_Private_Functions_Group1 - * @brief Initialization and Configuration functions - * -@verbatim - ============================================================================== - ##### Initialization and de_initialization functions ##### - ============================================================================== - [..] - This section provides functions allowing to: - (+) Initialize and configure the FSMC PCCARD interface - (+) De-initialize the FSMC PCCARD interface - (+) Configure the FSMC clock and associated GPIOs - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the FSMC_PCCARD device according to the specified - * control parameters in the FSMC_PCCARD_HandleTypeDef - * @param Device Pointer to PCCARD device instance - * @param Init Pointer to PCCARD Initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_PCCARD_Init(FSMC_PCCARD_TypeDef *Device, FSMC_PCCARD_InitTypeDef *Init) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_WAIT_FEATURE(Init->Waitfeature)); - assert_param(IS_FSMC_TCLR_TIME(Init->TCLRSetupTime)); - assert_param(IS_FSMC_TAR_TIME(Init->TARSetupTime)); - - /* Get PCCARD control register value */ - tmpr = Device->PCR4; - - /* Clear TAR, TCLR, PWAITEN and PWID bits */ - tmpr &= ((uint32_t)~(FSMC_PCR4_TAR | FSMC_PCR4_TCLR | FSMC_PCR4_PWAITEN | \ - FSMC_PCR4_PWID | FSMC_PCR4_PTYP)); - - /* Set FSMC_PCCARD device control parameters */ - tmpr |= (uint32_t)(Init->Waitfeature |\ - FSMC_NAND_PCC_MEM_BUS_WIDTH_16 |\ - (Init->TCLRSetupTime << 9U) |\ - (Init->TARSetupTime << 13U)); - - Device->PCR4 = tmpr; - - return HAL_OK; -} - -/** - * @brief Initializes the FSMC_PCCARD Common space Timing according to the specified - * parameters in the FSMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to PCCARD device instance - * @param Timing Pointer to PCCARD timing structure - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_PCCARD_CommonSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); - - /* Get PCCARD common space timing register value */ - tmpr = Device->PMEM4; - - /* Clear MEMSETx, MEMWAITx, MEMHOLDx and MEMHIZx bits */ - tmpr &= ((uint32_t)~(FSMC_PMEM4_MEMSET4 | FSMC_PMEM4_MEMWAIT4 | FSMC_PMEM4_MEMHOLD4 | \ - FSMC_PMEM4_MEMHIZ4)); - /* Set PCCARD timing parameters */ - tmpr |= (uint32_t)((Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - (Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U)); - - Device->PMEM4 = tmpr; - - return HAL_OK; -} - -/** - * @brief Initializes the FSMC_PCCARD Attribute space Timing according to the specified - * parameters in the FSMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to PCCARD device instance - * @param Timing Pointer to PCCARD timing structure - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_PCCARD_AttributeSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); - - /* Get PCCARD timing parameters */ - tmpr = Device->PATT4; - - /* Clear ATTSETx, ATTWAITx, ATTHOLDx and ATTHIZx bits */ - tmpr &= ((uint32_t)~(FSMC_PATT4_ATTSET4 | FSMC_PATT4_ATTWAIT4 | FSMC_PATT4_ATTHOLD4 | \ - FSMC_PATT4_ATTHIZ4)); - - /* Set PCCARD timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U)); - Device->PATT4 = tmpr; - - return HAL_OK; -} - -/** - * @brief Initializes the FSMC_PCCARD IO space Timing according to the specified - * parameters in the FSMC_NAND_PCC_TimingTypeDef - * @param Device Pointer to PCCARD device instance - * @param Timing Pointer to PCCARD timing structure - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_PCCARD_IOSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing) -{ - uint32_t tmpr = 0U; - - /* Check the parameters */ - assert_param(IS_FSMC_SETUP_TIME(Timing->SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(Timing->WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(Timing->HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(Timing->HiZSetupTime)); - - /* Get FSMC_PCCARD device timing parameters */ - tmpr = Device->PIO4; - - /* Clear IOSET4, IOWAIT4, IOHOLD4 and IOHIZ4 bits */ - tmpr &= ((uint32_t)~(FSMC_PIO4_IOSET4 | FSMC_PIO4_IOWAIT4 | FSMC_PIO4_IOHOLD4 | \ - FSMC_PIO4_IOHIZ4)); - - /* Set FSMC_PCCARD device timing parameters */ - tmpr |= (uint32_t)(Timing->SetupTime |\ - ((Timing->WaitSetupTime) << 8U) |\ - ((Timing->HoldSetupTime) << 16U) |\ - ((Timing->HiZSetupTime) << 24U)); - - Device->PIO4 = tmpr; - - return HAL_OK; -} - -/** - * @brief DeInitializes the FSMC_PCCARD device - * @param Device Pointer to PCCARD device instance - * @retval HAL status - */ -HAL_StatusTypeDef FSMC_PCCARD_DeInit(FSMC_PCCARD_TypeDef *Device) -{ - /* Disable the FSMC_PCCARD device */ - __FSMC_PCCARD_DISABLE(Device); - - /* De-initialize the FSMC_PCCARD device */ - Device->PCR4 = 0x00000018U; - Device->SR4 = 0x00000000U; - Device->PMEM4 = 0xFCFCFCFCU; - Device->PATT4 = 0xFCFCFCFCU; - Device->PIO4 = 0xFCFCFCFCU; - - return HAL_OK; -} -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx || STM32F413xx || STM32F423xx */ -#endif /* HAL_SRAM_MODULE_ENABLED || HAL_NOR_MODULE_ENABLED || HAL_NAND_MODULE_ENABLED || HAL_PCCARD_MODULE_ENABLED */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_gpio.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_gpio.c deleted file mode 100644 index bfdcb1e6eef5784..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_gpio.c +++ /dev/null @@ -1,305 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_gpio.c - * @author MCD Application Team - * @brief GPIO LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_gpio.h" -#include "stm32f4xx_ll_bus.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) - -/** @addtogroup GPIO_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup GPIO_LL_Private_Macros - * @{ - */ -#define IS_LL_GPIO_PIN(__VALUE__) (((0x00000000U) < (__VALUE__)) && ((__VALUE__) <= (LL_GPIO_PIN_ALL))) - -#define IS_LL_GPIO_MODE(__VALUE__) (((__VALUE__) == LL_GPIO_MODE_INPUT) ||\ - ((__VALUE__) == LL_GPIO_MODE_OUTPUT) ||\ - ((__VALUE__) == LL_GPIO_MODE_ALTERNATE) ||\ - ((__VALUE__) == LL_GPIO_MODE_ANALOG)) - -#define IS_LL_GPIO_OUTPUT_TYPE(__VALUE__) (((__VALUE__) == LL_GPIO_OUTPUT_PUSHPULL) ||\ - ((__VALUE__) == LL_GPIO_OUTPUT_OPENDRAIN)) - -#define IS_LL_GPIO_SPEED(__VALUE__) (((__VALUE__) == LL_GPIO_SPEED_FREQ_LOW) ||\ - ((__VALUE__) == LL_GPIO_SPEED_FREQ_MEDIUM) ||\ - ((__VALUE__) == LL_GPIO_SPEED_FREQ_HIGH) ||\ - ((__VALUE__) == LL_GPIO_SPEED_FREQ_VERY_HIGH)) - -#define IS_LL_GPIO_PULL(__VALUE__) (((__VALUE__) == LL_GPIO_PULL_NO) ||\ - ((__VALUE__) == LL_GPIO_PULL_UP) ||\ - ((__VALUE__) == LL_GPIO_PULL_DOWN)) - -#define IS_LL_GPIO_ALTERNATE(__VALUE__) (((__VALUE__) == LL_GPIO_AF_0 ) ||\ - ((__VALUE__) == LL_GPIO_AF_1 ) ||\ - ((__VALUE__) == LL_GPIO_AF_2 ) ||\ - ((__VALUE__) == LL_GPIO_AF_3 ) ||\ - ((__VALUE__) == LL_GPIO_AF_4 ) ||\ - ((__VALUE__) == LL_GPIO_AF_5 ) ||\ - ((__VALUE__) == LL_GPIO_AF_6 ) ||\ - ((__VALUE__) == LL_GPIO_AF_7 ) ||\ - ((__VALUE__) == LL_GPIO_AF_8 ) ||\ - ((__VALUE__) == LL_GPIO_AF_9 ) ||\ - ((__VALUE__) == LL_GPIO_AF_10 ) ||\ - ((__VALUE__) == LL_GPIO_AF_11 ) ||\ - ((__VALUE__) == LL_GPIO_AF_12 ) ||\ - ((__VALUE__) == LL_GPIO_AF_13 ) ||\ - ((__VALUE__) == LL_GPIO_AF_14 ) ||\ - ((__VALUE__) == LL_GPIO_AF_15 )) -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup GPIO_LL_Exported_Functions - * @{ - */ - -/** @addtogroup GPIO_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize GPIO registers (Registers restored to their default values). - * @param GPIOx GPIO Port - * @retval An ErrorStatus enumeration value: - * - SUCCESS: GPIO registers are de-initialized - * - ERROR: Wrong GPIO Port - */ -ErrorStatus LL_GPIO_DeInit(GPIO_TypeDef *GPIOx) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); - - /* Force and Release reset on clock of GPIOx Port */ - if (GPIOx == GPIOA) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOA); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOA); - } - else if (GPIOx == GPIOB) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOB); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOB); - } - else if (GPIOx == GPIOC) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOC); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOC); - } -#if defined(GPIOD) - else if (GPIOx == GPIOD) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOD); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOD); - } -#endif /* GPIOD */ -#if defined(GPIOE) - else if (GPIOx == GPIOE) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOE); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOE); - } -#endif /* GPIOE */ -#if defined(GPIOF) - else if (GPIOx == GPIOF) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOF); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOF); - } -#endif /* GPIOF */ -#if defined(GPIOG) - else if (GPIOx == GPIOG) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOG); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOG); - } -#endif /* GPIOG */ -#if defined(GPIOH) - else if (GPIOx == GPIOH) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOH); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOH); - } -#endif /* GPIOH */ -#if defined(GPIOI) - else if (GPIOx == GPIOI) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOI); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOI); - } -#endif /* GPIOI */ -#if defined(GPIOJ) - else if (GPIOx == GPIOJ) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOJ); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOJ); - } -#endif /* GPIOJ */ -#if defined(GPIOK) - else if (GPIOx == GPIOK) - { - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_GPIOK); - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_GPIOK); - } -#endif /* GPIOK */ - else - { - status = ERROR; - } - - return (status); -} - -/** - * @brief Initialize GPIO registers according to the specified parameters in GPIO_InitStruct. - * @param GPIOx GPIO Port - * @param GPIO_InitStruct pointer to a @ref LL_GPIO_InitTypeDef structure - * that contains the configuration information for the specified GPIO peripheral. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: GPIO registers are initialized according to GPIO_InitStruct content - * - ERROR: Not applicable - */ -ErrorStatus LL_GPIO_Init(GPIO_TypeDef *GPIOx, LL_GPIO_InitTypeDef *GPIO_InitStruct) -{ - uint32_t pinpos = 0x00000000U; - uint32_t currentpin = 0x00000000U; - - /* Check the parameters */ - assert_param(IS_GPIO_ALL_INSTANCE(GPIOx)); - assert_param(IS_LL_GPIO_PIN(GPIO_InitStruct->Pin)); - assert_param(IS_LL_GPIO_MODE(GPIO_InitStruct->Mode)); - assert_param(IS_LL_GPIO_PULL(GPIO_InitStruct->Pull)); - - /* ------------------------- Configure the port pins ---------------- */ - /* Initialize pinpos on first pin set */ - pinpos = POSITION_VAL(GPIO_InitStruct->Pin); - - /* Configure the port pins */ - while (((GPIO_InitStruct->Pin) >> pinpos) != 0x00000000U) - { - /* Get current io position */ - currentpin = (GPIO_InitStruct->Pin) & (0x00000001U << pinpos); - - if (currentpin) - { - - if ((GPIO_InitStruct->Mode == LL_GPIO_MODE_OUTPUT) || (GPIO_InitStruct->Mode == LL_GPIO_MODE_ALTERNATE)) - { - /* Check Speed mode parameters */ - assert_param(IS_LL_GPIO_SPEED(GPIO_InitStruct->Speed)); - - /* Speed mode configuration */ - LL_GPIO_SetPinSpeed(GPIOx, currentpin, GPIO_InitStruct->Speed); - - /* Check Output mode parameters */ - assert_param(IS_LL_GPIO_OUTPUT_TYPE(GPIO_InitStruct->OutputType)); - - /* Output mode configuration*/ - LL_GPIO_SetPinOutputType(GPIOx, currentpin, GPIO_InitStruct->OutputType); - } - - /* Pull-up Pull down resistor configuration*/ - LL_GPIO_SetPinPull(GPIOx, currentpin, GPIO_InitStruct->Pull); - - if (GPIO_InitStruct->Mode == LL_GPIO_MODE_ALTERNATE) - { - /* Check Alternate parameter */ - assert_param(IS_LL_GPIO_ALTERNATE(GPIO_InitStruct->Alternate)); - - /* Speed mode configuration */ - if (POSITION_VAL(currentpin) < 0x00000008U) - { - LL_GPIO_SetAFPin_0_7(GPIOx, currentpin, GPIO_InitStruct->Alternate); - } - else - { - LL_GPIO_SetAFPin_8_15(GPIOx, currentpin, GPIO_InitStruct->Alternate); - } - } - - /* Pin Mode configuration */ - LL_GPIO_SetPinMode(GPIOx, currentpin, GPIO_InitStruct->Mode); - } - pinpos++; - } - - return (SUCCESS); -} - -/** - * @brief Set each @ref LL_GPIO_InitTypeDef field to default value. - * @param GPIO_InitStruct pointer to a @ref LL_GPIO_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ - -void LL_GPIO_StructInit(LL_GPIO_InitTypeDef *GPIO_InitStruct) -{ - /* Reset GPIO init structure parameters values */ - GPIO_InitStruct->Pin = LL_GPIO_PIN_ALL; - GPIO_InitStruct->Mode = LL_GPIO_MODE_ANALOG; - GPIO_InitStruct->Speed = LL_GPIO_SPEED_FREQ_LOW; - GPIO_InitStruct->OutputType = LL_GPIO_OUTPUT_PUSHPULL; - GPIO_InitStruct->Pull = LL_GPIO_PULL_NO; - GPIO_InitStruct->Alternate = LL_GPIO_AF_0; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_i2c.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_i2c.c deleted file mode 100644 index 125fb2ca13fc7a5..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_i2c.c +++ /dev/null @@ -1,253 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_i2c.c - * @author MCD Application Team - * @brief I2C LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_i2c.h" -#include "stm32f4xx_ll_bus.h" -#include "stm32f4xx_ll_rcc.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (I2C1) || defined (I2C2) || defined (I2C3) - -/** @defgroup I2C_LL I2C - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup I2C_LL_Private_Macros - * @{ - */ - -#define IS_LL_I2C_PERIPHERAL_MODE(__VALUE__) (((__VALUE__) == LL_I2C_MODE_I2C) || \ - ((__VALUE__) == LL_I2C_MODE_SMBUS_HOST) || \ - ((__VALUE__) == LL_I2C_MODE_SMBUS_DEVICE) || \ - ((__VALUE__) == LL_I2C_MODE_SMBUS_DEVICE_ARP)) - -#define IS_LL_I2C_CLOCK_SPEED(__VALUE__) (((__VALUE__) > 0U) && ((__VALUE__) <= LL_I2C_MAX_SPEED_FAST)) - -#define IS_LL_I2C_DUTY_CYCLE(__VALUE__) (((__VALUE__) == LL_I2C_DUTYCYCLE_2) || \ - ((__VALUE__) == LL_I2C_DUTYCYCLE_16_9)) - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -#define IS_LL_I2C_ANALOG_FILTER(__VALUE__) (((__VALUE__) == LL_I2C_ANALOGFILTER_ENABLE) || \ - ((__VALUE__) == LL_I2C_ANALOGFILTER_DISABLE)) - -#define IS_LL_I2C_DIGITAL_FILTER(__VALUE__) ((__VALUE__) <= 0x0000000FU) - -#endif -#define IS_LL_I2C_OWN_ADDRESS1(__VALUE__) ((__VALUE__) <= 0x000003FFU) - -#define IS_LL_I2C_TYPE_ACKNOWLEDGE(__VALUE__) (((__VALUE__) == LL_I2C_ACK) || \ - ((__VALUE__) == LL_I2C_NACK)) - -#define IS_LL_I2C_OWN_ADDRSIZE(__VALUE__) (((__VALUE__) == LL_I2C_OWNADDRESS1_7BIT) || \ - ((__VALUE__) == LL_I2C_OWNADDRESS1_10BIT)) -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2C_LL_Exported_Functions - * @{ - */ - -/** @addtogroup I2C_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize the I2C registers to their default reset values. - * @param I2Cx I2C Instance. - * @retval An ErrorStatus enumeration value: - * - SUCCESS I2C registers are de-initialized - * - ERROR I2C registers are not de-initialized - */ -uint32_t LL_I2C_DeInit(I2C_TypeDef *I2Cx) -{ - ErrorStatus status = SUCCESS; - - /* Check the I2C Instance I2Cx */ - assert_param(IS_I2C_ALL_INSTANCE(I2Cx)); - - if (I2Cx == I2C1) - { - /* Force reset of I2C clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C1); - - /* Release reset of I2C clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C1); - } - else if (I2Cx == I2C2) - { - /* Force reset of I2C clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C2); - - /* Release reset of I2C clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C2); - - } -#if defined(I2C3) - else if (I2Cx == I2C3) - { - /* Force reset of I2C clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_I2C3); - - /* Release reset of I2C clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_I2C3); - } -#endif - else - { - status = ERROR; - } - - return status; -} - -/** - * @brief Initialize the I2C registers according to the specified parameters in I2C_InitStruct. - * @param I2Cx I2C Instance. - * @param I2C_InitStruct pointer to a @ref LL_I2C_InitTypeDef structure. - * @retval An ErrorStatus enumeration value: - * - SUCCESS I2C registers are initialized - * - ERROR Not applicable - */ -uint32_t LL_I2C_Init(I2C_TypeDef *I2Cx, LL_I2C_InitTypeDef *I2C_InitStruct) -{ - LL_RCC_ClocksTypeDef rcc_clocks; - - /* Check the I2C Instance I2Cx */ - assert_param(IS_I2C_ALL_INSTANCE(I2Cx)); - - /* Check the I2C parameters from I2C_InitStruct */ - assert_param(IS_LL_I2C_PERIPHERAL_MODE(I2C_InitStruct->PeripheralMode)); - assert_param(IS_LL_I2C_CLOCK_SPEED(I2C_InitStruct->ClockSpeed)); - assert_param(IS_LL_I2C_DUTY_CYCLE(I2C_InitStruct->DutyCycle)); -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) - assert_param(IS_LL_I2C_ANALOG_FILTER(I2C_InitStruct->AnalogFilter)); - assert_param(IS_LL_I2C_DIGITAL_FILTER(I2C_InitStruct->DigitalFilter)); -#endif - assert_param(IS_LL_I2C_OWN_ADDRESS1(I2C_InitStruct->OwnAddress1)); - assert_param(IS_LL_I2C_TYPE_ACKNOWLEDGE(I2C_InitStruct->TypeAcknowledge)); - assert_param(IS_LL_I2C_OWN_ADDRSIZE(I2C_InitStruct->OwnAddrSize)); - - /* Disable the selected I2Cx Peripheral */ - LL_I2C_Disable(I2Cx); - - /* Retrieve Clock frequencies */ - LL_RCC_GetSystemClocksFreq(&rcc_clocks); - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) - /*---------------------------- I2Cx FLTR Configuration ----------------------- - * Configure the analog and digital noise filters with parameters : - * - AnalogFilter: I2C_FLTR_ANFOFF bit - * - DigitalFilter: I2C_FLTR_DNF[3:0] bits - */ - LL_I2C_ConfigFilters(I2Cx, I2C_InitStruct->AnalogFilter, I2C_InitStruct->DigitalFilter); - -#endif - /*---------------------------- I2Cx SCL Clock Speed Configuration ------------ - * Configure the SCL speed : - * - ClockSpeed: I2C_CR2_FREQ[5:0], I2C_TRISE_TRISE[5:0], I2C_CCR_FS, - * and I2C_CCR_CCR[11:0] bits - * - DutyCycle: I2C_CCR_DUTY[7:0] bits - */ - LL_I2C_ConfigSpeed(I2Cx, rcc_clocks.PCLK1_Frequency, I2C_InitStruct->ClockSpeed, I2C_InitStruct->DutyCycle); - - /*---------------------------- I2Cx OAR1 Configuration ----------------------- - * Disable, Configure and Enable I2Cx device own address 1 with parameters : - * - OwnAddress1: I2C_OAR1_ADD[9:8], I2C_OAR1_ADD[7:1] and I2C_OAR1_ADD0 bits - * - OwnAddrSize: I2C_OAR1_ADDMODE bit - */ - LL_I2C_SetOwnAddress1(I2Cx, I2C_InitStruct->OwnAddress1, I2C_InitStruct->OwnAddrSize); - - /*---------------------------- I2Cx MODE Configuration ----------------------- - * Configure I2Cx peripheral mode with parameter : - * - PeripheralMode: I2C_CR1_SMBUS, I2C_CR1_SMBTYPE and I2C_CR1_ENARP bits - */ - LL_I2C_SetMode(I2Cx, I2C_InitStruct->PeripheralMode); - - /* Enable the selected I2Cx Peripheral */ - LL_I2C_Enable(I2Cx); - - /*---------------------------- I2Cx CR2 Configuration ------------------------ - * Configure the ACKnowledge or Non ACKnowledge condition - * after the address receive match code or next received byte with parameter : - * - TypeAcknowledge: I2C_CR2_NACK bit - */ - LL_I2C_AcknowledgeNextData(I2Cx, I2C_InitStruct->TypeAcknowledge); - - return SUCCESS; -} - -/** - * @brief Set each @ref LL_I2C_InitTypeDef field to default value. - * @param I2C_InitStruct Pointer to a @ref LL_I2C_InitTypeDef structure. - * @retval None - */ -void LL_I2C_StructInit(LL_I2C_InitTypeDef *I2C_InitStruct) -{ - /* Set I2C_InitStruct fields to default values */ - I2C_InitStruct->PeripheralMode = LL_I2C_MODE_I2C; - I2C_InitStruct->ClockSpeed = 5000U; - I2C_InitStruct->DutyCycle = LL_I2C_DUTYCYCLE_2; -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) - I2C_InitStruct->AnalogFilter = LL_I2C_ANALOGFILTER_ENABLE; - I2C_InitStruct->DigitalFilter = 0U; -#endif - I2C_InitStruct->OwnAddress1 = 0U; - I2C_InitStruct->TypeAcknowledge = LL_I2C_NACK; - I2C_InitStruct->OwnAddrSize = LL_I2C_OWNADDRESS1_7BIT; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* I2C1 || I2C2 || I2C3 */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_lptim.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_lptim.c deleted file mode 100644 index 780961d58c63f51..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_lptim.c +++ /dev/null @@ -1,300 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_lptim.c - * @author MCD Application Team - * @brief LPTIM LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_lptim.h" -#include "stm32f4xx_ll_bus.h" -#include "stm32f4xx_ll_rcc.h" - - -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (LPTIM1) - -/** @addtogroup LPTIM_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup LPTIM_LL_Private_Macros - * @{ - */ -#define IS_LL_LPTIM_CLOCK_SOURCE(__VALUE__) (((__VALUE__) == LL_LPTIM_CLK_SOURCE_INTERNAL) \ - || ((__VALUE__) == LL_LPTIM_CLK_SOURCE_EXTERNAL)) - -#define IS_LL_LPTIM_CLOCK_PRESCALER(__VALUE__) (((__VALUE__) == LL_LPTIM_PRESCALER_DIV1) \ - || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV2) \ - || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV4) \ - || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV8) \ - || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV16) \ - || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV32) \ - || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV64) \ - || ((__VALUE__) == LL_LPTIM_PRESCALER_DIV128)) - -#define IS_LL_LPTIM_WAVEFORM(__VALUE__) (((__VALUE__) == LL_LPTIM_OUTPUT_WAVEFORM_PWM) \ - || ((__VALUE__) == LL_LPTIM_OUTPUT_WAVEFORM_SETONCE)) - -#define IS_LL_LPTIM_OUTPUT_POLARITY(__VALUE__) (((__VALUE__) == LL_LPTIM_OUTPUT_POLARITY_REGULAR) \ - || ((__VALUE__) == LL_LPTIM_OUTPUT_POLARITY_INVERSE)) -/** - * @} - */ - - -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Functions LPTIM Private Functions - * @{ - */ -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup LPTIM_LL_Exported_Functions - * @{ - */ - -/** @addtogroup LPTIM_LL_EF_Init - * @{ - */ - -/** - * @brief Set LPTIMx registers to their reset values. - * @param LPTIMx LP Timer instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: LPTIMx registers are de-initialized - * - ERROR: invalid LPTIMx instance - */ -ErrorStatus LL_LPTIM_DeInit(LPTIM_TypeDef *LPTIMx) -{ - ErrorStatus result = SUCCESS; - - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(LPTIMx)); - - if (LPTIMx == LPTIM1) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_LPTIM1); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_LPTIM1); - } - else - { - result = ERROR; - } - - return result; -} - -/** - * @brief Set each fields of the LPTIM_InitStruct structure to its default - * value. - * @param LPTIM_InitStruct pointer to a @ref LL_LPTIM_InitTypeDef structure - * @retval None - */ -void LL_LPTIM_StructInit(LL_LPTIM_InitTypeDef *LPTIM_InitStruct) -{ - /* Set the default configuration */ - LPTIM_InitStruct->ClockSource = LL_LPTIM_CLK_SOURCE_INTERNAL; - LPTIM_InitStruct->Prescaler = LL_LPTIM_PRESCALER_DIV1; - LPTIM_InitStruct->Waveform = LL_LPTIM_OUTPUT_WAVEFORM_PWM; - LPTIM_InitStruct->Polarity = LL_LPTIM_OUTPUT_POLARITY_REGULAR; -} - -/** - * @brief Configure the LPTIMx peripheral according to the specified parameters. - * @note LL_LPTIM_Init can only be called when the LPTIM instance is disabled. - * @note LPTIMx can be disabled using unitary function @ref LL_LPTIM_Disable(). - * @param LPTIMx LP Timer Instance - * @param LPTIM_InitStruct pointer to a @ref LL_LPTIM_InitTypeDef structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: LPTIMx instance has been initialized - * - ERROR: LPTIMx instance hasn't been initialized - */ -ErrorStatus LL_LPTIM_Init(LPTIM_TypeDef *LPTIMx, LL_LPTIM_InitTypeDef *LPTIM_InitStruct) -{ - ErrorStatus result = SUCCESS; - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(LPTIMx)); - assert_param(IS_LL_LPTIM_CLOCK_SOURCE(LPTIM_InitStruct->ClockSource)); - assert_param(IS_LL_LPTIM_CLOCK_PRESCALER(LPTIM_InitStruct->Prescaler)); - assert_param(IS_LL_LPTIM_WAVEFORM(LPTIM_InitStruct->Waveform)); - assert_param(IS_LL_LPTIM_OUTPUT_POLARITY(LPTIM_InitStruct->Polarity)); - - /* The LPTIMx_CFGR register must only be modified when the LPTIM is disabled - (ENABLE bit is reset to 0). - */ - if (LL_LPTIM_IsEnabled(LPTIMx) == 1UL) - { - result = ERROR; - } - else - { - /* Set CKSEL bitfield according to ClockSource value */ - /* Set PRESC bitfield according to Prescaler value */ - /* Set WAVE bitfield according to Waveform value */ - /* Set WAVEPOL bitfield according to Polarity value */ - MODIFY_REG(LPTIMx->CFGR, - (LPTIM_CFGR_CKSEL | LPTIM_CFGR_PRESC | LPTIM_CFGR_WAVE | LPTIM_CFGR_WAVPOL), - LPTIM_InitStruct->ClockSource | \ - LPTIM_InitStruct->Prescaler | \ - LPTIM_InitStruct->Waveform | \ - LPTIM_InitStruct->Polarity); - } - - return result; -} - -/** - * @brief Disable the LPTIM instance - * @rmtoll CR ENABLE LL_LPTIM_Disable - * @param LPTIMx Low-Power Timer instance - * @note The following sequence is required to solve LPTIM disable HW limitation. - * Please check Errata Sheet ES0335 for more details under "MCU may remain - * stuck in LPTIM interrupt when entering Stop mode" section. - * @retval None - */ -void LL_LPTIM_Disable(LPTIM_TypeDef *LPTIMx) -{ - LL_RCC_ClocksTypeDef rcc_clock; - uint32_t tmpclksource = 0; - uint32_t tmpIER; - uint32_t tmpCFGR; - uint32_t tmpCMP; - uint32_t tmpARR; - uint32_t tmpOR; - - /* Check the parameters */ - assert_param(IS_LPTIM_INSTANCE(LPTIMx)); - - __disable_irq(); - - /********** Save LPTIM Config *********/ - /* Save LPTIM source clock */ - switch ((uint32_t)LPTIMx) - { - case LPTIM1_BASE: - tmpclksource = LL_RCC_GetLPTIMClockSource(LL_RCC_LPTIM1_CLKSOURCE); - break; - default: - break; - } - - /* Save LPTIM configuration registers */ - tmpIER = LPTIMx->IER; - tmpCFGR = LPTIMx->CFGR; - tmpCMP = LPTIMx->CMP; - tmpARR = LPTIMx->ARR; - tmpOR = LPTIMx->OR; - - /************* Reset LPTIM ************/ - (void)LL_LPTIM_DeInit(LPTIMx); - - /********* Restore LPTIM Config *******/ - LL_RCC_GetSystemClocksFreq(&rcc_clock); - - if ((tmpCMP != 0UL) || (tmpARR != 0UL)) - { - /* Force LPTIM source kernel clock from APB */ - switch ((uint32_t)LPTIMx) - { - case LPTIM1_BASE: - LL_RCC_SetLPTIMClockSource(LL_RCC_LPTIM1_CLKSOURCE_PCLK1); - break; - default: - break; - } - - if (tmpCMP != 0UL) - { - /* Restore CMP and ARR registers (LPTIM should be enabled first) */ - LPTIMx->CR |= LPTIM_CR_ENABLE; - LPTIMx->CMP = tmpCMP; - - /* Polling on CMP write ok status after above restore operation */ - do - { - rcc_clock.SYSCLK_Frequency--; /* Used for timeout */ - } while (((LL_LPTIM_IsActiveFlag_CMPOK(LPTIMx) != 1UL)) && ((rcc_clock.SYSCLK_Frequency) > 0UL)); - - LL_LPTIM_ClearFlag_CMPOK(LPTIMx); - } - - if (tmpARR != 0UL) - { - LPTIMx->CR |= LPTIM_CR_ENABLE; - LPTIMx->ARR = tmpARR; - - LL_RCC_GetSystemClocksFreq(&rcc_clock); - /* Polling on ARR write ok status after above restore operation */ - do - { - rcc_clock.SYSCLK_Frequency--; /* Used for timeout */ - } - while (((LL_LPTIM_IsActiveFlag_ARROK(LPTIMx) != 1UL)) && ((rcc_clock.SYSCLK_Frequency) > 0UL)); - - LL_LPTIM_ClearFlag_ARROK(LPTIMx); - } - - - /* Restore LPTIM source kernel clock */ - LL_RCC_SetLPTIMClockSource(tmpclksource); - } - - /* Restore configuration registers (LPTIM should be disabled first) */ - LPTIMx->CR &= ~(LPTIM_CR_ENABLE); - LPTIMx->IER = tmpIER; - LPTIMx->CFGR = tmpCFGR; - LPTIMx->OR = tmpOR; - - __enable_irq(); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* LPTIM1 */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_pwr.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_pwr.c deleted file mode 100644 index fe04bc44c935a60..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_pwr.c +++ /dev/null @@ -1,85 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_pwr.c - * @author MCD Application Team - * @brief PWR LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_pwr.h" -#include "stm32f4xx_ll_bus.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(PWR) - -/** @defgroup PWR_LL PWR - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PWR_LL_Exported_Functions - * @{ - */ - -/** @addtogroup PWR_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize the PWR registers to their default reset values. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: PWR registers are de-initialized - * - ERROR: not applicable - */ -ErrorStatus LL_PWR_DeInit(void) -{ - /* Force reset of PWR clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_PWR); - - /* Release reset of PWR clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_PWR); - - return SUCCESS; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined(PWR) */ -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rcc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rcc.c deleted file mode 100644 index ea18adc325e78b6..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rcc.c +++ /dev/null @@ -1,1663 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rcc.c - * @author MCD Application Team - * @brief RCC LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_rcc.h" -#ifdef USE_FULL_ASSERT - #include "stm32_assert.h" -#else - #define assert_param(expr) ((void)0U) -#endif -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RCC) - -/** @addtogroup RCC_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup RCC_LL_Private_Macros - * @{ - */ -#if defined(FMPI2C1) -#define IS_LL_RCC_FMPI2C_CLKSOURCE(__VALUE__) ((__VALUE__) == LL_RCC_FMPI2C1_CLKSOURCE) -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -#define IS_LL_RCC_LPTIM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_LPTIM1_CLKSOURCE)) -#endif /* LPTIM1 */ - -#if defined(SAI1) -#if defined(RCC_DCKCFGR_SAI1SRC) -#define IS_LL_RCC_SAI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SAI1_CLKSOURCE) \ - || ((__VALUE__) == LL_RCC_SAI2_CLKSOURCE)) -#elif defined(RCC_DCKCFGR_SAI1ASRC) -#define IS_LL_RCC_SAI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SAI1_A_CLKSOURCE) \ - || ((__VALUE__) == LL_RCC_SAI1_B_CLKSOURCE)) -#endif /* RCC_DCKCFGR_SAI1SRC */ -#endif /* SAI1 */ - -#if defined(SDIO) -#define IS_LL_RCC_SDIO_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SDIO_CLKSOURCE)) -#endif /* SDIO */ - -#if defined(RNG) -#define IS_LL_RCC_RNG_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_RNG_CLKSOURCE)) -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -#define IS_LL_RCC_USB_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_USB_CLKSOURCE)) -#endif /* USB_OTG_FS || USB_OTG_HS */ - -#if defined(DFSDM2_Channel0) -#define IS_LL_RCC_DFSDM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_CLKSOURCE)) - -#define IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_AUDIO_CLKSOURCE) \ - || ((__VALUE__) == LL_RCC_DFSDM2_AUDIO_CLKSOURCE)) -#elif defined(DFSDM1_Channel0) -#define IS_LL_RCC_DFSDM_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_CLKSOURCE)) - -#define IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DFSDM1_AUDIO_CLKSOURCE)) -#endif /* DFSDM2_Channel0 */ - -#if defined(RCC_DCKCFGR_I2S2SRC) -#define IS_LL_RCC_I2S_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2S1_CLKSOURCE) \ - || ((__VALUE__) == LL_RCC_I2S2_CLKSOURCE)) -#else -#define IS_LL_RCC_I2S_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_I2S1_CLKSOURCE)) -#endif /* RCC_DCKCFGR_I2S2SRC */ - -#if defined(CEC) -#define IS_LL_RCC_CEC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_CEC_CLKSOURCE)) -#endif /* CEC */ - -#if defined(DSI) -#define IS_LL_RCC_DSI_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_DSI_CLKSOURCE)) -#endif /* DSI */ - -#if defined(LTDC) -#define IS_LL_RCC_LTDC_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_LTDC_CLKSOURCE)) -#endif /* LTDC */ - -#if defined(SPDIFRX) -#define IS_LL_RCC_SPDIFRX_CLKSOURCE(__VALUE__) (((__VALUE__) == LL_RCC_SPDIFRX1_CLKSOURCE)) -#endif /* SPDIFRX */ -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup RCC_LL_Private_Functions RCC Private functions - * @{ - */ -uint32_t RCC_GetSystemClockFreq(void); -uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency); -uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency); -uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency); -uint32_t RCC_PLL_GetFreqDomain_SYS(uint32_t SYSCLK_Source); -uint32_t RCC_PLL_GetFreqDomain_48M(void); -#if defined(RCC_DCKCFGR_I2SSRC) || defined(RCC_DCKCFGR_I2S1SRC) -uint32_t RCC_PLL_GetFreqDomain_I2S(void); -#endif /* RCC_DCKCFGR_I2SSRC || RCC_DCKCFGR_I2S1SRC */ -#if defined(SPDIFRX) -uint32_t RCC_PLL_GetFreqDomain_SPDIFRX(void); -#endif /* SPDIFRX */ -#if defined(RCC_PLLCFGR_PLLR) -#if defined(SAI1) -uint32_t RCC_PLL_GetFreqDomain_SAI(void); -#endif /* SAI1 */ -#endif /* RCC_PLLCFGR_PLLR */ -#if defined(DSI) -uint32_t RCC_PLL_GetFreqDomain_DSI(void); -#endif /* DSI */ -#if defined(RCC_PLLSAI_SUPPORT) -uint32_t RCC_PLLSAI_GetFreqDomain_SAI(void); -#if defined(RCC_PLLSAICFGR_PLLSAIP) -uint32_t RCC_PLLSAI_GetFreqDomain_48M(void); -#endif /* RCC_PLLSAICFGR_PLLSAIP */ -#if defined(LTDC) -uint32_t RCC_PLLSAI_GetFreqDomain_LTDC(void); -#endif /* LTDC */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2S_SUPPORT) -uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void); -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -uint32_t RCC_PLLI2S_GetFreqDomain_48M(void); -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -#if defined(SAI1) -uint32_t RCC_PLLI2S_GetFreqDomain_SAI(void); -#endif /* SAI1 */ -#if defined(SPDIFRX) -uint32_t RCC_PLLI2S_GetFreqDomain_SPDIFRX(void); -#endif /* SPDIFRX */ -#endif /* RCC_PLLI2S_SUPPORT */ -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup RCC_LL_Exported_Functions - * @{ - */ - -/** @addtogroup RCC_LL_EF_Init - * @{ - */ - -/** - * @brief Reset the RCC clock configuration to the default reset state. - * @note The default reset state of the clock configuration is given below: - * - HSI ON and used as system clock source - * - HSE and PLL OFF - * - AHB, APB1 and APB2 prescaler set to 1. - * - CSS, MCO OFF - * - All interrupts disabled - * @note This function doesn't modify the configuration of the - * - Peripheral clocks - * - LSI, LSE and RTC clocks - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RCC registers are de-initialized - * - ERROR: not applicable - */ -ErrorStatus LL_RCC_DeInit(void) -{ - __IO uint32_t vl_mask; - - /* Set HSION bit */ - LL_RCC_HSI_Enable(); - - /* Wait for HSI READY bit */ - while(LL_RCC_HSI_IsReady() != 1U) - {} - - /* Reset CFGR register */ - LL_RCC_WriteReg(CFGR, 0x00000000U); - - /* Read CR register */ - vl_mask = LL_RCC_ReadReg(CR); - - /* Reset HSEON, HSEBYP, PLLON, CSSON bits */ - CLEAR_BIT(vl_mask, - (RCC_CR_HSEON | RCC_CR_HSEBYP | RCC_CR_PLLON | RCC_CR_CSSON)); - -#if defined(RCC_PLLSAI_SUPPORT) - /* Reset PLLSAION bit */ - CLEAR_BIT(vl_mask, RCC_CR_PLLSAION); -#endif /* RCC_PLLSAI_SUPPORT */ - -#if defined(RCC_PLLI2S_SUPPORT) - /* Reset PLLI2SON bit */ - CLEAR_BIT(vl_mask, RCC_CR_PLLI2SON); -#endif /* RCC_PLLI2S_SUPPORT */ - - /* Write new value in CR register */ - LL_RCC_WriteReg(CR, vl_mask); - - /* Set HSITRIM bits to the reset value*/ - LL_RCC_HSI_SetCalibTrimming(0x10U); - - /* Wait for PLL READY bit to be reset */ - while(LL_RCC_PLL_IsReady() != 0U) - {} - - /* Reset PLLCFGR register */ - LL_RCC_WriteReg(PLLCFGR, RCC_PLLCFGR_RST_VALUE); - -#if defined(RCC_PLLI2S_SUPPORT) - /* Reset PLLI2SCFGR register */ - LL_RCC_WriteReg(PLLI2SCFGR, RCC_PLLI2SCFGR_RST_VALUE); -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) - /* Reset PLLSAICFGR register */ - LL_RCC_WriteReg(PLLSAICFGR, RCC_PLLSAICFGR_RST_VALUE); -#endif /* RCC_PLLSAI_SUPPORT */ - - /* Disable all interrupts */ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE | RCC_CIR_LSERDYIE | RCC_CIR_HSIRDYIE | RCC_CIR_HSERDYIE | RCC_CIR_PLLRDYIE); - -#if defined(RCC_CIR_PLLI2SRDYIE) - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -#endif /* RCC_CIR_PLLI2SRDYIE */ - -#if defined(RCC_CIR_PLLSAIRDYIE) - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -#endif /* RCC_CIR_PLLSAIRDYIE */ - - /* Clear all interrupt flags */ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC | RCC_CIR_LSERDYC | RCC_CIR_HSIRDYC | RCC_CIR_HSERDYC | RCC_CIR_PLLRDYC | RCC_CIR_CSSC); - -#if defined(RCC_CIR_PLLI2SRDYC) - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); -#endif /* RCC_CIR_PLLI2SRDYC */ - -#if defined(RCC_CIR_PLLSAIRDYC) - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); -#endif /* RCC_CIR_PLLSAIRDYC */ - - /* Clear LSION bit */ - CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); - - /* Reset all CSR flags */ - SET_BIT(RCC->CSR, RCC_CSR_RMVF); - - return SUCCESS; -} - -/** - * @} - */ - -/** @addtogroup RCC_LL_EF_Get_Freq - * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks - * and different peripheral clocks available on the device. - * @note If SYSCLK source is HSI, function returns values based on HSI_VALUE(**) - * @note If SYSCLK source is HSE, function returns values based on HSE_VALUE(***) - * @note If SYSCLK source is PLL, function returns values based on HSE_VALUE(***) - * or HSI_VALUE(**) multiplied/divided by the PLL factors. - * @note (**) HSI_VALUE is a constant defined in this file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * @note (***) HSE_VALUE is a constant defined in this file (default value - * 25 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * @note The result of this function could be incorrect when using fractional - * value for HSE crystal. - * @note This function can be used by the user application to compute the - * baud-rate for the communication peripherals or configure other parameters. - * @{ - */ - -/** - * @brief Return the frequencies of different on chip clocks; System, AHB, APB1 and APB2 buses clocks - * @note Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function - * must be called to update structure fields. Otherwise, any - * configuration based on this function will be incorrect. - * @param RCC_Clocks pointer to a @ref LL_RCC_ClocksTypeDef structure which will hold the clocks frequencies - * @retval None - */ -void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks) -{ - /* Get SYSCLK frequency */ - RCC_Clocks->SYSCLK_Frequency = RCC_GetSystemClockFreq(); - - /* HCLK clock frequency */ - RCC_Clocks->HCLK_Frequency = RCC_GetHCLKClockFreq(RCC_Clocks->SYSCLK_Frequency); - - /* PCLK1 clock frequency */ - RCC_Clocks->PCLK1_Frequency = RCC_GetPCLK1ClockFreq(RCC_Clocks->HCLK_Frequency); - - /* PCLK2 clock frequency */ - RCC_Clocks->PCLK2_Frequency = RCC_GetPCLK2ClockFreq(RCC_Clocks->HCLK_Frequency); -} - -#if defined(FMPI2C1) -/** - * @brief Return FMPI2Cx clock frequency - * @param FMPI2CxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE - * @retval FMPI2C clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that HSI oscillator is not ready - */ -uint32_t LL_RCC_GetFMPI2CClockFreq(uint32_t FMPI2CxSource) -{ - uint32_t FMPI2C_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_FMPI2C_CLKSOURCE(FMPI2CxSource)); - - if (FMPI2CxSource == LL_RCC_FMPI2C1_CLKSOURCE) - { - /* FMPI2C1 CLK clock frequency */ - switch (LL_RCC_GetFMPI2CClockSource(FMPI2CxSource)) - { - case LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK: /* FMPI2C1 Clock is System Clock */ - FMPI2C_frequency = RCC_GetSystemClockFreq(); - break; - - case LL_RCC_FMPI2C1_CLKSOURCE_HSI: /* FMPI2C1 Clock is HSI Osc. */ - if (LL_RCC_HSI_IsReady()) - { - FMPI2C_frequency = HSI_VALUE; - } - break; - - case LL_RCC_FMPI2C1_CLKSOURCE_PCLK1: /* FMPI2C1 Clock is PCLK1 */ - default: - FMPI2C_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq())); - break; - } - } - - return FMPI2C_frequency; -} -#endif /* FMPI2C1 */ - -/** - * @brief Return I2Sx clock frequency - * @param I2SxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE - * @arg @ref LL_RCC_I2S2_CLKSOURCE (*) - * - * (*) value not defined in all devices. - * @retval I2S clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready - */ -uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource) -{ - uint32_t i2s_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_I2S_CLKSOURCE(I2SxSource)); - - if (I2SxSource == LL_RCC_I2S1_CLKSOURCE) - { - /* I2S1 CLK clock frequency */ - switch (LL_RCC_GetI2SClockSource(I2SxSource)) - { -#if defined(RCC_PLLI2S_SUPPORT) - case LL_RCC_I2S1_CLKSOURCE_PLLI2S: /* I2S1 Clock is PLLI2S */ - if (LL_RCC_PLLI2S_IsReady()) - { - i2s_frequency = RCC_PLLI2S_GetFreqDomain_I2S(); - } - break; -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_DCKCFGR_I2SSRC) || defined(RCC_DCKCFGR_I2S1SRC) - case LL_RCC_I2S1_CLKSOURCE_PLL: /* I2S1 Clock is PLL */ - if (LL_RCC_PLL_IsReady()) - { - i2s_frequency = RCC_PLL_GetFreqDomain_I2S(); - } - break; - - case LL_RCC_I2S1_CLKSOURCE_PLLSRC: /* I2S1 Clock is PLL Main source */ - switch (LL_RCC_PLL_GetMainSource()) - { - case LL_RCC_PLLSOURCE_HSE: /* I2S1 Clock is HSE Osc. */ - if (LL_RCC_HSE_IsReady()) - { - i2s_frequency = HSE_VALUE; - } - break; - - case LL_RCC_PLLSOURCE_HSI: /* I2S1 Clock is HSI Osc. */ - default: - if (LL_RCC_HSI_IsReady()) - { - i2s_frequency = HSI_VALUE; - } - break; - } - break; -#endif /* RCC_DCKCFGR_I2SSRC || RCC_DCKCFGR_I2S1SRC */ - - case LL_RCC_I2S1_CLKSOURCE_PIN: /* I2S1 Clock is External clock */ - default: - i2s_frequency = EXTERNAL_CLOCK_VALUE; - break; - } - } -#if defined(RCC_DCKCFGR_I2S2SRC) - else - { - /* I2S2 CLK clock frequency */ - switch (LL_RCC_GetI2SClockSource(I2SxSource)) - { - case LL_RCC_I2S2_CLKSOURCE_PLLI2S: /* I2S2 Clock is PLLI2S */ - if (LL_RCC_PLLI2S_IsReady()) - { - i2s_frequency = RCC_PLLI2S_GetFreqDomain_I2S(); - } - break; - - case LL_RCC_I2S2_CLKSOURCE_PLL: /* I2S2 Clock is PLL */ - if (LL_RCC_PLL_IsReady()) - { - i2s_frequency = RCC_PLL_GetFreqDomain_I2S(); - } - break; - - case LL_RCC_I2S2_CLKSOURCE_PLLSRC: /* I2S2 Clock is PLL Main source */ - switch (LL_RCC_PLL_GetMainSource()) - { - case LL_RCC_PLLSOURCE_HSE: /* I2S2 Clock is HSE Osc. */ - if (LL_RCC_HSE_IsReady()) - { - i2s_frequency = HSE_VALUE; - } - break; - - case LL_RCC_PLLSOURCE_HSI: /* I2S2 Clock is HSI Osc. */ - default: - if (LL_RCC_HSI_IsReady()) - { - i2s_frequency = HSI_VALUE; - } - break; - } - break; - - case LL_RCC_I2S2_CLKSOURCE_PIN: /* I2S2 Clock is External clock */ - default: - i2s_frequency = EXTERNAL_CLOCK_VALUE; - break; - } - } -#endif /* RCC_DCKCFGR_I2S2SRC */ - - return i2s_frequency; -} - -#if defined(LPTIM1) -/** - * @brief Return LPTIMx clock frequency - * @param LPTIMxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE - * @retval LPTIM clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI, LSI or LSE) is not ready - */ -uint32_t LL_RCC_GetLPTIMClockFreq(uint32_t LPTIMxSource) -{ - uint32_t lptim_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_LPTIM_CLKSOURCE(LPTIMxSource)); - - if (LPTIMxSource == LL_RCC_LPTIM1_CLKSOURCE) - { - /* LPTIM1CLK clock frequency */ - switch (LL_RCC_GetLPTIMClockSource(LPTIMxSource)) - { - case LL_RCC_LPTIM1_CLKSOURCE_LSI: /* LPTIM1 Clock is LSI Osc. */ - if (LL_RCC_LSI_IsReady()) - { - lptim_frequency = LSI_VALUE; - } - break; - - case LL_RCC_LPTIM1_CLKSOURCE_HSI: /* LPTIM1 Clock is HSI Osc. */ - if (LL_RCC_HSI_IsReady()) - { - lptim_frequency = HSI_VALUE; - } - break; - - case LL_RCC_LPTIM1_CLKSOURCE_LSE: /* LPTIM1 Clock is LSE Osc. */ - if (LL_RCC_LSE_IsReady()) - { - lptim_frequency = LSE_VALUE; - } - break; - - case LL_RCC_LPTIM1_CLKSOURCE_PCLK1: /* LPTIM1 Clock is PCLK1 */ - default: - lptim_frequency = RCC_GetPCLK1ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq())); - break; - } - } - - return lptim_frequency; -} -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** - * @brief Return SAIx clock frequency - * @param SAIxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE (*) - * - * (*) value not defined in all devices. - * @retval SAI clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready - */ -uint32_t LL_RCC_GetSAIClockFreq(uint32_t SAIxSource) -{ - uint32_t sai_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_SAI_CLKSOURCE(SAIxSource)); - -#if defined(RCC_DCKCFGR_SAI1SRC) - if ((SAIxSource == LL_RCC_SAI1_CLKSOURCE) || (SAIxSource == LL_RCC_SAI2_CLKSOURCE)) - { - /* SAI1CLK clock frequency */ - switch (LL_RCC_GetSAIClockSource(SAIxSource)) - { - case LL_RCC_SAI1_CLKSOURCE_PLLSAI: /* PLLSAI clock used as SAI1 clock source */ - case LL_RCC_SAI2_CLKSOURCE_PLLSAI: /* PLLSAI clock used as SAI2 clock source */ - if (LL_RCC_PLLSAI_IsReady()) - { - sai_frequency = RCC_PLLSAI_GetFreqDomain_SAI(); - } - break; - - case LL_RCC_SAI1_CLKSOURCE_PLLI2S: /* PLLI2S clock used as SAI1 clock source */ - case LL_RCC_SAI2_CLKSOURCE_PLLI2S: /* PLLI2S clock used as SAI2 clock source */ - if (LL_RCC_PLLI2S_IsReady()) - { - sai_frequency = RCC_PLLI2S_GetFreqDomain_SAI(); - } - break; - - case LL_RCC_SAI1_CLKSOURCE_PLL: /* PLL clock used as SAI1 clock source */ - case LL_RCC_SAI2_CLKSOURCE_PLL: /* PLL clock used as SAI2 clock source */ - if (LL_RCC_PLL_IsReady()) - { - sai_frequency = RCC_PLL_GetFreqDomain_SAI(); - } - break; - - case LL_RCC_SAI2_CLKSOURCE_PLLSRC: - switch (LL_RCC_PLL_GetMainSource()) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE clock used as SAI2 clock source */ - if (LL_RCC_HSE_IsReady()) - { - sai_frequency = HSE_VALUE; - } - break; - - case LL_RCC_PLLSOURCE_HSI: /* HSI clock used as SAI2 clock source */ - default: - if (LL_RCC_HSI_IsReady()) - { - sai_frequency = HSI_VALUE; - } - break; - } - break; - - case LL_RCC_SAI1_CLKSOURCE_PIN: /* External input clock used as SAI1 clock source */ - default: - sai_frequency = EXTERNAL_CLOCK_VALUE; - break; - } - } -#endif /* RCC_DCKCFGR_SAI1SRC */ -#if defined(RCC_DCKCFGR_SAI1ASRC) - if ((SAIxSource == LL_RCC_SAI1_A_CLKSOURCE) || (SAIxSource == LL_RCC_SAI1_B_CLKSOURCE)) - { - /* SAI1CLK clock frequency */ - switch (LL_RCC_GetSAIClockSource(SAIxSource)) - { -#if defined(RCC_PLLSAI_SUPPORT) - case LL_RCC_SAI1_A_CLKSOURCE_PLLSAI: /* PLLSAI clock used as SAI1 Block A clock source */ - case LL_RCC_SAI1_B_CLKSOURCE_PLLSAI: /* PLLSAI clock used as SAI1 Block B clock source */ - if (LL_RCC_PLLSAI_IsReady()) - { - sai_frequency = RCC_PLLSAI_GetFreqDomain_SAI(); - } - break; -#endif /* RCC_PLLSAI_SUPPORT */ - - case LL_RCC_SAI1_A_CLKSOURCE_PLLI2S: /* PLLI2S clock used as SAI1 Block A clock source */ - case LL_RCC_SAI1_B_CLKSOURCE_PLLI2S: /* PLLI2S clock used as SAI1 Block B clock source */ - if (LL_RCC_PLLI2S_IsReady()) - { - sai_frequency = RCC_PLLI2S_GetFreqDomain_SAI(); - } - break; - -#if defined(RCC_SAI1A_PLLSOURCE_SUPPORT) - case LL_RCC_SAI1_A_CLKSOURCE_PLL: /* PLL clock used as SAI1 Block A clock source */ - case LL_RCC_SAI1_B_CLKSOURCE_PLL: /* PLL clock used as SAI1 Block B clock source */ - if (LL_RCC_PLL_IsReady()) - { - sai_frequency = RCC_PLL_GetFreqDomain_SAI(); - } - break; - - case LL_RCC_SAI1_A_CLKSOURCE_PLLSRC: - case LL_RCC_SAI1_B_CLKSOURCE_PLLSRC: - switch (LL_RCC_PLL_GetMainSource()) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE clock used as SAI1 Block A or B clock source */ - if (LL_RCC_HSE_IsReady()) - { - sai_frequency = HSE_VALUE; - } - break; - - case LL_RCC_PLLSOURCE_HSI: /* HSI clock used as SAI1 Block A or B clock source */ - default: - if (LL_RCC_HSI_IsReady()) - { - sai_frequency = HSI_VALUE; - } - break; - } - break; -#endif /* RCC_SAI1A_PLLSOURCE_SUPPORT */ - - case LL_RCC_SAI1_A_CLKSOURCE_PIN: /* External input clock used as SAI1 Block A clock source */ - case LL_RCC_SAI1_B_CLKSOURCE_PIN: /* External input clock used as SAI1 Block B clock source */ - default: - sai_frequency = EXTERNAL_CLOCK_VALUE; - break; - } - } -#endif /* RCC_DCKCFGR_SAI1ASRC */ - - return sai_frequency; -} -#endif /* SAI1 */ - -#if defined(SDIO) -/** - * @brief Return SDIOx clock frequency - * @param SDIOxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE - * @retval SDIO clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready - */ -uint32_t LL_RCC_GetSDIOClockFreq(uint32_t SDIOxSource) -{ - uint32_t SDIO_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_SDIO_CLKSOURCE(SDIOxSource)); - - if (SDIOxSource == LL_RCC_SDIO_CLKSOURCE) - { -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) - /* SDIOCLK clock frequency */ - switch (LL_RCC_GetSDIOClockSource(SDIOxSource)) - { - case LL_RCC_SDIO_CLKSOURCE_PLL48CLK: /* PLL48M clock used as SDIO clock source */ - switch (LL_RCC_GetCK48MClockSource(LL_RCC_CK48M_CLKSOURCE)) - { - case LL_RCC_CK48M_CLKSOURCE_PLL: /* PLL clock used as 48Mhz domain clock */ - if (LL_RCC_PLL_IsReady()) - { - SDIO_frequency = RCC_PLL_GetFreqDomain_48M(); - } - break; - -#if defined(RCC_PLLSAI_SUPPORT) - case LL_RCC_CK48M_CLKSOURCE_PLLSAI: /* PLLSAI clock used as 48Mhz domain clock */ - default: - if (LL_RCC_PLLSAI_IsReady()) - { - SDIO_frequency = RCC_PLLSAI_GetFreqDomain_48M(); - } - break; -#endif /* RCC_PLLSAI_SUPPORT */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) - case LL_RCC_CK48M_CLKSOURCE_PLLI2S: /* PLLI2S clock used as 48Mhz domain clock */ - default: - if (LL_RCC_PLLI2S_IsReady()) - { - SDIO_frequency = RCC_PLLI2S_GetFreqDomain_48M(); - } - break; -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ - } - break; - - case LL_RCC_SDIO_CLKSOURCE_SYSCLK: /* PLL clock used as SDIO clock source */ - default: - SDIO_frequency = RCC_GetSystemClockFreq(); - break; - } -#else - /* PLL clock used as 48Mhz domain clock */ - if (LL_RCC_PLL_IsReady()) - { - SDIO_frequency = RCC_PLL_GetFreqDomain_48M(); - } -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - } - - return SDIO_frequency; -} -#endif /* SDIO */ - -#if defined(RNG) -/** - * @brief Return RNGx clock frequency - * @param RNGxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE - * @retval RNG clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready - */ -uint32_t LL_RCC_GetRNGClockFreq(uint32_t RNGxSource) -{ - uint32_t rng_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_RNG_CLKSOURCE(RNGxSource)); - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) - /* RNGCLK clock frequency */ - switch (LL_RCC_GetRNGClockSource(RNGxSource)) - { -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) - case LL_RCC_RNG_CLKSOURCE_PLLI2S: /* PLLI2S clock used as RNG clock source */ - if (LL_RCC_PLLI2S_IsReady()) - { - rng_frequency = RCC_PLLI2S_GetFreqDomain_48M(); - } - break; -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(RCC_PLLSAI_SUPPORT) - case LL_RCC_RNG_CLKSOURCE_PLLSAI: /* PLLSAI clock used as RNG clock source */ - if (LL_RCC_PLLSAI_IsReady()) - { - rng_frequency = RCC_PLLSAI_GetFreqDomain_48M(); - } - break; -#endif /* RCC_PLLSAI_SUPPORT */ - - case LL_RCC_RNG_CLKSOURCE_PLL: /* PLL clock used as RNG clock source */ - default: - if (LL_RCC_PLL_IsReady()) - { - rng_frequency = RCC_PLL_GetFreqDomain_48M(); - } - break; - } -#else - /* PLL clock used as RNG clock source */ - if (LL_RCC_PLL_IsReady()) - { - rng_frequency = RCC_PLL_GetFreqDomain_48M(); - } -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - - return rng_frequency; -} -#endif /* RNG */ - -#if defined(CEC) -/** - * @brief Return CEC clock frequency - * @param CECxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE - * @retval CEC clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator (HSI or LSE) is not ready - */ -uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource) -{ - uint32_t cec_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_CEC_CLKSOURCE(CECxSource)); - - /* CECCLK clock frequency */ - switch (LL_RCC_GetCECClockSource(CECxSource)) - { - case LL_RCC_CEC_CLKSOURCE_LSE: /* CEC Clock is LSE Osc. */ - if (LL_RCC_LSE_IsReady()) - { - cec_frequency = LSE_VALUE; - } - break; - - case LL_RCC_CEC_CLKSOURCE_HSI_DIV488: /* CEC Clock is HSI Osc. */ - default: - if (LL_RCC_HSI_IsReady()) - { - cec_frequency = HSI_VALUE/488U; - } - break; - } - - return cec_frequency; -} -#endif /* CEC */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** - * @brief Return USBx clock frequency - * @param USBxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE - * @retval USB clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready - */ -uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource) -{ - uint32_t usb_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_USB_CLKSOURCE(USBxSource)); - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) - /* USBCLK clock frequency */ - switch (LL_RCC_GetUSBClockSource(USBxSource)) - { -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) - case LL_RCC_USB_CLKSOURCE_PLLI2S: /* PLLI2S clock used as USB clock source */ - if (LL_RCC_PLLI2S_IsReady()) - { - usb_frequency = RCC_PLLI2S_GetFreqDomain_48M(); - } - break; - -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(RCC_PLLSAI_SUPPORT) - case LL_RCC_USB_CLKSOURCE_PLLSAI: /* PLLSAI clock used as USB clock source */ - if (LL_RCC_PLLSAI_IsReady()) - { - usb_frequency = RCC_PLLSAI_GetFreqDomain_48M(); - } - break; -#endif /* RCC_PLLSAI_SUPPORT */ - - case LL_RCC_USB_CLKSOURCE_PLL: /* PLL clock used as USB clock source */ - default: - if (LL_RCC_PLL_IsReady()) - { - usb_frequency = RCC_PLL_GetFreqDomain_48M(); - } - break; - } -#else - /* PLL clock used as USB clock source */ - if (LL_RCC_PLL_IsReady()) - { - usb_frequency = RCC_PLL_GetFreqDomain_48M(); - } -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - - return usb_frequency; -} -#endif /* USB_OTG_FS || USB_OTG_HS */ - -#if defined(DFSDM1_Channel0) -/** - * @brief Return DFSDMx clock frequency - * @param DFSDMxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE (*) - * - * (*) value not defined in all devices. - * @retval DFSDM clock frequency (in Hz) - */ -uint32_t LL_RCC_GetDFSDMClockFreq(uint32_t DFSDMxSource) -{ - uint32_t dfsdm_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_DFSDM_CLKSOURCE(DFSDMxSource)); - - if (DFSDMxSource == LL_RCC_DFSDM1_CLKSOURCE) - { - /* DFSDM1CLK clock frequency */ - switch (LL_RCC_GetDFSDMClockSource(DFSDMxSource)) - { - case LL_RCC_DFSDM1_CLKSOURCE_SYSCLK: /* DFSDM1 Clock is SYSCLK */ - dfsdm_frequency = RCC_GetSystemClockFreq(); - break; - - case LL_RCC_DFSDM1_CLKSOURCE_PCLK2: /* DFSDM1 Clock is PCLK2 */ - default: - dfsdm_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq())); - break; - } - } -#if defined(DFSDM2_Channel0) - else - { - /* DFSDM2CLK clock frequency */ - switch (LL_RCC_GetDFSDMClockSource(DFSDMxSource)) - { - case LL_RCC_DFSDM2_CLKSOURCE_SYSCLK: /* DFSDM2 Clock is SYSCLK */ - dfsdm_frequency = RCC_GetSystemClockFreq(); - break; - - case LL_RCC_DFSDM2_CLKSOURCE_PCLK2: /* DFSDM2 Clock is PCLK2 */ - default: - dfsdm_frequency = RCC_GetPCLK2ClockFreq(RCC_GetHCLKClockFreq(RCC_GetSystemClockFreq())); - break; - } - } -#endif /* DFSDM2_Channel0 */ - - return dfsdm_frequency; -} - -/** - * @brief Return DFSDMx Audio clock frequency - * @param DFSDMxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE (*) - * - * (*) value not defined in all devices. - * @retval DFSDM clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready - */ -uint32_t LL_RCC_GetDFSDMAudioClockFreq(uint32_t DFSDMxSource) -{ - uint32_t dfsdm_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_DFSDM_AUDIO_CLKSOURCE(DFSDMxSource)); - - if (DFSDMxSource == LL_RCC_DFSDM1_AUDIO_CLKSOURCE) - { - /* DFSDM1CLK clock frequency */ - switch (LL_RCC_GetDFSDMAudioClockSource(DFSDMxSource)) - { - case LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1: /* I2S1 clock used as DFSDM1 clock */ - dfsdm_frequency = LL_RCC_GetI2SClockFreq(LL_RCC_I2S1_CLKSOURCE); - break; - - case LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2: /* I2S2 clock used as DFSDM1 clock */ - default: - dfsdm_frequency = LL_RCC_GetI2SClockFreq(LL_RCC_I2S2_CLKSOURCE); - break; - } - } -#if defined(DFSDM2_Channel0) - else - { - /* DFSDM2CLK clock frequency */ - switch (LL_RCC_GetDFSDMAudioClockSource(DFSDMxSource)) - { - case LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1: /* I2S1 clock used as DFSDM2 clock */ - dfsdm_frequency = LL_RCC_GetI2SClockFreq(LL_RCC_I2S1_CLKSOURCE); - break; - - case LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2: /* I2S2 clock used as DFSDM2 clock */ - default: - dfsdm_frequency = LL_RCC_GetI2SClockFreq(LL_RCC_I2S2_CLKSOURCE); - break; - } - } -#endif /* DFSDM2_Channel0 */ - - return dfsdm_frequency; -} -#endif /* DFSDM1_Channel0 */ - -#if defined(DSI) -/** - * @brief Return DSI clock frequency - * @param DSIxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE - * @retval DSI clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready - * - @ref LL_RCC_PERIPH_FREQUENCY_NA indicates that external clock is used - */ -uint32_t LL_RCC_GetDSIClockFreq(uint32_t DSIxSource) -{ - uint32_t dsi_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_DSI_CLKSOURCE(DSIxSource)); - - /* DSICLK clock frequency */ - switch (LL_RCC_GetDSIClockSource(DSIxSource)) - { - case LL_RCC_DSI_CLKSOURCE_PLL: /* DSI Clock is PLL Osc. */ - if (LL_RCC_PLL_IsReady()) - { - dsi_frequency = RCC_PLL_GetFreqDomain_DSI(); - } - break; - - case LL_RCC_DSI_CLKSOURCE_PHY: /* DSI Clock is DSI physical clock. */ - default: - dsi_frequency = LL_RCC_PERIPH_FREQUENCY_NA; - break; - } - - return dsi_frequency; -} -#endif /* DSI */ - -#if defined(LTDC) -/** - * @brief Return LTDC clock frequency - * @param LTDCxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_LTDC_CLKSOURCE - * @retval LTDC clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator PLLSAI is not ready - */ -uint32_t LL_RCC_GetLTDCClockFreq(uint32_t LTDCxSource) -{ - uint32_t ltdc_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_LTDC_CLKSOURCE(LTDCxSource)); - - if (LL_RCC_PLLSAI_IsReady()) - { - ltdc_frequency = RCC_PLLSAI_GetFreqDomain_LTDC(); - } - - return ltdc_frequency; -} -#endif /* LTDC */ - -#if defined(SPDIFRX) -/** - * @brief Return SPDIFRX clock frequency - * @param SPDIFRXxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE - * @retval SPDIFRX clock frequency (in Hz) - * - @ref LL_RCC_PERIPH_FREQUENCY_NO indicates that oscillator is not ready - */ -uint32_t LL_RCC_GetSPDIFRXClockFreq(uint32_t SPDIFRXxSource) -{ - uint32_t spdifrx_frequency = LL_RCC_PERIPH_FREQUENCY_NO; - - /* Check parameter */ - assert_param(IS_LL_RCC_SPDIFRX_CLKSOURCE(SPDIFRXxSource)); - - /* SPDIFRX1CLK clock frequency */ - switch (LL_RCC_GetSPDIFRXClockSource(SPDIFRXxSource)) - { - case LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S: /* SPDIFRX Clock is PLLI2S Osc. */ - if (LL_RCC_PLLI2S_IsReady()) - { - spdifrx_frequency = RCC_PLLI2S_GetFreqDomain_SPDIFRX(); - } - break; - - case LL_RCC_SPDIFRX1_CLKSOURCE_PLL: /* SPDIFRX Clock is PLL Osc. */ - default: - if (LL_RCC_PLL_IsReady()) - { - spdifrx_frequency = RCC_PLL_GetFreqDomain_SPDIFRX(); - } - break; - } - - return spdifrx_frequency; -} -#endif /* SPDIFRX */ - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup RCC_LL_Private_Functions - * @{ - */ - -/** - * @brief Return SYSTEM clock frequency - * @retval SYSTEM clock frequency (in Hz) - */ -uint32_t RCC_GetSystemClockFreq(void) -{ - uint32_t frequency = 0U; - - /* Get SYSCLK source -------------------------------------------------------*/ - switch (LL_RCC_GetSysClkSource()) - { - case LL_RCC_SYS_CLKSOURCE_STATUS_HSI: /* HSI used as system clock source */ - frequency = HSI_VALUE; - break; - - case LL_RCC_SYS_CLKSOURCE_STATUS_HSE: /* HSE used as system clock source */ - frequency = HSE_VALUE; - break; - - case LL_RCC_SYS_CLKSOURCE_STATUS_PLL: /* PLL used as system clock source */ - frequency = RCC_PLL_GetFreqDomain_SYS(LL_RCC_SYS_CLKSOURCE_STATUS_PLL); - break; - -#if defined(RCC_PLLR_SYSCLK_SUPPORT) - case LL_RCC_SYS_CLKSOURCE_STATUS_PLLR: /* PLLR used as system clock source */ - frequency = RCC_PLL_GetFreqDomain_SYS(LL_RCC_SYS_CLKSOURCE_STATUS_PLLR); - break; -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ - - default: - frequency = HSI_VALUE; - break; - } - - return frequency; -} - -/** - * @brief Return HCLK clock frequency - * @param SYSCLK_Frequency SYSCLK clock frequency - * @retval HCLK clock frequency (in Hz) - */ -uint32_t RCC_GetHCLKClockFreq(uint32_t SYSCLK_Frequency) -{ - /* HCLK clock frequency */ - return __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency, LL_RCC_GetAHBPrescaler()); -} - -/** - * @brief Return PCLK1 clock frequency - * @param HCLK_Frequency HCLK clock frequency - * @retval PCLK1 clock frequency (in Hz) - */ -uint32_t RCC_GetPCLK1ClockFreq(uint32_t HCLK_Frequency) -{ - /* PCLK1 clock frequency */ - return __LL_RCC_CALC_PCLK1_FREQ(HCLK_Frequency, LL_RCC_GetAPB1Prescaler()); -} - -/** - * @brief Return PCLK2 clock frequency - * @param HCLK_Frequency HCLK clock frequency - * @retval PCLK2 clock frequency (in Hz) - */ -uint32_t RCC_GetPCLK2ClockFreq(uint32_t HCLK_Frequency) -{ - /* PCLK2 clock frequency */ - return __LL_RCC_CALC_PCLK2_FREQ(HCLK_Frequency, LL_RCC_GetAPB2Prescaler()); -} - -/** - * @brief Return PLL clock frequency used for system domain - * @param SYSCLK_Source System clock source - * @retval PLL clock frequency (in Hz) - */ -uint32_t RCC_PLL_GetFreqDomain_SYS(uint32_t SYSCLK_Source) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U, plloutputfreq = 0U; - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SYSCLK = PLL_VCO / (PLLP or PLLR) - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ - pllinputfreq = HSI_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ - pllinputfreq = HSE_VALUE; - break; - - default: - pllinputfreq = HSI_VALUE; - break; - } - - if (SYSCLK_Source == LL_RCC_SYS_CLKSOURCE_STATUS_PLL) - { - plloutputfreq = __LL_RCC_CALC_PLLCLK_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), - LL_RCC_PLL_GetN(), LL_RCC_PLL_GetP()); - } -#if defined(RCC_PLLR_SYSCLK_SUPPORT) - else - { - plloutputfreq = __LL_RCC_CALC_PLLRCLK_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), - LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); - } -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ - - return plloutputfreq; -} - -/** - * @brief Return PLL clock frequency used for 48 MHz domain - * @retval PLL clock frequency (in Hz) - */ -uint32_t RCC_PLL_GetFreqDomain_48M(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U; - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM ) * PLLN - 48M Domain clock = PLL_VCO / PLLQ - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ - pllinputfreq = HSI_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ - pllinputfreq = HSE_VALUE; - break; - - default: - pllinputfreq = HSI_VALUE; - break; - } - return __LL_RCC_CALC_PLLCLK_48M_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), - LL_RCC_PLL_GetN(), LL_RCC_PLL_GetQ()); -} - -#if defined(DSI) -/** - * @brief Return PLL clock frequency used for DSI clock - * @retval PLL clock frequency (in Hz) - */ -uint32_t RCC_PLL_GetFreqDomain_DSI(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U; - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - DSICLK = PLL_VCO / PLLR - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ - pllinputfreq = HSE_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ - default: - pllinputfreq = HSI_VALUE; - break; - } - return __LL_RCC_CALC_PLLCLK_DSI_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), - LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); -} -#endif /* DSI */ - -#if defined(RCC_DCKCFGR_I2SSRC) || defined(RCC_DCKCFGR_I2S1SRC) -/** - * @brief Return PLL clock frequency used for I2S clock - * @retval PLL clock frequency (in Hz) - */ -uint32_t RCC_PLL_GetFreqDomain_I2S(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U; - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - I2SCLK = PLL_VCO / PLLR - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ - pllinputfreq = HSE_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ - default: - pllinputfreq = HSI_VALUE; - break; - } - return __LL_RCC_CALC_PLLCLK_I2S_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), - LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); -} -#endif /* RCC_DCKCFGR_I2SSRC || RCC_DCKCFGR_I2S1SRC */ - -#if defined(SPDIFRX) -/** - * @brief Return PLL clock frequency used for SPDIFRX clock - * @retval PLL clock frequency (in Hz) - */ -uint32_t RCC_PLL_GetFreqDomain_SPDIFRX(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U; - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SPDIFRXCLK = PLL_VCO / PLLR - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ - pllinputfreq = HSE_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ - default: - pllinputfreq = HSI_VALUE; - break; - } - return __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), - LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); -} -#endif /* SPDIFRX */ - -#if defined(RCC_PLLCFGR_PLLR) -#if defined(SAI1) -/** - * @brief Return PLL clock frequency used for SAI clock - * @retval PLL clock frequency (in Hz) - */ -uint32_t RCC_PLL_GetFreqDomain_SAI(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U, plloutputfreq = 0U; - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN - SAICLK = (PLL_VCO / PLLR) / PLLDIVR - or - SAICLK = PLL_VCO / PLLR - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLL clock source */ - pllinputfreq = HSE_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLL clock source */ - default: - pllinputfreq = HSI_VALUE; - break; - } - -#if defined(RCC_DCKCFGR_PLLDIVR) - plloutputfreq = __LL_RCC_CALC_PLLCLK_SAI_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), - LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR(), LL_RCC_PLL_GetDIVR()); -#else - plloutputfreq = __LL_RCC_CALC_PLLCLK_SAI_FREQ(pllinputfreq, LL_RCC_PLL_GetDivider(), - LL_RCC_PLL_GetN(), LL_RCC_PLL_GetR()); -#endif /* RCC_DCKCFGR_PLLDIVR */ - - return plloutputfreq; -} -#endif /* SAI1 */ -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Return PLLSAI clock frequency used for SAI domain - * @retval PLLSAI clock frequency (in Hz) - */ -uint32_t RCC_PLLSAI_GetFreqDomain_SAI(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U; - - /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLSAIM) * PLLSAIN - SAI domain clock = (PLLSAI_VCO / PLLSAIQ) / PLLSAIDIVQ - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLSAI clock source */ - pllinputfreq = HSI_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLSAI clock source */ - pllinputfreq = HSE_VALUE; - break; - - default: - pllinputfreq = HSI_VALUE; - break; - } - return __LL_RCC_CALC_PLLSAI_SAI_FREQ(pllinputfreq, LL_RCC_PLLSAI_GetDivider(), - LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetQ(), LL_RCC_PLLSAI_GetDIVQ()); -} - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Return PLLSAI clock frequency used for 48Mhz domain - * @retval PLLSAI clock frequency (in Hz) - */ -uint32_t RCC_PLLSAI_GetFreqDomain_48M(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U; - - /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLSAIM) * PLLSAIN - 48M Domain clock = PLLSAI_VCO / PLLSAIP - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLSAI clock source */ - pllinputfreq = HSI_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLSAI clock source */ - pllinputfreq = HSE_VALUE; - break; - - default: - pllinputfreq = HSI_VALUE; - break; - } - return __LL_RCC_CALC_PLLSAI_48M_FREQ(pllinputfreq, LL_RCC_PLLSAI_GetDivider(), - LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetP()); -} -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -#if defined(LTDC) -/** - * @brief Return PLLSAI clock frequency used for LTDC domain - * @retval PLLSAI clock frequency (in Hz) - */ -uint32_t RCC_PLLSAI_GetFreqDomain_LTDC(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U; - - /* PLLSAI_VCO = (HSE_VALUE or HSI_VALUE / PLLSAIM) * PLLSAIN - LTDC Domain clock = (PLLSAI_VCO / PLLSAIR) / PLLSAIDIVR - */ - pllsource = LL_RCC_PLL_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLSAI clock source */ - pllinputfreq = HSI_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLSAI clock source */ - pllinputfreq = HSE_VALUE; - break; - - default: - pllinputfreq = HSI_VALUE; - break; - } - return __LL_RCC_CALC_PLLSAI_LTDC_FREQ(pllinputfreq, LL_RCC_PLLSAI_GetDivider(), - LL_RCC_PLLSAI_GetN(), LL_RCC_PLLSAI_GetR(), LL_RCC_PLLSAI_GetDIVR()); -} -#endif /* LTDC */ -#endif /* RCC_PLLSAI_SUPPORT */ - -#if defined(RCC_PLLI2S_SUPPORT) -#if defined(SAI1) -/** - * @brief Return PLLI2S clock frequency used for SAI domains - * @retval PLLI2S clock frequency (in Hz) - */ -uint32_t RCC_PLLI2S_GetFreqDomain_SAI(void) -{ - uint32_t plli2sinputfreq = 0U, plli2ssource = 0U, plli2soutputfreq = 0U; - - /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLI2SM) * PLLI2SN - SAI domain clock = (PLLI2S_VCO / PLLI2SQ) / PLLI2SDIVQ - or - SAI domain clock = (PLLI2S_VCO / PLLI2SR) / PLLI2SDIVR - */ - plli2ssource = LL_RCC_PLLI2S_GetMainSource(); - - switch (plli2ssource) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLI2S clock source */ - plli2sinputfreq = HSE_VALUE; - break; - -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) - case LL_RCC_PLLI2SSOURCE_PIN: /* External pin input clock used as PLLI2S clock source */ - plli2sinputfreq = EXTERNAL_CLOCK_VALUE; - break; -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ - - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLI2S clock source */ - default: - plli2sinputfreq = HSI_VALUE; - break; - } - -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) - plli2soutputfreq = __LL_RCC_CALC_PLLI2S_SAI_FREQ(plli2sinputfreq, LL_RCC_PLLI2S_GetDivider(), - LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetQ(), LL_RCC_PLLI2S_GetDIVQ()); -#else - plli2soutputfreq = __LL_RCC_CALC_PLLI2S_SAI_FREQ(plli2sinputfreq, LL_RCC_PLLI2S_GetDivider(), - LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetR(), LL_RCC_PLLI2S_GetDIVR()); -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ - - return plli2soutputfreq; -} -#endif /* SAI1 */ - -#if defined(SPDIFRX) -/** - * @brief Return PLLI2S clock frequency used for SPDIFRX domain - * @retval PLLI2S clock frequency (in Hz) - */ -uint32_t RCC_PLLI2S_GetFreqDomain_SPDIFRX(void) -{ - uint32_t pllinputfreq = 0U, pllsource = 0U; - - /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLI2SM) * PLLI2SN - SPDIFRX Domain clock = PLLI2S_VCO / PLLI2SP - */ - pllsource = LL_RCC_PLLI2S_GetMainSource(); - - switch (pllsource) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLI2S clock source */ - pllinputfreq = HSE_VALUE; - break; - - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLI2S clock source */ - default: - pllinputfreq = HSI_VALUE; - break; - } - - return __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ(pllinputfreq, LL_RCC_PLLI2S_GetDivider(), - LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetP()); -} -#endif /* SPDIFRX */ - -/** - * @brief Return PLLI2S clock frequency used for I2S domain - * @retval PLLI2S clock frequency (in Hz) - */ -uint32_t RCC_PLLI2S_GetFreqDomain_I2S(void) -{ - uint32_t plli2sinputfreq = 0U, plli2ssource = 0U, plli2soutputfreq = 0U; - - /* PLLI2S_VCO = (HSE_VALUE or HSI_VALUE / PLLI2SM) * PLLI2SN - I2S Domain clock = PLLI2S_VCO / PLLI2SR - */ - plli2ssource = LL_RCC_PLLI2S_GetMainSource(); - - switch (plli2ssource) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLI2S clock source */ - plli2sinputfreq = HSE_VALUE; - break; - -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) - case LL_RCC_PLLI2SSOURCE_PIN: /* External pin input clock used as PLLI2S clock source */ - plli2sinputfreq = EXTERNAL_CLOCK_VALUE; - break; -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ - - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLI2S clock source */ - default: - plli2sinputfreq = HSI_VALUE; - break; - } - - plli2soutputfreq = __LL_RCC_CALC_PLLI2S_I2S_FREQ(plli2sinputfreq, LL_RCC_PLLI2S_GetDivider(), - LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetR()); - - return plli2soutputfreq; -} - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Return PLLI2S clock frequency used for 48Mhz domain - * @retval PLLI2S clock frequency (in Hz) - */ -uint32_t RCC_PLLI2S_GetFreqDomain_48M(void) -{ - uint32_t plli2sinputfreq = 0U, plli2ssource = 0U, plli2soutputfreq = 0U; - - /* PLL48M_VCO = (HSE_VALUE or HSI_VALUE / PLLI2SM) * PLLI2SN - 48M Domain clock = PLLI2S_VCO / PLLI2SQ - */ - plli2ssource = LL_RCC_PLLI2S_GetMainSource(); - - switch (plli2ssource) - { - case LL_RCC_PLLSOURCE_HSE: /* HSE used as PLLI2S clock source */ - plli2sinputfreq = HSE_VALUE; - break; - -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) - case LL_RCC_PLLI2SSOURCE_PIN: /* External pin input clock used as PLLI2S clock source */ - plli2sinputfreq = EXTERNAL_CLOCK_VALUE; - break; -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ - - case LL_RCC_PLLSOURCE_HSI: /* HSI used as PLLI2S clock source */ - default: - plli2sinputfreq = HSI_VALUE; - break; - } - - plli2soutputfreq = __LL_RCC_CALC_PLLI2S_48M_FREQ(plli2sinputfreq, LL_RCC_PLLI2S_GetDivider(), - LL_RCC_PLLI2S_GetN(), LL_RCC_PLLI2S_GetQ()); - - return plli2soutputfreq; -} -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_PLLI2S_SUPPORT */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RCC) */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rng.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rng.c deleted file mode 100644 index 1b202c9606d0370..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rng.c +++ /dev/null @@ -1,104 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rng.c - * @author MCD Application Team - * @brief RNG LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_rng.h" -#include "stm32f4xx_ll_bus.h" - -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (RNG) - -/** @addtogroup RNG_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup RNG_LL_Exported_Functions - * @{ - */ - -/** @addtogroup RNG_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize RNG registers (Registers restored to their default values). - * @param RNGx RNG Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RNG registers are de-initialized - * - ERROR: not applicable - */ -ErrorStatus LL_RNG_DeInit(RNG_TypeDef *RNGx) -{ - /* Check the parameters */ - assert_param(IS_RNG_ALL_INSTANCE(RNGx)); -#if !defined(RCC_AHB2_SUPPORT) - /* Enable RNG reset state */ - LL_AHB1_GRP1_ForceReset(LL_AHB1_GRP1_PERIPH_RNG); - - /* Release RNG from reset state */ - LL_AHB1_GRP1_ReleaseReset(LL_AHB1_GRP1_PERIPH_RNG); -#else - /* Enable RNG reset state */ - LL_AHB2_GRP1_ForceReset(LL_AHB2_GRP1_PERIPH_RNG); - - /* Release RNG from reset state */ - LL_AHB2_GRP1_ReleaseReset(LL_AHB2_GRP1_PERIPH_RNG); -#endif /* !RCC_AHB2_SUPPORT */ - return (SUCCESS); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* RNG */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rtc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rtc.c deleted file mode 100644 index 14c3cfa5ca0f3cd..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_rtc.c +++ /dev/null @@ -1,865 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rtc.c - * @author MCD Application Team - * @brief RTC LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_rtc.h" -#include "stm32f4xx_ll_cortex.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RTC) - -/** @addtogroup RTC_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @addtogroup RTC_LL_Private_Constants - * @{ - */ -/* Default values used for prescaler */ -#define RTC_ASYNCH_PRESC_DEFAULT 0x0000007FU -#define RTC_SYNCH_PRESC_DEFAULT 0x000000FFU - -/* Values used for timeout */ -#define RTC_INITMODE_TIMEOUT 1000U /* 1s when tick set to 1ms */ -#define RTC_SYNCHRO_TIMEOUT 1000U /* 1s when tick set to 1ms */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup RTC_LL_Private_Macros - * @{ - */ - -#define IS_LL_RTC_HOURFORMAT(__VALUE__) (((__VALUE__) == LL_RTC_HOURFORMAT_24HOUR) \ - || ((__VALUE__) == LL_RTC_HOURFORMAT_AMPM)) - -#define IS_LL_RTC_ASYNCH_PREDIV(__VALUE__) ((__VALUE__) <= 0x7FU) - -#define IS_LL_RTC_SYNCH_PREDIV(__VALUE__) ((__VALUE__) <= 0x7FFFU) - -#define IS_LL_RTC_FORMAT(__VALUE__) (((__VALUE__) == LL_RTC_FORMAT_BIN) \ - || ((__VALUE__) == LL_RTC_FORMAT_BCD)) - -#define IS_LL_RTC_TIME_FORMAT(__VALUE__) (((__VALUE__) == LL_RTC_TIME_FORMAT_AM_OR_24) \ - || ((__VALUE__) == LL_RTC_TIME_FORMAT_PM)) - -#define IS_LL_RTC_HOUR12(__HOUR__) (((__HOUR__) > 0U) && ((__HOUR__) <= 12U)) -#define IS_LL_RTC_HOUR24(__HOUR__) ((__HOUR__) <= 23U) -#define IS_LL_RTC_MINUTES(__MINUTES__) ((__MINUTES__) <= 59U) -#define IS_LL_RTC_SECONDS(__SECONDS__) ((__SECONDS__) <= 59U) - -#define IS_LL_RTC_WEEKDAY(__VALUE__) (((__VALUE__) == LL_RTC_WEEKDAY_MONDAY) \ - || ((__VALUE__) == LL_RTC_WEEKDAY_TUESDAY) \ - || ((__VALUE__) == LL_RTC_WEEKDAY_WEDNESDAY) \ - || ((__VALUE__) == LL_RTC_WEEKDAY_THURSDAY) \ - || ((__VALUE__) == LL_RTC_WEEKDAY_FRIDAY) \ - || ((__VALUE__) == LL_RTC_WEEKDAY_SATURDAY) \ - || ((__VALUE__) == LL_RTC_WEEKDAY_SUNDAY)) - -#define IS_LL_RTC_DAY(__DAY__) (((__DAY__) >= 1U) && ((__DAY__) <= 31U)) - -#define IS_LL_RTC_MONTH(__MONTH__) (((__MONTH__) >= 1U) && ((__MONTH__) <= 12U)) - -#define IS_LL_RTC_YEAR(__YEAR__) ((__YEAR__) <= 99U) - -#define IS_LL_RTC_ALMA_MASK(__VALUE__) (((__VALUE__) == LL_RTC_ALMA_MASK_NONE) \ - || ((__VALUE__) == LL_RTC_ALMA_MASK_DATEWEEKDAY) \ - || ((__VALUE__) == LL_RTC_ALMA_MASK_HOURS) \ - || ((__VALUE__) == LL_RTC_ALMA_MASK_MINUTES) \ - || ((__VALUE__) == LL_RTC_ALMA_MASK_SECONDS) \ - || ((__VALUE__) == LL_RTC_ALMA_MASK_ALL)) - -#define IS_LL_RTC_ALMB_MASK(__VALUE__) (((__VALUE__) == LL_RTC_ALMB_MASK_NONE) \ - || ((__VALUE__) == LL_RTC_ALMB_MASK_DATEWEEKDAY) \ - || ((__VALUE__) == LL_RTC_ALMB_MASK_HOURS) \ - || ((__VALUE__) == LL_RTC_ALMB_MASK_MINUTES) \ - || ((__VALUE__) == LL_RTC_ALMB_MASK_SECONDS) \ - || ((__VALUE__) == LL_RTC_ALMB_MASK_ALL)) - - -#define IS_LL_RTC_ALMA_DATE_WEEKDAY_SEL(__SEL__) (((__SEL__) == LL_RTC_ALMA_DATEWEEKDAYSEL_DATE) || \ - ((__SEL__) == LL_RTC_ALMA_DATEWEEKDAYSEL_WEEKDAY)) - -#define IS_LL_RTC_ALMB_DATE_WEEKDAY_SEL(__SEL__) (((__SEL__) == LL_RTC_ALMB_DATEWEEKDAYSEL_DATE) || \ - ((__SEL__) == LL_RTC_ALMB_DATEWEEKDAYSEL_WEEKDAY)) - - -/** - * @} - */ -/* Private function prototypes -----------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup RTC_LL_Exported_Functions - * @{ - */ - -/** @addtogroup RTC_LL_EF_Init - * @{ - */ - -/** - * @brief De-Initializes the RTC registers to their default reset values. - * @note This function doesn't reset the RTC Clock source and RTC Backup Data - * registers. - * @param RTCx RTC Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RTC registers are de-initialized - * - ERROR: RTC registers are not de-initialized - */ -ErrorStatus LL_RTC_DeInit(RTC_TypeDef *RTCx) -{ - ErrorStatus status = ERROR; - - /* Check the parameter */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - - /* Disable the write protection for RTC registers */ - LL_RTC_DisableWriteProtection(RTCx); - - /* Set Initialization mode */ - if (LL_RTC_EnterInitMode(RTCx) != ERROR) - { - /* Reset TR, DR and CR registers */ - LL_RTC_WriteReg(RTCx, TR, 0x00000000U); -#if defined(RTC_WAKEUP_SUPPORT) - LL_RTC_WriteReg(RTCx, WUTR, RTC_WUTR_WUT); -#endif /* RTC_WAKEUP_SUPPORT */ - LL_RTC_WriteReg(RTCx, DR , (RTC_DR_WDU_0 | RTC_DR_MU_0 | RTC_DR_DU_0)); - /* Reset All CR bits except CR[2:0] */ -#if defined(RTC_WAKEUP_SUPPORT) - LL_RTC_WriteReg(RTCx, CR, (LL_RTC_ReadReg(RTCx, CR) & RTC_CR_WUCKSEL)); -#else - LL_RTC_WriteReg(RTCx, CR, 0x00000000U); -#endif /* RTC_WAKEUP_SUPPORT */ - LL_RTC_WriteReg(RTCx, PRER, (RTC_PRER_PREDIV_A | RTC_SYNCH_PRESC_DEFAULT)); - LL_RTC_WriteReg(RTCx, ALRMAR, 0x00000000U); - LL_RTC_WriteReg(RTCx, ALRMBR, 0x00000000U); - LL_RTC_WriteReg(RTCx, SHIFTR, 0x00000000U); - LL_RTC_WriteReg(RTCx, CALR, 0x00000000U); - LL_RTC_WriteReg(RTCx, ALRMASSR, 0x00000000U); - LL_RTC_WriteReg(RTCx, ALRMBSSR, 0x00000000U); - - /* Reset ISR register and exit initialization mode */ - LL_RTC_WriteReg(RTCx, ISR, 0x00000000U); - - /* Reset Tamper and alternate functions configuration register */ - LL_RTC_WriteReg(RTCx, TAFCR, 0x00000000U); - - /* Wait till the RTC RSF flag is set */ - status = LL_RTC_WaitForSynchro(RTCx); - } - - /* Enable the write protection for RTC registers */ - LL_RTC_EnableWriteProtection(RTCx); - - return status; -} - -/** - * @brief Initializes the RTC registers according to the specified parameters - * in RTC_InitStruct. - * @param RTCx RTC Instance - * @param RTC_InitStruct pointer to a @ref LL_RTC_InitTypeDef structure that contains - * the configuration information for the RTC peripheral. - * @note The RTC Prescaler register is write protected and can be written in - * initialization mode only. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RTC registers are initialized - * - ERROR: RTC registers are not initialized - */ -ErrorStatus LL_RTC_Init(RTC_TypeDef *RTCx, LL_RTC_InitTypeDef *RTC_InitStruct) -{ - ErrorStatus status = ERROR; - - /* Check the parameters */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - assert_param(IS_LL_RTC_HOURFORMAT(RTC_InitStruct->HourFormat)); - assert_param(IS_LL_RTC_ASYNCH_PREDIV(RTC_InitStruct->AsynchPrescaler)); - assert_param(IS_LL_RTC_SYNCH_PREDIV(RTC_InitStruct->SynchPrescaler)); - - /* Disable the write protection for RTC registers */ - LL_RTC_DisableWriteProtection(RTCx); - - /* Set Initialization mode */ - if (LL_RTC_EnterInitMode(RTCx) != ERROR) - { - /* Set Hour Format */ - LL_RTC_SetHourFormat(RTCx, RTC_InitStruct->HourFormat); - - /* Configure Synchronous and Asynchronous prescaler factor */ - LL_RTC_SetSynchPrescaler(RTCx, RTC_InitStruct->SynchPrescaler); - LL_RTC_SetAsynchPrescaler(RTCx, RTC_InitStruct->AsynchPrescaler); - - /* Exit Initialization mode */ - LL_RTC_DisableInitMode(RTCx); - - status = SUCCESS; - } - /* Enable the write protection for RTC registers */ - LL_RTC_EnableWriteProtection(RTCx); - - return status; -} - -/** - * @brief Set each @ref LL_RTC_InitTypeDef field to default value. - * @param RTC_InitStruct pointer to a @ref LL_RTC_InitTypeDef structure which will be initialized. - * @retval None - */ -void LL_RTC_StructInit(LL_RTC_InitTypeDef *RTC_InitStruct) -{ - /* Set RTC_InitStruct fields to default values */ - RTC_InitStruct->HourFormat = LL_RTC_HOURFORMAT_24HOUR; - RTC_InitStruct->AsynchPrescaler = RTC_ASYNCH_PRESC_DEFAULT; - RTC_InitStruct->SynchPrescaler = RTC_SYNCH_PRESC_DEFAULT; -} - -/** - * @brief Set the RTC current time. - * @param RTCx RTC Instance - * @param RTC_Format This parameter can be one of the following values: - * @arg @ref LL_RTC_FORMAT_BIN - * @arg @ref LL_RTC_FORMAT_BCD - * @param RTC_TimeStruct pointer to a RTC_TimeTypeDef structure that contains - * the time configuration information for the RTC. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RTC Time register is configured - * - ERROR: RTC Time register is not configured - */ -ErrorStatus LL_RTC_TIME_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_TimeTypeDef *RTC_TimeStruct) -{ - ErrorStatus status = ERROR; - - /* Check the parameters */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - assert_param(IS_LL_RTC_FORMAT(RTC_Format)); - - if (RTC_Format == LL_RTC_FORMAT_BIN) - { - if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) - { - assert_param(IS_LL_RTC_HOUR12(RTC_TimeStruct->Hours)); - assert_param(IS_LL_RTC_TIME_FORMAT(RTC_TimeStruct->TimeFormat)); - } - else - { - RTC_TimeStruct->TimeFormat = 0x00U; - assert_param(IS_LL_RTC_HOUR24(RTC_TimeStruct->Hours)); - } - assert_param(IS_LL_RTC_MINUTES(RTC_TimeStruct->Minutes)); - assert_param(IS_LL_RTC_SECONDS(RTC_TimeStruct->Seconds)); - } - else - { - if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) - { - assert_param(IS_LL_RTC_HOUR12(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Hours))); - assert_param(IS_LL_RTC_TIME_FORMAT(RTC_TimeStruct->TimeFormat)); - } - else - { - RTC_TimeStruct->TimeFormat = 0x00U; - assert_param(IS_LL_RTC_HOUR24(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Hours))); - } - assert_param(IS_LL_RTC_MINUTES(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Minutes))); - assert_param(IS_LL_RTC_SECONDS(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Seconds))); - } - - /* Disable the write protection for RTC registers */ - LL_RTC_DisableWriteProtection(RTCx); - - /* Set Initialization mode */ - if (LL_RTC_EnterInitMode(RTCx) != ERROR) - { - /* Check the input parameters format */ - if (RTC_Format != LL_RTC_FORMAT_BIN) - { - LL_RTC_TIME_Config(RTCx, RTC_TimeStruct->TimeFormat, RTC_TimeStruct->Hours, - RTC_TimeStruct->Minutes, RTC_TimeStruct->Seconds); - } - else - { - LL_RTC_TIME_Config(RTCx, RTC_TimeStruct->TimeFormat, __LL_RTC_CONVERT_BIN2BCD(RTC_TimeStruct->Hours), - __LL_RTC_CONVERT_BIN2BCD(RTC_TimeStruct->Minutes), - __LL_RTC_CONVERT_BIN2BCD(RTC_TimeStruct->Seconds)); - } - - /* Exit Initialization mode */ - LL_RTC_DisableInitMode(RTCx); - - /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ - if (LL_RTC_IsShadowRegBypassEnabled(RTCx) == 0U) - { - status = LL_RTC_WaitForSynchro(RTCx); - } - else - { - status = SUCCESS; - } - } - /* Enable the write protection for RTC registers */ - LL_RTC_EnableWriteProtection(RTCx); - - return status; -} - -/** - * @brief Set each @ref LL_RTC_TimeTypeDef field to default value (Time = 00h:00min:00sec). - * @param RTC_TimeStruct pointer to a @ref LL_RTC_TimeTypeDef structure which will be initialized. - * @retval None - */ -void LL_RTC_TIME_StructInit(LL_RTC_TimeTypeDef *RTC_TimeStruct) -{ - /* Time = 00h:00min:00sec */ - RTC_TimeStruct->TimeFormat = LL_RTC_TIME_FORMAT_AM_OR_24; - RTC_TimeStruct->Hours = 0U; - RTC_TimeStruct->Minutes = 0U; - RTC_TimeStruct->Seconds = 0U; -} - -/** - * @brief Set the RTC current date. - * @param RTCx RTC Instance - * @param RTC_Format This parameter can be one of the following values: - * @arg @ref LL_RTC_FORMAT_BIN - * @arg @ref LL_RTC_FORMAT_BCD - * @param RTC_DateStruct pointer to a RTC_DateTypeDef structure that contains - * the date configuration information for the RTC. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RTC Day register is configured - * - ERROR: RTC Day register is not configured - */ -ErrorStatus LL_RTC_DATE_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_DateTypeDef *RTC_DateStruct) -{ - ErrorStatus status = ERROR; - - /* Check the parameters */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - assert_param(IS_LL_RTC_FORMAT(RTC_Format)); - - if ((RTC_Format == LL_RTC_FORMAT_BIN) && ((RTC_DateStruct->Month & 0x10U) == 0x10U)) - { - RTC_DateStruct->Month = (RTC_DateStruct->Month & (uint32_t)~(0x10U)) + 0x0AU; - } - if (RTC_Format == LL_RTC_FORMAT_BIN) - { - assert_param(IS_LL_RTC_YEAR(RTC_DateStruct->Year)); - assert_param(IS_LL_RTC_MONTH(RTC_DateStruct->Month)); - assert_param(IS_LL_RTC_DAY(RTC_DateStruct->Day)); - } - else - { - assert_param(IS_LL_RTC_YEAR(__LL_RTC_CONVERT_BCD2BIN(RTC_DateStruct->Year))); - assert_param(IS_LL_RTC_MONTH(__LL_RTC_CONVERT_BCD2BIN(RTC_DateStruct->Month))); - assert_param(IS_LL_RTC_DAY(__LL_RTC_CONVERT_BCD2BIN(RTC_DateStruct->Day))); - } - assert_param(IS_LL_RTC_WEEKDAY(RTC_DateStruct->WeekDay)); - - /* Disable the write protection for RTC registers */ - LL_RTC_DisableWriteProtection(RTCx); - - /* Set Initialization mode */ - if (LL_RTC_EnterInitMode(RTCx) != ERROR) - { - /* Check the input parameters format */ - if (RTC_Format != LL_RTC_FORMAT_BIN) - { - LL_RTC_DATE_Config(RTCx, RTC_DateStruct->WeekDay, RTC_DateStruct->Day, RTC_DateStruct->Month, RTC_DateStruct->Year); - } - else - { - LL_RTC_DATE_Config(RTCx, RTC_DateStruct->WeekDay, __LL_RTC_CONVERT_BIN2BCD(RTC_DateStruct->Day), - __LL_RTC_CONVERT_BIN2BCD(RTC_DateStruct->Month), __LL_RTC_CONVERT_BIN2BCD(RTC_DateStruct->Year)); - } - - /* Exit Initialization mode */ - LL_RTC_DisableInitMode(RTCx); - - /* If RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */ - if (LL_RTC_IsShadowRegBypassEnabled(RTCx) == 0U) - { - status = LL_RTC_WaitForSynchro(RTCx); - } - else - { - status = SUCCESS; - } - } - /* Enable the write protection for RTC registers */ - LL_RTC_EnableWriteProtection(RTCx); - - return status; -} - -/** - * @brief Set each @ref LL_RTC_DateTypeDef field to default value (date = Monday, January 01 xx00) - * @param RTC_DateStruct pointer to a @ref LL_RTC_DateTypeDef structure which will be initialized. - * @retval None - */ -void LL_RTC_DATE_StructInit(LL_RTC_DateTypeDef *RTC_DateStruct) -{ - /* Monday, January 01 xx00 */ - RTC_DateStruct->WeekDay = LL_RTC_WEEKDAY_MONDAY; - RTC_DateStruct->Day = 1U; - RTC_DateStruct->Month = LL_RTC_MONTH_JANUARY; - RTC_DateStruct->Year = 0U; -} - -/** - * @brief Set the RTC Alarm A. - * @note The Alarm register can only be written when the corresponding Alarm - * is disabled (Use @ref LL_RTC_ALMA_Disable function). - * @param RTCx RTC Instance - * @param RTC_Format This parameter can be one of the following values: - * @arg @ref LL_RTC_FORMAT_BIN - * @arg @ref LL_RTC_FORMAT_BCD - * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure that - * contains the alarm configuration parameters. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: ALARMA registers are configured - * - ERROR: ALARMA registers are not configured - */ -ErrorStatus LL_RTC_ALMA_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct) -{ - /* Check the parameters */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - assert_param(IS_LL_RTC_FORMAT(RTC_Format)); - assert_param(IS_LL_RTC_ALMA_MASK(RTC_AlarmStruct->AlarmMask)); - assert_param(IS_LL_RTC_ALMA_DATE_WEEKDAY_SEL(RTC_AlarmStruct->AlarmDateWeekDaySel)); - - if (RTC_Format == LL_RTC_FORMAT_BIN) - { - if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) - { - assert_param(IS_LL_RTC_HOUR12(RTC_AlarmStruct->AlarmTime.Hours)); - assert_param(IS_LL_RTC_TIME_FORMAT(RTC_AlarmStruct->AlarmTime.TimeFormat)); - } - else - { - RTC_AlarmStruct->AlarmTime.TimeFormat = 0x00U; - assert_param(IS_LL_RTC_HOUR24(RTC_AlarmStruct->AlarmTime.Hours)); - } - assert_param(IS_LL_RTC_MINUTES(RTC_AlarmStruct->AlarmTime.Minutes)); - assert_param(IS_LL_RTC_SECONDS(RTC_AlarmStruct->AlarmTime.Seconds)); - - if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMA_DATEWEEKDAYSEL_DATE) - { - assert_param(IS_LL_RTC_DAY(RTC_AlarmStruct->AlarmDateWeekDay)); - } - else - { - assert_param(IS_LL_RTC_WEEKDAY(RTC_AlarmStruct->AlarmDateWeekDay)); - } - } - else - { - if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) - { - assert_param(IS_LL_RTC_HOUR12(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours))); - assert_param(IS_LL_RTC_TIME_FORMAT(RTC_AlarmStruct->AlarmTime.TimeFormat)); - } - else - { - RTC_AlarmStruct->AlarmTime.TimeFormat = 0x00U; - assert_param(IS_LL_RTC_HOUR24(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours))); - } - - assert_param(IS_LL_RTC_MINUTES(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Minutes))); - assert_param(IS_LL_RTC_SECONDS(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Seconds))); - - if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMA_DATEWEEKDAYSEL_DATE) - { - assert_param(IS_LL_RTC_DAY(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmDateWeekDay))); - } - else - { - assert_param(IS_LL_RTC_WEEKDAY(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmDateWeekDay))); - } - } - - /* Disable the write protection for RTC registers */ - LL_RTC_DisableWriteProtection(RTCx); - - /* Select weekday selection */ - if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMA_DATEWEEKDAYSEL_DATE) - { - /* Set the date for ALARM */ - LL_RTC_ALMA_DisableWeekday(RTCx); - if (RTC_Format != LL_RTC_FORMAT_BIN) - { - LL_RTC_ALMA_SetDay(RTCx, RTC_AlarmStruct->AlarmDateWeekDay); - } - else - { - LL_RTC_ALMA_SetDay(RTCx, __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmDateWeekDay)); - } - } - else - { - /* Set the week day for ALARM */ - LL_RTC_ALMA_EnableWeekday(RTCx); - LL_RTC_ALMA_SetWeekDay(RTCx, RTC_AlarmStruct->AlarmDateWeekDay); - } - - /* Configure the Alarm register */ - if (RTC_Format != LL_RTC_FORMAT_BIN) - { - LL_RTC_ALMA_ConfigTime(RTCx, RTC_AlarmStruct->AlarmTime.TimeFormat, RTC_AlarmStruct->AlarmTime.Hours, - RTC_AlarmStruct->AlarmTime.Minutes, RTC_AlarmStruct->AlarmTime.Seconds); - } - else - { - LL_RTC_ALMA_ConfigTime(RTCx, RTC_AlarmStruct->AlarmTime.TimeFormat, - __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Hours), - __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Minutes), - __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Seconds)); - } - /* Set ALARM mask */ - LL_RTC_ALMA_SetMask(RTCx, RTC_AlarmStruct->AlarmMask); - - /* Enable the write protection for RTC registers */ - LL_RTC_EnableWriteProtection(RTCx); - - return SUCCESS; -} - -/** - * @brief Set the RTC Alarm B. - * @note The Alarm register can only be written when the corresponding Alarm - * is disabled (@ref LL_RTC_ALMB_Disable function). - * @param RTCx RTC Instance - * @param RTC_Format This parameter can be one of the following values: - * @arg @ref LL_RTC_FORMAT_BIN - * @arg @ref LL_RTC_FORMAT_BCD - * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure that - * contains the alarm configuration parameters. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: ALARMB registers are configured - * - ERROR: ALARMB registers are not configured - */ -ErrorStatus LL_RTC_ALMB_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct) -{ - /* Check the parameters */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - assert_param(IS_LL_RTC_FORMAT(RTC_Format)); - assert_param(IS_LL_RTC_ALMB_MASK(RTC_AlarmStruct->AlarmMask)); - assert_param(IS_LL_RTC_ALMB_DATE_WEEKDAY_SEL(RTC_AlarmStruct->AlarmDateWeekDaySel)); - - if (RTC_Format == LL_RTC_FORMAT_BIN) - { - if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) - { - assert_param(IS_LL_RTC_HOUR12(RTC_AlarmStruct->AlarmTime.Hours)); - assert_param(IS_LL_RTC_TIME_FORMAT(RTC_AlarmStruct->AlarmTime.TimeFormat)); - } - else - { - RTC_AlarmStruct->AlarmTime.TimeFormat = 0x00U; - assert_param(IS_LL_RTC_HOUR24(RTC_AlarmStruct->AlarmTime.Hours)); - } - assert_param(IS_LL_RTC_MINUTES(RTC_AlarmStruct->AlarmTime.Minutes)); - assert_param(IS_LL_RTC_SECONDS(RTC_AlarmStruct->AlarmTime.Seconds)); - - if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMB_DATEWEEKDAYSEL_DATE) - { - assert_param(IS_LL_RTC_DAY(RTC_AlarmStruct->AlarmDateWeekDay)); - } - else - { - assert_param(IS_LL_RTC_WEEKDAY(RTC_AlarmStruct->AlarmDateWeekDay)); - } - } - else - { - if (LL_RTC_GetHourFormat(RTCx) != LL_RTC_HOURFORMAT_24HOUR) - { - assert_param(IS_LL_RTC_HOUR12(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours))); - assert_param(IS_LL_RTC_TIME_FORMAT(RTC_AlarmStruct->AlarmTime.TimeFormat)); - } - else - { - RTC_AlarmStruct->AlarmTime.TimeFormat = 0x00U; - assert_param(IS_LL_RTC_HOUR24(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours))); - } - - assert_param(IS_LL_RTC_MINUTES(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Minutes))); - assert_param(IS_LL_RTC_SECONDS(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Seconds))); - - if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMB_DATEWEEKDAYSEL_DATE) - { - assert_param(IS_LL_RTC_DAY(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmDateWeekDay))); - } - else - { - assert_param(IS_LL_RTC_WEEKDAY(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmDateWeekDay))); - } - } - - /* Disable the write protection for RTC registers */ - LL_RTC_DisableWriteProtection(RTCx); - - /* Select weekday selection */ - if (RTC_AlarmStruct->AlarmDateWeekDaySel == LL_RTC_ALMB_DATEWEEKDAYSEL_DATE) - { - /* Set the date for ALARM */ - LL_RTC_ALMB_DisableWeekday(RTCx); - if (RTC_Format != LL_RTC_FORMAT_BIN) - { - LL_RTC_ALMB_SetDay(RTCx, RTC_AlarmStruct->AlarmDateWeekDay); - } - else - { - LL_RTC_ALMB_SetDay(RTCx, __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmDateWeekDay)); - } - } - else - { - /* Set the week day for ALARM */ - LL_RTC_ALMB_EnableWeekday(RTCx); - LL_RTC_ALMB_SetWeekDay(RTCx, RTC_AlarmStruct->AlarmDateWeekDay); - } - - /* Configure the Alarm register */ - if (RTC_Format != LL_RTC_FORMAT_BIN) - { - LL_RTC_ALMB_ConfigTime(RTCx, RTC_AlarmStruct->AlarmTime.TimeFormat, RTC_AlarmStruct->AlarmTime.Hours, - RTC_AlarmStruct->AlarmTime.Minutes, RTC_AlarmStruct->AlarmTime.Seconds); - } - else - { - LL_RTC_ALMB_ConfigTime(RTCx, RTC_AlarmStruct->AlarmTime.TimeFormat, - __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Hours), - __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Minutes), - __LL_RTC_CONVERT_BIN2BCD(RTC_AlarmStruct->AlarmTime.Seconds)); - } - /* Set ALARM mask */ - LL_RTC_ALMB_SetMask(RTCx, RTC_AlarmStruct->AlarmMask); - - /* Enable the write protection for RTC registers */ - LL_RTC_EnableWriteProtection(RTCx); - - return SUCCESS; -} - -/** - * @brief Set each @ref LL_RTC_AlarmTypeDef of ALARMA field to default value (Time = 00h:00mn:00sec / - * Day = 1st day of the month/Mask = all fields are masked). - * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure which will be initialized. - * @retval None - */ -void LL_RTC_ALMA_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct) -{ - /* Alarm Time Settings : Time = 00h:00mn:00sec */ - RTC_AlarmStruct->AlarmTime.TimeFormat = LL_RTC_ALMA_TIME_FORMAT_AM; - RTC_AlarmStruct->AlarmTime.Hours = 0U; - RTC_AlarmStruct->AlarmTime.Minutes = 0U; - RTC_AlarmStruct->AlarmTime.Seconds = 0U; - - /* Alarm Day Settings : Day = 1st day of the month */ - RTC_AlarmStruct->AlarmDateWeekDaySel = LL_RTC_ALMA_DATEWEEKDAYSEL_DATE; - RTC_AlarmStruct->AlarmDateWeekDay = 1U; - - /* Alarm Masks Settings : Mask = all fields are not masked */ - RTC_AlarmStruct->AlarmMask = LL_RTC_ALMA_MASK_NONE; -} - -/** - * @brief Set each @ref LL_RTC_AlarmTypeDef of ALARMA field to default value (Time = 00h:00mn:00sec / - * Day = 1st day of the month/Mask = all fields are masked). - * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure which will be initialized. - * @retval None - */ -void LL_RTC_ALMB_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct) -{ - /* Alarm Time Settings : Time = 00h:00mn:00sec */ - RTC_AlarmStruct->AlarmTime.TimeFormat = LL_RTC_ALMB_TIME_FORMAT_AM; - RTC_AlarmStruct->AlarmTime.Hours = 0U; - RTC_AlarmStruct->AlarmTime.Minutes = 0U; - RTC_AlarmStruct->AlarmTime.Seconds = 0U; - - /* Alarm Day Settings : Day = 1st day of the month */ - RTC_AlarmStruct->AlarmDateWeekDaySel = LL_RTC_ALMB_DATEWEEKDAYSEL_DATE; - RTC_AlarmStruct->AlarmDateWeekDay = 1U; - - /* Alarm Masks Settings : Mask = all fields are not masked */ - RTC_AlarmStruct->AlarmMask = LL_RTC_ALMB_MASK_NONE; -} - -/** - * @brief Enters the RTC Initialization mode. - * @note The RTC Initialization mode is write protected, use the - * @ref LL_RTC_DisableWriteProtection before calling this function. - * @param RTCx RTC Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RTC is in Init mode - * - ERROR: RTC is not in Init mode - */ -ErrorStatus LL_RTC_EnterInitMode(RTC_TypeDef *RTCx) -{ - __IO uint32_t timeout = RTC_INITMODE_TIMEOUT; - ErrorStatus status = SUCCESS; - uint32_t tmp = 0U; - - /* Check the parameter */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - - /* Check if the Initialization mode is set */ - if (LL_RTC_IsActiveFlag_INIT(RTCx) == 0U) - { - /* Set the Initialization mode */ - LL_RTC_EnableInitMode(RTCx); - - /* Wait till RTC is in INIT state and if Time out is reached exit */ - tmp = LL_RTC_IsActiveFlag_INIT(RTCx); - while ((timeout != 0U) && (tmp != 1U)) - { - if (LL_SYSTICK_IsActiveCounterFlag() == 1U) - { - timeout --; - } - tmp = LL_RTC_IsActiveFlag_INIT(RTCx); - if (timeout == 0U) - { - status = ERROR; - } - } - } - return status; -} - -/** - * @brief Exit the RTC Initialization mode. - * @note When the initialization sequence is complete, the calendar restarts - * counting after 4 RTCCLK cycles. - * @note The RTC Initialization mode is write protected, use the - * @ref LL_RTC_DisableWriteProtection before calling this function. - * @param RTCx RTC Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RTC exited from in Init mode - * - ERROR: Not applicable - */ -ErrorStatus LL_RTC_ExitInitMode(RTC_TypeDef *RTCx) -{ - /* Check the parameter */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - - /* Disable initialization mode */ - LL_RTC_DisableInitMode(RTCx); - - return SUCCESS; -} - -/** - * @brief Waits until the RTC Time and Day registers (RTC_TR and RTC_DR) are - * synchronized with RTC APB clock. - * @note The RTC Resynchronization mode is write protected, use the - * @ref LL_RTC_DisableWriteProtection before calling this function. - * @note To read the calendar through the shadow registers after Calendar - * initialization, calendar update or after wakeup from low power modes - * the software must first clear the RSF flag. - * The software must then wait until it is set again before reading - * the calendar, which means that the calendar registers have been - * correctly copied into the RTC_TR and RTC_DR shadow registers. - * @param RTCx RTC Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: RTC registers are synchronised - * - ERROR: RTC registers are not synchronised - */ -ErrorStatus LL_RTC_WaitForSynchro(RTC_TypeDef *RTCx) -{ - __IO uint32_t timeout = RTC_SYNCHRO_TIMEOUT; - ErrorStatus status = SUCCESS; - uint32_t tmp = 0U; - - /* Check the parameter */ - assert_param(IS_RTC_ALL_INSTANCE(RTCx)); - - /* Clear RSF flag */ - LL_RTC_ClearFlag_RS(RTCx); - - /* Wait the registers to be synchronised */ - tmp = LL_RTC_IsActiveFlag_RS(RTCx); - while ((timeout != 0U) && (tmp != 0U)) - { - if (LL_SYSTICK_IsActiveCounterFlag() == 1U) - { - timeout--; - } - tmp = LL_RTC_IsActiveFlag_RS(RTCx); - if (timeout == 0U) - { - status = ERROR; - } - } - - if (status != ERROR) - { - timeout = RTC_SYNCHRO_TIMEOUT; - tmp = LL_RTC_IsActiveFlag_RS(RTCx); - while ((timeout != 0U) && (tmp != 1U)) - { - if (LL_SYSTICK_IsActiveCounterFlag() == 1U) - { - timeout--; - } - tmp = LL_RTC_IsActiveFlag_RS(RTCx); - if (timeout == 0U) - { - status = ERROR; - } - } - } - - return (status); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RTC) */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c deleted file mode 100644 index ff89435bf7e2e45..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_sdmmc.c +++ /dev/null @@ -1,1547 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_sdmmc.c - * @author MCD Application Team - * @brief SDMMC Low Layer HAL module driver. - * - * This file provides firmware functions to manage the following - * functionalities of the SDMMC peripheral: - * + Initialization/de-initialization functions - * + I/O operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### SDMMC peripheral features ##### - ============================================================================== - [..] The SD/SDMMC MMC card host interface (SDMMC) provides an interface between the AHB - peripheral bus and MultiMedia cards (MMCs), SD memory cards, SDMMC cards and CE-ATA - devices. - - [..] The SDMMC features include the following: - (+) Full compliance with MultiMedia Card System Specification Version 4.2. Card support - for three different databus modes: 1-bit (default), 4-bit and 8-bit - (+) Full compatibility with previous versions of MultiMedia Cards (forward compatibility) - (+) Full compliance with SD Memory Card Specifications Version 2.0 - (+) Full compliance with SD I/O Card Specification Version 2.0: card support for two - different data bus modes: 1-bit (default) and 4-bit - (+) Full support of the CE-ATA features (full compliance with CE-ATA digital protocol - Rev1.1) - (+) Data transfer up to 48 MHz for the 8 bit mode - (+) Data and command output enable signals to control external bidirectional drivers - - ##### How to use this driver ##### - ============================================================================== - [..] - This driver is a considered as a driver of service for external devices drivers - that interfaces with the SDMMC peripheral. - According to the device used (SD card/ MMC card / SDMMC card ...), a set of APIs - is used in the device's driver to perform SDMMC operations and functionalities. - - This driver is almost transparent for the final user, it is only used to implement other - functionalities of the external device. - - [..] - (+) The SDMMC clock (SDMMCCLK = 48 MHz) is coming from a specific output (MSI, PLLUSB1CLK, - PLLUSB2CLK). Before start working with SDMMC peripheral make sure that the - PLL is well configured. - The SDMMC peripheral uses two clock signals: - (++) SDMMC adapter clock (SDMMCCLK = 48 MHz) - (++) APB2 bus clock (PCLK2) - - -@@- PCLK2 and SDMMC_CK clock frequencies must respect the following condition: - Frequency(PCLK2) >= (3 / 8 x Frequency(SDMMC_CK)) - - (+) Enable/Disable peripheral clock using RCC peripheral macros related to SDMMC - peripheral. - - (+) Enable the Power ON State using the SDIO_PowerState_ON() - function and disable it using the function SDIO_PowerState_OFF(). - - (+) Enable/Disable the clock using the __SDIO_ENABLE()/__SDIO_DISABLE() macros. - - (+) Enable/Disable the peripheral interrupts using the macros __SDIO_ENABLE_IT() - and __SDIO_DISABLE_IT() if you need to use interrupt mode. - - (+) When using the DMA mode - (++) Configure the DMA in the MSP layer of the external device - (++) Active the needed channel Request - (++) Enable the DMA using __SDIO_DMA_ENABLE() macro or Disable it using the macro - __SDIO_DMA_DISABLE(). - - (+) To control the CPSM (Command Path State Machine) and send - commands to the card use the SDIO_SendCommand(), - SDIO_GetCommandResponse() and SDIO_GetResponse() functions. First, user has - to fill the command structure (pointer to SDIO_CmdInitTypeDef) according - to the selected command to be sent. - The parameters that should be filled are: - (++) Command Argument - (++) Command Index - (++) Command Response type - (++) Command Wait - (++) CPSM Status (Enable or Disable). - - -@@- To check if the command is well received, read the SDIO_CMDRESP - register using the SDIO_GetCommandResponse(). - The SDMMC responses registers (SDIO_RESP1 to SDIO_RESP2), use the - SDIO_GetResponse() function. - - (+) To control the DPSM (Data Path State Machine) and send/receive - data to/from the card use the SDIO_DataConfig(), SDIO_GetDataCounter(), - SDIO_ReadFIFO(), SDIO_WriteFIFO() and SDIO_GetFIFOCount() functions. - - *** Read Operations *** - ======================= - [..] - (#) First, user has to fill the data structure (pointer to - SDIO_DataInitTypeDef) according to the selected data type to be received. - The parameters that should be filled are: - (++) Data TimeOut - (++) Data Length - (++) Data Block size - (++) Data Transfer direction: should be from card (To SDMMC) - (++) Data Transfer mode - (++) DPSM Status (Enable or Disable) - - (#) Configure the SDMMC resources to receive the data from the card - according to selected transfer mode (Refer to Step 8, 9 and 10). - - (#) Send the selected Read command (refer to step 11). - - (#) Use the SDIO flags/interrupts to check the transfer status. - - *** Write Operations *** - ======================== - [..] - (#) First, user has to fill the data structure (pointer to - SDIO_DataInitTypeDef) according to the selected data type to be received. - The parameters that should be filled are: - (++) Data TimeOut - (++) Data Length - (++) Data Block size - (++) Data Transfer direction: should be to card (To CARD) - (++) Data Transfer mode - (++) DPSM Status (Enable or Disable) - - (#) Configure the SDMMC resources to send the data to the card according to - selected transfer mode. - - (#) Send the selected Write command. - - (#) Use the SDIO flags/interrupts to check the transfer status. - - *** Command management operations *** - ===================================== - [..] - (#) The commands used for Read/Write/Erase operations are managed in - separate functions. - Each function allows to send the needed command with the related argument, - then check the response. - By the same approach, you could implement a command and check the response. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -#if defined(SDIO) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SDMMC_LL SDMMC Low Layer - * @brief Low layer module for SD - * @{ - */ - -#if defined(HAL_SD_MODULE_ENABLED) || defined(HAL_MMC_MODULE_ENABLED) - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -static uint32_t SDMMC_GetCmdError(SDIO_TypeDef *SDIOx); -static uint32_t SDMMC_GetCmdResp1(SDIO_TypeDef *SDIOx, uint8_t SD_CMD, uint32_t Timeout); -static uint32_t SDMMC_GetCmdResp2(SDIO_TypeDef *SDIOx); -static uint32_t SDMMC_GetCmdResp3(SDIO_TypeDef *SDIOx); -static uint32_t SDMMC_GetCmdResp7(SDIO_TypeDef *SDIOx); -static uint32_t SDMMC_GetCmdResp6(SDIO_TypeDef *SDIOx, uint8_t SD_CMD, uint16_t *pRCA); - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup SDMMC_LL_Exported_Functions SDMMC Low Layer Exported Functions - * @{ - */ - -/** @defgroup HAL_SDMMC_LL_Group1 Initialization de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization/de-initialization functions ##### - =============================================================================== - [..] This section provides functions allowing to: - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the SDMMC according to the specified - * parameters in the SDMMC_InitTypeDef and create the associated handle. - * @param SDIOx: Pointer to SDMMC register base - * @param Init: SDMMC initialization structure - * @retval HAL status - */ -HAL_StatusTypeDef SDIO_Init(SDIO_TypeDef *SDIOx, SDIO_InitTypeDef Init) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_SDIO_ALL_INSTANCE(SDIOx)); - assert_param(IS_SDIO_CLOCK_EDGE(Init.ClockEdge)); - assert_param(IS_SDIO_CLOCK_BYPASS(Init.ClockBypass)); - assert_param(IS_SDIO_CLOCK_POWER_SAVE(Init.ClockPowerSave)); - assert_param(IS_SDIO_BUS_WIDE(Init.BusWide)); - assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(Init.HardwareFlowControl)); - assert_param(IS_SDIO_CLKDIV(Init.ClockDiv)); - - /* Set SDMMC configuration parameters */ - tmpreg |= (Init.ClockEdge |\ - Init.ClockBypass |\ - Init.ClockPowerSave |\ - Init.BusWide |\ - Init.HardwareFlowControl |\ - Init.ClockDiv - ); - - /* Write to SDMMC CLKCR */ - MODIFY_REG(SDIOx->CLKCR, CLKCR_CLEAR_MASK, tmpreg); - - return HAL_OK; -} - - -/** - * @} - */ - -/** @defgroup HAL_SDMMC_LL_Group2 IO operation functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### I/O operation functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the SDMMC data - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Read data (word) from Rx FIFO in blocking mode (polling) - * @param SDIOx: Pointer to SDMMC register base - * @retval HAL status - */ -uint32_t SDIO_ReadFIFO(SDIO_TypeDef *SDIOx) -{ - /* Read data from Rx FIFO */ - return (SDIOx->FIFO); -} - -/** - * @brief Write data (word) to Tx FIFO in blocking mode (polling) - * @param SDIOx: Pointer to SDMMC register base - * @param pWriteData: pointer to data to write - * @retval HAL status - */ -HAL_StatusTypeDef SDIO_WriteFIFO(SDIO_TypeDef *SDIOx, uint32_t *pWriteData) -{ - /* Write data to FIFO */ - SDIOx->FIFO = *pWriteData; - - return HAL_OK; -} - -/** - * @} - */ - -/** @defgroup HAL_SDMMC_LL_Group3 Peripheral Control functions - * @brief management functions - * -@verbatim - =============================================================================== - ##### Peripheral Control functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to control the SDMMC data - transfers. - -@endverbatim - * @{ - */ - -/** - * @brief Set SDMMC Power state to ON. - * @param SDIOx: Pointer to SDMMC register base - * @retval HAL status - */ -HAL_StatusTypeDef SDIO_PowerState_ON(SDIO_TypeDef *SDIOx) -{ - /* Set power state to ON */ - SDIOx->POWER = SDIO_POWER_PWRCTRL; - - /* 1ms: required power up waiting time before starting the SD initialization - sequence */ - HAL_Delay(2); - - return HAL_OK; -} - -/** - * @brief Set SDMMC Power state to OFF. - * @param SDIOx: Pointer to SDMMC register base - * @retval HAL status - */ -HAL_StatusTypeDef SDIO_PowerState_OFF(SDIO_TypeDef *SDIOx) -{ - /* Set power state to OFF */ - SDIOx->POWER = (uint32_t)0x00000000; - - return HAL_OK; -} - -/** - * @brief Get SDMMC Power state. - * @param SDIOx: Pointer to SDMMC register base - * @retval Power status of the controller. The returned value can be one of the - * following values: - * - 0x00: Power OFF - * - 0x02: Power UP - * - 0x03: Power ON - */ -uint32_t SDIO_GetPowerState(SDIO_TypeDef *SDIOx) -{ - return (SDIOx->POWER & SDIO_POWER_PWRCTRL); -} - -/** - * @brief Configure the SDMMC command path according to the specified parameters in - * SDIO_CmdInitTypeDef structure and send the command - * @param SDIOx: Pointer to SDMMC register base - * @param Command: pointer to a SDIO_CmdInitTypeDef structure that contains - * the configuration information for the SDMMC command - * @retval HAL status - */ -HAL_StatusTypeDef SDIO_SendCommand(SDIO_TypeDef *SDIOx, SDIO_CmdInitTypeDef *Command) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_SDIO_CMD_INDEX(Command->CmdIndex)); - assert_param(IS_SDIO_RESPONSE(Command->Response)); - assert_param(IS_SDIO_WAIT(Command->WaitForInterrupt)); - assert_param(IS_SDIO_CPSM(Command->CPSM)); - - /* Set the SDMMC Argument value */ - SDIOx->ARG = Command->Argument; - - /* Set SDMMC command parameters */ - tmpreg |= (uint32_t)(Command->CmdIndex |\ - Command->Response |\ - Command->WaitForInterrupt |\ - Command->CPSM); - - /* Write to SDMMC CMD register */ - MODIFY_REG(SDIOx->CMD, CMD_CLEAR_MASK, tmpreg); - - return HAL_OK; -} - -/** - * @brief Return the command index of last command for which response received - * @param SDIOx: Pointer to SDMMC register base - * @retval Command index of the last command response received - */ -uint8_t SDIO_GetCommandResponse(SDIO_TypeDef *SDIOx) -{ - return (uint8_t)(SDIOx->RESPCMD); -} - - -/** - * @brief Return the response received from the card for the last command - * @param SDIOx: Pointer to SDMMC register base - * @param Response: Specifies the SDMMC response register. - * This parameter can be one of the following values: - * @arg SDIO_RESP1: Response Register 1 - * @arg SDIO_RESP2: Response Register 2 - * @arg SDIO_RESP3: Response Register 3 - * @arg SDIO_RESP4: Response Register 4 - * @retval The Corresponding response register value - */ -uint32_t SDIO_GetResponse(SDIO_TypeDef *SDIOx, uint32_t Response) -{ - uint32_t tmp; - - /* Check the parameters */ - assert_param(IS_SDIO_RESP(Response)); - - /* Get the response */ - tmp = (uint32_t)(&(SDIOx->RESP1)) + Response; - - return (*(__IO uint32_t *) tmp); -} - -/** - * @brief Configure the SDMMC data path according to the specified - * parameters in the SDIO_DataInitTypeDef. - * @param SDIOx: Pointer to SDIO register base - * @param Data : pointer to a SDIO_DataInitTypeDef structure - * that contains the configuration information for the SDMMC data. - * @retval HAL status - */ -HAL_StatusTypeDef SDIO_ConfigData(SDIO_TypeDef *SDIOx, SDIO_DataInitTypeDef* Data) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_SDIO_DATA_LENGTH(Data->DataLength)); - assert_param(IS_SDIO_BLOCK_SIZE(Data->DataBlockSize)); - assert_param(IS_SDIO_TRANSFER_DIR(Data->TransferDir)); - assert_param(IS_SDIO_TRANSFER_MODE(Data->TransferMode)); - assert_param(IS_SDIO_DPSM(Data->DPSM)); - - /* Set the SDMMC Data TimeOut value */ - SDIOx->DTIMER = Data->DataTimeOut; - - /* Set the SDMMC DataLength value */ - SDIOx->DLEN = Data->DataLength; - - /* Set the SDMMC data configuration parameters */ - tmpreg |= (uint32_t)(Data->DataBlockSize |\ - Data->TransferDir |\ - Data->TransferMode |\ - Data->DPSM); - - /* Write to SDMMC DCTRL */ - MODIFY_REG(SDIOx->DCTRL, DCTRL_CLEAR_MASK, tmpreg); - - return HAL_OK; - -} - -/** - * @brief Returns number of remaining data bytes to be transferred. - * @param SDIOx: Pointer to SDIO register base - * @retval Number of remaining data bytes to be transferred - */ -uint32_t SDIO_GetDataCounter(SDIO_TypeDef *SDIOx) -{ - return (SDIOx->DCOUNT); -} - -/** - * @brief Get the FIFO data - * @param SDIOx: Pointer to SDIO register base - * @retval Data received - */ -uint32_t SDIO_GetFIFOCount(SDIO_TypeDef *SDIOx) -{ - return (SDIOx->FIFO); -} - -/** - * @brief Sets one of the two options of inserting read wait interval. - * @param SDIOx: Pointer to SDIO register base - * @param SDIO_ReadWaitMode: SDMMC Read Wait operation mode. - * This parameter can be: - * @arg SDIO_READ_WAIT_MODE_CLK: Read Wait control by stopping SDMMCCLK - * @arg SDIO_READ_WAIT_MODE_DATA2: Read Wait control using SDMMC_DATA2 - * @retval None - */ -HAL_StatusTypeDef SDIO_SetSDMMCReadWaitMode(SDIO_TypeDef *SDIOx, uint32_t SDIO_ReadWaitMode) -{ - /* Check the parameters */ - assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode)); - - /* Set SDMMC read wait mode */ - MODIFY_REG(SDIOx->DCTRL, SDIO_DCTRL_RWMOD, SDIO_ReadWaitMode); - - return HAL_OK; -} - -/** - * @} - */ - - -/** @defgroup HAL_SDMMC_LL_Group4 Command management functions - * @brief Data transfers functions - * -@verbatim - =============================================================================== - ##### Commands management functions ##### - =============================================================================== - [..] - This subsection provides a set of functions allowing to manage the needed commands. - -@endverbatim - * @{ - */ - -/** - * @brief Send the Data Block Length command and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdBlockLength(SDIO_TypeDef *SDIOx, uint32_t BlockSize) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)BlockSize; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SET_BLOCKLEN; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SET_BLOCKLEN, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Read Single Block command and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdReadSingleBlock(SDIO_TypeDef *SDIOx, uint32_t ReadAdd) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)ReadAdd; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_READ_SINGLE_BLOCK; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_READ_SINGLE_BLOCK, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Read Multi Block command and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdReadMultiBlock(SDIO_TypeDef *SDIOx, uint32_t ReadAdd) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)ReadAdd; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_READ_MULT_BLOCK; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_READ_MULT_BLOCK, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Write Single Block command and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdWriteSingleBlock(SDIO_TypeDef *SDIOx, uint32_t WriteAdd) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)WriteAdd; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_WRITE_SINGLE_BLOCK; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_WRITE_SINGLE_BLOCK, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Write Multi Block command and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdWriteMultiBlock(SDIO_TypeDef *SDIOx, uint32_t WriteAdd) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)WriteAdd; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_WRITE_MULT_BLOCK; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_WRITE_MULT_BLOCK, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Start Address Erase command for SD and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdSDEraseStartAdd(SDIO_TypeDef *SDIOx, uint32_t StartAdd) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)StartAdd; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_ERASE_GRP_START; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SD_ERASE_GRP_START, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the End Address Erase command for SD and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdSDEraseEndAdd(SDIO_TypeDef *SDIOx, uint32_t EndAdd) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)EndAdd; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_ERASE_GRP_END; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SD_ERASE_GRP_END, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Start Address Erase command and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdEraseStartAdd(SDIO_TypeDef *SDIOx, uint32_t StartAdd) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)StartAdd; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_ERASE_GRP_START; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_ERASE_GRP_START, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the End Address Erase command and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdEraseEndAdd(SDIO_TypeDef *SDIOx, uint32_t EndAdd) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = (uint32_t)EndAdd; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_ERASE_GRP_END; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_ERASE_GRP_END, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Erase command and check the response - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdErase(SDIO_TypeDef *SDIOx) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Set Block Size for Card */ - sdmmc_cmdinit.Argument = 0U; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_ERASE; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_ERASE, SDIO_MAXERASETIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Stop Transfer command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdStopTransfer(SDIO_TypeDef *SDIOx) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD12 STOP_TRANSMISSION */ - sdmmc_cmdinit.Argument = 0U; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_STOP_TRANSMISSION; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_STOP_TRANSMISSION, SDIO_STOPTRANSFERTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Select Deselect command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @param addr: Address of the card to be selected - * @retval HAL status - */ -uint32_t SDMMC_CmdSelDesel(SDIO_TypeDef *SDIOx, uint64_t Addr) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD7 SDMMC_SEL_DESEL_CARD */ - sdmmc_cmdinit.Argument = (uint32_t)Addr; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEL_DESEL_CARD; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SEL_DESEL_CARD, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Go Idle State command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdGoIdleState(SDIO_TypeDef *SDIOx) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - sdmmc_cmdinit.Argument = 0U; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_GO_IDLE_STATE; - sdmmc_cmdinit.Response = SDIO_RESPONSE_NO; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdError(SDIOx); - - return errorstate; -} - -/** - * @brief Send the Operating Condition command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdOperCond(SDIO_TypeDef *SDIOx) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD8 to verify SD card interface operating condition */ - /* Argument: - [31:12]: Reserved (shall be set to '0') - - [11:8]: Supply Voltage (VHS) 0x1 (Range: 2.7-3.6 V) - - [7:0]: Check Pattern (recommended 0xAA) */ - /* CMD Response: R7 */ - sdmmc_cmdinit.Argument = SDMMC_CHECK_PATTERN; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_HS_SEND_EXT_CSD; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp7(SDIOx); - - return errorstate; -} - -/** - * @brief Send the Application command to verify that that the next command - * is an application specific com-mand rather than a standard command - * and check the response. - * @param SDIOx: Pointer to SDIO register base - * @param Argument: Command Argument - * @retval HAL status - */ -uint32_t SDMMC_CmdAppCommand(SDIO_TypeDef *SDIOx, uint32_t Argument) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - sdmmc_cmdinit.Argument = (uint32_t)Argument; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_APP_CMD; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - /* If there is a HAL_ERROR, it is a MMC card, else - it is a SD card: SD card 2.0 (voltage range mismatch) - or SD card 1.x */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_APP_CMD, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the command asking the accessed card to send its operating - * condition register (OCR) - * @param SDIOx: Pointer to SDIO register base - * @param Argument: Command Argument - * @retval HAL status - */ -uint32_t SDMMC_CmdAppOperCommand(SDIO_TypeDef *SDIOx, uint32_t Argument) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - sdmmc_cmdinit.Argument = SDMMC_VOLTAGE_WINDOW_SD | Argument; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_APP_OP_COND; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp3(SDIOx); - - return errorstate; -} - -/** - * @brief Send the Bus Width command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @param BusWidth: BusWidth - * @retval HAL status - */ -uint32_t SDMMC_CmdBusWidth(SDIO_TypeDef *SDIOx, uint32_t BusWidth) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - sdmmc_cmdinit.Argument = (uint32_t)BusWidth; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_APP_SD_SET_BUSWIDTH; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_APP_SD_SET_BUSWIDTH, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Send SCR command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdSendSCR(SDIO_TypeDef *SDIOx) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD51 SD_APP_SEND_SCR */ - sdmmc_cmdinit.Argument = 0U; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_APP_SEND_SCR; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SD_APP_SEND_SCR, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Send CID command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdSendCID(SDIO_TypeDef *SDIOx) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD2 ALL_SEND_CID */ - sdmmc_cmdinit.Argument = 0U; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_ALL_SEND_CID; - sdmmc_cmdinit.Response = SDIO_RESPONSE_LONG; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp2(SDIOx); - - return errorstate; -} - -/** - * @brief Send the Send CSD command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @param Argument: Command Argument - * @retval HAL status - */ -uint32_t SDMMC_CmdSendCSD(SDIO_TypeDef *SDIOx, uint32_t Argument) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD9 SEND_CSD */ - sdmmc_cmdinit.Argument = Argument; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEND_CSD; - sdmmc_cmdinit.Response = SDIO_RESPONSE_LONG; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp2(SDIOx); - - return errorstate; -} - -/** - * @brief Send the Send CSD command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @param pRCA: Card RCA - * @retval HAL status - */ -uint32_t SDMMC_CmdSetRelAdd(SDIO_TypeDef *SDIOx, uint16_t *pRCA) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD3 SD_CMD_SET_REL_ADDR */ - sdmmc_cmdinit.Argument = 0U; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SET_REL_ADDR; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp6(SDIOx, SDMMC_CMD_SET_REL_ADDR, pRCA); - - return errorstate; -} - -/** - * @brief Send the Status command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @param Argument: Command Argument - * @retval HAL status - */ -uint32_t SDMMC_CmdSendStatus(SDIO_TypeDef *SDIOx, uint32_t Argument) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - sdmmc_cmdinit.Argument = Argument; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEND_STATUS; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SEND_STATUS, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Send the Status register command and check the response. - * @param SDIOx: Pointer to SDIO register base - * @retval HAL status - */ -uint32_t SDMMC_CmdStatusRegister(SDIO_TypeDef *SDIOx) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - sdmmc_cmdinit.Argument = 0U; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SD_APP_STATUS; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_SD_APP_STATUS, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @brief Sends host capacity support information and activates the card's - * initialization process. Send SDMMC_CMD_SEND_OP_COND command - * @param SDIOx: Pointer to SDIO register base - * @parame Argument: Argument used for the command - * @retval HAL status - */ -uint32_t SDMMC_CmdOpCondition(SDIO_TypeDef *SDIOx, uint32_t Argument) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - sdmmc_cmdinit.Argument = Argument; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEND_OP_COND; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp3(SDIOx); - - return errorstate; -} - -/** - * @brief Checks switchable function and switch card function. SDMMC_CMD_HS_SWITCH command - * @param SDIOx: Pointer to SDIO register base - * @parame Argument: Argument used for the command - * @retval HAL status - */ -uint32_t SDMMC_CmdSwitch(SDIO_TypeDef *SDIOx, uint32_t Argument) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD6 to activate SDR50 Mode and Power Limit 1.44W */ - /* CMD Response: R1 */ - sdmmc_cmdinit.Argument = Argument; /* SDMMC_SDR25_SWITCH_PATTERN */ - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_HS_SWITCH; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_HS_SWITCH, SDIO_CMDTIMEOUT); - - return errorstate; -} - -/** - * @} - */ - -/* Private function ----------------------------------------------------------*/ -/** @addtogroup SD_Private_Functions - * @{ - */ - -/** - * @brief Checks for error conditions for CMD0. - * @param hsd: SD handle - * @retval SD Card error state - */ -static uint32_t SDMMC_GetCmdError(SDIO_TypeDef *SDIOx) -{ - /* 8 is the number of required instructions cycles for the below loop statement. - The SDIO_CMDTIMEOUT is expressed in ms */ - uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); - - do - { - if (count-- == 0U) - { - return SDMMC_ERROR_TIMEOUT; - } - - }while(!__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CMDSENT)); - - /* Clear all the static flags */ - __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); - - return SDMMC_ERROR_NONE; -} - -/** - * @brief Checks for error conditions for R1 response. - * @param hsd: SD handle - * @param SD_CMD: The sent command index - * @retval SD Card error state - */ -static uint32_t SDMMC_GetCmdResp1(SDIO_TypeDef *SDIOx, uint8_t SD_CMD, uint32_t Timeout) -{ - uint32_t response_r1; - uint32_t sta_reg; - - /* 8 is the number of required instructions cycles for the below loop statement. - The Timeout is expressed in ms */ - uint32_t count = Timeout * (SystemCoreClock / 8U /1000U); - - do - { - if (count-- == 0U) - { - return SDMMC_ERROR_TIMEOUT; - } - sta_reg = SDIOx->STA; - }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || - ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); - - if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) - { - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); - - return SDMMC_ERROR_CMD_RSP_TIMEOUT; - } - else if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL)) - { - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL); - - return SDMMC_ERROR_CMD_CRC_FAIL; - } - else - { - /* Nothing to do */ - } - - /* Clear all the static flags */ - __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); - - /* Check response received is of desired command */ - if(SDIO_GetCommandResponse(SDIOx) != SD_CMD) - { - return SDMMC_ERROR_CMD_CRC_FAIL; - } - - /* We have received response, retrieve it for analysis */ - response_r1 = SDIO_GetResponse(SDIOx, SDIO_RESP1); - - if((response_r1 & SDMMC_OCR_ERRORBITS) == SDMMC_ALLZERO) - { - return SDMMC_ERROR_NONE; - } - else if((response_r1 & SDMMC_OCR_ADDR_OUT_OF_RANGE) == SDMMC_OCR_ADDR_OUT_OF_RANGE) - { - return SDMMC_ERROR_ADDR_OUT_OF_RANGE; - } - else if((response_r1 & SDMMC_OCR_ADDR_MISALIGNED) == SDMMC_OCR_ADDR_MISALIGNED) - { - return SDMMC_ERROR_ADDR_MISALIGNED; - } - else if((response_r1 & SDMMC_OCR_BLOCK_LEN_ERR) == SDMMC_OCR_BLOCK_LEN_ERR) - { - return SDMMC_ERROR_BLOCK_LEN_ERR; - } - else if((response_r1 & SDMMC_OCR_ERASE_SEQ_ERR) == SDMMC_OCR_ERASE_SEQ_ERR) - { - return SDMMC_ERROR_ERASE_SEQ_ERR; - } - else if((response_r1 & SDMMC_OCR_BAD_ERASE_PARAM) == SDMMC_OCR_BAD_ERASE_PARAM) - { - return SDMMC_ERROR_BAD_ERASE_PARAM; - } - else if((response_r1 & SDMMC_OCR_WRITE_PROT_VIOLATION) == SDMMC_OCR_WRITE_PROT_VIOLATION) - { - return SDMMC_ERROR_WRITE_PROT_VIOLATION; - } - else if((response_r1 & SDMMC_OCR_LOCK_UNLOCK_FAILED) == SDMMC_OCR_LOCK_UNLOCK_FAILED) - { - return SDMMC_ERROR_LOCK_UNLOCK_FAILED; - } - else if((response_r1 & SDMMC_OCR_COM_CRC_FAILED) == SDMMC_OCR_COM_CRC_FAILED) - { - return SDMMC_ERROR_COM_CRC_FAILED; - } - else if((response_r1 & SDMMC_OCR_ILLEGAL_CMD) == SDMMC_OCR_ILLEGAL_CMD) - { - return SDMMC_ERROR_ILLEGAL_CMD; - } - else if((response_r1 & SDMMC_OCR_CARD_ECC_FAILED) == SDMMC_OCR_CARD_ECC_FAILED) - { - return SDMMC_ERROR_CARD_ECC_FAILED; - } - else if((response_r1 & SDMMC_OCR_CC_ERROR) == SDMMC_OCR_CC_ERROR) - { - return SDMMC_ERROR_CC_ERR; - } - else if((response_r1 & SDMMC_OCR_STREAM_READ_UNDERRUN) == SDMMC_OCR_STREAM_READ_UNDERRUN) - { - return SDMMC_ERROR_STREAM_READ_UNDERRUN; - } - else if((response_r1 & SDMMC_OCR_STREAM_WRITE_OVERRUN) == SDMMC_OCR_STREAM_WRITE_OVERRUN) - { - return SDMMC_ERROR_STREAM_WRITE_OVERRUN; - } - else if((response_r1 & SDMMC_OCR_CID_CSD_OVERWRITE) == SDMMC_OCR_CID_CSD_OVERWRITE) - { - return SDMMC_ERROR_CID_CSD_OVERWRITE; - } - else if((response_r1 & SDMMC_OCR_WP_ERASE_SKIP) == SDMMC_OCR_WP_ERASE_SKIP) - { - return SDMMC_ERROR_WP_ERASE_SKIP; - } - else if((response_r1 & SDMMC_OCR_CARD_ECC_DISABLED) == SDMMC_OCR_CARD_ECC_DISABLED) - { - return SDMMC_ERROR_CARD_ECC_DISABLED; - } - else if((response_r1 & SDMMC_OCR_ERASE_RESET) == SDMMC_OCR_ERASE_RESET) - { - return SDMMC_ERROR_ERASE_RESET; - } - else if((response_r1 & SDMMC_OCR_AKE_SEQ_ERROR) == SDMMC_OCR_AKE_SEQ_ERROR) - { - return SDMMC_ERROR_AKE_SEQ_ERR; - } - else - { - return SDMMC_ERROR_GENERAL_UNKNOWN_ERR; - } -} - -/** - * @brief Checks for error conditions for R2 (CID or CSD) response. - * @param hsd: SD handle - * @retval SD Card error state - */ -static uint32_t SDMMC_GetCmdResp2(SDIO_TypeDef *SDIOx) -{ - uint32_t sta_reg; - /* 8 is the number of required instructions cycles for the below loop statement. - The SDIO_CMDTIMEOUT is expressed in ms */ - uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); - - do - { - if (count-- == 0U) - { - return SDMMC_ERROR_TIMEOUT; - } - sta_reg = SDIOx->STA; - }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || - ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); - - if (__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) - { - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); - - return SDMMC_ERROR_CMD_RSP_TIMEOUT; - } - else if (__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL)) - { - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL); - - return SDMMC_ERROR_CMD_CRC_FAIL; - } - else - { - /* No error flag set */ - /* Clear all the static flags */ - __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); - } - - return SDMMC_ERROR_NONE; -} - -/** - * @brief Checks for error conditions for R3 (OCR) response. - * @param hsd: SD handle - * @retval SD Card error state - */ -static uint32_t SDMMC_GetCmdResp3(SDIO_TypeDef *SDIOx) -{ - uint32_t sta_reg; - /* 8 is the number of required instructions cycles for the below loop statement. - The SDIO_CMDTIMEOUT is expressed in ms */ - uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); - - do - { - if (count-- == 0U) - { - return SDMMC_ERROR_TIMEOUT; - } - sta_reg = SDIOx->STA; - }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || - ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); - - if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) - { - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); - - return SDMMC_ERROR_CMD_RSP_TIMEOUT; - } - else - { - /* Clear all the static flags */ - __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); - } - - return SDMMC_ERROR_NONE; -} - -/** - * @brief Checks for error conditions for R6 (RCA) response. - * @param hsd: SD handle - * @param SD_CMD: The sent command index - * @param pRCA: Pointer to the variable that will contain the SD card relative - * address RCA - * @retval SD Card error state - */ -static uint32_t SDMMC_GetCmdResp6(SDIO_TypeDef *SDIOx, uint8_t SD_CMD, uint16_t *pRCA) -{ - uint32_t response_r1; - uint32_t sta_reg; - - /* 8 is the number of required instructions cycles for the below loop statement. - The SDIO_CMDTIMEOUT is expressed in ms */ - uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); - - do - { - if (count-- == 0U) - { - return SDMMC_ERROR_TIMEOUT; - } - sta_reg = SDIOx->STA; - }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || - ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); - - if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) - { - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); - - return SDMMC_ERROR_CMD_RSP_TIMEOUT; - } - else if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL)) - { - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL); - - return SDMMC_ERROR_CMD_CRC_FAIL; - } - else - { - /* Nothing to do */ - } - - /* Check response received is of desired command */ - if(SDIO_GetCommandResponse(SDIOx) != SD_CMD) - { - return SDMMC_ERROR_CMD_CRC_FAIL; - } - - /* Clear all the static flags */ - __SDIO_CLEAR_FLAG(SDIOx, SDIO_STATIC_CMD_FLAGS); - - /* We have received response, retrieve it. */ - response_r1 = SDIO_GetResponse(SDIOx, SDIO_RESP1); - - if((response_r1 & (SDMMC_R6_GENERAL_UNKNOWN_ERROR | SDMMC_R6_ILLEGAL_CMD | SDMMC_R6_COM_CRC_FAILED)) == SDMMC_ALLZERO) - { - *pRCA = (uint16_t) (response_r1 >> 16); - - return SDMMC_ERROR_NONE; - } - else if((response_r1 & SDMMC_R6_ILLEGAL_CMD) == SDMMC_R6_ILLEGAL_CMD) - { - return SDMMC_ERROR_ILLEGAL_CMD; - } - else if((response_r1 & SDMMC_R6_COM_CRC_FAILED) == SDMMC_R6_COM_CRC_FAILED) - { - return SDMMC_ERROR_COM_CRC_FAILED; - } - else - { - return SDMMC_ERROR_GENERAL_UNKNOWN_ERR; - } -} - -/** - * @brief Checks for error conditions for R7 response. - * @param hsd: SD handle - * @retval SD Card error state - */ -static uint32_t SDMMC_GetCmdResp7(SDIO_TypeDef *SDIOx) -{ - uint32_t sta_reg; - /* 8 is the number of required instructions cycles for the below loop statement. - The SDIO_CMDTIMEOUT is expressed in ms */ - uint32_t count = SDIO_CMDTIMEOUT * (SystemCoreClock / 8U /1000U); - - do - { - if (count-- == 0U) - { - return SDMMC_ERROR_TIMEOUT; - } - sta_reg = SDIOx->STA; - }while(((sta_reg & (SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CMDREND | SDIO_FLAG_CTIMEOUT)) == 0U) || - ((sta_reg & SDIO_FLAG_CMDACT) != 0U )); - - if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT)) - { - /* Card is SD V2.0 compliant */ - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CTIMEOUT); - - return SDMMC_ERROR_CMD_RSP_TIMEOUT; - } - else if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL)) - { - /* Card is SD V2.0 compliant */ - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CCRCFAIL); - - return SDMMC_ERROR_CMD_CRC_FAIL; - } - else - { - /* Nothing to do */ - } - - if(__SDIO_GET_FLAG(SDIOx, SDIO_FLAG_CMDREND)) - { - /* Card is SD V2.0 compliant */ - __SDIO_CLEAR_FLAG(SDIOx, SDIO_FLAG_CMDREND); - } - - return SDMMC_ERROR_NONE; - -} - -/** - * @brief Send the Send EXT_CSD command and check the response. - * @param SDIOx: Pointer to SDMMC register base - * @param Argument: Command Argument - * @retval HAL status - */ -uint32_t SDMMC_CmdSendEXTCSD(SDIO_TypeDef *SDIOx, uint32_t Argument) -{ - SDIO_CmdInitTypeDef sdmmc_cmdinit; - uint32_t errorstate; - - /* Send CMD9 SEND_CSD */ - sdmmc_cmdinit.Argument = Argument; - sdmmc_cmdinit.CmdIndex = SDMMC_CMD_HS_SEND_EXT_CSD; - sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT; - sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO; - sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE; - (void)SDIO_SendCommand(SDIOx, &sdmmc_cmdinit); - - /* Check for error conditions */ - errorstate = SDMMC_GetCmdResp1(SDIOx, SDMMC_CMD_HS_SEND_EXT_CSD,SDIO_CMDTIMEOUT); - - return errorstate; -} - - -/** - * @} - */ - -#endif /* HAL_SD_MODULE_ENABLED || HAL_MMC_MODULE_ENABLED */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* SDIO */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_spi.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_spi.c deleted file mode 100644 index 2fde18057e5321b..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_spi.c +++ /dev/null @@ -1,626 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_spi.c - * @author MCD Application Team - * @brief SPI LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_spi.h" -#include "stm32f4xx_ll_bus.h" -#include "stm32f4xx_ll_rcc.h" - -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) - -/** @addtogroup SPI_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SPI_LL_Private_Constants SPI Private Constants - * @{ - */ -/* SPI registers Masks */ -#define SPI_CR1_CLEAR_MASK (SPI_CR1_CPHA | SPI_CR1_CPOL | SPI_CR1_MSTR | \ - SPI_CR1_BR | SPI_CR1_LSBFIRST | SPI_CR1_SSI | \ - SPI_CR1_SSM | SPI_CR1_RXONLY | SPI_CR1_DFF | \ - SPI_CR1_CRCNEXT | SPI_CR1_CRCEN | SPI_CR1_BIDIOE | \ - SPI_CR1_BIDIMODE) -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SPI_LL_Private_Macros SPI Private Macros - * @{ - */ -#define IS_LL_SPI_TRANSFER_DIRECTION(__VALUE__) (((__VALUE__) == LL_SPI_FULL_DUPLEX) \ - || ((__VALUE__) == LL_SPI_SIMPLEX_RX) \ - || ((__VALUE__) == LL_SPI_HALF_DUPLEX_RX) \ - || ((__VALUE__) == LL_SPI_HALF_DUPLEX_TX)) - -#define IS_LL_SPI_MODE(__VALUE__) (((__VALUE__) == LL_SPI_MODE_MASTER) \ - || ((__VALUE__) == LL_SPI_MODE_SLAVE)) - -#define IS_LL_SPI_DATAWIDTH(__VALUE__) (((__VALUE__) == LL_SPI_DATAWIDTH_8BIT) \ - || ((__VALUE__) == LL_SPI_DATAWIDTH_16BIT)) - -#define IS_LL_SPI_POLARITY(__VALUE__) (((__VALUE__) == LL_SPI_POLARITY_LOW) \ - || ((__VALUE__) == LL_SPI_POLARITY_HIGH)) - -#define IS_LL_SPI_PHASE(__VALUE__) (((__VALUE__) == LL_SPI_PHASE_1EDGE) \ - || ((__VALUE__) == LL_SPI_PHASE_2EDGE)) - -#define IS_LL_SPI_NSS(__VALUE__) (((__VALUE__) == LL_SPI_NSS_SOFT) \ - || ((__VALUE__) == LL_SPI_NSS_HARD_INPUT) \ - || ((__VALUE__) == LL_SPI_NSS_HARD_OUTPUT)) - -#define IS_LL_SPI_BAUDRATE(__VALUE__) (((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV2) \ - || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV4) \ - || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV8) \ - || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV16) \ - || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV32) \ - || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV64) \ - || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV128) \ - || ((__VALUE__) == LL_SPI_BAUDRATEPRESCALER_DIV256)) - -#define IS_LL_SPI_BITORDER(__VALUE__) (((__VALUE__) == LL_SPI_LSB_FIRST) \ - || ((__VALUE__) == LL_SPI_MSB_FIRST)) - -#define IS_LL_SPI_CRCCALCULATION(__VALUE__) (((__VALUE__) == LL_SPI_CRCCALCULATION_ENABLE) \ - || ((__VALUE__) == LL_SPI_CRCCALCULATION_DISABLE)) - -#define IS_LL_SPI_CRC_POLYNOMIAL(__VALUE__) ((__VALUE__) >= 0x1U) - -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SPI_LL_Exported_Functions - * @{ - */ - -/** @addtogroup SPI_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize the SPI registers to their default reset values. - * @param SPIx SPI Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: SPI registers are de-initialized - * - ERROR: SPI registers are not de-initialized - */ -ErrorStatus LL_SPI_DeInit(SPI_TypeDef *SPIx) -{ - ErrorStatus status = ERROR; - - /* Check the parameters */ - assert_param(IS_SPI_ALL_INSTANCE(SPIx)); - -#if defined(SPI1) - if (SPIx == SPI1) - { - /* Force reset of SPI clock */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI1); - - /* Release reset of SPI clock */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI1); - - status = SUCCESS; - } -#endif /* SPI1 */ -#if defined(SPI2) - if (SPIx == SPI2) - { - /* Force reset of SPI clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_SPI2); - - /* Release reset of SPI clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_SPI2); - - status = SUCCESS; - } -#endif /* SPI2 */ -#if defined(SPI3) - if (SPIx == SPI3) - { - /* Force reset of SPI clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_SPI3); - - /* Release reset of SPI clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_SPI3); - - status = SUCCESS; - } -#endif /* SPI3 */ -#if defined(SPI4) - if (SPIx == SPI4) - { - /* Force reset of SPI clock */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI4); - - /* Release reset of SPI clock */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI4); - - status = SUCCESS; - } -#endif /* SPI4 */ -#if defined(SPI5) - if (SPIx == SPI5) - { - /* Force reset of SPI clock */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI5); - - /* Release reset of SPI clock */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI5); - - status = SUCCESS; - } -#endif /* SPI5 */ -#if defined(SPI6) - if (SPIx == SPI6) - { - /* Force reset of SPI clock */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_SPI6); - - /* Release reset of SPI clock */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_SPI6); - - status = SUCCESS; - } -#endif /* SPI6 */ - - return status; -} - -/** - * @brief Initialize the SPI registers according to the specified parameters in SPI_InitStruct. - * @note As some bits in SPI configuration registers can only be written when the SPI is disabled (SPI_CR1_SPE bit =0), - * SPI peripheral should be in disabled state prior calling this function. Otherwise, ERROR result will be returned. - * @param SPIx SPI Instance - * @param SPI_InitStruct pointer to a @ref LL_SPI_InitTypeDef structure - * @retval An ErrorStatus enumeration value. (Return always SUCCESS) - */ -ErrorStatus LL_SPI_Init(SPI_TypeDef *SPIx, LL_SPI_InitTypeDef *SPI_InitStruct) -{ - ErrorStatus status = ERROR; - - /* Check the SPI Instance SPIx*/ - assert_param(IS_SPI_ALL_INSTANCE(SPIx)); - - /* Check the SPI parameters from SPI_InitStruct*/ - assert_param(IS_LL_SPI_TRANSFER_DIRECTION(SPI_InitStruct->TransferDirection)); - assert_param(IS_LL_SPI_MODE(SPI_InitStruct->Mode)); - assert_param(IS_LL_SPI_DATAWIDTH(SPI_InitStruct->DataWidth)); - assert_param(IS_LL_SPI_POLARITY(SPI_InitStruct->ClockPolarity)); - assert_param(IS_LL_SPI_PHASE(SPI_InitStruct->ClockPhase)); - assert_param(IS_LL_SPI_NSS(SPI_InitStruct->NSS)); - assert_param(IS_LL_SPI_BAUDRATE(SPI_InitStruct->BaudRate)); - assert_param(IS_LL_SPI_BITORDER(SPI_InitStruct->BitOrder)); - assert_param(IS_LL_SPI_CRCCALCULATION(SPI_InitStruct->CRCCalculation)); - - if (LL_SPI_IsEnabled(SPIx) == 0x00000000U) - { - /*---------------------------- SPIx CR1 Configuration ------------------------ - * Configure SPIx CR1 with parameters: - * - TransferDirection: SPI_CR1_BIDIMODE, SPI_CR1_BIDIOE and SPI_CR1_RXONLY bits - * - Master/Slave Mode: SPI_CR1_MSTR bit - * - DataWidth: SPI_CR1_DFF bit - * - ClockPolarity: SPI_CR1_CPOL bit - * - ClockPhase: SPI_CR1_CPHA bit - * - NSS management: SPI_CR1_SSM bit - * - BaudRate prescaler: SPI_CR1_BR[2:0] bits - * - BitOrder: SPI_CR1_LSBFIRST bit - * - CRCCalculation: SPI_CR1_CRCEN bit - */ - MODIFY_REG(SPIx->CR1, - SPI_CR1_CLEAR_MASK, - SPI_InitStruct->TransferDirection | SPI_InitStruct->Mode | SPI_InitStruct->DataWidth | - SPI_InitStruct->ClockPolarity | SPI_InitStruct->ClockPhase | - SPI_InitStruct->NSS | SPI_InitStruct->BaudRate | - SPI_InitStruct->BitOrder | SPI_InitStruct->CRCCalculation); - - /*---------------------------- SPIx CR2 Configuration ------------------------ - * Configure SPIx CR2 with parameters: - * - NSS management: SSOE bit - */ - MODIFY_REG(SPIx->CR2, SPI_CR2_SSOE, (SPI_InitStruct->NSS >> 16U)); - - /*---------------------------- SPIx CRCPR Configuration ---------------------- - * Configure SPIx CRCPR with parameters: - * - CRCPoly: CRCPOLY[15:0] bits - */ - if (SPI_InitStruct->CRCCalculation == LL_SPI_CRCCALCULATION_ENABLE) - { - assert_param(IS_LL_SPI_CRC_POLYNOMIAL(SPI_InitStruct->CRCPoly)); - LL_SPI_SetCRCPolynomial(SPIx, SPI_InitStruct->CRCPoly); - } - status = SUCCESS; - } - - /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */ - CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD); - return status; -} - -/** - * @brief Set each @ref LL_SPI_InitTypeDef field to default value. - * @param SPI_InitStruct pointer to a @ref LL_SPI_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_SPI_StructInit(LL_SPI_InitTypeDef *SPI_InitStruct) -{ - /* Set SPI_InitStruct fields to default values */ - SPI_InitStruct->TransferDirection = LL_SPI_FULL_DUPLEX; - SPI_InitStruct->Mode = LL_SPI_MODE_SLAVE; - SPI_InitStruct->DataWidth = LL_SPI_DATAWIDTH_8BIT; - SPI_InitStruct->ClockPolarity = LL_SPI_POLARITY_LOW; - SPI_InitStruct->ClockPhase = LL_SPI_PHASE_1EDGE; - SPI_InitStruct->NSS = LL_SPI_NSS_HARD_INPUT; - SPI_InitStruct->BaudRate = LL_SPI_BAUDRATEPRESCALER_DIV2; - SPI_InitStruct->BitOrder = LL_SPI_MSB_FIRST; - SPI_InitStruct->CRCCalculation = LL_SPI_CRCCALCULATION_DISABLE; - SPI_InitStruct->CRCPoly = 7U; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup I2S_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2S_LL_Private_Constants I2S Private Constants - * @{ - */ -/* I2S registers Masks */ -#define I2S_I2SCFGR_CLEAR_MASK (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN | \ - SPI_I2SCFGR_CKPOL | SPI_I2SCFGR_I2SSTD | \ - SPI_I2SCFGR_I2SCFG | SPI_I2SCFGR_I2SMOD ) - -#define I2S_I2SPR_CLEAR_MASK 0x0002U -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2S_LL_Private_Macros I2S Private Macros - * @{ - */ - -#define IS_LL_I2S_DATAFORMAT(__VALUE__) (((__VALUE__) == LL_I2S_DATAFORMAT_16B) \ - || ((__VALUE__) == LL_I2S_DATAFORMAT_16B_EXTENDED) \ - || ((__VALUE__) == LL_I2S_DATAFORMAT_24B) \ - || ((__VALUE__) == LL_I2S_DATAFORMAT_32B)) - -#define IS_LL_I2S_CPOL(__VALUE__) (((__VALUE__) == LL_I2S_POLARITY_LOW) \ - || ((__VALUE__) == LL_I2S_POLARITY_HIGH)) - -#define IS_LL_I2S_STANDARD(__VALUE__) (((__VALUE__) == LL_I2S_STANDARD_PHILIPS) \ - || ((__VALUE__) == LL_I2S_STANDARD_MSB) \ - || ((__VALUE__) == LL_I2S_STANDARD_LSB) \ - || ((__VALUE__) == LL_I2S_STANDARD_PCM_SHORT) \ - || ((__VALUE__) == LL_I2S_STANDARD_PCM_LONG)) - -#define IS_LL_I2S_MODE(__VALUE__) (((__VALUE__) == LL_I2S_MODE_SLAVE_TX) \ - || ((__VALUE__) == LL_I2S_MODE_SLAVE_RX) \ - || ((__VALUE__) == LL_I2S_MODE_MASTER_TX) \ - || ((__VALUE__) == LL_I2S_MODE_MASTER_RX)) - -#define IS_LL_I2S_MCLK_OUTPUT(__VALUE__) (((__VALUE__) == LL_I2S_MCLK_OUTPUT_ENABLE) \ - || ((__VALUE__) == LL_I2S_MCLK_OUTPUT_DISABLE)) - -#define IS_LL_I2S_AUDIO_FREQ(__VALUE__) ((((__VALUE__) >= LL_I2S_AUDIOFREQ_8K) \ - && ((__VALUE__) <= LL_I2S_AUDIOFREQ_192K)) \ - || ((__VALUE__) == LL_I2S_AUDIOFREQ_DEFAULT)) - -#define IS_LL_I2S_PRESCALER_LINEAR(__VALUE__) ((__VALUE__) >= 0x2U) - -#define IS_LL_I2S_PRESCALER_PARITY(__VALUE__) (((__VALUE__) == LL_I2S_PRESCALER_PARITY_EVEN) \ - || ((__VALUE__) == LL_I2S_PRESCALER_PARITY_ODD)) -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2S_LL_Exported_Functions - * @{ - */ - -/** @addtogroup I2S_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize the SPI/I2S registers to their default reset values. - * @param SPIx SPI Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: SPI registers are de-initialized - * - ERROR: SPI registers are not de-initialized - */ -ErrorStatus LL_I2S_DeInit(SPI_TypeDef *SPIx) -{ - return LL_SPI_DeInit(SPIx); -} - -/** - * @brief Initializes the SPI/I2S registers according to the specified parameters in I2S_InitStruct. - * @note As some bits in SPI configuration registers can only be written when the SPI is disabled (SPI_CR1_SPE bit =0), - * SPI peripheral should be in disabled state prior calling this function. Otherwise, ERROR result will be returned. - * @param SPIx SPI Instance - * @param I2S_InitStruct pointer to a @ref LL_I2S_InitTypeDef structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: SPI registers are Initialized - * - ERROR: SPI registers are not Initialized - */ -ErrorStatus LL_I2S_Init(SPI_TypeDef *SPIx, LL_I2S_InitTypeDef *I2S_InitStruct) -{ - uint32_t i2sdiv = 2U; - uint32_t i2sodd = 0U; - uint32_t packetlength = 1U; - uint32_t tmp; - uint32_t sourceclock; - ErrorStatus status = ERROR; - - /* Check the I2S parameters */ - assert_param(IS_I2S_ALL_INSTANCE(SPIx)); - assert_param(IS_LL_I2S_MODE(I2S_InitStruct->Mode)); - assert_param(IS_LL_I2S_STANDARD(I2S_InitStruct->Standard)); - assert_param(IS_LL_I2S_DATAFORMAT(I2S_InitStruct->DataFormat)); - assert_param(IS_LL_I2S_MCLK_OUTPUT(I2S_InitStruct->MCLKOutput)); - assert_param(IS_LL_I2S_AUDIO_FREQ(I2S_InitStruct->AudioFreq)); - assert_param(IS_LL_I2S_CPOL(I2S_InitStruct->ClockPolarity)); - - if (LL_I2S_IsEnabled(SPIx) == 0x00000000U) - { - /*---------------------------- SPIx I2SCFGR Configuration -------------------- - * Configure SPIx I2SCFGR with parameters: - * - Mode: SPI_I2SCFGR_I2SCFG[1:0] bit - * - Standard: SPI_I2SCFGR_I2SSTD[1:0] and SPI_I2SCFGR_PCMSYNC bits - * - DataFormat: SPI_I2SCFGR_CHLEN and SPI_I2SCFGR_DATLEN bits - * - ClockPolarity: SPI_I2SCFGR_CKPOL bit - */ - - /* Write to SPIx I2SCFGR */ - MODIFY_REG(SPIx->I2SCFGR, - I2S_I2SCFGR_CLEAR_MASK, - I2S_InitStruct->Mode | I2S_InitStruct->Standard | - I2S_InitStruct->DataFormat | I2S_InitStruct->ClockPolarity | - SPI_I2SCFGR_I2SMOD); - - /*---------------------------- SPIx I2SPR Configuration ---------------------- - * Configure SPIx I2SPR with parameters: - * - MCLKOutput: SPI_I2SPR_MCKOE bit - * - AudioFreq: SPI_I2SPR_I2SDIV[7:0] and SPI_I2SPR_ODD bits - */ - - /* If the requested audio frequency is not the default, compute the prescaler (i2sodd, i2sdiv) - * else, default values are used: i2sodd = 0U, i2sdiv = 2U. - */ - if (I2S_InitStruct->AudioFreq != LL_I2S_AUDIOFREQ_DEFAULT) - { - /* Check the frame length (For the Prescaler computing) - * Default value: LL_I2S_DATAFORMAT_16B (packetlength = 1U). - */ - if (I2S_InitStruct->DataFormat != LL_I2S_DATAFORMAT_16B) - { - /* Packet length is 32 bits */ - packetlength = 2U; - } - - /* If an external I2S clock has to be used, the specific define should be set - in the project configuration or in the stm32f4xx_ll_rcc.h file */ - /* Get the I2S source clock value */ - sourceclock = LL_RCC_GetI2SClockFreq(LL_RCC_I2S1_CLKSOURCE); - - /* Compute the Real divider depending on the MCLK output state with a floating point */ - if (I2S_InitStruct->MCLKOutput == LL_I2S_MCLK_OUTPUT_ENABLE) - { - /* MCLK output is enabled */ - tmp = (((((sourceclock / 256U) * 10U) / I2S_InitStruct->AudioFreq)) + 5U); - } - else - { - /* MCLK output is disabled */ - tmp = (((((sourceclock / (32U * packetlength)) * 10U) / I2S_InitStruct->AudioFreq)) + 5U); - } - - /* Remove the floating point */ - tmp = tmp / 10U; - - /* Check the parity of the divider */ - i2sodd = (tmp & (uint16_t)0x0001U); - - /* Compute the i2sdiv prescaler */ - i2sdiv = ((tmp - i2sodd) / 2U); - - /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ - i2sodd = (i2sodd << 8U); - } - - /* Test if the divider is 1 or 0 or greater than 0xFF */ - if ((i2sdiv < 2U) || (i2sdiv > 0xFFU)) - { - /* Set the default values */ - i2sdiv = 2U; - i2sodd = 0U; - } - - /* Write to SPIx I2SPR register the computed value */ - WRITE_REG(SPIx->I2SPR, i2sdiv | i2sodd | I2S_InitStruct->MCLKOutput); - - status = SUCCESS; - } - return status; -} - -/** - * @brief Set each @ref LL_I2S_InitTypeDef field to default value. - * @param I2S_InitStruct pointer to a @ref LL_I2S_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_I2S_StructInit(LL_I2S_InitTypeDef *I2S_InitStruct) -{ - /*--------------- Reset I2S init structure parameters values -----------------*/ - I2S_InitStruct->Mode = LL_I2S_MODE_SLAVE_TX; - I2S_InitStruct->Standard = LL_I2S_STANDARD_PHILIPS; - I2S_InitStruct->DataFormat = LL_I2S_DATAFORMAT_16B; - I2S_InitStruct->MCLKOutput = LL_I2S_MCLK_OUTPUT_DISABLE; - I2S_InitStruct->AudioFreq = LL_I2S_AUDIOFREQ_DEFAULT; - I2S_InitStruct->ClockPolarity = LL_I2S_POLARITY_LOW; -} - -/** - * @brief Set linear and parity prescaler. - * @note To calculate value of PrescalerLinear(I2SDIV[7:0] bits) and PrescalerParity(ODD bit)\n - * Check Audio frequency table and formulas inside Reference Manual (SPI/I2S). - * @param SPIx SPI Instance - * @param PrescalerLinear value Min_Data=0x02 and Max_Data=0xFF. - * @param PrescalerParity This parameter can be one of the following values: - * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN - * @arg @ref LL_I2S_PRESCALER_PARITY_ODD - * @retval None - */ -void LL_I2S_ConfigPrescaler(SPI_TypeDef *SPIx, uint32_t PrescalerLinear, uint32_t PrescalerParity) -{ - /* Check the I2S parameters */ - assert_param(IS_I2S_ALL_INSTANCE(SPIx)); - assert_param(IS_LL_I2S_PRESCALER_LINEAR(PrescalerLinear)); - assert_param(IS_LL_I2S_PRESCALER_PARITY(PrescalerParity)); - - /* Write to SPIx I2SPR */ - MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_I2SDIV | SPI_I2SPR_ODD, PrescalerLinear | (PrescalerParity << 8U)); -} - -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) -/** - * @brief Configures the full duplex mode for the I2Sx peripheral using its extension - * I2Sxext according to the specified parameters in the I2S_InitStruct. - * @note The structure pointed by I2S_InitStruct parameter should be the same - * used for the master I2S peripheral. In this case, if the master is - * configured as transmitter, the slave will be receiver and vice versa. - * Or you can force a different mode by modifying the field I2S_Mode to the - * value I2S_SlaveRx or I2S_SlaveTx independently of the master configuration. - * @param I2Sxext SPI Instance - * @param I2S_InitStruct pointer to a @ref LL_I2S_InitTypeDef structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: I2Sxext registers are Initialized - * - ERROR: I2Sxext registers are not Initialized - */ -ErrorStatus LL_I2S_InitFullDuplex(SPI_TypeDef *I2Sxext, LL_I2S_InitTypeDef *I2S_InitStruct) -{ - uint32_t mode = 0U; - ErrorStatus status = ERROR; - - /* Check the I2S parameters */ - assert_param(IS_I2S_EXT_ALL_INSTANCE(I2Sxext)); - assert_param(IS_LL_I2S_MODE(I2S_InitStruct->Mode)); - assert_param(IS_LL_I2S_STANDARD(I2S_InitStruct->Standard)); - assert_param(IS_LL_I2S_DATAFORMAT(I2S_InitStruct->DataFormat)); - assert_param(IS_LL_I2S_CPOL(I2S_InitStruct->ClockPolarity)); - - if (LL_I2S_IsEnabled(I2Sxext) == 0x00000000U) - { - /*---------------------------- SPIx I2SCFGR Configuration -------------------- - * Configure SPIx I2SCFGR with parameters: - * - Mode: SPI_I2SCFGR_I2SCFG[1:0] bit - * - Standard: SPI_I2SCFGR_I2SSTD[1:0] and SPI_I2SCFGR_PCMSYNC bits - * - DataFormat: SPI_I2SCFGR_CHLEN and SPI_I2SCFGR_DATLEN bits - * - ClockPolarity: SPI_I2SCFGR_CKPOL bit - */ - - /* Reset I2SPR registers */ - WRITE_REG(I2Sxext->I2SPR, I2S_I2SPR_CLEAR_MASK); - - /* Get the mode to be configured for the extended I2S */ - if ((I2S_InitStruct->Mode == LL_I2S_MODE_MASTER_TX) || (I2S_InitStruct->Mode == LL_I2S_MODE_SLAVE_TX)) - { - mode = LL_I2S_MODE_SLAVE_RX; - } - else - { - if ((I2S_InitStruct->Mode == LL_I2S_MODE_MASTER_RX) || (I2S_InitStruct->Mode == LL_I2S_MODE_SLAVE_RX)) - { - mode = LL_I2S_MODE_SLAVE_TX; - } - } - - /* Write to SPIx I2SCFGR */ - MODIFY_REG(I2Sxext->I2SCFGR, - I2S_I2SCFGR_CLEAR_MASK, - I2S_InitStruct->Standard | - I2S_InitStruct->DataFormat | I2S_InitStruct->ClockPolarity | - SPI_I2SCFGR_I2SMOD | mode); - - status = SUCCESS; - } - return status; -} -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_tim.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_tim.c deleted file mode 100644 index 089c5adebbd488e..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_tim.c +++ /dev/null @@ -1,1191 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_tim.c - * @author MCD Application Team - * @brief TIM LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_tim.h" -#include "stm32f4xx_ll_bus.h" - -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (TIM1) || defined (TIM2) || defined (TIM3) || defined (TIM4) || defined (TIM5) || defined (TIM6) || defined (TIM7) || defined (TIM8) || defined (TIM9) || defined (TIM10) || defined (TIM11) || defined (TIM12) || defined (TIM13) || defined (TIM14) - -/** @addtogroup TIM_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup TIM_LL_Private_Macros - * @{ - */ -#define IS_LL_TIM_COUNTERMODE(__VALUE__) (((__VALUE__) == LL_TIM_COUNTERMODE_UP) \ - || ((__VALUE__) == LL_TIM_COUNTERMODE_DOWN) \ - || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_UP) \ - || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_DOWN) \ - || ((__VALUE__) == LL_TIM_COUNTERMODE_CENTER_UP_DOWN)) - -#define IS_LL_TIM_CLOCKDIVISION(__VALUE__) (((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV1) \ - || ((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV2) \ - || ((__VALUE__) == LL_TIM_CLOCKDIVISION_DIV4)) - -#define IS_LL_TIM_OCMODE(__VALUE__) (((__VALUE__) == LL_TIM_OCMODE_FROZEN) \ - || ((__VALUE__) == LL_TIM_OCMODE_ACTIVE) \ - || ((__VALUE__) == LL_TIM_OCMODE_INACTIVE) \ - || ((__VALUE__) == LL_TIM_OCMODE_TOGGLE) \ - || ((__VALUE__) == LL_TIM_OCMODE_FORCED_INACTIVE) \ - || ((__VALUE__) == LL_TIM_OCMODE_FORCED_ACTIVE) \ - || ((__VALUE__) == LL_TIM_OCMODE_PWM1) \ - || ((__VALUE__) == LL_TIM_OCMODE_PWM2)) - -#define IS_LL_TIM_OCSTATE(__VALUE__) (((__VALUE__) == LL_TIM_OCSTATE_DISABLE) \ - || ((__VALUE__) == LL_TIM_OCSTATE_ENABLE)) - -#define IS_LL_TIM_OCPOLARITY(__VALUE__) (((__VALUE__) == LL_TIM_OCPOLARITY_HIGH) \ - || ((__VALUE__) == LL_TIM_OCPOLARITY_LOW)) - -#define IS_LL_TIM_OCIDLESTATE(__VALUE__) (((__VALUE__) == LL_TIM_OCIDLESTATE_LOW) \ - || ((__VALUE__) == LL_TIM_OCIDLESTATE_HIGH)) - -#define IS_LL_TIM_ACTIVEINPUT(__VALUE__) (((__VALUE__) == LL_TIM_ACTIVEINPUT_DIRECTTI) \ - || ((__VALUE__) == LL_TIM_ACTIVEINPUT_INDIRECTTI) \ - || ((__VALUE__) == LL_TIM_ACTIVEINPUT_TRC)) - -#define IS_LL_TIM_ICPSC(__VALUE__) (((__VALUE__) == LL_TIM_ICPSC_DIV1) \ - || ((__VALUE__) == LL_TIM_ICPSC_DIV2) \ - || ((__VALUE__) == LL_TIM_ICPSC_DIV4) \ - || ((__VALUE__) == LL_TIM_ICPSC_DIV8)) - -#define IS_LL_TIM_IC_FILTER(__VALUE__) (((__VALUE__) == LL_TIM_IC_FILTER_FDIV1) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N2) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N4) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV1_N8) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV2_N6) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV2_N8) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV4_N6) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV4_N8) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV8_N6) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV8_N8) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N5) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N6) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV16_N8) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N5) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N6) \ - || ((__VALUE__) == LL_TIM_IC_FILTER_FDIV32_N8)) - -#define IS_LL_TIM_IC_POLARITY(__VALUE__) (((__VALUE__) == LL_TIM_IC_POLARITY_RISING) \ - || ((__VALUE__) == LL_TIM_IC_POLARITY_FALLING) \ - || ((__VALUE__) == LL_TIM_IC_POLARITY_BOTHEDGE)) - -#define IS_LL_TIM_ENCODERMODE(__VALUE__) (((__VALUE__) == LL_TIM_ENCODERMODE_X2_TI1) \ - || ((__VALUE__) == LL_TIM_ENCODERMODE_X2_TI2) \ - || ((__VALUE__) == LL_TIM_ENCODERMODE_X4_TI12)) - -#define IS_LL_TIM_IC_POLARITY_ENCODER(__VALUE__) (((__VALUE__) == LL_TIM_IC_POLARITY_RISING) \ - || ((__VALUE__) == LL_TIM_IC_POLARITY_FALLING)) - -#define IS_LL_TIM_OSSR_STATE(__VALUE__) (((__VALUE__) == LL_TIM_OSSR_DISABLE) \ - || ((__VALUE__) == LL_TIM_OSSR_ENABLE)) - -#define IS_LL_TIM_OSSI_STATE(__VALUE__) (((__VALUE__) == LL_TIM_OSSI_DISABLE) \ - || ((__VALUE__) == LL_TIM_OSSI_ENABLE)) - -#define IS_LL_TIM_LOCK_LEVEL(__VALUE__) (((__VALUE__) == LL_TIM_LOCKLEVEL_OFF) \ - || ((__VALUE__) == LL_TIM_LOCKLEVEL_1) \ - || ((__VALUE__) == LL_TIM_LOCKLEVEL_2) \ - || ((__VALUE__) == LL_TIM_LOCKLEVEL_3)) - -#define IS_LL_TIM_BREAK_STATE(__VALUE__) (((__VALUE__) == LL_TIM_BREAK_DISABLE) \ - || ((__VALUE__) == LL_TIM_BREAK_ENABLE)) - -#define IS_LL_TIM_BREAK_POLARITY(__VALUE__) (((__VALUE__) == LL_TIM_BREAK_POLARITY_LOW) \ - || ((__VALUE__) == LL_TIM_BREAK_POLARITY_HIGH)) - -#define IS_LL_TIM_AUTOMATIC_OUTPUT_STATE(__VALUE__) (((__VALUE__) == LL_TIM_AUTOMATICOUTPUT_DISABLE) \ - || ((__VALUE__) == LL_TIM_AUTOMATICOUTPUT_ENABLE)) -/** - * @} - */ - - -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup TIM_LL_Private_Functions TIM Private Functions - * @{ - */ -static ErrorStatus OC1Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct); -static ErrorStatus OC2Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct); -static ErrorStatus OC3Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct); -static ErrorStatus OC4Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct); -static ErrorStatus IC1Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); -static ErrorStatus IC2Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); -static ErrorStatus IC3Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); -static ErrorStatus IC4Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup TIM_LL_Exported_Functions - * @{ - */ - -/** @addtogroup TIM_LL_EF_Init - * @{ - */ - -/** - * @brief Set TIMx registers to their reset values. - * @param TIMx Timer instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: invalid TIMx instance - */ -ErrorStatus LL_TIM_DeInit(TIM_TypeDef *TIMx) -{ - ErrorStatus result = SUCCESS; - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(TIMx)); - - if (TIMx == TIM1) - { - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM1); - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM1); - } -#if defined(TIM2) - else if (TIMx == TIM2) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM2); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM2); - } -#endif /* TIM2 */ -#if defined(TIM3) - else if (TIMx == TIM3) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM3); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM3); - } -#endif /* TIM3 */ -#if defined(TIM4) - else if (TIMx == TIM4) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM4); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM4); - } -#endif /* TIM4 */ -#if defined(TIM5) - else if (TIMx == TIM5) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM5); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM5); - } -#endif /* TIM5 */ -#if defined(TIM6) - else if (TIMx == TIM6) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM6); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM6); - } -#endif /* TIM6 */ -#if defined (TIM7) - else if (TIMx == TIM7) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM7); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM7); - } -#endif /* TIM7 */ -#if defined(TIM8) - else if (TIMx == TIM8) - { - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM8); - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM8); - } -#endif /* TIM8 */ -#if defined(TIM9) - else if (TIMx == TIM9) - { - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM9); - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM9); - } -#endif /* TIM9 */ -#if defined(TIM10) - else if (TIMx == TIM10) - { - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM10); - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM10); - } -#endif /* TIM10 */ -#if defined(TIM11) - else if (TIMx == TIM11) - { - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_TIM11); - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_TIM11); - } -#endif /* TIM11 */ -#if defined(TIM12) - else if (TIMx == TIM12) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM12); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM12); - } -#endif /* TIM12 */ -#if defined(TIM13) - else if (TIMx == TIM13) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM13); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM13); - } -#endif /* TIM13 */ -#if defined(TIM14) - else if (TIMx == TIM14) - { - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_TIM14); - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_TIM14); - } -#endif /* TIM14 */ - else - { - result = ERROR; - } - - return result; -} - -/** - * @brief Set the fields of the time base unit configuration data structure - * to their default values. - * @param TIM_InitStruct pointer to a @ref LL_TIM_InitTypeDef structure (time base unit configuration data structure) - * @retval None - */ -void LL_TIM_StructInit(LL_TIM_InitTypeDef *TIM_InitStruct) -{ - /* Set the default configuration */ - TIM_InitStruct->Prescaler = (uint16_t)0x0000; - TIM_InitStruct->CounterMode = LL_TIM_COUNTERMODE_UP; - TIM_InitStruct->Autoreload = 0xFFFFFFFFU; - TIM_InitStruct->ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; - TIM_InitStruct->RepetitionCounter = 0x00000000U; -} - -/** - * @brief Configure the TIMx time base unit. - * @param TIMx Timer Instance - * @param TIM_InitStruct pointer to a @ref LL_TIM_InitTypeDef structure - * (TIMx time base unit configuration data structure) - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -ErrorStatus LL_TIM_Init(TIM_TypeDef *TIMx, LL_TIM_InitTypeDef *TIM_InitStruct) -{ - uint32_t tmpcr1; - - /* Check the parameters */ - assert_param(IS_TIM_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_COUNTERMODE(TIM_InitStruct->CounterMode)); - assert_param(IS_LL_TIM_CLOCKDIVISION(TIM_InitStruct->ClockDivision)); - - tmpcr1 = LL_TIM_ReadReg(TIMx, CR1); - - if (IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx)) - { - /* Select the Counter Mode */ - MODIFY_REG(tmpcr1, (TIM_CR1_DIR | TIM_CR1_CMS), TIM_InitStruct->CounterMode); - } - - if (IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx)) - { - /* Set the clock division */ - MODIFY_REG(tmpcr1, TIM_CR1_CKD, TIM_InitStruct->ClockDivision); - } - - /* Write to TIMx CR1 */ - LL_TIM_WriteReg(TIMx, CR1, tmpcr1); - - /* Set the Autoreload value */ - LL_TIM_SetAutoReload(TIMx, TIM_InitStruct->Autoreload); - - /* Set the Prescaler value */ - LL_TIM_SetPrescaler(TIMx, TIM_InitStruct->Prescaler); - - if (IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx)) - { - /* Set the Repetition Counter value */ - LL_TIM_SetRepetitionCounter(TIMx, TIM_InitStruct->RepetitionCounter); - } - - /* Generate an update event to reload the Prescaler - and the repetition counter value (if applicable) immediately */ - LL_TIM_GenerateEvent_UPDATE(TIMx); - - return SUCCESS; -} - -/** - * @brief Set the fields of the TIMx output channel configuration data - * structure to their default values. - * @param TIM_OC_InitStruct pointer to a @ref LL_TIM_OC_InitTypeDef structure - * (the output channel configuration data structure) - * @retval None - */ -void LL_TIM_OC_StructInit(LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct) -{ - /* Set the default configuration */ - TIM_OC_InitStruct->OCMode = LL_TIM_OCMODE_FROZEN; - TIM_OC_InitStruct->OCState = LL_TIM_OCSTATE_DISABLE; - TIM_OC_InitStruct->OCNState = LL_TIM_OCSTATE_DISABLE; - TIM_OC_InitStruct->CompareValue = 0x00000000U; - TIM_OC_InitStruct->OCPolarity = LL_TIM_OCPOLARITY_HIGH; - TIM_OC_InitStruct->OCNPolarity = LL_TIM_OCPOLARITY_HIGH; - TIM_OC_InitStruct->OCIdleState = LL_TIM_OCIDLESTATE_LOW; - TIM_OC_InitStruct->OCNIdleState = LL_TIM_OCIDLESTATE_LOW; -} - -/** - * @brief Configure the TIMx output channel. - * @param TIMx Timer Instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param TIM_OC_InitStruct pointer to a @ref LL_TIM_OC_InitTypeDef structure (TIMx output channel configuration - * data structure) - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx output channel is initialized - * - ERROR: TIMx output channel is not initialized - */ -ErrorStatus LL_TIM_OC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct) -{ - ErrorStatus result = ERROR; - - switch (Channel) - { - case LL_TIM_CHANNEL_CH1: - result = OC1Config(TIMx, TIM_OC_InitStruct); - break; - case LL_TIM_CHANNEL_CH2: - result = OC2Config(TIMx, TIM_OC_InitStruct); - break; - case LL_TIM_CHANNEL_CH3: - result = OC3Config(TIMx, TIM_OC_InitStruct); - break; - case LL_TIM_CHANNEL_CH4: - result = OC4Config(TIMx, TIM_OC_InitStruct); - break; - default: - break; - } - - return result; -} - -/** - * @brief Set the fields of the TIMx input channel configuration data - * structure to their default values. - * @param TIM_ICInitStruct pointer to a @ref LL_TIM_IC_InitTypeDef structure (the input channel configuration - * data structure) - * @retval None - */ -void LL_TIM_IC_StructInit(LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) -{ - /* Set the default configuration */ - TIM_ICInitStruct->ICPolarity = LL_TIM_IC_POLARITY_RISING; - TIM_ICInitStruct->ICActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI; - TIM_ICInitStruct->ICPrescaler = LL_TIM_ICPSC_DIV1; - TIM_ICInitStruct->ICFilter = LL_TIM_IC_FILTER_FDIV1; -} - -/** - * @brief Configure the TIMx input channel. - * @param TIMx Timer Instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param TIM_IC_InitStruct pointer to a @ref LL_TIM_IC_InitTypeDef structure (TIMx input channel configuration data - * structure) - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx output channel is initialized - * - ERROR: TIMx output channel is not initialized - */ -ErrorStatus LL_TIM_IC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_IC_InitTypeDef *TIM_IC_InitStruct) -{ - ErrorStatus result = ERROR; - - switch (Channel) - { - case LL_TIM_CHANNEL_CH1: - result = IC1Config(TIMx, TIM_IC_InitStruct); - break; - case LL_TIM_CHANNEL_CH2: - result = IC2Config(TIMx, TIM_IC_InitStruct); - break; - case LL_TIM_CHANNEL_CH3: - result = IC3Config(TIMx, TIM_IC_InitStruct); - break; - case LL_TIM_CHANNEL_CH4: - result = IC4Config(TIMx, TIM_IC_InitStruct); - break; - default: - break; - } - - return result; -} - -/** - * @brief Fills each TIM_EncoderInitStruct field with its default value - * @param TIM_EncoderInitStruct pointer to a @ref LL_TIM_ENCODER_InitTypeDef structure (encoder interface - * configuration data structure) - * @retval None - */ -void LL_TIM_ENCODER_StructInit(LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct) -{ - /* Set the default configuration */ - TIM_EncoderInitStruct->EncoderMode = LL_TIM_ENCODERMODE_X2_TI1; - TIM_EncoderInitStruct->IC1Polarity = LL_TIM_IC_POLARITY_RISING; - TIM_EncoderInitStruct->IC1ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI; - TIM_EncoderInitStruct->IC1Prescaler = LL_TIM_ICPSC_DIV1; - TIM_EncoderInitStruct->IC1Filter = LL_TIM_IC_FILTER_FDIV1; - TIM_EncoderInitStruct->IC2Polarity = LL_TIM_IC_POLARITY_RISING; - TIM_EncoderInitStruct->IC2ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI; - TIM_EncoderInitStruct->IC2Prescaler = LL_TIM_ICPSC_DIV1; - TIM_EncoderInitStruct->IC2Filter = LL_TIM_IC_FILTER_FDIV1; -} - -/** - * @brief Configure the encoder interface of the timer instance. - * @param TIMx Timer Instance - * @param TIM_EncoderInitStruct pointer to a @ref LL_TIM_ENCODER_InitTypeDef structure (TIMx encoder interface - * configuration data structure) - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -ErrorStatus LL_TIM_ENCODER_Init(TIM_TypeDef *TIMx, LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - - /* Check the parameters */ - assert_param(IS_TIM_ENCODER_INTERFACE_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_ENCODERMODE(TIM_EncoderInitStruct->EncoderMode)); - assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_EncoderInitStruct->IC1Polarity)); - assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_EncoderInitStruct->IC1ActiveInput)); - assert_param(IS_LL_TIM_ICPSC(TIM_EncoderInitStruct->IC1Prescaler)); - assert_param(IS_LL_TIM_IC_FILTER(TIM_EncoderInitStruct->IC1Filter)); - assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_EncoderInitStruct->IC2Polarity)); - assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_EncoderInitStruct->IC2ActiveInput)); - assert_param(IS_LL_TIM_ICPSC(TIM_EncoderInitStruct->IC2Prescaler)); - assert_param(IS_LL_TIM_IC_FILTER(TIM_EncoderInitStruct->IC2Filter)); - - /* Disable the CC1 and CC2: Reset the CC1E and CC2E Bits */ - TIMx->CCER &= (uint32_t)~(TIM_CCER_CC1E | TIM_CCER_CC2E); - - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1); - - /* Get the TIMx CCER register value */ - tmpccer = LL_TIM_ReadReg(TIMx, CCER); - - /* Configure TI1 */ - tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC); - tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1ActiveInput >> 16U); - tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1Filter >> 16U); - tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC1Prescaler >> 16U); - - /* Configure TI2 */ - tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC); - tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2ActiveInput >> 8U); - tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2Filter >> 8U); - tmpccmr1 |= (uint32_t)(TIM_EncoderInitStruct->IC2Prescaler >> 8U); - - /* Set TI1 and TI2 polarity and enable TI1 and TI2 */ - tmpccer &= (uint32_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP | TIM_CCER_CC2P | TIM_CCER_CC2NP); - tmpccer |= (uint32_t)(TIM_EncoderInitStruct->IC1Polarity); - tmpccer |= (uint32_t)(TIM_EncoderInitStruct->IC2Polarity << 4U); - tmpccer |= (uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E); - - /* Set encoder mode */ - LL_TIM_SetEncoderMode(TIMx, TIM_EncoderInitStruct->EncoderMode); - - /* Write to TIMx CCMR1 */ - LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1); - - /* Write to TIMx CCER */ - LL_TIM_WriteReg(TIMx, CCER, tmpccer); - - return SUCCESS; -} - -/** - * @brief Set the fields of the TIMx Hall sensor interface configuration data - * structure to their default values. - * @param TIM_HallSensorInitStruct pointer to a @ref LL_TIM_HALLSENSOR_InitTypeDef structure (HALL sensor interface - * configuration data structure) - * @retval None - */ -void LL_TIM_HALLSENSOR_StructInit(LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct) -{ - /* Set the default configuration */ - TIM_HallSensorInitStruct->IC1Polarity = LL_TIM_IC_POLARITY_RISING; - TIM_HallSensorInitStruct->IC1Prescaler = LL_TIM_ICPSC_DIV1; - TIM_HallSensorInitStruct->IC1Filter = LL_TIM_IC_FILTER_FDIV1; - TIM_HallSensorInitStruct->CommutationDelay = 0U; -} - -/** - * @brief Configure the Hall sensor interface of the timer instance. - * @note TIMx CH1, CH2 and CH3 inputs connected through a XOR - * to the TI1 input channel - * @note TIMx slave mode controller is configured in reset mode. - Selected internal trigger is TI1F_ED. - * @note Channel 1 is configured as input, IC1 is mapped on TRC. - * @note Captured value stored in TIMx_CCR1 correspond to the time elapsed - * between 2 changes on the inputs. It gives information about motor speed. - * @note Channel 2 is configured in output PWM 2 mode. - * @note Compare value stored in TIMx_CCR2 corresponds to the commutation delay. - * @note OC2REF is selected as trigger output on TRGO. - * @note LL_TIM_IC_POLARITY_BOTHEDGE must not be used for TI1 when it is used - * when TIMx operates in Hall sensor interface mode. - * @param TIMx Timer Instance - * @param TIM_HallSensorInitStruct pointer to a @ref LL_TIM_HALLSENSOR_InitTypeDef structure (TIMx HALL sensor - * interface configuration data structure) - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -ErrorStatus LL_TIM_HALLSENSOR_Init(TIM_TypeDef *TIMx, LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct) -{ - uint32_t tmpcr2; - uint32_t tmpccmr1; - uint32_t tmpccer; - uint32_t tmpsmcr; - - /* Check the parameters */ - assert_param(IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_IC_POLARITY_ENCODER(TIM_HallSensorInitStruct->IC1Polarity)); - assert_param(IS_LL_TIM_ICPSC(TIM_HallSensorInitStruct->IC1Prescaler)); - assert_param(IS_LL_TIM_IC_FILTER(TIM_HallSensorInitStruct->IC1Filter)); - - /* Disable the CC1 and CC2: Reset the CC1E and CC2E Bits */ - TIMx->CCER &= (uint32_t)~(TIM_CCER_CC1E | TIM_CCER_CC2E); - - /* Get the TIMx CR2 register value */ - tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); - - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1); - - /* Get the TIMx CCER register value */ - tmpccer = LL_TIM_ReadReg(TIMx, CCER); - - /* Get the TIMx SMCR register value */ - tmpsmcr = LL_TIM_ReadReg(TIMx, SMCR); - - /* Connect TIMx_CH1, CH2 and CH3 pins to the TI1 input */ - tmpcr2 |= TIM_CR2_TI1S; - - /* OC2REF signal is used as trigger output (TRGO) */ - tmpcr2 |= LL_TIM_TRGO_OC2REF; - - /* Configure the slave mode controller */ - tmpsmcr &= (uint32_t)~(TIM_SMCR_TS | TIM_SMCR_SMS); - tmpsmcr |= LL_TIM_TS_TI1F_ED; - tmpsmcr |= LL_TIM_SLAVEMODE_RESET; - - /* Configure input channel 1 */ - tmpccmr1 &= (uint32_t)~(TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC); - tmpccmr1 |= (uint32_t)(LL_TIM_ACTIVEINPUT_TRC >> 16U); - tmpccmr1 |= (uint32_t)(TIM_HallSensorInitStruct->IC1Filter >> 16U); - tmpccmr1 |= (uint32_t)(TIM_HallSensorInitStruct->IC1Prescaler >> 16U); - - /* Configure input channel 2 */ - tmpccmr1 &= (uint32_t)~(TIM_CCMR1_OC2M | TIM_CCMR1_OC2FE | TIM_CCMR1_OC2PE | TIM_CCMR1_OC2CE); - tmpccmr1 |= (uint32_t)(LL_TIM_OCMODE_PWM2 << 8U); - - /* Set Channel 1 polarity and enable Channel 1 and Channel2 */ - tmpccer &= (uint32_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP | TIM_CCER_CC2P | TIM_CCER_CC2NP); - tmpccer |= (uint32_t)(TIM_HallSensorInitStruct->IC1Polarity); - tmpccer |= (uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E); - - /* Write to TIMx CR2 */ - LL_TIM_WriteReg(TIMx, CR2, tmpcr2); - - /* Write to TIMx SMCR */ - LL_TIM_WriteReg(TIMx, SMCR, tmpsmcr); - - /* Write to TIMx CCMR1 */ - LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1); - - /* Write to TIMx CCER */ - LL_TIM_WriteReg(TIMx, CCER, tmpccer); - - /* Write to TIMx CCR2 */ - LL_TIM_OC_SetCompareCH2(TIMx, TIM_HallSensorInitStruct->CommutationDelay); - - return SUCCESS; -} - -/** - * @brief Set the fields of the Break and Dead Time configuration data structure - * to their default values. - * @param TIM_BDTRInitStruct pointer to a @ref LL_TIM_BDTR_InitTypeDef structure (Break and Dead Time configuration - * data structure) - * @retval None - */ -void LL_TIM_BDTR_StructInit(LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct) -{ - /* Set the default configuration */ - TIM_BDTRInitStruct->OSSRState = LL_TIM_OSSR_DISABLE; - TIM_BDTRInitStruct->OSSIState = LL_TIM_OSSI_DISABLE; - TIM_BDTRInitStruct->LockLevel = LL_TIM_LOCKLEVEL_OFF; - TIM_BDTRInitStruct->DeadTime = (uint8_t)0x00; - TIM_BDTRInitStruct->BreakState = LL_TIM_BREAK_DISABLE; - TIM_BDTRInitStruct->BreakPolarity = LL_TIM_BREAK_POLARITY_LOW; - TIM_BDTRInitStruct->AutomaticOutput = LL_TIM_AUTOMATICOUTPUT_DISABLE; -} - -/** - * @brief Configure the Break and Dead Time feature of the timer instance. - * @note As the bits AOE, BKP, BKE, OSSR, OSSI and DTG[7:0] can be write-locked - * depending on the LOCK configuration, it can be necessary to configure all of - * them during the first write access to the TIMx_BDTR register. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @param TIMx Timer Instance - * @param TIM_BDTRInitStruct pointer to a @ref LL_TIM_BDTR_InitTypeDef structure (Break and Dead Time configuration - * data structure) - * @retval An ErrorStatus enumeration value: - * - SUCCESS: Break and Dead Time is initialized - * - ERROR: not applicable - */ -ErrorStatus LL_TIM_BDTR_Init(TIM_TypeDef *TIMx, LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct) -{ - uint32_t tmpbdtr = 0; - - /* Check the parameters */ - assert_param(IS_TIM_BREAK_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_OSSR_STATE(TIM_BDTRInitStruct->OSSRState)); - assert_param(IS_LL_TIM_OSSI_STATE(TIM_BDTRInitStruct->OSSIState)); - assert_param(IS_LL_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->LockLevel)); - assert_param(IS_LL_TIM_BREAK_STATE(TIM_BDTRInitStruct->BreakState)); - assert_param(IS_LL_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->BreakPolarity)); - assert_param(IS_LL_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->AutomaticOutput)); - - /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State, - the OSSI State, the dead time value and the Automatic Output Enable Bit */ - - /* Set the BDTR bits */ - MODIFY_REG(tmpbdtr, TIM_BDTR_DTG, TIM_BDTRInitStruct->DeadTime); - MODIFY_REG(tmpbdtr, TIM_BDTR_LOCK, TIM_BDTRInitStruct->LockLevel); - MODIFY_REG(tmpbdtr, TIM_BDTR_OSSI, TIM_BDTRInitStruct->OSSIState); - MODIFY_REG(tmpbdtr, TIM_BDTR_OSSR, TIM_BDTRInitStruct->OSSRState); - MODIFY_REG(tmpbdtr, TIM_BDTR_BKE, TIM_BDTRInitStruct->BreakState); - MODIFY_REG(tmpbdtr, TIM_BDTR_BKP, TIM_BDTRInitStruct->BreakPolarity); - MODIFY_REG(tmpbdtr, TIM_BDTR_AOE, TIM_BDTRInitStruct->AutomaticOutput); - MODIFY_REG(tmpbdtr, TIM_BDTR_MOE, TIM_BDTRInitStruct->AutomaticOutput); - - /* Set TIMx_BDTR */ - LL_TIM_WriteReg(TIMx, BDTR, tmpbdtr); - - return SUCCESS; -} -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup TIM_LL_Private_Functions TIM Private Functions - * @brief Private functions - * @{ - */ -/** - * @brief Configure the TIMx output channel 1. - * @param TIMx Timer Instance - * @param TIM_OCInitStruct pointer to the the TIMx output channel 1 configuration data structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -static ErrorStatus OC1Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode)); - assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState)); - assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity)); - assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState)); - assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity)); - - /* Disable the Channel 1: Reset the CC1E Bit */ - CLEAR_BIT(TIMx->CCER, TIM_CCER_CC1E); - - /* Get the TIMx CCER register value */ - tmpccer = LL_TIM_ReadReg(TIMx, CCER); - - /* Get the TIMx CR2 register value */ - tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); - - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1); - - /* Reset Capture/Compare selection Bits */ - CLEAR_BIT(tmpccmr1, TIM_CCMR1_CC1S); - - /* Set the Output Compare Mode */ - MODIFY_REG(tmpccmr1, TIM_CCMR1_OC1M, TIM_OCInitStruct->OCMode); - - /* Set the Output Compare Polarity */ - MODIFY_REG(tmpccer, TIM_CCER_CC1P, TIM_OCInitStruct->OCPolarity); - - /* Set the Output State */ - MODIFY_REG(tmpccer, TIM_CCER_CC1E, TIM_OCInitStruct->OCState); - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState)); - assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState)); - - /* Set the complementary output Polarity */ - MODIFY_REG(tmpccer, TIM_CCER_CC1NP, TIM_OCInitStruct->OCNPolarity << 2U); - - /* Set the complementary output State */ - MODIFY_REG(tmpccer, TIM_CCER_CC1NE, TIM_OCInitStruct->OCNState << 2U); - - /* Set the Output Idle state */ - MODIFY_REG(tmpcr2, TIM_CR2_OIS1, TIM_OCInitStruct->OCIdleState); - - /* Set the complementary output Idle state */ - MODIFY_REG(tmpcr2, TIM_CR2_OIS1N, TIM_OCInitStruct->OCNIdleState << 1U); - } - - /* Write to TIMx CR2 */ - LL_TIM_WriteReg(TIMx, CR2, tmpcr2); - - /* Write to TIMx CCMR1 */ - LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1); - - /* Set the Capture Compare Register value */ - LL_TIM_OC_SetCompareCH1(TIMx, TIM_OCInitStruct->CompareValue); - - /* Write to TIMx CCER */ - LL_TIM_WriteReg(TIMx, CCER, tmpccer); - - return SUCCESS; -} - -/** - * @brief Configure the TIMx output channel 2. - * @param TIMx Timer Instance - * @param TIM_OCInitStruct pointer to the the TIMx output channel 2 configuration data structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -static ErrorStatus OC2Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct) -{ - uint32_t tmpccmr1; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode)); - assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState)); - assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity)); - assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState)); - assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity)); - - /* Disable the Channel 2: Reset the CC2E Bit */ - CLEAR_BIT(TIMx->CCER, TIM_CCER_CC2E); - - /* Get the TIMx CCER register value */ - tmpccer = LL_TIM_ReadReg(TIMx, CCER); - - /* Get the TIMx CR2 register value */ - tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); - - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = LL_TIM_ReadReg(TIMx, CCMR1); - - /* Reset Capture/Compare selection Bits */ - CLEAR_BIT(tmpccmr1, TIM_CCMR1_CC2S); - - /* Select the Output Compare Mode */ - MODIFY_REG(tmpccmr1, TIM_CCMR1_OC2M, TIM_OCInitStruct->OCMode << 8U); - - /* Set the Output Compare Polarity */ - MODIFY_REG(tmpccer, TIM_CCER_CC2P, TIM_OCInitStruct->OCPolarity << 4U); - - /* Set the Output State */ - MODIFY_REG(tmpccer, TIM_CCER_CC2E, TIM_OCInitStruct->OCState << 4U); - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState)); - assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState)); - - /* Set the complementary output Polarity */ - MODIFY_REG(tmpccer, TIM_CCER_CC2NP, TIM_OCInitStruct->OCNPolarity << 6U); - - /* Set the complementary output State */ - MODIFY_REG(tmpccer, TIM_CCER_CC2NE, TIM_OCInitStruct->OCNState << 6U); - - /* Set the Output Idle state */ - MODIFY_REG(tmpcr2, TIM_CR2_OIS2, TIM_OCInitStruct->OCIdleState << 2U); - - /* Set the complementary output Idle state */ - MODIFY_REG(tmpcr2, TIM_CR2_OIS2N, TIM_OCInitStruct->OCNIdleState << 3U); - } - - /* Write to TIMx CR2 */ - LL_TIM_WriteReg(TIMx, CR2, tmpcr2); - - /* Write to TIMx CCMR1 */ - LL_TIM_WriteReg(TIMx, CCMR1, tmpccmr1); - - /* Set the Capture Compare Register value */ - LL_TIM_OC_SetCompareCH2(TIMx, TIM_OCInitStruct->CompareValue); - - /* Write to TIMx CCER */ - LL_TIM_WriteReg(TIMx, CCER, tmpccer); - - return SUCCESS; -} - -/** - * @brief Configure the TIMx output channel 3. - * @param TIMx Timer Instance - * @param TIM_OCInitStruct pointer to the the TIMx output channel 3 configuration data structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -static ErrorStatus OC3Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct) -{ - uint32_t tmpccmr2; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Check the parameters */ - assert_param(IS_TIM_CC3_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode)); - assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState)); - assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity)); - assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState)); - assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity)); - - /* Disable the Channel 3: Reset the CC3E Bit */ - CLEAR_BIT(TIMx->CCER, TIM_CCER_CC3E); - - /* Get the TIMx CCER register value */ - tmpccer = LL_TIM_ReadReg(TIMx, CCER); - - /* Get the TIMx CR2 register value */ - tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); - - /* Get the TIMx CCMR2 register value */ - tmpccmr2 = LL_TIM_ReadReg(TIMx, CCMR2); - - /* Reset Capture/Compare selection Bits */ - CLEAR_BIT(tmpccmr2, TIM_CCMR2_CC3S); - - /* Select the Output Compare Mode */ - MODIFY_REG(tmpccmr2, TIM_CCMR2_OC3M, TIM_OCInitStruct->OCMode); - - /* Set the Output Compare Polarity */ - MODIFY_REG(tmpccer, TIM_CCER_CC3P, TIM_OCInitStruct->OCPolarity << 8U); - - /* Set the Output State */ - MODIFY_REG(tmpccer, TIM_CCER_CC3E, TIM_OCInitStruct->OCState << 8U); - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState)); - assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState)); - - /* Set the complementary output Polarity */ - MODIFY_REG(tmpccer, TIM_CCER_CC3NP, TIM_OCInitStruct->OCNPolarity << 10U); - - /* Set the complementary output State */ - MODIFY_REG(tmpccer, TIM_CCER_CC3NE, TIM_OCInitStruct->OCNState << 10U); - - /* Set the Output Idle state */ - MODIFY_REG(tmpcr2, TIM_CR2_OIS3, TIM_OCInitStruct->OCIdleState << 4U); - - /* Set the complementary output Idle state */ - MODIFY_REG(tmpcr2, TIM_CR2_OIS3N, TIM_OCInitStruct->OCNIdleState << 5U); - } - - /* Write to TIMx CR2 */ - LL_TIM_WriteReg(TIMx, CR2, tmpcr2); - - /* Write to TIMx CCMR2 */ - LL_TIM_WriteReg(TIMx, CCMR2, tmpccmr2); - - /* Set the Capture Compare Register value */ - LL_TIM_OC_SetCompareCH3(TIMx, TIM_OCInitStruct->CompareValue); - - /* Write to TIMx CCER */ - LL_TIM_WriteReg(TIMx, CCER, tmpccer); - - return SUCCESS; -} - -/** - * @brief Configure the TIMx output channel 4. - * @param TIMx Timer Instance - * @param TIM_OCInitStruct pointer to the the TIMx output channel 4 configuration data structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -static ErrorStatus OC4Config(TIM_TypeDef *TIMx, LL_TIM_OC_InitTypeDef *TIM_OCInitStruct) -{ - uint32_t tmpccmr2; - uint32_t tmpccer; - uint32_t tmpcr2; - - /* Check the parameters */ - assert_param(IS_TIM_CC4_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_OCMODE(TIM_OCInitStruct->OCMode)); - assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCState)); - assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCPolarity)); - assert_param(IS_LL_TIM_OCPOLARITY(TIM_OCInitStruct->OCNPolarity)); - assert_param(IS_LL_TIM_OCSTATE(TIM_OCInitStruct->OCNState)); - - /* Disable the Channel 4: Reset the CC4E Bit */ - CLEAR_BIT(TIMx->CCER, TIM_CCER_CC4E); - - /* Get the TIMx CCER register value */ - tmpccer = LL_TIM_ReadReg(TIMx, CCER); - - /* Get the TIMx CR2 register value */ - tmpcr2 = LL_TIM_ReadReg(TIMx, CR2); - - /* Get the TIMx CCMR2 register value */ - tmpccmr2 = LL_TIM_ReadReg(TIMx, CCMR2); - - /* Reset Capture/Compare selection Bits */ - CLEAR_BIT(tmpccmr2, TIM_CCMR2_CC4S); - - /* Select the Output Compare Mode */ - MODIFY_REG(tmpccmr2, TIM_CCMR2_OC4M, TIM_OCInitStruct->OCMode << 8U); - - /* Set the Output Compare Polarity */ - MODIFY_REG(tmpccer, TIM_CCER_CC4P, TIM_OCInitStruct->OCPolarity << 12U); - - /* Set the Output State */ - MODIFY_REG(tmpccer, TIM_CCER_CC4E, TIM_OCInitStruct->OCState << 12U); - - if (IS_TIM_BREAK_INSTANCE(TIMx)) - { - assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCNIdleState)); - assert_param(IS_LL_TIM_OCIDLESTATE(TIM_OCInitStruct->OCIdleState)); - - /* Set the Output Idle state */ - MODIFY_REG(tmpcr2, TIM_CR2_OIS4, TIM_OCInitStruct->OCIdleState << 6U); - } - - /* Write to TIMx CR2 */ - LL_TIM_WriteReg(TIMx, CR2, tmpcr2); - - /* Write to TIMx CCMR2 */ - LL_TIM_WriteReg(TIMx, CCMR2, tmpccmr2); - - /* Set the Capture Compare Register value */ - LL_TIM_OC_SetCompareCH4(TIMx, TIM_OCInitStruct->CompareValue); - - /* Write to TIMx CCER */ - LL_TIM_WriteReg(TIMx, CCER, tmpccer); - - return SUCCESS; -} - - -/** - * @brief Configure the TIMx input channel 1. - * @param TIMx Timer Instance - * @param TIM_ICInitStruct pointer to the the TIMx input channel 1 configuration data structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -static ErrorStatus IC1Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) -{ - /* Check the parameters */ - assert_param(IS_TIM_CC1_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity)); - assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput)); - assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler)); - assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter)); - - /* Disable the Channel 1: Reset the CC1E Bit */ - TIMx->CCER &= (uint32_t)~TIM_CCER_CC1E; - - /* Select the Input and set the filter and the prescaler value */ - MODIFY_REG(TIMx->CCMR1, - (TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC), - (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 16U); - - /* Select the Polarity and set the CC1E Bit */ - MODIFY_REG(TIMx->CCER, - (TIM_CCER_CC1P | TIM_CCER_CC1NP), - (TIM_ICInitStruct->ICPolarity | TIM_CCER_CC1E)); - - return SUCCESS; -} - -/** - * @brief Configure the TIMx input channel 2. - * @param TIMx Timer Instance - * @param TIM_ICInitStruct pointer to the the TIMx input channel 2 configuration data structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -static ErrorStatus IC2Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) -{ - /* Check the parameters */ - assert_param(IS_TIM_CC2_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity)); - assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput)); - assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler)); - assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter)); - - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= (uint32_t)~TIM_CCER_CC2E; - - /* Select the Input and set the filter and the prescaler value */ - MODIFY_REG(TIMx->CCMR1, - (TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC), - (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 8U); - - /* Select the Polarity and set the CC2E Bit */ - MODIFY_REG(TIMx->CCER, - (TIM_CCER_CC2P | TIM_CCER_CC2NP), - ((TIM_ICInitStruct->ICPolarity << 4U) | TIM_CCER_CC2E)); - - return SUCCESS; -} - -/** - * @brief Configure the TIMx input channel 3. - * @param TIMx Timer Instance - * @param TIM_ICInitStruct pointer to the the TIMx input channel 3 configuration data structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -static ErrorStatus IC3Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) -{ - /* Check the parameters */ - assert_param(IS_TIM_CC3_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity)); - assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput)); - assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler)); - assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter)); - - /* Disable the Channel 3: Reset the CC3E Bit */ - TIMx->CCER &= (uint32_t)~TIM_CCER_CC3E; - - /* Select the Input and set the filter and the prescaler value */ - MODIFY_REG(TIMx->CCMR2, - (TIM_CCMR2_CC3S | TIM_CCMR2_IC3F | TIM_CCMR2_IC3PSC), - (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 16U); - - /* Select the Polarity and set the CC3E Bit */ - MODIFY_REG(TIMx->CCER, - (TIM_CCER_CC3P | TIM_CCER_CC3NP), - ((TIM_ICInitStruct->ICPolarity << 8U) | TIM_CCER_CC3E)); - - return SUCCESS; -} - -/** - * @brief Configure the TIMx input channel 4. - * @param TIMx Timer Instance - * @param TIM_ICInitStruct pointer to the the TIMx input channel 4 configuration data structure - * @retval An ErrorStatus enumeration value: - * - SUCCESS: TIMx registers are de-initialized - * - ERROR: not applicable - */ -static ErrorStatus IC4Config(TIM_TypeDef *TIMx, LL_TIM_IC_InitTypeDef *TIM_ICInitStruct) -{ - /* Check the parameters */ - assert_param(IS_TIM_CC4_INSTANCE(TIMx)); - assert_param(IS_LL_TIM_IC_POLARITY(TIM_ICInitStruct->ICPolarity)); - assert_param(IS_LL_TIM_ACTIVEINPUT(TIM_ICInitStruct->ICActiveInput)); - assert_param(IS_LL_TIM_ICPSC(TIM_ICInitStruct->ICPrescaler)); - assert_param(IS_LL_TIM_IC_FILTER(TIM_ICInitStruct->ICFilter)); - - /* Disable the Channel 4: Reset the CC4E Bit */ - TIMx->CCER &= (uint32_t)~TIM_CCER_CC4E; - - /* Select the Input and set the filter and the prescaler value */ - MODIFY_REG(TIMx->CCMR2, - (TIM_CCMR2_CC4S | TIM_CCMR2_IC4F | TIM_CCMR2_IC4PSC), - (TIM_ICInitStruct->ICActiveInput | TIM_ICInitStruct->ICFilter | TIM_ICInitStruct->ICPrescaler) >> 8U); - - /* Select the Polarity and set the CC2E Bit */ - MODIFY_REG(TIMx->CCER, - (TIM_CCER_CC4P | TIM_CCER_CC4NP), - ((TIM_ICInitStruct->ICPolarity << 12U) | TIM_CCER_CC4E)); - - return SUCCESS; -} - - -/** - * @} - */ - -/** - * @} - */ - -#endif /* TIM1 || TIM2 || TIM3 || TIM4 || TIM5 || TIM6 || TIM7 || TIM8 || TIM9 || TIM10 || TIM11 || TIM12 || TIM13 || TIM14 */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usart.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usart.c deleted file mode 100644 index 150d8bbf6293587..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usart.c +++ /dev/null @@ -1,502 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usart.c - * @author MCD Application Team - * @brief USART LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -#if defined(USE_FULL_LL_DRIVER) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_usart.h" -#include "stm32f4xx_ll_rcc.h" -#include "stm32f4xx_ll_bus.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8) || defined (UART9) || defined (UART10) - -/** @addtogroup USART_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @addtogroup USART_LL_Private_Constants - * @{ - */ - -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup USART_LL_Private_Macros - * @{ - */ - -/* __BAUDRATE__ The maximum Baud Rate is derived from the maximum clock available - * divided by the smallest oversampling used on the USART (i.e. 8) */ -#define IS_LL_USART_BAUDRATE(__BAUDRATE__) ((__BAUDRATE__) <= 12500000U) - -/* __VALUE__ In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d. */ -#define IS_LL_USART_BRR_MIN(__VALUE__) ((__VALUE__) >= 16U) - -#define IS_LL_USART_DIRECTION(__VALUE__) (((__VALUE__) == LL_USART_DIRECTION_NONE) \ - || ((__VALUE__) == LL_USART_DIRECTION_RX) \ - || ((__VALUE__) == LL_USART_DIRECTION_TX) \ - || ((__VALUE__) == LL_USART_DIRECTION_TX_RX)) - -#define IS_LL_USART_PARITY(__VALUE__) (((__VALUE__) == LL_USART_PARITY_NONE) \ - || ((__VALUE__) == LL_USART_PARITY_EVEN) \ - || ((__VALUE__) == LL_USART_PARITY_ODD)) - -#define IS_LL_USART_DATAWIDTH(__VALUE__) (((__VALUE__) == LL_USART_DATAWIDTH_8B) \ - || ((__VALUE__) == LL_USART_DATAWIDTH_9B)) - -#define IS_LL_USART_OVERSAMPLING(__VALUE__) (((__VALUE__) == LL_USART_OVERSAMPLING_16) \ - || ((__VALUE__) == LL_USART_OVERSAMPLING_8)) - -#define IS_LL_USART_LASTBITCLKOUTPUT(__VALUE__) (((__VALUE__) == LL_USART_LASTCLKPULSE_NO_OUTPUT) \ - || ((__VALUE__) == LL_USART_LASTCLKPULSE_OUTPUT)) - -#define IS_LL_USART_CLOCKPHASE(__VALUE__) (((__VALUE__) == LL_USART_PHASE_1EDGE) \ - || ((__VALUE__) == LL_USART_PHASE_2EDGE)) - -#define IS_LL_USART_CLOCKPOLARITY(__VALUE__) (((__VALUE__) == LL_USART_POLARITY_LOW) \ - || ((__VALUE__) == LL_USART_POLARITY_HIGH)) - -#define IS_LL_USART_CLOCKOUTPUT(__VALUE__) (((__VALUE__) == LL_USART_CLOCK_DISABLE) \ - || ((__VALUE__) == LL_USART_CLOCK_ENABLE)) - -#define IS_LL_USART_STOPBITS(__VALUE__) (((__VALUE__) == LL_USART_STOPBITS_0_5) \ - || ((__VALUE__) == LL_USART_STOPBITS_1) \ - || ((__VALUE__) == LL_USART_STOPBITS_1_5) \ - || ((__VALUE__) == LL_USART_STOPBITS_2)) - -#define IS_LL_USART_HWCONTROL(__VALUE__) (((__VALUE__) == LL_USART_HWCONTROL_NONE) \ - || ((__VALUE__) == LL_USART_HWCONTROL_RTS) \ - || ((__VALUE__) == LL_USART_HWCONTROL_CTS) \ - || ((__VALUE__) == LL_USART_HWCONTROL_RTS_CTS)) - -/** - * @} - */ - -/* Private function prototypes -----------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup USART_LL_Exported_Functions - * @{ - */ - -/** @addtogroup USART_LL_EF_Init - * @{ - */ - -/** - * @brief De-initialize USART registers (Registers restored to their default values). - * @param USARTx USART Instance - * @retval An ErrorStatus enumeration value: - * - SUCCESS: USART registers are de-initialized - * - ERROR: USART registers are not de-initialized - */ -ErrorStatus LL_USART_DeInit(USART_TypeDef *USARTx) -{ - ErrorStatus status = SUCCESS; - - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(USARTx)); - - if (USARTx == USART1) - { - /* Force reset of USART clock */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_USART1); - - /* Release reset of USART clock */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_USART1); - } - else if (USARTx == USART2) - { - /* Force reset of USART clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_USART2); - - /* Release reset of USART clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_USART2); - } -#if defined(USART3) - else if (USARTx == USART3) - { - /* Force reset of USART clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_USART3); - - /* Release reset of USART clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_USART3); - } -#endif /* USART3 */ -#if defined(USART6) - else if (USARTx == USART6) - { - /* Force reset of USART clock */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_USART6); - - /* Release reset of USART clock */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_USART6); - } -#endif /* USART6 */ -#if defined(UART4) - else if (USARTx == UART4) - { - /* Force reset of UART clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_UART4); - - /* Release reset of UART clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_UART4); - } -#endif /* UART4 */ -#if defined(UART5) - else if (USARTx == UART5) - { - /* Force reset of UART clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_UART5); - - /* Release reset of UART clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_UART5); - } -#endif /* UART5 */ -#if defined(UART7) - else if (USARTx == UART7) - { - /* Force reset of UART clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_UART7); - - /* Release reset of UART clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_UART7); - } -#endif /* UART7 */ -#if defined(UART8) - else if (USARTx == UART8) - { - /* Force reset of UART clock */ - LL_APB1_GRP1_ForceReset(LL_APB1_GRP1_PERIPH_UART8); - - /* Release reset of UART clock */ - LL_APB1_GRP1_ReleaseReset(LL_APB1_GRP1_PERIPH_UART8); - } -#endif /* UART8 */ -#if defined(UART9) - else if (USARTx == UART9) - { - /* Force reset of UART clock */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_UART9); - - /* Release reset of UART clock */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_UART9); - } -#endif /* UART9 */ -#if defined(UART10) - else if (USARTx == UART10) - { - /* Force reset of UART clock */ - LL_APB2_GRP1_ForceReset(LL_APB2_GRP1_PERIPH_UART10); - - /* Release reset of UART clock */ - LL_APB2_GRP1_ReleaseReset(LL_APB2_GRP1_PERIPH_UART10); - } -#endif /* UART10 */ - else - { - status = ERROR; - } - - return (status); -} - -/** - * @brief Initialize USART registers according to the specified - * parameters in USART_InitStruct. - * @note As some bits in USART configuration registers can only be written when the USART is disabled (USART_CR1_UE bit =0), - * USART IP should be in disabled state prior calling this function. Otherwise, ERROR result will be returned. - * @note Baud rate value stored in USART_InitStruct BaudRate field, should be valid (different from 0). - * @param USARTx USART Instance - * @param USART_InitStruct pointer to a LL_USART_InitTypeDef structure - * that contains the configuration information for the specified USART peripheral. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: USART registers are initialized according to USART_InitStruct content - * - ERROR: Problem occurred during USART Registers initialization - */ -ErrorStatus LL_USART_Init(USART_TypeDef *USARTx, LL_USART_InitTypeDef *USART_InitStruct) -{ - ErrorStatus status = ERROR; - uint32_t periphclk = LL_RCC_PERIPH_FREQUENCY_NO; - LL_RCC_ClocksTypeDef rcc_clocks; - - /* Check the parameters */ - assert_param(IS_UART_INSTANCE(USARTx)); - assert_param(IS_LL_USART_BAUDRATE(USART_InitStruct->BaudRate)); - assert_param(IS_LL_USART_DATAWIDTH(USART_InitStruct->DataWidth)); - assert_param(IS_LL_USART_STOPBITS(USART_InitStruct->StopBits)); - assert_param(IS_LL_USART_PARITY(USART_InitStruct->Parity)); - assert_param(IS_LL_USART_DIRECTION(USART_InitStruct->TransferDirection)); - assert_param(IS_LL_USART_HWCONTROL(USART_InitStruct->HardwareFlowControl)); - assert_param(IS_LL_USART_OVERSAMPLING(USART_InitStruct->OverSampling)); - - /* USART needs to be in disabled state, in order to be able to configure some bits in - CRx registers */ - if (LL_USART_IsEnabled(USARTx) == 0U) - { - /*---------------------------- USART CR1 Configuration ----------------------- - * Configure USARTx CR1 (USART Word Length, Parity, Mode and Oversampling bits) with parameters: - * - DataWidth: USART_CR1_M bits according to USART_InitStruct->DataWidth value - * - Parity: USART_CR1_PCE, USART_CR1_PS bits according to USART_InitStruct->Parity value - * - TransferDirection: USART_CR1_TE, USART_CR1_RE bits according to USART_InitStruct->TransferDirection value - * - Oversampling: USART_CR1_OVER8 bit according to USART_InitStruct->OverSampling value. - */ - MODIFY_REG(USARTx->CR1, - (USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | - USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8), - (USART_InitStruct->DataWidth | USART_InitStruct->Parity | - USART_InitStruct->TransferDirection | USART_InitStruct->OverSampling)); - - /*---------------------------- USART CR2 Configuration ----------------------- - * Configure USARTx CR2 (Stop bits) with parameters: - * - Stop Bits: USART_CR2_STOP bits according to USART_InitStruct->StopBits value. - * - CLKEN, CPOL, CPHA and LBCL bits are to be configured using LL_USART_ClockInit(). - */ - LL_USART_SetStopBitsLength(USARTx, USART_InitStruct->StopBits); - - /*---------------------------- USART CR3 Configuration ----------------------- - * Configure USARTx CR3 (Hardware Flow Control) with parameters: - * - HardwareFlowControl: USART_CR3_RTSE, USART_CR3_CTSE bits according to USART_InitStruct->HardwareFlowControl value. - */ - LL_USART_SetHWFlowCtrl(USARTx, USART_InitStruct->HardwareFlowControl); - - /*---------------------------- USART BRR Configuration ----------------------- - * Retrieve Clock frequency used for USART Peripheral - */ - LL_RCC_GetSystemClocksFreq(&rcc_clocks); - if (USARTx == USART1) - { - periphclk = rcc_clocks.PCLK2_Frequency; - } - else if (USARTx == USART2) - { - periphclk = rcc_clocks.PCLK1_Frequency; - } -#if defined(USART3) - else if (USARTx == USART3) - { - periphclk = rcc_clocks.PCLK1_Frequency; - } -#endif /* USART3 */ -#if defined(USART6) - else if (USARTx == USART6) - { - periphclk = rcc_clocks.PCLK2_Frequency; - } -#endif /* USART6 */ -#if defined(UART4) - else if (USARTx == UART4) - { - periphclk = rcc_clocks.PCLK1_Frequency; - } -#endif /* UART4 */ -#if defined(UART5) - else if (USARTx == UART5) - { - periphclk = rcc_clocks.PCLK1_Frequency; - } -#endif /* UART5 */ -#if defined(UART7) - else if (USARTx == UART7) - { - periphclk = rcc_clocks.PCLK1_Frequency; - } -#endif /* UART7 */ -#if defined(UART8) - else if (USARTx == UART8) - { - periphclk = rcc_clocks.PCLK1_Frequency; - } -#endif /* UART8 */ -#if defined(UART9) - else if (USARTx == UART9) - { - periphclk = rcc_clocks.PCLK2_Frequency; - } -#endif /* UART9 */ -#if defined(UART10) - else if (USARTx == UART10) - { - periphclk = rcc_clocks.PCLK2_Frequency; - } -#endif /* UART10 */ - else - { - /* Nothing to do, as error code is already assigned to ERROR value */ - } - - /* Configure the USART Baud Rate : - - valid baud rate value (different from 0) is required - - Peripheral clock as returned by RCC service, should be valid (different from 0). - */ - if ((periphclk != LL_RCC_PERIPH_FREQUENCY_NO) - && (USART_InitStruct->BaudRate != 0U)) - { - status = SUCCESS; - LL_USART_SetBaudRate(USARTx, - periphclk, - USART_InitStruct->OverSampling, - USART_InitStruct->BaudRate); - - /* Check BRR is greater than or equal to 16d */ - assert_param(IS_LL_USART_BRR_MIN(USARTx->BRR)); - } - } - /* Endif (=> USART not in Disabled state => return ERROR) */ - - return (status); -} - -/** - * @brief Set each @ref LL_USART_InitTypeDef field to default value. - * @param USART_InitStruct Pointer to a @ref LL_USART_InitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ - -void LL_USART_StructInit(LL_USART_InitTypeDef *USART_InitStruct) -{ - /* Set USART_InitStruct fields to default values */ - USART_InitStruct->BaudRate = 9600U; - USART_InitStruct->DataWidth = LL_USART_DATAWIDTH_8B; - USART_InitStruct->StopBits = LL_USART_STOPBITS_1; - USART_InitStruct->Parity = LL_USART_PARITY_NONE ; - USART_InitStruct->TransferDirection = LL_USART_DIRECTION_TX_RX; - USART_InitStruct->HardwareFlowControl = LL_USART_HWCONTROL_NONE; - USART_InitStruct->OverSampling = LL_USART_OVERSAMPLING_16; -} - -/** - * @brief Initialize USART Clock related settings according to the - * specified parameters in the USART_ClockInitStruct. - * @note As some bits in USART configuration registers can only be written when the USART is disabled (USART_CR1_UE bit =0), - * USART IP should be in disabled state prior calling this function. Otherwise, ERROR result will be returned. - * @param USARTx USART Instance - * @param USART_ClockInitStruct Pointer to a @ref LL_USART_ClockInitTypeDef structure - * that contains the Clock configuration information for the specified USART peripheral. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: USART registers related to Clock settings are initialized according to USART_ClockInitStruct content - * - ERROR: Problem occurred during USART Registers initialization - */ -ErrorStatus LL_USART_ClockInit(USART_TypeDef *USARTx, LL_USART_ClockInitTypeDef *USART_ClockInitStruct) -{ - ErrorStatus status = SUCCESS; - - /* Check USART Instance and Clock signal output parameters */ - assert_param(IS_UART_INSTANCE(USARTx)); - assert_param(IS_LL_USART_CLOCKOUTPUT(USART_ClockInitStruct->ClockOutput)); - - /* USART needs to be in disabled state, in order to be able to configure some bits in - CRx registers */ - if (LL_USART_IsEnabled(USARTx) == 0U) - { - /*---------------------------- USART CR2 Configuration -----------------------*/ - /* If Clock signal has to be output */ - if (USART_ClockInitStruct->ClockOutput == LL_USART_CLOCK_DISABLE) - { - /* Deactivate Clock signal delivery : - * - Disable Clock Output: USART_CR2_CLKEN cleared - */ - LL_USART_DisableSCLKOutput(USARTx); - } - else - { - /* Ensure USART instance is USART capable */ - assert_param(IS_USART_INSTANCE(USARTx)); - - /* Check clock related parameters */ - assert_param(IS_LL_USART_CLOCKPOLARITY(USART_ClockInitStruct->ClockPolarity)); - assert_param(IS_LL_USART_CLOCKPHASE(USART_ClockInitStruct->ClockPhase)); - assert_param(IS_LL_USART_LASTBITCLKOUTPUT(USART_ClockInitStruct->LastBitClockPulse)); - - /*---------------------------- USART CR2 Configuration ----------------------- - * Configure USARTx CR2 (Clock signal related bits) with parameters: - * - Enable Clock Output: USART_CR2_CLKEN set - * - Clock Polarity: USART_CR2_CPOL bit according to USART_ClockInitStruct->ClockPolarity value - * - Clock Phase: USART_CR2_CPHA bit according to USART_ClockInitStruct->ClockPhase value - * - Last Bit Clock Pulse Output: USART_CR2_LBCL bit according to USART_ClockInitStruct->LastBitClockPulse value. - */ - MODIFY_REG(USARTx->CR2, - USART_CR2_CLKEN | USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_LBCL, - USART_CR2_CLKEN | USART_ClockInitStruct->ClockPolarity | - USART_ClockInitStruct->ClockPhase | USART_ClockInitStruct->LastBitClockPulse); - } - } - /* Else (USART not in Disabled state => return ERROR */ - else - { - status = ERROR; - } - - return (status); -} - -/** - * @brief Set each field of a @ref LL_USART_ClockInitTypeDef type structure to default value. - * @param USART_ClockInitStruct Pointer to a @ref LL_USART_ClockInitTypeDef structure - * whose fields will be set to default values. - * @retval None - */ -void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef *USART_ClockInitStruct) -{ - /* Set LL_USART_ClockInitStruct fields with default values */ - USART_ClockInitStruct->ClockOutput = LL_USART_CLOCK_DISABLE; - USART_ClockInitStruct->ClockPolarity = LL_USART_POLARITY_LOW; /* Not relevant when ClockOutput = LL_USART_CLOCK_DISABLE */ - USART_ClockInitStruct->ClockPhase = LL_USART_PHASE_1EDGE; /* Not relevant when ClockOutput = LL_USART_CLOCK_DISABLE */ - USART_ClockInitStruct->LastBitClockPulse = LL_USART_LASTCLKPULSE_NO_OUTPUT; /* Not relevant when ClockOutput = LL_USART_CLOCK_DISABLE */ -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 || UART9 || UART10 */ - -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c deleted file mode 100644 index cdd837da2db3094..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_usb.c +++ /dev/null @@ -1,2106 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usb.c - * @author MCD Application Team - * @brief USB Low Layer HAL module driver. - * - * This file provides firmware functions to manage the following - * functionalities of the USB Peripheral Controller: - * + Initialization/de-initialization functions - * + I/O operation functions - * + Peripheral Control functions - * + Peripheral State functions - * - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - (#) Fill parameters of Init structure in USB_OTG_CfgTypeDef structure. - - (#) Call USB_CoreInit() API to initialize the USB Core peripheral. - - (#) The upper HAL HCD/PCD driver will call the right routines for its internal processes. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal.h" - -/** @addtogroup STM32F4xx_LL_USB_DRIVER - * @{ - */ - -#if defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx); - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup USB_LL_Exported_Functions USB Low Layer Exported Functions - * @{ - */ - -/** @defgroup USB_LL_Exported_Functions_Group1 Initialization/de-initialization functions - * @brief Initialization and Configuration functions - * -@verbatim - =============================================================================== - ##### Initialization/de-initialization functions ##### - =============================================================================== - -@endverbatim - * @{ - */ - -/** - * @brief Initializes the USB Core - * @param USBx USB Instance - * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains - * the configuration information for the specified USBx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) -{ - HAL_StatusTypeDef ret; - - if (cfg.phy_itface == USB_OTG_ULPI_PHY) - { - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - - /* Init The ULPI Interface */ - USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); - - /* Select vbus source */ - USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); - if (cfg.use_external_vbus == 1U) - { - USBx->GUSBCFG |= USB_OTG_GUSBCFG_ULPIEVBUSD; - } - - /* Reset after a PHY select */ - ret = USB_CoreReset(USBx); - } - else /* FS interface (embedded Phy) */ - { - /* Select FS Embedded PHY */ - USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; - - /* Reset after a PHY select */ - ret = USB_CoreReset(USBx); - - if (cfg.battery_charging_enable == 0U) - { - /* Activate the USB Transceiver */ - USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; - } - else - { - /* Deactivate the USB Transceiver */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_PWRDWN); - } - } - - if (cfg.dma_enable == 1U) - { - USBx->GAHBCFG |= USB_OTG_GAHBCFG_HBSTLEN_2; - USBx->GAHBCFG |= USB_OTG_GAHBCFG_DMAEN; - } - - return ret; -} - - -/** - * @brief Set the USB turnaround time - * @param USBx USB Instance - * @param hclk: AHB clock frequency - * @retval USB turnaround time In PHY Clocks number - */ -HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, - uint32_t hclk, uint8_t speed) -{ - uint32_t UsbTrd; - - /* The USBTRD is configured according to the tables below, depending on AHB frequency - used by application. In the low AHB frequency range it is used to stretch enough the USB response - time to IN tokens, the USB turnaround time, so to compensate for the longer AHB read access - latency to the Data FIFO */ - if (speed == USBD_FS_SPEED) - { - if ((hclk >= 14200000U) && (hclk < 15000000U)) - { - /* hclk Clock Range between 14.2-15 MHz */ - UsbTrd = 0xFU; - } - else if ((hclk >= 15000000U) && (hclk < 16000000U)) - { - /* hclk Clock Range between 15-16 MHz */ - UsbTrd = 0xEU; - } - else if ((hclk >= 16000000U) && (hclk < 17200000U)) - { - /* hclk Clock Range between 16-17.2 MHz */ - UsbTrd = 0xDU; - } - else if ((hclk >= 17200000U) && (hclk < 18500000U)) - { - /* hclk Clock Range between 17.2-18.5 MHz */ - UsbTrd = 0xCU; - } - else if ((hclk >= 18500000U) && (hclk < 20000000U)) - { - /* hclk Clock Range between 18.5-20 MHz */ - UsbTrd = 0xBU; - } - else if ((hclk >= 20000000U) && (hclk < 21800000U)) - { - /* hclk Clock Range between 20-21.8 MHz */ - UsbTrd = 0xAU; - } - else if ((hclk >= 21800000U) && (hclk < 24000000U)) - { - /* hclk Clock Range between 21.8-24 MHz */ - UsbTrd = 0x9U; - } - else if ((hclk >= 24000000U) && (hclk < 27700000U)) - { - /* hclk Clock Range between 24-27.7 MHz */ - UsbTrd = 0x8U; - } - else if ((hclk >= 27700000U) && (hclk < 32000000U)) - { - /* hclk Clock Range between 27.7-32 MHz */ - UsbTrd = 0x7U; - } - else /* if(hclk >= 32000000) */ - { - /* hclk Clock Range between 32-200 MHz */ - UsbTrd = 0x6U; - } - } - else if (speed == USBD_HS_SPEED) - { - UsbTrd = USBD_HS_TRDT_VALUE; - } - else - { - UsbTrd = USBD_DEFAULT_TRDT_VALUE; - } - - USBx->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; - USBx->GUSBCFG |= (uint32_t)((UsbTrd << 10) & USB_OTG_GUSBCFG_TRDT); - - return HAL_OK; -} - -/** - * @brief USB_EnableGlobalInt - * Enables the controller's Global Int in the AHB Config reg - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx) -{ - USBx->GAHBCFG |= USB_OTG_GAHBCFG_GINT; - return HAL_OK; -} - -/** - * @brief USB_DisableGlobalInt - * Disable the controller's Global Int in the AHB Config reg - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx) -{ - USBx->GAHBCFG &= ~USB_OTG_GAHBCFG_GINT; - return HAL_OK; -} - -/** - * @brief USB_SetCurrentMode Set functional mode - * @param USBx Selected device - * @param mode current core mode - * This parameter can be one of these values: - * @arg USB_DEVICE_MODE Peripheral mode - * @arg USB_HOST_MODE Host mode - * @retval HAL status - */ -HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode) -{ - uint32_t ms = 0U; - - USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_FHMOD | USB_OTG_GUSBCFG_FDMOD); - - if (mode == USB_HOST_MODE) - { - USBx->GUSBCFG |= USB_OTG_GUSBCFG_FHMOD; - - do - { - HAL_Delay(1U); - ms++; - } while ((USB_GetMode(USBx) != (uint32_t)USB_HOST_MODE) && (ms < 50U)); - } - else if (mode == USB_DEVICE_MODE) - { - USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - - do - { - HAL_Delay(1U); - ms++; - } while ((USB_GetMode(USBx) != (uint32_t)USB_DEVICE_MODE) && (ms < 50U)); - } - else - { - return HAL_ERROR; - } - - if (ms == 50U) - { - return HAL_ERROR; - } - - return HAL_OK; -} - -/** - * @brief USB_DevInit Initializes the USB_OTG controller registers - * for device mode - * @param USBx Selected device - * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains - * the configuration information for the specified USBx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) -{ - HAL_StatusTypeDef ret = HAL_OK; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t i; - - for (i = 0U; i < 15U; i++) - { - USBx->DIEPTXF[i] = 0U; - } - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* VBUS Sensing setup */ - if (cfg.vbus_sensing_enable == 0U) - { - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - - /* Deactivate VBUS Sensing B */ - USBx->GCCFG &= ~USB_OTG_GCCFG_VBDEN; - - /* B-peripheral session valid override enable */ - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - } - else - { - /* Enable HW VBUS sensing */ - USBx->GCCFG |= USB_OTG_GCCFG_VBDEN; - } -#else - /* VBUS Sensing setup */ - if (cfg.vbus_sensing_enable == 0U) - { - /* - * Disable HW VBUS sensing. VBUS is internally considered to be always - * at VBUS-Valid level (5V). - */ - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - USBx->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; - USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; - USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; - } - else - { - /* Enable HW VBUS sensing */ - USBx->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS; - USBx->GCCFG |= USB_OTG_GCCFG_VBUSBSEN; - } -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ - - /* Restart the Phy Clock */ - USBx_PCGCCTL = 0U; - - /* Device mode configuration */ - USBx_DEVICE->DCFG |= DCFG_FRAME_INTERVAL_80; - - if (cfg.phy_itface == USB_OTG_ULPI_PHY) - { - if (cfg.speed == USBD_HS_SPEED) - { - /* Set Core speed to High speed mode */ - (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH); - } - else - { - /* Set Core speed to Full speed mode */ - (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_HIGH_IN_FULL); - } - } - else - { - /* Set Core speed to Full speed mode */ - (void)USB_SetDevSpeed(USBx, USB_OTG_SPEED_FULL); - } - - /* Flush the FIFOs */ - if (USB_FlushTxFifo(USBx, 0x10U) != HAL_OK) /* all Tx FIFOs */ - { - ret = HAL_ERROR; - } - - if (USB_FlushRxFifo(USBx) != HAL_OK) - { - ret = HAL_ERROR; - } - - /* Clear all pending Device Interrupts */ - USBx_DEVICE->DIEPMSK = 0U; - USBx_DEVICE->DOEPMSK = 0U; - USBx_DEVICE->DAINTMSK = 0U; - - for (i = 0U; i < cfg.dev_endpoints; i++) - { - if ((USBx_INEP(i)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) - { - if (i == 0U) - { - USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_SNAK; - } - else - { - USBx_INEP(i)->DIEPCTL = USB_OTG_DIEPCTL_EPDIS | USB_OTG_DIEPCTL_SNAK; - } - } - else - { - USBx_INEP(i)->DIEPCTL = 0U; - } - - USBx_INEP(i)->DIEPTSIZ = 0U; - USBx_INEP(i)->DIEPINT = 0xFB7FU; - } - - for (i = 0U; i < cfg.dev_endpoints; i++) - { - if ((USBx_OUTEP(i)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - if (i == 0U) - { - USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_SNAK; - } - else - { - USBx_OUTEP(i)->DOEPCTL = USB_OTG_DOEPCTL_EPDIS | USB_OTG_DOEPCTL_SNAK; - } - } - else - { - USBx_OUTEP(i)->DOEPCTL = 0U; - } - - USBx_OUTEP(i)->DOEPTSIZ = 0U; - USBx_OUTEP(i)->DOEPINT = 0xFB7FU; - } - - USBx_DEVICE->DIEPMSK &= ~(USB_OTG_DIEPMSK_TXFURM); - - /* Disable all interrupts. */ - USBx->GINTMSK = 0U; - - /* Clear any pending interrupts */ - USBx->GINTSTS = 0xBFFFFFFFU; - - /* Enable the common interrupts */ - if (cfg.dma_enable == 0U) - { - USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; - } - - /* Enable interrupts matching to the Device mode ONLY */ - USBx->GINTMSK |= USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_USBRST | - USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_IEPINT | - USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IISOIXFRM | - USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM; - - if (cfg.Sof_enable != 0U) - { - USBx->GINTMSK |= USB_OTG_GINTMSK_SOFM; - } - - if (cfg.vbus_sensing_enable == 1U) - { - USBx->GINTMSK |= (USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_OTGINT); - } - - return ret; -} - -/** - * @brief USB_OTG_FlushTxFifo : Flush a Tx FIFO - * @param USBx Selected device - * @param num FIFO number - * This parameter can be a value from 1 to 15 - 15 means Flush all Tx FIFOs - * @retval HAL status - */ -HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num) -{ - __IO uint32_t count = 0U; - - USBx->GRSTCTL = (USB_OTG_GRSTCTL_TXFFLSH | (num << 6)); - - do - { - if (++count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); - - return HAL_OK; -} - -/** - * @brief USB_FlushRxFifo : Flush Rx FIFO - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx) -{ - __IO uint32_t count = 0U; - - USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; - - do - { - if (++count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); - - return HAL_OK; -} - -/** - * @brief USB_SetDevSpeed Initializes the DevSpd field of DCFG register - * depending the PHY type and the enumeration speed of the device. - * @param USBx Selected device - * @param speed device speed - * This parameter can be one of these values: - * @arg USB_OTG_SPEED_HIGH: High speed mode - * @arg USB_OTG_SPEED_HIGH_IN_FULL: High speed core in Full Speed mode - * @arg USB_OTG_SPEED_FULL: Full speed mode - * @retval Hal status - */ -HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - USBx_DEVICE->DCFG |= speed; - return HAL_OK; -} - -/** - * @brief USB_GetDevSpeed Return the Dev Speed - * @param USBx Selected device - * @retval speed device speed - * This parameter can be one of these values: - * @arg USBD_HS_SPEED: High speed mode - * @arg USBD_FS_SPEED: Full speed mode - */ -uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint8_t speed; - uint32_t DevEnumSpeed = USBx_DEVICE->DSTS & USB_OTG_DSTS_ENUMSPD; - - if (DevEnumSpeed == DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ) - { - speed = USBD_HS_SPEED; - } - else if ((DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ) || - (DevEnumSpeed == DSTS_ENUMSPD_FS_PHY_48MHZ)) - { - speed = USBD_FS_SPEED; - } - else - { - speed = 0xFU; - } - - return speed; -} - -/** - * @brief Activate and configure an endpoint - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - if (ep->is_in == 1U) - { - USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)); - - if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_USBAEP) == 0U) - { - USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) | - ((uint32_t)ep->type << 18) | (epnum << 22) | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | - USB_OTG_DIEPCTL_USBAEP; - } - } - else - { - USBx_DEVICE->DAINTMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16); - - if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U) - { - USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) | - ((uint32_t)ep->type << 18) | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | - USB_OTG_DOEPCTL_USBAEP; - } - } - return HAL_OK; -} - -/** - * @brief Activate and configure a dedicated endpoint - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - /* Read DEPCTLn register */ - if (ep->is_in == 1U) - { - if (((USBx_INEP(epnum)->DIEPCTL) & USB_OTG_DIEPCTL_USBAEP) == 0U) - { - USBx_INEP(epnum)->DIEPCTL |= (ep->maxpacket & USB_OTG_DIEPCTL_MPSIZ) | - ((uint32_t)ep->type << 18) | (epnum << 22) | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | - USB_OTG_DIEPCTL_USBAEP; - } - - USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK)); - } - else - { - if (((USBx_OUTEP(epnum)->DOEPCTL) & USB_OTG_DOEPCTL_USBAEP) == 0U) - { - USBx_OUTEP(epnum)->DOEPCTL |= (ep->maxpacket & USB_OTG_DOEPCTL_MPSIZ) | - ((uint32_t)ep->type << 18) | (epnum << 22) | - USB_OTG_DOEPCTL_USBAEP; - } - - USBx_DEVICE->DEACHMSK |= USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16); - } - - return HAL_OK; -} - -/** - * @brief De-activate and de-initialize an endpoint - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - /* Read DEPCTLn register */ - if (ep->is_in == 1U) - { - if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS; - } - - USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); - USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); - USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_USBAEP | - USB_OTG_DIEPCTL_MPSIZ | - USB_OTG_DIEPCTL_TXFNUM | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | - USB_OTG_DIEPCTL_EPTYP); - } - else - { - if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS; - } - - USBx_DEVICE->DEACHMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); - USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); - USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_USBAEP | - USB_OTG_DOEPCTL_MPSIZ | - USB_OTG_DOEPCTL_SD0PID_SEVNFRM | - USB_OTG_DOEPCTL_EPTYP); - } - - return HAL_OK; -} - -/** - * @brief De-activate and de-initialize a dedicated endpoint - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - /* Read DEPCTLn register */ - if (ep->is_in == 1U) - { - if ((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == USB_OTG_DIEPCTL_EPENA) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SNAK; - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_EPDIS; - } - - USBx_INEP(epnum)->DIEPCTL &= ~ USB_OTG_DIEPCTL_USBAEP; - USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_IEPM & (uint32_t)(1UL << (ep->num & EP_ADDR_MSK))); - } - else - { - if ((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SNAK; - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_EPDIS; - } - - USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_USBAEP; - USBx_DEVICE->DAINTMSK &= ~(USB_OTG_DAINTMSK_OEPM & ((uint32_t)(1UL << (ep->num & EP_ADDR_MSK)) << 16)); - } - - return HAL_OK; -} - -/** - * @brief USB_EPStartXfer : setup and starts a transfer over an EP - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @retval HAL status - */ -HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - uint16_t pktcnt; - - /* IN endpoint */ - if (ep->is_in == 1U) - { - /* Zero Length Packet? */ - if (ep->xfer_len == 0U) - { - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); - } - else - { - /* Program the transfer size and packet count - * as follows: xfersize = N * maxpacket + - * short_packet pktcnt = N + (short_packet - * exist ? 1 : 0) - */ - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & - (((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket) << 19)); - - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len); - - if (ep->type == EP_TYPE_ISOC) - { - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_MULCNT); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_MULCNT & (1U << 29)); - } - } - - if (dma == 1U) - { - if ((uint32_t)ep->dma_addr != 0U) - { - USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr); - } - - if (ep->type == EP_TYPE_ISOC) - { - if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM; - } - else - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; - } - } - - /* EP enable, IN data in FIFO */ - USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - } - else - { - /* EP enable, IN data in FIFO */ - USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - - if (ep->type != EP_TYPE_ISOC) - { - /* Enable the Tx FIFO Empty Interrupt for this EP */ - if (ep->xfer_len > 0U) - { - USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK); - } - } - else - { - if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SODDFRM; - } - else - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; - } - - (void)USB_WritePacket(USBx, ep->xfer_buff, ep->num, (uint16_t)ep->xfer_len, dma); - } - } - } - else /* OUT endpoint */ - { - /* Program the transfer size and packet count as follows: - * pktcnt = N - * xfersize = N * maxpacket - */ - USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ); - USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT); - - if (ep->xfer_len == 0U) - { - USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & ep->maxpacket); - USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); - } - else - { - pktcnt = (uint16_t)((ep->xfer_len + ep->maxpacket - 1U) / ep->maxpacket); - USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_PKTCNT & ((uint32_t)pktcnt << 19); - USBx_OUTEP(epnum)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_XFRSIZ & (ep->maxpacket * pktcnt); - } - - if (dma == 1U) - { - if ((uint32_t)ep->xfer_buff != 0U) - { - USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff); - } - } - - if (ep->type == EP_TYPE_ISOC) - { - if ((USBx_DEVICE->DSTS & (1U << 8)) == 0U) - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SODDFRM; - } - else - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; - } - } - /* EP enable */ - USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA); - } - - return HAL_OK; -} - -/** - * @brief USB_EP0StartXfer : setup and starts a transfer over the EP 0 - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @retval HAL status - */ -HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - /* IN endpoint */ - if (ep->is_in == 1U) - { - /* Zero Length Packet? */ - if (ep->xfer_len == 0U) - { - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); - } - else - { - /* Program the transfer size and packet count - * as follows: xfersize = N * maxpacket + - * short_packet pktcnt = N + (short_packet - * exist ? 1 : 0) - */ - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_XFRSIZ); - USBx_INEP(epnum)->DIEPTSIZ &= ~(USB_OTG_DIEPTSIZ_PKTCNT); - - if (ep->xfer_len > ep->maxpacket) - { - ep->xfer_len = ep->maxpacket; - } - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_PKTCNT & (1U << 19)); - USBx_INEP(epnum)->DIEPTSIZ |= (USB_OTG_DIEPTSIZ_XFRSIZ & ep->xfer_len); - } - - if (dma == 1U) - { - if ((uint32_t)ep->dma_addr != 0U) - { - USBx_INEP(epnum)->DIEPDMA = (uint32_t)(ep->dma_addr); - } - - /* EP enable, IN data in FIFO */ - USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - } - else - { - /* EP enable, IN data in FIFO */ - USBx_INEP(epnum)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - - /* Enable the Tx FIFO Empty Interrupt for this EP */ - if (ep->xfer_len > 0U) - { - USBx_DEVICE->DIEPEMPMSK |= 1UL << (ep->num & EP_ADDR_MSK); - } - } - } - else /* OUT endpoint */ - { - /* Program the transfer size and packet count as follows: - * pktcnt = N - * xfersize = N * maxpacket - */ - USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_XFRSIZ); - USBx_OUTEP(epnum)->DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT); - - if (ep->xfer_len > 0U) - { - ep->xfer_len = ep->maxpacket; - } - - USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); - USBx_OUTEP(epnum)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_XFRSIZ & (ep->maxpacket)); - - if (dma == 1U) - { - if ((uint32_t)ep->xfer_buff != 0U) - { - USBx_OUTEP(epnum)->DOEPDMA = (uint32_t)(ep->xfer_buff); - } - } - - /* EP enable */ - USBx_OUTEP(epnum)->DOEPCTL |= (USB_OTG_DOEPCTL_CNAK | USB_OTG_DOEPCTL_EPENA); - } - - return HAL_OK; -} - -/** - * @brief USB_WritePacket : Writes a packet into the Tx FIFO associated - * with the EP/channel - * @param USBx Selected device - * @param src pointer to source buffer - * @param ch_ep_num endpoint or host channel number - * @param len Number of bytes to write - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @retval HAL status - */ -HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, - uint8_t ch_ep_num, uint16_t len, uint8_t dma) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint8_t *pSrc = src; - uint32_t count32b; - uint32_t i; - - if (dma == 0U) - { - count32b = ((uint32_t)len + 3U) / 4U; - for (i = 0U; i < count32b; i++) - { - USBx_DFIFO((uint32_t)ch_ep_num) = __UNALIGNED_UINT32_READ(pSrc); - pSrc++; - pSrc++; - pSrc++; - pSrc++; - } - } - - return HAL_OK; -} - -/** - * @brief USB_ReadPacket : read a packet from the RX FIFO - * @param USBx Selected device - * @param dest source pointer - * @param len Number of bytes to read - * @retval pointer to destination buffer - */ -void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint8_t *pDest = dest; - uint32_t pData; - uint32_t i; - uint32_t count32b = (uint32_t)len >> 2U; - uint16_t remaining_bytes = len % 4U; - - for (i = 0U; i < count32b; i++) - { - __UNALIGNED_UINT32_WRITE(pDest, USBx_DFIFO(0U)); - pDest++; - pDest++; - pDest++; - pDest++; - } - - /* When Number of data is not word aligned, read the remaining byte */ - if (remaining_bytes != 0U) - { - i = 0U; - __UNALIGNED_UINT32_WRITE(&pData, USBx_DFIFO(0U)); - - do - { - *(uint8_t *)pDest = (uint8_t)(pData >> (8U * (uint8_t)(i))); - i++; - pDest++; - remaining_bytes--; - } while (remaining_bytes != 0U); - } - - return ((void *)pDest); -} - -/** - * @brief USB_EPSetStall : set a stall condition over an EP - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - if (ep->is_in == 1U) - { - if (((USBx_INEP(epnum)->DIEPCTL & USB_OTG_DIEPCTL_EPENA) == 0U) && (epnum != 0U)) - { - USBx_INEP(epnum)->DIEPCTL &= ~(USB_OTG_DIEPCTL_EPDIS); - } - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_STALL; - } - else - { - if (((USBx_OUTEP(epnum)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == 0U) && (epnum != 0U)) - { - USBx_OUTEP(epnum)->DOEPCTL &= ~(USB_OTG_DOEPCTL_EPDIS); - } - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_STALL; - } - - return HAL_OK; -} - -/** - * @brief USB_EPClearStall : Clear a stall condition over an EP - * @param USBx Selected device - * @param ep pointer to endpoint structure - * @retval HAL status - */ -HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t epnum = (uint32_t)ep->num; - - if (ep->is_in == 1U) - { - USBx_INEP(epnum)->DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; - if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK)) - { - USBx_INEP(epnum)->DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; /* DATA0 */ - } - } - else - { - USBx_OUTEP(epnum)->DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; - if ((ep->type == EP_TYPE_INTR) || (ep->type == EP_TYPE_BULK)) - { - USBx_OUTEP(epnum)->DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; /* DATA0 */ - } - } - return HAL_OK; -} - -/** - * @brief USB_StopDevice : Stop the usb device mode - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx) -{ - HAL_StatusTypeDef ret; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t i; - - /* Clear Pending interrupt */ - for (i = 0U; i < 15U; i++) - { - USBx_INEP(i)->DIEPINT = 0xFB7FU; - USBx_OUTEP(i)->DOEPINT = 0xFB7FU; - } - - /* Clear interrupt masks */ - USBx_DEVICE->DIEPMSK = 0U; - USBx_DEVICE->DOEPMSK = 0U; - USBx_DEVICE->DAINTMSK = 0U; - - /* Flush the FIFO */ - ret = USB_FlushRxFifo(USBx); - if (ret != HAL_OK) - { - return ret; - } - - ret = USB_FlushTxFifo(USBx, 0x10U); - if (ret != HAL_OK) - { - return ret; - } - - return ret; -} - -/** - * @brief USB_SetDevAddress : Stop the usb device mode - * @param USBx Selected device - * @param address new device address to be assigned - * This parameter can be a value from 0 to 255 - * @retval HAL status - */ -HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - USBx_DEVICE->DCFG &= ~(USB_OTG_DCFG_DAD); - USBx_DEVICE->DCFG |= ((uint32_t)address << 4) & USB_OTG_DCFG_DAD; - - return HAL_OK; -} - -/** - * @brief USB_DevConnect : Connect the USB device by enabling Rpu - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - /* In case phy is stopped, ensure to ungate and restore the phy CLK */ - USBx_PCGCCTL &= ~(USB_OTG_PCGCCTL_STOPCLK | USB_OTG_PCGCCTL_GATECLK); - - USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_SDIS; - - return HAL_OK; -} - -/** - * @brief USB_DevDisconnect : Disconnect the USB device by disabling Rpu - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - /* In case phy is stopped, ensure to ungate and restore the phy CLK */ - USBx_PCGCCTL &= ~(USB_OTG_PCGCCTL_STOPCLK | USB_OTG_PCGCCTL_GATECLK); - - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - - return HAL_OK; -} - -/** - * @brief USB_ReadInterrupts: return the global USB interrupt status - * @param USBx Selected device - * @retval HAL status - */ -uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t tmpreg; - - tmpreg = USBx->GINTSTS; - tmpreg &= USBx->GINTMSK; - - return tmpreg; -} - -/** - * @brief USB_ReadDevAllOutEpInterrupt: return the USB device OUT endpoints interrupt status - * @param USBx Selected device - * @retval HAL status - */ -uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t tmpreg; - - tmpreg = USBx_DEVICE->DAINT; - tmpreg &= USBx_DEVICE->DAINTMSK; - - return ((tmpreg & 0xffff0000U) >> 16); -} - -/** - * @brief USB_ReadDevAllInEpInterrupt: return the USB device IN endpoints interrupt status - * @param USBx Selected device - * @retval HAL status - */ -uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t tmpreg; - - tmpreg = USBx_DEVICE->DAINT; - tmpreg &= USBx_DEVICE->DAINTMSK; - - return ((tmpreg & 0xFFFFU)); -} - -/** - * @brief Returns Device OUT EP Interrupt register - * @param USBx Selected device - * @param epnum endpoint number - * This parameter can be a value from 0 to 15 - * @retval Device OUT EP Interrupt register - */ -uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t tmpreg; - - tmpreg = USBx_OUTEP((uint32_t)epnum)->DOEPINT; - tmpreg &= USBx_DEVICE->DOEPMSK; - - return tmpreg; -} - -/** - * @brief Returns Device IN EP Interrupt register - * @param USBx Selected device - * @param epnum endpoint number - * This parameter can be a value from 0 to 15 - * @retval Device IN EP Interrupt register - */ -uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t tmpreg; - uint32_t msk; - uint32_t emp; - - msk = USBx_DEVICE->DIEPMSK; - emp = USBx_DEVICE->DIEPEMPMSK; - msk |= ((emp >> (epnum & EP_ADDR_MSK)) & 0x1U) << 7; - tmpreg = USBx_INEP((uint32_t)epnum)->DIEPINT & msk; - - return tmpreg; -} - -/** - * @brief USB_ClearInterrupts: clear a USB interrupt - * @param USBx Selected device - * @param interrupt flag - * @retval None - */ -void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt) -{ - USBx->GINTSTS |= interrupt; -} - -/** - * @brief Returns USB core mode - * @param USBx Selected device - * @retval return core mode : Host or Device - * This parameter can be one of these values: - * 0 : Host - * 1 : Device - */ -uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx) -{ - return ((USBx->GINTSTS) & 0x1U); -} - -/** - * @brief Activate EP0 for Setup transactions - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - /* Set the MPS of the IN EP0 to 64 bytes */ - USBx_INEP(0U)->DIEPCTL &= ~USB_OTG_DIEPCTL_MPSIZ; - - USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; - - return HAL_OK; -} - -/** - * @brief Prepare the EP0 to start the first control setup - * @param USBx Selected device - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @param psetup pointer to setup packet - * @retval HAL status - */ -HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t gSNPSiD = *(__IO uint32_t *)(&USBx->CID + 0x1U); - - if (gSNPSiD > USB_OTG_CORE_ID_300A) - { - if ((USBx_OUTEP(0U)->DOEPCTL & USB_OTG_DOEPCTL_EPENA) == USB_OTG_DOEPCTL_EPENA) - { - return HAL_OK; - } - } - - USBx_OUTEP(0U)->DOEPTSIZ = 0U; - USBx_OUTEP(0U)->DOEPTSIZ |= (USB_OTG_DOEPTSIZ_PKTCNT & (1U << 19)); - USBx_OUTEP(0U)->DOEPTSIZ |= (3U * 8U); - USBx_OUTEP(0U)->DOEPTSIZ |= USB_OTG_DOEPTSIZ_STUPCNT; - - if (dma == 1U) - { - USBx_OUTEP(0U)->DOEPDMA = (uint32_t)psetup; - /* EP enable */ - USBx_OUTEP(0U)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_USBAEP; - } - - return HAL_OK; -} - -/** - * @brief Reset the USB Core (needed after USB clock settings change) - * @param USBx Selected device - * @retval HAL status - */ -static HAL_StatusTypeDef USB_CoreReset(USB_OTG_GlobalTypeDef *USBx) -{ - __IO uint32_t count = 0U; - - /* Wait for AHB master IDLE state. */ - do - { - if (++count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U); - - /* Core Soft Reset */ - count = 0U; - USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - - do - { - if (++count > 200000U) - { - return HAL_TIMEOUT; - } - } while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); - - return HAL_OK; -} - -/** - * @brief USB_HostInit : Initializes the USB OTG controller registers - * for Host mode - * @param USBx Selected device - * @param cfg pointer to a USB_OTG_CfgTypeDef structure that contains - * the configuration information for the specified USBx peripheral. - * @retval HAL status - */ -HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t i; - - /* Restart the Phy Clock */ - USBx_PCGCCTL = 0U; - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Disable HW VBUS sensing */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_VBDEN); -#else - /* - * Disable HW VBUS sensing. VBUS is internally considered to be always - * at VBUS-Valid level (5V). - */ - USBx->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS; - USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN; - USBx->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN; -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - /* Disable Battery chargin detector */ - USBx->GCCFG &= ~(USB_OTG_GCCFG_BCDEN); -#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ - - if ((USBx->CID & (0x1U << 8)) != 0U) - { - if (cfg.speed == USBH_FSLS_SPEED) - { - /* Force Device Enumeration to FS/LS mode only */ - USBx_HOST->HCFG |= USB_OTG_HCFG_FSLSS; - } - else - { - /* Set default Max speed support */ - USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS); - } - } - else - { - /* Set default Max speed support */ - USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSS); - } - - /* Make sure the FIFOs are flushed. */ - (void)USB_FlushTxFifo(USBx, 0x10U); /* all Tx FIFOs */ - (void)USB_FlushRxFifo(USBx); - - /* Clear all pending HC Interrupts */ - for (i = 0U; i < cfg.Host_channels; i++) - { - USBx_HC(i)->HCINT = 0xFFFFFFFFU; - USBx_HC(i)->HCINTMSK = 0U; - } - - /* Disable all interrupts. */ - USBx->GINTMSK = 0U; - - /* Clear any pending interrupts */ - USBx->GINTSTS = 0xFFFFFFFFU; - - if ((USBx->CID & (0x1U << 8)) != 0U) - { - /* set Rx FIFO size */ - USBx->GRXFSIZ = 0x200U; - USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x100U << 16) & USB_OTG_NPTXFD) | 0x200U); - USBx->HPTXFSIZ = (uint32_t)(((0xE0U << 16) & USB_OTG_HPTXFSIZ_PTXFD) | 0x300U); - } - else - { - /* set Rx FIFO size */ - USBx->GRXFSIZ = 0x80U; - USBx->DIEPTXF0_HNPTXFSIZ = (uint32_t)(((0x60U << 16) & USB_OTG_NPTXFD) | 0x80U); - USBx->HPTXFSIZ = (uint32_t)(((0x40U << 16)& USB_OTG_HPTXFSIZ_PTXFD) | 0xE0U); - } - - /* Enable the common interrupts */ - if (cfg.dma_enable == 0U) - { - USBx->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; - } - - /* Enable interrupts matching to the Host mode ONLY */ - USBx->GINTMSK |= (USB_OTG_GINTMSK_PRTIM | USB_OTG_GINTMSK_HCIM | \ - USB_OTG_GINTMSK_SOFM | USB_OTG_GINTSTS_DISCINT | \ - USB_OTG_GINTMSK_PXFRM_IISOOXFRM | USB_OTG_GINTMSK_WUIM); - - return HAL_OK; -} - -/** - * @brief USB_InitFSLSPClkSel : Initializes the FSLSPClkSel field of the - * HCFG register on the PHY type and set the right frame interval - * @param USBx Selected device - * @param freq clock frequency - * This parameter can be one of these values: - * HCFG_48_MHZ : Full Speed 48 MHz Clock - * HCFG_6_MHZ : Low Speed 6 MHz Clock - * @retval HAL status - */ -HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - USBx_HOST->HCFG &= ~(USB_OTG_HCFG_FSLSPCS); - USBx_HOST->HCFG |= (uint32_t)freq & USB_OTG_HCFG_FSLSPCS; - - if (freq == HCFG_48_MHZ) - { - USBx_HOST->HFIR = 48000U; - } - else if (freq == HCFG_6_MHZ) - { - USBx_HOST->HFIR = 6000U; - } - else - { - /* ... */ - } - - return HAL_OK; -} - -/** - * @brief USB_OTG_ResetPort : Reset Host Port - * @param USBx Selected device - * @retval HAL status - * @note (1)The application must wait at least 10 ms - * before clearing the reset bit. - */ -HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - __IO uint32_t hprt0 = 0U; - - hprt0 = USBx_HPRT0; - - hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | - USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); - - USBx_HPRT0 = (USB_OTG_HPRT_PRST | hprt0); - HAL_Delay(100U); /* See Note #1 */ - USBx_HPRT0 = ((~USB_OTG_HPRT_PRST) & hprt0); - HAL_Delay(10U); - - return HAL_OK; -} - -/** - * @brief USB_DriveVbus : activate or de-activate vbus - * @param state VBUS state - * This parameter can be one of these values: - * 0 : Deactivate VBUS - * 1 : Activate VBUS - * @retval HAL status - */ -HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - __IO uint32_t hprt0 = 0U; - - hprt0 = USBx_HPRT0; - - hprt0 &= ~(USB_OTG_HPRT_PENA | USB_OTG_HPRT_PCDET | - USB_OTG_HPRT_PENCHNG | USB_OTG_HPRT_POCCHNG); - - if (((hprt0 & USB_OTG_HPRT_PPWR) == 0U) && (state == 1U)) - { - USBx_HPRT0 = (USB_OTG_HPRT_PPWR | hprt0); - } - if (((hprt0 & USB_OTG_HPRT_PPWR) == USB_OTG_HPRT_PPWR) && (state == 0U)) - { - USBx_HPRT0 = ((~USB_OTG_HPRT_PPWR) & hprt0); - } - return HAL_OK; -} - -/** - * @brief Return Host Core speed - * @param USBx Selected device - * @retval speed : Host speed - * This parameter can be one of these values: - * @arg HCD_SPEED_HIGH: High speed mode - * @arg HCD_SPEED_FULL: Full speed mode - * @arg HCD_SPEED_LOW: Low speed mode - */ -uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - __IO uint32_t hprt0 = 0U; - - hprt0 = USBx_HPRT0; - return ((hprt0 & USB_OTG_HPRT_PSPD) >> 17); -} - -/** - * @brief Return Host Current Frame number - * @param USBx Selected device - * @retval current frame number - */ -uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - return (USBx_HOST->HFNUM & USB_OTG_HFNUM_FRNUM); -} - -/** - * @brief Initialize a host channel - * @param USBx Selected device - * @param ch_num Channel number - * This parameter can be a value from 1 to 15 - * @param epnum Endpoint number - * This parameter can be a value from 1 to 15 - * @param dev_address Current device address - * This parameter can be a value from 0 to 255 - * @param speed Current device speed - * This parameter can be one of these values: - * @arg USB_OTG_SPEED_HIGH: High speed mode - * @arg USB_OTG_SPEED_FULL: Full speed mode - * @arg USB_OTG_SPEED_LOW: Low speed mode - * @param ep_type Endpoint Type - * This parameter can be one of these values: - * @arg EP_TYPE_CTRL: Control type - * @arg EP_TYPE_ISOC: Isochronous type - * @arg EP_TYPE_BULK: Bulk type - * @arg EP_TYPE_INTR: Interrupt type - * @param mps Max Packet Size - * This parameter can be a value from 0 to 32K - * @retval HAL state - */ -HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num, - uint8_t epnum, uint8_t dev_address, uint8_t speed, - uint8_t ep_type, uint16_t mps) -{ - HAL_StatusTypeDef ret = HAL_OK; - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t HCcharEpDir; - uint32_t HCcharLowSpeed; - uint32_t HostCoreSpeed; - - /* Clear old interrupt conditions for this host channel. */ - USBx_HC((uint32_t)ch_num)->HCINT = 0xFFFFFFFFU; - - /* Enable channel interrupts required for this transfer. */ - switch (ep_type) - { - case EP_TYPE_CTRL: - case EP_TYPE_BULK: - USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | - USB_OTG_HCINTMSK_STALLM | - USB_OTG_HCINTMSK_TXERRM | - USB_OTG_HCINTMSK_DTERRM | - USB_OTG_HCINTMSK_AHBERR | - USB_OTG_HCINTMSK_NAKM; - - if ((epnum & 0x80U) == 0x80U) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM; - } - else - { - if ((USBx->CID & (0x1U << 8)) != 0U) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_NYET | - USB_OTG_HCINTMSK_ACKM; - } - } - break; - - case EP_TYPE_INTR: - USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | - USB_OTG_HCINTMSK_STALLM | - USB_OTG_HCINTMSK_TXERRM | - USB_OTG_HCINTMSK_DTERRM | - USB_OTG_HCINTMSK_NAKM | - USB_OTG_HCINTMSK_AHBERR | - USB_OTG_HCINTMSK_FRMORM; - - if ((epnum & 0x80U) == 0x80U) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK |= USB_OTG_HCINTMSK_BBERRM; - } - - break; - - case EP_TYPE_ISOC: - USBx_HC((uint32_t)ch_num)->HCINTMSK = USB_OTG_HCINTMSK_XFRCM | - USB_OTG_HCINTMSK_ACKM | - USB_OTG_HCINTMSK_AHBERR | - USB_OTG_HCINTMSK_FRMORM; - - if ((epnum & 0x80U) == 0x80U) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK |= (USB_OTG_HCINTMSK_TXERRM | USB_OTG_HCINTMSK_BBERRM); - } - break; - - default: - ret = HAL_ERROR; - break; - } - - /* Enable the top level host channel interrupt. */ - USBx_HOST->HAINTMSK |= 1UL << (ch_num & 0xFU); - - /* Make sure host channel interrupts are enabled. */ - USBx->GINTMSK |= USB_OTG_GINTMSK_HCIM; - - /* Program the HCCHAR register */ - if ((epnum & 0x80U) == 0x80U) - { - HCcharEpDir = (0x1U << 15) & USB_OTG_HCCHAR_EPDIR; - } - else - { - HCcharEpDir = 0U; - } - - HostCoreSpeed = USB_GetHostSpeed(USBx); - - /* LS device plugged to HUB */ - if ((speed == HPRT0_PRTSPD_LOW_SPEED) && (HostCoreSpeed != HPRT0_PRTSPD_LOW_SPEED)) - { - HCcharLowSpeed = (0x1U << 17) & USB_OTG_HCCHAR_LSDEV; - } - else - { - HCcharLowSpeed = 0U; - } - - USBx_HC((uint32_t)ch_num)->HCCHAR = (((uint32_t)dev_address << 22) & USB_OTG_HCCHAR_DAD) | - ((((uint32_t)epnum & 0x7FU) << 11) & USB_OTG_HCCHAR_EPNUM) | - (((uint32_t)ep_type << 18) & USB_OTG_HCCHAR_EPTYP) | - ((uint32_t)mps & USB_OTG_HCCHAR_MPSIZ) | HCcharEpDir | HCcharLowSpeed; - - if (ep_type == EP_TYPE_INTR) - { - USBx_HC((uint32_t)ch_num)->HCCHAR |= USB_OTG_HCCHAR_ODDFRM ; - } - - return ret; -} - -/** - * @brief Start a transfer over a host channel - * @param USBx Selected device - * @param hc pointer to host channel structure - * @param dma USB dma enabled or disabled - * This parameter can be one of these values: - * 0 : DMA feature not used - * 1 : DMA feature used - * @retval HAL state - */ -HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_HCTypeDef *hc, uint8_t dma) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t ch_num = (uint32_t)hc->ch_num; - __IO uint32_t tmpreg; - uint8_t is_oddframe; - uint16_t len_words; - uint16_t num_packets; - uint16_t max_hc_pkt_count = 256U; - - if (((USBx->CID & (0x1U << 8)) != 0U) && (hc->speed == USBH_HS_SPEED)) - { - /* in DMA mode host Core automatically issues ping in case of NYET/NAK */ - if ((dma == 1U) && ((hc->ep_type == EP_TYPE_CTRL) || (hc->ep_type == EP_TYPE_BULK))) - { - USBx_HC((uint32_t)ch_num)->HCINTMSK &= ~(USB_OTG_HCINTMSK_NYET | - USB_OTG_HCINTMSK_ACKM | - USB_OTG_HCINTMSK_NAKM); - } - - if ((dma == 0U) && (hc->do_ping == 1U)) - { - (void)USB_DoPing(USBx, hc->ch_num); - return HAL_OK; - } - - } - - /* Compute the expected number of packets associated to the transfer */ - if (hc->xfer_len > 0U) - { - num_packets = (uint16_t)((hc->xfer_len + hc->max_packet - 1U) / hc->max_packet); - - if (num_packets > max_hc_pkt_count) - { - num_packets = max_hc_pkt_count; - hc->XferSize = (uint32_t)num_packets * hc->max_packet; - } - } - else - { - num_packets = 1U; - } - - /* - * For IN channel HCTSIZ.XferSize is expected to be an integer multiple of - * max_packet size. - */ - if (hc->ep_is_in != 0U) - { - hc->XferSize = (uint32_t)num_packets * hc->max_packet; - } - else - { - hc->XferSize = hc->xfer_len; - } - - /* Initialize the HCTSIZn register */ - USBx_HC(ch_num)->HCTSIZ = (hc->XferSize & USB_OTG_HCTSIZ_XFRSIZ) | - (((uint32_t)num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) | - (((uint32_t)hc->data_pid << 29) & USB_OTG_HCTSIZ_DPID); - - if (dma != 0U) - { - /* xfer_buff MUST be 32-bits aligned */ - USBx_HC(ch_num)->HCDMA = (uint32_t)hc->xfer_buff; - } - - is_oddframe = (((uint32_t)USBx_HOST->HFNUM & 0x01U) != 0U) ? 0U : 1U; - USBx_HC(ch_num)->HCCHAR &= ~USB_OTG_HCCHAR_ODDFRM; - USBx_HC(ch_num)->HCCHAR |= (uint32_t)is_oddframe << 29; - - /* Set host channel enable */ - tmpreg = USBx_HC(ch_num)->HCCHAR; - tmpreg &= ~USB_OTG_HCCHAR_CHDIS; - - /* make sure to set the correct ep direction */ - if (hc->ep_is_in != 0U) - { - tmpreg |= USB_OTG_HCCHAR_EPDIR; - } - else - { - tmpreg &= ~USB_OTG_HCCHAR_EPDIR; - } - tmpreg |= USB_OTG_HCCHAR_CHENA; - USBx_HC(ch_num)->HCCHAR = tmpreg; - - if (dma != 0U) /* dma mode */ - { - return HAL_OK; - } - - if ((hc->ep_is_in == 0U) && (hc->xfer_len > 0U)) - { - switch (hc->ep_type) - { - /* Non periodic transfer */ - case EP_TYPE_CTRL: - case EP_TYPE_BULK: - - len_words = (uint16_t)((hc->xfer_len + 3U) / 4U); - - /* check if there is enough space in FIFO space */ - if (len_words > (USBx->HNPTXSTS & 0xFFFFU)) - { - /* need to process data in nptxfempty interrupt */ - USBx->GINTMSK |= USB_OTG_GINTMSK_NPTXFEM; - } - break; - - /* Periodic transfer */ - case EP_TYPE_INTR: - case EP_TYPE_ISOC: - len_words = (uint16_t)((hc->xfer_len + 3U) / 4U); - /* check if there is enough space in FIFO space */ - if (len_words > (USBx_HOST->HPTXSTS & 0xFFFFU)) /* split the transfer */ - { - /* need to process data in ptxfempty interrupt */ - USBx->GINTMSK |= USB_OTG_GINTMSK_PTXFEM; - } - break; - - default: - break; - } - - /* Write packet into the Tx FIFO. */ - (void)USB_WritePacket(USBx, hc->xfer_buff, hc->ch_num, (uint16_t)hc->xfer_len, 0); - } - - return HAL_OK; -} - -/** - * @brief Read all host channel interrupts status - * @param USBx Selected device - * @retval HAL state - */ -uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - return ((USBx_HOST->HAINT) & 0xFFFFU); -} - -/** - * @brief Halt a host channel - * @param USBx Selected device - * @param hc_num Host Channel number - * This parameter can be a value from 1 to 15 - * @retval HAL state - */ -HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t hcnum = (uint32_t)hc_num; - uint32_t count = 0U; - uint32_t HcEpType = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_EPTYP) >> 18; - uint32_t ChannelEna = (USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) >> 31; - - if (((USBx->GAHBCFG & USB_OTG_GAHBCFG_DMAEN) == USB_OTG_GAHBCFG_DMAEN) && - (ChannelEna == 0U)) - { - return HAL_OK; - } - - /* Check for space in the request queue to issue the halt. */ - if ((HcEpType == HCCHAR_CTRL) || (HcEpType == HCCHAR_BULK)) - { - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS; - - if ((USBx->GAHBCFG & USB_OTG_GAHBCFG_DMAEN) == 0U) - { - if ((USBx->HNPTXSTS & (0xFFU << 16)) == 0U) - { - USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA; - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; - USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_EPDIR; - do - { - if (++count > 1000U) - { - break; - } - } while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); - } - else - { - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; - } - } - } - else - { - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHDIS; - - if ((USBx_HOST->HPTXSTS & (0xFFU << 16)) == 0U) - { - USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_CHENA; - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; - USBx_HC(hcnum)->HCCHAR &= ~USB_OTG_HCCHAR_EPDIR; - do - { - if (++count > 1000U) - { - break; - } - } while ((USBx_HC(hcnum)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); - } - else - { - USBx_HC(hcnum)->HCCHAR |= USB_OTG_HCCHAR_CHENA; - } - } - - return HAL_OK; -} - -/** - * @brief Initiate Do Ping protocol - * @param USBx Selected device - * @param hc_num Host Channel number - * This parameter can be a value from 1 to 15 - * @retval HAL state - */ -HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t chnum = (uint32_t)ch_num; - uint32_t num_packets = 1U; - uint32_t tmpreg; - - USBx_HC(chnum)->HCTSIZ = ((num_packets << 19) & USB_OTG_HCTSIZ_PKTCNT) | - USB_OTG_HCTSIZ_DOPING; - - /* Set host channel enable */ - tmpreg = USBx_HC(chnum)->HCCHAR; - tmpreg &= ~USB_OTG_HCCHAR_CHDIS; - tmpreg |= USB_OTG_HCCHAR_CHENA; - USBx_HC(chnum)->HCCHAR = tmpreg; - - return HAL_OK; -} - -/** - * @brief Stop Host Core - * @param USBx Selected device - * @retval HAL state - */ -HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - uint32_t count = 0U; - uint32_t value; - uint32_t i; - - (void)USB_DisableGlobalInt(USBx); - - /* Flush FIFO */ - (void)USB_FlushTxFifo(USBx, 0x10U); - (void)USB_FlushRxFifo(USBx); - - /* Flush out any leftover queued requests. */ - for (i = 0U; i <= 15U; i++) - { - value = USBx_HC(i)->HCCHAR; - value |= USB_OTG_HCCHAR_CHDIS; - value &= ~USB_OTG_HCCHAR_CHENA; - value &= ~USB_OTG_HCCHAR_EPDIR; - USBx_HC(i)->HCCHAR = value; - } - - /* Halt all channels to put them into a known state. */ - for (i = 0U; i <= 15U; i++) - { - value = USBx_HC(i)->HCCHAR; - value |= USB_OTG_HCCHAR_CHDIS; - value |= USB_OTG_HCCHAR_CHENA; - value &= ~USB_OTG_HCCHAR_EPDIR; - USBx_HC(i)->HCCHAR = value; - - do - { - if (++count > 1000U) - { - break; - } - } while ((USBx_HC(i)->HCCHAR & USB_OTG_HCCHAR_CHENA) == USB_OTG_HCCHAR_CHENA); - } - - /* Clear any pending Host interrupts */ - USBx_HOST->HAINT = 0xFFFFFFFFU; - USBx->GINTSTS = 0xFFFFFFFFU; - - (void)USB_EnableGlobalInt(USBx); - - return HAL_OK; -} - -/** - * @brief USB_ActivateRemoteWakeup active remote wakeup signalling - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - if ((USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS) == USB_OTG_DSTS_SUSPSTS) - { - /* active Remote wakeup signalling */ - USBx_DEVICE->DCTL |= USB_OTG_DCTL_RWUSIG; - } - - return HAL_OK; -} - -/** - * @brief USB_DeActivateRemoteWakeup de-active remote wakeup signalling - * @param USBx Selected device - * @retval HAL status - */ -HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx) -{ - uint32_t USBx_BASE = (uint32_t)USBx; - - /* active Remote wakeup signalling */ - USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_RWUSIG); - - return HAL_OK; -} -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -#endif /* defined (HAL_PCD_MODULE_ENABLED) || defined (HAL_HCD_MODULE_ENABLED) */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_utils.c b/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_utils.c deleted file mode 100644 index 96f65272be19876..000000000000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_ll_utils.c +++ /dev/null @@ -1,752 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_utils.c - * @author MCD Application Team - * @brief UTILS LL module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_utils.h" -#include "stm32f4xx_ll_rcc.h" -#include "stm32f4xx_ll_system.h" -#include "stm32f4xx_ll_pwr.h" -#ifdef USE_FULL_ASSERT -#include "stm32_assert.h" -#else -#define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -/** @addtogroup UTILS_LL - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @addtogroup UTILS_LL_Private_Constants - * @{ - */ -#if defined(RCC_MAX_FREQUENCY_SCALE1) -#define UTILS_MAX_FREQUENCY_SCALE1 RCC_MAX_FREQUENCY /*!< Maximum frequency for system clock at power scale1, in Hz */ -#endif /*RCC_MAX_FREQUENCY_SCALE1 */ -#define UTILS_MAX_FREQUENCY_SCALE2 RCC_MAX_FREQUENCY_SCALE2 /*!< Maximum frequency for system clock at power scale2, in Hz */ -#if defined(RCC_MAX_FREQUENCY_SCALE3) -#define UTILS_MAX_FREQUENCY_SCALE3 RCC_MAX_FREQUENCY_SCALE3 /*!< Maximum frequency for system clock at power scale3, in Hz */ -#endif /* MAX_FREQUENCY_SCALE3 */ - -/* Defines used for PLL range */ -#define UTILS_PLLVCO_INPUT_MIN RCC_PLLVCO_INPUT_MIN /*!< Frequency min for PLLVCO input, in Hz */ -#define UTILS_PLLVCO_INPUT_MAX RCC_PLLVCO_INPUT_MAX /*!< Frequency max for PLLVCO input, in Hz */ -#define UTILS_PLLVCO_OUTPUT_MIN RCC_PLLVCO_OUTPUT_MIN /*!< Frequency min for PLLVCO output, in Hz */ -#define UTILS_PLLVCO_OUTPUT_MAX RCC_PLLVCO_OUTPUT_MAX /*!< Frequency max for PLLVCO output, in Hz */ - -/* Defines used for HSE range */ -#define UTILS_HSE_FREQUENCY_MIN 4000000U /*!< Frequency min for HSE frequency, in Hz */ -#define UTILS_HSE_FREQUENCY_MAX 26000000U /*!< Frequency max for HSE frequency, in Hz */ - -/* Defines used for FLASH latency according to HCLK Frequency */ -#if defined(FLASH_SCALE1_LATENCY1_FREQ) -#define UTILS_SCALE1_LATENCY1_FREQ FLASH_SCALE1_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 1 */ -#endif -#if defined(FLASH_SCALE1_LATENCY2_FREQ) -#define UTILS_SCALE1_LATENCY2_FREQ FLASH_SCALE1_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 1 */ -#endif -#if defined(FLASH_SCALE1_LATENCY3_FREQ) -#define UTILS_SCALE1_LATENCY3_FREQ FLASH_SCALE1_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 3 in power scale 1 */ -#endif -#if defined(FLASH_SCALE1_LATENCY4_FREQ) -#define UTILS_SCALE1_LATENCY4_FREQ FLASH_SCALE1_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 1 */ -#endif -#if defined(FLASH_SCALE1_LATENCY5_FREQ) -#define UTILS_SCALE1_LATENCY5_FREQ FLASH_SCALE1_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 1 */ -#endif -#define UTILS_SCALE2_LATENCY1_FREQ FLASH_SCALE2_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 2 */ -#define UTILS_SCALE2_LATENCY2_FREQ FLASH_SCALE2_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 2 */ -#if defined(FLASH_SCALE2_LATENCY3_FREQ) -#define UTILS_SCALE2_LATENCY3_FREQ FLASH_SCALE2_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 2 */ -#endif -#if defined(FLASH_SCALE2_LATENCY4_FREQ) -#define UTILS_SCALE2_LATENCY4_FREQ FLASH_SCALE2_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 2 */ -#endif -#if defined(FLASH_SCALE2_LATENCY5_FREQ) -#define UTILS_SCALE2_LATENCY5_FREQ FLASH_SCALE2_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 2 */ -#endif -#if defined(FLASH_SCALE3_LATENCY1_FREQ) -#define UTILS_SCALE3_LATENCY1_FREQ FLASH_SCALE3_LATENCY1_FREQ /*!< HCLK frequency to set FLASH latency 1 in power scale 3 */ -#endif -#if defined(FLASH_SCALE3_LATENCY2_FREQ) -#define UTILS_SCALE3_LATENCY2_FREQ FLASH_SCALE3_LATENCY2_FREQ /*!< HCLK frequency to set FLASH latency 2 in power scale 3 */ -#endif -#if defined(FLASH_SCALE3_LATENCY3_FREQ) -#define UTILS_SCALE3_LATENCY3_FREQ FLASH_SCALE3_LATENCY3_FREQ /*!< HCLK frequency to set FLASH latency 3 in power scale 3 */ -#endif -#if defined(FLASH_SCALE3_LATENCY4_FREQ) -#define UTILS_SCALE3_LATENCY4_FREQ FLASH_SCALE3_LATENCY4_FREQ /*!< HCLK frequency to set FLASH latency 4 in power scale 3 */ -#endif -#if defined(FLASH_SCALE3_LATENCY5_FREQ) -#define UTILS_SCALE3_LATENCY5_FREQ FLASH_SCALE3_LATENCY5_FREQ /*!< HCLK frequency to set FLASH latency 5 in power scale 3 */ -#endif -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup UTILS_LL_Private_Macros - * @{ - */ -#define IS_LL_UTILS_SYSCLK_DIV(__VALUE__) (((__VALUE__) == LL_RCC_SYSCLK_DIV_1) \ - || ((__VALUE__) == LL_RCC_SYSCLK_DIV_2) \ - || ((__VALUE__) == LL_RCC_SYSCLK_DIV_4) \ - || ((__VALUE__) == LL_RCC_SYSCLK_DIV_8) \ - || ((__VALUE__) == LL_RCC_SYSCLK_DIV_16) \ - || ((__VALUE__) == LL_RCC_SYSCLK_DIV_64) \ - || ((__VALUE__) == LL_RCC_SYSCLK_DIV_128) \ - || ((__VALUE__) == LL_RCC_SYSCLK_DIV_256) \ - || ((__VALUE__) == LL_RCC_SYSCLK_DIV_512)) - -#define IS_LL_UTILS_APB1_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB1_DIV_1) \ - || ((__VALUE__) == LL_RCC_APB1_DIV_2) \ - || ((__VALUE__) == LL_RCC_APB1_DIV_4) \ - || ((__VALUE__) == LL_RCC_APB1_DIV_8) \ - || ((__VALUE__) == LL_RCC_APB1_DIV_16)) - -#define IS_LL_UTILS_APB2_DIV(__VALUE__) (((__VALUE__) == LL_RCC_APB2_DIV_1) \ - || ((__VALUE__) == LL_RCC_APB2_DIV_2) \ - || ((__VALUE__) == LL_RCC_APB2_DIV_4) \ - || ((__VALUE__) == LL_RCC_APB2_DIV_8) \ - || ((__VALUE__) == LL_RCC_APB2_DIV_16)) - -#define IS_LL_UTILS_PLLM_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLLM_DIV_2) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_3) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_4) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_5) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_6) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_7) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_8) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_9) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_10) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_11) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_12) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_13) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_14) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_15) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_16) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_17) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_18) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_19) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_20) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_21) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_22) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_23) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_24) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_25) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_26) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_27) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_28) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_29) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_30) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_31) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_32) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_33) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_34) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_35) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_36) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_37) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_38) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_39) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_40) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_41) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_42) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_43) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_44) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_45) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_46) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_47) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_48) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_49) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_50) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_51) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_52) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_53) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_54) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_55) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_56) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_57) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_58) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_59) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_60) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_61) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_62) \ - || ((__VALUE__) == LL_RCC_PLLM_DIV_63)) - -#define IS_LL_UTILS_PLLN_VALUE(__VALUE__) ((RCC_PLLN_MIN_VALUE <= (__VALUE__)) && ((__VALUE__) <= RCC_PLLN_MAX_VALUE)) - -#define IS_LL_UTILS_PLLP_VALUE(__VALUE__) (((__VALUE__) == LL_RCC_PLLP_DIV_2) \ - || ((__VALUE__) == LL_RCC_PLLP_DIV_4) \ - || ((__VALUE__) == LL_RCC_PLLP_DIV_6) \ - || ((__VALUE__) == LL_RCC_PLLP_DIV_8)) - -#define IS_LL_UTILS_PLLVCO_INPUT(__VALUE__) ((UTILS_PLLVCO_INPUT_MIN <= (__VALUE__)) && ((__VALUE__) <= UTILS_PLLVCO_INPUT_MAX)) - -#define IS_LL_UTILS_PLLVCO_OUTPUT(__VALUE__) ((UTILS_PLLVCO_OUTPUT_MIN <= (__VALUE__)) && ((__VALUE__) <= UTILS_PLLVCO_OUTPUT_MAX)) - -#if !defined(RCC_MAX_FREQUENCY_SCALE1) -#define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2) : \ - ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE3)) - -#elif defined(RCC_MAX_FREQUENCY_SCALE3) -#define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE1) : \ - (LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2) : \ - ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE3)) - -#else -#define IS_LL_UTILS_PLL_FREQUENCY(__VALUE__) ((LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1) ? ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE1) : \ - ((__VALUE__) <= UTILS_MAX_FREQUENCY_SCALE2)) - -#endif /* RCC_MAX_FREQUENCY_SCALE1*/ -#define IS_LL_UTILS_HSE_BYPASS(__STATE__) (((__STATE__) == LL_UTILS_HSEBYPASS_ON) \ - || ((__STATE__) == LL_UTILS_HSEBYPASS_OFF)) - -#define IS_LL_UTILS_HSE_FREQUENCY(__FREQUENCY__) (((__FREQUENCY__) >= UTILS_HSE_FREQUENCY_MIN) && ((__FREQUENCY__) <= UTILS_HSE_FREQUENCY_MAX)) -/** - * @} - */ -/* Private function prototypes -----------------------------------------------*/ -/** @defgroup UTILS_LL_Private_Functions UTILS Private functions - * @{ - */ -static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency, - LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct); -static ErrorStatus UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); -static ErrorStatus UTILS_PLL_IsBusy(void); -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup UTILS_LL_Exported_Functions - * @{ - */ - -/** @addtogroup UTILS_LL_EF_DELAY - * @{ - */ - -/** - * @brief This function configures the Cortex-M SysTick source to have 1ms time base. - * @note When a RTOS is used, it is recommended to avoid changing the Systick - * configuration by calling this function, for a delay use rather osDelay RTOS service. - * @param HCLKFrequency HCLK frequency in Hz - * @note HCLK frequency can be calculated thanks to RCC helper macro or function @ref LL_RCC_GetSystemClocksFreq - * @retval None - */ -void LL_Init1msTick(uint32_t HCLKFrequency) -{ - /* Use frequency provided in argument */ - LL_InitTick(HCLKFrequency, 1000U); -} - -/** - * @brief This function provides accurate delay (in milliseconds) based - * on SysTick counter flag - * @note When a RTOS is used, it is recommended to avoid using blocking delay - * and use rather osDelay service. - * @note To respect 1ms timebase, user should call @ref LL_Init1msTick function which - * will configure Systick to 1ms - * @param Delay specifies the delay time length, in milliseconds. - * @retval None - */ -void LL_mDelay(uint32_t Delay) -{ - __IO uint32_t tmp = SysTick->CTRL; /* Clear the COUNTFLAG first */ - /* Add this code to indicate that local variable is not used */ - ((void)tmp); - - /* Add a period to guaranty minimum wait */ - if(Delay < LL_MAX_DELAY) - { - Delay++; - } - - while (Delay) - { - if((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) != 0U) - { - Delay--; - } - } -} - -/** - * @} - */ - -/** @addtogroup UTILS_EF_SYSTEM - * @brief System Configuration functions - * - @verbatim - =============================================================================== - ##### System Configuration functions ##### - =============================================================================== - [..] - System, AHB and APB buses clocks configuration - - (+) The maximum frequency of the SYSCLK, HCLK, PCLK1 and PCLK2 is 180000000 Hz. - @endverbatim - @internal - Depending on the device voltage range, the maximum frequency should be - adapted accordingly to the Refenece manual. - @endinternal - * @{ - */ - -/** - * @brief This function sets directly SystemCoreClock CMSIS variable. - * @note Variable can be calculated also through SystemCoreClockUpdate function. - * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro) - * @retval None - */ -void LL_SetSystemCoreClock(uint32_t HCLKFrequency) -{ - /* HCLK clock frequency */ - SystemCoreClock = HCLKFrequency; -} - -/** - * @brief Update number of Flash wait states in line with new frequency and current - voltage range. - * @note This Function support ONLY devices with supply voltage (voltage range) between 2.7V and 3.6V - * @param HCLK_Frequency HCLK frequency - * @retval An ErrorStatus enumeration value: - * - SUCCESS: Latency has been modified - * - ERROR: Latency cannot be modified - */ -ErrorStatus LL_SetFlashLatency(uint32_t HCLK_Frequency) -{ - uint32_t timeout; - uint32_t getlatency; - uint32_t latency = LL_FLASH_LATENCY_0; /* default value 0WS */ - ErrorStatus status = SUCCESS; - - - /* Frequency cannot be equal to 0 */ - if(HCLK_Frequency == 0U) - { - status = ERROR; - } - else - { - if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE1) - { -#if defined (UTILS_SCALE1_LATENCY5_FREQ) - if((HCLK_Frequency > UTILS_SCALE1_LATENCY5_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_5; - } -#endif /*UTILS_SCALE1_LATENCY5_FREQ */ -#if defined (UTILS_SCALE1_LATENCY4_FREQ) - if((HCLK_Frequency > UTILS_SCALE1_LATENCY4_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_4; - } -#endif /* UTILS_SCALE1_LATENCY4_FREQ */ -#if defined (UTILS_SCALE1_LATENCY3_FREQ) - if((HCLK_Frequency > UTILS_SCALE1_LATENCY3_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_3; - } -#endif /* UTILS_SCALE1_LATENCY3_FREQ */ -#if defined (UTILS_SCALE1_LATENCY2_FREQ) - if((HCLK_Frequency > UTILS_SCALE1_LATENCY2_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_2; - } - else - { - if((HCLK_Frequency > UTILS_SCALE1_LATENCY1_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_1; - } - } -#endif /* UTILS_SCALE1_LATENCY2_FREQ */ - } - if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE2) - { -#if defined (UTILS_SCALE2_LATENCY5_FREQ) - if((HCLK_Frequency > UTILS_SCALE2_LATENCY5_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_5; - } -#endif /*UTILS_SCALE1_LATENCY5_FREQ */ -#if defined (UTILS_SCALE2_LATENCY4_FREQ) - if((HCLK_Frequency > UTILS_SCALE2_LATENCY4_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_4; - } -#endif /*UTILS_SCALE1_LATENCY4_FREQ */ -#if defined (UTILS_SCALE2_LATENCY3_FREQ) - if((HCLK_Frequency > UTILS_SCALE2_LATENCY3_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_3; - } -#endif /*UTILS_SCALE1_LATENCY3_FREQ */ - if((HCLK_Frequency > UTILS_SCALE2_LATENCY2_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_2; - } - else - { - if((HCLK_Frequency > UTILS_SCALE2_LATENCY1_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_1; - } - } - } -#if defined (LL_PWR_REGU_VOLTAGE_SCALE3) - if(LL_PWR_GetRegulVoltageScaling() == LL_PWR_REGU_VOLTAGE_SCALE3) - { -#if defined (UTILS_SCALE3_LATENCY3_FREQ) - if((HCLK_Frequency > UTILS_SCALE3_LATENCY3_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_3; - } -#endif /*UTILS_SCALE1_LATENCY3_FREQ */ -#if defined (UTILS_SCALE3_LATENCY2_FREQ) - if((HCLK_Frequency > UTILS_SCALE3_LATENCY2_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_2; - } - else - { - if((HCLK_Frequency > UTILS_SCALE3_LATENCY1_FREQ)&&(latency == LL_FLASH_LATENCY_0)) - { - latency = LL_FLASH_LATENCY_1; - } - } - } -#endif /*UTILS_SCALE1_LATENCY2_FREQ */ -#endif /* LL_PWR_REGU_VOLTAGE_SCALE3 */ - - LL_FLASH_SetLatency(latency); - /* Check that the new number of wait states is taken into account to access the Flash - memory by reading the FLASH_ACR register */ - timeout = 2; - do - { - /* Wait for Flash latency to be updated */ - getlatency = LL_FLASH_GetLatency(); - timeout--; - } while ((getlatency != latency) && (timeout > 0)); - - if(getlatency != latency) - { - status = ERROR; - } - else - { - status = SUCCESS; - } - } - return status; -} - -/** - * @brief This function configures system clock at maximum frequency with HSI as clock source of the PLL - * @note The application need to ensure that PLL is disabled. - * @note Function is based on the following formula: - * - PLL output frequency = (((HSI frequency / PLLM) * PLLN) / PLLP) - * - PLLM: ensure that the VCO input frequency ranges from @ref RCC_PLLVCO_INPUT_MIN to @ref RCC_PLLVCO_INPUT_MAX (PLLVCO_input = HSI frequency / PLLM) - * - PLLN: ensure that the VCO output frequency is between @ref RCC_PLLVCO_OUTPUT_MIN and @ref RCC_PLLVCO_OUTPUT_MAX (PLLVCO_output = PLLVCO_input * PLLN) - * - PLLP: ensure that max frequency at 180000000 Hz is reach (PLLVCO_output / PLLP) - * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains - * the configuration information for the PLL. - * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains - * the configuration information for the BUS prescalers. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: Max frequency configuration done - * - ERROR: Max frequency configuration not done - */ -ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, - LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct) -{ - ErrorStatus status = SUCCESS; - uint32_t pllfreq = 0U; - - /* Check if one of the PLL is enabled */ - if(UTILS_PLL_IsBusy() == SUCCESS) - { - /* Calculate the new PLL output frequency */ - pllfreq = UTILS_GetPLLOutputFrequency(HSI_VALUE, UTILS_PLLInitStruct); - - /* Enable HSI if not enabled */ - if(LL_RCC_HSI_IsReady() != 1U) - { - LL_RCC_HSI_Enable(); - while (LL_RCC_HSI_IsReady() != 1U) - { - /* Wait for HSI ready */ - } - } - - /* Configure PLL */ - LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSI, UTILS_PLLInitStruct->PLLM, UTILS_PLLInitStruct->PLLN, - UTILS_PLLInitStruct->PLLP); - - /* Enable PLL and switch system clock to PLL */ - status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct); - } - else - { - /* Current PLL configuration cannot be modified */ - status = ERROR; - } - - return status; -} - -/** - * @brief This function configures system clock with HSE as clock source of the PLL - * @note The application need to ensure that PLL is disabled. - * - PLL output frequency = (((HSI frequency / PLLM) * PLLN) / PLLP) - * - PLLM: ensure that the VCO input frequency ranges from @ref RCC_PLLVCO_INPUT_MIN to @ref RCC_PLLVCO_INPUT_MAX (PLLVCO_input = HSI frequency / PLLM) - * - PLLN: ensure that the VCO output frequency is between @ref RCC_PLLVCO_OUTPUT_MIN and @ref RCC_PLLVCO_OUTPUT_MAX (PLLVCO_output = PLLVCO_input * PLLN) - * - PLLP: ensure that max frequency at 180000000 Hz is reach (PLLVCO_output / PLLP) - * @param HSEFrequency Value between Min_Data = 4000000 and Max_Data = 26000000 - * @param HSEBypass This parameter can be one of the following values: - * @arg @ref LL_UTILS_HSEBYPASS_ON - * @arg @ref LL_UTILS_HSEBYPASS_OFF - * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains - * the configuration information for the PLL. - * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains - * the configuration information for the BUS prescalers. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: Max frequency configuration done - * - ERROR: Max frequency configuration not done - */ -ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass, - LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct) -{ - ErrorStatus status = SUCCESS; - uint32_t pllfreq = 0U; - - /* Check the parameters */ - assert_param(IS_LL_UTILS_HSE_FREQUENCY(HSEFrequency)); - assert_param(IS_LL_UTILS_HSE_BYPASS(HSEBypass)); - - /* Check if one of the PLL is enabled */ - if(UTILS_PLL_IsBusy() == SUCCESS) - { - /* Calculate the new PLL output frequency */ - pllfreq = UTILS_GetPLLOutputFrequency(HSEFrequency, UTILS_PLLInitStruct); - - /* Enable HSE if not enabled */ - if(LL_RCC_HSE_IsReady() != 1U) - { - /* Check if need to enable HSE bypass feature or not */ - if(HSEBypass == LL_UTILS_HSEBYPASS_ON) - { - LL_RCC_HSE_EnableBypass(); - } - else - { - LL_RCC_HSE_DisableBypass(); - } - - /* Enable HSE */ - LL_RCC_HSE_Enable(); - while (LL_RCC_HSE_IsReady() != 1U) - { - /* Wait for HSE ready */ - } - } - - /* Configure PLL */ - LL_RCC_PLL_ConfigDomain_SYS(LL_RCC_PLLSOURCE_HSE, UTILS_PLLInitStruct->PLLM, UTILS_PLLInitStruct->PLLN, - UTILS_PLLInitStruct->PLLP); - - /* Enable PLL and switch system clock to PLL */ - status = UTILS_EnablePLLAndSwitchSystem(pllfreq, UTILS_ClkInitStruct); - } - else - { - /* Current PLL configuration cannot be modified */ - status = ERROR; - } - - return status; -} - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup UTILS_LL_Private_Functions - * @{ - */ -/** - * @brief Function to check that PLL can be modified - * @param PLL_InputFrequency PLL input frequency (in Hz) - * @param UTILS_PLLInitStruct pointer to a @ref LL_UTILS_PLLInitTypeDef structure that contains - * the configuration information for the PLL. - * @retval PLL output frequency (in Hz) - */ -static uint32_t UTILS_GetPLLOutputFrequency(uint32_t PLL_InputFrequency, LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct) -{ - uint32_t pllfreq = 0U; - - /* Check the parameters */ - assert_param(IS_LL_UTILS_PLLM_VALUE(UTILS_PLLInitStruct->PLLM)); - assert_param(IS_LL_UTILS_PLLN_VALUE(UTILS_PLLInitStruct->PLLN)); - assert_param(IS_LL_UTILS_PLLP_VALUE(UTILS_PLLInitStruct->PLLP)); - - /* Check different PLL parameters according to RM */ - /* - PLLM: ensure that the VCO input frequency ranges from @ref UTILS_PLLVCO_INPUT_MIN to @ref UTILS_PLLVCO_INPUT_MAX MHz. */ - pllfreq = PLL_InputFrequency / (UTILS_PLLInitStruct->PLLM & (RCC_PLLCFGR_PLLM >> RCC_PLLCFGR_PLLM_Pos)); - assert_param(IS_LL_UTILS_PLLVCO_INPUT(pllfreq)); - - /* - PLLN: ensure that the VCO output frequency is between @ref UTILS_PLLVCO_OUTPUT_MIN and @ref UTILS_PLLVCO_OUTPUT_MAX .*/ - pllfreq = pllfreq * (UTILS_PLLInitStruct->PLLN & (RCC_PLLCFGR_PLLN >> RCC_PLLCFGR_PLLN_Pos)); - assert_param(IS_LL_UTILS_PLLVCO_OUTPUT(pllfreq)); - - /* - PLLP: ensure that max frequency at @ref RCC_MAX_FREQUENCY Hz is reached */ - pllfreq = pllfreq / (((UTILS_PLLInitStruct->PLLP >> RCC_PLLCFGR_PLLP_Pos) + 1) * 2); - assert_param(IS_LL_UTILS_PLL_FREQUENCY(pllfreq)); - - return pllfreq; -} - -/** - * @brief Function to check that PLL can be modified - * @retval An ErrorStatus enumeration value: - * - SUCCESS: PLL modification can be done - * - ERROR: PLL is busy - */ -static ErrorStatus UTILS_PLL_IsBusy(void) -{ - ErrorStatus status = SUCCESS; - - /* Check if PLL is busy*/ - if(LL_RCC_PLL_IsReady() != 0U) - { - /* PLL configuration cannot be modified */ - status = ERROR; - } - -#if defined(RCC_PLLSAI_SUPPORT) - /* Check if PLLSAI is busy*/ - if(LL_RCC_PLLSAI_IsReady() != 0U) - { - /* PLLSAI1 configuration cannot be modified */ - status = ERROR; - } -#endif /*RCC_PLLSAI_SUPPORT*/ -#if defined(RCC_PLLI2S_SUPPORT) - /* Check if PLLI2S is busy*/ - if(LL_RCC_PLLI2S_IsReady() != 0U) - { - /* PLLI2S configuration cannot be modified */ - status = ERROR; - } -#endif /*RCC_PLLI2S_SUPPORT*/ - return status; -} - -/** - * @brief Function to enable PLL and switch system clock to PLL - * @param SYSCLK_Frequency SYSCLK frequency - * @param UTILS_ClkInitStruct pointer to a @ref LL_UTILS_ClkInitTypeDef structure that contains - * the configuration information for the BUS prescalers. - * @retval An ErrorStatus enumeration value: - * - SUCCESS: No problem to switch system to PLL - * - ERROR: Problem to switch system to PLL - */ -static ErrorStatus UTILS_EnablePLLAndSwitchSystem(uint32_t SYSCLK_Frequency, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct) -{ - ErrorStatus status = SUCCESS; - uint32_t hclk_frequency = 0U; - - assert_param(IS_LL_UTILS_SYSCLK_DIV(UTILS_ClkInitStruct->AHBCLKDivider)); - assert_param(IS_LL_UTILS_APB1_DIV(UTILS_ClkInitStruct->APB1CLKDivider)); - assert_param(IS_LL_UTILS_APB2_DIV(UTILS_ClkInitStruct->APB2CLKDivider)); - - /* Calculate HCLK frequency */ - hclk_frequency = __LL_RCC_CALC_HCLK_FREQ(SYSCLK_Frequency, UTILS_ClkInitStruct->AHBCLKDivider); - - /* Increasing the number of wait states because of higher CPU frequency */ - if(SystemCoreClock < hclk_frequency) - { - /* Set FLASH latency to highest latency */ - status = LL_SetFlashLatency(hclk_frequency); - } - - /* Update system clock configuration */ - if(status == SUCCESS) - { - /* Enable PLL */ - LL_RCC_PLL_Enable(); - while (LL_RCC_PLL_IsReady() != 1U) - { - /* Wait for PLL ready */ - } - - /* Sysclk activation on the main PLL */ - LL_RCC_SetAHBPrescaler(UTILS_ClkInitStruct->AHBCLKDivider); - LL_RCC_SetSysClkSource(LL_RCC_SYS_CLKSOURCE_PLL); - while (LL_RCC_GetSysClkSource() != LL_RCC_SYS_CLKSOURCE_STATUS_PLL) - { - /* Wait for system clock switch to PLL */ - } - - /* Set APB1 & APB2 prescaler*/ - LL_RCC_SetAPB1Prescaler(UTILS_ClkInitStruct->APB1CLKDivider); - LL_RCC_SetAPB2Prescaler(UTILS_ClkInitStruct->APB2CLKDivider); - } - - /* Decreasing the number of wait states because of lower CPU frequency */ - if(SystemCoreClock > hclk_frequency) - { - /* Set FLASH latency to lowest latency */ - status = LL_SetFlashLatency(hclk_frequency); - } - - /* Update SystemCoreClock variable */ - if(status == SUCCESS) - { - LL_SetSystemCoreClock(hclk_frequency); - } - - return status; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/arm_common_tables.h b/body/board/inc/arm_common_tables.h deleted file mode 100644 index 8742a5699153c3d..000000000000000 --- a/body/board/inc/arm_common_tables.h +++ /dev/null @@ -1,136 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010-2014 ARM Limited. All rights reserved. -* -* $Date: 19. October 2015 -* $Revision: V.1.4.5 a -* -* Project: CMSIS DSP Library -* Title: arm_common_tables.h -* -* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* - Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* - 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. -* - Neither the name of ARM LIMITED 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 OWNER 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. -* -------------------------------------------------------------------- */ - -#ifndef _ARM_COMMON_TABLES_H -#define _ARM_COMMON_TABLES_H - -#include "arm_math.h" - -extern const uint16_t armBitRevTable[1024]; -extern const q15_t armRecipTableQ15[64]; -extern const q31_t armRecipTableQ31[64]; -/* extern const q31_t realCoefAQ31[1024]; */ -/* extern const q31_t realCoefBQ31[1024]; */ -extern const float32_t twiddleCoef_16[32]; -extern const float32_t twiddleCoef_32[64]; -extern const float32_t twiddleCoef_64[128]; -extern const float32_t twiddleCoef_128[256]; -extern const float32_t twiddleCoef_256[512]; -extern const float32_t twiddleCoef_512[1024]; -extern const float32_t twiddleCoef_1024[2048]; -extern const float32_t twiddleCoef_2048[4096]; -extern const float32_t twiddleCoef_4096[8192]; -#define twiddleCoef twiddleCoef_4096 -extern const q31_t twiddleCoef_16_q31[24]; -extern const q31_t twiddleCoef_32_q31[48]; -extern const q31_t twiddleCoef_64_q31[96]; -extern const q31_t twiddleCoef_128_q31[192]; -extern const q31_t twiddleCoef_256_q31[384]; -extern const q31_t twiddleCoef_512_q31[768]; -extern const q31_t twiddleCoef_1024_q31[1536]; -extern const q31_t twiddleCoef_2048_q31[3072]; -extern const q31_t twiddleCoef_4096_q31[6144]; -extern const q15_t twiddleCoef_16_q15[24]; -extern const q15_t twiddleCoef_32_q15[48]; -extern const q15_t twiddleCoef_64_q15[96]; -extern const q15_t twiddleCoef_128_q15[192]; -extern const q15_t twiddleCoef_256_q15[384]; -extern const q15_t twiddleCoef_512_q15[768]; -extern const q15_t twiddleCoef_1024_q15[1536]; -extern const q15_t twiddleCoef_2048_q15[3072]; -extern const q15_t twiddleCoef_4096_q15[6144]; -extern const float32_t twiddleCoef_rfft_32[32]; -extern const float32_t twiddleCoef_rfft_64[64]; -extern const float32_t twiddleCoef_rfft_128[128]; -extern const float32_t twiddleCoef_rfft_256[256]; -extern const float32_t twiddleCoef_rfft_512[512]; -extern const float32_t twiddleCoef_rfft_1024[1024]; -extern const float32_t twiddleCoef_rfft_2048[2048]; -extern const float32_t twiddleCoef_rfft_4096[4096]; - - -/* floating-point bit reversal tables */ -#define ARMBITREVINDEXTABLE__16_TABLE_LENGTH ((uint16_t)20 ) -#define ARMBITREVINDEXTABLE__32_TABLE_LENGTH ((uint16_t)48 ) -#define ARMBITREVINDEXTABLE__64_TABLE_LENGTH ((uint16_t)56 ) -#define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208 ) -#define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440 ) -#define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448 ) -#define ARMBITREVINDEXTABLE1024_TABLE_LENGTH ((uint16_t)1800) -#define ARMBITREVINDEXTABLE2048_TABLE_LENGTH ((uint16_t)3808) -#define ARMBITREVINDEXTABLE4096_TABLE_LENGTH ((uint16_t)4032) - -extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE__16_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE__32_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE__64_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE1024_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE2048_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE4096_TABLE_LENGTH]; - -/* fixed-point bit reversal tables */ -#define ARMBITREVINDEXTABLE_FIXED___16_TABLE_LENGTH ((uint16_t)12 ) -#define ARMBITREVINDEXTABLE_FIXED___32_TABLE_LENGTH ((uint16_t)24 ) -#define ARMBITREVINDEXTABLE_FIXED___64_TABLE_LENGTH ((uint16_t)56 ) -#define ARMBITREVINDEXTABLE_FIXED__128_TABLE_LENGTH ((uint16_t)112 ) -#define ARMBITREVINDEXTABLE_FIXED__256_TABLE_LENGTH ((uint16_t)240 ) -#define ARMBITREVINDEXTABLE_FIXED__512_TABLE_LENGTH ((uint16_t)480 ) -#define ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH ((uint16_t)992 ) -#define ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH ((uint16_t)1984) -#define ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH ((uint16_t)4032) - -extern const uint16_t armBitRevIndexTable_fixed_16[ARMBITREVINDEXTABLE_FIXED___16_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_32[ARMBITREVINDEXTABLE_FIXED___32_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_64[ARMBITREVINDEXTABLE_FIXED___64_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_128[ARMBITREVINDEXTABLE_FIXED__128_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_256[ARMBITREVINDEXTABLE_FIXED__256_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_512[ARMBITREVINDEXTABLE_FIXED__512_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_1024[ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_2048[ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_4096[ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH]; - -/* Tables for Fast Math Sine and Cosine */ -extern const float32_t sinTable_f32[FAST_MATH_TABLE_SIZE + 1]; -extern const q31_t sinTable_q31[FAST_MATH_TABLE_SIZE + 1]; -extern const q15_t sinTable_q15[FAST_MATH_TABLE_SIZE + 1]; - -#endif /* ARM_COMMON_TABLES_H */ diff --git a/body/board/inc/arm_const_structs.h b/body/board/inc/arm_const_structs.h deleted file mode 100644 index 726d06eb692f053..000000000000000 --- a/body/board/inc/arm_const_structs.h +++ /dev/null @@ -1,79 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010-2014 ARM Limited. All rights reserved. -* -* $Date: 19. March 2015 -* $Revision: V.1.4.5 -* -* Project: CMSIS DSP Library -* Title: arm_const_structs.h -* -* Description: This file has constant structs that are initialized for -* user convenience. For example, some can be given as -* arguments to the arm_cfft_f32() function. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* - Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* - 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. -* - Neither the name of ARM LIMITED 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 OWNER 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. -* -------------------------------------------------------------------- */ - -#ifndef _ARM_CONST_STRUCTS_H -#define _ARM_CONST_STRUCTS_H - -#include "arm_math.h" -#include "arm_common_tables.h" - - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096; - - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len16; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len32; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len64; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len128; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len256; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len512; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len1024; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len2048; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len4096; - - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len16; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len32; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len64; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len128; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len256; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len512; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len1024; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096; - -#endif diff --git a/body/board/inc/arm_math.h b/body/board/inc/arm_math.h deleted file mode 100644 index d33f8a9b3b57f9b..000000000000000 --- a/body/board/inc/arm_math.h +++ /dev/null @@ -1,7154 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010-2015 ARM Limited. All rights reserved. -* -* $Date: 20. October 2015 -* $Revision: V1.4.5 b -* -* Project: CMSIS DSP Library -* Title: arm_math.h -* -* Description: Public header file for CMSIS DSP Library -* -* Target Processor: Cortex-M7/Cortex-M4/Cortex-M3/Cortex-M0 -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* - Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* - 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. -* - Neither the name of ARM LIMITED 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 OWNER 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. - * -------------------------------------------------------------------- */ - -/** - \mainpage CMSIS DSP Software Library - * - * Introduction - * ------------ - * - * This user manual describes the CMSIS DSP software library, - * a suite of common signal processing functions for use on Cortex-M processor based devices. - * - * The library is divided into a number of functions each covering a specific category: - * - Basic math functions - * - Fast math functions - * - Complex math functions - * - Filters - * - Matrix functions - * - Transforms - * - Motor control functions - * - Statistical functions - * - Support functions - * - Interpolation functions - * - * The library has separate functions for operating on 8-bit integers, 16-bit integers, - * 32-bit integer and 32-bit floating-point values. - * - * Using the Library - * ------------ - * - * The library installer contains prebuilt versions of the libraries in the Lib folder. - * - arm_cortexM7lfdp_math.lib (Little endian and Double Precision Floating Point Unit on Cortex-M7) - * - arm_cortexM7bfdp_math.lib (Big endian and Double Precision Floating Point Unit on Cortex-M7) - * - arm_cortexM7lfsp_math.lib (Little endian and Single Precision Floating Point Unit on Cortex-M7) - * - arm_cortexM7bfsp_math.lib (Big endian and Single Precision Floating Point Unit on Cortex-M7) - * - arm_cortexM7l_math.lib (Little endian on Cortex-M7) - * - arm_cortexM7b_math.lib (Big endian on Cortex-M7) - * - arm_cortexM4lf_math.lib (Little endian and Floating Point Unit on Cortex-M4) - * - arm_cortexM4bf_math.lib (Big endian and Floating Point Unit on Cortex-M4) - * - arm_cortexM4l_math.lib (Little endian on Cortex-M4) - * - arm_cortexM4b_math.lib (Big endian on Cortex-M4) - * - arm_cortexM3l_math.lib (Little endian on Cortex-M3) - * - arm_cortexM3b_math.lib (Big endian on Cortex-M3) - * - arm_cortexM0l_math.lib (Little endian on Cortex-M0 / CortexM0+) - * - arm_cortexM0b_math.lib (Big endian on Cortex-M0 / CortexM0+) - * - * The library functions are declared in the public file arm_math.h which is placed in the Include folder. - * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single - * public header file arm_math.h for Cortex-M7/M4/M3/M0/M0+ with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. - * Define the appropriate pre processor MACRO ARM_MATH_CM7 or ARM_MATH_CM4 or ARM_MATH_CM3 or - * ARM_MATH_CM0 or ARM_MATH_CM0PLUS depending on the target processor in the application. - * - * Examples - * -------- - * - * The library ships with a number of examples which demonstrate how to use the library functions. - * - * Toolchain Support - * ------------ - * - * The library has been developed and tested with MDK-ARM version 5.14.0.0 - * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly. - * - * Building the Library - * ------------ - * - * The library installer contains a project file to re build libraries on MDK-ARM Tool chain in the CMSIS\\DSP_Lib\\Source\\ARM folder. - * - arm_cortexM_math.uvprojx - * - * - * The libraries can be built by opening the arm_cortexM_math.uvprojx project in MDK-ARM, selecting a specific target, and defining the optional pre processor MACROs detailed above. - * - * Pre-processor Macros - * ------------ - * - * Each library project have differant pre-processor macros. - * - * - UNALIGNED_SUPPORT_DISABLE: - * - * Define macro UNALIGNED_SUPPORT_DISABLE, If the silicon does not support unaligned memory access - * - * - ARM_MATH_BIG_ENDIAN: - * - * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets. - * - * - ARM_MATH_MATRIX_CHECK: - * - * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices - * - * - ARM_MATH_ROUNDING: - * - * Define macro ARM_MATH_ROUNDING for rounding on support functions - * - * - ARM_MATH_CMx: - * - * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target - * and ARM_MATH_CM0 for building library on Cortex-M0 target, ARM_MATH_CM0PLUS for building library on Cortex-M0+ target, and - * ARM_MATH_CM7 for building the library on cortex-M7. - * - * - __FPU_PRESENT: - * - * Initialize macro __FPU_PRESENT = 1 when building on FPU supported Targets. Enable this macro for M4bf and M4lf libraries - * - *
- * CMSIS-DSP in ARM::CMSIS Pack - * ----------------------------- - * - * The following files relevant to CMSIS-DSP are present in the ARM::CMSIS Pack directories: - * |File/Folder |Content | - * |------------------------------|------------------------------------------------------------------------| - * |\b CMSIS\\Documentation\\DSP | This documentation | - * |\b CMSIS\\DSP_Lib | Software license agreement (license.txt) | - * |\b CMSIS\\DSP_Lib\\Examples | Example projects demonstrating the usage of the library functions | - * |\b CMSIS\\DSP_Lib\\Source | Source files for rebuilding the library | - * - *
- * Revision History of CMSIS-DSP - * ------------ - * Please refer to \ref ChangeLog_pg. - * - * Copyright Notice - * ------------ - * - * Copyright (C) 2010-2015 ARM Limited. All rights reserved. - */ - - -/** - * @defgroup groupMath Basic Math Functions - */ - -/** - * @defgroup groupFastMath Fast Math Functions - * This set of functions provides a fast approximation to sine, cosine, and square root. - * As compared to most of the other functions in the CMSIS math library, the fast math functions - * operate on individual values and not arrays. - * There are separate functions for Q15, Q31, and floating-point data. - * - */ - -/** - * @defgroup groupCmplxMath Complex Math Functions - * This set of functions operates on complex data vectors. - * The data in the complex arrays is stored in an interleaved fashion - * (real, imag, real, imag, ...). - * In the API functions, the number of samples in a complex array refers - * to the number of complex values; the array contains twice this number of - * real values. - */ - -/** - * @defgroup groupFilters Filtering Functions - */ - -/** - * @defgroup groupMatrix Matrix Functions - * - * This set of functions provides basic matrix math operations. - * The functions operate on matrix data structures. For example, - * the type - * definition for the floating-point matrix structure is shown - * below: - *
- *     typedef struct
- *     {
- *       uint16_t numRows;     // number of rows of the matrix.
- *       uint16_t numCols;     // number of columns of the matrix.
- *       float32_t *pData;     // points to the data of the matrix.
- *     } arm_matrix_instance_f32;
- * 
- * There are similar definitions for Q15 and Q31 data types. - * - * The structure specifies the size of the matrix and then points to - * an array of data. The array is of size numRows X numCols - * and the values are arranged in row order. That is, the - * matrix element (i, j) is stored at: - *
- *     pData[i*numCols + j]
- * 
- * - * \par Init Functions - * There is an associated initialization function for each type of matrix - * data structure. - * The initialization function sets the values of the internal structure fields. - * Refer to the function arm_mat_init_f32(), arm_mat_init_q31() - * and arm_mat_init_q15() for floating-point, Q31 and Q15 types, respectively. - * - * \par - * Use of the initialization function is optional. However, if initialization function is used - * then the instance structure cannot be placed into a const data section. - * To place the instance structure in a const data - * section, manually initialize the data structure. For example: - *
- * arm_matrix_instance_f32 S = {nRows, nColumns, pData};
- * arm_matrix_instance_q31 S = {nRows, nColumns, pData};
- * arm_matrix_instance_q15 S = {nRows, nColumns, pData};
- * 
- * where nRows specifies the number of rows, nColumns - * specifies the number of columns, and pData points to the - * data array. - * - * \par Size Checking - * By default all of the matrix functions perform size checking on the input and - * output matrices. For example, the matrix addition function verifies that the - * two input matrices and the output matrix all have the same number of rows and - * columns. If the size check fails the functions return: - *
- *     ARM_MATH_SIZE_MISMATCH
- * 
- * Otherwise the functions return - *
- *     ARM_MATH_SUCCESS
- * 
- * There is some overhead associated with this matrix size checking. - * The matrix size checking is enabled via the \#define - *
- *     ARM_MATH_MATRIX_CHECK
- * 
- * within the library project settings. By default this macro is defined - * and size checking is enabled. By changing the project settings and - * undefining this macro size checking is eliminated and the functions - * run a bit faster. With size checking disabled the functions always - * return ARM_MATH_SUCCESS. - */ - -/** - * @defgroup groupTransforms Transform Functions - */ - -/** - * @defgroup groupController Controller Functions - */ - -/** - * @defgroup groupStats Statistics Functions - */ -/** - * @defgroup groupSupport Support Functions - */ - -/** - * @defgroup groupInterpolation Interpolation Functions - * These functions perform 1- and 2-dimensional interpolation of data. - * Linear interpolation is used for 1-dimensional data and - * bilinear interpolation is used for 2-dimensional data. - */ - -/** - * @defgroup groupExamples Examples - */ -#ifndef _ARM_MATH_H -#define _ARM_MATH_H - -/* ignore some GCC warnings */ -#if defined ( __GNUC__ ) -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" -#endif - -#define __CMSIS_GENERIC /* disable NVIC and Systick functions */ - -#if defined(ARM_MATH_CM7) - #include "core_cm7.h" -#elif defined (ARM_MATH_CM4) - #include "core_cm4.h" -#elif defined (ARM_MATH_CM3) - #include "core_cm3.h" -#elif defined (ARM_MATH_CM0) - #include "core_cm0.h" - #define ARM_MATH_CM0_FAMILY -#elif defined (ARM_MATH_CM0PLUS) - #include "core_cm0plus.h" - #define ARM_MATH_CM0_FAMILY -#else - #error "Define according the used Cortex core ARM_MATH_CM7, ARM_MATH_CM4, ARM_MATH_CM3, ARM_MATH_CM0PLUS or ARM_MATH_CM0" -#endif - -#undef __CMSIS_GENERIC /* enable NVIC and Systick functions */ -#include "string.h" -#include "math.h" -#ifdef __cplusplus -extern "C" -{ -#endif - - - /** - * @brief Macros required for reciprocal calculation in Normalized LMS - */ - -#define DELTA_Q31 (0x100) -#define DELTA_Q15 0x5 -#define INDEX_MASK 0x0000003F -#ifndef PI -#define PI 3.14159265358979f -#endif - - /** - * @brief Macros required for SINE and COSINE Fast math approximations - */ - -#define FAST_MATH_TABLE_SIZE 512 -#define FAST_MATH_Q31_SHIFT (32 - 10) -#define FAST_MATH_Q15_SHIFT (16 - 10) -#define CONTROLLER_Q31_SHIFT (32 - 9) -#define TABLE_SIZE 256 -#define TABLE_SPACING_Q31 0x400000 -#define TABLE_SPACING_Q15 0x80 - - /** - * @brief Macros required for SINE and COSINE Controller functions - */ - /* 1.31(q31) Fixed value of 2/360 */ - /* -1 to +1 is divided into 360 values so total spacing is (2/360) */ -#define INPUT_SPACING 0xB60B61 - - /** - * @brief Macro for Unaligned Support - */ -#ifndef UNALIGNED_SUPPORT_DISABLE - #define ALIGN4 -#else - #if defined (__GNUC__) - #define ALIGN4 __attribute__((aligned(4))) - #else - #define ALIGN4 __align(4) - #endif -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /** - * @brief Error status returned by some functions in the library. - */ - - typedef enum - { - ARM_MATH_SUCCESS = 0, /**< No error */ - ARM_MATH_ARGUMENT_ERROR = -1, /**< One or more arguments are incorrect */ - ARM_MATH_LENGTH_ERROR = -2, /**< Length of data buffer is incorrect */ - ARM_MATH_SIZE_MISMATCH = -3, /**< Size of matrices is not compatible with the operation. */ - ARM_MATH_NANINF = -4, /**< Not-a-number (NaN) or infinity is generated */ - ARM_MATH_SINGULAR = -5, /**< Generated by matrix inversion if the input matrix is singular and cannot be inverted. */ - ARM_MATH_TEST_FAILURE = -6 /**< Test Failed */ - } arm_status; - - /** - * @brief 8-bit fractional data type in 1.7 format. - */ - typedef int8_t q7_t; - - /** - * @brief 16-bit fractional data type in 1.15 format. - */ - typedef int16_t q15_t; - - /** - * @brief 32-bit fractional data type in 1.31 format. - */ - typedef int32_t q31_t; - - /** - * @brief 64-bit fractional data type in 1.63 format. - */ - typedef int64_t q63_t; - - /** - * @brief 32-bit floating-point type definition. - */ - typedef float float32_t; - - /** - * @brief 64-bit floating-point type definition. - */ - typedef double float64_t; - - /** - * @brief definition to read/write two 16 bit values. - */ -#if defined __CC_ARM - #define __SIMD32_TYPE int32_t __packed - #define CMSIS_UNUSED __attribute__((unused)) - -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #define __SIMD32_TYPE int32_t - #define CMSIS_UNUSED __attribute__((unused)) - -#elif defined __GNUC__ - #define __SIMD32_TYPE int32_t - #define CMSIS_UNUSED __attribute__((unused)) - -#elif defined __ICCARM__ - #define __SIMD32_TYPE int32_t __packed - #define CMSIS_UNUSED - -#elif defined __CSMC__ - #define __SIMD32_TYPE int32_t - #define CMSIS_UNUSED - -#elif defined __TASKING__ - #define __SIMD32_TYPE __unaligned int32_t - #define CMSIS_UNUSED - -#else - #error Unknown compiler -#endif - -#define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr)) -#define __SIMD32_CONST(addr) ((__SIMD32_TYPE *)(addr)) -#define _SIMD32_OFFSET(addr) (*(__SIMD32_TYPE *) (addr)) -#define __SIMD64(addr) (*(int64_t **) & (addr)) - -#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) - /** - * @brief definition to pack two 16 bit values. - */ -#define __PKHBT(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0x0000FFFF) | \ - (((int32_t)(ARG2) << ARG3) & (int32_t)0xFFFF0000) ) -#define __PKHTB(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0xFFFF0000) | \ - (((int32_t)(ARG2) >> ARG3) & (int32_t)0x0000FFFF) ) - -#endif - - - /** - * @brief definition to pack four 8 bit values. - */ -#ifndef ARM_MATH_BIG_ENDIAN - -#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v0) << 0) & (int32_t)0x000000FF) | \ - (((int32_t)(v1) << 8) & (int32_t)0x0000FF00) | \ - (((int32_t)(v2) << 16) & (int32_t)0x00FF0000) | \ - (((int32_t)(v3) << 24) & (int32_t)0xFF000000) ) -#else - -#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v3) << 0) & (int32_t)0x000000FF) | \ - (((int32_t)(v2) << 8) & (int32_t)0x0000FF00) | \ - (((int32_t)(v1) << 16) & (int32_t)0x00FF0000) | \ - (((int32_t)(v0) << 24) & (int32_t)0xFF000000) ) - -#endif - - - /** - * @brief Clips Q63 to Q31 values. - */ - static __INLINE q31_t clip_q63_to_q31( - q63_t x) - { - return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? - ((0x7FFFFFFF ^ ((q31_t) (x >> 63)))) : (q31_t) x; - } - - /** - * @brief Clips Q63 to Q15 values. - */ - static __INLINE q15_t clip_q63_to_q15( - q63_t x) - { - return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? - ((0x7FFF ^ ((q15_t) (x >> 63)))) : (q15_t) (x >> 15); - } - - /** - * @brief Clips Q31 to Q7 values. - */ - static __INLINE q7_t clip_q31_to_q7( - q31_t x) - { - return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ? - ((0x7F ^ ((q7_t) (x >> 31)))) : (q7_t) x; - } - - /** - * @brief Clips Q31 to Q15 values. - */ - static __INLINE q15_t clip_q31_to_q15( - q31_t x) - { - return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ? - ((0x7FFF ^ ((q15_t) (x >> 31)))) : (q15_t) x; - } - - /** - * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format. - */ - - static __INLINE q63_t mult32x64( - q63_t x, - q31_t y) - { - return ((((q63_t) (x & 0x00000000FFFFFFFF) * y) >> 32) + - (((q63_t) (x >> 32) * y))); - } - -/* - #if defined (ARM_MATH_CM0_FAMILY) && defined ( __CC_ARM ) - #define __CLZ __clz - #endif - */ -/* note: function can be removed when all toolchain support __CLZ for Cortex-M0 */ -#if defined (ARM_MATH_CM0_FAMILY) && ((defined (__ICCARM__)) ) - static __INLINE uint32_t __CLZ( - q31_t data); - - static __INLINE uint32_t __CLZ( - q31_t data) - { - uint32_t count = 0; - uint32_t mask = 0x80000000; - - while((data & mask) == 0) - { - count += 1u; - mask = mask >> 1u; - } - - return (count); - } -#endif - - /** - * @brief Function to Calculates 1/in (reciprocal) value of Q31 Data type. - */ - - static __INLINE uint32_t arm_recip_q31( - q31_t in, - q31_t * dst, - q31_t * pRecipTable) - { - q31_t out; - uint32_t tempVal; - uint32_t index, i; - uint32_t signBits; - - if(in > 0) - { - signBits = ((uint32_t) (__CLZ( in) - 1)); - } - else - { - signBits = ((uint32_t) (__CLZ(-in) - 1)); - } - - /* Convert input sample to 1.31 format */ - in = (in << signBits); - - /* calculation of index for initial approximated Val */ - index = (uint32_t)(in >> 24); - index = (index & INDEX_MASK); - - /* 1.31 with exp 1 */ - out = pRecipTable[index]; - - /* calculation of reciprocal value */ - /* running approximation for two iterations */ - for (i = 0u; i < 2u; i++) - { - tempVal = (uint32_t) (((q63_t) in * out) >> 31); - tempVal = 0x7FFFFFFFu - tempVal; - /* 1.31 with exp 1 */ - /* out = (q31_t) (((q63_t) out * tempVal) >> 30); */ - out = clip_q63_to_q31(((q63_t) out * tempVal) >> 30); - } - - /* write output */ - *dst = out; - - /* return num of signbits of out = 1/in value */ - return (signBits + 1u); - } - - - /** - * @brief Function to Calculates 1/in (reciprocal) value of Q15 Data type. - */ - static __INLINE uint32_t arm_recip_q15( - q15_t in, - q15_t * dst, - q15_t * pRecipTable) - { - q15_t out = 0; - uint32_t tempVal = 0; - uint32_t index = 0, i = 0; - uint32_t signBits = 0; - - if(in > 0) - { - signBits = ((uint32_t)(__CLZ( in) - 17)); - } - else - { - signBits = ((uint32_t)(__CLZ(-in) - 17)); - } - - /* Convert input sample to 1.15 format */ - in = (in << signBits); - - /* calculation of index for initial approximated Val */ - index = (uint32_t)(in >> 8); - index = (index & INDEX_MASK); - - /* 1.15 with exp 1 */ - out = pRecipTable[index]; - - /* calculation of reciprocal value */ - /* running approximation for two iterations */ - for (i = 0u; i < 2u; i++) - { - tempVal = (uint32_t) (((q31_t) in * out) >> 15); - tempVal = 0x7FFFu - tempVal; - /* 1.15 with exp 1 */ - out = (q15_t) (((q31_t) out * tempVal) >> 14); - /* out = clip_q31_to_q15(((q31_t) out * tempVal) >> 14); */ - } - - /* write output */ - *dst = out; - - /* return num of signbits of out = 1/in value */ - return (signBits + 1); - } - - - /* - * @brief C custom defined intrinisic function for only M0 processors - */ -#if defined(ARM_MATH_CM0_FAMILY) - static __INLINE q31_t __SSAT( - q31_t x, - uint32_t y) - { - int32_t posMax, negMin; - uint32_t i; - - posMax = 1; - for (i = 0; i < (y - 1); i++) - { - posMax = posMax * 2; - } - - if(x > 0) - { - posMax = (posMax - 1); - - if(x > posMax) - { - x = posMax; - } - } - else - { - negMin = -posMax; - - if(x < negMin) - { - x = negMin; - } - } - return (x); - } -#endif /* end of ARM_MATH_CM0_FAMILY */ - - - /* - * @brief C custom defined intrinsic function for M3 and M0 processors - */ -#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) - - /* - * @brief C custom defined QADD8 for M3 and M0 processors - */ - static __INLINE uint32_t __QADD8( - uint32_t x, - uint32_t y) - { - q31_t r, s, t, u; - - r = __SSAT(((((q31_t)x << 24) >> 24) + (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF; - s = __SSAT(((((q31_t)x << 16) >> 24) + (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF; - t = __SSAT(((((q31_t)x << 8) >> 24) + (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF; - u = __SSAT(((((q31_t)x ) >> 24) + (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF; - - return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r ))); - } - - - /* - * @brief C custom defined QSUB8 for M3 and M0 processors - */ - static __INLINE uint32_t __QSUB8( - uint32_t x, - uint32_t y) - { - q31_t r, s, t, u; - - r = __SSAT(((((q31_t)x << 24) >> 24) - (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF; - s = __SSAT(((((q31_t)x << 16) >> 24) - (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF; - t = __SSAT(((((q31_t)x << 8) >> 24) - (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF; - u = __SSAT(((((q31_t)x ) >> 24) - (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF; - - return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r ))); - } - - - /* - * @brief C custom defined QADD16 for M3 and M0 processors - */ - static __INLINE uint32_t __QADD16( - uint32_t x, - uint32_t y) - { -/* q31_t r, s; without initialisation 'arm_offset_q15 test' fails but 'intrinsic' tests pass! for armCC */ - q31_t r = 0, s = 0; - - r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; - s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SHADD16 for M3 and M0 processors - */ - static __INLINE uint32_t __SHADD16( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = (((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; - s = (((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined QSUB16 for M3 and M0 processors - */ - static __INLINE uint32_t __QSUB16( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; - s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SHSUB16 for M3 and M0 processors - */ - static __INLINE uint32_t __SHSUB16( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = (((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; - s = (((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined QASX for M3 and M0 processors - */ - static __INLINE uint32_t __QASX( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; - s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SHASX for M3 and M0 processors - */ - static __INLINE uint32_t __SHASX( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = (((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; - s = (((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined QSAX for M3 and M0 processors - */ - static __INLINE uint32_t __QSAX( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; - s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SHSAX for M3 and M0 processors - */ - static __INLINE uint32_t __SHSAX( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = (((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; - s = (((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SMUSDX for M3 and M0 processors - */ - static __INLINE uint32_t __SMUSDX( - uint32_t x, - uint32_t y) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) - - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) )); - } - - /* - * @brief C custom defined SMUADX for M3 and M0 processors - */ - static __INLINE uint32_t __SMUADX( - uint32_t x, - uint32_t y) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) )); - } - - - /* - * @brief C custom defined QADD for M3 and M0 processors - */ - static __INLINE int32_t __QADD( - int32_t x, - int32_t y) - { - return ((int32_t)(clip_q63_to_q31((q63_t)x + (q31_t)y))); - } - - - /* - * @brief C custom defined QSUB for M3 and M0 processors - */ - static __INLINE int32_t __QSUB( - int32_t x, - int32_t y) - { - return ((int32_t)(clip_q63_to_q31((q63_t)x - (q31_t)y))); - } - - - /* - * @brief C custom defined SMLAD for M3 and M0 processors - */ - static __INLINE uint32_t __SMLAD( - uint32_t x, - uint32_t y, - uint32_t sum) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) + - ( ((q31_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMLADX for M3 and M0 processors - */ - static __INLINE uint32_t __SMLADX( - uint32_t x, - uint32_t y, - uint32_t sum) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + - ( ((q31_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMLSDX for M3 and M0 processors - */ - static __INLINE uint32_t __SMLSDX( - uint32_t x, - uint32_t y, - uint32_t sum) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) - - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + - ( ((q31_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMLALD for M3 and M0 processors - */ - static __INLINE uint64_t __SMLALD( - uint32_t x, - uint32_t y, - uint64_t sum) - { -/* return (sum + ((q15_t) (x >> 16) * (q15_t) (y >> 16)) + ((q15_t) x * (q15_t) y)); */ - return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) + - ( ((q63_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMLALDX for M3 and M0 processors - */ - static __INLINE uint64_t __SMLALDX( - uint32_t x, - uint32_t y, - uint64_t sum) - { -/* return (sum + ((q15_t) (x >> 16) * (q15_t) y)) + ((q15_t) x * (q15_t) (y >> 16)); */ - return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + - ( ((q63_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMUAD for M3 and M0 processors - */ - static __INLINE uint32_t __SMUAD( - uint32_t x, - uint32_t y) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) )); - } - - - /* - * @brief C custom defined SMUSD for M3 and M0 processors - */ - static __INLINE uint32_t __SMUSD( - uint32_t x, - uint32_t y) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) - - ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) )); - } - - - /* - * @brief C custom defined SXTB16 for M3 and M0 processors - */ - static __INLINE uint32_t __SXTB16( - uint32_t x) - { - return ((uint32_t)(((((q31_t)x << 24) >> 24) & (q31_t)0x0000FFFF) | - ((((q31_t)x << 8) >> 8) & (q31_t)0xFFFF0000) )); - } - -#endif /* defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) */ - - - /** - * @brief Instance structure for the Q7 FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of filter coefficients in the filter. */ - q7_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - } arm_fir_instance_q7; - - /** - * @brief Instance structure for the Q15 FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of filter coefficients in the filter. */ - q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - } arm_fir_instance_q15; - - /** - * @brief Instance structure for the Q31 FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of filter coefficients in the filter. */ - q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - } arm_fir_instance_q31; - - /** - * @brief Instance structure for the floating-point FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of filter coefficients in the filter. */ - float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - } arm_fir_instance_f32; - - - /** - * @brief Processing function for the Q7 FIR filter. - * @param[in] S points to an instance of the Q7 FIR filter structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_q7( - const arm_fir_instance_q7 * S, - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q7 FIR filter. - * @param[in,out] S points to an instance of the Q7 FIR structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of samples that are processed. - */ - void arm_fir_init_q7( - arm_fir_instance_q7 * S, - uint16_t numTaps, - q7_t * pCoeffs, - q7_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 FIR filter. - * @param[in] S points to an instance of the Q15 FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the fast Q15 FIR filter for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q15 FIR filter structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_fast_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 FIR filter. - * @param[in,out] S points to an instance of the Q15 FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of samples that are processed at a time. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_ARGUMENT_ERROR if - * numTaps is not a supported value. - */ - arm_status arm_fir_init_q15( - arm_fir_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 FIR filter. - * @param[in] S points to an instance of the Q31 FIR filter structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_q31( - const arm_fir_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the fast Q31 FIR filter for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q31 FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_fast_q31( - const arm_fir_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 FIR filter. - * @param[in,out] S points to an instance of the Q31 FIR structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of samples that are processed at a time. - */ - void arm_fir_init_q31( - arm_fir_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the floating-point FIR filter. - * @param[in] S points to an instance of the floating-point FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_f32( - const arm_fir_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point FIR filter. - * @param[in,out] S points to an instance of the floating-point FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of samples that are processed at a time. - */ - void arm_fir_init_f32( - arm_fir_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 Biquad cascade filter. - */ - typedef struct - { - int8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - q15_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ - q15_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ - int8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ - } arm_biquad_casd_df1_inst_q15; - - /** - * @brief Instance structure for the Q31 Biquad cascade filter. - */ - typedef struct - { - uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - q31_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ - q31_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ - uint8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ - } arm_biquad_casd_df1_inst_q31; - - /** - * @brief Instance structure for the floating-point Biquad cascade filter. - */ - typedef struct - { - uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - float32_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ - float32_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ - } arm_biquad_casd_df1_inst_f32; - - - /** - * @brief Processing function for the Q15 Biquad cascade filter. - * @param[in] S points to an instance of the Q15 Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_q15( - const arm_biquad_casd_df1_inst_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 Biquad cascade filter. - * @param[in,out] S points to an instance of the Q15 Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format - */ - void arm_biquad_cascade_df1_init_q15( - arm_biquad_casd_df1_inst_q15 * S, - uint8_t numStages, - q15_t * pCoeffs, - q15_t * pState, - int8_t postShift); - - - /** - * @brief Fast but less precise processing function for the Q15 Biquad cascade filter for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q15 Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_fast_q15( - const arm_biquad_casd_df1_inst_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 Biquad cascade filter - * @param[in] S points to an instance of the Q31 Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_q31( - const arm_biquad_casd_df1_inst_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fast but less precise processing function for the Q31 Biquad cascade filter for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q31 Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_fast_q31( - const arm_biquad_casd_df1_inst_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 Biquad cascade filter. - * @param[in,out] S points to an instance of the Q31 Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format - */ - void arm_biquad_cascade_df1_init_q31( - arm_biquad_casd_df1_inst_q31 * S, - uint8_t numStages, - q31_t * pCoeffs, - q31_t * pState, - int8_t postShift); - - - /** - * @brief Processing function for the floating-point Biquad cascade filter. - * @param[in] S points to an instance of the floating-point Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_f32( - const arm_biquad_casd_df1_inst_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point Biquad cascade filter. - * @param[in,out] S points to an instance of the floating-point Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - */ - void arm_biquad_cascade_df1_init_f32( - arm_biquad_casd_df1_inst_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState); - - - /** - * @brief Instance structure for the floating-point matrix structure. - */ - typedef struct - { - uint16_t numRows; /**< number of rows of the matrix. */ - uint16_t numCols; /**< number of columns of the matrix. */ - float32_t *pData; /**< points to the data of the matrix. */ - } arm_matrix_instance_f32; - - - /** - * @brief Instance structure for the floating-point matrix structure. - */ - typedef struct - { - uint16_t numRows; /**< number of rows of the matrix. */ - uint16_t numCols; /**< number of columns of the matrix. */ - float64_t *pData; /**< points to the data of the matrix. */ - } arm_matrix_instance_f64; - - /** - * @brief Instance structure for the Q15 matrix structure. - */ - typedef struct - { - uint16_t numRows; /**< number of rows of the matrix. */ - uint16_t numCols; /**< number of columns of the matrix. */ - q15_t *pData; /**< points to the data of the matrix. */ - } arm_matrix_instance_q15; - - /** - * @brief Instance structure for the Q31 matrix structure. - */ - typedef struct - { - uint16_t numRows; /**< number of rows of the matrix. */ - uint16_t numCols; /**< number of columns of the matrix. */ - q31_t *pData; /**< points to the data of the matrix. */ - } arm_matrix_instance_q31; - - - /** - * @brief Floating-point matrix addition. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_add_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix addition. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_add_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst); - - - /** - * @brief Q31 matrix addition. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_add_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point, complex, matrix multiplication. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_cmplx_mult_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15, complex, matrix multiplication. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_cmplx_mult_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pScratch); - - - /** - * @brief Q31, complex, matrix multiplication. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_cmplx_mult_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point matrix transpose. - * @param[in] pSrc points to the input matrix - * @param[out] pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_trans_f32( - const arm_matrix_instance_f32 * pSrc, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix transpose. - * @param[in] pSrc points to the input matrix - * @param[out] pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_trans_q15( - const arm_matrix_instance_q15 * pSrc, - arm_matrix_instance_q15 * pDst); - - - /** - * @brief Q31 matrix transpose. - * @param[in] pSrc points to the input matrix - * @param[out] pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_trans_q31( - const arm_matrix_instance_q31 * pSrc, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point matrix multiplication - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix multiplication - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @param[in] pState points to the array for storing intermediate results - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pState); - - - /** - * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @param[in] pState points to the array for storing intermediate results - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_fast_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pState); - - - /** - * @brief Q31 matrix multiplication - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_fast_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point matrix subtraction - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_sub_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix subtraction - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_sub_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst); - - - /** - * @brief Q31 matrix subtraction - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_sub_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point matrix scaling. - * @param[in] pSrc points to the input matrix - * @param[in] scale scale factor - * @param[out] pDst points to the output matrix - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_scale_f32( - const arm_matrix_instance_f32 * pSrc, - float32_t scale, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix scaling. - * @param[in] pSrc points to input matrix - * @param[in] scaleFract fractional portion of the scale factor - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to output matrix - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_scale_q15( - const arm_matrix_instance_q15 * pSrc, - q15_t scaleFract, - int32_t shift, - arm_matrix_instance_q15 * pDst); - - - /** - * @brief Q31 matrix scaling. - * @param[in] pSrc points to input matrix - * @param[in] scaleFract fractional portion of the scale factor - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_scale_q31( - const arm_matrix_instance_q31 * pSrc, - q31_t scaleFract, - int32_t shift, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Q31 matrix initialization. - * @param[in,out] S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] pData points to the matrix data array. - */ - void arm_mat_init_q31( - arm_matrix_instance_q31 * S, - uint16_t nRows, - uint16_t nColumns, - q31_t * pData); - - - /** - * @brief Q15 matrix initialization. - * @param[in,out] S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] pData points to the matrix data array. - */ - void arm_mat_init_q15( - arm_matrix_instance_q15 * S, - uint16_t nRows, - uint16_t nColumns, - q15_t * pData); - - - /** - * @brief Floating-point matrix initialization. - * @param[in,out] S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] pData points to the matrix data array. - */ - void arm_mat_init_f32( - arm_matrix_instance_f32 * S, - uint16_t nRows, - uint16_t nColumns, - float32_t * pData); - - - - /** - * @brief Instance structure for the Q15 PID Control. - */ - typedef struct - { - q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ -#ifdef ARM_MATH_CM0_FAMILY - q15_t A1; - q15_t A2; -#else - q31_t A1; /**< The derived gain A1 = -Kp - 2Kd | Kd.*/ -#endif - q15_t state[3]; /**< The state array of length 3. */ - q15_t Kp; /**< The proportional gain. */ - q15_t Ki; /**< The integral gain. */ - q15_t Kd; /**< The derivative gain. */ - } arm_pid_instance_q15; - - /** - * @brief Instance structure for the Q31 PID Control. - */ - typedef struct - { - q31_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ - q31_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ - q31_t A2; /**< The derived gain, A2 = Kd . */ - q31_t state[3]; /**< The state array of length 3. */ - q31_t Kp; /**< The proportional gain. */ - q31_t Ki; /**< The integral gain. */ - q31_t Kd; /**< The derivative gain. */ - } arm_pid_instance_q31; - - /** - * @brief Instance structure for the floating-point PID Control. - */ - typedef struct - { - float32_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ - float32_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ - float32_t A2; /**< The derived gain, A2 = Kd . */ - float32_t state[3]; /**< The state array of length 3. */ - float32_t Kp; /**< The proportional gain. */ - float32_t Ki; /**< The integral gain. */ - float32_t Kd; /**< The derivative gain. */ - } arm_pid_instance_f32; - - - - /** - * @brief Initialization function for the floating-point PID Control. - * @param[in,out] S points to an instance of the PID structure. - * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. - */ - void arm_pid_init_f32( - arm_pid_instance_f32 * S, - int32_t resetStateFlag); - - - /** - * @brief Reset function for the floating-point PID Control. - * @param[in,out] S is an instance of the floating-point PID Control structure - */ - void arm_pid_reset_f32( - arm_pid_instance_f32 * S); - - - /** - * @brief Initialization function for the Q31 PID Control. - * @param[in,out] S points to an instance of the Q15 PID structure. - * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. - */ - void arm_pid_init_q31( - arm_pid_instance_q31 * S, - int32_t resetStateFlag); - - - /** - * @brief Reset function for the Q31 PID Control. - * @param[in,out] S points to an instance of the Q31 PID Control structure - */ - - void arm_pid_reset_q31( - arm_pid_instance_q31 * S); - - - /** - * @brief Initialization function for the Q15 PID Control. - * @param[in,out] S points to an instance of the Q15 PID structure. - * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. - */ - void arm_pid_init_q15( - arm_pid_instance_q15 * S, - int32_t resetStateFlag); - - - /** - * @brief Reset function for the Q15 PID Control. - * @param[in,out] S points to an instance of the q15 PID Control structure - */ - void arm_pid_reset_q15( - arm_pid_instance_q15 * S); - - - /** - * @brief Instance structure for the floating-point Linear Interpolate function. - */ - typedef struct - { - uint32_t nValues; /**< nValues */ - float32_t x1; /**< x1 */ - float32_t xSpacing; /**< xSpacing */ - float32_t *pYData; /**< pointer to the table of Y values */ - } arm_linear_interp_instance_f32; - - /** - * @brief Instance structure for the floating-point bilinear interpolation function. - */ - typedef struct - { - uint16_t numRows; /**< number of rows in the data table. */ - uint16_t numCols; /**< number of columns in the data table. */ - float32_t *pData; /**< points to the data table. */ - } arm_bilinear_interp_instance_f32; - - /** - * @brief Instance structure for the Q31 bilinear interpolation function. - */ - typedef struct - { - uint16_t numRows; /**< number of rows in the data table. */ - uint16_t numCols; /**< number of columns in the data table. */ - q31_t *pData; /**< points to the data table. */ - } arm_bilinear_interp_instance_q31; - - /** - * @brief Instance structure for the Q15 bilinear interpolation function. - */ - typedef struct - { - uint16_t numRows; /**< number of rows in the data table. */ - uint16_t numCols; /**< number of columns in the data table. */ - q15_t *pData; /**< points to the data table. */ - } arm_bilinear_interp_instance_q15; - - /** - * @brief Instance structure for the Q15 bilinear interpolation function. - */ - typedef struct - { - uint16_t numRows; /**< number of rows in the data table. */ - uint16_t numCols; /**< number of columns in the data table. */ - q7_t *pData; /**< points to the data table. */ - } arm_bilinear_interp_instance_q7; - - - /** - * @brief Q7 vector multiplication. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_mult_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q15 vector multiplication. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_mult_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q31 vector multiplication. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_mult_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Floating-point vector multiplication. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_mult_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q15_t *pTwiddle; /**< points to the Sin twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix2_instance_q15; - -/* Deprecated */ - arm_status arm_cfft_radix2_init_q15( - arm_cfft_radix2_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix2_q15( - const arm_cfft_radix2_instance_q15 * S, - q15_t * pSrc); - - - /** - * @brief Instance structure for the Q15 CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q15_t *pTwiddle; /**< points to the twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix4_instance_q15; - -/* Deprecated */ - arm_status arm_cfft_radix4_init_q15( - arm_cfft_radix4_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix4_q15( - const arm_cfft_radix4_instance_q15 * S, - q15_t * pSrc); - - /** - * @brief Instance structure for the Radix-2 Q31 CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q31_t *pTwiddle; /**< points to the Twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix2_instance_q31; - -/* Deprecated */ - arm_status arm_cfft_radix2_init_q31( - arm_cfft_radix2_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix2_q31( - const arm_cfft_radix2_instance_q31 * S, - q31_t * pSrc); - - /** - * @brief Instance structure for the Q31 CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q31_t *pTwiddle; /**< points to the twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix4_instance_q31; - -/* Deprecated */ - void arm_cfft_radix4_q31( - const arm_cfft_radix4_instance_q31 * S, - q31_t * pSrc); - -/* Deprecated */ - arm_status arm_cfft_radix4_init_q31( - arm_cfft_radix4_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Instance structure for the floating-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - float32_t *pTwiddle; /**< points to the Twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - float32_t onebyfftLen; /**< value of 1/fftLen. */ - } arm_cfft_radix2_instance_f32; - -/* Deprecated */ - arm_status arm_cfft_radix2_init_f32( - arm_cfft_radix2_instance_f32 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix2_f32( - const arm_cfft_radix2_instance_f32 * S, - float32_t * pSrc); - - /** - * @brief Instance structure for the floating-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - float32_t *pTwiddle; /**< points to the Twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - float32_t onebyfftLen; /**< value of 1/fftLen. */ - } arm_cfft_radix4_instance_f32; - -/* Deprecated */ - arm_status arm_cfft_radix4_init_f32( - arm_cfft_radix4_instance_f32 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix4_f32( - const arm_cfft_radix4_instance_f32 * S, - float32_t * pSrc); - - /** - * @brief Instance structure for the fixed-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - const q15_t *pTwiddle; /**< points to the Twiddle factor table. */ - const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t bitRevLength; /**< bit reversal table length. */ - } arm_cfft_instance_q15; - -void arm_cfft_q15( - const arm_cfft_instance_q15 * S, - q15_t * p1, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Instance structure for the fixed-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - const q31_t *pTwiddle; /**< points to the Twiddle factor table. */ - const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t bitRevLength; /**< bit reversal table length. */ - } arm_cfft_instance_q31; - -void arm_cfft_q31( - const arm_cfft_instance_q31 * S, - q31_t * p1, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Instance structure for the floating-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ - const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t bitRevLength; /**< bit reversal table length. */ - } arm_cfft_instance_f32; - - void arm_cfft_f32( - const arm_cfft_instance_f32 * S, - float32_t * p1, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Instance structure for the Q15 RFFT/RIFFT function. - */ - typedef struct - { - uint32_t fftLenReal; /**< length of the real FFT. */ - uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ - uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ - uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - q15_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ - q15_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ - const arm_cfft_instance_q15 *pCfft; /**< points to the complex FFT instance. */ - } arm_rfft_instance_q15; - - arm_status arm_rfft_init_q15( - arm_rfft_instance_q15 * S, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag); - - void arm_rfft_q15( - const arm_rfft_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst); - - /** - * @brief Instance structure for the Q31 RFFT/RIFFT function. - */ - typedef struct - { - uint32_t fftLenReal; /**< length of the real FFT. */ - uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ - uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ - uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - q31_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ - q31_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ - const arm_cfft_instance_q31 *pCfft; /**< points to the complex FFT instance. */ - } arm_rfft_instance_q31; - - arm_status arm_rfft_init_q31( - arm_rfft_instance_q31 * S, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag); - - void arm_rfft_q31( - const arm_rfft_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst); - - /** - * @brief Instance structure for the floating-point RFFT/RIFFT function. - */ - typedef struct - { - uint32_t fftLenReal; /**< length of the real FFT. */ - uint16_t fftLenBy2; /**< length of the complex FFT. */ - uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ - uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ - uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - float32_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ - float32_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ - arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ - } arm_rfft_instance_f32; - - arm_status arm_rfft_init_f32( - arm_rfft_instance_f32 * S, - arm_cfft_radix4_instance_f32 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag); - - void arm_rfft_f32( - const arm_rfft_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst); - - /** - * @brief Instance structure for the floating-point RFFT/RIFFT function. - */ -typedef struct - { - arm_cfft_instance_f32 Sint; /**< Internal CFFT structure. */ - uint16_t fftLenRFFT; /**< length of the real sequence */ - float32_t * pTwiddleRFFT; /**< Twiddle factors real stage */ - } arm_rfft_fast_instance_f32 ; - -arm_status arm_rfft_fast_init_f32 ( - arm_rfft_fast_instance_f32 * S, - uint16_t fftLen); - -void arm_rfft_fast_f32( - arm_rfft_fast_instance_f32 * S, - float32_t * p, float32_t * pOut, - uint8_t ifftFlag); - - /** - * @brief Instance structure for the floating-point DCT4/IDCT4 function. - */ - typedef struct - { - uint16_t N; /**< length of the DCT4. */ - uint16_t Nby2; /**< half of the length of the DCT4. */ - float32_t normalize; /**< normalizing factor. */ - float32_t *pTwiddle; /**< points to the twiddle factor table. */ - float32_t *pCosFactor; /**< points to the cosFactor table. */ - arm_rfft_instance_f32 *pRfft; /**< points to the real FFT instance. */ - arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ - } arm_dct4_instance_f32; - - - /** - * @brief Initialization function for the floating-point DCT4/IDCT4. - * @param[in,out] S points to an instance of floating-point DCT4/IDCT4 structure. - * @param[in] S_RFFT points to an instance of floating-point RFFT/RIFFT structure. - * @param[in] S_CFFT points to an instance of floating-point CFFT/CIFFT structure. - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported transform length. - */ - arm_status arm_dct4_init_f32( - arm_dct4_instance_f32 * S, - arm_rfft_instance_f32 * S_RFFT, - arm_cfft_radix4_instance_f32 * S_CFFT, - uint16_t N, - uint16_t Nby2, - float32_t normalize); - - - /** - * @brief Processing function for the floating-point DCT4/IDCT4. - * @param[in] S points to an instance of the floating-point DCT4/IDCT4 structure. - * @param[in] pState points to state buffer. - * @param[in,out] pInlineBuffer points to the in-place input and output buffer. - */ - void arm_dct4_f32( - const arm_dct4_instance_f32 * S, - float32_t * pState, - float32_t * pInlineBuffer); - - - /** - * @brief Instance structure for the Q31 DCT4/IDCT4 function. - */ - typedef struct - { - uint16_t N; /**< length of the DCT4. */ - uint16_t Nby2; /**< half of the length of the DCT4. */ - q31_t normalize; /**< normalizing factor. */ - q31_t *pTwiddle; /**< points to the twiddle factor table. */ - q31_t *pCosFactor; /**< points to the cosFactor table. */ - arm_rfft_instance_q31 *pRfft; /**< points to the real FFT instance. */ - arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */ - } arm_dct4_instance_q31; - - - /** - * @brief Initialization function for the Q31 DCT4/IDCT4. - * @param[in,out] S points to an instance of Q31 DCT4/IDCT4 structure. - * @param[in] S_RFFT points to an instance of Q31 RFFT/RIFFT structure - * @param[in] S_CFFT points to an instance of Q31 CFFT/CIFFT structure - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. - */ - arm_status arm_dct4_init_q31( - arm_dct4_instance_q31 * S, - arm_rfft_instance_q31 * S_RFFT, - arm_cfft_radix4_instance_q31 * S_CFFT, - uint16_t N, - uint16_t Nby2, - q31_t normalize); - - - /** - * @brief Processing function for the Q31 DCT4/IDCT4. - * @param[in] S points to an instance of the Q31 DCT4 structure. - * @param[in] pState points to state buffer. - * @param[in,out] pInlineBuffer points to the in-place input and output buffer. - */ - void arm_dct4_q31( - const arm_dct4_instance_q31 * S, - q31_t * pState, - q31_t * pInlineBuffer); - - - /** - * @brief Instance structure for the Q15 DCT4/IDCT4 function. - */ - typedef struct - { - uint16_t N; /**< length of the DCT4. */ - uint16_t Nby2; /**< half of the length of the DCT4. */ - q15_t normalize; /**< normalizing factor. */ - q15_t *pTwiddle; /**< points to the twiddle factor table. */ - q15_t *pCosFactor; /**< points to the cosFactor table. */ - arm_rfft_instance_q15 *pRfft; /**< points to the real FFT instance. */ - arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */ - } arm_dct4_instance_q15; - - - /** - * @brief Initialization function for the Q15 DCT4/IDCT4. - * @param[in,out] S points to an instance of Q15 DCT4/IDCT4 structure. - * @param[in] S_RFFT points to an instance of Q15 RFFT/RIFFT structure. - * @param[in] S_CFFT points to an instance of Q15 CFFT/CIFFT structure. - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. - */ - arm_status arm_dct4_init_q15( - arm_dct4_instance_q15 * S, - arm_rfft_instance_q15 * S_RFFT, - arm_cfft_radix4_instance_q15 * S_CFFT, - uint16_t N, - uint16_t Nby2, - q15_t normalize); - - - /** - * @brief Processing function for the Q15 DCT4/IDCT4. - * @param[in] S points to an instance of the Q15 DCT4 structure. - * @param[in] pState points to state buffer. - * @param[in,out] pInlineBuffer points to the in-place input and output buffer. - */ - void arm_dct4_q15( - const arm_dct4_instance_q15 * S, - q15_t * pState, - q15_t * pInlineBuffer); - - - /** - * @brief Floating-point vector addition. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_add_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q7 vector addition. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_add_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q15 vector addition. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_add_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q31 vector addition. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_add_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Floating-point vector subtraction. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_sub_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q7 vector subtraction. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_sub_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q15 vector subtraction. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_sub_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q31 vector subtraction. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_sub_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Multiplies a floating-point vector by a scalar. - * @param[in] pSrc points to the input vector - * @param[in] scale scale factor to be applied - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_scale_f32( - float32_t * pSrc, - float32_t scale, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Multiplies a Q7 vector by a scalar. - * @param[in] pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_scale_q7( - q7_t * pSrc, - q7_t scaleFract, - int8_t shift, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Multiplies a Q15 vector by a scalar. - * @param[in] pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_scale_q15( - q15_t * pSrc, - q15_t scaleFract, - int8_t shift, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Multiplies a Q31 vector by a scalar. - * @param[in] pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_scale_q31( - q31_t * pSrc, - q31_t scaleFract, - int8_t shift, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q7 vector absolute value. - * @param[in] pSrc points to the input buffer - * @param[out] pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - */ - void arm_abs_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Floating-point vector absolute value. - * @param[in] pSrc points to the input buffer - * @param[out] pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - */ - void arm_abs_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q15 vector absolute value. - * @param[in] pSrc points to the input buffer - * @param[out] pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - */ - void arm_abs_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q31 vector absolute value. - * @param[in] pSrc points to the input buffer - * @param[out] pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - */ - void arm_abs_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Dot product of floating-point vectors. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] result output result returned here - */ - void arm_dot_prod_f32( - float32_t * pSrcA, - float32_t * pSrcB, - uint32_t blockSize, - float32_t * result); - - - /** - * @brief Dot product of Q7 vectors. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] result output result returned here - */ - void arm_dot_prod_q7( - q7_t * pSrcA, - q7_t * pSrcB, - uint32_t blockSize, - q31_t * result); - - - /** - * @brief Dot product of Q15 vectors. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] result output result returned here - */ - void arm_dot_prod_q15( - q15_t * pSrcA, - q15_t * pSrcB, - uint32_t blockSize, - q63_t * result); - - - /** - * @brief Dot product of Q31 vectors. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] result output result returned here - */ - void arm_dot_prod_q31( - q31_t * pSrcA, - q31_t * pSrcB, - uint32_t blockSize, - q63_t * result); - - - /** - * @brief Shifts the elements of a Q7 vector a specified number of bits. - * @param[in] pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_shift_q7( - q7_t * pSrc, - int8_t shiftBits, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Shifts the elements of a Q15 vector a specified number of bits. - * @param[in] pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_shift_q15( - q15_t * pSrc, - int8_t shiftBits, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Shifts the elements of a Q31 vector a specified number of bits. - * @param[in] pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_shift_q31( - q31_t * pSrc, - int8_t shiftBits, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Adds a constant offset to a floating-point vector. - * @param[in] pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_offset_f32( - float32_t * pSrc, - float32_t offset, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Adds a constant offset to a Q7 vector. - * @param[in] pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_offset_q7( - q7_t * pSrc, - q7_t offset, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Adds a constant offset to a Q15 vector. - * @param[in] pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_offset_q15( - q15_t * pSrc, - q15_t offset, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Adds a constant offset to a Q31 vector. - * @param[in] pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_offset_q31( - q31_t * pSrc, - q31_t offset, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Negates the elements of a floating-point vector. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_negate_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Negates the elements of a Q7 vector. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_negate_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Negates the elements of a Q15 vector. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_negate_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Negates the elements of a Q31 vector. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_negate_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Copies the elements of a floating-point vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_copy_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Copies the elements of a Q7 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_copy_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Copies the elements of a Q15 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_copy_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Copies the elements of a Q31 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_copy_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fills a constant value into a floating-point vector. - * @param[in] value input value to be filled - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_fill_f32( - float32_t value, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fills a constant value into a Q7 vector. - * @param[in] value input value to be filled - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_fill_q7( - q7_t value, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fills a constant value into a Q15 vector. - * @param[in] value input value to be filled - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_fill_q15( - q15_t value, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fills a constant value into a Q31 vector. - * @param[in] value input value to be filled - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_fill_q31( - q31_t value, - q31_t * pDst, - uint32_t blockSize); - - -/** - * @brief Convolution of floating-point sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - */ - void arm_conv_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst); - - - /** - * @brief Convolution of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - */ - void arm_conv_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2); - - -/** - * @brief Convolution of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - */ - void arm_conv_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst); - - - /** - * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - */ - void arm_conv_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst); - - - /** - * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - */ - void arm_conv_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Convolution of Q31 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - */ - void arm_conv_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst); - - - /** - * @brief Convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - */ - void arm_conv_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst); - - - /** - * @brief Convolution of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - */ - void arm_conv_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Convolution of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - */ - void arm_conv_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst); - - - /** - * @brief Partial convolution of floating-point sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Partial convolution of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Partial convolution of Q31 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q7 sequences - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2); - - -/** - * @brief Partial convolution of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Instance structure for the Q15 FIR decimator. - */ - typedef struct - { - uint8_t M; /**< decimation factor. */ - uint16_t numTaps; /**< number of coefficients in the filter. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - } arm_fir_decimate_instance_q15; - - /** - * @brief Instance structure for the Q31 FIR decimator. - */ - typedef struct - { - uint8_t M; /**< decimation factor. */ - uint16_t numTaps; /**< number of coefficients in the filter. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - } arm_fir_decimate_instance_q31; - - /** - * @brief Instance structure for the floating-point FIR decimator. - */ - typedef struct - { - uint8_t M; /**< decimation factor. */ - uint16_t numTaps; /**< number of coefficients in the filter. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - } arm_fir_decimate_instance_f32; - - - /** - * @brief Processing function for the floating-point FIR decimator. - * @param[in] S points to an instance of the floating-point FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_f32( - const arm_fir_decimate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point FIR decimator. - * @param[in,out] S points to an instance of the floating-point FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - */ - arm_status arm_fir_decimate_init_f32( - arm_fir_decimate_instance_f32 * S, - uint16_t numTaps, - uint8_t M, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 FIR decimator. - * @param[in] S points to an instance of the Q15 FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q15 FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_fast_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 FIR decimator. - * @param[in,out] S points to an instance of the Q15 FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - */ - arm_status arm_fir_decimate_init_q15( - arm_fir_decimate_instance_q15 * S, - uint16_t numTaps, - uint8_t M, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 FIR decimator. - * @param[in] S points to an instance of the Q31 FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_q31( - const arm_fir_decimate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - /** - * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q31 FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_fast_q31( - arm_fir_decimate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 FIR decimator. - * @param[in,out] S points to an instance of the Q31 FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - */ - arm_status arm_fir_decimate_init_q31( - arm_fir_decimate_instance_q31 * S, - uint16_t numTaps, - uint8_t M, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 FIR interpolator. - */ - typedef struct - { - uint8_t L; /**< upsample factor. */ - uint16_t phaseLength; /**< length of each polyphase filter component. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ - q15_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ - } arm_fir_interpolate_instance_q15; - - /** - * @brief Instance structure for the Q31 FIR interpolator. - */ - typedef struct - { - uint8_t L; /**< upsample factor. */ - uint16_t phaseLength; /**< length of each polyphase filter component. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ - q31_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ - } arm_fir_interpolate_instance_q31; - - /** - * @brief Instance structure for the floating-point FIR interpolator. - */ - typedef struct - { - uint8_t L; /**< upsample factor. */ - uint16_t phaseLength; /**< length of each polyphase filter component. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ - float32_t *pState; /**< points to the state variable array. The array is of length phaseLength+numTaps-1. */ - } arm_fir_interpolate_instance_f32; - - - /** - * @brief Processing function for the Q15 FIR interpolator. - * @param[in] S points to an instance of the Q15 FIR interpolator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_interpolate_q15( - const arm_fir_interpolate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 FIR interpolator. - * @param[in,out] S points to an instance of the Q15 FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficient buffer. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - */ - arm_status arm_fir_interpolate_init_q15( - arm_fir_interpolate_instance_q15 * S, - uint8_t L, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 FIR interpolator. - * @param[in] S points to an instance of the Q15 FIR interpolator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_interpolate_q31( - const arm_fir_interpolate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 FIR interpolator. - * @param[in,out] S points to an instance of the Q31 FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficient buffer. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - */ - arm_status arm_fir_interpolate_init_q31( - arm_fir_interpolate_instance_q31 * S, - uint8_t L, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the floating-point FIR interpolator. - * @param[in] S points to an instance of the floating-point FIR interpolator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_interpolate_f32( - const arm_fir_interpolate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point FIR interpolator. - * @param[in,out] S points to an instance of the floating-point FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficient buffer. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - */ - arm_status arm_fir_interpolate_init_f32( - arm_fir_interpolate_instance_f32 * S, - uint8_t L, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize); - - - /** - * @brief Instance structure for the high precision Q31 Biquad cascade filter. - */ - typedef struct - { - uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - q63_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ - q31_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ - uint8_t postShift; /**< additional shift, in bits, applied to each output sample. */ - } arm_biquad_cas_df1_32x64_ins_q31; - - - /** - * @param[in] S points to an instance of the high precision Q31 Biquad cascade filter structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cas_df1_32x64_q31( - const arm_biquad_cas_df1_32x64_ins_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @param[in,out] S points to an instance of the high precision Q31 Biquad cascade filter structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] postShift shift to be applied to the output. Varies according to the coefficients format - */ - void arm_biquad_cas_df1_32x64_init_q31( - arm_biquad_cas_df1_32x64_ins_q31 * S, - uint8_t numStages, - q31_t * pCoeffs, - q63_t * pState, - uint8_t postShift); - - - /** - * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. - */ - typedef struct - { - uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - float32_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ - float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ - } arm_biquad_cascade_df2T_instance_f32; - - /** - * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. - */ - typedef struct - { - uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - float32_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ - float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ - } arm_biquad_cascade_stereo_df2T_instance_f32; - - /** - * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. - */ - typedef struct - { - uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - float64_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ - float64_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ - } arm_biquad_cascade_df2T_instance_f64; - - - /** - * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in] S points to an instance of the filter data structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df2T_f32( - const arm_biquad_cascade_df2T_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. 2 channels - * @param[in] S points to an instance of the filter data structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_stereo_df2T_f32( - const arm_biquad_cascade_stereo_df2T_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in] S points to an instance of the filter data structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df2T_f64( - const arm_biquad_cascade_df2T_instance_f64 * S, - float64_t * pSrc, - float64_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in,out] S points to an instance of the filter data structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - */ - void arm_biquad_cascade_df2T_init_f32( - arm_biquad_cascade_df2T_instance_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState); - - - /** - * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in,out] S points to an instance of the filter data structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - */ - void arm_biquad_cascade_stereo_df2T_init_f32( - arm_biquad_cascade_stereo_df2T_instance_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState); - - - /** - * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in,out] S points to an instance of the filter data structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - */ - void arm_biquad_cascade_df2T_init_f64( - arm_biquad_cascade_df2T_instance_f64 * S, - uint8_t numStages, - float64_t * pCoeffs, - float64_t * pState); - - - /** - * @brief Instance structure for the Q15 FIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of filter stages. */ - q15_t *pState; /**< points to the state variable array. The array is of length numStages. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ - } arm_fir_lattice_instance_q15; - - /** - * @brief Instance structure for the Q31 FIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of filter stages. */ - q31_t *pState; /**< points to the state variable array. The array is of length numStages. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ - } arm_fir_lattice_instance_q31; - - /** - * @brief Instance structure for the floating-point FIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of filter stages. */ - float32_t *pState; /**< points to the state variable array. The array is of length numStages. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ - } arm_fir_lattice_instance_f32; - - - /** - * @brief Initialization function for the Q15 FIR lattice filter. - * @param[in] S points to an instance of the Q15 FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] pState points to the state buffer. The array is of length numStages. - */ - void arm_fir_lattice_init_q15( - arm_fir_lattice_instance_q15 * S, - uint16_t numStages, - q15_t * pCoeffs, - q15_t * pState); - - - /** - * @brief Processing function for the Q15 FIR lattice filter. - * @param[in] S points to an instance of the Q15 FIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_lattice_q15( - const arm_fir_lattice_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 FIR lattice filter. - * @param[in] S points to an instance of the Q31 FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] pState points to the state buffer. The array is of length numStages. - */ - void arm_fir_lattice_init_q31( - arm_fir_lattice_instance_q31 * S, - uint16_t numStages, - q31_t * pCoeffs, - q31_t * pState); - - - /** - * @brief Processing function for the Q31 FIR lattice filter. - * @param[in] S points to an instance of the Q31 FIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_fir_lattice_q31( - const arm_fir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - -/** - * @brief Initialization function for the floating-point FIR lattice filter. - * @param[in] S points to an instance of the floating-point FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] pState points to the state buffer. The array is of length numStages. - */ - void arm_fir_lattice_init_f32( - arm_fir_lattice_instance_f32 * S, - uint16_t numStages, - float32_t * pCoeffs, - float32_t * pState); - - - /** - * @brief Processing function for the floating-point FIR lattice filter. - * @param[in] S points to an instance of the floating-point FIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_fir_lattice_f32( - const arm_fir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 IIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of stages in the filter. */ - q15_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ - q15_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ - q15_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ - } arm_iir_lattice_instance_q15; - - /** - * @brief Instance structure for the Q31 IIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of stages in the filter. */ - q31_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ - q31_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ - q31_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ - } arm_iir_lattice_instance_q31; - - /** - * @brief Instance structure for the floating-point IIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of stages in the filter. */ - float32_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ - float32_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ - float32_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ - } arm_iir_lattice_instance_f32; - - - /** - * @brief Processing function for the floating-point IIR lattice filter. - * @param[in] S points to an instance of the floating-point IIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_f32( - const arm_iir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point IIR lattice filter. - * @param[in] S points to an instance of the floating-point IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. - * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. - * @param[in] pState points to the state buffer. The array is of length numStages+blockSize-1. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_init_f32( - arm_iir_lattice_instance_f32 * S, - uint16_t numStages, - float32_t * pkCoeffs, - float32_t * pvCoeffs, - float32_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 IIR lattice filter. - * @param[in] S points to an instance of the Q31 IIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_q31( - const arm_iir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 IIR lattice filter. - * @param[in] S points to an instance of the Q31 IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. - * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. - * @param[in] pState points to the state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_init_q31( - arm_iir_lattice_instance_q31 * S, - uint16_t numStages, - q31_t * pkCoeffs, - q31_t * pvCoeffs, - q31_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 IIR lattice filter. - * @param[in] S points to an instance of the Q15 IIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_q15( - const arm_iir_lattice_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - -/** - * @brief Initialization function for the Q15 IIR lattice filter. - * @param[in] S points to an instance of the fixed-point Q15 IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] pkCoeffs points to reflection coefficient buffer. The array is of length numStages. - * @param[in] pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1. - * @param[in] pState points to state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process per call. - */ - void arm_iir_lattice_init_q15( - arm_iir_lattice_instance_q15 * S, - uint16_t numStages, - q15_t * pkCoeffs, - q15_t * pvCoeffs, - q15_t * pState, - uint32_t blockSize); - - - /** - * @brief Instance structure for the floating-point LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - float32_t mu; /**< step size that controls filter coefficient updates. */ - } arm_lms_instance_f32; - - - /** - * @brief Processing function for floating-point LMS filter. - * @param[in] S points to an instance of the floating-point LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_f32( - const arm_lms_instance_f32 * S, - float32_t * pSrc, - float32_t * pRef, - float32_t * pOut, - float32_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for floating-point LMS filter. - * @param[in] S points to an instance of the floating-point LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to the coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_init_f32( - arm_lms_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - float32_t mu, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - q15_t mu; /**< step size that controls filter coefficient updates. */ - uint32_t postShift; /**< bit shift applied to coefficients. */ - } arm_lms_instance_q15; - - - /** - * @brief Initialization function for the Q15 LMS filter. - * @param[in] S points to an instance of the Q15 LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to the coefficient buffer. - * @param[in] pState points to the state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - */ - void arm_lms_init_q15( - arm_lms_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - q15_t mu, - uint32_t blockSize, - uint32_t postShift); - - - /** - * @brief Processing function for Q15 LMS filter. - * @param[in] S points to an instance of the Q15 LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_q15( - const arm_lms_instance_q15 * S, - q15_t * pSrc, - q15_t * pRef, - q15_t * pOut, - q15_t * pErr, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q31 LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - q31_t mu; /**< step size that controls filter coefficient updates. */ - uint32_t postShift; /**< bit shift applied to coefficients. */ - } arm_lms_instance_q31; - - - /** - * @brief Processing function for Q31 LMS filter. - * @param[in] S points to an instance of the Q15 LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_q31( - const arm_lms_instance_q31 * S, - q31_t * pSrc, - q31_t * pRef, - q31_t * pOut, - q31_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for Q31 LMS filter. - * @param[in] S points to an instance of the Q31 LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - */ - void arm_lms_init_q31( - arm_lms_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - q31_t mu, - uint32_t blockSize, - uint32_t postShift); - - - /** - * @brief Instance structure for the floating-point normalized LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - float32_t mu; /**< step size that control filter coefficient updates. */ - float32_t energy; /**< saves previous frame energy. */ - float32_t x0; /**< saves previous input sample. */ - } arm_lms_norm_instance_f32; - - - /** - * @brief Processing function for floating-point normalized LMS filter. - * @param[in] S points to an instance of the floating-point normalized LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_norm_f32( - arm_lms_norm_instance_f32 * S, - float32_t * pSrc, - float32_t * pRef, - float32_t * pOut, - float32_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for floating-point normalized LMS filter. - * @param[in] S points to an instance of the floating-point LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_norm_init_f32( - arm_lms_norm_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - float32_t mu, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q31 normalized LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - q31_t mu; /**< step size that controls filter coefficient updates. */ - uint8_t postShift; /**< bit shift applied to coefficients. */ - q31_t *recipTable; /**< points to the reciprocal initial value table. */ - q31_t energy; /**< saves previous frame energy. */ - q31_t x0; /**< saves previous input sample. */ - } arm_lms_norm_instance_q31; - - - /** - * @brief Processing function for Q31 normalized LMS filter. - * @param[in] S points to an instance of the Q31 normalized LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_norm_q31( - arm_lms_norm_instance_q31 * S, - q31_t * pSrc, - q31_t * pRef, - q31_t * pOut, - q31_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for Q31 normalized LMS filter. - * @param[in] S points to an instance of the Q31 normalized LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - */ - void arm_lms_norm_init_q31( - arm_lms_norm_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - q31_t mu, - uint32_t blockSize, - uint8_t postShift); - - - /** - * @brief Instance structure for the Q15 normalized LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< Number of coefficients in the filter. */ - q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - q15_t mu; /**< step size that controls filter coefficient updates. */ - uint8_t postShift; /**< bit shift applied to coefficients. */ - q15_t *recipTable; /**< Points to the reciprocal initial value table. */ - q15_t energy; /**< saves previous frame energy. */ - q15_t x0; /**< saves previous input sample. */ - } arm_lms_norm_instance_q15; - - - /** - * @brief Processing function for Q15 normalized LMS filter. - * @param[in] S points to an instance of the Q15 normalized LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_norm_q15( - arm_lms_norm_instance_q15 * S, - q15_t * pSrc, - q15_t * pRef, - q15_t * pOut, - q15_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for Q15 normalized LMS filter. - * @param[in] S points to an instance of the Q15 normalized LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - */ - void arm_lms_norm_init_q15( - arm_lms_norm_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - q15_t mu, - uint32_t blockSize, - uint8_t postShift); - - - /** - * @brief Correlation of floating-point sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - void arm_correlate_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst); - - - /** - * @brief Correlation of Q15 sequences - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - */ - void arm_correlate_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch); - - - /** - * @brief Correlation of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - - void arm_correlate_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst); - - - /** - * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - - void arm_correlate_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst); - - - /** - * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - */ - void arm_correlate_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch); - - - /** - * @brief Correlation of Q31 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - void arm_correlate_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst); - - - /** - * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - void arm_correlate_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst); - - - /** - * @brief Correlation of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - */ - void arm_correlate_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Correlation of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - void arm_correlate_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst); - - - /** - * @brief Instance structure for the floating-point sparse FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ - float32_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ - int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ - } arm_fir_sparse_instance_f32; - - /** - * @brief Instance structure for the Q31 sparse FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ - q31_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ - int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ - } arm_fir_sparse_instance_q31; - - /** - * @brief Instance structure for the Q15 sparse FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ - q15_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ - int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ - } arm_fir_sparse_instance_q15; - - /** - * @brief Instance structure for the Q7 sparse FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ - q7_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ - q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ - int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ - } arm_fir_sparse_instance_q7; - - - /** - * @brief Processing function for the floating-point sparse FIR filter. - * @param[in] S points to an instance of the floating-point sparse FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] pScratchIn points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_sparse_f32( - arm_fir_sparse_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - float32_t * pScratchIn, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point sparse FIR filter. - * @param[in,out] S points to an instance of the floating-point sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] pCoeffs points to the array of filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - */ - void arm_fir_sparse_init_f32( - arm_fir_sparse_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 sparse FIR filter. - * @param[in] S points to an instance of the Q31 sparse FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] pScratchIn points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_sparse_q31( - arm_fir_sparse_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - q31_t * pScratchIn, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 sparse FIR filter. - * @param[in,out] S points to an instance of the Q31 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] pCoeffs points to the array of filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - */ - void arm_fir_sparse_init_q31( - arm_fir_sparse_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 sparse FIR filter. - * @param[in] S points to an instance of the Q15 sparse FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] pScratchIn points to a temporary buffer of size blockSize. - * @param[in] pScratchOut points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_sparse_q15( - arm_fir_sparse_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - q15_t * pScratchIn, - q31_t * pScratchOut, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 sparse FIR filter. - * @param[in,out] S points to an instance of the Q15 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] pCoeffs points to the array of filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - */ - void arm_fir_sparse_init_q15( - arm_fir_sparse_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q7 sparse FIR filter. - * @param[in] S points to an instance of the Q7 sparse FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] pScratchIn points to a temporary buffer of size blockSize. - * @param[in] pScratchOut points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_sparse_q7( - arm_fir_sparse_instance_q7 * S, - q7_t * pSrc, - q7_t * pDst, - q7_t * pScratchIn, - q31_t * pScratchOut, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q7 sparse FIR filter. - * @param[in,out] S points to an instance of the Q7 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] pCoeffs points to the array of filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - */ - void arm_fir_sparse_init_q7( - arm_fir_sparse_instance_q7 * S, - uint16_t numTaps, - q7_t * pCoeffs, - q7_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize); - - - /** - * @brief Floating-point sin_cos function. - * @param[in] theta input value in degrees - * @param[out] pSinVal points to the processed sine output. - * @param[out] pCosVal points to the processed cos output. - */ - void arm_sin_cos_f32( - float32_t theta, - float32_t * pSinVal, - float32_t * pCosVal); - - - /** - * @brief Q31 sin_cos function. - * @param[in] theta scaled input value in degrees - * @param[out] pSinVal points to the processed sine output. - * @param[out] pCosVal points to the processed cosine output. - */ - void arm_sin_cos_q31( - q31_t theta, - q31_t * pSinVal, - q31_t * pCosVal); - - - /** - * @brief Floating-point complex conjugate. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_conj_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t numSamples); - - /** - * @brief Q31 complex conjugate. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_conj_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q15 complex conjugate. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_conj_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t numSamples); - - - /** - * @brief Floating-point complex magnitude squared - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_squared_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q31 complex magnitude squared - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_squared_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q15 complex magnitude squared - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_squared_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t numSamples); - - - /** - * @ingroup groupController - */ - - /** - * @defgroup PID PID Motor Control - * - * A Proportional Integral Derivative (PID) controller is a generic feedback control - * loop mechanism widely used in industrial control systems. - * A PID controller is the most commonly used type of feedback controller. - * - * This set of functions implements (PID) controllers - * for Q15, Q31, and floating-point data types. The functions operate on a single sample - * of data and each call to the function returns a single processed value. - * S points to an instance of the PID control data structure. in - * is the input sample value. The functions return the output value. - * - * \par Algorithm: - *
-   *    y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2]
-   *    A0 = Kp + Ki + Kd
-   *    A1 = (-Kp ) - (2 * Kd )
-   *    A2 = Kd  
- * - * \par - * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant - * - * \par - * \image html PID.gif "Proportional Integral Derivative Controller" - * - * \par - * The PID controller calculates an "error" value as the difference between - * the measured output and the reference input. - * The controller attempts to minimize the error by adjusting the process control inputs. - * The proportional value determines the reaction to the current error, - * the integral value determines the reaction based on the sum of recent errors, - * and the derivative value determines the reaction based on the rate at which the error has been changing. - * - * \par Instance Structure - * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure. - * A separate instance structure must be defined for each PID Controller. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Reset Functions - * There is also an associated reset function for each data type which clears the state array. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains. - * - Zeros out the values in the state buffer. - * - * \par - * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the PID Controller functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup PID - * @{ - */ - - /** - * @brief Process function for the floating-point PID Control. - * @param[in,out] S is an instance of the floating-point PID Control structure - * @param[in] in input sample to process - * @return out processed output sample. - */ - static __INLINE float32_t arm_pid_f32( - arm_pid_instance_f32 * S, - float32_t in) - { - float32_t out; - - /* y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2] */ - out = (S->A0 * in) + - (S->A1 * S->state[0]) + (S->A2 * S->state[1]) + (S->state[2]); - - /* Update state */ - S->state[1] = S->state[0]; - S->state[0] = in; - S->state[2] = out; - - /* return to application */ - return (out); - - } - - /** - * @brief Process function for the Q31 PID Control. - * @param[in,out] S points to an instance of the Q31 PID Control structure - * @param[in] in input sample to process - * @return out processed output sample. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions. - * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. - */ - static __INLINE q31_t arm_pid_q31( - arm_pid_instance_q31 * S, - q31_t in) - { - q63_t acc; - q31_t out; - - /* acc = A0 * x[n] */ - acc = (q63_t) S->A0 * in; - - /* acc += A1 * x[n-1] */ - acc += (q63_t) S->A1 * S->state[0]; - - /* acc += A2 * x[n-2] */ - acc += (q63_t) S->A2 * S->state[1]; - - /* convert output to 1.31 format to add y[n-1] */ - out = (q31_t) (acc >> 31u); - - /* out += y[n-1] */ - out += S->state[2]; - - /* Update state */ - S->state[1] = S->state[0]; - S->state[0] = in; - S->state[2] = out; - - /* return to application */ - return (out); - } - - - /** - * @brief Process function for the Q15 PID Control. - * @param[in,out] S points to an instance of the Q15 PID Control structure - * @param[in] in input sample to process - * @return out processed output sample. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - */ - static __INLINE q15_t arm_pid_q15( - arm_pid_instance_q15 * S, - q15_t in) - { - q63_t acc; - q15_t out; - -#ifndef ARM_MATH_CM0_FAMILY - __SIMD32_TYPE *vstate; - - /* Implementation of PID controller */ - - /* acc = A0 * x[n] */ - acc = (q31_t) __SMUAD((uint32_t)S->A0, (uint32_t)in); - - /* acc += A1 * x[n-1] + A2 * x[n-2] */ - vstate = __SIMD32_CONST(S->state); - acc = (q63_t)__SMLALD((uint32_t)S->A1, (uint32_t)*vstate, (uint64_t)acc); -#else - /* acc = A0 * x[n] */ - acc = ((q31_t) S->A0) * in; - - /* acc += A1 * x[n-1] + A2 * x[n-2] */ - acc += (q31_t) S->A1 * S->state[0]; - acc += (q31_t) S->A2 * S->state[1]; -#endif - - /* acc += y[n-1] */ - acc += (q31_t) S->state[2] << 15; - - /* saturate the output */ - out = (q15_t) (__SSAT((acc >> 15), 16)); - - /* Update state */ - S->state[1] = S->state[0]; - S->state[0] = in; - S->state[2] = out; - - /* return to application */ - return (out); - } - - /** - * @} end of PID group - */ - - - /** - * @brief Floating-point matrix inverse. - * @param[in] src points to the instance of the input floating-point matrix structure. - * @param[out] dst points to the instance of the output floating-point matrix structure. - * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. - * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. - */ - arm_status arm_mat_inverse_f32( - const arm_matrix_instance_f32 * src, - arm_matrix_instance_f32 * dst); - - - /** - * @brief Floating-point matrix inverse. - * @param[in] src points to the instance of the input floating-point matrix structure. - * @param[out] dst points to the instance of the output floating-point matrix structure. - * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. - * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. - */ - arm_status arm_mat_inverse_f64( - const arm_matrix_instance_f64 * src, - arm_matrix_instance_f64 * dst); - - - - /** - * @ingroup groupController - */ - - /** - * @defgroup clarke Vector Clarke Transform - * Forward Clarke transform converts the instantaneous stator phases into a two-coordinate time invariant vector. - * Generally the Clarke transform uses three-phase currents Ia, Ib and Ic to calculate currents - * in the two-phase orthogonal stator axis Ialpha and Ibeta. - * When Ialpha is superposed with Ia as shown in the figure below - * \image html clarke.gif Stator current space vector and its components in (a,b). - * and Ia + Ib + Ic = 0, in this condition Ialpha and Ibeta - * can be calculated using only Ia and Ib. - * - * The function operates on a single sample of data and each call to the function returns the processed output. - * The library provides separate functions for Q31 and floating-point data types. - * \par Algorithm - * \image html clarkeFormula.gif - * where Ia and Ib are the instantaneous stator phases and - * pIalpha and pIbeta are the two coordinates of time invariant vector. - * \par Fixed-Point Behavior - * Care must be taken when using the Q31 version of the Clarke transform. - * In particular, the overflow and saturation behavior of the accumulator used must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup clarke - * @{ - */ - - /** - * - * @brief Floating-point Clarke transform - * @param[in] Ia input three-phase coordinate a - * @param[in] Ib input three-phase coordinate b - * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha - * @param[out] pIbeta points to output two-phase orthogonal vector axis beta - */ - static __INLINE void arm_clarke_f32( - float32_t Ia, - float32_t Ib, - float32_t * pIalpha, - float32_t * pIbeta) - { - /* Calculate pIalpha using the equation, pIalpha = Ia */ - *pIalpha = Ia; - - /* Calculate pIbeta using the equation, pIbeta = (1/sqrt(3)) * Ia + (2/sqrt(3)) * Ib */ - *pIbeta = ((float32_t) 0.57735026919 * Ia + (float32_t) 1.15470053838 * Ib); - } - - - /** - * @brief Clarke transform for Q31 version - * @param[in] Ia input three-phase coordinate a - * @param[in] Ib input three-phase coordinate b - * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha - * @param[out] pIbeta points to output two-phase orthogonal vector axis beta - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. - * There is saturation on the addition, hence there is no risk of overflow. - */ - static __INLINE void arm_clarke_q31( - q31_t Ia, - q31_t Ib, - q31_t * pIalpha, - q31_t * pIbeta) - { - q31_t product1, product2; /* Temporary variables used to store intermediate results */ - - /* Calculating pIalpha from Ia by equation pIalpha = Ia */ - *pIalpha = Ia; - - /* Intermediate product is calculated by (1/(sqrt(3)) * Ia) */ - product1 = (q31_t) (((q63_t) Ia * 0x24F34E8B) >> 30); - - /* Intermediate product is calculated by (2/sqrt(3) * Ib) */ - product2 = (q31_t) (((q63_t) Ib * 0x49E69D16) >> 30); - - /* pIbeta is calculated by adding the intermediate products */ - *pIbeta = __QADD(product1, product2); - } - - /** - * @} end of clarke group - */ - - /** - * @brief Converts the elements of the Q7 vector to Q31 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_q7_to_q31( - q7_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - - /** - * @ingroup groupController - */ - - /** - * @defgroup inv_clarke Vector Inverse Clarke Transform - * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases. - * - * The function operates on a single sample of data and each call to the function returns the processed output. - * The library provides separate functions for Q31 and floating-point data types. - * \par Algorithm - * \image html clarkeInvFormula.gif - * where pIa and pIb are the instantaneous stator phases and - * Ialpha and Ibeta are the two coordinates of time invariant vector. - * \par Fixed-Point Behavior - * Care must be taken when using the Q31 version of the Clarke transform. - * In particular, the overflow and saturation behavior of the accumulator used must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup inv_clarke - * @{ - */ - - /** - * @brief Floating-point Inverse Clarke transform - * @param[in] Ialpha input two-phase orthogonal vector axis alpha - * @param[in] Ibeta input two-phase orthogonal vector axis beta - * @param[out] pIa points to output three-phase coordinate a - * @param[out] pIb points to output three-phase coordinate b - */ - static __INLINE void arm_inv_clarke_f32( - float32_t Ialpha, - float32_t Ibeta, - float32_t * pIa, - float32_t * pIb) - { - /* Calculating pIa from Ialpha by equation pIa = Ialpha */ - *pIa = Ialpha; - - /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */ - *pIb = -0.5f * Ialpha + 0.8660254039f * Ibeta; - } - - - /** - * @brief Inverse Clarke transform for Q31 version - * @param[in] Ialpha input two-phase orthogonal vector axis alpha - * @param[in] Ibeta input two-phase orthogonal vector axis beta - * @param[out] pIa points to output three-phase coordinate a - * @param[out] pIb points to output three-phase coordinate b - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. - * There is saturation on the subtraction, hence there is no risk of overflow. - */ - static __INLINE void arm_inv_clarke_q31( - q31_t Ialpha, - q31_t Ibeta, - q31_t * pIa, - q31_t * pIb) - { - q31_t product1, product2; /* Temporary variables used to store intermediate results */ - - /* Calculating pIa from Ialpha by equation pIa = Ialpha */ - *pIa = Ialpha; - - /* Intermediate product is calculated by (1/(2*sqrt(3)) * Ia) */ - product1 = (q31_t) (((q63_t) (Ialpha) * (0x40000000)) >> 31); - - /* Intermediate product is calculated by (1/sqrt(3) * pIb) */ - product2 = (q31_t) (((q63_t) (Ibeta) * (0x6ED9EBA1)) >> 31); - - /* pIb is calculated by subtracting the products */ - *pIb = __QSUB(product2, product1); - } - - /** - * @} end of inv_clarke group - */ - - /** - * @brief Converts the elements of the Q7 vector to Q15 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_q7_to_q15( - q7_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - - /** - * @ingroup groupController - */ - - /** - * @defgroup park Vector Park Transform - * - * Forward Park transform converts the input two-coordinate vector to flux and torque components. - * The Park transform can be used to realize the transformation of the Ialpha and the Ibeta currents - * from the stationary to the moving reference frame and control the spatial relationship between - * the stator vector current and rotor flux vector. - * If we consider the d axis aligned with the rotor flux, the diagram below shows the - * current vector and the relationship from the two reference frames: - * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame" - * - * The function operates on a single sample of data and each call to the function returns the processed output. - * The library provides separate functions for Q31 and floating-point data types. - * \par Algorithm - * \image html parkFormula.gif - * where Ialpha and Ibeta are the stator vector components, - * pId and pIq are rotor vector components and cosVal and sinVal are the - * cosine and sine values of theta (rotor flux position). - * \par Fixed-Point Behavior - * Care must be taken when using the Q31 version of the Park transform. - * In particular, the overflow and saturation behavior of the accumulator used must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup park - * @{ - */ - - /** - * @brief Floating-point Park transform - * @param[in] Ialpha input two-phase vector coordinate alpha - * @param[in] Ibeta input two-phase vector coordinate beta - * @param[out] pId points to output rotor reference frame d - * @param[out] pIq points to output rotor reference frame q - * @param[in] sinVal sine value of rotation angle theta - * @param[in] cosVal cosine value of rotation angle theta - * - * The function implements the forward Park transform. - * - */ - static __INLINE void arm_park_f32( - float32_t Ialpha, - float32_t Ibeta, - float32_t * pId, - float32_t * pIq, - float32_t sinVal, - float32_t cosVal) - { - /* Calculate pId using the equation, pId = Ialpha * cosVal + Ibeta * sinVal */ - *pId = Ialpha * cosVal + Ibeta * sinVal; - - /* Calculate pIq using the equation, pIq = - Ialpha * sinVal + Ibeta * cosVal */ - *pIq = -Ialpha * sinVal + Ibeta * cosVal; - } - - - /** - * @brief Park transform for Q31 version - * @param[in] Ialpha input two-phase vector coordinate alpha - * @param[in] Ibeta input two-phase vector coordinate beta - * @param[out] pId points to output rotor reference frame d - * @param[out] pIq points to output rotor reference frame q - * @param[in] sinVal sine value of rotation angle theta - * @param[in] cosVal cosine value of rotation angle theta - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. - * There is saturation on the addition and subtraction, hence there is no risk of overflow. - */ - static __INLINE void arm_park_q31( - q31_t Ialpha, - q31_t Ibeta, - q31_t * pId, - q31_t * pIq, - q31_t sinVal, - q31_t cosVal) - { - q31_t product1, product2; /* Temporary variables used to store intermediate results */ - q31_t product3, product4; /* Temporary variables used to store intermediate results */ - - /* Intermediate product is calculated by (Ialpha * cosVal) */ - product1 = (q31_t) (((q63_t) (Ialpha) * (cosVal)) >> 31); - - /* Intermediate product is calculated by (Ibeta * sinVal) */ - product2 = (q31_t) (((q63_t) (Ibeta) * (sinVal)) >> 31); - - - /* Intermediate product is calculated by (Ialpha * sinVal) */ - product3 = (q31_t) (((q63_t) (Ialpha) * (sinVal)) >> 31); - - /* Intermediate product is calculated by (Ibeta * cosVal) */ - product4 = (q31_t) (((q63_t) (Ibeta) * (cosVal)) >> 31); - - /* Calculate pId by adding the two intermediate products 1 and 2 */ - *pId = __QADD(product1, product2); - - /* Calculate pIq by subtracting the two intermediate products 3 from 4 */ - *pIq = __QSUB(product4, product3); - } - - /** - * @} end of park group - */ - - /** - * @brief Converts the elements of the Q7 vector to floating-point vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q7_to_float( - q7_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @ingroup groupController - */ - - /** - * @defgroup inv_park Vector Inverse Park transform - * Inverse Park transform converts the input flux and torque components to two-coordinate vector. - * - * The function operates on a single sample of data and each call to the function returns the processed output. - * The library provides separate functions for Q31 and floating-point data types. - * \par Algorithm - * \image html parkInvFormula.gif - * where pIalpha and pIbeta are the stator vector components, - * Id and Iq are rotor vector components and cosVal and sinVal are the - * cosine and sine values of theta (rotor flux position). - * \par Fixed-Point Behavior - * Care must be taken when using the Q31 version of the Park transform. - * In particular, the overflow and saturation behavior of the accumulator used must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup inv_park - * @{ - */ - - /** - * @brief Floating-point Inverse Park transform - * @param[in] Id input coordinate of rotor reference frame d - * @param[in] Iq input coordinate of rotor reference frame q - * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha - * @param[out] pIbeta points to output two-phase orthogonal vector axis beta - * @param[in] sinVal sine value of rotation angle theta - * @param[in] cosVal cosine value of rotation angle theta - */ - static __INLINE void arm_inv_park_f32( - float32_t Id, - float32_t Iq, - float32_t * pIalpha, - float32_t * pIbeta, - float32_t sinVal, - float32_t cosVal) - { - /* Calculate pIalpha using the equation, pIalpha = Id * cosVal - Iq * sinVal */ - *pIalpha = Id * cosVal - Iq * sinVal; - - /* Calculate pIbeta using the equation, pIbeta = Id * sinVal + Iq * cosVal */ - *pIbeta = Id * sinVal + Iq * cosVal; - } - - - /** - * @brief Inverse Park transform for Q31 version - * @param[in] Id input coordinate of rotor reference frame d - * @param[in] Iq input coordinate of rotor reference frame q - * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha - * @param[out] pIbeta points to output two-phase orthogonal vector axis beta - * @param[in] sinVal sine value of rotation angle theta - * @param[in] cosVal cosine value of rotation angle theta - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. - * There is saturation on the addition, hence there is no risk of overflow. - */ - static __INLINE void arm_inv_park_q31( - q31_t Id, - q31_t Iq, - q31_t * pIalpha, - q31_t * pIbeta, - q31_t sinVal, - q31_t cosVal) - { - q31_t product1, product2; /* Temporary variables used to store intermediate results */ - q31_t product3, product4; /* Temporary variables used to store intermediate results */ - - /* Intermediate product is calculated by (Id * cosVal) */ - product1 = (q31_t) (((q63_t) (Id) * (cosVal)) >> 31); - - /* Intermediate product is calculated by (Iq * sinVal) */ - product2 = (q31_t) (((q63_t) (Iq) * (sinVal)) >> 31); - - - /* Intermediate product is calculated by (Id * sinVal) */ - product3 = (q31_t) (((q63_t) (Id) * (sinVal)) >> 31); - - /* Intermediate product is calculated by (Iq * cosVal) */ - product4 = (q31_t) (((q63_t) (Iq) * (cosVal)) >> 31); - - /* Calculate pIalpha by using the two intermediate products 1 and 2 */ - *pIalpha = __QSUB(product1, product2); - - /* Calculate pIbeta by using the two intermediate products 3 and 4 */ - *pIbeta = __QADD(product4, product3); - } - - /** - * @} end of Inverse park group - */ - - - /** - * @brief Converts the elements of the Q31 vector to floating-point vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q31_to_float( - q31_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - /** - * @ingroup groupInterpolation - */ - - /** - * @defgroup LinearInterpolate Linear Interpolation - * - * Linear interpolation is a method of curve fitting using linear polynomials. - * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line - * - * \par - * \image html LinearInterp.gif "Linear interpolation" - * - * \par - * A Linear Interpolate function calculates an output value(y), for the input(x) - * using linear interpolation of the input values x0, x1( nearest input values) and the output values y0 and y1(nearest output values) - * - * \par Algorithm: - *
-   *       y = y0 + (x - x0) * ((y1 - y0)/(x1-x0))
-   *       where x0, x1 are nearest values of input x
-   *             y0, y1 are nearest values to output y
-   * 
- * - * \par - * This set of functions implements Linear interpolation process - * for Q7, Q15, Q31, and floating-point data types. The functions operate on a single - * sample of data and each call to the function returns a single processed value. - * S points to an instance of the Linear Interpolate function data structure. - * x is the input sample value. The functions returns the output value. - * - * \par - * if x is outside of the table boundary, Linear interpolation returns first value of the table - * if x is below input range and returns last value of table if x is above range. - */ - - /** - * @addtogroup LinearInterpolate - * @{ - */ - - /** - * @brief Process function for the floating-point Linear Interpolation Function. - * @param[in,out] S is an instance of the floating-point Linear Interpolation structure - * @param[in] x input sample to process - * @return y processed output sample. - * - */ - static __INLINE float32_t arm_linear_interp_f32( - arm_linear_interp_instance_f32 * S, - float32_t x) - { - float32_t y; - float32_t x0, x1; /* Nearest input values */ - float32_t y0, y1; /* Nearest output values */ - float32_t xSpacing = S->xSpacing; /* spacing between input values */ - int32_t i; /* Index variable */ - float32_t *pYData = S->pYData; /* pointer to output table */ - - /* Calculation of index */ - i = (int32_t) ((x - S->x1) / xSpacing); - - if(i < 0) - { - /* Iniatilize output for below specified range as least output value of table */ - y = pYData[0]; - } - else if((uint32_t)i >= S->nValues) - { - /* Iniatilize output for above specified range as last output value of table */ - y = pYData[S->nValues - 1]; - } - else - { - /* Calculation of nearest input values */ - x0 = S->x1 + i * xSpacing; - x1 = S->x1 + (i + 1) * xSpacing; - - /* Read of nearest output values */ - y0 = pYData[i]; - y1 = pYData[i + 1]; - - /* Calculation of output */ - y = y0 + (x - x0) * ((y1 - y0) / (x1 - x0)); - - } - - /* returns output value */ - return (y); - } - - - /** - * - * @brief Process function for the Q31 Linear Interpolation Function. - * @param[in] pYData pointer to Q31 Linear Interpolation table - * @param[in] x input sample to process - * @param[in] nValues number of table values - * @return y processed output sample. - * - * \par - * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. - * This function can support maximum of table size 2^12. - * - */ - static __INLINE q31_t arm_linear_interp_q31( - q31_t * pYData, - q31_t x, - uint32_t nValues) - { - q31_t y; /* output */ - q31_t y0, y1; /* Nearest output values */ - q31_t fract; /* fractional part */ - int32_t index; /* Index to read nearest output values */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - index = ((x & (q31_t)0xFFF00000) >> 20); - - if(index >= (int32_t)(nValues - 1)) - { - return (pYData[nValues - 1]); - } - else if(index < 0) - { - return (pYData[0]); - } - else - { - /* 20 bits for the fractional part */ - /* shift left by 11 to keep fract in 1.31 format */ - fract = (x & 0x000FFFFF) << 11; - - /* Read two nearest output values from the index in 1.31(q31) format */ - y0 = pYData[index]; - y1 = pYData[index + 1]; - - /* Calculation of y0 * (1-fract) and y is in 2.30 format */ - y = ((q31_t) ((q63_t) y0 * (0x7FFFFFFF - fract) >> 32)); - - /* Calculation of y0 * (1-fract) + y1 *fract and y is in 2.30 format */ - y += ((q31_t) (((q63_t) y1 * fract) >> 32)); - - /* Convert y to 1.31 format */ - return (y << 1u); - } - } - - - /** - * - * @brief Process function for the Q15 Linear Interpolation Function. - * @param[in] pYData pointer to Q15 Linear Interpolation table - * @param[in] x input sample to process - * @param[in] nValues number of table values - * @return y processed output sample. - * - * \par - * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. - * This function can support maximum of table size 2^12. - * - */ - static __INLINE q15_t arm_linear_interp_q15( - q15_t * pYData, - q31_t x, - uint32_t nValues) - { - q63_t y; /* output */ - q15_t y0, y1; /* Nearest output values */ - q31_t fract; /* fractional part */ - int32_t index; /* Index to read nearest output values */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - index = ((x & (int32_t)0xFFF00000) >> 20); - - if(index >= (int32_t)(nValues - 1)) - { - return (pYData[nValues - 1]); - } - else if(index < 0) - { - return (pYData[0]); - } - else - { - /* 20 bits for the fractional part */ - /* fract is in 12.20 format */ - fract = (x & 0x000FFFFF); - - /* Read two nearest output values from the index */ - y0 = pYData[index]; - y1 = pYData[index + 1]; - - /* Calculation of y0 * (1-fract) and y is in 13.35 format */ - y = ((q63_t) y0 * (0xFFFFF - fract)); - - /* Calculation of (y0 * (1-fract) + y1 * fract) and y is in 13.35 format */ - y += ((q63_t) y1 * (fract)); - - /* convert y to 1.15 format */ - return (q15_t) (y >> 20); - } - } - - - /** - * - * @brief Process function for the Q7 Linear Interpolation Function. - * @param[in] pYData pointer to Q7 Linear Interpolation table - * @param[in] x input sample to process - * @param[in] nValues number of table values - * @return y processed output sample. - * - * \par - * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. - * This function can support maximum of table size 2^12. - */ - static __INLINE q7_t arm_linear_interp_q7( - q7_t * pYData, - q31_t x, - uint32_t nValues) - { - q31_t y; /* output */ - q7_t y0, y1; /* Nearest output values */ - q31_t fract; /* fractional part */ - uint32_t index; /* Index to read nearest output values */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - if (x < 0) - { - return (pYData[0]); - } - index = (x >> 20) & 0xfff; - - if(index >= (nValues - 1)) - { - return (pYData[nValues - 1]); - } - else - { - /* 20 bits for the fractional part */ - /* fract is in 12.20 format */ - fract = (x & 0x000FFFFF); - - /* Read two nearest output values from the index and are in 1.7(q7) format */ - y0 = pYData[index]; - y1 = pYData[index + 1]; - - /* Calculation of y0 * (1-fract ) and y is in 13.27(q27) format */ - y = ((y0 * (0xFFFFF - fract))); - - /* Calculation of y1 * fract + y0 * (1-fract) and y is in 13.27(q27) format */ - y += (y1 * fract); - - /* convert y to 1.7(q7) format */ - return (q7_t) (y >> 20); - } - } - - /** - * @} end of LinearInterpolate group - */ - - /** - * @brief Fast approximation to the trigonometric sine function for floating-point data. - * @param[in] x input value in radians. - * @return sin(x). - */ - float32_t arm_sin_f32( - float32_t x); - - - /** - * @brief Fast approximation to the trigonometric sine function for Q31 data. - * @param[in] x Scaled input value in radians. - * @return sin(x). - */ - q31_t arm_sin_q31( - q31_t x); - - - /** - * @brief Fast approximation to the trigonometric sine function for Q15 data. - * @param[in] x Scaled input value in radians. - * @return sin(x). - */ - q15_t arm_sin_q15( - q15_t x); - - - /** - * @brief Fast approximation to the trigonometric cosine function for floating-point data. - * @param[in] x input value in radians. - * @return cos(x). - */ - float32_t arm_cos_f32( - float32_t x); - - - /** - * @brief Fast approximation to the trigonometric cosine function for Q31 data. - * @param[in] x Scaled input value in radians. - * @return cos(x). - */ - q31_t arm_cos_q31( - q31_t x); - - - /** - * @brief Fast approximation to the trigonometric cosine function for Q15 data. - * @param[in] x Scaled input value in radians. - * @return cos(x). - */ - q15_t arm_cos_q15( - q15_t x); - - - /** - * @ingroup groupFastMath - */ - - - /** - * @defgroup SQRT Square Root - * - * Computes the square root of a number. - * There are separate functions for Q15, Q31, and floating-point data types. - * The square root function is computed using the Newton-Raphson algorithm. - * This is an iterative algorithm of the form: - *
-   *      x1 = x0 - f(x0)/f'(x0)
-   * 
- * where x1 is the current estimate, - * x0 is the previous estimate, and - * f'(x0) is the derivative of f() evaluated at x0. - * For the square root function, the algorithm reduces to: - *
-   *     x0 = in/2                         [initial guess]
-   *     x1 = 1/2 * ( x0 + in / x0)        [each iteration]
-   * 
- */ - - - /** - * @addtogroup SQRT - * @{ - */ - - /** - * @brief Floating-point square root function. - * @param[in] in input value. - * @param[out] pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - static __INLINE arm_status arm_sqrt_f32( - float32_t in, - float32_t * pOut) - { - if(in >= 0.0f) - { - -#if (__FPU_USED == 1) && defined ( __CC_ARM ) - *pOut = __sqrtf(in); -#elif (__FPU_USED == 1) && (defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) - *pOut = __builtin_sqrtf(in); -#elif (__FPU_USED == 1) && defined(__GNUC__) - *pOut = __builtin_sqrtf(in); -#elif (__FPU_USED == 1) && defined ( __ICCARM__ ) && (__VER__ >= 6040000) - __ASM("VSQRT.F32 %0,%1" : "=t"(*pOut) : "t"(in)); -#else - *pOut = sqrtf(in); -#endif - - return (ARM_MATH_SUCCESS); - } - else - { - *pOut = 0.0f; - return (ARM_MATH_ARGUMENT_ERROR); - } - } - - - /** - * @brief Q31 square root function. - * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF. - * @param[out] pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - arm_status arm_sqrt_q31( - q31_t in, - q31_t * pOut); - - - /** - * @brief Q15 square root function. - * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF. - * @param[out] pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - arm_status arm_sqrt_q15( - q15_t in, - q15_t * pOut); - - /** - * @} end of SQRT group - */ - - - /** - * @brief floating-point Circular write function. - */ - static __INLINE void arm_circularWrite_f32( - int32_t * circBuffer, - int32_t L, - uint16_t * writeOffset, - int32_t bufferInc, - const int32_t * src, - int32_t srcInc, - uint32_t blockSize) - { - uint32_t i = 0u; - int32_t wOffset; - - /* Copy the value of Index pointer that points - * to the current location where the input samples to be copied */ - wOffset = *writeOffset; - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the input sample to the circular buffer */ - circBuffer[wOffset] = *src; - - /* Update the input pointer */ - src += srcInc; - - /* Circularly update wOffset. Watch out for positive and negative value */ - wOffset += bufferInc; - if(wOffset >= L) - wOffset -= L; - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *writeOffset = (uint16_t)wOffset; - } - - - - /** - * @brief floating-point Circular Read function. - */ - static __INLINE void arm_circularRead_f32( - int32_t * circBuffer, - int32_t L, - int32_t * readOffset, - int32_t bufferInc, - int32_t * dst, - int32_t * dst_base, - int32_t dst_length, - int32_t dstInc, - uint32_t blockSize) - { - uint32_t i = 0u; - int32_t rOffset, dst_end; - - /* Copy the value of Index pointer that points - * to the current location from where the input samples to be read */ - rOffset = *readOffset; - dst_end = (int32_t) (dst_base + dst_length); - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the sample from the circular buffer to the destination buffer */ - *dst = circBuffer[rOffset]; - - /* Update the input pointer */ - dst += dstInc; - - if(dst == (int32_t *) dst_end) - { - dst = dst_base; - } - - /* Circularly update rOffset. Watch out for positive and negative value */ - rOffset += bufferInc; - - if(rOffset >= L) - { - rOffset -= L; - } - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *readOffset = rOffset; - } - - - /** - * @brief Q15 Circular write function. - */ - static __INLINE void arm_circularWrite_q15( - q15_t * circBuffer, - int32_t L, - uint16_t * writeOffset, - int32_t bufferInc, - const q15_t * src, - int32_t srcInc, - uint32_t blockSize) - { - uint32_t i = 0u; - int32_t wOffset; - - /* Copy the value of Index pointer that points - * to the current location where the input samples to be copied */ - wOffset = *writeOffset; - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the input sample to the circular buffer */ - circBuffer[wOffset] = *src; - - /* Update the input pointer */ - src += srcInc; - - /* Circularly update wOffset. Watch out for positive and negative value */ - wOffset += bufferInc; - if(wOffset >= L) - wOffset -= L; - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *writeOffset = (uint16_t)wOffset; - } - - - /** - * @brief Q15 Circular Read function. - */ - static __INLINE void arm_circularRead_q15( - q15_t * circBuffer, - int32_t L, - int32_t * readOffset, - int32_t bufferInc, - q15_t * dst, - q15_t * dst_base, - int32_t dst_length, - int32_t dstInc, - uint32_t blockSize) - { - uint32_t i = 0; - int32_t rOffset, dst_end; - - /* Copy the value of Index pointer that points - * to the current location from where the input samples to be read */ - rOffset = *readOffset; - - dst_end = (int32_t) (dst_base + dst_length); - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the sample from the circular buffer to the destination buffer */ - *dst = circBuffer[rOffset]; - - /* Update the input pointer */ - dst += dstInc; - - if(dst == (q15_t *) dst_end) - { - dst = dst_base; - } - - /* Circularly update wOffset. Watch out for positive and negative value */ - rOffset += bufferInc; - - if(rOffset >= L) - { - rOffset -= L; - } - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *readOffset = rOffset; - } - - - /** - * @brief Q7 Circular write function. - */ - static __INLINE void arm_circularWrite_q7( - q7_t * circBuffer, - int32_t L, - uint16_t * writeOffset, - int32_t bufferInc, - const q7_t * src, - int32_t srcInc, - uint32_t blockSize) - { - uint32_t i = 0u; - int32_t wOffset; - - /* Copy the value of Index pointer that points - * to the current location where the input samples to be copied */ - wOffset = *writeOffset; - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the input sample to the circular buffer */ - circBuffer[wOffset] = *src; - - /* Update the input pointer */ - src += srcInc; - - /* Circularly update wOffset. Watch out for positive and negative value */ - wOffset += bufferInc; - if(wOffset >= L) - wOffset -= L; - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *writeOffset = (uint16_t)wOffset; - } - - - /** - * @brief Q7 Circular Read function. - */ - static __INLINE void arm_circularRead_q7( - q7_t * circBuffer, - int32_t L, - int32_t * readOffset, - int32_t bufferInc, - q7_t * dst, - q7_t * dst_base, - int32_t dst_length, - int32_t dstInc, - uint32_t blockSize) - { - uint32_t i = 0; - int32_t rOffset, dst_end; - - /* Copy the value of Index pointer that points - * to the current location from where the input samples to be read */ - rOffset = *readOffset; - - dst_end = (int32_t) (dst_base + dst_length); - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the sample from the circular buffer to the destination buffer */ - *dst = circBuffer[rOffset]; - - /* Update the input pointer */ - dst += dstInc; - - if(dst == (q7_t *) dst_end) - { - dst = dst_base; - } - - /* Circularly update rOffset. Watch out for positive and negative value */ - rOffset += bufferInc; - - if(rOffset >= L) - { - rOffset -= L; - } - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *readOffset = rOffset; - } - - - /** - * @brief Sum of the squares of the elements of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_power_q31( - q31_t * pSrc, - uint32_t blockSize, - q63_t * pResult); - - - /** - * @brief Sum of the squares of the elements of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_power_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Sum of the squares of the elements of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_power_q15( - q15_t * pSrc, - uint32_t blockSize, - q63_t * pResult); - - - /** - * @brief Sum of the squares of the elements of a Q7 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_power_q7( - q7_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Mean value of a Q7 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_mean_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult); - - - /** - * @brief Mean value of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_mean_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult); - - - /** - * @brief Mean value of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_mean_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Mean value of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_mean_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Variance of the elements of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_var_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Variance of the elements of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_var_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Variance of the elements of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_var_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult); - - - /** - * @brief Root Mean Square of the elements of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_rms_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Root Mean Square of the elements of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_rms_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Root Mean Square of the elements of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_rms_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult); - - - /** - * @brief Standard deviation of the elements of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_std_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Standard deviation of the elements of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_std_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Standard deviation of the elements of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_std_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult); - - - /** - * @brief Floating-point complex magnitude - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q31 complex magnitude - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q15 complex magnitude - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q15 complex dot product - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] numSamples number of complex samples in each vector - * @param[out] realResult real part of the result returned here - * @param[out] imagResult imaginary part of the result returned here - */ - void arm_cmplx_dot_prod_q15( - q15_t * pSrcA, - q15_t * pSrcB, - uint32_t numSamples, - q31_t * realResult, - q31_t * imagResult); - - - /** - * @brief Q31 complex dot product - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] numSamples number of complex samples in each vector - * @param[out] realResult real part of the result returned here - * @param[out] imagResult imaginary part of the result returned here - */ - void arm_cmplx_dot_prod_q31( - q31_t * pSrcA, - q31_t * pSrcB, - uint32_t numSamples, - q63_t * realResult, - q63_t * imagResult); - - - /** - * @brief Floating-point complex dot product - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] numSamples number of complex samples in each vector - * @param[out] realResult real part of the result returned here - * @param[out] imagResult imaginary part of the result returned here - */ - void arm_cmplx_dot_prod_f32( - float32_t * pSrcA, - float32_t * pSrcB, - uint32_t numSamples, - float32_t * realResult, - float32_t * imagResult); - - - /** - * @brief Q15 complex-by-real multiplication - * @param[in] pSrcCmplx points to the complex input vector - * @param[in] pSrcReal points to the real input vector - * @param[out] pCmplxDst points to the complex output vector - * @param[in] numSamples number of samples in each vector - */ - void arm_cmplx_mult_real_q15( - q15_t * pSrcCmplx, - q15_t * pSrcReal, - q15_t * pCmplxDst, - uint32_t numSamples); - - - /** - * @brief Q31 complex-by-real multiplication - * @param[in] pSrcCmplx points to the complex input vector - * @param[in] pSrcReal points to the real input vector - * @param[out] pCmplxDst points to the complex output vector - * @param[in] numSamples number of samples in each vector - */ - void arm_cmplx_mult_real_q31( - q31_t * pSrcCmplx, - q31_t * pSrcReal, - q31_t * pCmplxDst, - uint32_t numSamples); - - - /** - * @brief Floating-point complex-by-real multiplication - * @param[in] pSrcCmplx points to the complex input vector - * @param[in] pSrcReal points to the real input vector - * @param[out] pCmplxDst points to the complex output vector - * @param[in] numSamples number of samples in each vector - */ - void arm_cmplx_mult_real_f32( - float32_t * pSrcCmplx, - float32_t * pSrcReal, - float32_t * pCmplxDst, - uint32_t numSamples); - - - /** - * @brief Minimum value of a Q7 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] result is output pointer - * @param[in] index is the array index of the minimum value in the input buffer. - */ - void arm_min_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * result, - uint32_t * index); - - - /** - * @brief Minimum value of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output pointer - * @param[in] pIndex is the array index of the minimum value in the input buffer. - */ - void arm_min_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult, - uint32_t * pIndex); - - - /** - * @brief Minimum value of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output pointer - * @param[out] pIndex is the array index of the minimum value in the input buffer. - */ - void arm_min_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult, - uint32_t * pIndex); - - - /** - * @brief Minimum value of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output pointer - * @param[out] pIndex is the array index of the minimum value in the input buffer. - */ - void arm_min_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult, - uint32_t * pIndex); - - -/** - * @brief Maximum value of a Q7 vector. - * @param[in] pSrc points to the input buffer - * @param[in] blockSize length of the input vector - * @param[out] pResult maximum value returned here - * @param[out] pIndex index of maximum value returned here - */ - void arm_max_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult, - uint32_t * pIndex); - - -/** - * @brief Maximum value of a Q15 vector. - * @param[in] pSrc points to the input buffer - * @param[in] blockSize length of the input vector - * @param[out] pResult maximum value returned here - * @param[out] pIndex index of maximum value returned here - */ - void arm_max_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult, - uint32_t * pIndex); - - -/** - * @brief Maximum value of a Q31 vector. - * @param[in] pSrc points to the input buffer - * @param[in] blockSize length of the input vector - * @param[out] pResult maximum value returned here - * @param[out] pIndex index of maximum value returned here - */ - void arm_max_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult, - uint32_t * pIndex); - - -/** - * @brief Maximum value of a floating-point vector. - * @param[in] pSrc points to the input buffer - * @param[in] blockSize length of the input vector - * @param[out] pResult maximum value returned here - * @param[out] pIndex index of maximum value returned here - */ - void arm_max_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult, - uint32_t * pIndex); - - - /** - * @brief Q15 complex-by-complex multiplication - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_mult_cmplx_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q31 complex-by-complex multiplication - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_mult_cmplx_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t numSamples); - - - /** - * @brief Floating-point complex-by-complex multiplication - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_mult_cmplx_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t numSamples); - - - /** - * @brief Converts the elements of the floating-point vector to Q31 vector. - * @param[in] pSrc points to the floating-point input vector - * @param[out] pDst points to the Q31 output vector - * @param[in] blockSize length of the input vector - */ - void arm_float_to_q31( - float32_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the floating-point vector to Q15 vector. - * @param[in] pSrc points to the floating-point input vector - * @param[out] pDst points to the Q15 output vector - * @param[in] blockSize length of the input vector - */ - void arm_float_to_q15( - float32_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the floating-point vector to Q7 vector. - * @param[in] pSrc points to the floating-point input vector - * @param[out] pDst points to the Q7 output vector - * @param[in] blockSize length of the input vector - */ - void arm_float_to_q7( - float32_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q31 vector to Q15 vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q31_to_q15( - q31_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q31 vector to Q7 vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q31_to_q7( - q31_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q15 vector to floating-point vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q15_to_float( - q15_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q15 vector to Q31 vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q15_to_q31( - q15_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q15 vector to Q7 vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q15_to_q7( - q15_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @ingroup groupInterpolation - */ - - /** - * @defgroup BilinearInterpolate Bilinear Interpolation - * - * Bilinear interpolation is an extension of linear interpolation applied to a two dimensional grid. - * The underlying function f(x, y) is sampled on a regular grid and the interpolation process - * determines values between the grid points. - * Bilinear interpolation is equivalent to two step linear interpolation, first in the x-dimension and then in the y-dimension. - * Bilinear interpolation is often used in image processing to rescale images. - * The CMSIS DSP library provides bilinear interpolation functions for Q7, Q15, Q31, and floating-point data types. - * - * Algorithm - * \par - * The instance structure used by the bilinear interpolation functions describes a two dimensional data table. - * For floating-point, the instance structure is defined as: - *
-   *   typedef struct
-   *   {
-   *     uint16_t numRows;
-   *     uint16_t numCols;
-   *     float32_t *pData;
-   * } arm_bilinear_interp_instance_f32;
-   * 
- * - * \par - * where numRows specifies the number of rows in the table; - * numCols specifies the number of columns in the table; - * and pData points to an array of size numRows*numCols values. - * The data table pTable is organized in row order and the supplied data values fall on integer indexes. - * That is, table element (x,y) is located at pTable[x + y*numCols] where x and y are integers. - * - * \par - * Let (x, y) specify the desired interpolation point. Then define: - *
-   *     XF = floor(x)
-   *     YF = floor(y)
-   * 
- * \par - * The interpolated output point is computed as: - *
-   *  f(x, y) = f(XF, YF) * (1-(x-XF)) * (1-(y-YF))
-   *           + f(XF+1, YF) * (x-XF)*(1-(y-YF))
-   *           + f(XF, YF+1) * (1-(x-XF))*(y-YF)
-   *           + f(XF+1, YF+1) * (x-XF)*(y-YF)
-   * 
- * Note that the coordinates (x, y) contain integer and fractional components. - * The integer components specify which portion of the table to use while the - * fractional components control the interpolation processor. - * - * \par - * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output. - */ - - /** - * @addtogroup BilinearInterpolate - * @{ - */ - - - /** - * - * @brief Floating-point bilinear interpolation. - * @param[in,out] S points to an instance of the interpolation structure. - * @param[in] X interpolation coordinate. - * @param[in] Y interpolation coordinate. - * @return out interpolated value. - */ - static __INLINE float32_t arm_bilinear_interp_f32( - const arm_bilinear_interp_instance_f32 * S, - float32_t X, - float32_t Y) - { - float32_t out; - float32_t f00, f01, f10, f11; - float32_t *pData = S->pData; - int32_t xIndex, yIndex, index; - float32_t xdiff, ydiff; - float32_t b1, b2, b3, b4; - - xIndex = (int32_t) X; - yIndex = (int32_t) Y; - - /* Care taken for table outside boundary */ - /* Returns zero output when values are outside table boundary */ - if(xIndex < 0 || xIndex > (S->numRows - 1) || yIndex < 0 || yIndex > (S->numCols - 1)) - { - return (0); - } - - /* Calculation of index for two nearest points in X-direction */ - index = (xIndex - 1) + (yIndex - 1) * S->numCols; - - - /* Read two nearest points in X-direction */ - f00 = pData[index]; - f01 = pData[index + 1]; - - /* Calculation of index for two nearest points in Y-direction */ - index = (xIndex - 1) + (yIndex) * S->numCols; - - - /* Read two nearest points in Y-direction */ - f10 = pData[index]; - f11 = pData[index + 1]; - - /* Calculation of intermediate values */ - b1 = f00; - b2 = f01 - f00; - b3 = f10 - f00; - b4 = f00 - f01 - f10 + f11; - - /* Calculation of fractional part in X */ - xdiff = X - xIndex; - - /* Calculation of fractional part in Y */ - ydiff = Y - yIndex; - - /* Calculation of bi-linear interpolated output */ - out = b1 + b2 * xdiff + b3 * ydiff + b4 * xdiff * ydiff; - - /* return to application */ - return (out); - } - - - /** - * - * @brief Q31 bilinear interpolation. - * @param[in,out] S points to an instance of the interpolation structure. - * @param[in] X interpolation coordinate in 12.20 format. - * @param[in] Y interpolation coordinate in 12.20 format. - * @return out interpolated value. - */ - static __INLINE q31_t arm_bilinear_interp_q31( - arm_bilinear_interp_instance_q31 * S, - q31_t X, - q31_t Y) - { - q31_t out; /* Temporary output */ - q31_t acc = 0; /* output */ - q31_t xfract, yfract; /* X, Y fractional parts */ - q31_t x1, x2, y1, y2; /* Nearest output values */ - int32_t rI, cI; /* Row and column indices */ - q31_t *pYData = S->pData; /* pointer to output table values */ - uint32_t nCols = S->numCols; /* num of rows */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - rI = ((X & (q31_t)0xFFF00000) >> 20); - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - cI = ((Y & (q31_t)0xFFF00000) >> 20); - - /* Care taken for table outside boundary */ - /* Returns zero output when values are outside table boundary */ - if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1)) - { - return (0); - } - - /* 20 bits for the fractional part */ - /* shift left xfract by 11 to keep 1.31 format */ - xfract = (X & 0x000FFFFF) << 11u; - - /* Read two nearest output values from the index */ - x1 = pYData[(rI) + (int32_t)nCols * (cI) ]; - x2 = pYData[(rI) + (int32_t)nCols * (cI) + 1]; - - /* 20 bits for the fractional part */ - /* shift left yfract by 11 to keep 1.31 format */ - yfract = (Y & 0x000FFFFF) << 11u; - - /* Read two nearest output values from the index */ - y1 = pYData[(rI) + (int32_t)nCols * (cI + 1) ]; - y2 = pYData[(rI) + (int32_t)nCols * (cI + 1) + 1]; - - /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 3.29(q29) format */ - out = ((q31_t) (((q63_t) x1 * (0x7FFFFFFF - xfract)) >> 32)); - acc = ((q31_t) (((q63_t) out * (0x7FFFFFFF - yfract)) >> 32)); - - /* x2 * (xfract) * (1-yfract) in 3.29(q29) and adding to acc */ - out = ((q31_t) ((q63_t) x2 * (0x7FFFFFFF - yfract) >> 32)); - acc += ((q31_t) ((q63_t) out * (xfract) >> 32)); - - /* y1 * (1 - xfract) * (yfract) in 3.29(q29) and adding to acc */ - out = ((q31_t) ((q63_t) y1 * (0x7FFFFFFF - xfract) >> 32)); - acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); - - /* y2 * (xfract) * (yfract) in 3.29(q29) and adding to acc */ - out = ((q31_t) ((q63_t) y2 * (xfract) >> 32)); - acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); - - /* Convert acc to 1.31(q31) format */ - return ((q31_t)(acc << 2)); - } - - - /** - * @brief Q15 bilinear interpolation. - * @param[in,out] S points to an instance of the interpolation structure. - * @param[in] X interpolation coordinate in 12.20 format. - * @param[in] Y interpolation coordinate in 12.20 format. - * @return out interpolated value. - */ - static __INLINE q15_t arm_bilinear_interp_q15( - arm_bilinear_interp_instance_q15 * S, - q31_t X, - q31_t Y) - { - q63_t acc = 0; /* output */ - q31_t out; /* Temporary output */ - q15_t x1, x2, y1, y2; /* Nearest output values */ - q31_t xfract, yfract; /* X, Y fractional parts */ - int32_t rI, cI; /* Row and column indices */ - q15_t *pYData = S->pData; /* pointer to output table values */ - uint32_t nCols = S->numCols; /* num of rows */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - rI = ((X & (q31_t)0xFFF00000) >> 20); - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - cI = ((Y & (q31_t)0xFFF00000) >> 20); - - /* Care taken for table outside boundary */ - /* Returns zero output when values are outside table boundary */ - if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1)) - { - return (0); - } - - /* 20 bits for the fractional part */ - /* xfract should be in 12.20 format */ - xfract = (X & 0x000FFFFF); - - /* Read two nearest output values from the index */ - x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ]; - x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1]; - - /* 20 bits for the fractional part */ - /* yfract should be in 12.20 format */ - yfract = (Y & 0x000FFFFF); - - /* Read two nearest output values from the index */ - y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ]; - y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1]; - - /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 13.51 format */ - - /* x1 is in 1.15(q15), xfract in 12.20 format and out is in 13.35 format */ - /* convert 13.35 to 13.31 by right shifting and out is in 1.31 */ - out = (q31_t) (((q63_t) x1 * (0xFFFFF - xfract)) >> 4u); - acc = ((q63_t) out * (0xFFFFF - yfract)); - - /* x2 * (xfract) * (1-yfract) in 1.51 and adding to acc */ - out = (q31_t) (((q63_t) x2 * (0xFFFFF - yfract)) >> 4u); - acc += ((q63_t) out * (xfract)); - - /* y1 * (1 - xfract) * (yfract) in 1.51 and adding to acc */ - out = (q31_t) (((q63_t) y1 * (0xFFFFF - xfract)) >> 4u); - acc += ((q63_t) out * (yfract)); - - /* y2 * (xfract) * (yfract) in 1.51 and adding to acc */ - out = (q31_t) (((q63_t) y2 * (xfract)) >> 4u); - acc += ((q63_t) out * (yfract)); - - /* acc is in 13.51 format and down shift acc by 36 times */ - /* Convert out to 1.15 format */ - return ((q15_t)(acc >> 36)); - } - - - /** - * @brief Q7 bilinear interpolation. - * @param[in,out] S points to an instance of the interpolation structure. - * @param[in] X interpolation coordinate in 12.20 format. - * @param[in] Y interpolation coordinate in 12.20 format. - * @return out interpolated value. - */ - static __INLINE q7_t arm_bilinear_interp_q7( - arm_bilinear_interp_instance_q7 * S, - q31_t X, - q31_t Y) - { - q63_t acc = 0; /* output */ - q31_t out; /* Temporary output */ - q31_t xfract, yfract; /* X, Y fractional parts */ - q7_t x1, x2, y1, y2; /* Nearest output values */ - int32_t rI, cI; /* Row and column indices */ - q7_t *pYData = S->pData; /* pointer to output table values */ - uint32_t nCols = S->numCols; /* num of rows */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - rI = ((X & (q31_t)0xFFF00000) >> 20); - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - cI = ((Y & (q31_t)0xFFF00000) >> 20); - - /* Care taken for table outside boundary */ - /* Returns zero output when values are outside table boundary */ - if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1)) - { - return (0); - } - - /* 20 bits for the fractional part */ - /* xfract should be in 12.20 format */ - xfract = (X & (q31_t)0x000FFFFF); - - /* Read two nearest output values from the index */ - x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ]; - x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1]; - - /* 20 bits for the fractional part */ - /* yfract should be in 12.20 format */ - yfract = (Y & (q31_t)0x000FFFFF); - - /* Read two nearest output values from the index */ - y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ]; - y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1]; - - /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 16.47 format */ - out = ((x1 * (0xFFFFF - xfract))); - acc = (((q63_t) out * (0xFFFFF - yfract))); - - /* x2 * (xfract) * (1-yfract) in 2.22 and adding to acc */ - out = ((x2 * (0xFFFFF - yfract))); - acc += (((q63_t) out * (xfract))); - - /* y1 * (1 - xfract) * (yfract) in 2.22 and adding to acc */ - out = ((y1 * (0xFFFFF - xfract))); - acc += (((q63_t) out * (yfract))); - - /* y2 * (xfract) * (yfract) in 2.22 and adding to acc */ - out = ((y2 * (yfract))); - acc += (((q63_t) out * (xfract))); - - /* acc in 16.47 format and down shift by 40 to convert to 1.7 format */ - return ((q7_t)(acc >> 40)); - } - - /** - * @} end of BilinearInterpolate group - */ - - -/* SMMLAR */ -#define multAcc_32x32_keep32_R(a, x, y) \ - a = (q31_t) (((((q63_t) a) << 32) + ((q63_t) x * y) + 0x80000000LL ) >> 32) - -/* SMMLSR */ -#define multSub_32x32_keep32_R(a, x, y) \ - a = (q31_t) (((((q63_t) a) << 32) - ((q63_t) x * y) + 0x80000000LL ) >> 32) - -/* SMMULR */ -#define mult_32x32_keep32_R(a, x, y) \ - a = (q31_t) (((q63_t) x * y + 0x80000000LL ) >> 32) - -/* SMMLA */ -#define multAcc_32x32_keep32(a, x, y) \ - a += (q31_t) (((q63_t) x * y) >> 32) - -/* SMMLS */ -#define multSub_32x32_keep32(a, x, y) \ - a -= (q31_t) (((q63_t) x * y) >> 32) - -/* SMMUL */ -#define mult_32x32_keep32(a, x, y) \ - a = (q31_t) (((q63_t) x * y ) >> 32) - - -#if defined ( __CC_ARM ) - /* Enter low optimization region - place directly above function definition */ - #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7) - #define LOW_OPTIMIZATION_ENTER \ - _Pragma ("push") \ - _Pragma ("O1") - #else - #define LOW_OPTIMIZATION_ENTER - #endif - - /* Exit low optimization region - place directly after end of function definition */ - #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7) - #define LOW_OPTIMIZATION_EXIT \ - _Pragma ("pop") - #else - #define LOW_OPTIMIZATION_EXIT - #endif - - /* Enter low optimization region - place directly above function definition */ - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - - /* Exit low optimization region - place directly after end of function definition */ - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #define LOW_OPTIMIZATION_ENTER - #define LOW_OPTIMIZATION_EXIT - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__GNUC__) - #define LOW_OPTIMIZATION_ENTER __attribute__(( optimize("-O1") )) - #define LOW_OPTIMIZATION_EXIT - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__ICCARM__) - /* Enter low optimization region - place directly above function definition */ - #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7) - #define LOW_OPTIMIZATION_ENTER \ - _Pragma ("optimize=low") - #else - #define LOW_OPTIMIZATION_ENTER - #endif - - /* Exit low optimization region - place directly after end of function definition */ - #define LOW_OPTIMIZATION_EXIT - - /* Enter low optimization region - place directly above function definition */ - #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7) - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER \ - _Pragma ("optimize=low") - #else - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #endif - - /* Exit low optimization region - place directly after end of function definition */ - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__CSMC__) - #define LOW_OPTIMIZATION_ENTER - #define LOW_OPTIMIZATION_EXIT - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__TASKING__) - #define LOW_OPTIMIZATION_ENTER - #define LOW_OPTIMIZATION_EXIT - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#endif - - -#ifdef __cplusplus -} -#endif - - -#if defined ( __GNUC__ ) -#pragma GCC diagnostic pop -#endif - -#endif /* _ARM_MATH_H */ - -/** - * - * End of file. - */ diff --git a/body/board/inc/cmsis_armcc.h b/body/board/inc/cmsis_armcc.h deleted file mode 100644 index 4d9d0645d3f7479..000000000000000 --- a/body/board/inc/cmsis_armcc.h +++ /dev/null @@ -1,865 +0,0 @@ -/**************************************************************************//** - * @file cmsis_armcc.h - * @brief CMSIS compiler ARMCC (Arm Compiler 5) header file - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_ARMCC_H -#define __CMSIS_ARMCC_H - - -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 400677) - #error "Please use Arm Compiler Toolchain V4.0.677 or later!" -#endif - -/* CMSIS compiler control architecture macros */ -#if ((defined (__TARGET_ARCH_6_M ) && (__TARGET_ARCH_6_M == 1)) || \ - (defined (__TARGET_ARCH_6S_M ) && (__TARGET_ARCH_6S_M == 1)) ) - #define __ARM_ARCH_6M__ 1 -#endif - -#if (defined (__TARGET_ARCH_7_M ) && (__TARGET_ARCH_7_M == 1)) - #define __ARM_ARCH_7M__ 1 -#endif - -#if (defined (__TARGET_ARCH_7E_M) && (__TARGET_ARCH_7E_M == 1)) - #define __ARM_ARCH_7EM__ 1 -#endif - - /* __ARM_ARCH_8M_BASE__ not applicable */ - /* __ARM_ARCH_8M_MAIN__ not applicable */ - - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE __inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static __inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE static __forceinline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __declspec(noreturn) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed)) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT __packed struct -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION __packed union -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #define __UNALIGNED_UINT32(x) (*((__packed uint32_t *)(x))) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #define __UNALIGNED_UINT16_WRITE(addr, val) ((*((__packed uint16_t *)(addr))) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #define __UNALIGNED_UINT16_READ(addr) (*((const __packed uint16_t *)(addr))) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #define __UNALIGNED_UINT32_WRITE(addr, val) ((*((__packed uint32_t *)(addr))) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #define __UNALIGNED_UINT32_READ(addr) (*((const __packed uint32_t *)(addr))) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __enable_irq(); */ - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __disable_irq(); */ - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_INLINE uint32_t __get_CONTROL(void) -{ - register uint32_t __regControl __ASM("control"); - return(__regControl); -} - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_INLINE void __set_CONTROL(uint32_t control) -{ - register uint32_t __regControl __ASM("control"); - __regControl = control; -} - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_INLINE uint32_t __get_IPSR(void) -{ - register uint32_t __regIPSR __ASM("ipsr"); - return(__regIPSR); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_INLINE uint32_t __get_APSR(void) -{ - register uint32_t __regAPSR __ASM("apsr"); - return(__regAPSR); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_INLINE uint32_t __get_xPSR(void) -{ - register uint32_t __regXPSR __ASM("xpsr"); - return(__regXPSR); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_INLINE uint32_t __get_PSP(void) -{ - register uint32_t __regProcessStackPointer __ASM("psp"); - return(__regProcessStackPointer); -} - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) -{ - register uint32_t __regProcessStackPointer __ASM("psp"); - __regProcessStackPointer = topOfProcStack; -} - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_INLINE uint32_t __get_MSP(void) -{ - register uint32_t __regMainStackPointer __ASM("msp"); - return(__regMainStackPointer); -} - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) -{ - register uint32_t __regMainStackPointer __ASM("msp"); - __regMainStackPointer = topOfMainStack; -} - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_INLINE uint32_t __get_PRIMASK(void) -{ - register uint32_t __regPriMask __ASM("primask"); - return(__regPriMask); -} - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_INLINE void __set_PRIMASK(uint32_t priMask) -{ - register uint32_t __regPriMask __ASM("primask"); - __regPriMask = (priMask); -} - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __enable_fault_irq __enable_fiq - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __disable_fault_irq __disable_fiq - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_INLINE uint32_t __get_BASEPRI(void) -{ - register uint32_t __regBasePri __ASM("basepri"); - return(__regBasePri); -} - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_INLINE void __set_BASEPRI(uint32_t basePri) -{ - register uint32_t __regBasePri __ASM("basepri"); - __regBasePri = (basePri & 0xFFU); -} - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_INLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - register uint32_t __regBasePriMax __ASM("basepri_max"); - __regBasePriMax = (basePri & 0xFFU); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_INLINE uint32_t __get_FAULTMASK(void) -{ - register uint32_t __regFaultMask __ASM("faultmask"); - return(__regFaultMask); -} - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) -{ - register uint32_t __regFaultMask __ASM("faultmask"); - __regFaultMask = (faultMask & (uint32_t)1U); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_INLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) - register uint32_t __regfpscr __ASM("fpscr"); - return(__regfpscr); -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_INLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) - register uint32_t __regfpscr __ASM("fpscr"); - __regfpscr = (fpscr); -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __nop - - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI __wfi - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __wfe - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __sev - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -#define __ISB() do {\ - __schedule_barrier();\ - __isb(0xF);\ - __schedule_barrier();\ - } while (0U) - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() do {\ - __schedule_barrier();\ - __dsb(0xF);\ - __schedule_barrier();\ - } while (0U) - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() do {\ - __schedule_barrier();\ - __dmb(0xF);\ - __schedule_barrier();\ - } while (0U) - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV __rev - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) -{ - rev16 r0, r0 - bx lr -} -#endif - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int16_t __REVSH(int16_t value) -{ - revsh r0, r0 - bx lr -} -#endif - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -#define __ROR __ror - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __breakpoint(value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - #define __RBIT __rbit -#else -__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ - return result; -} -#endif - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ __clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) -#else - #define __LDREXB(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint8_t ) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) -#else - #define __LDREXH(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint16_t) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) -#else - #define __LDREXW(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint32_t ) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXB(value, ptr) __strex(value, ptr) -#else - #define __STREXB(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXH(value, ptr) __strex(value, ptr) -#else - #define __STREXH(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXW(value, ptr) __strex(value, ptr) -#else - #define __STREXW(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -#define __CLREX __clrex - - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT __ssat - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __usat - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) -{ - rrx r0, r0 - bx lr -} -#endif - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRBT(value, ptr) __strt(value, ptr) - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRHT(value, ptr) __strt(value, ptr) - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRT(value, ptr) __strt(value, ptr) - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__attribute__((always_inline)) __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - -#define __SADD8 __sadd8 -#define __QADD8 __qadd8 -#define __SHADD8 __shadd8 -#define __UADD8 __uadd8 -#define __UQADD8 __uqadd8 -#define __UHADD8 __uhadd8 -#define __SSUB8 __ssub8 -#define __QSUB8 __qsub8 -#define __SHSUB8 __shsub8 -#define __USUB8 __usub8 -#define __UQSUB8 __uqsub8 -#define __UHSUB8 __uhsub8 -#define __SADD16 __sadd16 -#define __QADD16 __qadd16 -#define __SHADD16 __shadd16 -#define __UADD16 __uadd16 -#define __UQADD16 __uqadd16 -#define __UHADD16 __uhadd16 -#define __SSUB16 __ssub16 -#define __QSUB16 __qsub16 -#define __SHSUB16 __shsub16 -#define __USUB16 __usub16 -#define __UQSUB16 __uqsub16 -#define __UHSUB16 __uhsub16 -#define __SASX __sasx -#define __QASX __qasx -#define __SHASX __shasx -#define __UASX __uasx -#define __UQASX __uqasx -#define __UHASX __uhasx -#define __SSAX __ssax -#define __QSAX __qsax -#define __SHSAX __shsax -#define __USAX __usax -#define __UQSAX __uqsax -#define __UHSAX __uhsax -#define __USAD8 __usad8 -#define __USADA8 __usada8 -#define __SSAT16 __ssat16 -#define __USAT16 __usat16 -#define __UXTB16 __uxtb16 -#define __UXTAB16 __uxtab16 -#define __SXTB16 __sxtb16 -#define __SXTAB16 __sxtab16 -#define __SMUAD __smuad -#define __SMUADX __smuadx -#define __SMLAD __smlad -#define __SMLADX __smladx -#define __SMLALD __smlald -#define __SMLALDX __smlaldx -#define __SMUSD __smusd -#define __SMUSDX __smusdx -#define __SMLSD __smlsd -#define __SMLSDX __smlsdx -#define __SMLSLD __smlsld -#define __SMLSLDX __smlsldx -#define __SEL __sel -#define __QADD __qadd -#define __QSUB __qsub - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \ - ((int64_t)(ARG3) << 32U) ) >> 32U)) - -#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#endif /* __CMSIS_ARMCC_H */ diff --git a/body/board/inc/cmsis_armcc_V6.h b/body/board/inc/cmsis_armcc_V6.h deleted file mode 100644 index cd13240ce360250..000000000000000 --- a/body/board/inc/cmsis_armcc_V6.h +++ /dev/null @@ -1,1800 +0,0 @@ -/**************************************************************************//** - * @file cmsis_armcc_V6.h - * @brief CMSIS Cortex-M Core Function/Instruction Header File - * @version V4.30 - * @date 20. October 2015 - ******************************************************************************/ -/* Copyright (c) 2009 - 2015 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - 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. - - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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. - ---------------------------------------------------------------------------*/ - - -#ifndef __CMSIS_ARMCC_V6_H -#define __CMSIS_ARMCC_V6_H - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__((always_inline)) __STATIC_INLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__((always_inline)) __STATIC_INLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get IPSR Register (non-secure) - \details Returns the content of the non-secure IPSR Register when in secure state. - \return IPSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_IPSR_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get APSR Register (non-secure) - \details Returns the content of the non-secure APSR Register when in secure state. - \return APSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_APSR_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get xPSR Register (non-secure) - \details Returns the content of the non-secure xPSR Register when in secure state. - \return xPSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_xPSR_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PSP(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_PSP_NS(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : "sp"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : "sp"); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_MSP(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_MSP_NS(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : "sp"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : "sp"); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) /* ToDo: ARMCC_V6: check if this is ok for cortex >=3 */ - -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__((always_inline)) __STATIC_INLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__((always_inline)) __STATIC_INLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_BASEPRI(uint32_t value) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_BASEPRI_NS(uint32_t value) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (value) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_BASEPRI_MAX(uint32_t value) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (value) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Base Priority with condition (non_secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_BASEPRI_MAX_NS(uint32_t value) -{ - __ASM volatile ("MSR basepri_max_ns, %0" : : "r" (value) : "memory"); -} -#endif - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - - -#endif /* ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_8M__ == 1U)) */ - - -#if (__ARM_ARCH_8M__ == 1U) - -/** - \brief Get Process Stack Pointer Limit - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PSPLIM(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) && (__ARM_ARCH_PROFILE == 'M') /* ToDo: ARMCC_V6: check predefined macro for mainline */ -/** - \brief Get Process Stack Pointer Limit (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -} - - -#if (__ARM_FEATURE_CMSE == 3U) && (__ARM_ARCH_PROFILE == 'M') /* ToDo: ARMCC_V6: check predefined macro for mainline */ -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_MSPLIM(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) && (__ARM_ARCH_PROFILE == 'M') /* ToDo: ARMCC_V6: check predefined macro for mainline */ -/** - \brief Get Main Stack Pointer Limit (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -} - - -#if (__ARM_FEATURE_CMSE == 3U) && (__ARM_ARCH_PROFILE == 'M') /* ToDo: ARMCC_V6: check predefined macro for mainline */ -/** - \brief Set Main Stack Pointer Limit (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -} -#endif - -#endif /* (__ARM_ARCH_8M__ == 1U) */ - - -#if ((__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) /* ToDo: ARMCC_V6: check if this is ok for cortex >=4 */ - -/** - \brief Get FPSCR - \details eturns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -#define __get_FPSCR __builtin_arm_get_fpscr -#if 0 -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_FPSCR(void) -{ -#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) - uint32_t result; - - __ASM volatile (""); /* Empty asm statement works as a scheduling barrier */ - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - __ASM volatile (""); - return(result); -#else - return(0); -#endif -} -#endif - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get FPSCR (non-secure) - \details Returns the current value of the non-secure Floating Point Status/Control register when in secure state. - \return Floating Point Status/Control register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_FPSCR_NS(void) -{ -#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) - uint32_t result; - - __ASM volatile (""); /* Empty asm statement works as a scheduling barrier */ - __ASM volatile ("VMRS %0, fpscr_ns" : "=r" (result) ); - __ASM volatile (""); - return(result); -#else - return(0); -#endif -} -#endif - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -#define __set_FPSCR __builtin_arm_set_fpscr -#if 0 -__attribute__((always_inline)) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) -{ -#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) - __ASM volatile (""); /* Empty asm statement works as a scheduling barrier */ - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc"); - __ASM volatile (""); -#endif -} -#endif - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set FPSCR (non-secure) - \details Assigns the given value to the non-secure Floating Point Status/Control register when in secure state. - \param [in] fpscr Floating Point Status/Control value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_FPSCR_NS(uint32_t fpscr) -{ -#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) - __ASM volatile (""); /* Empty asm statement works as a scheduling barrier */ - __ASM volatile ("VMSR fpscr_ns, %0" : : "r" (fpscr) : "vfpcc"); - __ASM volatile (""); -#endif -} -#endif - -#endif /* ((__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) */ - - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __builtin_arm_nop - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI __builtin_arm_wfi - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __builtin_arm_wfe - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __builtin_arm_sev - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -#define __ISB() __builtin_arm_isb(0xF); - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() __builtin_arm_dsb(0xF); - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() __builtin_arm_dmb(0xF); - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in integer value. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV __builtin_bswap32 - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in two unsigned short values. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV16 __builtin_bswap16 /* ToDo: ARMCC_V6: check if __builtin_bswap16 could be used */ -#if 0 -__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} -#endif - - -/** - \brief Reverse byte order in signed short value - \details Reverses the byte order in a signed short value with sign extension to integer. - \param [in] value Value to reverse - \return Reversed value - */ - /* ToDo: ARMCC_V6: check if __builtin_bswap16 could be used */ -__attribute__((always_inline)) __STATIC_INLINE int32_t __REVSH(int32_t value) -{ - int32_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ - /* ToDo: ARMCC_V6: check if __builtin_arm_rbit is supported */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) /* ToDo: ARMCC_V6: check if this is ok for cortex >=3 */ - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - int32_t s = 4 /*sizeof(v)*/ * 8 - 1; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return(result); -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ __builtin_clz - - -#if ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) /* ToDo: ARMCC_V6: check if this is ok for cortex >=3 */ - -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDREXB (uint8_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDREXH (uint16_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDREXW (uint32_t)__builtin_arm_ldrex - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXB (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXH (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXW (uint32_t)__builtin_arm_strex - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -#define __CLREX __builtin_arm_clrex - - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -/*#define __SSAT __builtin_arm_ssat*/ -#define __SSAT(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __builtin_arm_usat -#if 0 -#define __USAT(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) -#endif - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#endif /* ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) */ - - -#if (__ARM_ARCH_8M__ == 1U) - -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDAEXB (uint8_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDAEXH (uint16_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDAEX (uint32_t)__builtin_arm_ldaex - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXB (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXH (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEX (uint32_t)__builtin_arm_stlex - -#endif /* (__ARM_ARCH_8M__ == 1U) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (__ARM_FEATURE_DSP == 1U) /* ToDo: ARMCC_V6: This should be ARCH >= ARMv7-M + SIMD */ - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1U) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#endif /* __CMSIS_ARMCC_V6_H */ diff --git a/body/board/inc/cmsis_armclang.h b/body/board/inc/cmsis_armclang.h deleted file mode 100644 index 162a400ea1b0160..000000000000000 --- a/body/board/inc/cmsis_armclang.h +++ /dev/null @@ -1,1869 +0,0 @@ -/**************************************************************************//** - * @file cmsis_armclang.h - * @brief CMSIS compiler armclang (Arm Compiler 6) header file - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */ - -#ifndef __CMSIS_ARMCLANG_H -#define __CMSIS_ARMCLANG_H - -#pragma clang system_header /* treat file as system include file */ - -#ifndef __ARM_COMPAT_H -#include /* Compatibility header for Arm Compiler 5 intrinsics */ -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE __inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static __inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static __inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */ - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */ - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __enable_irq(); see arm_compat.h */ - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __disable_irq(); see arm_compat.h */ - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __enable_fault_irq __enable_fiq /* see arm_compat.h */ - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __disable_fault_irq __disable_fiq /* see arm_compat.h */ - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr -#else -#define __get_FPSCR() ((uint32_t)0U) -#endif - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#define __set_FPSCR __builtin_arm_set_fpscr -#else -#define __set_FPSCR(x) ((void)(x)) -#endif - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __builtin_arm_nop - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI __builtin_arm_wfi - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __builtin_arm_wfe - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __builtin_arm_sev - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -#define __ISB() __builtin_arm_isb(0xF); - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() __builtin_arm_dsb(0xF); - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() __builtin_arm_dmb(0xF); - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV(value) __builtin_bswap32(value) - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV16(value) __ROR(__REV(value), 16) - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REVSH(value) (int16_t)__builtin_bswap16(value) - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -#define __RBIT __builtin_arm_rbit - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ (uint8_t)__builtin_clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDREXB (uint8_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDREXH (uint16_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDREXW (uint32_t)__builtin_arm_ldrex - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXB (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXH (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXW (uint32_t)__builtin_arm_strex - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -#define __CLREX __builtin_arm_clrex - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT __builtin_arm_ssat - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __builtin_arm_usat - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDAEXB (uint8_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDAEXH (uint16_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDAEX (uint32_t)__builtin_arm_ldaex - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXB (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXH (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEX (uint32_t)__builtin_arm_stlex - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#endif /* __CMSIS_ARMCLANG_H */ diff --git a/body/board/inc/cmsis_compiler.h b/body/board/inc/cmsis_compiler.h deleted file mode 100644 index 94212eb87a94d11..000000000000000 --- a/body/board/inc/cmsis_compiler.h +++ /dev/null @@ -1,266 +0,0 @@ -/**************************************************************************//** - * @file cmsis_compiler.h - * @brief CMSIS compiler generic header file - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_COMPILER_H -#define __CMSIS_COMPILER_H - -#include - -/* - * Arm Compiler 4/5 - */ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - - -/* - * Arm Compiler 6 (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armclang.h" - - -/* - * GNU Compiler - */ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - - -/* - * IAR Compiler - */ -#elif defined ( __ICCARM__ ) - #include - - -/* - * TI Arm Compiler - */ -#elif defined ( __TI_ARM__ ) - #include - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __attribute__((packed)) - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed)) - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed)) - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -/* - * TASKING Compiler - */ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __packed__ - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __packed__ - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __packed__ - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __packed__ T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __align(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -/* - * COSMIC Compiler - */ -#elif defined ( __CSMC__ ) - #include - - #ifndef __ASM - #define __ASM _asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - // NO RETURN is automatically detected hence no warning here - #define __NO_RETURN - #endif - #ifndef __USED - #warning No compiler specific solution for __USED. __USED is ignored. - #define __USED - #endif - #ifndef __WEAK - #define __WEAK __weak - #endif - #ifndef __PACKED - #define __PACKED @packed - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT @packed struct - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION @packed union - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - @packed struct T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. - #define __ALIGNED(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -#else - #error Unknown compiler. -#endif - - -#endif /* __CMSIS_COMPILER_H */ - diff --git a/body/board/inc/cmsis_gcc.h b/body/board/inc/cmsis_gcc.h deleted file mode 100644 index 2d9db15a5def346..000000000000000 --- a/body/board/inc/cmsis_gcc.h +++ /dev/null @@ -1,2085 +0,0 @@ -/**************************************************************************//** - * @file cmsis_gcc.h - * @brief CMSIS compiler GCC header file - * @version V5.0.4 - * @date 09. April 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_GCC_H -#define __CMSIS_GCC_H - -/* ignore some GCC warnings */ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" - -/* Fallback for __has_builtin */ -#ifndef __has_builtin - #define __has_builtin(x) (0) -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory"); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory"); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_get_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - return __builtin_arm_get_fpscr(); -#else - uint32_t result; - - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - return(result); -#endif -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_set_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - __builtin_arm_set_fpscr(fpscr); -#else - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); -#endif -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_RW_REG(r) "+l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_RW_REG(r) "+r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP() __ASM volatile ("nop") - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI() __ASM volatile ("wfi") - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE() __ASM volatile ("wfe") - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV() __ASM volatile ("sev") - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -__STATIC_FORCEINLINE void __ISB(void) -{ - __ASM volatile ("isb 0xF":::"memory"); -} - - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__STATIC_FORCEINLINE void __DSB(void) -{ - __ASM volatile ("dsb 0xF":::"memory"); -} - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__STATIC_FORCEINLINE void __DMB(void) -{ - __ASM volatile ("dmb 0xF":::"memory"); -} - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (int16_t)__builtin_bswap16(value); -#else - int16_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return result; -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ (uint8_t)__builtin_clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -__STATIC_FORCEINLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -__extension__ \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ - __extension__ \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#pragma GCC diagnostic pop - -#endif /* __CMSIS_GCC_H */ diff --git a/body/board/inc/cmsis_iccarm.h b/body/board/inc/cmsis_iccarm.h deleted file mode 100644 index 11c4af0eba7f2c0..000000000000000 --- a/body/board/inc/cmsis_iccarm.h +++ /dev/null @@ -1,935 +0,0 @@ -/**************************************************************************//** - * @file cmsis_iccarm.h - * @brief CMSIS compiler ICCARM (IAR Compiler for Arm) header file - * @version V5.0.7 - * @date 19. June 2018 - ******************************************************************************/ - -//------------------------------------------------------------------------------ -// -// Copyright (c) 2017-2018 IAR Systems -// -// Licensed under the Apache License, Version 2.0 (the "License") -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -//------------------------------------------------------------------------------ - - -#ifndef __CMSIS_ICCARM_H__ -#define __CMSIS_ICCARM_H__ - -#ifndef __ICCARM__ - #error This file should only be compiled by ICCARM -#endif - -#pragma system_include - -#define __IAR_FT _Pragma("inline=forced") __intrinsic - -#if (__VER__ >= 8000000) - #define __ICCARM_V8 1 -#else - #define __ICCARM_V8 0 -#endif - -#ifndef __ALIGNED - #if __ICCARM_V8 - #define __ALIGNED(x) __attribute__((aligned(x))) - #elif (__VER__ >= 7080000) - /* Needs IAR language extensions */ - #define __ALIGNED(x) __attribute__((aligned(x))) - #else - #warning No compiler specific solution for __ALIGNED.__ALIGNED is ignored. - #define __ALIGNED(x) - #endif -#endif - - -/* Define compiler macros for CPU architecture, used in CMSIS 5. - */ -#if __ARM_ARCH_6M__ || __ARM_ARCH_7M__ || __ARM_ARCH_7EM__ || __ARM_ARCH_8M_BASE__ || __ARM_ARCH_8M_MAIN__ -/* Macros already defined */ -#else - #if defined(__ARM8M_MAINLINE__) || defined(__ARM8EM_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #elif defined(__ARM8M_BASELINE__) - #define __ARM_ARCH_8M_BASE__ 1 - #elif defined(__ARM_ARCH_PROFILE) && __ARM_ARCH_PROFILE == 'M' - #if __ARM_ARCH == 6 - #define __ARM_ARCH_6M__ 1 - #elif __ARM_ARCH == 7 - #if __ARM_FEATURE_DSP - #define __ARM_ARCH_7EM__ 1 - #else - #define __ARM_ARCH_7M__ 1 - #endif - #endif /* __ARM_ARCH */ - #endif /* __ARM_ARCH_PROFILE == 'M' */ -#endif - -/* Alternativ core deduction for older ICCARM's */ -#if !defined(__ARM_ARCH_6M__) && !defined(__ARM_ARCH_7M__) && !defined(__ARM_ARCH_7EM__) && \ - !defined(__ARM_ARCH_8M_BASE__) && !defined(__ARM_ARCH_8M_MAIN__) - #if defined(__ARM6M__) && (__CORE__ == __ARM6M__) - #define __ARM_ARCH_6M__ 1 - #elif defined(__ARM7M__) && (__CORE__ == __ARM7M__) - #define __ARM_ARCH_7M__ 1 - #elif defined(__ARM7EM__) && (__CORE__ == __ARM7EM__) - #define __ARM_ARCH_7EM__ 1 - #elif defined(__ARM8M_BASELINE__) && (__CORE == __ARM8M_BASELINE__) - #define __ARM_ARCH_8M_BASE__ 1 - #elif defined(__ARM8M_MAINLINE__) && (__CORE == __ARM8M_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #elif defined(__ARM8EM_MAINLINE__) && (__CORE == __ARM8EM_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #else - #error "Unknown target." - #endif -#endif - - - -#if defined(__ARM_ARCH_6M__) && __ARM_ARCH_6M__==1 - #define __IAR_M0_FAMILY 1 -#elif defined(__ARM_ARCH_8M_BASE__) && __ARM_ARCH_8M_BASE__==1 - #define __IAR_M0_FAMILY 1 -#else - #define __IAR_M0_FAMILY 0 -#endif - - -#ifndef __ASM - #define __ASM __asm -#endif - -#ifndef __INLINE - #define __INLINE inline -#endif - -#ifndef __NO_RETURN - #if __ICCARM_V8 - #define __NO_RETURN __attribute__((__noreturn__)) - #else - #define __NO_RETURN _Pragma("object_attribute=__noreturn") - #endif -#endif - -#ifndef __PACKED - #if __ICCARM_V8 - #define __PACKED __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED __packed - #endif -#endif - -#ifndef __PACKED_STRUCT - #if __ICCARM_V8 - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED_STRUCT __packed struct - #endif -#endif - -#ifndef __PACKED_UNION - #if __ICCARM_V8 - #define __PACKED_UNION union __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED_UNION __packed union - #endif -#endif - -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif - -#ifndef __FORCEINLINE - #define __FORCEINLINE _Pragma("inline=forced") -#endif - -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __FORCEINLINE __STATIC_INLINE -#endif - -#ifndef __UNALIGNED_UINT16_READ -#pragma language=save -#pragma language=extended -__IAR_FT uint16_t __iar_uint16_read(void const *ptr) -{ - return *(__packed uint16_t*)(ptr); -} -#pragma language=restore -#define __UNALIGNED_UINT16_READ(PTR) __iar_uint16_read(PTR) -#endif - - -#ifndef __UNALIGNED_UINT16_WRITE -#pragma language=save -#pragma language=extended -__IAR_FT void __iar_uint16_write(void const *ptr, uint16_t val) -{ - *(__packed uint16_t*)(ptr) = val;; -} -#pragma language=restore -#define __UNALIGNED_UINT16_WRITE(PTR,VAL) __iar_uint16_write(PTR,VAL) -#endif - -#ifndef __UNALIGNED_UINT32_READ -#pragma language=save -#pragma language=extended -__IAR_FT uint32_t __iar_uint32_read(void const *ptr) -{ - return *(__packed uint32_t*)(ptr); -} -#pragma language=restore -#define __UNALIGNED_UINT32_READ(PTR) __iar_uint32_read(PTR) -#endif - -#ifndef __UNALIGNED_UINT32_WRITE -#pragma language=save -#pragma language=extended -__IAR_FT void __iar_uint32_write(void const *ptr, uint32_t val) -{ - *(__packed uint32_t*)(ptr) = val;; -} -#pragma language=restore -#define __UNALIGNED_UINT32_WRITE(PTR,VAL) __iar_uint32_write(PTR,VAL) -#endif - -#ifndef __UNALIGNED_UINT32 /* deprecated */ -#pragma language=save -#pragma language=extended -__packed struct __iar_u32 { uint32_t v; }; -#pragma language=restore -#define __UNALIGNED_UINT32(PTR) (((struct __iar_u32 *)(PTR))->v) -#endif - -#ifndef __USED - #if __ICCARM_V8 - #define __USED __attribute__((used)) - #else - #define __USED _Pragma("__root") - #endif -#endif - -#ifndef __WEAK - #if __ICCARM_V8 - #define __WEAK __attribute__((weak)) - #else - #define __WEAK _Pragma("__weak") - #endif -#endif - - -#ifndef __ICCARM_INTRINSICS_VERSION__ - #define __ICCARM_INTRINSICS_VERSION__ 0 -#endif - -#if __ICCARM_INTRINSICS_VERSION__ == 2 - - #if defined(__CLZ) - #undef __CLZ - #endif - #if defined(__REVSH) - #undef __REVSH - #endif - #if defined(__RBIT) - #undef __RBIT - #endif - #if defined(__SSAT) - #undef __SSAT - #endif - #if defined(__USAT) - #undef __USAT - #endif - - #include "iccarm_builtin.h" - - #define __disable_fault_irq __iar_builtin_disable_fiq - #define __disable_irq __iar_builtin_disable_interrupt - #define __enable_fault_irq __iar_builtin_enable_fiq - #define __enable_irq __iar_builtin_enable_interrupt - #define __arm_rsr __iar_builtin_rsr - #define __arm_wsr __iar_builtin_wsr - - - #define __get_APSR() (__arm_rsr("APSR")) - #define __get_BASEPRI() (__arm_rsr("BASEPRI")) - #define __get_CONTROL() (__arm_rsr("CONTROL")) - #define __get_FAULTMASK() (__arm_rsr("FAULTMASK")) - - #if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) - #define __get_FPSCR() (__arm_rsr("FPSCR")) - #define __set_FPSCR(VALUE) (__arm_wsr("FPSCR", (VALUE))) - #else - #define __get_FPSCR() ( 0 ) - #define __set_FPSCR(VALUE) ((void)VALUE) - #endif - - #define __get_IPSR() (__arm_rsr("IPSR")) - #define __get_MSP() (__arm_rsr("MSP")) - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - #define __get_MSPLIM() (0U) - #else - #define __get_MSPLIM() (__arm_rsr("MSPLIM")) - #endif - #define __get_PRIMASK() (__arm_rsr("PRIMASK")) - #define __get_PSP() (__arm_rsr("PSP")) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __get_PSPLIM() (0U) - #else - #define __get_PSPLIM() (__arm_rsr("PSPLIM")) - #endif - - #define __get_xPSR() (__arm_rsr("xPSR")) - - #define __set_BASEPRI(VALUE) (__arm_wsr("BASEPRI", (VALUE))) - #define __set_BASEPRI_MAX(VALUE) (__arm_wsr("BASEPRI_MAX", (VALUE))) - #define __set_CONTROL(VALUE) (__arm_wsr("CONTROL", (VALUE))) - #define __set_FAULTMASK(VALUE) (__arm_wsr("FAULTMASK", (VALUE))) - #define __set_MSP(VALUE) (__arm_wsr("MSP", (VALUE))) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - #define __set_MSPLIM(VALUE) ((void)(VALUE)) - #else - #define __set_MSPLIM(VALUE) (__arm_wsr("MSPLIM", (VALUE))) - #endif - #define __set_PRIMASK(VALUE) (__arm_wsr("PRIMASK", (VALUE))) - #define __set_PSP(VALUE) (__arm_wsr("PSP", (VALUE))) - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __set_PSPLIM(VALUE) ((void)(VALUE)) - #else - #define __set_PSPLIM(VALUE) (__arm_wsr("PSPLIM", (VALUE))) - #endif - - #define __TZ_get_CONTROL_NS() (__arm_rsr("CONTROL_NS")) - #define __TZ_set_CONTROL_NS(VALUE) (__arm_wsr("CONTROL_NS", (VALUE))) - #define __TZ_get_PSP_NS() (__arm_rsr("PSP_NS")) - #define __TZ_set_PSP_NS(VALUE) (__arm_wsr("PSP_NS", (VALUE))) - #define __TZ_get_MSP_NS() (__arm_rsr("MSP_NS")) - #define __TZ_set_MSP_NS(VALUE) (__arm_wsr("MSP_NS", (VALUE))) - #define __TZ_get_SP_NS() (__arm_rsr("SP_NS")) - #define __TZ_set_SP_NS(VALUE) (__arm_wsr("SP_NS", (VALUE))) - #define __TZ_get_PRIMASK_NS() (__arm_rsr("PRIMASK_NS")) - #define __TZ_set_PRIMASK_NS(VALUE) (__arm_wsr("PRIMASK_NS", (VALUE))) - #define __TZ_get_BASEPRI_NS() (__arm_rsr("BASEPRI_NS")) - #define __TZ_set_BASEPRI_NS(VALUE) (__arm_wsr("BASEPRI_NS", (VALUE))) - #define __TZ_get_FAULTMASK_NS() (__arm_rsr("FAULTMASK_NS")) - #define __TZ_set_FAULTMASK_NS(VALUE)(__arm_wsr("FAULTMASK_NS", (VALUE))) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __TZ_get_PSPLIM_NS() (0U) - #define __TZ_set_PSPLIM_NS(VALUE) ((void)(VALUE)) - #else - #define __TZ_get_PSPLIM_NS() (__arm_rsr("PSPLIM_NS")) - #define __TZ_set_PSPLIM_NS(VALUE) (__arm_wsr("PSPLIM_NS", (VALUE))) - #endif - - #define __TZ_get_MSPLIM_NS() (__arm_rsr("MSPLIM_NS")) - #define __TZ_set_MSPLIM_NS(VALUE) (__arm_wsr("MSPLIM_NS", (VALUE))) - - #define __NOP __iar_builtin_no_operation - - #define __CLZ __iar_builtin_CLZ - #define __CLREX __iar_builtin_CLREX - - #define __DMB __iar_builtin_DMB - #define __DSB __iar_builtin_DSB - #define __ISB __iar_builtin_ISB - - #define __LDREXB __iar_builtin_LDREXB - #define __LDREXH __iar_builtin_LDREXH - #define __LDREXW __iar_builtin_LDREX - - #define __RBIT __iar_builtin_RBIT - #define __REV __iar_builtin_REV - #define __REV16 __iar_builtin_REV16 - - __IAR_FT int16_t __REVSH(int16_t val) - { - return (int16_t) __iar_builtin_REVSH(val); - } - - #define __ROR __iar_builtin_ROR - #define __RRX __iar_builtin_RRX - - #define __SEV __iar_builtin_SEV - - #if !__IAR_M0_FAMILY - #define __SSAT __iar_builtin_SSAT - #endif - - #define __STREXB __iar_builtin_STREXB - #define __STREXH __iar_builtin_STREXH - #define __STREXW __iar_builtin_STREX - - #if !__IAR_M0_FAMILY - #define __USAT __iar_builtin_USAT - #endif - - #define __WFE __iar_builtin_WFE - #define __WFI __iar_builtin_WFI - - #if __ARM_MEDIA__ - #define __SADD8 __iar_builtin_SADD8 - #define __QADD8 __iar_builtin_QADD8 - #define __SHADD8 __iar_builtin_SHADD8 - #define __UADD8 __iar_builtin_UADD8 - #define __UQADD8 __iar_builtin_UQADD8 - #define __UHADD8 __iar_builtin_UHADD8 - #define __SSUB8 __iar_builtin_SSUB8 - #define __QSUB8 __iar_builtin_QSUB8 - #define __SHSUB8 __iar_builtin_SHSUB8 - #define __USUB8 __iar_builtin_USUB8 - #define __UQSUB8 __iar_builtin_UQSUB8 - #define __UHSUB8 __iar_builtin_UHSUB8 - #define __SADD16 __iar_builtin_SADD16 - #define __QADD16 __iar_builtin_QADD16 - #define __SHADD16 __iar_builtin_SHADD16 - #define __UADD16 __iar_builtin_UADD16 - #define __UQADD16 __iar_builtin_UQADD16 - #define __UHADD16 __iar_builtin_UHADD16 - #define __SSUB16 __iar_builtin_SSUB16 - #define __QSUB16 __iar_builtin_QSUB16 - #define __SHSUB16 __iar_builtin_SHSUB16 - #define __USUB16 __iar_builtin_USUB16 - #define __UQSUB16 __iar_builtin_UQSUB16 - #define __UHSUB16 __iar_builtin_UHSUB16 - #define __SASX __iar_builtin_SASX - #define __QASX __iar_builtin_QASX - #define __SHASX __iar_builtin_SHASX - #define __UASX __iar_builtin_UASX - #define __UQASX __iar_builtin_UQASX - #define __UHASX __iar_builtin_UHASX - #define __SSAX __iar_builtin_SSAX - #define __QSAX __iar_builtin_QSAX - #define __SHSAX __iar_builtin_SHSAX - #define __USAX __iar_builtin_USAX - #define __UQSAX __iar_builtin_UQSAX - #define __UHSAX __iar_builtin_UHSAX - #define __USAD8 __iar_builtin_USAD8 - #define __USADA8 __iar_builtin_USADA8 - #define __SSAT16 __iar_builtin_SSAT16 - #define __USAT16 __iar_builtin_USAT16 - #define __UXTB16 __iar_builtin_UXTB16 - #define __UXTAB16 __iar_builtin_UXTAB16 - #define __SXTB16 __iar_builtin_SXTB16 - #define __SXTAB16 __iar_builtin_SXTAB16 - #define __SMUAD __iar_builtin_SMUAD - #define __SMUADX __iar_builtin_SMUADX - #define __SMMLA __iar_builtin_SMMLA - #define __SMLAD __iar_builtin_SMLAD - #define __SMLADX __iar_builtin_SMLADX - #define __SMLALD __iar_builtin_SMLALD - #define __SMLALDX __iar_builtin_SMLALDX - #define __SMUSD __iar_builtin_SMUSD - #define __SMUSDX __iar_builtin_SMUSDX - #define __SMLSD __iar_builtin_SMLSD - #define __SMLSDX __iar_builtin_SMLSDX - #define __SMLSLD __iar_builtin_SMLSLD - #define __SMLSLDX __iar_builtin_SMLSLDX - #define __SEL __iar_builtin_SEL - #define __QADD __iar_builtin_QADD - #define __QSUB __iar_builtin_QSUB - #define __PKHBT __iar_builtin_PKHBT - #define __PKHTB __iar_builtin_PKHTB - #endif - -#else /* __ICCARM_INTRINSICS_VERSION__ == 2 */ - - #if __IAR_M0_FAMILY - /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ - #define __CLZ __cmsis_iar_clz_not_active - #define __SSAT __cmsis_iar_ssat_not_active - #define __USAT __cmsis_iar_usat_not_active - #define __RBIT __cmsis_iar_rbit_not_active - #define __get_APSR __cmsis_iar_get_APSR_not_active - #endif - - - #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) - #define __get_FPSCR __cmsis_iar_get_FPSR_not_active - #define __set_FPSCR __cmsis_iar_set_FPSR_not_active - #endif - - #ifdef __INTRINSICS_INCLUDED - #error intrinsics.h is already included previously! - #endif - - #include - - #if __IAR_M0_FAMILY - /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ - #undef __CLZ - #undef __SSAT - #undef __USAT - #undef __RBIT - #undef __get_APSR - - __STATIC_INLINE uint8_t __CLZ(uint32_t data) - { - if (data == 0U) { return 32U; } - - uint32_t count = 0U; - uint32_t mask = 0x80000000U; - - while ((data & mask) == 0U) - { - count += 1U; - mask = mask >> 1U; - } - return count; - } - - __STATIC_INLINE uint32_t __RBIT(uint32_t v) - { - uint8_t sc = 31U; - uint32_t r = v; - for (v >>= 1U; v; v >>= 1U) - { - r <<= 1U; - r |= v & 1U; - sc--; - } - return (r << sc); - } - - __STATIC_INLINE uint32_t __get_APSR(void) - { - uint32_t res; - __asm("MRS %0,APSR" : "=r" (res)); - return res; - } - - #endif - - #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) - #undef __get_FPSCR - #undef __set_FPSCR - #define __get_FPSCR() (0) - #define __set_FPSCR(VALUE) ((void)VALUE) - #endif - - #pragma diag_suppress=Pe940 - #pragma diag_suppress=Pe177 - - #define __enable_irq __enable_interrupt - #define __disable_irq __disable_interrupt - #define __NOP __no_operation - - #define __get_xPSR __get_PSR - - #if (!defined(__ARM_ARCH_6M__) || __ARM_ARCH_6M__==0) - - __IAR_FT uint32_t __LDREXW(uint32_t volatile *ptr) - { - return __LDREX((unsigned long *)ptr); - } - - __IAR_FT uint32_t __STREXW(uint32_t value, uint32_t volatile *ptr) - { - return __STREX(value, (unsigned long *)ptr); - } - #endif - - - /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ - #if (__CORTEX_M >= 0x03) - - __IAR_FT uint32_t __RRX(uint32_t value) - { - uint32_t result; - __ASM("RRX %0, %1" : "=r"(result) : "r" (value) : "cc"); - return(result); - } - - __IAR_FT void __set_BASEPRI_MAX(uint32_t value) - { - __asm volatile("MSR BASEPRI_MAX,%0"::"r" (value)); - } - - - #define __enable_fault_irq __enable_fiq - #define __disable_fault_irq __disable_fiq - - - #endif /* (__CORTEX_M >= 0x03) */ - - __IAR_FT uint32_t __ROR(uint32_t op1, uint32_t op2) - { - return (op1 >> op2) | (op1 << ((sizeof(op1)*8)-op2)); - } - - #if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - - __IAR_FT uint32_t __get_MSPLIM(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,MSPLIM" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __set_MSPLIM(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR MSPLIM,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __get_PSPLIM(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,PSPLIM" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __set_PSPLIM(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR PSPLIM,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __TZ_get_CONTROL_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,CONTROL_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_CONTROL_NS(uint32_t value) - { - __asm volatile("MSR CONTROL_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PSP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,PSP_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_PSP_NS(uint32_t value) - { - __asm volatile("MSR PSP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_MSP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,MSP_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_MSP_NS(uint32_t value) - { - __asm volatile("MSR MSP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_SP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,SP_NS" : "=r" (res)); - return res; - } - __IAR_FT void __TZ_set_SP_NS(uint32_t value) - { - __asm volatile("MSR SP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PRIMASK_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,PRIMASK_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_PRIMASK_NS(uint32_t value) - { - __asm volatile("MSR PRIMASK_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_BASEPRI_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,BASEPRI_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_BASEPRI_NS(uint32_t value) - { - __asm volatile("MSR BASEPRI_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_FAULTMASK_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,FAULTMASK_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_FAULTMASK_NS(uint32_t value) - { - __asm volatile("MSR FAULTMASK_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PSPLIM_NS(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,PSPLIM_NS" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __TZ_set_PSPLIM_NS(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR PSPLIM_NS,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __TZ_get_MSPLIM_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,MSPLIM_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_MSPLIM_NS(uint32_t value) - { - __asm volatile("MSR MSPLIM_NS,%0" :: "r" (value)); - } - - #endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ - -#endif /* __ICCARM_INTRINSICS_VERSION__ == 2 */ - -#define __BKPT(value) __asm volatile ("BKPT %0" : : "i"(value)) - -#if __IAR_M0_FAMILY - __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) - { - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; - } - - __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) - { - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; - } -#endif - -#if (__CORTEX_M >= 0x03) /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ - - __IAR_FT uint8_t __LDRBT(volatile uint8_t *addr) - { - uint32_t res; - __ASM("LDRBT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDRHT(volatile uint16_t *addr) - { - uint32_t res; - __ASM("LDRHT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDRT(volatile uint32_t *addr) - { - uint32_t res; - __ASM("LDRT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return res; - } - - __IAR_FT void __STRBT(uint8_t value, volatile uint8_t *addr) - { - __ASM("STRBT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); - } - - __IAR_FT void __STRHT(uint16_t value, volatile uint16_t *addr) - { - __ASM("STRHT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); - } - - __IAR_FT void __STRT(uint32_t value, volatile uint32_t *addr) - { - __ASM("STRT %1, [%0]" : : "r" (addr), "r" (value) : "memory"); - } - -#endif /* (__CORTEX_M >= 0x03) */ - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - - - __IAR_FT uint8_t __LDAB(volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDAH(volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDA(volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("LDA %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return res; - } - - __IAR_FT void __STLB(uint8_t value, volatile uint8_t *ptr) - { - __ASM volatile ("STLB %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT void __STLH(uint16_t value, volatile uint16_t *ptr) - { - __ASM volatile ("STLH %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT void __STL(uint32_t value, volatile uint32_t *ptr) - { - __ASM volatile ("STL %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT uint8_t __LDAEXB(volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEXB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDAEXH(volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEXH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDAEX(volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEX %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEXB %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEXH %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEX %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - -#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ - -#undef __IAR_FT -#undef __IAR_M0_FAMILY -#undef __ICCARM_V8 - -#pragma diag_default=Pe940 -#pragma diag_default=Pe177 - -#endif /* __CMSIS_ICCARM_H__ */ diff --git a/body/board/inc/cmsis_version.h b/body/board/inc/cmsis_version.h deleted file mode 100644 index 660f612aa31fe2a..000000000000000 --- a/body/board/inc/cmsis_version.h +++ /dev/null @@ -1,39 +0,0 @@ -/**************************************************************************//** - * @file cmsis_version.h - * @brief CMSIS Core(M) Version definitions - * @version V5.0.2 - * @date 19. April 2017 - ******************************************************************************/ -/* - * Copyright (c) 2009-2017 ARM Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CMSIS_VERSION_H -#define __CMSIS_VERSION_H - -/* CMSIS Version definitions */ -#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ -#define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */ -#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ - __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ -#endif diff --git a/body/board/inc/core_armv8mbl.h b/body/board/inc/core_armv8mbl.h deleted file mode 100644 index 251e4ede3a9f54c..000000000000000 --- a/body/board/inc/core_armv8mbl.h +++ /dev/null @@ -1,1918 +0,0 @@ -/**************************************************************************//** - * @file core_armv8mbl.h - * @brief CMSIS Armv8-M Baseline Core Peripheral Access Layer Header File - * @version V5.0.7 - * @date 22. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_ARMV8MBL_H_GENERIC -#define __CORE_ARMV8MBL_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_ARMv8MBL - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS definitions */ -#define __ARMv8MBL_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __ARMv8MBL_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __ARMv8MBL_CMSIS_VERSION ((__ARMv8MBL_CMSIS_VERSION_MAIN << 16U) | \ - __ARMv8MBL_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M ( 2U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MBL_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_ARMV8MBL_H_DEPENDANT -#define __CORE_ARMV8MBL_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __ARMv8MBL_REV - #define __ARMv8MBL_REV 0x0000U - #warning "__ARMv8MBL_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __SAUREGION_PRESENT - #define __SAUREGION_PRESENT 0U - #warning "__SAUREGION_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __VTOR_PRESENT - #define __VTOR_PRESENT 0U - #warning "__VTOR_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif - - #ifndef __ETM_PRESENT - #define __ETM_PRESENT 0U - #warning "__ETM_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MTB_PRESENT - #define __MTB_PRESENT 0U - #warning "__MTB_PRESENT not defined in device header file; using default!" - #endif - -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group ARMv8MBL */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core SAU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[16U]; - __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[16U]; - __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[16U]; - __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[16U]; - __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[16U]; - __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ - uint32_t RESERVED5[16U]; - __IOM uint32_t IPR[124U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ -#else - uint32_t RESERVED0; -#endif - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHPR[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ -#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ - -#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ -#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ - -#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ -#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ -#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ -#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ - -#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ -#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ - -#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ -#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ -#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ - -#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ -#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ -#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ -#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ - -#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ -#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - uint32_t RESERVED0[6U]; - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - uint32_t RESERVED3[1U]; - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED4[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - uint32_t RESERVED5[1U]; - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED6[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - uint32_t RESERVED7[1U]; - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED8[1U]; - __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ - uint32_t RESERVED9[1U]; - __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ - uint32_t RESERVED10[1U]; - __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ - uint32_t RESERVED11[1U]; - __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ - uint32_t RESERVED12[1U]; - __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ - uint32_t RESERVED13[1U]; - __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ - uint32_t RESERVED14[1U]; - __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ - uint32_t RESERVED15[1U]; - __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ - uint32_t RESERVED16[1U]; - __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ - uint32_t RESERVED17[1U]; - __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ - uint32_t RESERVED18[1U]; - __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ - uint32_t RESERVED19[1U]; - __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ - uint32_t RESERVED20[1U]; - __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ - uint32_t RESERVED21[1U]; - __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ - uint32_t RESERVED22[1U]; - __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ - uint32_t RESERVED23[1U]; - __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ - uint32_t RESERVED24[1U]; - __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ - uint32_t RESERVED25[1U]; - __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ - uint32_t RESERVED26[1U]; - __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ - uint32_t RESERVED27[1U]; - __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ - uint32_t RESERVED28[1U]; - __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ - uint32_t RESERVED29[1U]; - __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ - uint32_t RESERVED30[1U]; - __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ - uint32_t RESERVED31[1U]; - __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ -#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ - -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ -#define DWT_FUNCTION_ACTION_Msk (0x3UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ - -#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ -#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Sizes Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Sizes Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ - uint32_t RESERVED3[809U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) Software Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) Software Lock Status Register */ - uint32_t RESERVED4[4U]; - __IM uint32_t TYPE; /*!< Offset: 0xFC8 (R/ ) Device Identifier Register */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Register */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */ -#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ -#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI Periodic Synchronization Control Register Definitions */ -#define TPI_PSCR_PSCount_Pos 0U /*!< TPI PSCR: PSCount Position */ -#define TPI_PSCR_PSCount_Msk (0x1FUL /*<< TPI_PSCR_PSCount_Pos*/) /*!< TPI PSCR: TPSCount Mask */ - -/* TPI Software Lock Status Register Definitions */ -#define TPI_LSR_nTT_Pos 1U /*!< TPI LSR: Not thirty-two bit. Position */ -#define TPI_LSR_nTT_Msk (0x1UL << TPI_LSR_nTT_Pos) /*!< TPI LSR: Not thirty-two bit. Mask */ - -#define TPI_LSR_SLK_Pos 1U /*!< TPI LSR: Software Lock status Position */ -#define TPI_LSR_SLK_Msk (0x1UL << TPI_LSR_SLK_Pos) /*!< TPI LSR: Software Lock status Mask */ - -#define TPI_LSR_SLI_Pos 0U /*!< TPI LSR: Software Lock implemented Position */ -#define TPI_LSR_SLI_Msk (0x1UL /*<< TPI_LSR_SLI_Pos*/) /*!< TPI LSR: Software Lock implemented Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFO depth Position */ -#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFO depth Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ - uint32_t RESERVED0[7U]; - union { - __IOM uint32_t MAIR[2]; - struct { - __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ - __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ - }; - }; -} MPU_Type; - -#define MPU_TYPE_RALIASES 1U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ -#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ - -#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ -#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ - -#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ -#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ - -#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ -#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ - -/* MPU Region Limit Address Register Definitions */ -#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ -#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ - -#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ -#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ - -#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: EN Position */ -#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: EN Mask */ - -/* MPU Memory Attribute Indirection Register 0 Definitions */ -#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ -#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ - -#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ -#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ - -#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ -#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ - -#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ -#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ - -/* MPU Memory Attribute Indirection Register 1 Definitions */ -#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ -#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ - -#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ -#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ - -#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ -#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ - -#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ -#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SAU Security Attribution Unit (SAU) - \brief Type definitions for the Security Attribution Unit (SAU) - @{ - */ - -/** - \brief Structure type to access the Security Attribution Unit (SAU). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ - __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ -#endif -} SAU_Type; - -/* SAU Control Register Definitions */ -#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ -#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ - -#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ -#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ - -/* SAU Type Register Definitions */ -#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ -#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ - -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) -/* SAU Region Number Register Definitions */ -#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ -#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ - -/* SAU Region Base Address Register Definitions */ -#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ -#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ - -/* SAU Region Limit Address Register Definitions */ -#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ -#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ - -#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ -#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ - -#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ -#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ - -#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ - -/*@} end of group CMSIS_SAU */ -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ - uint32_t RESERVED4[1U]; - __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ - __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ -#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register */ -#define CoreDebug_DEMCR_DWTENA_Pos 24U /*!< CoreDebug DEMCR: DWTENA Position */ -#define CoreDebug_DEMCR_DWTENA_Msk (1UL << CoreDebug_DEMCR_DWTENA_Pos) /*!< CoreDebug DEMCR: DWTENA Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/* Debug Authentication Control Register Definitions */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ - -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ - -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ - -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ - -/* Debug Security Control and Status Register Definitions */ -#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ -#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ - -#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ -#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ - -#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ -#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ - #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ - #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ - #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ - #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ - #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ - #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ - #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - - - #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ - #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ - #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ - #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ - #endif - - #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ - #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ - #endif - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ - #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ - #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ - #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ - #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ - - #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ - #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ - #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ - #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ - #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ - #endif - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* Special LR values for Secure/Non-Secure call handling and exception handling */ - -/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ -#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ - -/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ -#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ -#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ -#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ -#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ -#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ -#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ -#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ - -/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ -#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ -#else -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ -#endif - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Interrupt Target State - \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - \return 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Target State - \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Clear Interrupt Target State - \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - If VTOR is not present address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Enable Interrupt (non-secure) - \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status (non-secure) - \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt (non-secure) - \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Pending Interrupt (non-secure) - \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt (non-secure) - \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt (non-secure) - \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt (non-secure) - \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority (non-secure) - \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every non-secure processor exception. - */ -__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC_NS->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB_NS->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB_NS->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority (non-secure) - \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB_NS->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv8.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## SAU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SAUFunctions SAU Functions - \brief Functions that configure the SAU. - @{ - */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - -/** - \brief Enable SAU - \details Enables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Enable(void) -{ - SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); -} - - - -/** - \brief Disable SAU - \details Disables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Disable(void) -{ - SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); -} - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_SAUFunctions */ - - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief System Tick Configuration (non-secure) - \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function TZ_SysTick_Config_NS is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - - */ -__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MBL_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/body/board/inc/core_armv8mml.h b/body/board/inc/core_armv8mml.h deleted file mode 100644 index 3a3148ea3144bad..000000000000000 --- a/body/board/inc/core_armv8mml.h +++ /dev/null @@ -1,2927 +0,0 @@ -/**************************************************************************//** - * @file core_armv8mml.h - * @brief CMSIS Armv8-M Mainline Core Peripheral Access Layer Header File - * @version V5.0.7 - * @date 06. July 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_ARMV8MML_H_GENERIC -#define __CORE_ARMV8MML_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_ARMv8MML - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS Armv8MML definitions */ -#define __ARMv8MML_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __ARMv8MML_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __ARMv8MML_CMSIS_VERSION ((__ARMv8MML_CMSIS_VERSION_MAIN << 16U) | \ - __ARMv8MML_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (81U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MML_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_ARMV8MML_H_DEPENDANT -#define __CORE_ARMV8MML_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __ARMv8MML_REV - #define __ARMv8MML_REV 0x0000U - #warning "__ARMv8MML_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __SAUREGION_PRESENT - #define __SAUREGION_PRESENT 0U - #warning "__SAUREGION_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DSP_PRESENT - #define __DSP_PRESENT 0U - #warning "__DSP_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group ARMv8MML */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core SAU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */ -#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ - uint32_t FPCA:1; /*!< bit: 2 Floating-point context active */ - uint32_t SFPA:1; /*!< bit: 3 Secure floating-point active */ - uint32_t _reserved1:28; /*!< bit: 4..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SFPA_Pos 3U /*!< CONTROL: SFPA Position */ -#define CONTROL_SFPA_Msk (1UL << CONTROL_SFPA_Pos) /*!< CONTROL: SFPA Mask */ - -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[16U]; - __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[16U]; - __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[16U]; - __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[16U]; - __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[16U]; - __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ - uint32_t RESERVED5[16U]; - __IOM uint8_t IPR[496U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED6[580U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ID_ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t ID_MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ID_ISAR[6U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ - __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ - __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ - __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - __IOM uint32_t NSACR; /*!< Offset: 0x08C (R/W) Non-Secure Access Control Register */ - uint32_t RESERVED3[92U]; - __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ - uint32_t RESERVED4[15U]; - __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ - uint32_t RESERVED5[1U]; - __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ - uint32_t RESERVED6[1U]; - __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ - __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ - __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ - __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ - __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ - __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ - __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ - __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ - uint32_t RESERVED7[6U]; - __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ - __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ - __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ - __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ - __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ - uint32_t RESERVED8[1U]; - __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ -#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ - -#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ -#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ - -#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ -#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ -#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ -#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ - -#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ -#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ -#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ -#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ - -#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ -#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ -#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ - -#define SCB_SHCSR_SECUREFAULTPENDED_Pos 20U /*!< SCB SHCSR: SECUREFAULTPENDED Position */ -#define SCB_SHCSR_SECUREFAULTPENDED_Msk (1UL << SCB_SHCSR_SECUREFAULTPENDED_Pos) /*!< SCB SHCSR: SECUREFAULTPENDED Mask */ - -#define SCB_SHCSR_SECUREFAULTENA_Pos 19U /*!< SCB SHCSR: SECUREFAULTENA Position */ -#define SCB_SHCSR_SECUREFAULTENA_Msk (1UL << SCB_SHCSR_SECUREFAULTENA_Pos) /*!< SCB SHCSR: SECUREFAULTENA Mask */ - -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ -#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ - -#define SCB_SHCSR_SECUREFAULTACT_Pos 4U /*!< SCB SHCSR: SECUREFAULTACT Position */ -#define SCB_SHCSR_SECUREFAULTACT_Msk (1UL << SCB_SHCSR_SECUREFAULTACT_Pos) /*!< SCB SHCSR: SECUREFAULTACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ -#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_STKOF_Pos (SCB_CFSR_USGFAULTSR_Pos + 4U) /*!< SCB CFSR (UFSR): STKOF Position */ -#define SCB_CFSR_STKOF_Msk (1UL << SCB_CFSR_STKOF_Pos) /*!< SCB CFSR (UFSR): STKOF Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/* SCB Non-Secure Access Control Register Definitions */ -#define SCB_NSACR_CP11_Pos 11U /*!< SCB NSACR: CP11 Position */ -#define SCB_NSACR_CP11_Msk (1UL << SCB_NSACR_CP11_Pos) /*!< SCB NSACR: CP11 Mask */ - -#define SCB_NSACR_CP10_Pos 10U /*!< SCB NSACR: CP10 Position */ -#define SCB_NSACR_CP10_Msk (1UL << SCB_NSACR_CP10_Pos) /*!< SCB NSACR: CP10 Mask */ - -#define SCB_NSACR_CPn_Pos 0U /*!< SCB NSACR: CPn Position */ -#define SCB_NSACR_CPn_Msk (1UL /*<< SCB_NSACR_CPn_Pos*/) /*!< SCB NSACR: CPn Mask */ - -/* SCB Cache Level ID Register Definitions */ -#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ -#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ - -#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ -#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ - -/* SCB Cache Type Register Definitions */ -#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ -#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ - -#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ -#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ - -#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ -#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ - -#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ -#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ - -#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ -#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ - -/* SCB Cache Size ID Register Definitions */ -#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ -#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ - -#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ -#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ - -#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ -#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ - -#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ -#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ - -#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ -#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ - -#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ -#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ - -#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ -#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ - -/* SCB Cache Size Selection Register Definitions */ -#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ -#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ - -#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ -#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ - -/* SCB Software Triggered Interrupt Register Definitions */ -#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ -#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ - -/* SCB D-Cache Invalidate by Set-way Register Definitions */ -#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ -#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ - -#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ -#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ - -/* SCB D-Cache Clean by Set-way Register Definitions */ -#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ -#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ - -#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ -#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ - -/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ -#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ -#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ - -#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ -#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ - -/* Instruction Tightly-Coupled Memory Control Register Definitions */ -#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ -#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ - -#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ -#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ - -#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ -#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ - -#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ -#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ - -/* Data Tightly-Coupled Memory Control Register Definitions */ -#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ -#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ - -#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ -#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ - -#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ -#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ - -#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ -#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ - -/* AHBP Control Register Definitions */ -#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ -#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ - -#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ -#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ - -/* L1 Cache Control Register Definitions */ -#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ -#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ - -#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ -#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ - -#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ -#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ - -/* AHBS Control Register Definitions */ -#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ -#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ - -#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ -#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ - -#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ -#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ - -/* Auxiliary Bus Fault Status Register Definitions */ -#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ -#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ - -#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ -#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ - -#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ -#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ - -#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ -#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ - -#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ -#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ - -#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ -#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ - __IOM uint32_t CPPWR; /*!< Offset: 0x00C (R/W) Coprocessor Power Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[1U]; - __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) ITM Device Architecture Register */ - uint32_t RESERVED6[4U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Stimulus Port Register Definitions */ -#define ITM_STIM_DISABLED_Pos 1U /*!< ITM STIM: DISABLED Position */ -#define ITM_STIM_DISABLED_Msk (0x1UL << ITM_STIM_DISABLED_Pos) /*!< ITM STIM: DISABLED Mask */ - -#define ITM_STIM_FIFOREADY_Pos 0U /*!< ITM STIM: FIFOREADY Position */ -#define ITM_STIM_FIFOREADY_Msk (0x1UL /*<< ITM_STIM_FIFOREADY_Pos*/) /*!< ITM STIM: FIFOREADY Mask */ - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TRACEBUSID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TRACEBUSID_Msk (0x7FUL << ITM_TCR_TRACEBUSID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPRESCALE_Pos 8U /*!< ITM TCR: TSPRESCALE Position */ -#define ITM_TCR_TSPRESCALE_Msk (3UL << ITM_TCR_TSPRESCALE_Pos) /*!< ITM TCR: TSPRESCALE Mask */ - -#define ITM_TCR_STALLENA_Pos 5U /*!< ITM TCR: STALLENA Position */ -#define ITM_TCR_STALLENA_Msk (1UL << ITM_TCR_STALLENA_Pos) /*!< ITM TCR: STALLENA Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - uint32_t RESERVED3[1U]; - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED4[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - uint32_t RESERVED5[1U]; - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED6[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - uint32_t RESERVED7[1U]; - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED8[1U]; - __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ - uint32_t RESERVED9[1U]; - __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ - uint32_t RESERVED10[1U]; - __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ - uint32_t RESERVED11[1U]; - __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ - uint32_t RESERVED12[1U]; - __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ - uint32_t RESERVED13[1U]; - __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ - uint32_t RESERVED14[1U]; - __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ - uint32_t RESERVED15[1U]; - __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ - uint32_t RESERVED16[1U]; - __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ - uint32_t RESERVED17[1U]; - __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ - uint32_t RESERVED18[1U]; - __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ - uint32_t RESERVED19[1U]; - __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ - uint32_t RESERVED20[1U]; - __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ - uint32_t RESERVED21[1U]; - __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ - uint32_t RESERVED22[1U]; - __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ - uint32_t RESERVED23[1U]; - __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ - uint32_t RESERVED24[1U]; - __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ - uint32_t RESERVED25[1U]; - __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ - uint32_t RESERVED26[1U]; - __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ - uint32_t RESERVED27[1U]; - __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ - uint32_t RESERVED28[1U]; - __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ - uint32_t RESERVED29[1U]; - __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ - uint32_t RESERVED30[1U]; - __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ - uint32_t RESERVED31[1U]; - __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ - uint32_t RESERVED32[934U]; - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ - uint32_t RESERVED33[1U]; - __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) Device Architecture Register */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCDISS_Pos 23U /*!< DWT CTRL: CYCDISS Position */ -#define DWT_CTRL_CYCDISS_Msk (0x1UL << DWT_CTRL_CYCDISS_Pos) /*!< DWT CTRL: CYCDISS Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ -#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ - -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ -#define DWT_FUNCTION_ACTION_Msk (0x1UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ - -#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ -#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Sizes Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Sizes Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ - uint32_t RESERVED3[809U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) Software Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) Software Lock Status Register */ - uint32_t RESERVED4[4U]; - __IM uint32_t TYPE; /*!< Offset: 0xFC8 (R/ ) Device Identifier Register */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Register */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */ -#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ -#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI Periodic Synchronization Control Register Definitions */ -#define TPI_PSCR_PSCount_Pos 0U /*!< TPI PSCR: PSCount Position */ -#define TPI_PSCR_PSCount_Msk (0x1FUL /*<< TPI_PSCR_PSCount_Pos*/) /*!< TPI PSCR: TPSCount Mask */ - -/* TPI Software Lock Status Register Definitions */ -#define TPI_LSR_nTT_Pos 1U /*!< TPI LSR: Not thirty-two bit. Position */ -#define TPI_LSR_nTT_Msk (0x1UL << TPI_LSR_nTT_Pos) /*!< TPI LSR: Not thirty-two bit. Mask */ - -#define TPI_LSR_SLK_Pos 1U /*!< TPI LSR: Software Lock status Position */ -#define TPI_LSR_SLK_Msk (0x1UL << TPI_LSR_SLK_Pos) /*!< TPI LSR: Software Lock status Mask */ - -#define TPI_LSR_SLI_Pos 0U /*!< TPI LSR: Software Lock implemented Position */ -#define TPI_LSR_SLI_Msk (0x1UL /*<< TPI_LSR_SLI_Pos*/) /*!< TPI LSR: Software Lock implemented Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFO depth Position */ -#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFO depth Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Region Base Address Register Alias 1 */ - __IOM uint32_t RLAR_A1; /*!< Offset: 0x018 (R/W) MPU Region Limit Address Register Alias 1 */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Region Base Address Register Alias 2 */ - __IOM uint32_t RLAR_A2; /*!< Offset: 0x020 (R/W) MPU Region Limit Address Register Alias 2 */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Region Base Address Register Alias 3 */ - __IOM uint32_t RLAR_A3; /*!< Offset: 0x028 (R/W) MPU Region Limit Address Register Alias 3 */ - uint32_t RESERVED0[1]; - union { - __IOM uint32_t MAIR[2]; - struct { - __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ - __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ - }; - }; -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ -#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ - -#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ -#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ - -#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ -#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ - -#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ -#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ - -/* MPU Region Limit Address Register Definitions */ -#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ -#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ - -#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ -#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ - -#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: Region enable bit Position */ -#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: Region enable bit Disable Mask */ - -/* MPU Memory Attribute Indirection Register 0 Definitions */ -#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ -#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ - -#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ -#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ - -#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ -#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ - -#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ -#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ - -/* MPU Memory Attribute Indirection Register 1 Definitions */ -#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ -#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ - -#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ -#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ - -#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ -#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ - -#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ -#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SAU Security Attribution Unit (SAU) - \brief Type definitions for the Security Attribution Unit (SAU) - @{ - */ - -/** - \brief Structure type to access the Security Attribution Unit (SAU). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ - __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ -#else - uint32_t RESERVED0[3]; -#endif - __IOM uint32_t SFSR; /*!< Offset: 0x014 (R/W) Secure Fault Status Register */ - __IOM uint32_t SFAR; /*!< Offset: 0x018 (R/W) Secure Fault Address Register */ -} SAU_Type; - -/* SAU Control Register Definitions */ -#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ -#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ - -#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ -#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ - -/* SAU Type Register Definitions */ -#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ -#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ - -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) -/* SAU Region Number Register Definitions */ -#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ -#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ - -/* SAU Region Base Address Register Definitions */ -#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ -#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ - -/* SAU Region Limit Address Register Definitions */ -#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ -#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ - -#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ -#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ - -#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ -#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ - -#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ - -/* Secure Fault Status Register Definitions */ -#define SAU_SFSR_LSERR_Pos 7U /*!< SAU SFSR: LSERR Position */ -#define SAU_SFSR_LSERR_Msk (1UL << SAU_SFSR_LSERR_Pos) /*!< SAU SFSR: LSERR Mask */ - -#define SAU_SFSR_SFARVALID_Pos 6U /*!< SAU SFSR: SFARVALID Position */ -#define SAU_SFSR_SFARVALID_Msk (1UL << SAU_SFSR_SFARVALID_Pos) /*!< SAU SFSR: SFARVALID Mask */ - -#define SAU_SFSR_LSPERR_Pos 5U /*!< SAU SFSR: LSPERR Position */ -#define SAU_SFSR_LSPERR_Msk (1UL << SAU_SFSR_LSPERR_Pos) /*!< SAU SFSR: LSPERR Mask */ - -#define SAU_SFSR_INVTRAN_Pos 4U /*!< SAU SFSR: INVTRAN Position */ -#define SAU_SFSR_INVTRAN_Msk (1UL << SAU_SFSR_INVTRAN_Pos) /*!< SAU SFSR: INVTRAN Mask */ - -#define SAU_SFSR_AUVIOL_Pos 3U /*!< SAU SFSR: AUVIOL Position */ -#define SAU_SFSR_AUVIOL_Msk (1UL << SAU_SFSR_AUVIOL_Pos) /*!< SAU SFSR: AUVIOL Mask */ - -#define SAU_SFSR_INVER_Pos 2U /*!< SAU SFSR: INVER Position */ -#define SAU_SFSR_INVER_Msk (1UL << SAU_SFSR_INVER_Pos) /*!< SAU SFSR: INVER Mask */ - -#define SAU_SFSR_INVIS_Pos 1U /*!< SAU SFSR: INVIS Position */ -#define SAU_SFSR_INVIS_Msk (1UL << SAU_SFSR_INVIS_Pos) /*!< SAU SFSR: INVIS Mask */ - -#define SAU_SFSR_INVEP_Pos 0U /*!< SAU SFSR: INVEP Position */ -#define SAU_SFSR_INVEP_Msk (1UL /*<< SAU_SFSR_INVEP_Pos*/) /*!< SAU SFSR: INVEP Mask */ - -/*@} end of group CMSIS_SAU */ -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_LSPENS_Pos 29U /*!< FPCCR: LSPENS Position */ -#define FPU_FPCCR_LSPENS_Msk (1UL << FPU_FPCCR_LSPENS_Pos) /*!< FPCCR: LSPENS bit Mask */ - -#define FPU_FPCCR_CLRONRET_Pos 28U /*!< FPCCR: CLRONRET Position */ -#define FPU_FPCCR_CLRONRET_Msk (1UL << FPU_FPCCR_CLRONRET_Pos) /*!< FPCCR: CLRONRET bit Mask */ - -#define FPU_FPCCR_CLRONRETS_Pos 27U /*!< FPCCR: CLRONRETS Position */ -#define FPU_FPCCR_CLRONRETS_Msk (1UL << FPU_FPCCR_CLRONRETS_Pos) /*!< FPCCR: CLRONRETS bit Mask */ - -#define FPU_FPCCR_TS_Pos 26U /*!< FPCCR: TS Position */ -#define FPU_FPCCR_TS_Msk (1UL << FPU_FPCCR_TS_Pos) /*!< FPCCR: TS bit Mask */ - -#define FPU_FPCCR_UFRDY_Pos 10U /*!< FPCCR: UFRDY Position */ -#define FPU_FPCCR_UFRDY_Msk (1UL << FPU_FPCCR_UFRDY_Pos) /*!< FPCCR: UFRDY bit Mask */ - -#define FPU_FPCCR_SPLIMVIOL_Pos 9U /*!< FPCCR: SPLIMVIOL Position */ -#define FPU_FPCCR_SPLIMVIOL_Msk (1UL << FPU_FPCCR_SPLIMVIOL_Pos) /*!< FPCCR: SPLIMVIOL bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_SFRDY_Pos 7U /*!< FPCCR: SFRDY Position */ -#define FPU_FPCCR_SFRDY_Msk (1UL << FPU_FPCCR_SFRDY_Pos) /*!< FPCCR: SFRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_S_Pos 2U /*!< FPCCR: Security status of the FP context bit Position */ -#define FPU_FPCCR_S_Msk (1UL << FPU_FPCCR_S_Pos) /*!< FPCCR: Security status of the FP context bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ - uint32_t RESERVED4[1U]; - __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ - __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ -#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/* Debug Authentication Control Register Definitions */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ - -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ - -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ - -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ - -/* Debug Security Control and Status Register Definitions */ -#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ -#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ - -#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ -#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ - -#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ -#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ - #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ - #define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ - #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ - #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ - #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ - #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ - #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ - #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - - #define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ - #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ - #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - #define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ - #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ - #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ - #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ - #endif - - #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ - #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ - #endif - - #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ - #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ - #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ - #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ - #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ - #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ - - #define SCnSCB_NS ((SCnSCB_Type *) SCS_BASE_NS ) /*!< System control Register not in SCB(non-secure address space) */ - #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ - #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ - #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ - #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ - #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ - #endif - - #define FPU_BASE_NS (SCS_BASE_NS + 0x0F30UL) /*!< Floating Point Unit (non-secure address space) */ - #define FPU_NS ((FPU_Type *) FPU_BASE_NS ) /*!< Floating Point Unit (non-secure address space) */ - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* Special LR values for Secure/Non-Secure call handling and exception handling */ - -/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ -#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ - -/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ -#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ -#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ -#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ -#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ -#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ -#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ -#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ - -/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ -#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ -#else -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ -#endif - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Interrupt Target State - \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - \return 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Target State - \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Clear Interrupt Target State - \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Priority Grouping (non-secure) - \details Sets the non-secure priority grouping field when in secure state using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void TZ_NVIC_SetPriorityGrouping_NS(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB_NS->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ - SCB_NS->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping (non-secure) - \details Reads the priority grouping field from the non-secure NVIC when in secure state. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriorityGrouping_NS(void) -{ - return ((uint32_t)((SCB_NS->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt (non-secure) - \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status (non-secure) - \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt (non-secure) - \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Pending Interrupt (non-secure) - \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt (non-secure) - \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt (non-secure) - \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt (non-secure) - \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority (non-secure) - \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every non-secure processor exception. - */ -__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority (non-secure) - \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC_NS->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv8.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) - { - return 2U; /* Double + Single precision FPU */ - } - else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## SAU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SAUFunctions SAU Functions - \brief Functions that configure the SAU. - @{ - */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - -/** - \brief Enable SAU - \details Enables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Enable(void) -{ - SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); -} - - - -/** - \brief Disable SAU - \details Disables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Disable(void) -{ - SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); -} - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_SAUFunctions */ - - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief System Tick Configuration (non-secure) - \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function TZ_SysTick_Config_NS is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - - */ -__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MML_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/body/board/inc/core_cm0plus.h b/body/board/inc/core_cm0plus.h deleted file mode 100644 index 424011ac363ade4..000000000000000 --- a/body/board/inc/core_cm0plus.h +++ /dev/null @@ -1,1083 +0,0 @@ -/**************************************************************************//** - * @file core_cm0plus.h - * @brief CMSIS Cortex-M0+ Core Peripheral Access Layer Header File - * @version V5.0.6 - * @date 28. May 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM0PLUS_H_GENERIC -#define __CORE_CM0PLUS_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex-M0+ - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM0+ definitions */ -#define __CM0PLUS_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM0PLUS_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM0PLUS_CMSIS_VERSION ((__CM0PLUS_CMSIS_VERSION_MAIN << 16U) | \ - __CM0PLUS_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (0U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM0PLUS_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM0PLUS_H_DEPENDANT -#define __CORE_CM0PLUS_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM0PLUS_REV - #define __CM0PLUS_REV 0x0000U - #warning "__CM0PLUS_REV not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __VTOR_PRESENT - #define __VTOR_PRESENT 0U - #warning "__VTOR_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex-M0+ */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core MPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[31U]; - __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[31U]; - __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[31U]; - __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[31U]; - uint32_t RESERVED4[64U]; - __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ -#else - uint32_t RESERVED0; -#endif - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) -/* SCB Interrupt Control State Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 8U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0xFFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 1U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 8U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0xFFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Cortex-M0+ Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. - Therefore they are not covered by the Cortex-M0+ header file. - @{ - */ -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ -/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M0+ */ - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - If VTOR is not present address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; - -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM0PLUS_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/body/board/inc/core_cm4.h b/body/board/inc/core_cm4.h deleted file mode 100644 index 7d56873532c3144..000000000000000 --- a/body/board/inc/core_cm4.h +++ /dev/null @@ -1,2129 +0,0 @@ -/**************************************************************************//** - * @file core_cm4.h - * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File - * @version V5.0.8 - * @date 04. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM4_H_GENERIC -#define __CORE_CM4_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M4 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM4 definitions */ -#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ - __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (4U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM4_H_DEPENDANT -#define __CORE_CM4_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM4_REV - #define __CM4_REV 0x0000U - #warning "__CM4_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M4 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ - uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ -#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ - -#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ -#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ -#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ -#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ -#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/body/board/inc/core_cmFunc.h b/body/board/inc/core_cmFunc.h deleted file mode 100644 index 652a48af07a93d9..000000000000000 --- a/body/board/inc/core_cmFunc.h +++ /dev/null @@ -1,87 +0,0 @@ -/**************************************************************************//** - * @file core_cmFunc.h - * @brief CMSIS Cortex-M Core Function Access Header File - * @version V4.30 - * @date 20. October 2015 - ******************************************************************************/ -/* Copyright (c) 2009 - 2015 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - 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. - - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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. - ---------------------------------------------------------------------------*/ - - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CMFUNC_H -#define __CORE_CMFUNC_H - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ -*/ - -/*------------------ RealView Compiler -----------------*/ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - -/*------------------ ARM Compiler V6 -------------------*/ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armcc_V6.h" - -/*------------------ GNU Compiler ----------------------*/ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - -/*------------------ ICC Compiler ----------------------*/ -#elif defined ( __ICCARM__ ) - #include - -/*------------------ TI CCS Compiler -------------------*/ -#elif defined ( __TMS470__ ) - #include - -/*------------------ TASKING Compiler ------------------*/ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - -/*------------------ COSMIC Compiler -------------------*/ -#elif defined ( __CSMC__ ) - #include - -#endif - -/*@} end of CMSIS_Core_RegAccFunctions */ - -#endif /* __CORE_CMFUNC_H */ diff --git a/body/board/inc/core_cmInstr.h b/body/board/inc/core_cmInstr.h deleted file mode 100644 index f474b0e6f362c73..000000000000000 --- a/body/board/inc/core_cmInstr.h +++ /dev/null @@ -1,87 +0,0 @@ -/**************************************************************************//** - * @file core_cmInstr.h - * @brief CMSIS Cortex-M Core Instruction Access Header File - * @version V4.30 - * @date 20. October 2015 - ******************************************************************************/ -/* Copyright (c) 2009 - 2015 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - 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. - - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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. - ---------------------------------------------------------------------------*/ - - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CMINSTR_H -#define __CORE_CMINSTR_H - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/*------------------ RealView Compiler -----------------*/ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - -/*------------------ ARM Compiler V6 -------------------*/ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armcc_V6.h" - -/*------------------ GNU Compiler ----------------------*/ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - -/*------------------ ICC Compiler ----------------------*/ -#elif defined ( __ICCARM__ ) - #include - -/*------------------ TI CCS Compiler -------------------*/ -#elif defined ( __TMS470__ ) - #include - -/*------------------ TASKING Compiler ------------------*/ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - -/*------------------ COSMIC Compiler -------------------*/ -#elif defined ( __CSMC__ ) - #include - -#endif - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - -#endif /* __CORE_CMINSTR_H */ diff --git a/body/board/inc/core_cmSimd.h b/body/board/inc/core_cmSimd.h deleted file mode 100644 index 66bf5c2a725b6d1..000000000000000 --- a/body/board/inc/core_cmSimd.h +++ /dev/null @@ -1,96 +0,0 @@ -/**************************************************************************//** - * @file core_cmSimd.h - * @brief CMSIS Cortex-M SIMD Header File - * @version V4.30 - * @date 20. October 2015 - ******************************************************************************/ -/* Copyright (c) 2009 - 2015 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - 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. - - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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. - ---------------------------------------------------------------------------*/ - - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CMSIMD_H -#define __CORE_CMSIMD_H - -#ifdef __cplusplus - extern "C" { -#endif - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -/*------------------ RealView Compiler -----------------*/ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - -/*------------------ ARM Compiler V6 -------------------*/ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armcc_V6.h" - -/*------------------ GNU Compiler ----------------------*/ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - -/*------------------ ICC Compiler ----------------------*/ -#elif defined ( __ICCARM__ ) - #include - -/*------------------ TI CCS Compiler -------------------*/ -#elif defined ( __TMS470__ ) - #include - -/*------------------ TASKING Compiler ------------------*/ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - -/*------------------ COSMIC Compiler -------------------*/ -#elif defined ( __CSMC__ ) - #include - -#endif - -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CMSIMD_H */ diff --git a/body/board/inc/mpu_armv7.h b/body/board/inc/mpu_armv7.h deleted file mode 100644 index 01422033d087616..000000000000000 --- a/body/board/inc/mpu_armv7.h +++ /dev/null @@ -1,270 +0,0 @@ -/****************************************************************************** - * @file mpu_armv7.h - * @brief CMSIS MPU API for Armv7-M MPU - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV7_H -#define ARM_MPU_ARMV7_H - -#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes -#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes -#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes -#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes -#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes -#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte -#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes -#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes -#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes -#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes -#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes -#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes -#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes -#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes -#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes -#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte -#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes -#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes -#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes -#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes -#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes -#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes -#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes -#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes -#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes -#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte -#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes -#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes - -#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access -#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only -#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only -#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access -#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only -#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access - -/** MPU Region Base Address Register Value -* -* \param Region The region to be configured, number 0 to 15. -* \param BaseAddress The base address for the region. -*/ -#define ARM_MPU_RBAR(Region, BaseAddress) \ - (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \ - ((Region) & MPU_RBAR_REGION_Msk) | \ - (MPU_RBAR_VALID_Msk)) - -/** -* MPU Memory Access Attributes -* -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -*/ -#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ - ((((TypeExtField ) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \ - (((IsShareable ) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \ - (((IsCacheable ) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \ - (((IsBufferable ) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ - ((((DisableExec ) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \ - (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \ - (((AccessAttributes) ) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ - ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) - -/** -* MPU Memory Access Attribute for strongly ordered memory. -* - TEX: 000b -* - Shareable -* - Non-cacheable -* - Non-bufferable -*/ -#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) - -/** -* MPU Memory Access Attribute for device memory. -* - TEX: 000b (if non-shareable) or 010b (if shareable) -* - Shareable or non-shareable -* - Non-cacheable -* - Bufferable (if shareable) or non-bufferable (if non-shareable) -* -* \param IsShareable Configures the device memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) - -/** -* MPU Memory Access Attribute for normal memory. -* - TEX: 1BBb (reflecting outer cacheability rules) -* - Shareable or non-shareable -* - Cacheable or non-cacheable (reflecting inner cacheability rules) -* - Bufferable or non-bufferable (reflecting inner cacheability rules) -* -* \param OuterCp Configures the outer cache policy. -* \param InnerCp Configures the inner cache policy. -* \param IsShareable Configures the memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) & 2U), ((InnerCp) & 1U)) - -/** -* MPU Memory Access Attribute non-cacheable policy. -*/ -#define ARM_MPU_CACHEP_NOCACHE 0U - -/** -* MPU Memory Access Attribute write-back, write and read allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_WRA 1U - -/** -* MPU Memory Access Attribute write-through, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WT_NWA 2U - -/** -* MPU Memory Access Attribute write-back, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_NWA 3U - - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; //!< The region base address register value (RBAR) - uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - MPU->RNR = rnr; - MPU->RASR = 0U; -} - -/** Configure an MPU region. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) -{ - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) -{ - MPU->RNR = rnr; - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - while (cnt > MPU_TYPE_RALIASES) { - orderedCpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); - table += MPU_TYPE_RALIASES; - cnt -= MPU_TYPE_RALIASES; - } - orderedCpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); -} - -#endif diff --git a/body/board/inc/mpu_armv8.h b/body/board/inc/mpu_armv8.h deleted file mode 100644 index 62571da5b874cbe..000000000000000 --- a/body/board/inc/mpu_armv8.h +++ /dev/null @@ -1,333 +0,0 @@ -/****************************************************************************** - * @file mpu_armv8.h - * @brief CMSIS MPU API for Armv8-M MPU - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV8_H -#define ARM_MPU_ARMV8_H - -/** \brief Attribute for device memory (outer only) */ -#define ARM_MPU_ATTR_DEVICE ( 0U ) - -/** \brief Attribute for non-cacheable, normal memory */ -#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U ) - -/** \brief Attribute for normal memory (outer and inner) -* \param NT Non-Transient: Set to 1 for non-transient data. -* \param WB Write-Back: Set to 1 to use write-back update policy. -* \param RA Read Allocation: Set to 1 to use cache allocation on read miss. -* \param WA Write Allocation: Set to 1 to use cache allocation on write miss. -*/ -#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \ - (((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U)) - -/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U) - -/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRE (1U) - -/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGRE (2U) - -/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_GRE (3U) - -/** \brief Memory Attribute -* \param O Outer memory attributes -* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes -*/ -#define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U))) - -/** \brief Normal memory non-shareable */ -#define ARM_MPU_SH_NON (0U) - -/** \brief Normal memory outer shareable */ -#define ARM_MPU_SH_OUTER (2U) - -/** \brief Normal memory inner shareable */ -#define ARM_MPU_SH_INNER (3U) - -/** \brief Memory access permissions -* \param RO Read-Only: Set to 1 for read-only memory. -* \param NP Non-Privileged: Set to 1 for non-privileged memory. -*/ -#define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U)) - -/** \brief Region Base Address Register value -* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned. -* \param SH Defines the Shareability domain for this memory region. -* \param RO Read-Only: Set to 1 for a read-only memory region. -* \param NP Non-Privileged: Set to 1 for a non-privileged memory region. -* \oaram XN eXecute Never: Set to 1 for a non-executable memory region. -*/ -#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \ - ((BASE & MPU_RBAR_BASE_Msk) | \ - ((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \ - ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \ - ((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk)) - -/** \brief Region Limit Address Register value -* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. -* \param IDX The attribute index to be associated with this memory region. -*/ -#define ARM_MPU_RLAR(LIMIT, IDX) \ - ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ - ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ - (MPU_RLAR_EN_Msk)) - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; /*!< Region Base Address Register value */ - uint32_t RLAR; /*!< Region Limit Address Register value */ -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -#ifdef MPU_NS -/** Enable the Non-secure MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the Non-secure MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable_NS(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} -#endif - -/** Set the memory attribute encoding to the given MPU. -* \param mpu Pointer to the MPU to be configured. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr) -{ - const uint8_t reg = idx / 4U; - const uint32_t pos = ((idx % 4U) * 8U); - const uint32_t mask = 0xFFU << pos; - - if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) { - return; // invalid index - } - - mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask)); -} - -/** Set the memory attribute encoding. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU, idx, attr); -} - -#ifdef MPU_NS -/** Set the memory attribute encoding to the Non-secure MPU. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr); -} -#endif - -/** Clear and disable the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr) -{ - mpu->RNR = rnr; - mpu->RLAR = 0U; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU, rnr); -} - -#ifdef MPU_NS -/** Clear and disable the given Non-secure MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU_NS, rnr); -} -#endif - -/** Configure the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - mpu->RNR = rnr; - mpu->RBAR = rbar; - mpu->RLAR = rlar; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar); -} - -#ifdef MPU_NS -/** Configure the given Non-secure MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar); -} -#endif - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table to the given MPU. -* \param mpu Pointer to the MPU registers to be used. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - if (cnt == 1U) { - mpu->RNR = rnr; - orderedCpy(&(mpu->RBAR), &(table->RBAR), rowWordSize); - } else { - uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U); - uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES; - - mpu->RNR = rnrBase; - while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) { - uint32_t c = MPU_TYPE_RALIASES - rnrOffset; - orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); - table += c; - cnt -= c; - rnrOffset = 0U; - rnrBase += MPU_TYPE_RALIASES; - mpu->RNR = rnrBase; - } - - orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize); - } -} - -/** Load the given number of MPU regions from a table. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU, rnr, table, cnt); -} - -#ifdef MPU_NS -/** Load the given number of MPU regions from a table to the Non-secure MPU. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt); -} -#endif - -#endif - diff --git a/body/board/inc/stm32f413xx.h b/body/board/inc/stm32f413xx.h deleted file mode 100644 index e9db50f0cf92a3c..000000000000000 --- a/body/board/inc/stm32f413xx.h +++ /dev/null @@ -1,15467 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f413xx.h - * @author MCD Application Team - * @brief CMSIS STM32F413xx 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) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32f413xx - * @{ - */ - -#ifndef __STM32F413xx_H -#define __STM32F413xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Configuration_section_for_CMSIS - * @{ - */ - -/** - * @brief Configuration of the Cortex-M4 Processor and Core Peripherals - */ -#define __CM4_REV 0x0001U /*!< Core revision r0p1 */ -#define __MPU_PRESENT 1U /*!< STM32F4XX provides an MPU */ -#define __NVIC_PRIO_BITS 4U /*!< STM32F4XX uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ -#define __FPU_PRESENT 1U /*!< FPU present */ - -/** - * @} - */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32F4XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M4 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 global interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 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 */ - DFSDM1_FLT0_IRQn = 61, /*!< DFSDM1 Filter 0 global Interrupt */ - DFSDM1_FLT1_IRQn = 62, /*!< DFSDM1 Filter 1 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 */ - CAN3_TX_IRQn = 74, /*!< CAN3 TX Interrupt */ - CAN3_RX0_IRQn = 75, /*!< CAN3 RX0 Interrupt */ - CAN3_RX1_IRQn = 76, /*!< CAN3 RX1 Interrupt */ - CAN3_SCE_IRQn = 77, /*!< CAN3 SCE Interrupt */ - RNG_IRQn = 80, /*!< RNG global Interrupt */ - FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - UART9_IRQn = 88, /*!< UART9 global Interrupt */ - UART10_IRQn = 89, /*!< UART10 global Interrupt */ - QUADSPI_IRQn = 92, /*!< QuadSPI global Interrupt */ - FMPI2C1_EV_IRQn = 95, /*!< FMPI2C1 Event Interrupt */ - FMPI2C1_ER_IRQn = 96, /*!< FMPI2C1 Error Interrupt */ - LPTIM1_IRQn = 97, /*!< LP TIM1 interrupt */ - DFSDM2_FLT0_IRQn = 98, /*!< DFSDM2 Filter 0 global Interrupt */ - DFSDM2_FLT1_IRQn = 99, /*!< DFSDM2 Filter 1 global Interrupt */ - DFSDM2_FLT2_IRQn = 100, /*!< DFSDM2 Filter 2 global Interrupt */ - DFSDM2_FLT3_IRQn = 101 /*!< DFSDM2 Filter 3 global Interrupt */ -} IRQn_Type; - -/** - * @} - */ - -#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ -#include "system_stm32f4xx.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 DFSDM module registers - */ -typedef struct -{ - __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ - __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ - __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ - __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ - __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ - __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ - __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ - __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ - __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ - __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ - __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ - __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ - __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ - __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ - __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ -} DFSDM_Filter_TypeDef; - -/** - * @brief DFSDM channel configuration registers - */ -typedef struct -{ - __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ - __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ - __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and - short circuit detector register, Address offset: 0x08 */ - __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ - __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ -} DFSDM_Channel_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 */ - __IO uint32_t OPTCR1; /*!< FLASH option control register 1, Address offset: 0x18 */ -} 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 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; /*!< Reserved, 0x18 */ - __IO uint32_t CFGR2; /*!< SYSCFG Configuration register2, Address offset: 0x1C */ - __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x24-0x28 */ - __IO uint32_t CFGR; /*!< SYSCFG Configuration register, Address offset: 0x2C */ - __IO uint32_t MCHDLYCR; /*!< SYSCFG multi-channel delay register, Address offset: 0x30 */ -} 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 */ - __IO uint32_t FLTR; /*!< I2C FLTR register, Address offset: 0x24 */ -} I2C_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< FMPI2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< FMPI2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< FMPI2C Own address 1 register, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< FMPI2C Own address 2 register, Address offset: 0x0C */ - __IO uint32_t TIMINGR; /*!< FMPI2C Timing register, Address offset: 0x10 */ - __IO uint32_t TIMEOUTR; /*!< FMPI2C Timeout register, Address offset: 0x14 */ - __IO uint32_t ISR; /*!< FMPI2C Interrupt and status register, Address offset: 0x18 */ - __IO uint32_t ICR; /*!< FMPI2C Interrupt clear register, Address offset: 0x1C */ - __IO uint32_t PECR; /*!< FMPI2C PEC register, Address offset: 0x20 */ - __IO uint32_t RXDR; /*!< FMPI2C Receive data register, Address offset: 0x24 */ - __IO uint32_t TXDR; /*!< FMPI2C Transmit data register, Address offset: 0x28 */ -} FMPI2C_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 */ - uint32_t RESERVED7; /*!< Reserved, 0x84 */ - __IO uint32_t DCKCFGR; /*!< RCC Dedicated Clocks configuration register, Address offset: 0x8C */ - __IO uint32_t CKGATENR; /*!< RCC Clocks Gated ENable Register, Address offset: 0x90 */ - __IO uint32_t DCKCFGR2; /*!< RCC Dedicated Clocks configuration register 2, Address offset: 0x94 */ -} 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 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 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 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register, Address offset: 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 Serial Audio Interface - */ - -typedef struct -{ - __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ -} SAI_TypeDef; - -typedef struct -{ - __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ - __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ - __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ - __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ - __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ - __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ -} SAI_Block_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 QUAD Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< QUADSPI Control register, Address offset: 0x00 */ - __IO uint32_t DCR; /*!< QUADSPI Device Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< QUADSPI Status register, Address offset: 0x08 */ - __IO uint32_t FCR; /*!< QUADSPI Flag Clear register, Address offset: 0x0C */ - __IO uint32_t DLR; /*!< QUADSPI Data Length register, Address offset: 0x10 */ - __IO uint32_t CCR; /*!< QUADSPI Communication Configuration register, Address offset: 0x14 */ - __IO uint32_t AR; /*!< QUADSPI Address register, Address offset: 0x18 */ - __IO uint32_t ABR; /*!< QUADSPI Alternate Bytes register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< QUADSPI Data register, Address offset: 0x20 */ - __IO uint32_t PSMKR; /*!< QUADSPI Polling Status Mask register, Address offset: 0x24 */ - __IO uint32_t PSMAR; /*!< QUADSPI Polling Status Match register, Address offset: 0x28 */ - __IO uint32_t PIR; /*!< QUADSPI Polling Interval register, Address offset: 0x2C */ - __IO uint32_t LPTR; /*!< QUADSPI Low Power Timeout register, Address offset: 0x30 */ -} QUADSPI_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_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - uint32_t Reserved5[3]; /*!< Reserved 040h-048h */ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - uint32_t Reserved; /*!< Reserved 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - uint32_t Reserved43[40]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - -/** - * @brief USB_OTG_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 USB_OTG_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 USB_OTG_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 USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; - -/** - * @brief LPTIMER - */ -typedef struct -{ - __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ - __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ - __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ - __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ - __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ - __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ - __IO uint32_t OR; /*!< LPTIM Option register, Address offset: 0x20 */ -} LPTIM_TypeDef; - -/** - * @} - */ - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define FLASH_BASE 0x08000000UL /*!< FLASH (up to 1.5 MB) base address in the alias region */ -#define SRAM1_BASE 0x20000000UL /*!< SRAM1(256 KB) base address in the alias region */ -#define SRAM2_BASE 0x20040000UL /*!< SRAM2(64 KB) base address in the alias region */ -#define PERIPH_BASE 0x40000000UL /*!< Peripheral base address in the alias region */ -#define FSMC_R_BASE 0xA0000000UL /*!< FSMC registers base address */ -#define QSPI_R_BASE 0xA0001000UL /*!< QuadSPI registers base address */ -#define SRAM1_BB_BASE 0x22000000UL /*!< SRAM1(256 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE 0x22800000UL /*!< SRAM2(64 KB) base address in the bit-band region */ -#define PERIPH_BB_BASE 0x42000000UL /*!< Peripheral base address in the bit-band region */ -#define FLASH_END 0x0817FFFFUL /*!< FLASH end address */ -#define FLASH_OTP_BASE 0x1FFF7800UL /*!< Base address of : (up to 528 Bytes) embedded FLASH OTP Area */ -#define FLASH_OTP_END 0x1FFF7A0FUL /*!< End address of : (up to 528 Bytes) embedded FLASH OTP Area */ - -/* 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 + 0x00010000UL) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000UL) - -/*!< APB1 peripherals */ -#define TIM2_BASE (APB1PERIPH_BASE + 0x0000UL) -#define TIM3_BASE (APB1PERIPH_BASE + 0x0400UL) -#define TIM4_BASE (APB1PERIPH_BASE + 0x0800UL) -#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00UL) -#define TIM6_BASE (APB1PERIPH_BASE + 0x1000UL) -#define TIM7_BASE (APB1PERIPH_BASE + 0x1400UL) -#define TIM12_BASE (APB1PERIPH_BASE + 0x1800UL) -#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00UL) -#define TIM14_BASE (APB1PERIPH_BASE + 0x2000UL) -#define LPTIM1_BASE (APB1PERIPH_BASE + 0x2400UL) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800UL) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00UL) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000UL) -#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400UL) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800UL) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00UL) -#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000UL) -#define USART2_BASE (APB1PERIPH_BASE + 0x4400UL) -#define USART3_BASE (APB1PERIPH_BASE + 0x4800UL) -#define UART4_BASE (APB1PERIPH_BASE + 0x4C00UL) -#define UART5_BASE (APB1PERIPH_BASE + 0x5000UL) -#define I2C1_BASE (APB1PERIPH_BASE + 0x5400UL) -#define I2C2_BASE (APB1PERIPH_BASE + 0x5800UL) -#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00UL) -#define FMPI2C1_BASE (APB1PERIPH_BASE + 0x6000UL) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400UL) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800UL) -#define CAN3_BASE (APB1PERIPH_BASE + 0x6C00UL) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000UL) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400UL) -#define UART7_BASE (APB1PERIPH_BASE + 0x7800UL) -#define UART8_BASE (APB1PERIPH_BASE + 0x7C00UL) - -/*!< APB2 peripherals */ -#define TIM1_BASE (APB2PERIPH_BASE + 0x0000UL) -#define TIM8_BASE (APB2PERIPH_BASE + 0x0400UL) -#define USART1_BASE (APB2PERIPH_BASE + 0x1000UL) -#define USART6_BASE (APB2PERIPH_BASE + 0x1400UL) -#define UART9_BASE (APB2PERIPH_BASE + 0x1800UL) -#define UART10_BASE (APB2PERIPH_BASE + 0x1C00UL) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2000UL) -#define ADC1_COMMON_BASE (APB2PERIPH_BASE + 0x2300UL) -/* Legacy define */ -#define ADC_BASE ADC1_COMMON_BASE -#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00UL) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000UL) -#define SPI4_BASE (APB2PERIPH_BASE + 0x3400UL) -#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800UL) -#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00UL) -#define TIM9_BASE (APB2PERIPH_BASE + 0x4000UL) -#define TIM10_BASE (APB2PERIPH_BASE + 0x4400UL) -#define TIM11_BASE (APB2PERIPH_BASE + 0x4800UL) -#define SPI5_BASE (APB2PERIPH_BASE + 0x5000UL) -#define DFSDM1_BASE (APB2PERIPH_BASE + 0x6000UL) -#define DFSDM2_BASE (APB2PERIPH_BASE + 0x6400UL) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00UL) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20UL) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40UL) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60UL) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) -#define DFSDM2_Channel0_BASE (DFSDM2_BASE + 0x00UL) -#define DFSDM2_Channel1_BASE (DFSDM2_BASE + 0x20UL) -#define DFSDM2_Channel2_BASE (DFSDM2_BASE + 0x40UL) -#define DFSDM2_Channel3_BASE (DFSDM2_BASE + 0x60UL) -#define DFSDM2_Channel4_BASE (DFSDM2_BASE + 0x80UL) -#define DFSDM2_Channel5_BASE (DFSDM2_BASE + 0xA0UL) -#define DFSDM2_Channel6_BASE (DFSDM2_BASE + 0xC0UL) -#define DFSDM2_Channel7_BASE (DFSDM2_BASE + 0xE0UL) -#define DFSDM2_Filter0_BASE (DFSDM2_BASE + 0x100UL) -#define DFSDM2_Filter1_BASE (DFSDM2_BASE + 0x180UL) -#define DFSDM2_Filter2_BASE (DFSDM2_BASE + 0x200UL) -#define DFSDM2_Filter3_BASE (DFSDM2_BASE + 0x280UL) -#define SAI1_BASE (APB2PERIPH_BASE + 0x5800UL) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) - -/*!< AHB1 peripherals */ -#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000UL) -#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400UL) -#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800UL) -#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00UL) -#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000UL) -#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400UL) -#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800UL) -#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00UL) -#define CRC_BASE (AHB1PERIPH_BASE + 0x3000UL) -#define RCC_BASE (AHB1PERIPH_BASE + 0x3800UL) -#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00UL) -#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000UL) -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) -#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400UL) -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) - -/*!< AHB2 peripherals */ -#define RNG_BASE (AHB2PERIPH_BASE + 0x60800UL) - - -/*!< FSMC Bankx registers base address */ -#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000UL) -#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104UL) - -/*!< Debug MCU registers base address */ -#define DBGMCU_BASE 0xE0042000UL -/*!< USB registers base address */ -#define USB_OTG_FS_PERIPH_BASE 0x50000000UL - -#define USB_OTG_GLOBAL_BASE 0x000UL -#define USB_OTG_DEVICE_BASE 0x800UL -#define USB_OTG_IN_ENDPOINT_BASE 0x900UL -#define USB_OTG_OUT_ENDPOINT_BASE 0xB00UL -#define USB_OTG_EP_REG_SIZE 0x20UL -#define USB_OTG_HOST_BASE 0x400UL -#define USB_OTG_HOST_PORT_BASE 0x440UL -#define USB_OTG_HOST_CHANNEL_BASE 0x500UL -#define USB_OTG_HOST_CHANNEL_SIZE 0x20UL -#define USB_OTG_PCGCCTL_BASE 0xE00UL -#define USB_OTG_FIFO_BASE 0x1000UL -#define USB_OTG_FIFO_SIZE 0x1000UL - -#define UID_BASE 0x1FFF7A10UL /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE 0x1FFF7A22UL /*!< FLASH Size register base address */ -#define PACKAGE_BASE 0x1FFF7BF0UL /*!< Package size register base address */ -/** - * @} - */ - -/** @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 LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG ((WWDG_TypeDef *) WWDG_BASE) -#define IWDG ((IWDG_TypeDef *) IWDG_BASE) -#define I2S2ext ((SPI_TypeDef *) I2S2ext_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define I2S3ext ((SPI_TypeDef *) I2S3ext_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 FMPI2C1 ((FMPI2C_TypeDef *) FMPI2C1_BASE) -#define CAN1 ((CAN_TypeDef *) CAN1_BASE) -#define CAN2 ((CAN_TypeDef *) CAN2_BASE) -#define CAN3 ((CAN_TypeDef *) CAN3_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC_BASE) -#define DAC ((DAC_TypeDef *) DAC_BASE) /* Kept for legacy purpose */ -#define UART7 ((USART_TypeDef *) UART7_BASE) -#define UART8 ((USART_TypeDef *) UART8_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 UART9 ((USART_TypeDef *) UART9_BASE) -#define UART10 ((USART_TypeDef *) UART10_BASE) -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC1_COMMON ((ADC_Common_TypeDef *) ADC1_COMMON_BASE) -/* Legacy define */ -#define ADC ADC1_COMMON -#define SDIO ((SDIO_TypeDef *) SDIO_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define SPI4 ((SPI_TypeDef *) SPI4_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 SPI5 ((SPI_TypeDef *) SPI5_BASE) -#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) -#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) -#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) -#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) -#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) -#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) -#define DFSDM2_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel0_BASE) -#define DFSDM2_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel1_BASE) -#define DFSDM2_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel2_BASE) -#define DFSDM2_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel3_BASE) -#define DFSDM2_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel4_BASE) -#define DFSDM2_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel5_BASE) -#define DFSDM2_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel6_BASE) -#define DFSDM2_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel7_BASE) -#define DFSDM2_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter0_BASE) -#define DFSDM2_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter1_BASE) -#define DFSDM2_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter2_BASE) -#define DFSDM2_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter3_BASE) -#define SAI1 ((SAI_TypeDef *) SAI1_BASE) -#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) -#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_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 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 QUADSPI ((QUADSPI_TypeDef *) QSPI_R_BASE) -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) -#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - -/** @addtogroup Hardware_Constant_Definition - * @{ - */ -#define LSI_STARTUP_TIME 40U /*!< LSI Maximum startup time in us */ -/** - * @} - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ - -/******************** Bit definition for ADC_SR register ********************/ -#define ADC_SR_AWD_Pos (0U) -#define ADC_SR_AWD_Msk (0x1UL << ADC_SR_AWD_Pos) /*!< 0x00000001 */ -#define ADC_SR_AWD ADC_SR_AWD_Msk /*!
© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.
- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx - * @{ - */ - -#ifndef __STM32F4xx_H -#define __STM32F4xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Library_configuration_section - * @{ - */ - -/** - * @brief STM32 Family - */ -#if !defined (STM32F4) -#define STM32F4 -#endif /* STM32F4 */ - -/* Uncomment the line below according to the target STM32 device used in your - application - */ -#if !defined (STM32F405xx) && !defined (STM32F415xx) && !defined (STM32F407xx) && !defined (STM32F417xx) && \ - !defined (STM32F427xx) && !defined (STM32F437xx) && !defined (STM32F429xx) && !defined (STM32F439xx) && \ - !defined (STM32F401xC) && !defined (STM32F401xE) && !defined (STM32F410Tx) && !defined (STM32F410Cx) && \ - !defined (STM32F410Rx) && !defined (STM32F411xE) && !defined (STM32F446xx) && !defined (STM32F469xx) && \ - !defined (STM32F479xx) && !defined (STM32F412Cx) && !defined (STM32F412Rx) && !defined (STM32F412Vx) && \ - !defined (STM32F412Zx) && !defined (STM32F413xx) && !defined (STM32F423xx) - /* #define STM32F405xx */ /*!< STM32F405RG, STM32F405VG and STM32F405ZG Devices */ - /* #define STM32F415xx */ /*!< STM32F415RG, STM32F415VG and STM32F415ZG Devices */ - /* #define STM32F407xx */ /*!< STM32F407VG, STM32F407VE, STM32F407ZG, STM32F407ZE, STM32F407IG and STM32F407IE Devices */ - /* #define STM32F417xx */ /*!< STM32F417VG, STM32F417VE, STM32F417ZG, STM32F417ZE, STM32F417IG and STM32F417IE Devices */ - /* #define STM32F427xx */ /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG and STM32F427II Devices */ - /* #define STM32F437xx */ /*!< STM32F437VG, STM32F437VI, STM32F437ZG, STM32F437ZI, STM32F437IG and STM32F437II Devices */ - /* #define STM32F429xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, STM32F429NG, - STM32F439NI, STM32F429IG and STM32F429II Devices */ - /* #define STM32F439xx */ /*!< STM32F439VG, STM32F439VI, STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG, - STM32F439NI, STM32F439IG and STM32F439II Devices */ - /* #define STM32F401xC */ /*!< STM32F401CB, STM32F401CC, STM32F401RB, STM32F401RC, STM32F401VB and STM32F401VC Devices */ - /* #define STM32F401xE */ /*!< STM32F401CD, STM32F401RD, STM32F401VD, STM32F401CE, STM32F401RE and STM32F401VE Devices */ - /* #define STM32F410Tx */ /*!< STM32F410T8 and STM32F410TB Devices */ - /* #define STM32F410Cx */ /*!< STM32F410C8 and STM32F410CB Devices */ - /* #define STM32F410Rx */ /*!< STM32F410R8 and STM32F410RB Devices */ - /* #define STM32F411xE */ /*!< STM32F411CC, STM32F411RC, STM32F411VC, STM32F411CE, STM32F411RE and STM32F411VE Devices */ - /* #define STM32F446xx */ /*!< STM32F446MC, STM32F446ME, STM32F446RC, STM32F446RE, STM32F446VC, STM32F446VE, STM32F446ZC, - and STM32F446ZE Devices */ - /* #define STM32F469xx */ /*!< STM32F469AI, STM32F469II, STM32F469BI, STM32F469NI, STM32F469AG, STM32F469IG, STM32F469BG, - STM32F469NG, STM32F469AE, STM32F469IE, STM32F469BE and STM32F469NE Devices */ - /* #define STM32F479xx */ /*!< STM32F479AI, STM32F479II, STM32F479BI, STM32F479NI, STM32F479AG, STM32F479IG, STM32F479BG - and STM32F479NG Devices */ - /* #define STM32F412Cx */ /*!< STM32F412CEU and STM32F412CGU Devices */ - /* #define STM32F412Zx */ /*!< STM32F412ZET, STM32F412ZGT, STM32F412ZEJ and STM32F412ZGJ Devices */ - /* #define STM32F412Vx */ /*!< STM32F412VET, STM32F412VGT, STM32F412VEH and STM32F412VGH Devices */ - /* #define STM32F412Rx */ /*!< STM32F412RET, STM32F412RGT, STM32F412REY and STM32F412RGY Devices */ - /* #define STM32F413xx */ /*!< STM32F413CH, STM32F413MH, STM32F413RH, STM32F413VH, STM32F413ZH, STM32F413CG, STM32F413MG, - STM32F413RG, STM32F413VG and STM32F413ZG Devices */ - /* #define STM32F423xx */ /*!< STM32F423CH, STM32F423RH, STM32F423VH and STM32F423ZH 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 version number V2.6.7 - */ -#define __STM32F4xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ -#define __STM32F4xx_CMSIS_VERSION_SUB1 (0x06U) /*!< [23:16] sub1 version */ -#define __STM32F4xx_CMSIS_VERSION_SUB2 (0x07U) /*!< [15:8] sub2 version */ -#define __STM32F4xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ -#define __STM32F4xx_CMSIS_VERSION ((__STM32F4xx_CMSIS_VERSION_MAIN << 24)\ - |(__STM32F4xx_CMSIS_VERSION_SUB1 << 16)\ - |(__STM32F4xx_CMSIS_VERSION_SUB2 << 8 )\ - |(__STM32F4xx_CMSIS_VERSION_RC)) - -/** - * @} - */ - -/** @addtogroup Device_Included - * @{ - */ - -#if defined(STM32F405xx) - #include "stm32f405xx.h" -#elif defined(STM32F415xx) - #include "stm32f415xx.h" -#elif defined(STM32F407xx) - #include "stm32f407xx.h" -#elif defined(STM32F417xx) - #include "stm32f417xx.h" -#elif defined(STM32F427xx) - #include "stm32f427xx.h" -#elif defined(STM32F437xx) - #include "stm32f437xx.h" -#elif defined(STM32F429xx) - #include "stm32f429xx.h" -#elif defined(STM32F439xx) - #include "stm32f439xx.h" -#elif defined(STM32F401xC) - #include "stm32f401xc.h" -#elif defined(STM32F401xE) - #include "stm32f401xe.h" -#elif defined(STM32F410Tx) - #include "stm32f410tx.h" -#elif defined(STM32F410Cx) - #include "stm32f410cx.h" -#elif defined(STM32F410Rx) - #include "stm32f410rx.h" -#elif defined(STM32F411xE) - #include "stm32f411xe.h" -#elif defined(STM32F446xx) - #include "stm32f446xx.h" -#elif defined(STM32F469xx) - #include "stm32f469xx.h" -#elif defined(STM32F479xx) - #include "stm32f479xx.h" -#elif defined(STM32F412Cx) - #include "stm32f412cx.h" -#elif defined(STM32F412Zx) - #include "stm32f412zx.h" -#elif defined(STM32F412Rx) - #include "stm32f412rx.h" -#elif defined(STM32F412Vx) - #include "stm32f412vx.h" -#elif defined(STM32F413xx) - #include "stm32f413xx.h" -#elif defined(STM32F423xx) - #include "stm32f423xx.h" -#else - #error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)" -#endif - -/** - * @} - */ - -/** @addtogroup Exported_types - * @{ - */ -typedef enum -{ - RESET = 0U, - SET = !RESET -} FlagStatus, ITStatus; - -typedef enum -{ - DISABLE = 0U, - ENABLE = !DISABLE -} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum -{ - SUCCESS = 0U, - ERROR = !SUCCESS -} 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))) - -/* Use of CMSIS compiler intrinsics for register exclusive access */ -/* Atomic 32-bit register access macro to set one or several bits */ -#define ATOMIC_SET_BIT(REG, BIT) \ - do { \ - uint32_t val; \ - do { \ - val = __LDREXW((__IO uint32_t *)&(REG)) | (BIT); \ - } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 32-bit register access macro to clear one or several bits */ -#define ATOMIC_CLEAR_BIT(REG, BIT) \ - do { \ - uint32_t val; \ - do { \ - val = __LDREXW((__IO uint32_t *)&(REG)) & ~(BIT); \ - } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 32-bit register access macro to clear and set one or several bits */ -#define ATOMIC_MODIFY_REG(REG, CLEARMSK, SETMASK) \ - do { \ - uint32_t val; \ - do { \ - val = (__LDREXW((__IO uint32_t *)&(REG)) & ~(CLEARMSK)) | (SETMASK); \ - } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 16-bit register access macro to set one or several bits */ -#define ATOMIC_SETH_BIT(REG, BIT) \ - do { \ - uint16_t val; \ - do { \ - val = __LDREXH((__IO uint16_t *)&(REG)) | (BIT); \ - } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 16-bit register access macro to clear one or several bits */ -#define ATOMIC_CLEARH_BIT(REG, BIT) \ - do { \ - uint16_t val; \ - do { \ - val = __LDREXH((__IO uint16_t *)&(REG)) & ~(BIT); \ - } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 16-bit register access macro to clear and set one or several bits */ -#define ATOMIC_MODIFYH_REG(REG, CLEARMSK, SETMASK) \ - do { \ - uint16_t val; \ - do { \ - val = (__LDREXH((__IO uint16_t *)&(REG)) & ~(CLEARMSK)) | (SETMASK); \ - } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \ - } while(0) - -/** - * @} - */ - -#if defined (USE_HAL_DRIVER) - #include "stm32f4xx_hal.h" -#endif /* USE_HAL_DRIVER */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __STM32F4xx_H */ -/** - * @} - */ - -/** - * @} - */ - - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/stm32f4xx_hal_conf.h b/body/board/inc/stm32f4xx_hal_conf.h deleted file mode 100644 index 37e76267eca523a..000000000000000 --- a/body/board/inc/stm32f4xx_hal_conf.h +++ /dev/null @@ -1,477 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_conf.h - * @author MCD Application Team - * @brief HAL configuration file. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CONF_H -#define __STM32F4xx_HAL_CONF_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* ########################## Module Selection ############################## */ -/** - * @brief This is the list of modules to be used in the HAL driver - */ -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -/* #define HAL_CAN_MODULE_ENABLED */ -/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ -/* #define HAL_CRC_MODULE_ENABLED */ -/* #define HAL_CEC_MODULE_ENABLED */ -/* #define HAL_CRYP_MODULE_ENABLED */ -/* #define HAL_DAC_MODULE_ENABLED */ -/* #define HAL_DCMI_MODULE_ENABLED */ -#define HAL_DMA_MODULE_ENABLED -/* #define HAL_ETH_MODULE_ENABLED */ -#define HAL_FLASH_MODULE_ENABLED -/* #define HAL_NAND_MODULE_ENABLED */ -/* #define HAL_NOR_MODULE_ENABLED */ -/* #define HAL_PCCARD_MODULE_ENABLED */ -/* #define HAL_SRAM_MODULE_ENABLED */ -/* #define HAL_SDRAM_MODULE_ENABLED */ -/* #define HAL_HASH_MODULE_ENABLED */ -#define HAL_GPIO_MODULE_ENABLED -#define HAL_I2C_MODULE_ENABLED -/* #define HAL_I2S_MODULE_ENABLED */ -/* #define HAL_IWDG_MODULE_ENABLED */ -/* #define HAL_LTDC_MODULE_ENABLED */ -#define HAL_PWR_MODULE_ENABLED -/* #define HAL_QSPI_MODULE_ENABLED */ -#define HAL_RCC_MODULE_ENABLED -/* #define HAL_RNG_MODULE_ENABLED */ -/* #define HAL_RTC_MODULE_ENABLED */ -/* #define HAL_SAI_MODULE_ENABLED */ -/* #define HAL_SD_MODULE_ENABLED */ -/* #define HAL_SPI_MODULE_ENABLED */ -#define HAL_TIM_MODULE_ENABLED -#define HAL_UART_MODULE_ENABLED -/* #define HAL_USART_MODULE_ENABLED */ -/* #define HAL_IRDA_MODULE_ENABLED */ -/* #define HAL_SMARTCARD_MODULE_ENABLED */ -/* #define HAL_WWDG_MODULE_ENABLED */ -#define HAL_CORTEX_MODULE_ENABLED -/* #define HAL_PCD_MODULE_ENABLED */ -/* #define HAL_HCD_MODULE_ENABLED */ -/* #define HAL_FMPI2C_MODULE_ENABLED */ -/* #define HAL_SPDIFRX_MODULE_ENABLED */ -/* #define HAL_DFSDM_MODULE_ENABLED */ -/* #define HAL_LPTIM_MODULE_ENABLED */ - -/* ########################## HSE/HSI Values adaptation ##################### */ -/** - * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSE is used as system clock source, directly or through the PLL). - */ -#if !defined (HSE_VALUE) - #define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSE_STARTUP_TIMEOUT) - #define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ -#endif /* HSE_STARTUP_TIMEOUT */ - -/** - * @brief Internal High Speed oscillator (HSI) value. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSI is used as system clock source, directly or through the PLL). - */ -#if !defined (HSI_VALUE) - #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/ -#endif /* HSI_VALUE */ - -/** - * @brief Internal Low Speed oscillator (LSI) value. - */ -#if !defined (LSI_VALUE) - #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz*/ -#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz - The real value may vary depending on the variations - in voltage and temperature.*/ -/** - * @brief External Low Speed oscillator (LSE) value. - */ -#if !defined (LSE_VALUE) - #define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ -#endif /* LSE_VALUE */ - -#if !defined (LSE_STARTUP_TIMEOUT) - #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ -#endif /* LSE_STARTUP_TIMEOUT */ - -/** - * @brief External clock source for I2S peripheral - * This value is used by the I2S HAL module to compute the I2S clock source - * frequency, this source is inserted directly through I2S_CKIN pad. - */ -#if !defined (EXTERNAL_CLOCK_VALUE) - #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/ -#endif /* EXTERNAL_CLOCK_VALUE */ - -/* Tip: To avoid modifying this file each time you need to use different HSE, - === you can define the HSE value in your toolchain compiler preprocessor. */ - -/* ########################### System Configuration ######################### */ -/** - * @brief This is the HAL system configuration section - */ -#define VDD_VALUE 3300U /*!< Value of VDD in mv */ -#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */ -#define USE_RTOS 0U -#define PREFETCH_ENABLE 1U -#define INSTRUCTION_CACHE_ENABLE 1U -#define DATA_CACHE_ENABLE 1U - -#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ -#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ -#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ -#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ -#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ -#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ -#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ -#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ -#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ -#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ -#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ -#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ -#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ -#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ -#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ -#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ -#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ -#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ -#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ -#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ -#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ -#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ -#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ -#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ -#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ -#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ -#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ -#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ -#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ -#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ -#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ -#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ -#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ -#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ -#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ -#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ -#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ -#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ - -/* ########################## Assert Selection ############################## */ -/** - * @brief Uncomment the line below to expanse the "assert_param" macro in the - * HAL drivers code - */ -/* #define USE_FULL_ASSERT 1 */ - -/* ################## Ethernet peripheral configuration for NUCLEO 144 board ##################### */ - -/* Section 1 : Ethernet peripheral configuration */ - -/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ -#define MAC_ADDR0 2U -#define MAC_ADDR1 0U -#define MAC_ADDR2 0U -#define MAC_ADDR3 0U -#define MAC_ADDR4 0U -#define MAC_ADDR5 0U - -/* Definition of the Ethernet driver buffers size and count */ -#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ -#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ -#define ETH_RXBUFNB 5U /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ -#define ETH_TXBUFNB 5U /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ - -/* Section 2: PHY configuration section */ -/* LAN8742A PHY Address*/ -#define LAN8742A_PHY_ADDRESS 0x00U -/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ -#define PHY_RESET_DELAY 0x00000FFFU -/* PHY Configuration delay */ -#define PHY_CONFIG_DELAY 0x00000FFFU - -#define PHY_READ_TO 0x0000FFFFU -#define PHY_WRITE_TO 0x0000FFFFU - -/* Section 3: Common PHY Registers */ - -#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */ -#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */ - -#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ -#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ -#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ -#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ -#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ -#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ -#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ -#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ -#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ -#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ - -#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ -#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ -#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ - -/* Section 4: Extended PHY Registers */ - -#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */ - -#define PHY_SPEED_STATUS ((uint16_t)0x0004) /*!< PHY Speed mask */ -#define PHY_DUPLEX_STATUS ((uint16_t)0x0010) /*!< PHY Duplex mask */ - - -#define PHY_ISFR ((uint16_t)0x1D) /*!< PHY Interrupt Source Flag register Offset */ -#define PHY_ISFR_INT4 ((uint16_t)0x0010) /*!< PHY Link down inturrupt */ - -/* ################## SPI peripheral configuration ########################## */ - -/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver -* Activated: CRC code is present inside driver -* Deactivated: CRC code cleaned from driver -*/ - -#define USE_SPI_CRC 1U - -/* Includes ------------------------------------------------------------------*/ -/** - * @brief Include module's header file - */ - -#ifdef HAL_RCC_MODULE_ENABLED - #include "stm32f4xx_hal_rcc.h" - #include "stm32f4xx_hal_rcc_ex.h" -#endif /* HAL_RCC_MODULE_ENABLED */ - -#ifdef HAL_GPIO_MODULE_ENABLED - #include "stm32f4xx_hal_gpio.h" - #include "stm32f4xx_hal_gpio_ex.h" -#endif /* HAL_GPIO_MODULE_ENABLED */ - -#ifdef HAL_DMA_MODULE_ENABLED - #include "stm32f4xx_hal_dma.h" - #include "stm32f4xx_hal_dma_ex.h" -#endif /* HAL_DMA_MODULE_ENABLED */ - -#ifdef HAL_CORTEX_MODULE_ENABLED - #include "stm32f4xx_hal_cortex.h" -#endif /* HAL_CORTEX_MODULE_ENABLED */ - -#ifdef HAL_ADC_MODULE_ENABLED - #include "stm32f4xx_hal_adc.h" -#endif /* HAL_ADC_MODULE_ENABLED */ - -#ifdef HAL_CAN_MODULE_ENABLED - #include "stm32f4xx_hal_can.h" -#endif /* HAL_CAN_MODULE_ENABLED */ - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - #include "stm32f4xx_hal_can_legacy.h" -#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ - -#ifdef HAL_CRC_MODULE_ENABLED - #include "stm32f4xx_hal_crc.h" -#endif /* HAL_CRC_MODULE_ENABLED */ - -#ifdef HAL_CRYP_MODULE_ENABLED - #include "stm32f4xx_hal_cryp.h" - #include "stm32f4xx_hal_cryp_ex.h" -#endif /* HAL_CRYP_MODULE_ENABLED */ - -#ifdef HAL_DAC_MODULE_ENABLED - #include "stm32f4xx_hal_dac.h" -#endif /* HAL_DAC_MODULE_ENABLED */ - -#ifdef HAL_DCMI_MODULE_ENABLED - #include "stm32f4xx_hal_dcmi.h" -#endif /* HAL_DCMI_MODULE_ENABLED */ - -#ifdef HAL_ETH_MODULE_ENABLED - #include "stm32f4xx_hal_eth.h" -#endif /* HAL_ETH_MODULE_ENABLED */ - -#ifdef HAL_FLASH_MODULE_ENABLED - #include "stm32f4xx_hal_flash.h" - #include "stm32f4xx_hal_flash_ex.h" -#endif /* HAL_FLASH_MODULE_ENABLED */ - -#ifdef HAL_SRAM_MODULE_ENABLED - #include "stm32f4xx_hal_sram.h" -#endif /* HAL_SRAM_MODULE_ENABLED */ - -#ifdef HAL_NOR_MODULE_ENABLED - #include "stm32f4xx_hal_nor.h" -#endif /* HAL_NOR_MODULE_ENABLED */ - -#ifdef HAL_NAND_MODULE_ENABLED - #include "stm32f4xx_hal_nand.h" -#endif /* HAL_NAND_MODULE_ENABLED */ - -#ifdef HAL_PCCARD_MODULE_ENABLED - #include "stm32f4xx_hal_pccard.h" -#endif /* HAL_PCCARD_MODULE_ENABLED */ - -#ifdef HAL_SDRAM_MODULE_ENABLED - #include "stm32f4xx_hal_sdram.h" -#endif /* HAL_SDRAM_MODULE_ENABLED */ - -#ifdef HAL_HASH_MODULE_ENABLED - #include "stm32f4xx_hal_hash.h" -#endif /* HAL_HASH_MODULE_ENABLED */ - -#ifdef HAL_I2C_MODULE_ENABLED - #include "stm32f4xx_hal_i2c.h" - #include "stm32f4xx_hal_i2c_ex.h" -#endif /* HAL_I2C_MODULE_ENABLED */ - -#ifdef HAL_I2S_MODULE_ENABLED - #include "stm32f4xx_hal_i2s.h" - #include "stm32f4xx_hal_i2s_ex.h" -#endif /* HAL_I2S_MODULE_ENABLED */ - -#ifdef HAL_IWDG_MODULE_ENABLED - #include "stm32f4xx_hal_iwdg.h" -#endif /* HAL_IWDG_MODULE_ENABLED */ - -#ifdef HAL_LTDC_MODULE_ENABLED - #include "stm32f4xx_hal_ltdc.h" -#endif /* HAL_LTDC_MODULE_ENABLED */ - -#ifdef HAL_PWR_MODULE_ENABLED - #include "stm32f4xx_hal_pwr.h" - #include "stm32f4xx_hal_pwr_ex.h" -#endif /* HAL_PWR_MODULE_ENABLED */ - -#ifdef HAL_RNG_MODULE_ENABLED - #include "stm32f4xx_hal_rng.h" -#endif /* HAL_RNG_MODULE_ENABLED */ - -#ifdef HAL_RTC_MODULE_ENABLED - #include "stm32f4xx_hal_rtc.h" -#endif /* HAL_RTC_MODULE_ENABLED */ - -#ifdef HAL_SAI_MODULE_ENABLED - #include "stm32f4xx_hal_sai.h" -#endif /* HAL_SAI_MODULE_ENABLED */ - -#ifdef HAL_SD_MODULE_ENABLED - #include "stm32f4xx_hal_sd.h" -#endif /* HAL_SD_MODULE_ENABLED */ - -#ifdef HAL_SPI_MODULE_ENABLED - #include "stm32f4xx_hal_spi.h" -#endif /* HAL_SPI_MODULE_ENABLED */ - -#ifdef HAL_TIM_MODULE_ENABLED - #include "stm32f4xx_hal_tim.h" -#endif /* HAL_TIM_MODULE_ENABLED */ - -#ifdef HAL_UART_MODULE_ENABLED - #include "stm32f4xx_hal_uart.h" -#endif /* HAL_UART_MODULE_ENABLED */ - -#ifdef HAL_USART_MODULE_ENABLED - #include "stm32f4xx_hal_usart.h" -#endif /* HAL_USART_MODULE_ENABLED */ - -#ifdef HAL_IRDA_MODULE_ENABLED - #include "stm32f4xx_hal_irda.h" -#endif /* HAL_IRDA_MODULE_ENABLED */ - -#ifdef HAL_SMARTCARD_MODULE_ENABLED - #include "stm32f4xx_hal_smartcard.h" -#endif /* HAL_SMARTCARD_MODULE_ENABLED */ - -#ifdef HAL_WWDG_MODULE_ENABLED - #include "stm32f4xx_hal_wwdg.h" -#endif /* HAL_WWDG_MODULE_ENABLED */ - -#ifdef HAL_PCD_MODULE_ENABLED - #include "stm32f4xx_hal_pcd.h" -#endif /* HAL_PCD_MODULE_ENABLED */ - -#ifdef HAL_HCD_MODULE_ENABLED - #include "stm32f4xx_hal_hcd.h" -#endif /* HAL_HCD_MODULE_ENABLED */ - -#ifdef HAL_QSPI_MODULE_ENABLED - #include "stm32f4xx_hal_qspi.h" -#endif /* HAL_QSPI_MODULE_ENABLED */ - -#ifdef HAL_CEC_MODULE_ENABLED - #include "stm32f4xx_hal_cec.h" -#endif /* HAL_CEC_MODULE_ENABLED */ - -#ifdef HAL_FMPI2C_MODULE_ENABLED - #include "stm32f4xx_hal_fmpi2c.h" -#endif /* HAL_FMPI2C_MODULE_ENABLED */ - -#ifdef HAL_SPDIFRX_MODULE_ENABLED - #include "stm32f4xx_hal_spdifrx.h" -#endif /* HAL_SPDIFRX_MODULE_ENABLED */ - -#ifdef HAL_DFSDM_MODULE_ENABLED - #include "stm32f4xx_hal_dfsdm.h" -#endif /* HAL_DFSDM_MODULE_ENABLED */ - -#ifdef HAL_LPTIM_MODULE_ENABLED - #include "stm32f4xx_hal_lptim.h" -#endif /* HAL_LPTIM_MODULE_ENABLED */ - -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr: If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); -#else - #define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CONF_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/stm32f4xx_it.c b/body/board/inc/stm32f4xx_it.c deleted file mode 100644 index 5a9f5c367296945..000000000000000 --- a/body/board/inc/stm32f4xx_it.c +++ /dev/null @@ -1,169 +0,0 @@ -/** - ****************************************************************************** - * @file GPIO/GPIO_IOToggle/Src/stm32f4xx_it.c - * @author MCD Application Team - * @brief Main Interrupt Service Routines. - * This file provides template for all exceptions handler and - * peripherals interrupt service routine. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_it.h" - -/** @addtogroup STM32F4xx_HAL_Examples - * @{ - */ - -/** @addtogroup GPIO_IOToggle - * @{ - */ - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private function prototypes -----------------------------------------------*/ -void HAL_IncTick(void); -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************/ -/* Cortex-M4 Processor Exceptions Handlers */ -/******************************************************************************/ - -/** - * @brief This function handles NMI exception. - * @param None - * @retval None - */ -void NMI_Handler(void) -{ -} - -/** - * @brief This function handles Hard Fault exception. - * @param None - * @retval None - */ -void HardFault_Handler(void) -{ - /* Go to infinite loop when Hard Fault exception occurs */ - while (1) - { - } -} - -/** - * @brief This function handles Memory Manage exception. - * @param None - * @retval None - */ -void MemManage_Handler(void) -{ - /* Go to infinite loop when Memory Manage exception occurs */ - while (1) - { - } -} - -/** - * @brief This function handles Bus Fault exception. - * @param None - * @retval None - */ -void BusFault_Handler(void) -{ - /* Go to infinite loop when Bus Fault exception occurs */ - while (1) - { - } -} - -/** - * @brief This function handles Usage Fault exception. - * @param None - * @retval None - */ -void UsageFault_Handler(void) -{ - /* Go to infinite loop when Usage Fault exception occurs */ - while (1) - { - } -} - -/** - * @brief This function handles SVCall exception. - * @param None - * @retval None - */ -void SVC_Handler(void) -{ -} - -/** - * @brief This function handles Debug Monitor exception. - * @param None - * @retval None - */ -void DebugMon_Handler(void) -{ -} - -/** - * @brief This function handles PendSVC exception. - * @param None - * @retval None - */ -void PendSV_Handler(void) -{ -} - -/** - * @brief This function handles SysTick Handler. - * @param None - * @retval None - */ -void SysTick_Handler(void) -{ - HAL_IncTick(); -} - -/******************************************************************************/ -/* STM32F4xx Peripherals Interrupt Handlers */ -/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */ -/* available peripheral interrupt handler's name please refer to the startup */ -/* file (startup_stm32f4xx.s). */ -/******************************************************************************/ - -/** - * @brief This function handles PPP interrupt request. - * @param None - * @retval None - */ -/*void PPP_IRQHandler(void) -{ -}*/ - - -/** - * @} - */ - -/** - * @} - */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/stm32f4xx_it.h b/body/board/inc/stm32f4xx_it.h deleted file mode 100644 index 47e94acd502f966..000000000000000 --- a/body/board/inc/stm32f4xx_it.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * @file GPIO/GPIO_IOToggle/Inc/stm32f4xx_it.h - * @author MCD Application Team - * @brief This file contains the headers of the interrupt handlers. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_IT_H -#define __STM32F4xx_IT_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ - -void NMI_Handler(void); -void HardFault_Handler(void); -void MemManage_Handler(void); -void BusFault_Handler(void); -void UsageFault_Handler(void); -void SVC_Handler(void); -void DebugMon_Handler(void); -void PendSV_Handler(void); -void SysTick_Handler(void); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_IT_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/system_stm32f4xx.c b/body/board/inc/system_stm32f4xx.c deleted file mode 100644 index 048783d32f41613..000000000000000 --- a/body/board/inc/system_stm32f4xx.c +++ /dev/null @@ -1,255 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f4xx.c - * @author MCD Application Team - * @brief - CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. - * - This file is dedicated only for STM32F413 NUCLEO 144 boards. - * - * This file provides two functions and one global variable to be called from - * user application: - * - SystemInit(): This function is called at startup just after reset and - * before branch to main program. This call is made inside - * the "startup_stm32f4xx.s" file. - * - * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used - * by the user application to setup the SysTick - * timer or configure other parameters. - * - * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must - * be called whenever the core clock is changed - * during program execution. - * - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx_system - * @{ - */ - -/** @addtogroup STM32F4xx_System_Private_Includes - * @{ - */ - - -#include "stm32f4xx.h" - -#if !defined (HSE_VALUE) - #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSI_VALUE) - #define HSI_VALUE ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/ -#endif /* HSI_VALUE */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Defines - * @{ - */ - -/************************* Miscellaneous Configuration ************************/ -/*!< Uncomment the following line if you need to relocate your vector Table in - Internal SRAM. */ -/* #define VECT_TAB_SRAM */ -#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. - This value must be a multiple of 0x200. */ -/******************************************************************************/ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Variables - * @{ - */ - /* This variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetHCLKFreq() - 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. - */ -uint32_t SystemCoreClock = 16000000; -const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; -const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4}; -/** - * @} - */ - - -/** @addtogroup STM32F4xx_System_Private_Functions - * @{ - */ - -/** - * @brief Setup the microcontroller system - * Initialize the FPU setting, vector table location and External memory - * configuration. - * @param None - * @retval None - */ -void SystemInit(void) -{ - /* FPU settings ------------------------------------------------------------*/ - #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ - #endif - /* Reset the RCC clock configuration to the default reset state ------------*/ - /* Set HSION bit */ - RCC->CR |= (uint32_t)0x00000001; - - /* Reset CFGR register */ - RCC->CFGR = 0x00000000; - - /* Reset HSEON, CSSON and PLLON bits */ - RCC->CR &= (uint32_t)0xFEF6FFFF; - - /* Reset PLLCFGR register */ - RCC->PLLCFGR = 0x24003010; - - /* Reset HSEBYP bit */ - RCC->CR &= (uint32_t)0xFFFBFFFF; - - /* Disable all interrupts */ - RCC->CIR = 0x00000000; - - - /* Configure the Vector Table location add offset address ------------------*/ -#ifdef VECT_TAB_SRAM - SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ -#else - SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ -#endif -} - -/** - * @brief Update SystemCoreClock variable according to Clock Register Values. - * The SystemCoreClock variable contains the core clock (HCLK), it can - * be used by the user application to setup the SysTick timer or configure - * other parameters. - * - * @note Each time the core clock (HCLK) changes, this function must be called - * to update SystemCoreClock variable value. Otherwise, any configuration - * based on this variable will be incorrect. - * - * @note - The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * - * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) - * - * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) - * - * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * - * (*) HSI_VALUE is a constant defined in stm32f4xx_hal_conf.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * - * (**) HSE_VALUE is a constant defined in stm32f4xx_hal_conf.h file (its value - * depends on the application requirements), user has to ensure that HSE_VALUE - * is same as the real frequency of the crystal used. Otherwise, this function - * may have wrong result. - * - * - The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @param None - * @retval None - */ -void SystemCoreClockUpdate(void) -{ - uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; - - /* Get SYSCLK source -------------------------------------------------------*/ - tmp = RCC->CFGR & RCC_CFGR_SWS; - - switch (tmp) - { - case 0x00: /* HSI used as system clock source */ - SystemCoreClock = HSI_VALUE; - break; - case 0x04: /* HSE used as system clock source */ - SystemCoreClock = HSE_VALUE; - break; - case 0x08: /* PLL used as system clock source */ - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N - SYSCLK = PLL_VCO / PLL_P - */ - pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - - if (pllsource != 0) - { - /* HSE used as PLL clock source */ - pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); - } - - pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; - SystemCoreClock = pllvco/pllp; - break; - default: - SystemCoreClock = HSI_VALUE; - break; - } - /* Compute HCLK frequency --------------------------------------------------*/ - /* Get HCLK prescaler */ - tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; - /* HCLK frequency */ - SystemCoreClock >>= tmp; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/system_stm32f4xx.h b/body/board/inc/system_stm32f4xx.h deleted file mode 100644 index 99cb936c6fe9a20..000000000000000 --- a/body/board/inc/system_stm32f4xx.h +++ /dev/null @@ -1,122 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f4xx.h - * @author MCD Application Team - * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2017 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 stm32f4xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef __SYSTEM_STM32F4XX_H -#define __SYSTEM_STM32F4XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32F4xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32F4xx_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) */ - -extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ -extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__SYSTEM_STM32F4XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/tz_context.h b/body/board/inc/tz_context.h deleted file mode 100644 index 0d09749f3a5066f..000000000000000 --- a/body/board/inc/tz_context.h +++ /dev/null @@ -1,70 +0,0 @@ -/****************************************************************************** - * @file tz_context.h - * @brief Context Management for Armv8-M TrustZone - * @version V1.0.1 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef TZ_CONTEXT_H -#define TZ_CONTEXT_H - -#include - -#ifndef TZ_MODULEID_T -#define TZ_MODULEID_T -/// \details Data type that identifies secure software modules called by a process. -typedef uint32_t TZ_ModuleId_t; -#endif - -/// \details TZ Memory ID identifies an allocated memory slot. -typedef uint32_t TZ_MemoryId_t; - -/// Initialize secure context memory system -/// \return execution status (1: success, 0: error) -uint32_t TZ_InitContextSystem_S (void); - -/// Allocate context memory for calling secure software modules in TrustZone -/// \param[in] module identifies software modules called from non-secure mode -/// \return value != 0 id TrustZone memory slot identifier -/// \return value 0 no memory available or internal error -TZ_MemoryId_t TZ_AllocModuleContext_S (TZ_ModuleId_t module); - -/// Free context memory that was previously allocated with \ref TZ_AllocModuleContext_S -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_FreeModuleContext_S (TZ_MemoryId_t id); - -/// Load secure context (called on RTOS thread context switch) -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_LoadContext_S (TZ_MemoryId_t id); - -/// Store secure context (called on RTOS thread context switch) -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_StoreContext_S (TZ_MemoryId_t id); - -#endif // TZ_CONTEXT_H diff --git a/body/board/libc.h b/body/board/libc.h deleted file mode 100644 index 1e32d4206e481a5..000000000000000 --- a/body/board/libc.h +++ /dev/null @@ -1,64 +0,0 @@ -// **** libc **** - -void delay(uint32_t a) { - volatile uint32_t i; - for (i = 0; i < a; i++); -} - -void *memset(void *str, int c, unsigned int n) { - uint8_t *s = str; - for (unsigned int i = 0; i < n; i++) { - *s = c; - s++; - } - return str; -} - -#define UNALIGNED(X, Y) \ - (((uint32_t)(X) & (sizeof(uint32_t) - 1U)) | ((uint32_t)(Y) & (sizeof(uint32_t) - 1U))) - -void *memcpy(void *dest, const void *src, unsigned int len) { - unsigned int n = len; - uint8_t *d8 = dest; - const uint8_t *s8 = src; - - if ((n >= 4U) && !UNALIGNED(s8, d8)) { - uint32_t *d32 = (uint32_t *)d8; // cppcheck-suppress misra-c2012-11.3 ; already checked that it's properly aligned - const uint32_t *s32 = (const uint32_t *)s8; // cppcheck-suppress misra-c2012-11.3 ; already checked that it's properly aligned - - while(n >= 16U) { - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - n -= 16U; - } - - while(n >= 4U) { - *d32 = *s32; d32++; s32++; - n -= 4U; - } - - d8 = (uint8_t *)d32; - s8 = (const uint8_t *)s32; - } - while (n-- > 0U) { - *d8 = *s8; d8++; s8++; - } - return dest; -} - -int memcmp(const void * ptr1, const void * ptr2, unsigned int num) { - int ret = 0; - const uint8_t *p1 = ptr1; - const uint8_t *p2 = ptr2; - for (unsigned int i = 0; i < num; i++) { - if (*p1 != *p2) { - ret = -1; - break; - } - p1++; - p2++; - } - return ret; -} diff --git a/body/board/main.c b/body/board/main.c deleted file mode 100644 index 74837b17e6564cd..000000000000000 --- a/body/board/main.c +++ /dev/null @@ -1,380 +0,0 @@ -#include -#include -#include "libc.h" -#include "stm32f4xx_hal.h" -#include "defines.h" -#include "config.h" -#include "setup.h" -#include "util.h" -#include "bldc/BLDC_controller.h" /* BLDC's header file */ -#include "bldc/rtwtypes.h" -#include "version.h" -#include "obj/gitversion.h" -#include "comms.h" -#include "drivers/clock.h" -#include "early_init.h" -#include "drivers/i2c_soft.h" -#include "drivers/angle_sensor.h" -#include "boards.h" - - -//------------------------------------------------------------------------ -// Global variables set externally -//------------------------------------------------------------------------ -extern TIM_HandleTypeDef htim_left; -extern TIM_HandleTypeDef htim_right; -extern ADC_HandleTypeDef hadc; -extern volatile adc_buf_t adc_buffer; - -// Matlab defines - from auto-code generation -//--------------- -extern P rtP_Left; /* Block parameters (auto storage) */ -extern P rtP_Right; /* Block parameters (auto storage) */ -extern ExtY rtY_Left; /* External outputs */ -extern ExtY rtY_Right; /* External outputs */ -extern ExtU rtU_Left; /* External inputs */ -extern ExtU rtU_Right; /* External inputs */ -//--------------- - -// TODO: remove both, unneeded. Also func in util.c too -extern int16_t speedAvg; // Average measured speed -extern int16_t speedAvgAbs; // Average measured speed in absolute - -extern volatile int pwml; // global variable for pwm left. -1000 to 1000 -extern volatile int pwmr; // global variable for pwm right. -1000 to 1000 - -extern uint8_t enable_motors; // global variable for motor enable - -extern int16_t batVoltage; // global variable for battery voltage - -extern int32_t motPosL; -extern int32_t motPosR; - -extern board_t board; - -//------------------------------------------------------------------------ -// Global variables set here in main.c -//------------------------------------------------------------------------ -extern volatile uint32_t buzzerTimer; -volatile uint32_t torque_cmd_timeout = 0U; -volatile uint32_t ignition_off_counter = 0U; - -uint16_t cnt_press = 0; - -int16_t batVoltageCalib; // global variable for calibrated battery voltage -int16_t board_temp_deg_c; // global variable for calibrated temperature in degrees Celsius -volatile int16_t cmdL; // global variable for Left Command -volatile int16_t cmdR; // global variable for Right Command - -uint8_t hw_type; // type of the board detected(0 - base, 3 - knee) -uint8_t ignition = 0; // global variable for ignition on SBU2 line -uint8_t charger_connected = 0; // status of the charger port -uint8_t pkt_idx = 0; // For CAN msg counter -//------------------------------------------------------------------------ -// Local variables -//------------------------------------------------------------------------ -static uint32_t tick_prev = 0U; - -static uint32_t main_loop_1Hz = 0U; -static uint32_t main_loop_1Hz_runtime = 0U; - -static uint32_t main_loop_10Hz = 0U; -static uint32_t main_loop_10Hz_runtime = 0U; - -static uint32_t main_loop_100Hz = 0U; -static uint32_t main_loop_100Hz_runtime = 0U; - -void __initialize_hardware_early(void) { - early_initialization(); -} - -int main(void) { - HAL_Init(); - HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); - HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); - HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); - HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); - HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); - HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); - HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0); - HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); - - SystemClock_Config(); - MX_GPIO_Clocks_Init(); - - __HAL_RCC_DMA2_CLK_DISABLE(); - - board_detect(); - MX_GPIO_Common_Init(); - MX_TIM_Init(); - MX_ADC_Init(); - BLDC_Init(); - - HAL_ADC_Start(&hadc); - - if (hw_type == HW_TYPE_BASE) { - out_enable(POWERSWITCH, true); - out_enable(IGNITION, ignition); - out_enable(TRANSCEIVER, true); - // Loop until button is released, only for base board - while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { HAL_Delay(10); } - } else { - out_enable(POWERSWITCH, false); - ignition = 1; - knee_detected = 1; - } - // Reset LEDs on startup - out_enable(LED_RED, false); - out_enable(LED_GREEN, false); - out_enable(LED_BLUE, false); - - llcan_set_speed(board.CAN, 5000, false, false); - llcan_init(board.CAN); - - SW_I2C_init(); - IMU_soft_init(); - - poweronMelody(); - - int32_t board_temp_adcFixdt = adc_buffer.temp << 16; // Fixed-point filter output initialized with current ADC converted to fixed-point - int16_t board_temp_adcFilt = adc_buffer.temp; - - uint16_t sensor_angle[2] = { 0 }; - uint16_t hall_angle_offset[2] = { 0 }; - - uint16_t unknown_imu_data[6] = { 0 }; - - if (hw_type == HW_TYPE_KNEE) { - angle_sensor_read(sensor_angle); // Initial data to set offsets between angle sensor and hall sensor - hall_angle_offset[0] = (sensor_angle[0] * ANGLE_TO_DEGREES); - hall_angle_offset[1] = (sensor_angle[1] * ANGLE_TO_DEGREES); - } - - while(1) { - if ((HAL_GetTick() - tick_prev) >= 1) { // 1kHz loop - // runs at 100Hz - if ((HAL_GetTick() - (main_loop_100Hz - main_loop_100Hz_runtime)) >= 10) { - main_loop_100Hz_runtime = HAL_GetTick(); - - calcAvgSpeed(); - - if (ignition == 0) { - cmdL = cmdR = 0; - enable_motors = 0; - } - - if (!enable_motors || (torque_cmd_timeout > 10)) { - cmdL = cmdR = 0; - } - - if (ignition == 1 && enable_motors == 0 && (!rtY_Left.z_errCode && !rtY_Right.z_errCode) && (ABS(cmdL) < 50 && ABS(cmdR) < 50)) { - beepShort(6); // make 2 beeps indicating the motor enable - beepShort(4); - HAL_Delay(100); - cmdL = cmdR = 0; - enable_motors = 1; // enable motors - } - - if (hw_type == HW_TYPE_KNEE) { - // Safety to stop operation if angle sensor reading failed TODO: adjust sensivity and add lowpass to angle sensor? - fault_status.left_angle = (ABS((hall_angle_offset[0] + ((motPosL / 15 / GEARBOX_RATIO_LEFT) % 360)) - (sensor_angle[0] * ANGLE_TO_DEGREES)) > 5); - fault_status.right_angle = (ABS((hall_angle_offset[1] + ((motPosR / 15 / GEARBOX_RATIO_RIGHT) % 360)) - (sensor_angle[1] * ANGLE_TO_DEGREES)) > 5); - - if (fault_status.left_angle || fault_status.right_angle) { - cmdL = cmdR = 0; - } - // Safety to stop movement when reaching dead angles, around 20 and 340 degrees - if (((sensor_angle[0] < 900) && (cmdL < 0)) || ((sensor_angle[0] > 15500) && (cmdL > 0))) { - cmdL = 0; - } - if (((sensor_angle[1] < 900) && (cmdR < 0)) || ((sensor_angle[1] > 15500) && (cmdR > 0))) { - cmdR = 0; - } - } - - if (ABS(cmdL) < 10) { - rtP_Left.n_cruiseMotTgt = 0; - rtP_Left.b_cruiseCtrlEna = 1; - } else { - rtP_Left.b_cruiseCtrlEna = 0; - if (hw_type == HW_TYPE_KNEE) { - pwml = -CLAMP((int)cmdL, -TRQ_LIMIT_LEFT, TRQ_LIMIT_LEFT); - } else { - pwml = CLAMP((int)cmdL, -TORQUE_BASE_MAX, TORQUE_BASE_MAX); - } - } - if (ABS(cmdR) < 10) { - rtP_Right.n_cruiseMotTgt = 0; - rtP_Right.b_cruiseCtrlEna = 1; - } else { - rtP_Right.b_cruiseCtrlEna = 0; - if (hw_type == HW_TYPE_KNEE) { - pwmr = -CLAMP((int)cmdR, -TRQ_LIMIT_RIGHT, TRQ_LIMIT_RIGHT); - } else { - pwmr = -CLAMP((int)cmdR, -TORQUE_BASE_MAX, TORQUE_BASE_MAX); - } - } - - if (ignition_off_counter <= IGNITION_OFF_DELAY) { - // MOTORS_DATA: speed_L(2), speed_R(2), counter(1), checksum(1) - uint8_t dat[8]; - uint16_t speedL = rtY_Left.n_mot; - uint16_t speedR = -(rtY_Right.n_mot); // Invert speed sign for the right wheel - dat[0] = (speedL >> 8U) & 0xFFU; - dat[1] = speedL & 0xFFU; - dat[2] = (speedR >> 8U) & 0xFFU; - dat[3] = speedR & 0xFFU; - dat[4] = 0; - dat[5] = 0; - dat[6] = pkt_idx; - dat[7] = crc_checksum(dat, 7, crc_poly); - can_send_msg((0x201U + board.can_addr_offset), ((dat[7] << 24U) | (dat[6] << 16U) | (dat[5]<< 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 8U); - ++pkt_idx; - pkt_idx &= 0xFU; - - //MOTORS_CURRENT: left_pha_ab(2), left_pha_bc(2), right_pha_ab(2), right_pha_bc(2) - dat[0] = (rtU_Left.i_phaAB >> 8U) & 0xFFU; - dat[1] = rtU_Left.i_phaAB & 0xFFU; - dat[2] = (rtU_Left.i_phaBC >> 8U) & 0xFFU; - dat[3] = rtU_Left.i_phaBC & 0xFFU; - dat[4] = (rtU_Right.i_phaAB >> 8U) & 0xFFU; - dat[5] = rtU_Right.i_phaAB & 0xFFU; - dat[6] = (rtU_Right.i_phaBC >> 8U) & 0xFFU; - dat[7] = rtU_Right.i_phaBC & 0xFFU; - can_send_msg((0x204U + board.can_addr_offset), ((dat[7] << 24U) | (dat[6] << 16U) | (dat[5] << 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 8U); - - uint16_t left_hall_angle; - uint16_t right_hall_angle; - if (hw_type == HW_TYPE_KNEE) { - angle_sensor_read(sensor_angle); - left_hall_angle = hall_angle_offset[0] + ((motPosL / 15 / GEARBOX_RATIO_LEFT) % 360); - right_hall_angle = hall_angle_offset[1] + ((motPosR / 15 / GEARBOX_RATIO_RIGHT) % 360); - } else { - left_hall_angle = motPosL / 15; - right_hall_angle = -motPosR / 15; - } - //MOTORS_ANGLE: left angle sensor(2), right angle sensor(2), left hall angle(2), right hall angle(2) - dat[0] = (sensor_angle[0]>>8U) & 0xFFU; - dat[1] = sensor_angle[0] & 0xFFU; - dat[2] = (sensor_angle[1]>>8U) & 0xFFU; - dat[3] = sensor_angle[1] & 0xFFU; - dat[4] = (left_hall_angle>>8U) & 0xFFU; - dat[5] = left_hall_angle & 0xFFU; - dat[6] = (right_hall_angle>>8U) & 0xFFU; - dat[7] = right_hall_angle & 0xFFU; - can_send_msg((0x205U + board.can_addr_offset), ((dat[7] << 24U) | (dat[6] << 16U) | (dat[5] << 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 8U); - - IMU_soft_sensor_read(unknown_imu_data); - //BOARD_IMU_RAW1: FIXME: add comment after discovering data, looks like magnetometer - dat[0] = (unknown_imu_data[0]>>8U) & 0xFFU; - dat[1] = unknown_imu_data[0] & 0xFFU; - dat[2] = (unknown_imu_data[1]>>8U) & 0xFFU; - dat[3] = unknown_imu_data[1] & 0xFFU; - dat[4] = (unknown_imu_data[2]>>8U) & 0xFFU; - dat[5] = unknown_imu_data[2] & 0xFFU; - can_send_msg((0x206U + board.can_addr_offset), ((dat[5] << 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 6U); - - //BOARD_IMU_RAW2: FIXME: add comment after discovering data, looks like acceleration? - dat[0] = (unknown_imu_data[3]>>8U) & 0xFFU; - dat[1] = unknown_imu_data[3] & 0xFFU; - dat[2] = (unknown_imu_data[4]>>8U) & 0xFFU; - dat[3] = unknown_imu_data[4] & 0xFFU; - dat[4] = (unknown_imu_data[5]>>8U) & 0xFFU; - dat[5] = unknown_imu_data[5] & 0xFFU; - can_send_msg((0x207U + board.can_addr_offset), ((dat[5] << 8U) | dat[4]), ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 6U); - } - torque_cmd_timeout = (torque_cmd_timeout < MAX_uint32_T) ? (torque_cmd_timeout+1) : 0; - main_loop_100Hz_runtime = HAL_GetTick() - main_loop_100Hz_runtime; - main_loop_100Hz = HAL_GetTick(); - } - - // runs at 10Hz - if ((HAL_GetTick() - (main_loop_10Hz - main_loop_10Hz_runtime)) >= 100) { - main_loop_10Hz_runtime = HAL_GetTick(); - if (ignition_off_counter <= IGNITION_OFF_DELAY) { - // VAR_VALUES: fault_status(0:4), enable_motors(0:1), ignition(0:1), left motor error(1), right motor error(1) - uint8_t dat[2]; - dat[0] = ((fault_status.right_angle << 5U) | (fault_status.right_i2c << 4U) | (fault_status.left_angle << 3U) | (fault_status.left_i2c << 2U) | (enable_motors << 1U) | ignition); - dat[1] = rtY_Left.z_errCode; - dat[2] = rtY_Right.z_errCode; - can_send_msg((0x202U + board.can_addr_offset), 0x0U, ((dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 3U); - } - out_enable(LED_GREEN, ignition); - - main_loop_10Hz_runtime = HAL_GetTick() - main_loop_10Hz_runtime; - main_loop_10Hz = HAL_GetTick(); - } - - // runs at 1Hz - if ((HAL_GetTick() - (main_loop_1Hz - main_loop_1Hz_runtime)) >= 1000) { - main_loop_1Hz_runtime = HAL_GetTick(); - // ####### CALC BOARD TEMPERATURE ####### - filtLowPass32(adc_buffer.temp, TEMP_FILT_COEF, &board_temp_adcFixdt); - board_temp_adcFilt = (int16_t)(board_temp_adcFixdt >> 16); // convert fixed-point to integer - board_temp_deg_c = (TEMP_CAL_HIGH_DEG_C - TEMP_CAL_LOW_DEG_C) * (board_temp_adcFilt - TEMP_CAL_LOW_ADC) / (TEMP_CAL_HIGH_ADC - TEMP_CAL_LOW_ADC) + TEMP_CAL_LOW_DEG_C; - - // ####### CALC CALIBRATED BATTERY VOLTAGE ####### - batVoltageCalib = batVoltage * BAT_CALIB_REAL_VOLTAGE / BAT_CALIB_ADC; - - charger_connected = !HAL_GPIO_ReadPin(CHARGER_PORT, CHARGER_PIN); - uint8_t battery_percent = 100 - (((420 * BAT_CELLS) - batVoltageCalib) / BAT_CELLS / VOLTS_PER_PERCENT / 100); // Battery % left - - // BODY_DATA: MCU temp(2), battery voltage(2), battery_percent(0:7), charger_connected(0:1) - uint8_t dat[4]; - dat[0] = board_temp_deg_c & 0xFFU; - dat[1] = (batVoltageCalib >> 8U) & 0xFFU; - dat[2] = batVoltageCalib & 0xFFU; - dat[3] = (((battery_percent & 0x7FU) << 1U) | charger_connected); - can_send_msg((0x203U + board.can_addr_offset), 0x0U, ((dat[3] << 24U) | (dat[2] << 16U) | (dat[1] << 8U) | dat[0]), 4U); - - out_enable(LED_BLUE, false); // Reset LED after CAN RX - out_enable(LED_GREEN, true); // Always use LED to show that body is on - - if ((hw_type == HW_TYPE_BASE) && ignition) { - ignition_off_counter = 0; - } else { - ignition_off_counter = (ignition_off_counter < MAX_uint32_T) ? (ignition_off_counter+1) : 0; - } - - if ((TEMP_POWEROFF_ENABLE && board_temp_deg_c >= TEMP_POWEROFF && speedAvgAbs < 20) || (batVoltage < BAT_DEAD && speedAvgAbs < 20)) { // poweroff before mainboard burns OR low bat 3 - poweroff(); - } else if (rtY_Left.z_errCode || rtY_Right.z_errCode) { // 1 beep (low pitch): Motor error, disable motors - enable_motors = 0; - beepCount(1, 24, 1); - } else if (fault_status.left_angle || fault_status.left_i2c || fault_status.right_angle || fault_status.right_i2c) { // 2 beeps (low pitch): Motor error, disable motors - beepCount(2, 24, 1); - } else if (TEMP_WARNING_ENABLE && board_temp_deg_c >= TEMP_WARNING) { // 5 beeps (low pitch): Mainboard temperature warning - beepCount(5, 24, 1); - } else if (batVoltage < BAT_LVL1) { // 1 beep fast (medium pitch): Low bat 1 - beepCount(0, 10, 6); - out_enable(LED_RED, true); - } else if (batVoltage < BAT_LVL2) { // 1 beep slow (medium pitch): Low bat 2 - beepCount(0, 10, 30); - } else { // do not beep - beepCount(0, 0, 0); - out_enable(LED_RED, false); - } - - main_loop_1Hz_runtime = HAL_GetTick() - main_loop_1Hz_runtime; - main_loop_1Hz = HAL_GetTick(); - } - - if (hw_type == HW_TYPE_BASE) { - if (HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { - cnt_press += 1; - if (cnt_press == (2 * 1008)) { - poweroff(); - } - } else if (cnt_press >= 10) { - ignition = !ignition; - out_enable(IGNITION, ignition); - beepShort(5); - cnt_press = 0; - } - } - - process_can(); - tick_prev = HAL_GetTick(); - } - } -} diff --git a/body/board/provision.h b/body/board/provision.h deleted file mode 100644 index 0e549db5b02ca64..000000000000000 --- a/body/board/provision.h +++ /dev/null @@ -1,15 +0,0 @@ -#define PROVISION_CHUNK_LEN 0x20U -#define PROVISION_CHUNK_ADDRESS 0x1FFF79E0U - -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) { - (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/body/board/recover.sh b/body/board/recover.sh deleted file mode 100755 index 0a521e1a20bf1f4..000000000000000 --- a/body/board/recover.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env sh -set -e - -FLASH_UTIL="openocd" - -scons -u - -$FLASH_UTIL -f interface/stlink.cfg -c "set CPUTAPID 0" -f target/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase obj/body.bin.signed 0x08004000" -c "flash write_image erase obj/bootstub.body.bin 0x08000000" -c "reset run" -c "shutdown" diff --git a/body/board/setup.h b/body/board/setup.h deleted file mode 100644 index 898b2f393bd78a3..000000000000000 --- a/body/board/setup.h +++ /dev/null @@ -1,372 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef SETUP_H -#define SETUP_H - -#include "stm32f4xx_hal.h" - -TIM_HandleTypeDef htim_right; -TIM_HandleTypeDef htim_left; -ADC_HandleTypeDef hadc; -I2C_HandleTypeDef hi2c1; - -volatile adc_buf_t adc_buffer; -extern board_t board; - - -void MX_GPIO_Clocks_Init(void) { - /* GPIO Ports Clock Enable */ - __HAL_RCC_GPIOA_CLK_ENABLE(); - __HAL_RCC_GPIOB_CLK_ENABLE(); - __HAL_RCC_GPIOC_CLK_ENABLE(); - __HAL_RCC_GPIOD_CLK_ENABLE(); - - __HAL_RCC_CAN1_CLK_ENABLE(); - __HAL_RCC_CAN2_CLK_ENABLE(); -} - -void MX_GPIO_Common_Init(void) { - GPIO_InitTypeDef GPIO_InitStruct = { 0 }; - - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - - GPIO_InitStruct.Pin = board.hall_left.hall_pinA; - HAL_GPIO_Init(board.hall_left.hall_portA, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_left.hall_pinB; - HAL_GPIO_Init(board.hall_left.hall_portB, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_left.hall_pinC; - HAL_GPIO_Init(board.hall_left.hall_portC, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_right.hall_pinA; - HAL_GPIO_Init(board.hall_right.hall_portA, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_right.hall_pinB; - HAL_GPIO_Init(board.hall_right.hall_portB, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_right.hall_pinC; - HAL_GPIO_Init(board.hall_right.hall_portC, &GPIO_InitStruct); - - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Pin = CHARGER_PIN; - HAL_GPIO_Init(CHARGER_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pull = GPIO_NOPULL; - - GPIO_InitStruct.Pin = BUTTON_PIN; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - - GPIO_InitStruct.Pin = board.led_pinR; - HAL_GPIO_Init(board.led_portR, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.led_pinG; - HAL_GPIO_Init(board.led_portG, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.led_pinB; - HAL_GPIO_Init(board.led_portB, &GPIO_InitStruct); - - if (board.can_pinEN != 0) { - GPIO_InitStruct.Pin = board.can_pinEN; - HAL_GPIO_Init(board.can_portEN, &GPIO_InitStruct); - } - - if (board.ignition_pin != 0) { - GPIO_InitStruct.Pin = board.ignition_pin; - HAL_GPIO_Init(board.ignition_port, &GPIO_InitStruct); - - } - - GPIO_InitStruct.Pin = BUZZER_PIN; - HAL_GPIO_Init(BUZZER_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = OFF_PIN; - HAL_GPIO_Init(OFF_PORT, &GPIO_InitStruct); - - - GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - - GPIO_InitStruct.Pin = LEFT_DC_CUR_PIN; - HAL_GPIO_Init(LEFT_DC_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_U_CUR_PIN; - HAL_GPIO_Init(LEFT_U_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_V_CUR_PIN; - HAL_GPIO_Init(LEFT_V_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_DC_CUR_PIN; - HAL_GPIO_Init(RIGHT_DC_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_U_CUR_PIN; - HAL_GPIO_Init(RIGHT_U_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_V_CUR_PIN; - HAL_GPIO_Init(RIGHT_V_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = BATT_PIN; - HAL_GPIO_Init(BATT_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Alternate = GPIO_AF3_TIM8; - - GPIO_InitStruct.Pin = LEFT_TIM_UH_PIN; - HAL_GPIO_Init(LEFT_TIM_UH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_VH_PIN; - HAL_GPIO_Init(LEFT_TIM_VH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_WH_PIN; - HAL_GPIO_Init(LEFT_TIM_WH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_UL_PIN; - HAL_GPIO_Init(LEFT_TIM_UL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_VL_PIN; - HAL_GPIO_Init(LEFT_TIM_VL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_WL_PIN; - HAL_GPIO_Init(LEFT_TIM_WL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Alternate = GPIO_AF1_TIM1; - - GPIO_InitStruct.Pin = RIGHT_TIM_UH_PIN; - HAL_GPIO_Init(RIGHT_TIM_UH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_VH_PIN; - HAL_GPIO_Init(RIGHT_TIM_VH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_WH_PIN; - HAL_GPIO_Init(RIGHT_TIM_WH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_UL_PIN; - HAL_GPIO_Init(RIGHT_TIM_UL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_VL_PIN; - HAL_GPIO_Init(RIGHT_TIM_VL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_WL_PIN; - HAL_GPIO_Init(RIGHT_TIM_WL_PORT, &GPIO_InitStruct); - - // CAN bus - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - - GPIO_InitStruct.Alternate = board.can_alt_rx; - GPIO_InitStruct.Pin = board.can_pinRX; - HAL_GPIO_Init(board.can_portRX, &GPIO_InitStruct); - - GPIO_InitStruct.Alternate = board.can_alt_tx; - GPIO_InitStruct.Pin = board.can_pinTX; - HAL_GPIO_Init(board.can_portTX, &GPIO_InitStruct); -} - - -void MX_I2C_Init(void) { - GPIO_InitTypeDef GPIO_InitStruct = { 0 }; - - GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF4_I2C1; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - - __HAL_RCC_I2C1_CLK_ENABLE(); - - hi2c1.Instance = I2C1; - hi2c1.Init.ClockSpeed = (I2C_CLOCKSPEED * 1000); - hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2; - hi2c1.Init.OwnAddress1 = 0; - hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; - hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; - hi2c1.Init.OwnAddress2 = 0; - hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; - hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE; - HAL_I2C_Init(&hi2c1); -} - - -void MX_TIM_Init(void) { - __HAL_RCC_TIM1_CLK_ENABLE(); - __HAL_RCC_TIM8_CLK_ENABLE(); - - TIM_MasterConfigTypeDef sMasterConfig; - TIM_OC_InitTypeDef sConfigOC; - TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig; - TIM_SlaveConfigTypeDef sTimConfig; - - htim_right.Instance = RIGHT_TIM; - htim_right.Init.Prescaler = 0; - htim_right.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED1; - htim_right.Init.Period = CORE_FREQ / 2 / PWM_FREQ; - htim_right.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - htim_right.Init.RepetitionCounter = 0; - htim_right.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - HAL_TIM_PWM_Init(&htim_right); - - sMasterConfig.MasterOutputTrigger = TIM_TRGO_ENABLE; - sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - HAL_TIMEx_MasterConfigSynchronization(&htim_right, &sMasterConfig); - - sConfigOC.OCMode = TIM_OCMODE_PWM1; - sConfigOC.Pulse = 0; - sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; - sConfigOC.OCNPolarity = TIM_OCNPOLARITY_LOW; - sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; - sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET; - HAL_TIM_PWM_ConfigChannel(&htim_right, &sConfigOC, TIM_CHANNEL_1); - HAL_TIM_PWM_ConfigChannel(&htim_right, &sConfigOC, TIM_CHANNEL_2); - HAL_TIM_PWM_ConfigChannel(&htim_right, &sConfigOC, TIM_CHANNEL_3); - - sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_ENABLE; - sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_ENABLE; - sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF; - sBreakDeadTimeConfig.DeadTime = DEAD_TIME; - sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE; - sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_LOW; - sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE; - HAL_TIMEx_ConfigBreakDeadTime(&htim_right, &sBreakDeadTimeConfig); - - htim_left.Instance = LEFT_TIM; - htim_left.Init.Prescaler = 0; - htim_left.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED1; - htim_left.Init.Period = CORE_FREQ / 2 / PWM_FREQ; - htim_left.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - htim_left.Init.RepetitionCounter = 0; - htim_left.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - HAL_TIM_PWM_Init(&htim_left); - - sMasterConfig.MasterOutputTrigger = TIM_TRGO_UPDATE; - sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_ENABLE; - HAL_TIMEx_MasterConfigSynchronization(&htim_left, &sMasterConfig); - - sTimConfig.InputTrigger = TIM_TS_ITR0; - sTimConfig.SlaveMode = TIM_SLAVEMODE_GATED; - HAL_TIM_SlaveConfigSynchronization(&htim_left, &sTimConfig); - - // Start counting >0 to effectively offset timers by the time it takes for one ADC conversion to complete. - // This method allows that the Phase currents ADC measurements are properly aligned with LOW-FET ON region for both motors - LEFT_TIM->CNT = ADC_TOTAL_CONV_TIME; - - sConfigOC.OCMode = TIM_OCMODE_PWM1; - sConfigOC.Pulse = 0; - sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; - sConfigOC.OCNPolarity = TIM_OCNPOLARITY_LOW; - sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; - sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET; - HAL_TIM_PWM_ConfigChannel(&htim_left, &sConfigOC, TIM_CHANNEL_1); - HAL_TIM_PWM_ConfigChannel(&htim_left, &sConfigOC, TIM_CHANNEL_2); - HAL_TIM_PWM_ConfigChannel(&htim_left, &sConfigOC, TIM_CHANNEL_3); - - sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_ENABLE; - sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_ENABLE; - sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF; - sBreakDeadTimeConfig.DeadTime = DEAD_TIME; - sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE; - sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_LOW; - sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE; - HAL_TIMEx_ConfigBreakDeadTime(&htim_left, &sBreakDeadTimeConfig); - - LEFT_TIM->BDTR &= ~TIM_BDTR_MOE; - RIGHT_TIM->BDTR &= ~TIM_BDTR_MOE; - - HAL_TIM_PWM_Start(&htim_left, TIM_CHANNEL_1); - HAL_TIM_PWM_Start(&htim_left, TIM_CHANNEL_2); - HAL_TIM_PWM_Start(&htim_left, TIM_CHANNEL_3); - HAL_TIMEx_PWMN_Start(&htim_left, TIM_CHANNEL_1); - HAL_TIMEx_PWMN_Start(&htim_left, TIM_CHANNEL_2); - HAL_TIMEx_PWMN_Start(&htim_left, TIM_CHANNEL_3); - - HAL_TIM_PWM_Start(&htim_right, TIM_CHANNEL_1); - HAL_TIM_PWM_Start(&htim_right, TIM_CHANNEL_2); - HAL_TIM_PWM_Start(&htim_right, TIM_CHANNEL_3); - HAL_TIMEx_PWMN_Start(&htim_right, TIM_CHANNEL_1); - HAL_TIMEx_PWMN_Start(&htim_right, TIM_CHANNEL_2); - HAL_TIMEx_PWMN_Start(&htim_right, TIM_CHANNEL_3); - - htim_left.Instance->RCR = 1; - - __HAL_TIM_ENABLE(&htim_right); -} - -void MX_ADC_Init(void) { - ADC_MultiModeTypeDef multimode; - ADC_ChannelConfTypeDef sConfig; - - __HAL_RCC_ADC1_CLK_ENABLE(); - - hadc.Instance = ADC1; - hadc.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4; - hadc.Init.Resolution = ADC_RESOLUTION_12B; - hadc.Init.ScanConvMode = ENABLE; - hadc.Init.ContinuousConvMode = DISABLE; - hadc.Init.DiscontinuousConvMode = DISABLE; - hadc.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T8_TRGO; - hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING; - hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT; - hadc.Init.NbrOfConversion = 8; - HAL_ADC_Init(&hadc); - - HAL_ADCEx_MultiModeConfigChannel(&hadc, &multimode); - sConfig.SamplingTime = ADC_SAMPLETIME_15CYCLES; - - sConfig.Channel = ADC_CHANNEL_5; // pa5 left b -> right - sConfig.Rank = 1; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_6; // pa6 left c -> right - sConfig.Rank = 2; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_0; // pa0 right a -> left - sConfig.Rank = 3; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_1; // pa1 right b -> left - sConfig.Rank = 4; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_3; // pa3 left cur -> right - sConfig.Rank = 5; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_2; // pa2 right cur -> left - sConfig.Rank = 6; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_4; // pa4 vbat - sConfig.Rank = 7; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.SamplingTime = ADC_SAMPLETIME_144CYCLES; - sConfig.Channel = ADC_CHANNEL_TEMPSENSOR; // internal temp - sConfig.Rank = 8; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - hadc.Instance->CR2 |= ADC_CR2_DMA | ADC_CR2_DDS | ADC_CCR_TSVREFE; - - __HAL_ADC_ENABLE(&hadc); - - __HAL_RCC_DMA2_CLK_ENABLE(); - - DMA2_Stream0->CR = 0; - DMA2_Stream0->NDTR = 8; - DMA2_Stream0->PAR = (uint32_t)&(ADC1->DR); - DMA2_Stream0->M0AR = (uint32_t)&adc_buffer; - DMA2_Stream0->CR = DMA_SxCR_MSIZE_1 | DMA_SxCR_PSIZE_1 | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_TCIE; - DMA2_Stream0->CR &= ~DMA_SxCR_CHSEL; - DMA2_Stream0->FCR &= ~DMA_SxFCR_DMDIS; - DMA2_Stream0->CR |= DMA_SxCR_EN; - - HAL_NVIC_SetPriority(DMA2_Stream0_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(DMA2_Stream0_IRQn); -} - - -#endif diff --git a/body/board/startup_stm32f413xx.s b/body/board/startup_stm32f413xx.s deleted file mode 100644 index 52e2f833aac3412..000000000000000 --- a/body/board/startup_stm32f413xx.s +++ /dev/null @@ -1,565 +0,0 @@ -/** - ****************************************************************************** - * @file startup_stm32f413xx.s - * @author MCD Application Team - * @brief STM32F413xx Devices vector table for GCC based toolchains. - * 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-M4 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - - .syntax unified - .cpu cortex-m4 - .fpu softvfp - .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 intitialization 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, DAC1 and DAC2 */ - .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 DFSDM1_FLT0_IRQHandler /* DFSDM1 Filter0 */ - .word DFSDM1_FLT1_IRQHandler /* DFSDM1 Filter1 */ - .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 CAN3_TX_IRQHandler /* CAN3 TX */ - .word CAN3_RX0_IRQHandler /* CAN3 RX0 */ - .word CAN3_RX1_IRQHandler /* CAN3 RX1 */ - .word CAN3_SCE_IRQHandler /* CAN3 SCE */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word RNG_IRQHandler /* RNG */ - .word FPU_IRQHandler /* FPU */ - .word UART7_IRQHandler /* UART7 */ - .word UART8_IRQHandler /* UART8 */ - .word SPI4_IRQHandler /* SPI4 */ - .word SPI5_IRQHandler /* SPI5 */ - .word 0 /* Reserved */ - .word SAI1_IRQHandler /* SAI1 */ - .word UART9_IRQHandler /* UART9 */ - .word UART10_IRQHandler /* UART10 */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word QUADSPI_IRQHandler /* QuadSPI */ - .word 0 /* Reserved */ - .word 0 /* Reserved */ - .word FMPI2C1_EV_IRQHandler /* FMPI2C1 Event */ - .word FMPI2C1_ER_IRQHandler /* FMPI2C1 Error */ - .word LPTIM1_IRQHandler /* LPTIM1 */ - .word DFSDM2_FLT0_IRQHandler /* DFSDM2 Filter0 */ - .word DFSDM2_FLT1_IRQHandler /* DFSDM2 Filter1 */ - .word DFSDM2_FLT2_IRQHandler /* DFSDM2 Filter2 */ - .word DFSDM2_FLT3_IRQHandler /* DFSDM2 Filter3 */ - -/******************************************************************************* -* -* 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 DFSDM1_FLT0_IRQHandler - .thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler - - .weak DFSDM1_FLT1_IRQHandler - .thumb_set DFSDM1_FLT1_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 CAN3_TX_IRQHandler - .thumb_set CAN3_TX_IRQHandler,Default_Handler - - .weak CAN3_RX0_IRQHandler - .thumb_set CAN3_RX0_IRQHandler,Default_Handler - - .weak CAN3_RX1_IRQHandler - .thumb_set CAN3_RX1_IRQHandler,Default_Handler - - .weak CAN3_SCE_IRQHandler - .thumb_set CAN3_SCE_IRQHandler,Default_Handler - - .weak RNG_IRQHandler - .thumb_set RNG_IRQHandler,Default_Handler - - .weak FPU_IRQHandler - .thumb_set FPU_IRQHandler,Default_Handler - - .weak UART7_IRQHandler - .thumb_set UART7_IRQHandler,Default_Handler - - .weak UART8_IRQHandler - .thumb_set UART8_IRQHandler,Default_Handler - - .weak SPI4_IRQHandler - .thumb_set SPI4_IRQHandler,Default_Handler - - .weak SPI5_IRQHandler - .thumb_set SPI5_IRQHandler,Default_Handler - - .weak SAI1_IRQHandler - .thumb_set SAI1_IRQHandler,Default_Handler - - .weak UART9_IRQHandler - .thumb_set UART9_IRQHandler,Default_Handler - - .weak UART10_IRQHandler - .thumb_set UART10_IRQHandler,Default_Handler - - .weak QUADSPI_IRQHandler - .thumb_set QUADSPI_IRQHandler,Default_Handler - - .weak FMPI2C1_EV_IRQHandler - .thumb_set FMPI2C1_EV_IRQHandler,Default_Handler - - .weak FMPI2C1_ER_IRQHandler - .thumb_set FMPI2C1_ER_IRQHandler,Default_Handler - - .weak LPTIM1_IRQHandler - .thumb_set LPTIM1_IRQHandler,Default_Handler - - .weak DFSDM2_FLT0_IRQHandler - .thumb_set DFSDM2_FLT0_IRQHandler,Default_Handler - - .weak DFSDM2_FLT1_IRQHandler - .thumb_set DFSDM2_FLT1_IRQHandler,Default_Handler - - .weak DFSDM2_FLT2_IRQHandler - .thumb_set DFSDM2_FLT2_IRQHandler,Default_Handler - - .weak DFSDM2_FLT3_IRQHandler - .thumb_set DFSDM2_FLT3_IRQHandler,Default_Handler -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/stm32fx_flash.ld b/body/board/stm32fx_flash.ld deleted file mode 100644 index 9174e3d05b888b2..000000000000000 --- a/body/board/stm32fx_flash.ld +++ /dev/null @@ -1,161 +0,0 @@ -/* -***************************************************************************** -** - -** File : LinkerScript.ld -** -** Abstract : Linker script for STM32F413ZHTx Device with -** 1536KByte FLASH, 320KByte 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 -** -** -** Distribution: The file is distributed as is, without any warranty -** of any kind. -** -** (c)Copyright Ac6. -** 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. Ac6 permit registered System Workbench for MCU 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 System Workbench for MCU toolchain. -** -***************************************************************************** -*/ - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* Highest address of the user mode stack */ -enter_bootloader_mode = 0x2004FFFC; -_estack = 0x2004FFFC; /* 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 = 0x200; /* required amount of heap */ -_Min_Stack_Size = 0x400; /* required amount of stack */ - -/* Specify the memory areas */ -MEMORY -{ - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 320K -} - -/* 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) */ - *(.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 */ - } >FLASH - - /* Constant data goes into FLASH */ - .rodata : - { - . = ALIGN(4); - *(.rodata) /* .rodata sections (constants, strings, etc.) */ - *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ - . = ALIGN(4); - } >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 (*(SORT(.fini_array.*))) - KEEP (*(.fini_array*)) - PROVIDE_HIDDEN (__fini_array_end = .); - } >FLASH - - /* used by the startup to initialize data */ - _sidata = LOADADDR(.data); - - /* Initialized data sections goes into RAM, load LMA copy after code */ - .data : - { - . = 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 AT> FLASH - - /* 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(8); - PROVIDE ( end = . ); - PROVIDE ( _end = . ); - . = . + _Min_Heap_Size; - . = . + _Min_Stack_Size; - . = ALIGN(8); - } >RAM - - .ARM.attributes 0 : { *(.ARM.attributes) } -} - - diff --git a/body/board/uds.h b/body/board/uds.h deleted file mode 100644 index f9e151be77d2b63..000000000000000 --- a/body/board/uds.h +++ /dev/null @@ -1,127 +0,0 @@ -extern uint8_t hw_type; -void can_send_msg(uint32_t addr, uint32_t dhr, uint32_t dlr, uint8_t len); - -uint8_t uid[10]; -uint32_t uds_engine_request = 0; -uint32_t uds_debug_request = 0; -uint8_t knee_detected = 0; -uint8_t sep_time = 0; - -void process_uds(uint32_t addr, uint32_t dlr) { - memcpy(uid, (void *)0x1FFF7A10U, 0xAU); - - if ((hw_type == HW_TYPE_BASE) && - ((addr == BROADCAST_ADDR) || - (addr == FALLBACK_ADDR))) { // OBD2 broadcast request, redirect to UDS? - switch(dlr) { - // VIN 09 OBD2 - case 0x020902U: - can_send_msg(FALLBACK_R_ADDR, 0x4D4F4301U, 0x02491410U, 8U); - uds_engine_request = 0xF190U; - break; - // VIN : F190 on broadcast - case 0x90F12203U: - can_send_msg(FALLBACK_R_ADDR, 0x4D4F4390U, 0xF1621410U, 8U); - break; - // VIN continue - default: - if ((dlr & 0xFF) == 0x30U) { - sep_time = (dlr >> 16U) & 0xFF; - delay(sep_time); - can_send_msg(FALLBACK_R_ADDR, 0x5659444FU, 0x42414D21U, 8U); - can_send_msg(FALLBACK_R_ADDR, 0x314E4F49U, 0x53524522U, 8U); - } - break; - } - } else if (addr == (ENGINE_ADDR + board.uds_offset)) { // UDS request to "main" ECU - switch(dlr) { - // TESTER PRESENT - case 0x3E02U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x0U, 0x7E02U, 8U); - break; - // DIAGNOSTIC SESSION CONTROL: DEFAULT - case 0x011002U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x0U, 0x015002U, 8U); - break; - // DIAGNOSTIC SESSION CONTROL: EXTENDED - case 0x031002U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x0U, 0x035002U, 8U); - break; - // APPLICATION SOFTWARE IDENTIFICATION : F181 (used for fingerprinting, firmware version) - case 0x81F12203U: - COMPILE_TIME_ASSERT(sizeof(version) == 6U); - can_send_msg(ENGINE_R_ADDR + board.uds_offset, ((version[2] << 24U) | (version[1] << 16U) | (version[0] << 8U) | 0x81U), 0xF1620A10U, 8U); - uds_engine_request = 0xF181U; - break; - // ECU SERIAL NUMBER : F18C - case 0x8CF12203U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, ((uid[2] << 24U) | (uid[1] << 16U) | (uid[0] << 8U) | 0x8CU), 0xF1620D10U, 8U); - uds_engine_request = 0xF18CU; - break; - // VIN : F190 - case 0x90F12203U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x4D4F4390U, 0xF1621410U, 8U); - uds_engine_request = 0xF190U; - break; - // FLOW CONTROL MESSAGE - default: - if ((dlr & 0xFF) == 0x30U) { - sep_time = (dlr >> 16U) & 0xFF; - delay(sep_time); - switch(uds_engine_request) { - // APPLICATION SOFTWARE IDENTIFICATION : F181 - case 0xF181U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, (knee_detected + 0x61), ((version[5] << 24U) | (version[4] << 16U) | (version[3] << 8U) | 0x21U), 8U); - uds_engine_request = 0; - break; - // ECU SERIAL NUMBER : F18C - case 0xF18CU: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, ((uid[9] << 24U) | (uid[8] << 16U) | (uid[7]<< 8U) | uid[6]), ((uid[5] << 24U) | (uid[4] << 16U) | (uid[3] << 8U) | 0x21U), 8U); - uds_engine_request = 0; - break; - // VIN : F190 - case 0xF190U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x5659444FU, 0x42414D21U, 8U); - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x314E4F49U, 0x53524522U, 8U); - uds_engine_request = 0; - break; - } - } - break; - } - } else if (addr == (DEBUG_ADDR + board.uds_offset)) { // UDS request to "DEBUG" ECU - switch(dlr) { - // TESTER PRESENT - case 0x3E02U: - can_send_msg(DEBUG_R_ADDR + board.uds_offset, 0x0U, 0x7E02U, 8U); - break; - // DIAGNOSTIC SESSION CONTROL: DEFAULT - case 0x011002U: - can_send_msg(DEBUG_R_ADDR + board.uds_offset, 0x0U, 0x015002U, 8U); - break; - // DIAGNOSTIC SESSION CONTROL: EXTENDED - case 0x031002U: - can_send_msg(DEBUG_R_ADDR + board.uds_offset, 0x0U, 0x035002U, 8U); - break; - // APPLICATION SOFTWARE IDENTIFICATION : F181 (used for git hash logging) - case 0x81F12203U: - COMPILE_TIME_ASSERT(sizeof(gitversion) == 8U); - can_send_msg((DEBUG_R_ADDR + board.uds_offset), ((gitversion[2] << 24U) | (gitversion[1] << 16U) | (gitversion[0] << 8U) | 0x81U), 0xF1620B10U, 8U); - uds_debug_request = 0xF181U; - break; - default: - if ((dlr & 0xFF) == 0x30U) { - sep_time = (dlr >> 16U) & 0xFF; - delay(sep_time); - switch(uds_debug_request) { - // APPLICATION SOFTWARE IDENTIFICATION : F181 - case 0xF181U: - can_send_msg((DEBUG_R_ADDR + board.uds_offset), ((gitversion[7]<< 8U) | gitversion[6]), ((gitversion[5] << 24U) | (gitversion[4] << 16U) | (gitversion[3] << 8U) | 0x21U), 8U); - uds_debug_request = 0; - break; - } - } - break; - } - } -} diff --git a/body/board/util.c b/body/board/util.c deleted file mode 100644 index c0b19ff19ac493f..000000000000000 --- a/body/board/util.c +++ /dev/null @@ -1,258 +0,0 @@ -#include -#include "stm32f4xx_hal.h" -#include "defines.h" -#include "config.h" -#include "util.h" -#include "bldc/BLDC_controller.h" -#include "bldc/rtwtypes.h" - -// TODO: simplify util.c to util.h - -//------------------------------------------------------------------------ -// Global variables set externally -//------------------------------------------------------------------------ -extern int16_t batVoltage; -extern uint8_t buzzerCount; // global variable for the buzzer counts. can be 1, 2, 3, 4, 5, 6, 7... -extern uint8_t buzzerFreq; // global variable for the buzzer pitch. can be 1, 2, 3, 4, 5, 6, 7... -extern uint8_t buzzerPattern; // global variable for the buzzer pattern. can be 1, 2, 3, 4, 5, 6, 7... - -extern uint8_t enable_motors; // global variable for motor enable -extern uint8_t ignition; // global variable for ignition on SBU2 line - -extern uint8_t hw_type; - -extern board_t board; - -//------------------------------------------------------------------------ -// Matlab defines - from auto-code generation -//--------------- -RT_MODEL rtM_Left_; /* Real-time model */ -RT_MODEL rtM_Right_; /* Real-time model */ -RT_MODEL *const rtM_Left = &rtM_Left_; -RT_MODEL *const rtM_Right = &rtM_Right_; - -extern P rtP_Left; /* Block parameters (auto storage) */ -DW rtDW_Left; /* Observable states */ -ExtU rtU_Left; /* External inputs */ -ExtY rtY_Left; /* External outputs */ - -P rtP_Right; /* Block parameters (auto storage) */ -DW rtDW_Right; /* Observable states */ -ExtU rtU_Right; /* External inputs */ -ExtY rtY_Right; /* External outputs */ -//--------------- - -int16_t speedAvg; // average measured speed -int16_t speedAvgAbs; // average measured speed in absolute - -uint8_t ctrlModReqRaw = CTRL_MOD_REQ; -uint8_t ctrlModReq = CTRL_MOD_REQ; // Final control mode request - - -void BLDC_Init(void) { - /* Set BLDC controller parameters */ - rtP_Left.b_angleMeasEna = 0; // Motor angle input: 0 = estimated angle, 1 = measured angle (e.g. if encoder is available) - rtP_Left.z_selPhaCurMeasABC = 0; // Left motor measured current phases {Green, Blue} = {iA, iB} -> do NOT change - rtP_Left.z_ctrlTypSel = CTRL_TYP_SEL; - rtP_Left.b_diagEna = DIAG_ENA; - rtP_Left.i_max = (I_MOT_MAX * A2BIT_CONV) << 4; // fixdt(1,16,4) - rtP_Left.n_max = N_MOT_MAX << 4; // fixdt(1,16,4) - rtP_Left.b_fieldWeakEna = FIELD_WEAK_ENA; - rtP_Left.id_fieldWeakMax = (FIELD_WEAK_MAX * A2BIT_CONV) << 4; // fixdt(1,16,4) - rtP_Left.a_phaAdvMax = PHASE_ADV_MAX << 4; // fixdt(1,16,4) - rtP_Left.r_fieldWeakHi = FIELD_WEAK_HI << 4; // fixdt(1,16,4) - rtP_Left.r_fieldWeakLo = FIELD_WEAK_LO << 4; // fixdt(1,16,4) - - rtP_Right = rtP_Left; // Copy the Left motor parameters to the Right motor parameters - rtP_Right.n_max = N_MOT_MAX << 4; // But add separate max RPM limit - rtP_Right.z_selPhaCurMeasABC = 1; // Right motor measured current phases {Blue, Yellow} = {iB, iC} -> do NOT change - - /* Pack LEFT motor data into RTM */ - rtM_Left->defaultParam = &rtP_Left; - rtM_Left->dwork = &rtDW_Left; - rtM_Left->inputs = &rtU_Left; - rtM_Left->outputs = &rtY_Left; - - /* Pack RIGHT motor data into RTM */ - rtM_Right->defaultParam = &rtP_Right; - rtM_Right->dwork = &rtDW_Right; - rtM_Right->inputs = &rtU_Right; - rtM_Right->outputs = &rtY_Right; - - /* Initialize BLDC controllers */ - BLDC_controller_initialize(rtM_Left); - BLDC_controller_initialize(rtM_Right); -} - -void out_enable(uint8_t out, bool enabled) { - switch(out) { - case LED_GREEN: - HAL_GPIO_WritePin(board.led_portG, board.led_pinG, !enabled); - break; - case LED_RED: - HAL_GPIO_WritePin(board.led_portR, board.led_pinR, !enabled); - break; - case LED_BLUE: - HAL_GPIO_WritePin(board.led_portB, board.led_pinB, !enabled); - break; - case IGNITION: - HAL_GPIO_WritePin(board.ignition_port, board.ignition_pin, enabled); - break; - case POWERSWITCH: - HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, enabled); - break; - case TRANSCEIVER: - HAL_GPIO_WritePin(board.can_portEN, board.can_pinEN, !enabled); - break; - } -} - -void poweronMelody(void) { - buzzerCount = 0; - for (int i = 8; i >= 0; i--) { - buzzerFreq = (uint8_t)i; - HAL_Delay(100); - } - buzzerFreq = 0; -} - -void beepCount(uint8_t cnt, uint8_t freq, uint8_t pattern) { - buzzerCount = cnt; - buzzerFreq = freq; - buzzerPattern = pattern; -} - -void beepLong(uint8_t freq) { - buzzerCount = 0; - buzzerFreq = freq; - HAL_Delay(500); - buzzerFreq = 0; -} - -void beepShort(uint8_t freq) { - buzzerCount = 0; - buzzerFreq = freq; - HAL_Delay(100); - buzzerFreq = 0; -} - -void beepShortMany(uint8_t cnt, int8_t dir) { - if (dir >= 0) { // increasing tone - for(uint8_t i = 2*cnt; i >= 2; i=i-2) { - beepShort(i + 3); - } - } else { // decreasing tone - for(uint8_t i = 2; i <= 2*cnt; i=i+2) { - beepShort(i + 3); - } - } -} - -void calcAvgSpeed(void) { - // Calculate measured average speed. The minus sign (-) is because motors spin in opposite directions - speedAvg = ( rtY_Left.n_mot - rtY_Right.n_mot) / 2; - - // Handle the case when SPEED_COEFFICIENT sign is negative (which is when most significant bit is 1) - if (SPEED_COEFFICIENT & (1 << 16)) { - speedAvg = -speedAvg; - } - speedAvgAbs = ABS(speedAvg); -} - -void poweroff(void) { - enable_motors = 0; - buzzerCount = 0; - buzzerPattern = 0; - for (int i = 0; i < 8; i++) { - buzzerFreq = (uint8_t)i; - HAL_Delay(100); - } - out_enable(POWERSWITCH, false); - while(1) { - // Temporarily, to see that we went to power off but can't switch the latch - HAL_GPIO_TogglePin(board.led_portR, board.led_pinR); - HAL_Delay(100); - } -} - -#define PULL_EFFECTIVE_DELAY 4096 -uint8_t detect_with_pull(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, uint32_t mode) { - GPIO_InitTypeDef GPIO_InitStruct; - GPIO_InitStruct.Pin = GPIO_Pin; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = mode; - HAL_GPIO_Init(GPIOx, &GPIO_InitStruct); - for (volatile int i=0; i= 0; i--) { - crc ^= dat[i]; - for (j = 0; j < 8; j++) { - if ((crc & 0x80U) != 0U) { - crc = (uint8_t)((crc << 1) ^ poly); - } - else { - crc <<= 1; - } - } - } - return crc; -} - -/* =========================== Filtering Functions =========================== */ - - /* Low pass filter fixed-point 32 bits: fixdt(1,32,16) - * Max: 32767.99998474121 - * Min: -32768 - * Res: 1.52587890625e-05 - * - * Inputs: u = int16 or int32 - * Outputs: y = fixdt(1,32,16) - * Parameters: coef = fixdt(0,16,16) = [0,65535U] - * - * Example: - * If coef = 0.8 (in floating point), then coef = 0.8 * 2^16 = 52429 (in fixed-point) - * filtLowPass16(u, 52429, &y); - * yint = (int16_t)(y >> 16); // the integer output is the fixed-point ouput shifted by 16 bits - */ -void filtLowPass32(int32_t u, uint16_t coef, int32_t *y) { - int64_t tmp; - tmp = ((int64_t)((u << 4) - (*y >> 12)) * coef) >> 4; - tmp = CLAMP(tmp, -2147483648LL, 2147483647LL); // Overflow protection: 2147483647LL = 2^31 - 1 - *y = (int32_t)tmp + (*y); -} - - /* rateLimiter16(int16_t u, int16_t rate, int16_t *y); - * Inputs: u = int16 - * Outputs: y = fixdt(1,16,4) - * Parameters: rate = fixdt(1,16,4) = [0, 32767] Do NOT make rate negative (>32767) - */ -void rateLimiter16(int16_t u, int16_t rate, int16_t *y) { - int16_t q0; - int16_t q1; - - q0 = (u << 4) - *y; - - if (q0 > rate) { - q0 = rate; - } else { - q1 = -rate; - if (q0 < q1) { - q0 = q1; - } - } - - *y = q0 + *y; -} diff --git a/body/board/util.h b/body/board/util.h deleted file mode 100644 index 0eea10bd0e340bc..000000000000000 --- a/body/board/util.h +++ /dev/null @@ -1,33 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef UTIL_H -#define UTIL_H - -#include -#include - -// Initialization Functions -void BLDC_Init(void); - -// General Functions -void out_enable(uint8_t led, bool enabled); -void poweronMelody(void); -void beepCount(uint8_t cnt, uint8_t freq, uint8_t pattern); -void beepLong(uint8_t freq); -void beepShort(uint8_t freq); -void beepShortMany(uint8_t cnt, int8_t dir); -void calcAvgSpeed(void); - -// Poweroff Functions -void poweroff(void); - -// GPIO functions -uint8_t detect_with_pull(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, uint32_t mode); -uint8_t board_id(void); - -// Filtering Functions -void filtLowPass32(int32_t u, uint16_t coef, int32_t *y); -void rateLimiter16(int16_t u, int16_t rate, int16_t *y); - -uint8_t crc_checksum(uint8_t *dat, int len, const uint8_t poly); - -#endif diff --git a/body/board/version.h b/body/board/version.h deleted file mode 100644 index 2cc94a18092b215..000000000000000 --- a/body/board/version.h +++ /dev/null @@ -1 +0,0 @@ -const uint8_t version[6] = "0.3.00"; diff --git a/body/certs/debug b/body/certs/debug deleted file mode 100644 index 39864b6b1a36e43..000000000000000 --- a/body/certs/debug +++ /dev/null @@ -1,15 +0,0 @@ ------BEGIN RSA PRIVATE KEY----- -MIICXQIBAAKBgQC948lnRo4x44Rd7Y8bQAML4aKDC4XRx958fHV8K6+FbCaP1Z42 -U2kX0yygak0LjoDutpgObmGHZA+Iz3HeUD6VGjr/teN24vPk+A95cRsjt8rgmGQ9 -6HNjaNgjR+gl1F9XxFimMzir82Xpl1ekTueJNXa7ia5HVH1nFdiksOKHGQIDAQAB -AoGAQuPw2I6EHJLW1/eNB75e1FqhUqRGeYV8nEGDaUBCTi+wzc4kM2LijF/5QnDv -vvht9qkfm0XK2VSoHDtnEzcVM/l1ksb68n4R/1nUooAWY6cQI7dCSk/A6yS1EJFg -BXsgGbT/65khw9pzBW2zVtMVcVNWFayqfCO1I9WcDdA1x1kCQQDfrhoZTZNoDEUE -JKM4fiUdWr1h3Aw8KLJFFexSWeGDwo+qqnujYcKWkHa9qaH1RG5x8Kir9s9Oi4Js -mzKwov8fAkEA2VPJPWxJ4vVQpXle6wC1nyoL7s739yxMWFcabvkzDDhlIVBNdVJd -gZKsFWV7QnVNdDMjn9D27FwKu3i2D+kKxwJBANp1SMojqO765MEKI1t+YDNONx6H -cm+i85Fjuv4nCIjOEdCGVuCYDxtMFpxgO2y3HAMuHx5sm8XDnWsDHLvFRdMCQD7V -XqWHnYUk8AAnqy2+ssQl3/VXmZG5GQmhhV74Za3u0C5ljT+SZL6FrYMyKAT67T3f -WzllrT6BDglNyTWoZxkCQQCt0XSoGM3603GGYNt6AUlGSgtXSo/2Px7odGUtQoKA -FH9q6FVMYpQJ38spZxIGufZJmLP8LLg6YIWJj1F+akxr ------END RSA PRIVATE KEY----- diff --git a/body/certs/debug.pub b/body/certs/debug.pub deleted file mode 100644 index 00e219d7bb8cfaf..000000000000000 --- a/body/certs/debug.pub +++ /dev/null @@ -1 +0,0 @@ -ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQC948lnRo4x44Rd7Y8bQAML4aKDC4XRx958fHV8K6+FbCaP1Z42U2kX0yygak0LjoDutpgObmGHZA+Iz3HeUD6VGjr/teN24vPk+A95cRsjt8rgmGQ96HNjaNgjR+gl1F9XxFimMzir82Xpl1ekTueJNXa7ia5HVH1nFdiksOKHGQ== batman@y840 diff --git a/body/certs/release.pub b/body/certs/release.pub deleted file mode 100644 index 19066e29a75cad8..000000000000000 --- a/body/certs/release.pub +++ /dev/null @@ -1 +0,0 @@ -ssh-rsa AAAAB3NzaC1yc2EAAAADAQABAAAAgQDGN9GU2nOc0kKq6vdZI5qUMzHt234ngqofrgCFFxL0D2Whex0zACp9gar0HZp+bvtpoSgU/Ev8wexNKr+A9QTradljiuxi5ctrOra9k+wxqNj63Wrcu4+wU5UnJEVf/buV4jCOFffMT8z3PO4imt8LzHuEIC/m/ASKVYyvuvBRQQ== batman@y840 diff --git a/body/crypto/hash-internal.h b/body/crypto/hash-internal.h deleted file mode 100644 index 05ec3ec9fd22aa7..000000000000000 --- a/body/crypto/hash-internal.h +++ /dev/null @@ -1,63 +0,0 @@ -/* - * Copyright 2007 The Android Open Source Project - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * 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. - * * Neither the name of Google Inc. 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 Google Inc. ``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 Google Inc. 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. - */ - -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ - -#include "stdint.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -struct HASH_CTX; // forward decl - -typedef struct HASH_VTAB { - void (* const init)(struct HASH_CTX*); - void (* const update)(struct HASH_CTX*, const void*, int); - const uint8_t* (* const final)(struct HASH_CTX*); - const uint8_t* (* const hash)(const void*, int, uint8_t*); - int size; -} HASH_VTAB; - -typedef struct HASH_CTX { - const HASH_VTAB * f; - uint64_t count; - uint8_t buf[64]; - uint32_t state[8]; // upto SHA2 -} HASH_CTX; - -#define HASH_init(ctx) (ctx)->f->init(ctx) -#define HASH_update(ctx, data, len) (ctx)->f->update(ctx, data, len) -#define HASH_final(ctx) (ctx)->f->final(ctx) -#define HASH_hash(data, len, digest) (ctx)->f->hash(data, len, digest) -#define HASH_size(ctx) (ctx)->f->size - -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ diff --git a/body/crypto/rsa.c b/body/crypto/rsa.c deleted file mode 100644 index 24171e879092756..000000000000000 --- a/body/crypto/rsa.c +++ /dev/null @@ -1,294 +0,0 @@ -/* rsa.c -** -** Copyright 2012, The Android Open Source Project -** -** Redistribution and use in source and binary forms, with or without -** modification, are permitted provided that the following conditions are met: -** * Redistributions of source code must retain the above copyright -** notice, this list of conditions and the following disclaimer. -** * 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. -** * Neither the name of Google Inc. 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 Google Inc. ``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 Google Inc. 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. -*/ - -#include "rsa.h" -#include "sha.h" - -// a[] -= mod -static void subM(const RSAPublicKey* key, - uint32_t* a) { - int64_t A = 0; - int i; - for (i = 0; i < key->len; ++i) { - A += (uint64_t)a[i] - key->n[i]; - a[i] = (uint32_t)A; - A >>= 32; - } -} - -// return a[] >= mod -static int geM(const RSAPublicKey* key, - const uint32_t* a) { - int i; - for (i = key->len; i;) { - --i; - if (a[i] < key->n[i]) return 0; - if (a[i] > key->n[i]) return 1; - } - return 1; // equal -} - -// montgomery c[] += a * b[] / R % mod -static void montMulAdd(const RSAPublicKey* key, - uint32_t* c, - const uint32_t a, - const uint32_t* b) { - uint64_t A = (uint64_t)a * b[0] + c[0]; - uint32_t d0 = (uint32_t)A * key->n0inv; - uint64_t B = (uint64_t)d0 * key->n[0] + (uint32_t)A; - int i; - - for (i = 1; i < key->len; ++i) { - A = (A >> 32) + (uint64_t)a * b[i] + c[i]; - B = (B >> 32) + (uint64_t)d0 * key->n[i] + (uint32_t)A; - c[i - 1] = (uint32_t)B; - } - - A = (A >> 32) + (B >> 32); - - c[i - 1] = (uint32_t)A; - - if (A >> 32) { - subM(key, c); - } -} - -// montgomery c[] = a[] * b[] / R % mod -static void montMul(const RSAPublicKey* key, - uint32_t* c, - const uint32_t* a, - const uint32_t* b) { - int i; - for (i = 0; i < key->len; ++i) { - c[i] = 0; - } - for (i = 0; i < key->len; ++i) { - montMulAdd(key, c, a[i], b); - } -} - -// In-place public exponentiation. -// Input and output big-endian byte array in inout. -static void modpow(const RSAPublicKey* key, - uint8_t* inout) { - uint32_t a[RSANUMWORDS]; - uint32_t aR[RSANUMWORDS]; - uint32_t aaR[RSANUMWORDS]; - uint32_t* aaa = 0; - int i; - - // Convert from big endian byte array to little endian word array. - for (i = 0; i < key->len; ++i) { - uint32_t tmp = - (inout[((key->len - 1 - i) * 4) + 0] << 24) | - (inout[((key->len - 1 - i) * 4) + 1] << 16) | - (inout[((key->len - 1 - i) * 4) + 2] << 8) | - (inout[((key->len - 1 - i) * 4) + 3] << 0); - a[i] = tmp; - } - - if (key->exponent == 65537) { - aaa = aaR; // Re-use location. - montMul(key, aR, a, key->rr); // aR = a * RR / R mod M - for (i = 0; i < 16; i += 2) { - montMul(key, aaR, aR, aR); // aaR = aR * aR / R mod M - montMul(key, aR, aaR, aaR); // aR = aaR * aaR / R mod M - } - montMul(key, aaa, aR, a); // aaa = aR * a / R mod M - } else if (key->exponent == 3) { - aaa = aR; // Re-use location. - montMul(key, aR, a, key->rr); /* aR = a * RR / R mod M */ - montMul(key, aaR, aR, aR); /* aaR = aR * aR / R mod M */ - montMul(key, aaa, aaR, a); /* aaa = aaR * a / R mod M */ - } - - // Make sure aaa < mod; aaa is at most 1x mod too large. - if (geM(key, aaa)) { - subM(key, aaa); - } - - // Convert to bigendian byte array - for (i = key->len - 1; i >= 0; --i) { - uint32_t tmp = aaa[i]; - *inout++ = tmp >> 24; - *inout++ = tmp >> 16; - *inout++ = tmp >> 8; - *inout++ = tmp >> 0; - } -} - -// Expected PKCS1.5 signature padding bytes, for a keytool RSA signature. -// Has the 0-length optional parameter encoded in the ASN1 (as opposed to the -// other flavor which omits the optional parameter entirely). This code does not -// accept signatures without the optional parameter. - -/* -static const uint8_t sha_padding[RSANUMBYTES] = { - 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0x00, 0x30, 0x21, 0x30, - 0x09, 0x06, 0x05, 0x2b, 0x0e, 0x03, 0x02, 0x1a, - 0x05, 0x00, 0x04, 0x14, - - // 20 bytes of hash go here. - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -}; -*/ - -static const uint8_t sha_padding_1024[RSANUMBYTES] = { - 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0x00, - - // 20 bytes of hash go here. - 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -}; - -// SHA-1 of PKCS1.5 signature sha_padding for 2048 bit, as above. -// At the location of the bytes of the hash all 00 are hashed. -/*static const uint8_t kExpectedPadShaRsa2048[SHA_DIGEST_SIZE] = { - 0xdc, 0xbd, 0xbe, 0x42, 0xd5, 0xf5, 0xa7, 0x2e, - 0x6e, 0xfc, 0xf5, 0x5d, 0xaf, 0x9d, 0xea, 0x68, - 0x7c, 0xfb, 0xf1, 0x67 -};*/ - -// Verify a 2048-bit RSA PKCS1.5 signature against an expected hash. -// Both e=3 and e=65537 are supported. hash_len may be -// SHA_DIGEST_SIZE (== 20) to indicate a SHA-1 hash, or -// SHA256_DIGEST_SIZE (== 32) to indicate a SHA-256 hash. No other -// values are supported. -// -// Returns 1 on successful verification, 0 on failure. -int RSA_verify(const RSAPublicKey *key, - const uint8_t *signature, - const int len, - const uint8_t *hash, - const int hash_len) { - uint8_t buf[RSANUMBYTES]; - int i; - //const uint8_t* padding_hash; - - if (key->len != RSANUMWORDS) { - return 0; // Wrong key passed in. - } - - if (len != sizeof(buf)) { - return 0; // Wrong input length. - } - - if (hash_len != SHA_DIGEST_SIZE) { - return 0; // Unsupported hash. - } - - if (key->exponent != 3 && key->exponent != 65537) { - return 0; // Unsupported exponent. - } - - for (i = 0; i < len; ++i) { // Copy input to local workspace. - buf[i] = signature[i]; - } - - modpow(key, buf); // In-place exponentiation. - -#ifdef TEST_RSA - printf("sig\n"); - for (i=0;i> (32 - (bits)))) - -static void SHA1_Transform(SHA_CTX* ctx) { - uint32_t W[80]; - uint32_t A, B, C, D, E; - uint8_t* p = ctx->buf; - int t; - - for(t = 0; t < 16; ++t) { - uint32_t tmp = *p++ << 24; - tmp |= *p++ << 16; - tmp |= *p++ << 8; - tmp |= *p++; - W[t] = tmp; - } - - for(; t < 80; t++) { - W[t] = rol(1,W[t-3] ^ W[t-8] ^ W[t-14] ^ W[t-16]); - } - - A = ctx->state[0]; - B = ctx->state[1]; - C = ctx->state[2]; - D = ctx->state[3]; - E = ctx->state[4]; - - for(t = 0; t < 80; t++) { - uint32_t tmp = rol(5,A) + E + W[t]; - - if (t < 20) - tmp += (D^(B&(C^D))) + 0x5A827999; - else if ( t < 40) - tmp += (B^C^D) + 0x6ED9EBA1; - else if ( t < 60) - tmp += ((B&C)|(D&(B|C))) + 0x8F1BBCDC; - else - tmp += (B^C^D) + 0xCA62C1D6; - - E = D; - D = C; - C = rol(30,B); - B = A; - A = tmp; - } - - ctx->state[0] += A; - ctx->state[1] += B; - ctx->state[2] += C; - ctx->state[3] += D; - ctx->state[4] += E; -} - -static const HASH_VTAB SHA_VTAB = { - SHA_init, - SHA_update, - SHA_final, - SHA_hash, - SHA_DIGEST_SIZE -}; - -void SHA_init(SHA_CTX* ctx) { - ctx->f = &SHA_VTAB; - ctx->state[0] = 0x67452301; - ctx->state[1] = 0xEFCDAB89; - ctx->state[2] = 0x98BADCFE; - ctx->state[3] = 0x10325476; - ctx->state[4] = 0xC3D2E1F0; - ctx->count = 0; -} - - -void SHA_update(SHA_CTX* ctx, const void* data, int len) { - int i = (int) (ctx->count & 63); - const uint8_t* p = (const uint8_t*)data; - - ctx->count += len; - - while (len--) { - ctx->buf[i++] = *p++; - if (i == 64) { - SHA1_Transform(ctx); - i = 0; - } - } -} - - -const uint8_t* SHA_final(SHA_CTX* ctx) { - uint8_t *p = ctx->buf; - uint64_t cnt = ctx->count * 8; - int i; - - SHA_update(ctx, (uint8_t*)"\x80", 1); - while ((ctx->count & 63) != 56) { - SHA_update(ctx, (uint8_t*)"\0", 1); - } - - /* Hack - right shift operator with non const argument requires - * libgcc.a which is missing in EON - * thus expanding for loop from - - for (i = 0; i < 8; ++i) { - uint8_t tmp = (uint8_t) (cnt >> ((7 - i) * 8)); - SHA_update(ctx, &tmp, 1); - } - - to - */ - - uint8_t tmp = 0; - tmp = (uint8_t) (cnt >> ((7 - 0) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 1) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 2) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 3) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 4) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 5) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 6) * 8)); - SHA_update(ctx, &tmp, 1); - tmp = (uint8_t) (cnt >> ((7 - 7) * 8)); - SHA_update(ctx, &tmp, 1); - - for (i = 0; i < 5; i++) { - uint32_t tmp = ctx->state[i]; - *p++ = tmp >> 24; - *p++ = tmp >> 16; - *p++ = tmp >> 8; - *p++ = tmp >> 0; - } - - return ctx->buf; -} - -/* Convenience function */ -const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest) { - SHA_CTX ctx; - SHA_init(&ctx); - SHA_update(&ctx, data, len); - memcpy(digest, SHA_final(&ctx), SHA_DIGEST_SIZE); - return digest; -} diff --git a/body/crypto/sha.h b/body/crypto/sha.h deleted file mode 100644 index 4b51a531bf582ac..000000000000000 --- a/body/crypto/sha.h +++ /dev/null @@ -1,51 +0,0 @@ -/* - * Copyright 2005 The Android Open Source Project - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * 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. - * * Neither the name of Google Inc. 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 Google Inc. ``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 Google Inc. 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. - */ -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ - -#include "hash-internal.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -typedef HASH_CTX SHA_CTX; - -void SHA_init(SHA_CTX* ctx); -void SHA_update(SHA_CTX* ctx, const void* data, int len); -const uint8_t* SHA_final(SHA_CTX* ctx); - -// Convenience method. Returns digest address. -// NOTE: *digest needs to hold SHA_DIGEST_SIZE bytes. -const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest); - -#define SHA_DIGEST_SIZE 20 - -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ diff --git a/body/crypto/sign.py b/body/crypto/sign.py deleted file mode 100755 index fe188e59d54d0ab..000000000000000 --- a/body/crypto/sign.py +++ /dev/null @@ -1,38 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import struct -import hashlib -from Crypto.PublicKey import RSA -import binascii - -# increment this to make new hardware not run old versions -VERSION = 2 - -if __name__ == "__main__": - with open(sys.argv[3], encoding='utf8') as k: - rsa = RSA.importKey(k.read()) - - with open(sys.argv[1], "rb") as f: - dat = f.read() - - print("signing", len(dat), "bytes") - - with open(sys.argv[2], "wb") as f: - if os.getenv("SETLEN") is not None: - # add the version at the end - dat += b"VERS" + struct.pack("I", VERSION) - # add the length at the beginning - x = struct.pack("I", len(dat)) + dat[4:] - # mock signature of dat[4:] - dd = hashlib.sha1(dat[4:]).digest() - else: - x = dat - dd = hashlib.sha1(dat).digest() - - print("hash:", str(binascii.hexlify(dd), "utf-8")) - dd = b"\x00\x01" + b"\xff" * 0x69 + b"\x00" + dd - rsa_out = pow(int.from_bytes(dd, byteorder='big', signed=False), rsa.d, rsa.n) - sig = (hex(rsa_out)[2:].rjust(0x100, '0')) - x += binascii.unhexlify(sig) - f.write(x) diff --git a/body/crypto/stdint.h b/body/crypto/stdint.h deleted file mode 100644 index 67ac93ed75f0846..000000000000000 --- a/body/crypto/stdint.h +++ /dev/null @@ -1,4 +0,0 @@ -#define uint8_t unsigned char -#define uint32_t unsigned int -#define int64_t long long -#define uint64_t unsigned long long diff --git a/body/pyproject.toml b/body/pyproject.toml deleted file mode 100644 index bac2d7f0811503c..000000000000000 --- a/body/pyproject.toml +++ /dev/null @@ -1,7 +0,0 @@ -# https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml -[tool.ruff] -select = ["E", "F", "W", "PIE", "C4", "ISC", "RUF100", "A"] -ignore = ["W292", "E741", "E402", "C408", "ISC003"] -line-length = 160 -target-version="py311" -flake8-implicit-str-concat.allow-multiline=false diff --git a/body/requirements.txt b/body/requirements.txt deleted file mode 100644 index 032580429517047..000000000000000 --- a/body/requirements.txt +++ /dev/null @@ -1,5 +0,0 @@ -cffi -scons -ruff -pre-commit -pycryptodome==3.9.8 diff --git a/cereal/README.md b/cereal/README.md index e3326aab0e98ca1..ad940facdceaa6a 100644 --- a/cereal/README.md +++ b/cereal/README.md @@ -1,11 +1,6 @@ -# What is cereal? [![cereal tests](https://github.com/commaai/cereal/workflows/tests/badge.svg?event=push)](https://github.com/commaai/cereal/actions) [![codecov](https://codecov.io/gh/commaai/cereal/branch/master/graph/badge.svg)](https://codecov.io/gh/commaai/cereal) +# What is cereal? -cereal is both a messaging spec for robotics systems as well as generic high performance IPC pub sub messaging with a single publisher and multiple subscribers. - -Imagine this use case: -* A sensor process reads gyro measurements directly from an IMU and publishes a `sensorEvents` packet -* A calibration process subscribes to the `sensorEvents` packet to use the IMU -* A localization process subscribes to the `sensorEvents` packet to use the IMU also +cereal is the messaging system for openpilot. It uses [msgq](https://github.com/commaai/msgq) as a pub/sub backend, and [Cap'n proto](https://capnproto.org/capnp-tool.html) for serialization of the structs. ## Messaging Spec @@ -32,11 +27,7 @@ Forks of [openpilot](https://github.com/commaai/openpilot) might want to add thi spec, however this could conflict with future changes made in mainline cereal/openpilot. Rebasing against mainline openpilot then means breaking backwards-compatibility with all old logs of your fork. So we added reserved events in [custom.capnp](custom.capnp) that we will leave empty in mainline cereal/openpilot. **If you only modify those, you can ensure your -fork will remain backwards-compatible with all versions of mainline cereal/openpilot and your fork.** - -## Pub Sub Backends - -cereal supports two backends, one based on [zmq](https://zeromq.org/) and another called [msgq](messaging/msgq.cc), a custom pub sub based on shared memory that doesn't require the bytes to pass through the kernel. +fork will remain backwards-compatible with all versions of mainline openpilot and your fork.** Example --- diff --git a/cereal/SConscript b/cereal/SConscript index be5f161dea03a41..a58a9490ce6488c 100644 --- a/cereal/SConscript +++ b/cereal/SConscript @@ -1,31 +1,20 @@ -Import('env', 'envCython', 'arch', 'common', 'msgq') - -import shutil +Import('env', 'common', 'msgq') cereal_dir = Dir('.') gen_dir = Dir('gen') -other_dir = Dir('#msgq') # Build cereal schema_files = ['log.capnp', 'car.capnp', 'legacy.capnp', 'custom.capnp'] -env.Command(["gen/c/include/c++.capnp.h"], [], "mkdir -p " + gen_dir.path + "/c/include && touch $TARGETS") env.Command([f'gen/cpp/{s}.c++' for s in schema_files] + [f'gen/cpp/{s}.h' for s in schema_files], schema_files, f"capnpc --src-prefix={cereal_dir.path} $SOURCES -o c++:{gen_dir.path}/cpp/") -# TODO: remove non shared cereal and messaging -cereal_objects = env.SharedObject([f'gen/cpp/{s}.c++' for s in schema_files]) - -cereal = env.Library('cereal', cereal_objects) -env.SharedLibrary('cereal_shared', cereal_objects) +cereal = env.Library('cereal', [f'gen/cpp/{s}.c++' for s in schema_files]) # Build messaging - services_h = env.Command(['services.h'], ['services.py'], 'python3 ' + cereal_dir.path + '/services.py > $TARGET') -env.Program('messaging/bridge', ['messaging/bridge.cc'], LIBS=[msgq, 'zmq', common]) - +env.Program('messaging/bridge', ['messaging/bridge.cc', 'messaging/msgq_to_zmq.cc'], LIBS=[msgq, common, 'pthread']) -socketmaster = env.SharedObject(['messaging/socketmaster.cc']) -socketmaster = env.Library('socketmaster', socketmaster) +socketmaster = env.Library('socketmaster', ['messaging/socketmaster.cc']) Export('cereal', 'socketmaster') diff --git a/cereal/car.capnp b/cereal/car.capnp deleted file mode 100644 index 8d76f0ead8de510..000000000000000 --- a/cereal/car.capnp +++ /dev/null @@ -1,706 +0,0 @@ -using Cxx = import "./include/c++.capnp"; -$Cxx.namespace("cereal"); - -@0x8e2af1e708af8b8d; - -# ******* events causing controls state machine transition ******* - -struct CarEvent @0x9b1657f34caf3ad3 { - name @0 :EventName; - - # event types - enable @1 :Bool; - noEntry @2 :Bool; - warning @3 :Bool; # alerts presented only when enabled or soft disabling - userDisable @4 :Bool; - softDisable @5 :Bool; - immediateDisable @6 :Bool; - preEnable @7 :Bool; - permanent @8 :Bool; # alerts presented regardless of openpilot state - overrideLateral @10 :Bool; - overrideLongitudinal @9 :Bool; - - enum EventName @0xbaa8c5d505f727de { - canError @0; - steerUnavailable @1; - wrongGear @4; - doorOpen @5; - seatbeltNotLatched @6; - espDisabled @7; - wrongCarMode @8; - steerTempUnavailable @9; - reverseGear @10; - buttonCancel @11; - buttonEnable @12; - pedalPressed @13; # exits active state - preEnableStandstill @73; # added during pre-enable state with brake - gasPressedOverride @108; # added when user is pressing gas with no disengage on gas - steerOverride @114; - cruiseDisabled @14; - speedTooLow @17; - outOfSpace @18; - overheat @19; - calibrationIncomplete @20; - calibrationInvalid @21; - calibrationRecalibrating @117; - controlsMismatch @22; - pcmEnable @23; - pcmDisable @24; - radarFault @26; - brakeHold @28; - parkBrake @29; - manualRestart @30; - lowSpeedLockout @31; - joystickDebug @34; - steerTempUnavailableSilent @35; - resumeRequired @36; - preDriverDistracted @37; - promptDriverDistracted @38; - driverDistracted @39; - preDriverUnresponsive @43; - promptDriverUnresponsive @44; - driverUnresponsive @45; - belowSteerSpeed @46; - lowBattery @48; - accFaulted @51; - sensorDataInvalid @52; - commIssue @53; - commIssueAvgFreq @109; - tooDistracted @54; - posenetInvalid @55; - soundsUnavailable @56; - preLaneChangeLeft @57; - preLaneChangeRight @58; - laneChange @59; - lowMemory @63; - stockAeb @64; - ldw @65; - carUnrecognized @66; - invalidLkasSetting @69; - speedTooHigh @70; - laneChangeBlocked @71; - relayMalfunction @72; - stockFcw @74; - startup @75; - startupNoCar @76; - startupNoControl @77; - startupMaster @78; - startupNoFw @104; - fcw @79; - steerSaturated @80; - belowEngageSpeed @84; - noGps @85; - wrongCruiseMode @87; - modeldLagging @89; - deviceFalling @90; - fanMalfunction @91; - cameraMalfunction @92; - cameraFrameRate @110; - processNotRunning @95; - dashcamMode @96; - controlsInitializing @98; - usbError @99; - roadCameraError @100; - driverCameraError @101; - wideRoadCameraError @102; - highCpuUsage @105; - cruiseMismatch @106; - lkasDisabled @107; - canBusMissing @111; - controlsdLagging @112; - resumeBlocked @113; - steerTimeLimit @115; - vehicleSensorsInvalid @116; - locationdTemporaryError @103; - locationdPermanentError @118; - paramsdTemporaryError @50; - paramsdPermanentError @119; - actuatorsApiUnavailable @120; - - radarCanErrorDEPRECATED @15; - communityFeatureDisallowedDEPRECATED @62; - radarCommIssueDEPRECATED @67; - driverMonitorLowAccDEPRECATED @68; - gasUnavailableDEPRECATED @3; - dataNeededDEPRECATED @16; - modelCommIssueDEPRECATED @27; - ipasOverrideDEPRECATED @33; - geofenceDEPRECATED @40; - driverMonitorOnDEPRECATED @41; - driverMonitorOffDEPRECATED @42; - calibrationProgressDEPRECATED @47; - invalidGiraffeHondaDEPRECATED @49; - invalidGiraffeToyotaDEPRECATED @60; - internetConnectivityNeededDEPRECATED @61; - whitePandaUnsupportedDEPRECATED @81; - commIssueWarningDEPRECATED @83; - focusRecoverActiveDEPRECATED @86; - neosUpdateRequiredDEPRECATED @88; - modelLagWarningDEPRECATED @93; - startupOneplusDEPRECATED @82; - startupFuzzyFingerprintDEPRECATED @97; - noTargetDEPRECATED @25; - brakeUnavailableDEPRECATED @2; - plannerErrorDEPRECATED @32; - gpsMalfunctionDEPRECATED @94; - } -} - -# ******* main car state @ 100hz ******* -# all speeds in m/s - -struct CarState { - events @13 :List(CarEvent); - - # CAN health - canValid @26 :Bool; # invalid counter/checksums - canTimeout @40 :Bool; # CAN bus dropped out - canErrorCounter @48 :UInt32; - - # car speed - vEgo @1 :Float32; # best estimate of speed - aEgo @16 :Float32; # best estimate of acceleration - vEgoRaw @17 :Float32; # unfiltered speed from CAN sensors - vEgoCluster @44 :Float32; # best estimate of speed shown on car's instrument cluster, used for UI - - yawRate @22 :Float32; # best estimate of yaw rate - standstill @18 :Bool; - wheelSpeeds @2 :WheelSpeeds; - - # gas pedal, 0.0-1.0 - gas @3 :Float32; # this is user pedal only - gasPressed @4 :Bool; # this is user pedal only - - engineRpm @46 :Float32; - - # brake pedal, 0.0-1.0 - brake @5 :Float32; # this is user pedal only - brakePressed @6 :Bool; # this is user pedal only - regenBraking @45 :Bool; # this is user pedal only - parkingBrake @39 :Bool; - brakeHoldActive @38 :Bool; - - # steering wheel - steeringAngleDeg @7 :Float32; - steeringAngleOffsetDeg @37 :Float32; # Offset betweens sensors in case there multiple - steeringRateDeg @15 :Float32; - steeringTorque @8 :Float32; # TODO: standardize units - steeringTorqueEps @27 :Float32; # TODO: standardize units - steeringPressed @9 :Bool; # if the user is using the steering wheel - steerFaultTemporary @35 :Bool; # temporary EPS fault - steerFaultPermanent @36 :Bool; # permanent EPS fault - stockAeb @30 :Bool; - stockFcw @31 :Bool; - espDisabled @32 :Bool; - accFaulted @42 :Bool; - carFaultedNonCritical @47 :Bool; # some ECU is faulted, but car remains controllable - - # cruise state - cruiseState @10 :CruiseState; - - # gear - gearShifter @14 :GearShifter; - - # button presses - buttonEvents @11 :List(ButtonEvent); - leftBlinker @20 :Bool; - rightBlinker @21 :Bool; - genericToggle @23 :Bool; - - # lock info - doorOpen @24 :Bool; - seatbeltUnlatched @25 :Bool; - - # clutch (manual transmission only) - clutchPressed @28 :Bool; - - # blindspot sensors - leftBlindspot @33 :Bool; # Is there something blocking the left lane change - rightBlindspot @34 :Bool; # Is there something blocking the right lane change - - fuelGauge @41 :Float32; # battery or fuel tank level from 0.0 to 1.0 - charging @43 :Bool; - - # process meta - cumLagMs @50 :Float32; - - struct WheelSpeeds { - # optional wheel speeds - fl @0 :Float32; - fr @1 :Float32; - rl @2 :Float32; - rr @3 :Float32; - } - - struct CruiseState { - enabled @0 :Bool; - speed @1 :Float32; - speedCluster @6 :Float32; # Set speed as shown on instrument cluster - available @2 :Bool; - speedOffset @3 :Float32; - standstill @4 :Bool; - nonAdaptive @5 :Bool; - } - - enum GearShifter { - unknown @0; - park @1; - drive @2; - neutral @3; - reverse @4; - sport @5; - low @6; - brake @7; - eco @8; - manumatic @9; - } - - # send on change - struct ButtonEvent { - pressed @0 :Bool; - type @1 :Type; - - enum Type { - unknown @0; - leftBlinker @1; - rightBlinker @2; - accelCruise @3; - decelCruise @4; - cancel @5; - altButton1 @6; - altButton2 @7; - altButton3 @8; - setCruise @9; - resumeCruise @10; - gapAdjustCruise @11; - } - } - - # deprecated - errorsDEPRECATED @0 :List(CarEvent.EventName); - brakeLightsDEPRECATED @19 :Bool; - steeringRateLimitedDEPRECATED @29 :Bool; - canMonoTimesDEPRECATED @12: List(UInt64); - canRcvTimeoutDEPRECATED @49 :Bool; -} - -# ******* radar state @ 20hz ******* - -struct RadarData @0x888ad6581cf0aacb { - errors @0 :List(Error); - points @1 :List(RadarPoint); - - enum Error { - canError @0; - fault @1; - wrongConfig @2; - } - - # similar to LiveTracks - # is one timestamp valid for all? I think so - struct RadarPoint { - trackId @0 :UInt64; # no trackId reuse - - # these 3 are the minimum required - dRel @1 :Float32; # m from the front bumper of the car - yRel @2 :Float32; # m - vRel @3 :Float32; # m/s - - # these are optional and valid if they are not NaN - aRel @4 :Float32; # m/s^2 - yvRel @5 :Float32; # m/s - - # some radars flag measurements VS estimates - measured @6 :Bool; - } - - # deprecated - canMonoTimesDEPRECATED @2 :List(UInt64); -} - -# ******* car controls @ 100hz ******* - -struct CarControl { - # must be true for any actuator commands to work - enabled @0 :Bool; - latActive @11: Bool; - longActive @12: Bool; - - # Actuator commands as computed by controlsd - actuators @6 :Actuators; - - # moved to CarOutput - actuatorsOutputDEPRECATED @10 :Actuators; - - leftBlinker @15: Bool; - rightBlinker @16: Bool; - - orientationNED @13 :List(Float32); - angularVelocity @14 :List(Float32); - - cruiseControl @4 :CruiseControl; - hudControl @5 :HUDControl; - - struct Actuators { - # range from 0.0 - 1.0 - gas @0: Float32; - brake @1: Float32; - # range from -1.0 - 1.0 - steer @2: Float32; - # value sent over can to the car - steerOutputCan @8: Float32; - steeringAngleDeg @3: Float32; - - curvature @7: Float32; - - speed @6: Float32; # m/s - accel @4: Float32; # m/s^2 - longControlState @5: LongControlState; - - enum LongControlState @0xe40f3a917d908282{ - off @0; - pid @1; - stopping @2; - starting @3; - } - } - - struct CruiseControl { - cancel @0: Bool; - resume @1: Bool; - override @4: Bool; - speedOverrideDEPRECATED @2: Float32; - accelOverrideDEPRECATED @3: Float32; - } - - struct HUDControl { - speedVisible @0: Bool; - setSpeed @1: Float32; - lanesVisible @2: Bool; - leadVisible @3: Bool; - visualAlert @4: VisualAlert; - audibleAlert @5: AudibleAlert; - rightLaneVisible @6: Bool; - leftLaneVisible @7: Bool; - rightLaneDepart @8: Bool; - leftLaneDepart @9: Bool; - leadDistanceBars @10: Int8; # 1-3: 1 is closest, 3 is farthest. some ports may utilize 2-4 bars instead - - enum VisualAlert { - # these are the choices from the Honda - # map as good as you can for your car - none @0; - fcw @1; - steerRequired @2; - brakePressed @3; - wrongGear @4; - seatbeltUnbuckled @5; - speedTooHigh @6; - ldw @7; - } - - enum AudibleAlert { - none @0; - - engage @1; - disengage @2; - refuse @3; - - warningSoft @4; - warningImmediate @5; - - prompt @6; - promptRepeat @7; - promptDistracted @8; - } - } - - gasDEPRECATED @1 :Float32; - brakeDEPRECATED @2 :Float32; - steeringTorqueDEPRECATED @3 :Float32; - activeDEPRECATED @7 :Bool; - rollDEPRECATED @8 :Float32; - pitchDEPRECATED @9 :Float32; -} - -struct CarOutput { - # Any car specific rate limits or quirks applied by - # the CarController are reflected in actuatorsOutput - # and matches what is sent to the car - actuatorsOutput @0 :CarControl.Actuators; -} - -# ****** car param ****** - -struct CarParams { - carName @0 :Text; - carFingerprint @1 :Text; - fuzzyFingerprint @55 :Bool; - - notCar @66 :Bool; # flag for non-car robotics platforms - - pcmCruise @3 :Bool; # is openpilot's state tied to the PCM's cruise state? - enableDsu @5 :Bool; # driving support unit - enableBsm @56 :Bool; # blind spot monitoring - flags @64 :UInt32; # flags for car specific quirks - experimentalLongitudinalAvailable @71 :Bool; - - minEnableSpeed @7 :Float32; - minSteerSpeed @8 :Float32; - safetyConfigs @62 :List(SafetyConfig); - alternativeExperience @65 :Int16; # panda flag for features like no disengage on gas - - # Car docs fields - maxLateralAccel @68 :Float32; - autoResumeSng @69 :Bool; # describes whether car can resume from a stop automatically - - # things about the car in the manual - mass @17 :Float32; # [kg] curb weight: all fluids no cargo - wheelbase @18 :Float32; # [m] distance from rear axle to front axle - centerToFront @19 :Float32; # [m] distance from center of mass to front axle - steerRatio @20 :Float32; # [] ratio of steering wheel angle to front wheel angle - steerRatioRear @21 :Float32; # [] ratio of steering wheel angle to rear wheel angle (usually 0) - - # things we can derive - rotationalInertia @22 :Float32; # [kg*m2] body rotational inertia - tireStiffnessFactor @72 :Float32; # scaling factor used in calculating tireStiffness[Front,Rear] - tireStiffnessFront @23 :Float32; # [N/rad] front tire coeff of stiff - tireStiffnessRear @24 :Float32; # [N/rad] rear tire coeff of stiff - - longitudinalTuning @25 :LongitudinalPIDTuning; - lateralParams @48 :LateralParams; - lateralTuning :union { - pid @26 :LateralPIDTuning; - indiDEPRECATED @27 :LateralINDITuning; - lqrDEPRECATED @40 :LateralLQRTuning; - torque @67 :LateralTorqueTuning; - } - - steerLimitAlert @28 :Bool; - steerLimitTimer @47 :Float32; # time before steerLimitAlert is issued - - vEgoStopping @29 :Float32; # Speed at which the car goes into stopping state - vEgoStarting @59 :Float32; # Speed at which the car goes into starting state - stoppingControl @31 :Bool; # Does the car allow full control even at lows speeds when stopping - steerControlType @34 :SteerControlType; - radarUnavailable @35 :Bool; # True when radar objects aren't visible on CAN or aren't parsed out - stopAccel @60 :Float32; # Required acceleration to keep vehicle stationary - stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop - startAccel @32 :Float32; # Required acceleration to get car moving - startingState @70 :Bool; # Does this car make use of special starting state - - steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds - longitudinalActuatorDelayLowerBound @61 :Float32; # Gas/Brake actuator delay in seconds, lower bound - longitudinalActuatorDelayUpperBound @58 :Float32; # Gas/Brake actuator delay in seconds, upper bound - 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); - - radarTimeStep @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard - fingerprintSource @49: FingerprintSource; - networkLocation @50 :NetworkLocation; # Where Panda/C2 is integrated into the car's CAN network - - wheelSpeedFactor @63 :Float32; # Multiplier on wheels speeds to computer actual speeds - - struct SafetyConfig { - safetyModel @0 :SafetyModel; - safetyParam @3 :UInt16; - safetyParamDEPRECATED @1 :Int16; - safetyParam2DEPRECATED @2 :UInt32; - } - - struct LateralParams { - torqueBP @0 :List(Int32); - torqueV @1 :List(Int32); - } - - struct LateralPIDTuning { - kpBP @0 :List(Float32); - kpV @1 :List(Float32); - kiBP @2 :List(Float32); - kiV @3 :List(Float32); - kf @4 :Float32; - } - - struct LateralTorqueTuning { - useSteeringAngle @0 :Bool; - kp @1 :Float32; - ki @2 :Float32; - friction @3 :Float32; - kf @4 :Float32; - steeringAngleDeadzoneDeg @5 :Float32; - latAccelFactor @6 :Float32; - latAccelOffset @7 :Float32; - } - - struct LongitudinalPIDTuning { - kpBP @0 :List(Float32); - kpV @1 :List(Float32); - kiBP @2 :List(Float32); - kiV @3 :List(Float32); - kf @6 :Float32; - deadzoneBP @4 :List(Float32); - deadzoneV @5 :List(Float32); - } - - struct LateralINDITuning { - outerLoopGainBP @4 :List(Float32); - outerLoopGainV @5 :List(Float32); - innerLoopGainBP @6 :List(Float32); - innerLoopGainV @7 :List(Float32); - timeConstantBP @8 :List(Float32); - timeConstantV @9 :List(Float32); - actuatorEffectivenessBP @10 :List(Float32); - actuatorEffectivenessV @11 :List(Float32); - - outerLoopGainDEPRECATED @0 :Float32; - innerLoopGainDEPRECATED @1 :Float32; - timeConstantDEPRECATED @2 :Float32; - actuatorEffectivenessDEPRECATED @3 :Float32; - } - - struct LateralLQRTuning { - scale @0 :Float32; - ki @1 :Float32; - dcGain @2 :Float32; - - # State space system - a @3 :List(Float32); - b @4 :List(Float32); - c @5 :List(Float32); - - k @6 :List(Float32); # LQR gain - l @7 :List(Float32); # Kalman gain - } - - enum SafetyModel { - silent @0; - hondaNidec @1; - toyota @2; - elm327 @3; - gm @4; - hondaBoschGiraffe @5; - ford @6; - cadillac @7; - hyundai @8; - chrysler @9; - tesla @10; - subaru @11; - gmPassive @12; - mazda @13; - nissan @14; - volkswagen @15; - toyotaIpas @16; - allOutput @17; - gmAscm @18; - noOutput @19; # like silent but without silent CAN TXs - hondaBosch @20; - volkswagenPq @21; - subaruPreglobal @22; # pre-Global platform - hyundaiLegacy @23; - hyundaiCommunity @24; - volkswagenMlb @25; - hongqi @26; - body @27; - hyundaiCanfd @28; - volkswagenMqbEvo @29; - chryslerCusw @30; - psa @31; - } - - enum SteerControlType { - torque @0; - angle @1; - - curvatureDEPRECATED @2; - } - - enum TransmissionType { - unknown @0; - automatic @1; # Traditional auto, including DSG - manual @2; # True "stick shift" only - direct @3; # Electric vehicle or other direct drive - cvt @4; - } - - struct CarFw { - ecu @0 :Ecu; - fwVersion @1 :Data; - address @2 :UInt32; - subAddress @3 :UInt8; - responseAddress @4 :UInt32; - request @5 :List(Data); - brand @6 :Text; - bus @7 :UInt8; - logging @8 :Bool; - obdMultiplexing @9 :Bool; - } - - enum Ecu { - eps @0; - abs @1; - fwdRadar @2; - fwdCamera @3; - engine @4; - unknown @5; - transmission @8; # Transmission Control Module - hybrid @18; # hybrid control unit, e.g. Chrysler's HCP, Honda's IMA Control Unit, Toyota's hybrid control computer - srs @9; # airbag - gateway @10; # can gateway - hud @11; # heads up display - combinationMeter @12; # instrument cluster - electricBrakeBooster @15; - shiftByWire @16; - adas @19; - cornerRadar @21; - hvac @20; - parkingAdas @7; # parking assist system ECU, e.g. Toyota's IPAS, Hyundai's RSPA, etc. - epb @22; # electronic parking brake - telematics @23; - body @24; # body control module - - # Toyota only - dsu @6; - - # Honda only - vsa @13; # Vehicle Stability Assist - programmedFuelInjection @14; - - debug @17; - } - - enum FingerprintSource { - can @0; - fw @1; - fixed @2; - } - - enum NetworkLocation { - fwdCamera @0; # Standard/default integration at LKAS camera - gateway @1; # Integration at vehicle's CAN gateway - } - - enableGasInterceptorDEPRECATED @2 :Bool; - enableCameraDEPRECATED @4 :Bool; - enableApgsDEPRECATED @6 :Bool; - steerRateCostDEPRECATED @33 :Float32; - isPandaBlackDEPRECATED @39 :Bool; - hasStockCameraDEPRECATED @57 :Bool; - safetyParamDEPRECATED @10 :Int16; - safetyModelDEPRECATED @9 :SafetyModel; - safetyModelPassiveDEPRECATED @42 :SafetyModel = silent; - minSpeedCanDEPRECATED @51 :Float32; - communityFeatureDEPRECATED @46: Bool; - startingAccelRateDEPRECATED @53 :Float32; - steerMaxBPDEPRECATED @11 :List(Float32); - steerMaxVDEPRECATED @12 :List(Float32); - gasMaxBPDEPRECATED @13 :List(Float32); - gasMaxVDEPRECATED @14 :List(Float32); - brakeMaxBPDEPRECATED @15 :List(Float32); - brakeMaxVDEPRECATED @16 :List(Float32); - directAccelControlDEPRECATED @30 :Bool; - maxSteeringAngleDegDEPRECATED @54 :Float32; -} diff --git a/cereal/car.capnp b/cereal/car.capnp new file mode 120000 index 000000000000000..4bc7f89b1fb5f25 --- /dev/null +++ b/cereal/car.capnp @@ -0,0 +1 @@ +../opendbc_repo/opendbc/car/car.capnp \ No newline at end of file diff --git a/cereal/log.capnp b/cereal/log.capnp index 36ca692dcc32c32..142d4afcb99988b 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -17,6 +17,119 @@ struct Map(Key, Value) { } } +struct OnroadEvent @0xc4fa6047f024e718 { + name @0 :EventName; + + # event types + enable @1 :Bool; + noEntry @2 :Bool; + warning @3 :Bool; # alerts presented only when enabled or soft disabling + userDisable @4 :Bool; + softDisable @5 :Bool; + immediateDisable @6 :Bool; + preEnable @7 :Bool; + permanent @8 :Bool; # alerts presented regardless of openpilot state + overrideLateral @10 :Bool; + overrideLongitudinal @9 :Bool; + + enum EventName @0x91f1992a1f77fb03 { + canError @0; + steerUnavailable @1; + wrongGear @2; + doorOpen @3; + seatbeltNotLatched @4; + espDisabled @5; + wrongCarMode @6; + steerTempUnavailable @7; + reverseGear @8; + buttonCancel @9; + buttonEnable @10; + pedalPressed @11; # exits active state + preEnableStandstill @12; # added during pre-enable state with brake + gasPressedOverride @13; # added when user is pressing gas with no disengage on gas + steerOverride @14; + cruiseDisabled @15; + speedTooLow @16; + outOfSpace @17; + overheat @18; + calibrationIncomplete @19; + calibrationInvalid @20; + calibrationRecalibrating @21; + controlsMismatch @22; + pcmEnable @23; + pcmDisable @24; + radarFault @25; + brakeHold @26; + parkBrake @27; + manualRestart @28; + joystickDebug @29; + longitudinalManeuver @30; + steerTempUnavailableSilent @31; + resumeRequired @32; + preDriverDistracted @33; + promptDriverDistracted @34; + driverDistracted @35; + preDriverUnresponsive @36; + promptDriverUnresponsive @37; + driverUnresponsive @38; + belowSteerSpeed @39; + lowBattery @40; + accFaulted @41; + sensorDataInvalid @42; + commIssue @43; + commIssueAvgFreq @44; + tooDistracted @45; + posenetInvalid @46; + preLaneChangeLeft @48; + preLaneChangeRight @49; + laneChange @50; + lowMemory @51; + stockAeb @52; + ldw @53; + carUnrecognized @54; + invalidLkasSetting @55; + speedTooHigh @56; + laneChangeBlocked @57; + relayMalfunction @58; + stockFcw @59; + startup @60; + startupNoCar @61; + startupNoControl @62; + startupNoSecOcKey @63; + startupMaster @64; + fcw @65; + steerSaturated @66; + belowEngageSpeed @67; + noGps @68; + wrongCruiseMode @69; + modeldLagging @70; + deviceFalling @71; + fanMalfunction @72; + cameraMalfunction @73; + cameraFrameRate @74; + processNotRunning @75; + dashcamMode @76; + selfdriveInitializing @77; + usbError @78; + cruiseMismatch @79; + canBusMissing @80; + selfdrivedLagging @81; + resumeBlocked @82; + steerTimeLimit @83; + vehicleSensorsInvalid @84; + locationdTemporaryError @85; + locationdPermanentError @86; + paramsdTemporaryError @87; + paramsdPermanentError @88; + actuatorsApiUnavailable @89; + espActive @90; + personalityChanged @91; + aeb @92; + + soundsUnavailableDEPRECATED @47; + } +} + enum LongitudinalPersonality { aggressive @0; standard @1; @@ -137,8 +250,6 @@ struct FrameData { requestId @28 :UInt32; encodeId @1 :UInt32; - frameType @7 :FrameType; - # Timestamps timestampEof @2 :UInt64; timestampSof @8 :UInt64; @@ -158,7 +269,7 @@ struct FrameData { temperaturesC @24 :List(Float32); - enum FrameType { + enum FrameTypeDEPRECATED { unknown @0; neo @1; chffrAndroid @2; @@ -175,6 +286,7 @@ struct FrameData { frameLengthDEPRECATED @3 :Int32; globalGainDEPRECATED @5 :Int32; + frameTypeDEPRECATED @7 :FrameTypeDEPRECATED; androidCaptureResultDEPRECATED @9 :AndroidCaptureResult; lensPosDEPRECATED @11 :Int32; lensSagDEPRECATED @12 :Float32; @@ -337,9 +449,9 @@ enum LaneChangeDirection { struct CanData { address @0 :UInt32; - busTime @1 :UInt16; dat @2 :Data; src @3 :UInt8; + busTimeDEPRECATED @1 :UInt16; } struct DeviceState @0xa4d8b5af2aa492eb { @@ -612,7 +724,6 @@ struct RadarState @0x9a185389d6fdd05f { leadOne @3 :LeadData; leadTwo @4 :LeadData; - cumLagMs @5 :Float32; struct LeadData { dRel @0 :Float32; @@ -642,6 +753,7 @@ struct RadarState @0x9a185389d6fdd05f { calCycleDEPRECATED @8 :Int32; calPercDEPRECATED @9 :Int8; canMonoTimesDEPRECATED @10 :List(UInt64); + cumLagMsDEPRECATED @5 :Float32; } struct LiveCalibrationData { @@ -672,7 +784,7 @@ struct LiveCalibrationData { } } -struct LiveTracks { +struct LiveTracksDEPRECATED { trackId @0 :Int32; dRel @1 :Float32; yRel @2 :Float32; @@ -685,45 +797,61 @@ struct LiveTracks { oncoming @9 :Bool; } +struct SelfdriveState { + # high level system state + state @0 :OpenpilotState; + enabled @1 :Bool; + active @2 :Bool; + engageable @9 :Bool; # can OP be engaged? + + # UI alerts + alertText1 @3 :Text; + alertText2 @4 :Text; + alertStatus @5 :AlertStatus; + alertSize @6 :AlertSize; + alertType @7 :Text; + alertSound @8 :Car.CarControl.HUDControl.AudibleAlert; + alertHudVisual @12 :Car.CarControl.HUDControl.VisualAlert; + + # configurable driving settings + experimentalMode @10 :Bool; + personality @11 :LongitudinalPersonality; + + enum OpenpilotState @0xdbe58b96d2d1ac61 { + disabled @0; + preEnabled @1; + enabled @2; + softDisabling @3; + overriding @4; # superset of overriding with steering or accelerator + } + + enum AlertStatus @0xa0d0dcd113193c62 { + normal @0; + userPrompt @1; + critical @2; + } + + enum AlertSize @0xe98bb99d6e985f64 { + none @0; + small @1; + mid @2; + full @3; + } +} + struct ControlsState @0x97ff69c53601abf1 { - startMonoTime @48 :UInt64; longitudinalPlanMonoTime @28 :UInt64; lateralPlanMonoTime @50 :UInt64; - state @31 :OpenpilotState; - enabled @19 :Bool; - active @36 :Bool; - - experimentalMode @64 :Bool; - personality @66 :LongitudinalPersonality; - longControlState @30 :Car.CarControl.Actuators.LongControlState; - vPid @2 :Float32; - vTargetLead @3 :Float32; - vCruise @22 :Float32; # actual set speed - vCruiseCluster @63 :Float32; # set speed to display in the UI upAccelCmd @4 :Float32; uiAccelCmd @5 :Float32; ufAccelCmd @33 :Float32; - aTarget @35 :Float32; curvature @37 :Float32; # path curvature from vehicle model desiredCurvature @61 :Float32; # lag adjusted curvatures used by lateral controllers forceDecel @51 :Bool; - # UI alerts - alertText1 @24 :Text; - alertText2 @25 :Text; - alertStatus @38 :AlertStatus; - alertSize @39 :AlertSize; - alertBlinkingRate @42 :Float32; - alertType @44 :Text; - alertSound @56 :Car.CarControl.HUDControl.AudibleAlert; - engageable @41 :Bool; # can OP be engaged? - - cumLagMs @15 :Float32; - lateralControlState :union { - indiState @52 :LateralINDIState; pidState @53 :LateralPIDState; angleState @58 :LateralAngleState; debugState @59 :LateralDebugState; @@ -731,27 +859,7 @@ struct ControlsState @0x97ff69c53601abf1 { curvatureStateDEPRECATED @65 :LateralCurvatureState; lqrStateDEPRECATED @55 :LateralLQRState; - } - - enum OpenpilotState @0xdbe58b96d2d1ac61 { - disabled @0; - preEnabled @1; - enabled @2; - softDisabling @3; - overriding @4; # superset of overriding with steering or accelerator - } - - enum AlertStatus { - normal @0; # low priority alert for user's convenience - userPrompt @1; # mid priority alert that might require user intervention - critical @2; # high priority alert that needs immediate user intervention - } - - enum AlertSize { - none @0; # don't display the alert - small @1; # small box - mid @2; # mid screen - full @3; # full screen + indiStateDEPRECATED @52 :LateralINDIState; } struct LateralINDIState { @@ -866,6 +974,58 @@ struct ControlsState @0x97ff69c53601abf1 { canMonoTimesDEPRECATED @21 :List(UInt64); desiredCurvatureRateDEPRECATED @62 :Float32; canErrorCounterDEPRECATED @57 :UInt32; + vPidDEPRECATED @2 :Float32; + alertBlinkingRateDEPRECATED @42 :Float32; + alertText1DEPRECATED @24 :Text; + alertText2DEPRECATED @25 :Text; + alertStatusDEPRECATED @38 :SelfdriveState.AlertStatus; + alertSizeDEPRECATED @39 :SelfdriveState.AlertSize; + alertTypeDEPRECATED @44 :Text; + alertSound2DEPRECATED @56 :Car.CarControl.HUDControl.AudibleAlert; + engageableDEPRECATED @41 :Bool; # can OP be engaged? + stateDEPRECATED @31 :SelfdriveState.OpenpilotState; + enabledDEPRECATED @19 :Bool; + activeDEPRECATED @36 :Bool; + experimentalModeDEPRECATED @64 :Bool; + personalityDEPRECATED @66 :LongitudinalPersonality; + vCruiseDEPRECATED @22 :Float32; # actual set speed + vCruiseClusterDEPRECATED @63 :Float32; # set speed to display in the UI + startMonoTimeDEPRECATED @48 :UInt64; + cumLagMsDEPRECATED @15 :Float32; + aTargetDEPRECATED @35 :Float32; + vTargetLeadDEPRECATED @3 :Float32; +} + +struct DrivingModelData { + frameId @0 :UInt32; + frameIdExtra @1 :UInt32; + frameDropPerc @6 :Float32; + modelExecutionTime @7 :Float32; + + action @2 :ModelDataV2.Action; + + laneLineMeta @3 :LaneLineMeta; + meta @4 :MetaData; + + path @5 :PolyPath; + + struct PolyPath { + xCoefficients @0 :List(Float32); + yCoefficients @1 :List(Float32); + zCoefficients @2 :List(Float32); + } + + struct LaneLineMeta { + leftY @0 :Float32; + rightY @1 :Float32; + leftProb @2 :Float32; + rightProb @3 :Float32; + } + + struct MetaData { + laneChangeState @0 :LaneChangeState; + laneChangeDirection @1 :LaneChangeDirection; + } } # All SI units and in device frame @@ -886,7 +1046,6 @@ struct ModelDataV2 { frameDropPerc @2 :Float32; timestampEof @3 :UInt64; modelExecutionTime @15 :Float32; - gpuExecutionTime @17 :Float32; rawPredictions @16 :Data; # predicted future position, orientation, etc.. @@ -913,12 +1072,13 @@ struct ModelDataV2 { # Model perceived motion temporalPose @21 :Pose; + # e2e lateral planner + action @26: Action; + + gpuExecutionTimeDEPRECATED @17 :Float32; navEnabledDEPRECATED @22 :Bool; locationMonoTimeDEPRECATED @24 :UInt64; - - # e2e lateral planner lateralPlannerSolutionDEPRECATED @25: LateralPlannerSolution; - action @26: Action; struct LeadDataV2 { prob @0 :Float32; # probability that car is your lead at time t @@ -980,6 +1140,8 @@ struct ModelDataV2 { brake3MetersPerSecondSquaredProbs @4 :List(Float32); brake4MetersPerSecondSquaredProbs @5 :List(Float32); brake5MetersPerSecondSquaredProbs @6 :List(Float32); + gasPressProbs @7 :List(Float32); + brakePressProbs @8 :List(Float32); } struct Pose { @@ -1049,6 +1211,14 @@ struct AndroidLogEntry { message @6 :Text; } +struct DriverAssistance { + # Lane Departure Warnings + leftLaneDeparture @0 :Bool; + rightLaneDeparture @1 :Bool; + + # FCW, AEB, etc. will go here +} + struct LongitudinalPlan @0xe00b5b3eba12876c { modelMonoTime @9 :UInt64; hasLead @7 :Bool; @@ -1060,6 +1230,11 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { accels @32 :List(Float32); speeds @33 :List(Float32); jerks @34 :List(Float32); + aTarget @18 :Float32; + shouldStop @37: Bool; + allowThrottle @38: Bool; + allowBrake @39: Bool; + solverExecutionTime @35 :Float32; @@ -1076,7 +1251,6 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { aCruiseDEPRECATED @17 :Float32; vTargetDEPRECATED @3 :Float32; vTargetFutureDEPRECATED @14 :Float32; - aTargetDEPRECATED @18 :Float32; vStartDEPRECATED @26 :Float32; aStartDEPRECATED @27 :Float32; vMaxDEPRECATED @20 :Float32; @@ -1096,7 +1270,7 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { radarValidDEPRECATED @28 :Bool; radarCanErrorDEPRECATED @30 :Bool; commIssueDEPRECATED @31 :Bool; - eventsDEPRECATED @13 :List(Car.CarEvent); + eventsDEPRECATED @13 :List(Car.OnroadEventDEPRECATED); gpsTrajectoryDEPRECATED @12 :GpsTrajectory; gpsPlannerActiveDEPRECATED @19 :Bool; personalityDEPRECATED @36 :LongitudinalPersonality; @@ -1217,6 +1391,46 @@ struct LiveLocationKalman { } } + +struct LivePose { + # More info on reference frames: + # https://github.com/commaai/openpilot/tree/master/common/transformations + orientationNED @0 :XYZMeasurement; + velocityDevice @1 :XYZMeasurement; + accelerationDevice @2 :XYZMeasurement; + angularVelocityDevice @3 :XYZMeasurement; + + inputsOK @4 :Bool = false; + posenetOK @5 :Bool = false; + sensorsOK @6 :Bool = false; + + debugFilterState @7 :FilterState; + + struct XYZMeasurement { + x @0 :Float32; + y @1 :Float32; + z @2 :Float32; + xStd @3 :Float32; + yStd @4 :Float32; + zStd @5 :Float32; + valid @6 :Bool; + } + + struct FilterState { + value @0 : List(Float64); + std @1 : List(Float64); + valid @2 : Bool; + + observations @3 :List(Observation); + + struct Observation { + kind @0 :Int32; + value @1 :List(Float32); + error @2 :List(Float32); + } + } +} + struct ProcLog { cpuTimes @0 :List(CPUTimes); mem @1 :Mem; @@ -1911,7 +2125,8 @@ struct Joystick { struct DriverStateV2 { frameId @0 :UInt32; modelExecutionTime @1 :Float32; - dspExecutionTime @2 :Float32; + dspExecutionTimeDEPRECATED @2 :Float32; + gpuExecutionTime @8 :Float32; rawPredictions @3 :Data; poorVisionProb @4 :Float32; @@ -1970,7 +2185,7 @@ struct DriverStateDEPRECATED @0xb83c6cc593ed0a00 { } struct DriverMonitoringState @0xb83cda094a1da284 { - events @0 :List(Car.CarEvent); + events @18 :List(OnroadEvent); faceDetected @1 :Bool; isDistracted @2 :Bool; distractedType @17 :UInt32; @@ -1989,6 +2204,7 @@ struct DriverMonitoringState @0xb83cda094a1da284 { isPreviewDEPRECATED @15 :Bool; rhdCheckedDEPRECATED @5 :Bool; + eventsDEPRECATED @0 :List(Car.OnroadEventDEPRECATED); } struct Boot { @@ -2016,9 +2232,15 @@ struct LiveParametersData { stiffnessFactorStd @12 :Float32; steerRatioStd @13 :Float32; roll @14 :Float32; - filterState @15 :LiveLocationKalman.Measurement; + debugFilterState @16 :FilterState; yawRateDEPRECATED @7 :Float32; + filterStateDEPRECATED @15 :LiveLocationKalman.Measurement; + + struct FilterState { + value @0 : List(Float64); + std @1 : List(Float64); + } } struct LiveTorqueParametersData { @@ -2198,6 +2420,11 @@ struct EncodeData { height @5 :UInt32; } +struct DebugAlert { + alertText1 @0 :Text; + alertText2 @1 :Text; +} + struct UserFlag { } @@ -2226,6 +2453,7 @@ struct Event { gpsNMEA @3 :GPSNMEAData; can @5 :List(CanData); controlsState @7 :ControlsState; + selfdriveState @130 :SelfdriveState; gyroscope @99 :SensorEventData; gyroscope2 @100 :SensorEventData; accelerometer @98 :SensorEventData; @@ -2237,14 +2465,14 @@ struct Event { pandaStates @81 :List(PandaState); peripheralState @80 :PeripheralState; radarState @13 :RadarState; - liveTracks @16 :List(LiveTracks); + liveTracks @131 :Car.RadarData; sendcan @17 :List(CanData); liveCalibration @19 :LiveCalibrationData; carState @22 :Car.CarState; carControl @23 :Car.CarControl; carOutput @127 :Car.CarOutput; longitudinalPlan @24 :LongitudinalPlan; - uiPlan @106 :UiPlan; + driverAssistance @132 :DriverAssistance; ubloxGnss @34 :UbloxGnss; ubloxRaw @39 :Data; qcomGnss @31 :QcomGnss; @@ -2255,11 +2483,12 @@ struct Event { liveTorqueParameters @94 :LiveTorqueParametersData; cameraOdometry @63 :CameraOdometry; thumbnail @66: Thumbnail; - onroadEvents @68: List(Car.CarEvent); + onroadEvents @134: List(OnroadEvent); carParams @69: Car.CarParams; driverMonitoringState @71: DriverMonitoringState; - liveLocationKalman @72 :LiveLocationKalman; + livePose @129 :LivePose; modelV2 @75 :ModelDataV2; + drivingModelData @128 :DrivingModelData; driverStateV2 @92 :DriverStateV2; # camera stuff, each camera state has a matching encode idx @@ -2304,6 +2533,7 @@ struct Event { driverEncodeData @87 :EncodeData; wideRoadEncodeData @88 :EncodeData; qRoadEncodeData @89 :EncodeData; + alertDebug @133 :DebugAlert; livestreamRoadEncodeData @120 :EncodeData; livestreamWideRoadEncodeData @121 :EncodeData; @@ -2329,7 +2559,7 @@ struct Event { model @9 :Legacy.ModelData; # TODO: rename modelV2 and mark this as deprecated liveMpcDEPRECATED @36 :LiveMpcData; liveLongitudinalMpcDEPRECATED @37 :LiveLongitudinalMpcData; - liveLocationKalmanDEPRECATED @51 :Legacy.LiveLocationData; + liveLocationKalmanLegacyDEPRECATED @51 :Legacy.LiveLocationData; orbslamCorrectionDEPRECATED @45 :Legacy.OrbslamCorrection; liveUIDEPRECATED @14 :Legacy.LiveUI; sensorEventDEPRECATED @4 :SensorEventData; @@ -2365,5 +2595,9 @@ struct Event { sensorEventsDEPRECATED @11 :List(SensorEventData); lateralPlanDEPRECATED @64 :LateralPlan; navModelDEPRECATED @104 :NavModelData; + uiPlanDEPRECATED @106 :UiPlan; + liveLocationKalmanDEPRECATED @72 :LiveLocationKalman; + liveTracksDEPRECATED @16 :List(LiveTracksDEPRECATED); + onroadEventsDEPRECATED @68: List(Car.OnroadEventDEPRECATED); } } diff --git a/cereal/messaging/.gitignore b/cereal/messaging/.gitignore deleted file mode 100644 index dbbe8e22aee4889..000000000000000 --- a/cereal/messaging/.gitignore +++ /dev/null @@ -1,10 +0,0 @@ -demo -bridge -test_runner -*.o -*.os -*.d -*.a -*.so -messaging_pyx.cpp -build/ diff --git a/cereal/messaging/__init__.py b/cereal/messaging/__init__.py index 4ba55cf7b9432fc..2466f6e9c02f715 100644 --- a/cereal/messaging/__init__.py +++ b/cereal/messaging/__init__.py @@ -2,7 +2,8 @@ from msgq.ipc_pyx import Context, Poller, SubSocket, PubSocket, SocketEventHandle, toggle_fake_events, \ set_fake_prefix, get_fake_prefix, delete_fake_prefix, wait_for_one_event from msgq.ipc_pyx import MultiplePublishersError, IpcError -from msgq import fake_event_handle, pub_sock, sub_sock, drain_sock_raw, context +from msgq import fake_event_handle, pub_sock, sub_sock, drain_sock_raw +import msgq import os import capnp @@ -17,8 +18,12 @@ NO_TRAVERSAL_LIMIT = 2**64-1 -def log_from_bytes(dat: bytes) -> capnp.lib.capnp._DynamicStructReader: - with log.Event.from_bytes(dat, traversal_limit_in_words=NO_TRAVERSAL_LIMIT) as msg: +def reset_context(): + msgq.context = Context() + + +def log_from_bytes(dat: bytes, struct: capnp.lib.capnp._StructModule = log.Event) -> capnp.lib.capnp._DynamicStructReader: + with struct.from_bytes(dat, traversal_limit_in_words=NO_TRAVERSAL_LIMIT) as msg: return msg @@ -87,26 +92,76 @@ def recv_one_retry(sock: SubSocket) -> capnp.lib.capnp._DynamicStructReader: return log_from_bytes(dat) +class FrequencyTracker: + def __init__(self, service_freq: float, update_freq: float, is_poll: bool): + freq = max(min(service_freq, update_freq), 1.) + if is_poll: + min_freq = max_freq = freq + else: + max_freq = min(freq, update_freq) + if service_freq >= 2 * update_freq: + min_freq = update_freq + elif update_freq >= 2* service_freq: + min_freq = freq + else: + min_freq = min(freq, freq / 2.) + + self.min_freq = min_freq * 0.8 + self.max_freq = max_freq * 1.2 + self.recv_dts: Deque[float] = deque(maxlen=int(10 * freq)) + self.recv_dts_sum = 0.0 + self.recent_recv_dts: Deque[float] = deque(maxlen=int(freq)) + self.recent_recv_dts_sum = 0.0 + self.prev_time = 0.0 + + def record_recv_time(self, cur_time: float) -> None: + # TODO: Handle case where cur_time is less than prev_time + if self.prev_time > 1e-5: + dt = cur_time - self.prev_time + + if len(self.recv_dts) == self.recv_dts.maxlen: + self.recv_dts_sum -= self.recv_dts[0] + self.recv_dts.append(dt) + self.recv_dts_sum += dt + + if len(self.recent_recv_dts) == self.recent_recv_dts.maxlen: + self.recent_recv_dts_sum -= self.recent_recv_dts[0] + self.recent_recv_dts.append(dt) + self.recent_recv_dts_sum += dt + + self.prev_time = cur_time + + @property + def valid(self) -> bool: + if not self.recv_dts: + return False + + avg_freq = len(self.recv_dts) / self.recv_dts_sum + if self.min_freq <= avg_freq <= self.max_freq: + return True + + avg_freq_recent = len(self.recent_recv_dts) / self.recent_recv_dts_sum + return self.min_freq <= avg_freq_recent <= self.max_freq + + class SubMaster: def __init__(self, services: List[str], poll: Optional[str] = None, ignore_alive: Optional[List[str]] = None, ignore_avg_freq: Optional[List[str]] = None, ignore_valid: Optional[List[str]] = None, addr: str = "127.0.0.1", frequency: Optional[float] = None): self.frame = -1 + self.services = services self.seen = {s: False for s in services} self.updated = {s: False 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]] = {} self.sock = {} self.data = {} self.valid = {} self.logMonoTime = {} - self.max_freq = {} - self.min_freq = {} - + self.freq_tracker: Dict[str, FrequencyTracker] = {} self.poller = Poller() polled_services = set([poll, ] if poll is not None else services) self.non_polled_services = set(services) - polled_services @@ -132,23 +187,8 @@ def __init__(self, services: List[str], poll: Optional[str] = None, self.data[s] = getattr(data.as_reader(), s) self.logMonoTime[s] = 0 - 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)) + self.valid[s] = False + self.freq_tracker[s] = FrequencyTracker(SERVICE_LIST[s].frequency, self.update_freq, s == poll) def __getitem__(self, s: str) -> capnp.lib.capnp._DynamicStructReader: return self.data[s] @@ -168,7 +208,7 @@ def update(self, timeout: int = 100) -> None: def update_msgs(self, cur_time: float, msgs: List[capnp.lib.capnp._DynamicStructReader]) -> None: self.frame += 1 - self.updated = dict.fromkeys(self.updated, False) + self.updated = dict.fromkeys(self.services, False) for msg in msgs: if msg is None: continue @@ -177,54 +217,30 @@ def update_msgs(self, cur_time: float, msgs: List[capnp.lib.capnp._DynamicStruct self.seen[s] = True self.updated[s] = True - if self.recv_time[s] > 1e-5: - self.recv_dts[s].append(cur_time - self.recv_time[s]) + self.freq_tracker[s].record_recv_time(cur_time) 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 - for s in self.data: + for s in self.services: if SERVICE_LIST[s].frequency > 1e-5 and not self.simulation: # 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 + self.freq_ok[s] = self.freq_tracker[s].valid else: self.freq_ok[s] = True - if self.simulation: - self.alive[s] = self.seen[s] # alive is defined as seen when simulation flag set - else: - self.alive[s] = True + self.alive[s] = self.seen[s] if self.simulation else True 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) + return all(self.alive[s] for s in (service_list or self.services) if s not in self.ignore_alive) 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)) + return all(self.freq_ok[s] for s in (service_list or self.services) 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) + return all(self.valid[s] for s in (service_list or self.services) 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) diff --git a/cereal/messaging/bridge.cc b/cereal/messaging/bridge.cc index 8619c1e22640bb5..93af988358df85b 100644 --- a/cereal/messaging/bridge.cc +++ b/cereal/messaging/bridge.cc @@ -1,25 +1,10 @@ -#include #include -#include -#include -#include -#include - -typedef void (*sighandler_t)(int sig); +#include "cereal/messaging/msgq_to_zmq.h" #include "cereal/services.h" -#include "msgq/impl_msgq.h" -#include "msgq/impl_zmq.h" +#include "common/util.h" -std::atomic do_exit = false; -static void set_do_exit(int sig) { - do_exit = true; -} - -void sigpipe_handler(int sig) { - assert(sig == SIGPIPE); - std::cout << "SIGPIPE received" << std::endl; -} +ExitHandler do_exit; static std::vector get_services(std::string whitelist_str, bool zmq_to_msgq) { std::vector service_list; @@ -34,41 +19,22 @@ static std::vector get_services(std::string whitelist_str, bool zmq return service_list; } -int main(int argc, char** argv) { - signal(SIGPIPE, (sighandler_t)sigpipe_handler); - signal(SIGINT, (sighandler_t)set_do_exit); - signal(SIGTERM, (sighandler_t)set_do_exit); - - bool zmq_to_msgq = argc > 2; - std::string ip = zmq_to_msgq ? argv[1] : "127.0.0.1"; - std::string whitelist_str = zmq_to_msgq ? std::string(argv[2]) : ""; +void msgq_to_zmq(const std::vector &endpoints, const std::string &ip) { + MsgqToZmq bridge; + bridge.run(endpoints, ip); +} - Poller *poller; - Context *pub_context; - Context *sub_context; - if (zmq_to_msgq) { // republishes zmq debugging messages as msgq - poller = new ZMQPoller(); - pub_context = new MSGQContext(); - sub_context = new ZMQContext(); - } else { - poller = new MSGQPoller(); - pub_context = new ZMQContext(); - sub_context = new MSGQContext(); - } +void zmq_to_msgq(const std::vector &endpoints, const std::string &ip) { + auto poller = std::make_unique(); + auto pub_context = std::make_unique(); + auto sub_context = std::make_unique(); + std::map sub2pub; - std::map sub2pub; - for (auto endpoint : get_services(whitelist_str, zmq_to_msgq)) { - PubSocket * pub_sock; - SubSocket * sub_sock; - if (zmq_to_msgq) { - pub_sock = new MSGQPubSocket(); - sub_sock = new ZMQSubSocket(); - } else { - pub_sock = new ZMQPubSocket(); - sub_sock = new MSGQSubSocket(); - } - pub_sock->connect(pub_context, endpoint); - sub_sock->connect(sub_context, endpoint, ip, false); + for (auto endpoint : endpoints) { + auto pub_sock = new MSGQPubSocket(); + auto sub_sock = new ZMQSubSocket(); + pub_sock->connect(pub_context.get(), endpoint); + sub_sock->connect(sub_context.get(), endpoint, ip, false); poller->registerSocket(sub_sock); sub2pub[sub_sock] = pub_sock; @@ -76,17 +42,30 @@ int main(int argc, char** argv) { while (!do_exit) { for (auto sub_sock : poller->poll(100)) { - Message * msg = sub_sock->receive(); - if (msg == NULL) continue; - int ret; - do { - ret = sub2pub[sub_sock]->sendMessage(msg); - } while (ret == -1 && errno == EINTR && !do_exit); - assert(ret >= 0 || do_exit); - delete msg; - - if (do_exit) break; + std::unique_ptr msg(sub_sock->receive(true)); + if (msg) { + sub2pub[sub_sock]->sendMessage(msg.get()); + } } } + + // Clean up allocated sockets + for (auto &[sub_sock, pub_sock] : sub2pub) { + delete sub_sock; + delete pub_sock; + } +} + +int main(int argc, char **argv) { + bool is_zmq_to_msgq = argc > 2; + std::string ip = is_zmq_to_msgq ? argv[1] : "127.0.0.1"; + std::string whitelist_str = is_zmq_to_msgq ? std::string(argv[2]) : ""; + std::vector endpoints = get_services(whitelist_str, is_zmq_to_msgq); + + if (is_zmq_to_msgq) { + zmq_to_msgq(endpoints, ip); + } else { + msgq_to_zmq(endpoints, ip); + } return 0; } diff --git a/cereal/messaging/messaging.h b/cereal/messaging/messaging.h index f3850130e655e2c..fb9c261f2b57ea1 100644 --- a/cereal/messaging/messaging.h +++ b/cereal/messaging/messaging.h @@ -5,20 +5,13 @@ #include #include #include -#include #include #include "cereal/gen/cpp/log.capnp.h" +#include "common/timing.h" #include "msgq/ipc.h" -#ifdef __APPLE__ -#define CLOCK_BOOTTIME CLOCK_MONOTONIC -#endif - -#define MSG_MULTIPLE_PUBLISHERS 100 - - class SubMaster { public: SubMaster(const std::vector &service_list, const std::vector &poll = {}, @@ -53,10 +46,7 @@ class MessageBuilder : public capnp::MallocMessageBuilder { cereal::Event::Builder initEvent(bool valid = true) { cereal::Event::Builder event = initRoot(); - struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); - uint64_t current_time = t.tv_sec * 1000000000ULL + t.tv_nsec; - event.setLogMonoTime(current_time); + event.setLogMonoTime(nanos_since_boot()); event.setValid(valid); return event; } diff --git a/cereal/messaging/msgq_to_zmq.cc b/cereal/messaging/msgq_to_zmq.cc new file mode 100644 index 000000000000000..ce626f2aad36308 --- /dev/null +++ b/cereal/messaging/msgq_to_zmq.cc @@ -0,0 +1,144 @@ +#include "cereal/messaging/msgq_to_zmq.h" + +#include + +#include "common/util.h" + +extern ExitHandler do_exit; + +// Max messages to process per socket per poll +constexpr int MAX_MESSAGES_PER_SOCKET = 50; + +static std::string recv_zmq_msg(void *sock) { + zmq_msg_t msg; + zmq_msg_init(&msg); + std::string ret; + if (zmq_msg_recv(&msg, sock, 0) > 0) { + ret.assign((char *)zmq_msg_data(&msg), zmq_msg_size(&msg)); + } + zmq_msg_close(&msg); + return ret; +} + +void MsgqToZmq::run(const std::vector &endpoints, const std::string &ip) { + zmq_context = std::make_unique(); + msgq_context = std::make_unique(); + + // Create ZMQPubSockets for each endpoint + for (const auto &endpoint : endpoints) { + auto &socket_pair = socket_pairs.emplace_back(); + socket_pair.endpoint = endpoint; + socket_pair.pub_sock = std::make_unique(); + int ret = socket_pair.pub_sock->connect(zmq_context.get(), endpoint); + if (ret != 0) { + printf("Failed to create ZMQ publisher for [%s]: %s\n", endpoint.c_str(), zmq_strerror(zmq_errno())); + return; + } + } + + // Start ZMQ monitoring thread to monitor socket events + std::thread thread(&MsgqToZmq::zmqMonitorThread, this); + + // Main loop for processing messages + while (!do_exit) { + { + std::unique_lock lk(mutex); + cv.wait(lk, [this]() { return do_exit || !sub2pub.empty(); }); + if (do_exit) break; + + for (auto sub_sock : msgq_poller->poll(100)) { + // Process messages for each socket + ZMQPubSocket *pub_sock = sub2pub.at(sub_sock); + for (int i = 0; i < MAX_MESSAGES_PER_SOCKET; ++i) { + auto msg = std::unique_ptr(sub_sock->receive(true)); + if (!msg) break; + + while (pub_sock->sendMessage(msg.get()) == -1) { + if (errno != EINTR) break; + } + } + } + } + util::sleep_for(1); // Give zmqMonitorThread a chance to acquire the mutex + } + + thread.join(); +} + +void MsgqToZmq::zmqMonitorThread() { + std::vector pollitems; + + // Set up ZMQ monitor for each pub socket + for (int i = 0; i < socket_pairs.size(); ++i) { + std::string addr = "inproc://op-bridge-monitor-" + std::to_string(i); + zmq_socket_monitor(socket_pairs[i].pub_sock->sock, addr.c_str(), ZMQ_EVENT_ACCEPTED | ZMQ_EVENT_DISCONNECTED); + + void *monitor_socket = zmq_socket(zmq_context->getRawContext(), ZMQ_PAIR); + zmq_connect(monitor_socket, addr.c_str()); + pollitems.emplace_back(zmq_pollitem_t{.socket = monitor_socket, .events = ZMQ_POLLIN}); + } + + while (!do_exit) { + int ret = zmq_poll(pollitems.data(), pollitems.size(), 1000); + if (ret < 0) { + if (errno == EINTR) { + // Due to frequent EINTR signals from msgq, introduce a brief delay (200 ms) + // to reduce CPU usage during retry attempts. + util::sleep_for(200); + } + continue; + } + + for (int i = 0; i < pollitems.size(); ++i) { + if (pollitems[i].revents & ZMQ_POLLIN) { + // First frame in message contains event number and value + std::string frame = recv_zmq_msg(pollitems[i].socket); + if (frame.empty()) continue; + + uint16_t event_type = *(uint16_t *)(frame.data()); + + // Second frame in message contains event address + frame = recv_zmq_msg(pollitems[i].socket); + if (frame.empty()) continue; + + std::unique_lock lk(mutex); + auto &pair = socket_pairs[i]; + if (event_type & ZMQ_EVENT_ACCEPTED) { + printf("socket [%s] connected\n", pair.endpoint.c_str()); + if (++pair.connected_clients == 1) { + // Create new MSGQ subscriber socket and map to ZMQ publisher + pair.sub_sock = std::make_unique(); + pair.sub_sock->connect(msgq_context.get(), pair.endpoint, "127.0.0.1"); + sub2pub[pair.sub_sock.get()] = pair.pub_sock.get(); + registerSockets(); + } + } else if (event_type & ZMQ_EVENT_DISCONNECTED) { + printf("socket [%s] disconnected\n", pair.endpoint.c_str()); + if (pair.connected_clients == 0 || --pair.connected_clients == 0) { + // Remove MSGQ subscriber socket from mapping and reset it + sub2pub.erase(pair.sub_sock.get()); + pair.sub_sock.reset(nullptr); + registerSockets(); + } + } + cv.notify_one(); + } + } + } + + // Clean up monitor sockets + for (int i = 0; i < pollitems.size(); ++i) { + zmq_socket_monitor(socket_pairs[i].pub_sock->sock, nullptr, 0); + zmq_close(pollitems[i].socket); + } + cv.notify_one(); +} + +void MsgqToZmq::registerSockets() { + msgq_poller = std::make_unique(); + for (const auto &socket_pair : socket_pairs) { + if (socket_pair.sub_sock) { + msgq_poller->registerSocket(socket_pair.sub_sock.get()); + } + } +} diff --git a/cereal/messaging/msgq_to_zmq.h b/cereal/messaging/msgq_to_zmq.h new file mode 100644 index 000000000000000..ebdbe5df690e986 --- /dev/null +++ b/cereal/messaging/msgq_to_zmq.h @@ -0,0 +1,37 @@ +#pragma once + +#include +#include +#include +#include +#include +#include + +#define private public +#include "msgq/impl_msgq.h" +#include "msgq/impl_zmq.h" + +class MsgqToZmq { +public: + MsgqToZmq() {} + void run(const std::vector &endpoints, const std::string &ip); + +protected: + void registerSockets(); + void zmqMonitorThread(); + + struct SocketPair { + std::string endpoint; + std::unique_ptr pub_sock; + std::unique_ptr sub_sock; + int connected_clients = 0; + }; + + std::unique_ptr msgq_context; + std::unique_ptr zmq_context; + std::mutex mutex; + std::condition_variable cv; + std::unique_ptr msgq_poller; + std::map sub2pub; + std::vector socket_pairs; +}; diff --git a/cereal/messaging/socketmaster.cc b/cereal/messaging/socketmaster.cc index cd697b1f51ed202..1a7a48980e7b247 100644 --- a/cereal/messaging/socketmaster.cc +++ b/cereal/messaging/socketmaster.cc @@ -1,4 +1,3 @@ -#include #include #include #include @@ -7,15 +6,8 @@ #include "cereal/services.h" #include "cereal/messaging/messaging.h" - const bool SIMULATION = (getenv("SIMULATION") != nullptr) && (std::string(getenv("SIMULATION")) == "1"); -static inline uint64_t nanos_since_boot() { - struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); - return t.tv_sec * 1000000000ULL + t.tv_nsec; -} - static inline bool inList(const std::vector &list, const char *value) { for (auto &v : list) { if (strcmp(value, v) == 0) return true; @@ -42,7 +34,7 @@ struct SubMaster::SubMessage { std::string name; SubSocket *socket = nullptr; int freq = 0; - bool updated = false, alive = false, valid = true, ignore_alive; + bool updated = false, alive = false, valid = false, ignore_alive; uint64_t rcv_time = 0, rcv_frame = 0; void *allocated_msg_reader = nullptr; bool is_polled = false; diff --git a/cereal/services.py b/cereal/services.py index 2ab28f6d523ba34..771338f50780e12 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -16,14 +16,15 @@ def __init__(self, should_log: bool, frequency: float, decimation: Optional[int] "gyroscope2": (True, 100., 100), "accelerometer": (True, 104., 104), "accelerometer2": (True, 100., 100), - "magnetometer": (True, 25., 25), + "magnetometer": (True, 25.), "lightSensor": (True, 100., 100), "temperatureSensor": (True, 2., 200), "temperatureSensor2": (True, 2., 200), "gpsNMEA": (True, 9.), "deviceState": (True, 2., 1), - "can": (True, 100., 1223), # decimation gives ~5 msgs in a full segment + "can": (True, 100., 2053), # decimation gives ~3 msgs in a full segment "controlsState": (True, 100., 10), + "selfdriveState": (True, 100., 10), "pandaStates": (True, 10., 1), "peripheralState": (True, 2., 1), "radarState": (True, 20., 5), @@ -38,7 +39,8 @@ def __init__(self, should_log: bool, frequency: float, decimation: Optional[int] "carState": (True, 100., 10), "carControl": (True, 100., 10), "carOutput": (True, 100., 10), - "longitudinalPlan": (True, 20., 5), + "longitudinalPlan": (True, 20., 10), + "driverAssistance": (True, 20., 20), "procLog": (True, 0.5, 15), "gpsLocationExternal": (True, 10., 10), "gpsLocation": (True, 1., 1), @@ -47,9 +49,9 @@ def __init__(self, should_log: bool, frequency: float, decimation: Optional[int] "gnssMeasurements": (True, 10., 10), "clocks": (True, 0.1, 1), "ubloxRaw": (True, 20.), - "liveLocationKalman": (True, 20., 5), + "livePose": (True, 20., 4), "liveParameters": (True, 20., 5), - "cameraOdometry": (True, 20., 5), + "cameraOdometry": (True, 20., 10), "thumbnail": (True, 0.2, 1), "onroadEvents": (True, 1., 1), "carParams": (True, 0.02, 1), @@ -60,13 +62,13 @@ def __init__(self, should_log: bool, frequency: float, decimation: Optional[int] "driverMonitoringState": (True, 20., 10), "wideRoadEncodeIdx": (False, 20., 1), "wideRoadCameraState": (True, 20., 20), - "modelV2": (True, 20., 40), + "drivingModelData": (True, 20., 10), + "modelV2": (True, 20.), "managerState": (True, 2., 1), "uploaderState": (True, 0., 1), "navInstruction": (True, 1., 10), "navRoute": (True, 0.), "navThumbnail": (True, 0.), - "uiPlan": (True, 20., 40.), "qRoadEncodeIdx": (False, 20.), "userFlag": (True, 0., 1), "microphone": (True, 10., 10), @@ -74,6 +76,7 @@ def __init__(self, should_log: bool, frequency: float, decimation: Optional[int] # debug "uiDebug": (True, 0., 1), "testJoystick": (True, 0.), + "alertDebug": (True, 20., 5), "roadEncodeData": (False, 20.), "driverEncodeData": (False, 20.), "wideRoadEncodeData": (False, 20.), diff --git a/common/api/__init__.py b/common/api/__init__.py index f3a7d83842a5d49..ac231400a47cc79 100644 --- a/common/api/__init__.py +++ b/common/api/__init__.py @@ -1,7 +1,7 @@ import jwt import os import requests -from datetime import datetime, timedelta +from datetime import datetime, timedelta, UTC from openpilot.system.hardware.hw import Paths from openpilot.system.version import get_version @@ -23,7 +23,7 @@ def request(self, method, endpoint, timeout=None, access_token=None, **params): return api_get(endpoint, method=method, timeout=timeout, access_token=access_token, **params) def get_token(self, expiry_hours=1): - now = datetime.utcnow() + now = datetime.now(UTC).replace(tzinfo=None) payload = { 'identity': self.dongle_id, 'nbf': now, diff --git a/common/gps.py b/common/gps.py new file mode 100644 index 000000000000000..6f96d72e99aa959 --- /dev/null +++ b/common/gps.py @@ -0,0 +1,8 @@ +from openpilot.common.params import Params + + +def get_gps_location_service(params: Params) -> str: + if params.get_bool("UbloxAvailable"): + return "gpsLocationExternal" + else: + return "gpsLocation" diff --git a/common/mock/__init__.py b/common/mock/__init__.py index 8c86bbd394caee6..4b01dfe8411b11a 100644 --- a/common/mock/__init__.py +++ b/common/mock/__init__.py @@ -8,12 +8,12 @@ import threading from cereal.messaging import PubMaster from cereal.services import SERVICE_LIST -from openpilot.common.mock.generators import generate_liveLocationKalman +from openpilot.common.mock.generators import generate_livePose from openpilot.common.realtime import Ratekeeper MOCK_GENERATOR = { - "liveLocationKalman": generate_liveLocationKalman + "livePose": generate_livePose } diff --git a/common/mock/generators.py b/common/mock/generators.py index 40951faf8543bf8..5cd9c88a56fc330 100644 --- a/common/mock/generators.py +++ b/common/mock/generators.py @@ -1,20 +1,14 @@ from cereal import messaging -LOCATION1 = (32.7174, -117.16277) -LOCATION2 = (32.7558, -117.2037) - -LLK_DECIMATION = 10 -RENDER_FRAMES = 15 -DEFAULT_ITERATIONS = RENDER_FRAMES * LLK_DECIMATION - - -def generate_liveLocationKalman(location=LOCATION1): - msg = messaging.new_message('liveLocationKalman') - msg.liveLocationKalman.positionGeodetic = {'value': [*location, 0], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.positionECEF = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.calibratedOrientationNED = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.velocityCalibrated = {'value': [0., 0., 0.], 'std': [0., 0., 0.], 'valid': True} - msg.liveLocationKalman.status = 'valid' - msg.liveLocationKalman.gpsOK = True +def generate_livePose(): + msg = messaging.new_message('livePose') + meas = {'x': 0.0, 'y': 0.0, 'z': 0.0, 'xStd': 0.0, 'yStd': 0.0, 'zStd': 0.0, 'valid': True} + msg.livePose.orientationNED = meas + msg.livePose.velocityDevice = meas + msg.livePose.angularVelocityDevice = meas + msg.livePose.accelerationDevice = meas + msg.livePose.inputsOK = True + msg.livePose.posenetOK = True + msg.livePose.sensorsOK = True return msg diff --git a/common/params.cc b/common/params.cc index 2330160173ffb63..9e62ed582caba72 100644 --- a/common/params.cc +++ b/common/params.cc @@ -24,8 +24,8 @@ int fsync_dir(const std::string &path) { int result = -1; int fd = HANDLE_EINTR(open(path.c_str(), O_RDONLY, 0755)); if (fd >= 0) { - result = fsync(fd); - close(fd); + result = HANDLE_EINTR(fsync(fd)); + HANDLE_EINTR(close(fd)); } return result; } @@ -91,7 +91,6 @@ std::unordered_map keys = { {"AccessToken", CLEAR_ON_MANAGER_START | DONT_LOG}, {"AlwaysOnDM", PERSISTENT}, {"ApiCache_Device", PERSISTENT}, - {"ApiCache_NavDestinations", PERSISTENT}, {"AssistNowToken", PERSISTENT}, {"AthenadPid", PERSISTENT}, {"AthenadUploadQueue", PERSISTENT}, @@ -105,7 +104,6 @@ std::unordered_map keys = { {"CarParamsCache", CLEAR_ON_MANAGER_START}, {"CarParamsPersistent", PERSISTENT}, {"CarParamsPrevRoute", PERSISTENT}, - {"CarVin", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"CompletedTrainingVersion", PERSISTENT}, {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"CurrentBootlog", PERSISTENT}, @@ -159,12 +157,9 @@ std::unordered_map keys = { {"LastUpdateTime", PERSISTENT}, {"LiveParameters", PERSISTENT}, {"LiveTorqueParameters", PERSISTENT | DONT_LOG}, + {"LocationFilterInitialState", PERSISTENT}, + {"LongitudinalManeuverMode", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"LongitudinalPersonality", PERSISTENT}, - {"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"NavDestinationWaypoints", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"NavPastDestinations", PERSISTENT}, - {"NavSettingLeftSide", PERSISTENT}, - {"NavSettingTime24h", PERSISTENT}, {"NetworkMetered", PERSISTENT}, {"ObdMultiplexingChanged", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, {"ObdMultiplexingEnabled", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, @@ -187,12 +182,11 @@ std::unordered_map keys = { {"PrimeType", PERSISTENT}, {"RecordFront", PERSISTENT}, {"RecordFrontLock", PERSISTENT}, // for the internal fleet - {"ReplayControlsState", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, + {"SecOCKey", PERSISTENT | DONT_LOG}, {"RouteCount", PERSISTENT}, {"SnoozeUpdate", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, {"SshEnabled", PERSISTENT}, {"TermsVersion", PERSISTENT}, - {"Timezone", PERSISTENT}, {"TrainingVersion", PERSISTENT}, {"UbloxAvailable", PERSISTENT}, {"UpdateAvailable", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, diff --git a/common/pid.py b/common/pid.py new file mode 100644 index 000000000000000..36cbf9c4e9b59e9 --- /dev/null +++ b/common/pid.py @@ -0,0 +1,73 @@ +import numpy as np +from numbers import Number + +from openpilot.common.numpy_fast import clip, interp + + +class PIDController: + def __init__(self, k_p, k_i, k_f=0., k_d=0., pos_limit=1e308, neg_limit=-1e308, rate=100): + self._k_p = k_p + self._k_i = k_i + self._k_d = k_d + self.k_f = k_f # feedforward gain + if isinstance(self._k_p, Number): + self._k_p = [[0], [self._k_p]] + if isinstance(self._k_i, Number): + self._k_i = [[0], [self._k_i]] + if isinstance(self._k_d, Number): + self._k_d = [[0], [self._k_d]] + + self.pos_limit = pos_limit + self.neg_limit = neg_limit + + self.i_unwind_rate = 0.3 / rate + self.i_rate = 1.0 / rate + self.speed = 0.0 + + self.reset() + + @property + def k_p(self): + return interp(self.speed, self._k_p[0], self._k_p[1]) + + @property + def k_i(self): + return interp(self.speed, self._k_i[0], self._k_i[1]) + + @property + def k_d(self): + return interp(self.speed, self._k_d[0], self._k_d[1]) + + @property + def error_integral(self): + return self.i/self.k_i + + def reset(self): + self.p = 0.0 + self.i = 0.0 + self.d = 0.0 + self.f = 0.0 + self.control = 0 + + def update(self, error, error_rate=0.0, speed=0.0, override=False, feedforward=0., freeze_integrator=False): + self.speed = speed + + self.p = float(error) * self.k_p + self.f = feedforward * self.k_f + self.d = error_rate * self.k_d + + if override: + self.i -= self.i_unwind_rate * float(np.sign(self.i)) + else: + if not freeze_integrator: + self.i = self.i + error * self.k_i * self.i_rate + + # Clip i to prevent exceeding control limits + control_no_i = self.p + self.d + self.f + control_no_i = clip(control_no_i, self.neg_limit, self.pos_limit) + self.i = clip(self.i, self.neg_limit - control_no_i, self.pos_limit - control_no_i) + + control = self.p + self.i + self.d + self.f + + self.control = clip(control, self.neg_limit, self.pos_limit) + return self.control diff --git a/common/swaglog.py b/common/swaglog.py index ba81318234de1ae..d009f00e76177d4 100644 --- a/common/swaglog.py +++ b/common/swaglog.py @@ -104,6 +104,15 @@ def emit(self, record): pass +class ForwardingHandler(logging.Handler): + def __init__(self, target_logger): + super().__init__() + self.target_logger = target_logger + + def emit(self, record): + self.target_logger.handle(record) + + def add_file_handler(log): """ Function to add the file log handler to swaglog. diff --git a/common/time.py b/common/time.py index 5379faf22a81bdc..60233e17fd861e5 100644 --- a/common/time.py +++ b/common/time.py @@ -1,7 +1,7 @@ import datetime from pathlib import Path -_MIN_DATE = datetime.datetime(year=2024, month=3, day=30) +_MIN_DATE = datetime.datetime(year=2024, month=8, day=26) def min_date(): # on systemd systems, the default time is the systemd build time diff --git a/common/transformations/camera.py b/common/transformations/camera.py index dc3ca5f38873419..2e68b5e37c56c66 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -47,9 +47,9 @@ def all_cams(self): yield cam, getattr(self, cam) _ar_ox_fisheye = CameraConfig(1928, 1208, 567.0) # focal length probably wrong? magnification is not consistent across frame -_os_fisheye = CameraConfig(2688, 1520, 567.0 / 2 * 3) +_os_fisheye = CameraConfig(2688 // 2, 1520 // 2, 567.0 / 4 * 3) _ar_ox_config = DeviceCameraConfig(CameraConfig(1928, 1208, 2648.0), _ar_ox_fisheye, _ar_ox_fisheye) -_os_config = DeviceCameraConfig(CameraConfig(2688, 1520, 2648.0 * 2 / 3), _os_fisheye, _os_fisheye) +_os_config = DeviceCameraConfig(CameraConfig(2688 // 2, 1520 // 2, 1522.0 * 3 / 4), _os_fisheye, _os_fisheye) _neo_config = DeviceCameraConfig(CameraConfig(1164, 874, 910.0), CameraConfig(816, 612, 650.0), _NoneCameraConfig()) DEVICE_CAMERAS = { diff --git a/common/transformations/coordinates.cc b/common/transformations/coordinates.cc index 5b00b53a4f4928c..f3f10e547f51057 100644 --- a/common/transformations/coordinates.cc +++ b/common/transformations/coordinates.cc @@ -25,8 +25,8 @@ static Geodetic to_radians(Geodetic geodetic){ } -ECEF geodetic2ecef(Geodetic g){ - g = to_radians(g); +ECEF geodetic2ecef(const Geodetic &geodetic) { + auto g = to_radians(geodetic); double xi = sqrt(1.0 - esq * pow(sin(g.lat), 2)); double x = (a / xi + g.alt) * cos(g.lat) * cos(g.lon); double y = (a / xi + g.alt) * cos(g.lat) * sin(g.lon); @@ -34,7 +34,7 @@ ECEF geodetic2ecef(Geodetic g){ return {x, y, z}; } -Geodetic ecef2geodetic(ECEF e){ +Geodetic ecef2geodetic(const ECEF &e) { // Convert from ECEF to geodetic using Ferrari's methods // https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution double x = e.x; @@ -61,10 +61,10 @@ Geodetic ecef2geodetic(ECEF e){ return to_degrees({lat, lon, h}); } -LocalCoord::LocalCoord(Geodetic g, ECEF e){ +LocalCoord::LocalCoord(const Geodetic &geodetic, const ECEF &e) { init_ecef << e.x, e.y, e.z; - g = to_radians(g); + auto g = to_radians(geodetic); ned2ecef_matrix << -sin(g.lat)*cos(g.lon), -sin(g.lon), -cos(g.lat)*cos(g.lon), @@ -73,7 +73,7 @@ LocalCoord::LocalCoord(Geodetic g, ECEF e){ ecef2ned_matrix = ned2ecef_matrix.transpose(); } -NED LocalCoord::ecef2ned(ECEF e) { +NED LocalCoord::ecef2ned(const ECEF &e) { Eigen::Vector3d ecef; ecef << e.x, e.y, e.z; @@ -81,7 +81,7 @@ NED LocalCoord::ecef2ned(ECEF e) { return {ned[0], ned[1], ned[2]}; } -ECEF LocalCoord::ned2ecef(NED n) { +ECEF LocalCoord::ned2ecef(const NED &n) { Eigen::Vector3d ned; ned << n.n, n.e, n.d; @@ -89,12 +89,12 @@ ECEF LocalCoord::ned2ecef(NED n) { return {ecef[0], ecef[1], ecef[2]}; } -NED LocalCoord::geodetic2ned(Geodetic g) { +NED LocalCoord::geodetic2ned(const Geodetic &g) { ECEF e = ::geodetic2ecef(g); return ecef2ned(e); } -Geodetic LocalCoord::ned2geodetic(NED n){ +Geodetic LocalCoord::ned2geodetic(const NED &n) { ECEF e = ned2ecef(n); return ::ecef2geodetic(e); } diff --git a/common/transformations/coordinates.hpp b/common/transformations/coordinates.hpp index 32ec2ff66e3058a..dc8ff7a4b6a4f16 100644 --- a/common/transformations/coordinates.hpp +++ b/common/transformations/coordinates.hpp @@ -7,14 +7,14 @@ struct ECEF { double x, y, z; - Eigen::Vector3d to_vector(){ + Eigen::Vector3d to_vector() const { return Eigen::Vector3d(x, y, z); } }; struct NED { double n, e, d; - Eigen::Vector3d to_vector(){ + Eigen::Vector3d to_vector() const { return Eigen::Vector3d(n, e, d); } }; @@ -24,20 +24,20 @@ struct Geodetic { bool radians=false; }; -ECEF geodetic2ecef(Geodetic g); -Geodetic ecef2geodetic(ECEF e); +ECEF geodetic2ecef(const Geodetic &g); +Geodetic ecef2geodetic(const ECEF &e); class LocalCoord { public: Eigen::Matrix3d ned2ecef_matrix; Eigen::Matrix3d ecef2ned_matrix; Eigen::Vector3d init_ecef; - LocalCoord(Geodetic g, ECEF e); - LocalCoord(Geodetic g) : LocalCoord(g, ::geodetic2ecef(g)) {} - LocalCoord(ECEF e) : LocalCoord(::ecef2geodetic(e), e) {} - - NED ecef2ned(ECEF e); - ECEF ned2ecef(NED n); - NED geodetic2ned(Geodetic g); - Geodetic ned2geodetic(NED n); + LocalCoord(const Geodetic &g, const ECEF &e); + LocalCoord(const Geodetic &g) : LocalCoord(g, ::geodetic2ecef(g)) {} + LocalCoord(const ECEF &e) : LocalCoord(::ecef2geodetic(e), e) {} + + NED ecef2ned(const ECEF &e); + ECEF ned2ecef(const NED &n); + NED geodetic2ned(const Geodetic &g); + Geodetic ned2geodetic(const NED &n); }; diff --git a/common/transformations/orientation.cc b/common/transformations/orientation.cc index 00888c3a9260803..fb5e47a86a3ea29 100644 --- a/common/transformations/orientation.cc +++ b/common/transformations/orientation.cc @@ -7,7 +7,7 @@ #include "common/transformations/orientation.hpp" #include "common/transformations/coordinates.hpp" -Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat){ +Eigen::Quaterniond ensure_unique(const Eigen::Quaterniond &quat) { if (quat.w() > 0){ return quat; } else { @@ -15,7 +15,7 @@ Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat){ } } -Eigen::Quaterniond euler2quat(Eigen::Vector3d euler){ +Eigen::Quaterniond euler2quat(const Eigen::Vector3d &euler) { Eigen::Quaterniond q; q = Eigen::AngleAxisd(euler(2), Eigen::Vector3d::UnitZ()) @@ -25,7 +25,7 @@ Eigen::Quaterniond euler2quat(Eigen::Vector3d euler){ } -Eigen::Vector3d quat2euler(Eigen::Quaterniond quat){ +Eigen::Vector3d quat2euler(const Eigen::Quaterniond &quat) { // TODO: switch to eigen implementation if the range of the Euler angles doesn't matter anymore // Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(2, 1, 0); // return {euler(2), euler(1), euler(0)}; @@ -36,34 +36,34 @@ Eigen::Vector3d quat2euler(Eigen::Quaterniond quat){ return {gamma, theta, psi}; } -Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat){ +Eigen::Matrix3d quat2rot(const Eigen::Quaterniond &quat) { return quat.toRotationMatrix(); } -Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot){ +Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot) { return ensure_unique(Eigen::Quaterniond(rot)); } -Eigen::Matrix3d euler2rot(Eigen::Vector3d euler){ +Eigen::Matrix3d euler2rot(const Eigen::Vector3d &euler) { return quat2rot(euler2quat(euler)); } -Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot){ +Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot) { return quat2euler(rot2quat(rot)); } -Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw){ +Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw) { return euler2rot({roll, pitch, yaw}); } -Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle){ +Eigen::Matrix3d rot(const Eigen::Vector3d &axis, double angle) { Eigen::Quaterniond q; q = Eigen::AngleAxisd(angle, axis); return q.toRotationMatrix(); } -Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose) { +Eigen::Vector3d ecef_euler_from_ned(const ECEF &ecef_init, const Eigen::Vector3d &ned_pose) { /* Using Rotations to Build Aerospace Coordinate Systems Don Koks @@ -103,7 +103,7 @@ Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose) { return {phi, theta, psi}; } -Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose){ +Eigen::Vector3d ned_euler_from_ecef(const ECEF &ecef_init, const Eigen::Vector3d &ecef_pose) { /* Using Rotations to Build Aerospace Coordinate Systems Don Koks diff --git a/common/transformations/orientation.hpp b/common/transformations/orientation.hpp index 150b12cadee1d1d..0874a0a814b2829 100644 --- a/common/transformations/orientation.hpp +++ b/common/transformations/orientation.hpp @@ -3,15 +3,15 @@ #include "common/transformations/coordinates.hpp" -Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat); +Eigen::Quaterniond ensure_unique(const Eigen::Quaterniond &quat); -Eigen::Quaterniond euler2quat(Eigen::Vector3d euler); -Eigen::Vector3d quat2euler(Eigen::Quaterniond quat); -Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat); +Eigen::Quaterniond euler2quat(const Eigen::Vector3d &euler); +Eigen::Vector3d quat2euler(const Eigen::Quaterniond &quat); +Eigen::Matrix3d quat2rot(const Eigen::Quaterniond &quat); Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot); -Eigen::Matrix3d euler2rot(Eigen::Vector3d euler); +Eigen::Matrix3d euler2rot(const Eigen::Vector3d &euler); Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot); Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw); -Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle); -Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose); -Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose); +Eigen::Matrix3d rot(const Eigen::Vector3d &axis, double angle); +Eigen::Vector3d ecef_euler_from_ned(const ECEF &ecef_init, const Eigen::Vector3d &ned_pose); +Eigen::Vector3d ned_euler_from_ecef(const ECEF &ecef_init, const Eigen::Vector3d &ecef_pose); diff --git a/common/transformations/transformations.pxd b/common/transformations/transformations.pxd index 964adf06ece9e88..fe32e18deac88ba 100644 --- a/common/transformations/transformations.pxd +++ b/common/transformations/transformations.pxd @@ -24,15 +24,15 @@ cdef extern from "orientation.hpp": double operator()(int, int) - Quaternion euler2quat(Vector3) - Vector3 quat2euler(Quaternion) - Matrix3 quat2rot(Quaternion) - Quaternion rot2quat(Matrix3) - Vector3 rot2euler(Matrix3) - Matrix3 euler2rot(Vector3) + Quaternion euler2quat(const Vector3 &) + Vector3 quat2euler(const Quaternion &) + Matrix3 quat2rot(const Quaternion &) + Quaternion rot2quat(const Matrix3 &) + Vector3 rot2euler(const Matrix3 &) + Matrix3 euler2rot(const Vector3 &) Matrix3 rot_matrix(double, double, double) - Vector3 ecef_euler_from_ned(ECEF, Vector3) - Vector3 ned_euler_from_ecef(ECEF, Vector3) + Vector3 ecef_euler_from_ned(const ECEF &, const Vector3 &) + Vector3 ned_euler_from_ecef(const ECEF &, const Vector3 &) cdef extern from "coordinates.cc": @@ -52,21 +52,21 @@ cdef extern from "coordinates.cc": double alt bool radians - ECEF geodetic2ecef(Geodetic) - Geodetic ecef2geodetic(ECEF) + ECEF geodetic2ecef(const Geodetic &) + Geodetic ecef2geodetic(const ECEF &) cdef cppclass LocalCoord_c "LocalCoord": Matrix3 ned2ecef_matrix Matrix3 ecef2ned_matrix - LocalCoord_c(Geodetic, ECEF) - LocalCoord_c(Geodetic) - LocalCoord_c(ECEF) + LocalCoord_c(const Geodetic &, const ECEF &) + LocalCoord_c(const Geodetic &) + LocalCoord_c(const ECEF &) - NED ecef2ned(ECEF) - ECEF ned2ecef(NED) - NED geodetic2ned(Geodetic) - Geodetic ned2geodetic(NED) + NED ecef2ned(const ECEF &) + ECEF ned2ecef(const NED &) + NED geodetic2ned(const Geodetic &) + Geodetic ned2geodetic(const NED &) cdef extern from "coordinates.hpp": pass diff --git a/common/util.h b/common/util.h index 186873ac216b289..7cfa008509e2587 100644 --- a/common/util.h +++ b/common/util.h @@ -37,6 +37,8 @@ const double MS_TO_MPH = MS_TO_KPH * KM_TO_MILE; const double METER_TO_MILE = KM_TO_MILE / 1000.0; const double METER_TO_FOOT = 3.28084; +#define ALIGNED_SIZE(x, align) (((x) + (align)-1) & ~((align)-1)) + namespace util { void set_thread_name(const char* name); diff --git a/common/utils.py b/common/utils.py deleted file mode 100644 index b9de020ee6208e8..000000000000000 --- a/common/utils.py +++ /dev/null @@ -1,11 +0,0 @@ -class Freezable: - _frozen: bool = False - - def freeze(self): - if not self._frozen: - self._frozen = True - - def __setattr__(self, *args, **kwargs): - if self._frozen: - raise Exception("cannot modify frozen object") - super().__setattr__(*args, **kwargs) diff --git a/common/version.h b/common/version.h index 177882e31d48da2..1f651fb3926dd60 100644 --- a/common/version.h +++ b/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.9.7" +#define COMMA_VERSION "0.9.8" diff --git a/conftest.py b/conftest.py index fc4931fb54d2f99..7ee0c789435537e 100644 --- a/conftest.py +++ b/conftest.py @@ -8,6 +8,19 @@ from openpilot.system.manager import manager from openpilot.system.hardware import TICI, HARDWARE +# TODO: pytest-cpp doesn't support FAIL, and we need to create test translations in sessionstart +# pending https://github.com/pytest-dev/pytest-cpp/pull/147 +collect_ignore = [ + "selfdrive/ui/tests/test_translations", + "selfdrive/test/process_replay/test_processes.py", + "selfdrive/test/process_replay/test_regen.py", + "selfdrive/test/test_time_to_onroad.py", +] +collect_ignore_glob = [ + "selfdrive/debug/*.py", + "selfdrive/modeld/*.py", +] + def pytest_sessionstart(session): # TODO: fix tests and enable test order randomization diff --git a/docs/BOUNTIES.md b/docs/BOUNTIES.md deleted file mode 100644 index 31e19e12061c55b..000000000000000 --- a/docs/BOUNTIES.md +++ /dev/null @@ -1,62 +0,0 @@ -# [Bounties](https://github.com/orgs/commaai/projects/26/views/1) - -Get paid to improve openpilot! - -## Rules - -* code must be merged into openpilot master -* bounty eligibility is solely at our discretion -* once you open a PR, the bounty is locked to you until you stop working on it -* open a ticket at [comma.ai/support](https://comma.ai/support/shop-order) with links to your PRs to claim -* get an extra 20% if you redeem your bounty in [comma shop](https://comma.ai/shop) credit (including refunds on previous orders) -* for bounties >$100, the first PR gets a lock, which times out after a week of no progress - -We put up each bounty with the intention that it'll get merged, but occasionally the right resolution is to close the bounty, which only becomes clear once some effort is put in. -This is still valuable work, so we'll pay out $100 for getting any bounty closed with a good explanation. - -## Issue bounties - -We've tagged bounty-eligible issues across openpilot and the rest of our repos; check out all the open ones [here](https://github.com/orgs/commaai/projects/26/views/1). These bounties roughly work out like this: -* **$100** - a few hours of work for an experienced openpilot developer; a good intro for someone new to openpilot -* **$300** - a day of work for an experienced openpilot developer -* **$500** - a few days of work for an experienced openpilot developer -* **$1k+** - a week or two of work (could be less for the right person) - -New bounties can be proposed in the [**#contributing**](https://discord.com/channels/469524606043160576/1183173332531687454) channel in Discord. - -## Car bounties - -The car bounties only apply to cars that have a path to ship in openpilot release, which excludes unsupportable cars (e.g. Fords with a steering lockout) or cars that require extra hardware (Honda Accord with serial steering). - -#### Brand or platform port - $2000 -Example PR: [commaai/openpilot#23331](https://github.com/commaai/openpilot/pull/23331) - -This is for adding support for an entirely new brand or a substantially new ADAS platform within a brand (e.g. the Volkswagen PQ platform). - -#### Model port - $250 -Example PR: [commaai/openpilot#30245](https://github.com/commaai/openpilot/pull/30245) - -This is for porting a new car model that runs on a platform openpilot already supports. -In the average case, this is a few hours of work for an experienced software developer. - -This bounty also covers getting openpilot supported on a previously unsupported trim of an already supported car, e.g. the Chevy Bolt without ACC. - -#### Reverse Engineering a new Actuation Message - $300 - -This is for cars that are already supported, and it has three components: -* reverse a new steering, adaptive cruise, or AEB message -* merge the DBC definitions to [opendbc](http://github.com/commaai/opendbc) -* merge the openpilot code to use it and post a demo route - -The control doesn't have to be perfect, but it should generally do what it's supposed to do. - -### Specific Cars - -#### Rivian R1T or R1S - $3000 - -Get a Rivian driving with openpilot. -Requires a merged port with lateral control and at least a POC of longitudinal control. - -#### Chevy Bolt with SuperCruise - $2500 - -The Bolt is already supported on the trim with standard ACC. Get openpilot working on the trim with SuperCruise. It must be a normal install: no extra pandas or other hardware, no ECU reflashes, etc. The full bounty is for a port with lateral and longitudinal control. $1500 of the bounty can be claimed with a lateral-only port. diff --git a/docs/CARS.md b/docs/CARS.md index 3b163dcee3da698..6861f411d26ac35 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -4,19 +4,19 @@ 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. -# 288 Supported Cars +# 289 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|ILX 2016-19|AcuraWatch Plus|openpilot|26 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|26 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,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 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
|| @@ -25,60 +25,61 @@ A supported vehicle is one that just works when you install a comma device. All |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-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
|| +|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 Hybrid 2019-24|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|| -|CUPRA|Ateca 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
|| +|CUPRA|Ateca 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 USB-C coupler
- 1 VW J533 connector
- 1 comma 3X
- 1 harness box
- 1 long OBD-C cable
- 1 mount
- 1 right angle OBD-C cable (1.5 ft)
Buy Here
|| |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-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 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|Escape Hybrid 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|Escape Plug-in Hybrid 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|Explorer Hybrid 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|Focus Hybrid 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|Kuga Hybrid 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|Kuga Plug-in Hybrid 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
|| -|Ford|Maverick 2023-24|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|Maverick Hybrid 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
|| -|Ford|Maverick Hybrid 2023-24|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|Bronco Sport 2021-24|Co-Pilot360 Assist+|openpilot|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|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|Escape Hybrid 2020-22|Co-Pilot360 Assist+|openpilot|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|Escape Plug-in Hybrid 2020-22|Co-Pilot360 Assist+|openpilot|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-24|Co-Pilot360 Assist+|openpilot|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 Hybrid 2020-24|Co-Pilot360 Assist+|openpilot|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|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 Hybrid 2018[3](#footnotes)|Adaptive Cruise Control with Lane Centering|openpilot|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|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 Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|openpilot|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 Plug-in Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|openpilot|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|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|Maverick 2023-24|Co-Pilot360 Assist|openpilot|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|Maverick Hybrid 2022|LARIAT Luxury|openpilot|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|Maverick Hybrid 2023-24|Co-Pilot360 Assist|openpilot|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
|| |Genesis|G70 2018|All|Stock|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
|| |Genesis|G70 2019-21|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
|| |Genesis|G70 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
|| |Genesis|G80 2017|All|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai J 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
|| |Genesis|G80 2018-19|All|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
|| +|Genesis|G80 (2.5T Advanced Trim, with HDA II) 2024[5](#footnotes)|Highway Driving Assist II|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
|| |Genesis|G90 2017-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 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
|| |Genesis|GV60 (Advanced Trim) 2023[5](#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
|| -|Genesis|GV60 (Performance Trim) 2023[5](#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
|| -|Genesis|GV70 (2.5T Trim) 2022-23[5](#footnotes)|All|Stock|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
|| -|Genesis|GV70 (3.5T Trim) 2022-23[5](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M 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
|| +|Genesis|GV60 (Performance Trim) 2022-23[5](#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
|| +|Genesis|GV70 (2.5T Trim, without HDA II) 2022-23[5](#footnotes)|All|Stock|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
|| +|Genesis|GV70 (3.5T Trim, without HDA II) 2022-23[5](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M 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
|| +|Genesis|GV70 Electrified (with HDA II) 2023[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q 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
|| |Genesis|GV80 2023[5](#footnotes)|All|Stock|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai M 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
|| |GMC|Sierra 1500 2020-21|Driver Alert 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
|| |Honda|Accord 2018-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
|| |Honda|Accord Hybrid 2018-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
|| |Honda|Civic 2016-18|Honda Sensing|openpilot|0 mph|12 mph|[![star](assets/icon-star-empty.svg)](##)|[![star](assets/icon-star-full.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|Civic 2019-21|All|openpilot available[1](#footnotes)|0 mph|2 mph[4](#footnotes)|[![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|Civic 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|Civic 2022-24|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|Civic Hatchback 2017-21|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|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|Civic Hatchback 2022-24|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|26 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-21|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-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|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
|| -|Honda|HR-V 2019-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|Fit 2018-20|Honda Sensing|openpilot|26 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|26 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|HR-V 2019-22|Honda Sensing|openpilot|26 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|HR-V 2023|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|Insight 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
|| |Honda|Inspire 2018|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|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-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
|| +|Honda|Odyssey 2018-20|Honda Sensing|openpilot|26 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|26 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|26 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|26 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
|| @@ -90,9 +91,9 @@ A supported vehicle is one that just works when you install a comma device. All |Hyundai|Elantra Hybrid 2021-23|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 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|Genesis 2015-16|Smart Cruise Control (SCC)|Stock|19 mph|37 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-empty.svg)](##)|
Parts- 1 Hyundai J 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|i30 2017-19|Smart Cruise Control (SCC)|Stock|0 mph|32 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|Ioniq 5 (Southeast Asia only) 2022-23[5](#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 Q 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|Ioniq 5 (with HDA II) 2022-23[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q 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|Ioniq 5 (without HDA II) 2022-23[5](#footnotes)|Highway Driving Assist|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|Ioniq 5 (Non-US only) 2022-24[5](#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 Q 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|Ioniq 5 (with HDA II) 2022-24[5](#footnotes)|Highway Driving Assist II|openpilot available[1](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 Hyundai Q 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|Ioniq 5 (without HDA II) 2022-24[5](#footnotes)|Highway Driving Assist|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|Ioniq 6 (with HDA II) 2023-24[5](#footnotes)|Highway Driving Assist II|Stock|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
|| |Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|Stock|0 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
|| |Hyundai|Ioniq Electric 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 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
|| @@ -183,10 +184,10 @@ A supported vehicle is one that just works when you install a comma device. All |Lexus|RX Hybrid 2017-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|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-23|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
|| -|Lincoln|Aviator Plug-in Hybrid 2020-23|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-24|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-24|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
|| +|Lincoln|Aviator 2020-24|Co-Pilot360 Plus|openpilot|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
|| +|Lincoln|Aviator Plug-in Hybrid 2020-24|Co-Pilot360 Plus|openpilot|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-24|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 USB-C coupler
- 1 VW J533 connector
- 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-24|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 USB-C coupler
- 1 VW J533 connector
- 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
|| @@ -194,8 +195,8 @@ A supported vehicle is one that just works when you install a comma device. All |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-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 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
|| -|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
|| +|SEAT|Ateca 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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[6](#footnotes)|openpilot available[1,7](#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[6](#footnotes)|openpilot available[1,7](#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[6](#footnotes)|openpilot available[1,7](#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)
|| @@ -206,15 +207,15 @@ A supported vehicle is one that just works when you install a comma device. All |Subaru|Outback 2020-22|All[6](#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[6](#footnotes)|openpilot available[1,7](#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[6](#footnotes)|openpilot available[1,7](#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[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|Octavia Scout 2017-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|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
|| +|Š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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 Scout 2017-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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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
|| @@ -260,42 +261,42 @@ A supported vehicle is one that just works when you install a comma device. All |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-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
|| -|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|Arteon Shooting Brake 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-24|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-24|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-24|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-24|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-24|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-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|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-24|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,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 Shooting Brake 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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-24|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 USB-C coupler
- 1 VW J533 connector
- 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-24|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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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-24|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 USB-C coupler
- 1 VW J533 connector
- 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-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 USB-C coupler
- 1 VW J533 connector
- 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-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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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-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 USB-C coupler
- 1 VW J533 connector
- 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|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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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,12](#footnotes)|0 mph|0 mph|[![star](assets/icon-star-full.svg)](##)|[![star](assets/icon-star-full.svg)](##)|
Parts- 1 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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 USB-C coupler
- 1 VW J533 connector
- 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`.
diff --git a/docs/CONTRIBUTING.md b/docs/CONTRIBUTING.md index 755ca82220fad39..d455fa6fd3c37a6 100644 --- a/docs/CONTRIBUTING.md +++ b/docs/CONTRIBUTING.md @@ -1,6 +1,8 @@ # 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/). Development activity is coordinated through our GitHub Issues, [GitHub Discussions](https://github.com/commaai/openpilot/discussions), and [Discord](https://discord.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 is coordinated through [Discord](https://discord.comma.ai) and GitHub. ### Getting Started @@ -11,7 +13,8 @@ Our software is open source so you can solve your own problems without needing h ## 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. +**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? @@ -27,24 +30,21 @@ All of these are examples of good PRs: ### What doesn't get merged? -* **arbitrary style changes**: code is art, and it's up to the author to make it beautiful +* **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 +* **UI design**: 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. +* **Negative expected value**: This a class of PRs that makes an improvement, but the risk or validation costs more than the improvement. The risk can be mitigated by first getting a failing test merged. ### First contribution -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. +[Projects / openpilot bounties](https://github.com/orgs/commaai/projects/26/views/1?pane=info) is the best place to get started and goes in-depth on what's expected when working on a bounty. +There's lot of bounties that don't require a comma 3/3X or a car. ## Pull Requests -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. +Pull requests should be against the master branch. A good pull request has all of the following: * a clearly stated purpose diff --git a/docs/Makefile b/docs/Makefile deleted file mode 100644 index 09103e206ec444c..000000000000000 --- a/docs/Makefile +++ /dev/null @@ -1,53 +0,0 @@ -# Minimal makefile for Sphinx documentation -# - -OPENPILOT_ROOT = `git rev-parse --show-toplevel` - -# You can set these variables from the command line, and also -# from the environment for the first two. -SPHINXOPTS ?= -SPHINXBUILD ?= sphinx-build -DOCSDIR = "$(OPENPILOT_ROOT)/docs" -SOURCEDIR = "$(OPENPILOT_ROOT)/build/docs" -DOCSBUILDDIR = "$(OPENPILOT_ROOT)/build/docs" -BUILDDIR = "$(OPENPILOT_ROOT)/build" - -# Put it first so that "make" without argument is like "make help". -help: - @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(DOCSBUILDDIR)" $(SPHINXOPTS) $(O) - -clean: - @echo "Cleaning build folder..." - rm -rf "$(BUILDDIR)" - -.PHONY: help Makefile - -# Catch-all target: route all unknown targets to Sphinx using the new -# "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). -%: Makefile - @echo "Cleaning build folder..." - rm -rf "$(BUILDDIR)" - mkdir -p "$(DOCSBUILDDIR)" - - @echo "Copying docs & config to build folder..." - cp -a "$(DOCSDIR)" "$(BUILDDIR)" - cd "$(OPENPILOT_ROOT)" && \ - find . -type f \( -name "*.md" -o -name "*.rst" -o -name "*.png" -o -name "*.jpg" -o -name "*.svg" \) \ - -not -path "*/.*" \ - -not -path "./build/*" \ - -not -path "./docs/*" \ - -not -path "./xx/*" \ - -exec cp --parents "{}" ./build/docs/ \; - - @echo "Building rst files..." - sphinx-apidoc -o "$(DOCSBUILDDIR)" ../ \ - ../xx ../rednose_repo ../notebooks ../panda_jungle \ - ../third_party \ - ../panda/examples \ - ../scripts \ - ../selfdrive/modeld \ - ../selfdrive/debug \ - $(shell find .. -type d -name "*test* -not -path "**.venv**" \") - - @echo "Building html files..." - @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(DOCSBUILDDIR)" $(SPHINXOPTS) $(O) diff --git a/docs/README.md b/docs/README.md index 838b00e7ae09c27..08dd4fa8bcca9be 100644 --- a/docs/README.md +++ b/docs/README.md @@ -1,3 +1,26 @@ -# openpilot-docs +# openpilot docs -These docs are autogenerated from [this folder](https://github.com/commaai/openpilot/tree/master/docs) in the main openpilot repository. \ No newline at end of file +This is the source for [docs.comma.ai](https://docs.comma.ai). +The site is updated on pushes to master by this [workflow](../.github/workflows/docs.yaml). + +## Development +NOTE: Those commands must be run in the root directory of openpilot, **not /docs** + +**1. Install the docs dependencies** +``` bash +pip install .[docs] +``` + +**2. Build the new site** +``` bash +mkdocs build +``` + +**3. Run the new site locally** +``` bash +mkdocs serve +``` + +References: +* https://www.mkdocs.org/getting-started/ +* https://github.com/ntno/mkdocs-terminal diff --git a/docs/WORKFLOW.md b/docs/WORKFLOW.md index 85ae8d86f46f765..477c7511ca6a9c9 100644 --- a/docs/WORKFLOW.md +++ b/docs/WORKFLOW.md @@ -9,6 +9,7 @@ Most development happens on normal Ubuntu workstations, and not in cars or direc ```bash # get the latest stuff git pull +git lfs pull git submodule update --init --recursive # update dependencies @@ -22,13 +23,13 @@ scons -j8 selfdrive/ui/ cd selfdrive/ui/ && scons -u -j8 # test everything -pytest . +pytest # test just logging services cd system/loggerd && pytest . # run the linter -pre-commit run --all +op lint ``` ## Testing diff --git a/docs/_static/favicon.ico b/docs/_static/favicon.ico deleted file mode 100644 index 976929954f3dacd..000000000000000 Binary files a/docs/_static/favicon.ico and /dev/null differ diff --git a/docs/_static/logo.png b/docs/_static/logo.png deleted file mode 100644 index 269956508556e48..000000000000000 Binary files a/docs/_static/logo.png and /dev/null differ diff --git a/docs/_static/robots.txt b/docs/_static/robots.txt deleted file mode 100644 index 3bcd24fb5d5f9db..000000000000000 --- a/docs/_static/robots.txt +++ /dev/null @@ -1,2 +0,0 @@ -User-agent: * -Sitemap: https://docs.comma.ai/sitemap.xml \ No newline at end of file diff --git a/docs/c_docs.rst b/docs/c_docs.rst deleted file mode 100644 index 3b89fe987472008..000000000000000 --- a/docs/c_docs.rst +++ /dev/null @@ -1,89 +0,0 @@ -openpilot -========== - - -opendbc ------- -.. autodoxygenindex:: - :project: opendbc_can - - -cereal ------- - -messaging -^^^^^^^^^ -.. autodoxygenindex:: - :project: msgq_repo_msgq - -visionipc -^^^^^^^^^ -.. autodoxygenindex:: - :project: msgq_repo_msgq_visionipc - - -selfdrive ---------- - -camerad -^^^^^^^ -.. autodoxygenindex:: - :project: system_camerad_cameras - -locationd -^^^^^^^^^ -.. autodoxygenindex:: - :project: selfdrive_locationd - -ui -^^ - -.. autodoxygenindex:: - :project: selfdrive_ui - -replay -"""""" -.. autodoxygenindex:: - :project: tools_replay - -qt -"" -.. autodoxygenindex:: - :project: selfdrive_ui_qt_offroad -.. autodoxygenindex:: - :project: selfdrive_ui_qt_maps - -proclogd -^^^^^^^^ -.. autodoxygenindex:: - :project: system_proclogd - -modeld -^^^^^^ -.. autodoxygenindex:: - :project: selfdrive_modeld_transforms -.. autodoxygenindex:: - :project: selfdrive_modeld_models -.. autodoxygenindex:: - :project: selfdrive_modeld_runners - -common -^^^^^^ -.. autodoxygenindex:: - :project: common - -sensorsd -^^^^^^^^ -.. autodoxygenindex:: - :project: system_sensord_sensors - -pandad -^^^^^^ -.. autodoxygenindex:: - :project: selfdrive_pandad - - -rednose -------- -.. autodoxygenindex:: - :project: rednose_repo_rednose_helpers diff --git a/docs/car-porting/brand-port.md b/docs/car-porting/brand-port.md new file mode 100644 index 000000000000000..a3daa7a84850f33 --- /dev/null +++ b/docs/car-porting/brand-port.md @@ -0,0 +1,5 @@ +# Developing a car brand port + +A brand port is a port of openpilot to a substantially new car brand or platform within a brand. + +Here's an example of one: https://github.com/commaai/openpilot/pull/23331. diff --git a/docs/car-porting/model-port.md b/docs/car-porting/model-port.md new file mode 100644 index 000000000000000..e148a40ecb131b8 --- /dev/null +++ b/docs/car-porting/model-port.md @@ -0,0 +1,5 @@ +# Developing a car model port + +A model port is a port of openpilot to a new car model within an already supported brand. Model ports are easier than brand ports because the car's existing APIs are already known. + +Here's an example of one: https://github.com/commaai/openpilot/pull/30672/. diff --git a/docs/car-porting/what-is-a-car-port.md b/docs/car-porting/what-is-a-car-port.md new file mode 100644 index 000000000000000..55cce94da1f39db --- /dev/null +++ b/docs/car-porting/what-is-a-car-port.md @@ -0,0 +1,39 @@ +# What is a car port? + +A car port enables openpilot support on a particular car. Each car model openpilot supports needs to be individually ported. The complexity of a car port varies depending on many factors including: + +* existing openpilot support for similar cars +* architecture and APIs available in the car + + +# Structure of a car port + +Virtually all car-specific code is contained in two other repositories: [opendbc](https://github.com/commaai/opendbc) and [panda](https://github.com/commaai/panda). + +## opendbc + +Each car brand is supported by a standard interface structure in `opendbc/car/[brand]`: + +* `interface.py`: Interface for the car, defines the CarInterface class +* `carstate.py`: Reads CAN messages from the car and builds openpilot CarState messages +* `carcontroller.py`: Control logic for executing openpilot CarControl actions on the car +* `[brand]can.py`: Composes CAN messages for carcontroller to send +* `values.py`: Limits for actuation, general constants for cars, and supported car documentation +* `radar_interface.py`: Interface for parsing radar points from the car, if applicable + +## panda + +* `board/safety/safety_[brand].h`: Brand-specific safety logic +* `tests/safety/test_[brand].py`: Brand-specific safety CI tests + +## openpilot + +For historical reasons, openpilot still contains a small amount of car-specific logic. This will eventually be migrated to opendbc or otherwise removed. + +* `selfdrive/car/car_specific.py`: Brand-specific event logic + +# Overview + +[Jason Young](https://github.com/jyoung8607) gave a talk at COMMA_CON with an overview of the car porting process. The talk is available on YouTube: + +https://www.youtube.com/watch?v=XxPS5TpTUnI diff --git a/docs/concepts/glossary.md b/docs/concepts/glossary.md new file mode 100644 index 000000000000000..a09b0f07853e782 --- /dev/null +++ b/docs/concepts/glossary.md @@ -0,0 +1,9 @@ +# openpilot glossary + +* **onroad**: openpilot's system state while ignition is on +* **offroad**: openpilot's system state while ignition is off +* **route**: a route is a recording of an onroad session +* **segment**: routes are split into one minute chunks called segments. +* **comma connect**: the web viewer for all your routes; check it out at [connect.comma.ai](https://connect.comma.ai). +* **panda**: this is the secondary processor on the device that implements the functional safety and directly talks to the car over CAN. See the [panda repo](https://github.com/commaai/panda). +* **comma 3X**: the latest hardware by comma.ai for running openpilot. more info at [comma.ai/shop](https://comma.ai/shop). diff --git a/docs/concepts/logs.md b/docs/concepts/logs.md new file mode 100644 index 000000000000000..46ab2897df9eec8 --- /dev/null +++ b/docs/concepts/logs.md @@ -0,0 +1,29 @@ +# Logging + +openpilot records routes in one minute chunks called segments. A route starts on the rising edge of ignition and ends on the falling edge. + +Check out our [Python library](https://github.com/commaai/openpilot/blob/master/tools/lib/logreader.py) for reading openpilot logs. Also checkout our [tools](https://github.com/commaai/openpilot/tree/master/tools) to replay and view your data. These are the same tools we use to debug and develop openpilot. + +For each segment, openpilot records the following log types: + +## rlog.bz2 + +rlogs contain all the messages passed amongst openpilot's processes. See [cereal/services.py](https://github.com/commaai/cereal/blob/master/services.py) for a list of all the logged services. They're a bzip2 archive of the serialized capnproto messages. + +## {f,e,d}camera.hevc + +Each camera stream is H.265 encoded and written to its respective file. + +* `fcamera.hevc` is the road camera +* `ecamera.hevc` is the wide road camera +* `dcamera.hevc` is the driver camera + +## qlog.bz2 & qcamera.ts + +qlogs are a decimated subset of the rlogs. Check out [cereal/services.py](https://github.com/commaai/cereal/blob/master/services.py) for the decimation. + + +qcameras are H.264 encoded, lower res versions of the fcamera.hevc. The video shown in [comma connect](https://connect.comma.ai/) is from the qcameras. + + +qlogs and qcameras are designed to be small enough to upload instantly on slow internet and store forever, yet useful enough for most analysis and debugging. diff --git a/docs/concepts/safety.md b/docs/concepts/safety.md new file mode 120000 index 000000000000000..f286ad4b152ffc0 --- /dev/null +++ b/docs/concepts/safety.md @@ -0,0 +1 @@ +../SAFETY.md \ No newline at end of file diff --git a/docs/conf.py b/docs/conf.py deleted file mode 100644 index 9a8d64669707772..000000000000000 --- a/docs/conf.py +++ /dev/null @@ -1,147 +0,0 @@ -# type: ignore - -# Configuration file for the Sphinx documentation builder. -# -# This file only contains a selection of the most common options. For a full -# list see the documentation: -# https://www.sphinx-doc.org/en/master/usage/configuration.html - -# -- Path setup -------------------------------------------------------------- - -# If extensions (or modules to document with autodoc) are in another directory, -# add these directories to sys.path here. If the directory is relative to the -# documentation root, use os.path.abspath to make it absolute, like shown here. -# -import os -import sys -from os.path import exists - -from openpilot.common.basedir import BASEDIR -from openpilot.system.version import get_version - -sys.path.insert(0, os.path.abspath('.')) -sys.path.insert(0, os.path.abspath('..')) - -VERSION = get_version() - - -# -- Project information ----------------------------------------------------- - -project = 'openpilot docs' -copyright = '2021, comma.ai' # noqa: A001 -author = 'comma.ai' -version = VERSION -release = VERSION -language = 'en' - - -# -- General configuration --------------------------------------------------- - -# Add any Sphinx extension module names here, as strings. They can be -# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom -# ones. -extensions = [ - 'sphinx.ext.autodoc', # Auto-generate docs - 'sphinx.ext.viewcode', # Add view code link to modules - 'sphinx_rtd_theme', # Read The Docs theme - 'myst_parser', # Markdown parsing - 'breathe', # Doxygen C/C++ integration - 'sphinx_sitemap', # sitemap generation for SEO -] - -myst_html_meta = { - "description": "openpilot docs", - "keywords": "op, openpilot, docs, documentation", - "robots": "all,follow", - "googlebot": "index,follow,snippet,archive", - "property=og:locale": "en_US", - "property=og:site_name": "docs.comma.ai", - "property=og:url": "https://docs.comma.ai", - "property=og:title": "openpilot Documentation", - "property=og:type": "website", - "property=og:image:type": "image/jpeg", - "property=og:image:width": "400", - "property=og:image": "https://docs.comma.ai/_static/logo.png", - "property=og:image:url": "https://docs.comma.ai/_static/logo.png", - "property=og:image:secure_url": "https://docs.comma.ai/_static/logo.png", - "property=og:description": "openpilot Documentation", - "property=twitter:card": "summary_large_image", - "property=twitter:logo": "https://docs.comma.ai/_static/logo.png", - "property=twitter:title": "openpilot Documentation", - "property=twitter:description": "openpilot Documentation" -} - -html_baseurl = 'https://docs.comma.ai/' -sitemap_filename = "sitemap.xml" - -# Add any paths that contain templates here, relative to this directory. -templates_path = ['_templates'] - -# List of patterns, relative to source directory, that match files and -# directories to ignore when looking for source files. -# This pattern also affects html_static_path and html_extra_path. -exclude_patterns = [] - - -# -- c docs configuration --------------------------------------------------- - -# Breathe Configuration -# breathe_default_project = "c_docs" -breathe_build_directory = f"{BASEDIR}/build/docs/html/xml" -breathe_separate_member_pages = True -breathe_default_members = ('members', 'private-members', 'undoc-members') -breathe_domain_by_extension = { - "h": "cc", -} -breathe_implementation_filename_extensions = ['.c', '.cc'] -breathe_doxygen_config_options = {} -breathe_projects_source = {} - -# only document files that have accompanying .cc files next to them -print("searching for c_docs...") -for root, _, files in os.walk(BASEDIR): - found = False - breath_src = {} - breathe_srcs_list = [] - - for file in files: - ccFile = os.path.join(root, file)[:-2] + ".cc" - - if file.endswith(".h") and exists(ccFile): - f = os.path.join(root, file) - - parent_dir_abs = os.path.dirname(f) - parent_dir = parent_dir_abs[len(BASEDIR) + 1:] - parent_project = parent_dir.replace('/', '_') - print(f"\tFOUND: {f} in {parent_project}") - - breathe_srcs_list.append(file) - found = True - - if found: - breath_src[parent_project] = (parent_dir_abs, breathe_srcs_list) - breathe_projects_source.update(breath_src) - -print(f"breathe_projects_source: {breathe_projects_source.keys()}") - -# -- Options for HTML output ------------------------------------------------- - -# The theme to use for HTML and HTML Help pages. See the documentation for -# a list of builtin themes. -# -html_theme = 'sphinx_rtd_theme' -html_show_copyright = True - -# Add any paths that contain custom static files (such as style sheets) here, -# relative to this directory. They are copied after the builtin static files, -# so a file named "default.css" will overwrite the builtin "default.css". -html_static_path = ['_static'] -html_logo = '_static/logo.png' -html_favicon = '_static/favicon.ico' -html_theme_options = { - 'logo_only': False, - 'display_version': True, - 'vcs_pageview_mode': 'blob', - 'style_nav_header_background': '#000000', -} -html_extra_path = ['_static'] diff --git a/docs/contributing/architecture.md b/docs/contributing/architecture.md new file mode 100644 index 000000000000000..c79bec1ac69aea0 --- /dev/null +++ b/docs/contributing/architecture.md @@ -0,0 +1 @@ +# Architecture diff --git a/docs/contributing/roadmap.md b/docs/contributing/roadmap.md new file mode 100644 index 000000000000000..ce50ad5577e2e6d --- /dev/null +++ b/docs/contributing/roadmap.md @@ -0,0 +1,31 @@ +# Roadmap + +This is the roadmap for the next major openpilot releases. Also check out + +* [Milestones](https://github.com/commaai/openpilot/milestones) for minor releases +* [Projects](https://github.com/commaai/openpilot/projects?query=is%3Aopen) for shorter-term projects not tied to releases +* [Bounties](https://comma.ai/bounties) for paid individual issues +* [#current-projects](https://discord.com/channels/469524606043160576/1249579909739708446) in Discord for discussion on work-in-progress projects + +## openpilot 0.10 + +openpilot 0.10 will be the first release with a driving policy trained in +a [learned simulator](https://youtu.be/EqQNZXqzFSI). + +* Driving model trained in a learned simlator +* Always-on driver monitoring (behind a toggle) +* GPS removed from the driving stack +* 100KB qlogs +* `master-ci` pushed after 1000 hours of hardware-in-the-loop testing +* Car interface code moved into [opendbc](https://github.com/commaai/opendbc) +* openpilot on PC for Linux x86, Linux arm64, and Mac (Apple Silicon) + +## openpilot 1.0 + +openpilot 1.0 will feature a fully end-to-end driving policy. + +* End-to-end longitudinal control in Chill mode +* Automatic Emergency Braking (AEB) +* Driver monitoring with sleep detection +* Rolling updates/releases pushed out by CI +* [panda safety 1.0](https://github.com/orgs/commaai/projects/27) diff --git a/docs/getting-started/what-is-openpilot.md b/docs/getting-started/what-is-openpilot.md new file mode 100644 index 000000000000000..b3c56c8410d8039 --- /dev/null +++ b/docs/getting-started/what-is-openpilot.md @@ -0,0 +1,12 @@ +# What is openpilot? + +[openpilot](http://github.com/commaai/openpilot) is an open source driver assistance system. Currently, openpilot performs the functions of Adaptive Cruise Control (ACC), Automated Lane Centering (ALC), Forward Collision Warning (FCW), and Lane Departure Warning (LDW) for a growing variety of [supported car makes, models, and model years](https://github.com/commaai/openpilot/blob/master/docs/CARS.md). In addition, while openpilot is engaged, a camera-based Driver Monitoring (DM) feature alerts distracted and asleep drivers. See more about [the vehicle integration](https://github.com/commaai/openpilot/blob/master/docs/INTEGRATION.md) and [limitations](https://github.com/commaai/openpilot/blob/master/docs/LIMITATIONS.md). + + +## How do I use it? + +openpilot is designed to be used on the comma 3X. + +## How does it work? + +In short, openpilot uses the car's existing APIs for the built-in [ADAS](https://en.wikipedia.org/wiki/Advanced_driver-assistance_system) system and simply provides better acceleration, braking, and steering inputs than the stock system. diff --git a/docs/how-to/connect-to-comma.md b/docs/how-to/connect-to-comma.md new file mode 100644 index 000000000000000..5797f8618fd8414 --- /dev/null +++ b/docs/how-to/connect-to-comma.md @@ -0,0 +1,79 @@ +# connect to a comma 3/3X + +A comma 3/3X is a normal [Linux](https://github.com/commaai/agnos-builder) computer that exposes [SSH](https://wiki.archlinux.org/title/Secure_Shell) and a [serial console](https://wiki.archlinux.org/title/Working_with_the_serial_console). + +## Serial Console + +On both the comma three and 3X, the serial console is accessible from the main OBD-C port. +Connect the comma 3/3X to your computer with a normal USB C cable, or use a [comma serial](https://comma.ai/shop/comma-serial) for steady 12V power. + +On the comma three, the serial console is exposed through a UART-to-USB chip, and `tools/scripts/serial.sh` can be used to connect. + +On the comma 3X, the serial console is accessible through the [panda](https://github.com/commaai/panda) using the `panda/tests/som_debug.sh` script. + + * Username: `comma` + * Password: `comma` + +## SSH + +In order to SSH into your device, you'll need a GitHub account with SSH keys. See this [GitHub article](https://docs.github.com/en/github/authenticating-to-github/connecting-to-github-with-ssh) for getting your account setup with SSH keys. + +* Enable SSH in your device's settings +* Enter your GitHub username in the device's settings +* Connect to your device + * Username: `comma` + * Port: `22` + +Here's an example command for connecting to your device using its tethered connection:
+`ssh comma@192.168.43.1` + +For doing development work on device, it's recommended to use [SSH agent forwarding](https://docs.github.com/en/developers/overview/using-ssh-agent-forwarding). + +### Notes + +The public keys are only fetched from your GitHub account once. In order to update your device's authorized keys, you'll need to re-enter your GitHub username. + +The `id_rsa` key in this directory only works while your device is in the setup state with no software installed. After installation, that default key will be removed. + +#### ssh.comma.ai proxy + +With a [comma prime subscription](https://comma.ai/connect), you can SSH into your comma device from anywhere. + +With the below SSH configuration, you can type `ssh comma-{dongleid}` to connect to your device through `ssh.comma.ai`. + +``` +Host comma-* + Port 22 + User comma + IdentityFile ~/.ssh/my_github_key + ProxyCommand ssh %h@ssh.comma.ai -W %h:%p + +Host ssh.comma.ai + Hostname ssh.comma.ai + Port 22 + IdentityFile ~/.ssh/my_github_key +``` + +### One-off connection + +``` +ssh -i ~/.ssh/my_github_key -o ProxyCommand="ssh -i ~/.ssh/my_github_key -W %h:%p -p %p %h@ssh.comma.ai" comma@ffffffffffffffff +``` +(Replace `ffffffffffffffff` with your dongle_id) + +### ssh.comma.ai host key fingerprint + +``` +Host key fingerprint is SHA256:X22GOmfjGb9J04IA2+egtdaJ7vW9Fbtmpz9/x8/W1X4 ++---[RSA 4096]----+ +| | +| | +| . | +| + o | +| S = + +..| +| + @ = .=| +| . B @ ++=| +| o * B XE| +| .o o OB/| ++----[SHA256]-----+ +``` diff --git a/docs/how-to/replay-a-drive.md b/docs/how-to/replay-a-drive.md new file mode 100644 index 000000000000000..084b6bf825a785a --- /dev/null +++ b/docs/how-to/replay-a-drive.md @@ -0,0 +1,14 @@ +# Replay + +Replaying is a critical tool for openpilot development and debugging. + +## Replaying a route +*Hardware required: none* + +Just run `tools/replay/replay --demo`. + +## Replaying CAN data +*Hardware required: jungle and comma 3/3X* + +1. Connect your PC to a jungle. +2. diff --git a/docs/how-to/turn-the-speed-blue.md b/docs/how-to/turn-the-speed-blue.md new file mode 100644 index 000000000000000..e8b55ef81b86ca9 --- /dev/null +++ b/docs/how-to/turn-the-speed-blue.md @@ -0,0 +1,98 @@ +# Turn the speed blue +*A getting started guide for openpilot development* + +In 30 minutes, we'll get an openpilot development environment setup on your computer and make some changes to openpilot's UI. + +And if you have a comma 3/3X, we'll deploy the change to your device for testing. + +## 1. Setup your development environment + +Run this to clone openpilot and install all the dependencies: +```bash +bash <(curl -fsSL openpilot.comma.ai) +``` + +Navigate to openpilot folder & activate a Python virtual environment +```bash +cd openpilot +source .venv/bin/activate +``` + +Then, compile openpilot: +```bash +scons -j8 +``` + +## 2. Run replay + +We'll run the `replay` tool with the demo route to get data streaming for testing our UI changes. +```bash +# in terminal 1 +tools/replay/replay --demo + +# in terminal 2 +selfdrive/ui/ui +``` + +The openpilot UI should launch and show a replay of the demo route. + +If you have your own comma device, you can replace `--demo` with one of your own routes from comma connect. + +## 3. Make the speed blue + +Search for “mph” with git grep in the `ui` folder. +```bash +$ git grep "mph" selfdrive/ui/ +paint.cc: ui_draw_text(s, s->fb_w/2, 290, s->scene.is_metric ? "km/h" : "mph", 36 * 2.5, COLOR_WHITE_ALPHA(200), "sans-regular"); +``` + +The line right above contains the actual speed. Unfortunately, COLOR_BLUE isn’t defined, but a git grep of COLOR_WHITE shows it’s nvgRGBA(255, 255, 255, 255). Personally, I like a lighter blue, so I went with #8080FF. +```bash +$ git diff +diff --git a/selfdrive/ui/paint.cc b/selfdrive/ui/paint.cc +index 821d95115..cc996eaa1 100644 +--- a/selfdrive/ui/paint.cc ++++ b/selfdrive/ui/paint.cc +@@ -175,8 +175,8 @@ static void ui_draw_vision_speed(UIState *s) { + const float speed = std::max(0.0, (*s->sm)["carState"].getCarState().getVEgo() * (s->scene.is_metric ? 3.6 : 2.2369363)); + const std::string speed_str = std::to_string((int)std::nearbyint(speed)); + nvgTextAlign(s->vg, NVG_ALIGN_CENTER | NVG_ALIGN_BASELINE); +- ui_draw_text(s, s->fb_w/2, 210, speed_str.c_str(), 96 * 2.5, COLOR_WHITE, "sans-bold"); +- ui_draw_text(s, s->fb_w/2, 290, s->scene.is_metric ? "km/h" : "mph", 36 * 2.5, COLOR_WHITE_ALPHA(200), "sans-regular"); ++ ui_draw_text(s, s->fb_w/2, 210, speed_str.c_str(), 96 * 2.5, nvgRGBA(128, 128, 255, 255), "sans-bold"); ++ ui_draw_text(s, s->fb_w/2, 290, s->scene.is_metric ? "km/h" : "mph", 36 * 2.5, nvgRGBA(128, 128, 255, 200), "sans-regular"); + } + + static void ui_draw_vision_event(UIState *s) { +``` + + +## 4. Rebuild UI, and admire your work + +``` +scons -j8 && selfdrive/ui/ui +``` + +![](https://blog.comma.ai/img/blue_speed_ui.png) + +## 5. Push your fork to GitHub + +Click fork on GitHub. Then, push with: +```bash +git remote rm origin +git remote add origin git@github.com:/openpilot.git +git add . +git commit -m "Make the speed blue." +git push --set-upstream origin master +``` + +## 6. Run your fork on device in your car! + +Uninstall openpilot from your device through the settings. Then, enter the URL for your very own installer: +``` +installer.comma.ai//master +``` + +## 7. Admire your work IRL + +![](https://blog.comma.ai/img/c3_blue_ui.jpg) diff --git a/docs/index.md b/docs/index.md deleted file mode 100644 index 0fb2617a5b74ab5..000000000000000 --- a/docs/index.md +++ /dev/null @@ -1,42 +0,0 @@ -# openpilot Documentation - -```{include} README.md -``` - -```{toctree} -:caption: 'General' -:maxdepth: 4 - -CARS.md -CONTRIBUTING.md -INTEGRATION.md -LIMITATIONS.md -SAFETY.md -``` - -```{toctree} -:caption: 'Overview' -:maxdepth: 2 - -overview.rst -``` - -## API Documentation - -- {ref}`genindex` -- {ref}`modindex` -- {ref}`search` - -```{toctree} -:caption: 'Python API' -:maxdepth: 2 - -modules.rst -``` - -```{toctree} -:caption: 'C/C++ API' -:maxdepth: 4 - -c_docs.rst -``` \ No newline at end of file diff --git a/docs/index.md b/docs/index.md new file mode 120000 index 000000000000000..74ea27aeeb6b72a --- /dev/null +++ b/docs/index.md @@ -0,0 +1 @@ +getting-started/what-is-openpilot.md \ No newline at end of file diff --git a/docs/overview.rst b/docs/overview.rst deleted file mode 100644 index 8c552077f38fc54..000000000000000 --- a/docs/overview.rst +++ /dev/null @@ -1,72 +0,0 @@ -openpilot -========= - -.. toctree:: - :maxdepth: 4 - - Debugging - system/loggerd/README.md - Driver Monitoring - Process Replay - -cereal -========= - -.. toctree:: - :maxdepth: 4 - - cereal/README.md - cereal/messaging/msgq.md - -models -========= - -.. toctree:: - :maxdepth: 4 - - models/README.md - -opendbc -========= - -.. toctree:: - :maxdepth: 4 - - opendbc/README.md - -panda -========= - -.. toctree:: - :maxdepth: 4 - - panda/README.md - panda/UPDATING.md - panda/board/README.md - panda/drivers/linux/README.md - panda/drivers/windows/README.md - - -rednose -========= -.. toctree:: - :maxdepth: 4 - - rednose_repo/README.md - - -tools -========= -.. toctree:: - :maxdepth: 4 - - tools/CTF.md - tools/joystick/README.md - tools/lib/README.md - tools/plotjuggler/README.md - tools/replay/README.md - tools/serial/README.md - Simulator - tools/ssh/README.md - Webcam - tools/cabana/README.md diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh index 9256f463af7e17e..442a811b1606032 100755 --- a/launch_chffrplus.sh +++ b/launch_chffrplus.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash if [ -z "$BASEDIR" ]; then BASEDIR="/data/openpilot" diff --git a/launch_env.sh b/launch_env.sh index 81578aff0157e3a..781f40fc7e960db 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash export OMP_NUM_THREADS=1 export MKL_NUM_THREADS=1 @@ -7,7 +7,7 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="10.1" + export AGNOS_VERSION="11.2" fi export STAGING_ROOT="/data/safe_staging" diff --git a/launch_openpilot.sh b/launch_openpilot.sh index 2888814c2234994..d6e3424c348bf5c 100755 --- a/launch_openpilot.sh +++ b/launch_openpilot.sh @@ -1,3 +1,3 @@ -#!/usr/bin/bash +#!/usr/bin/env bash exec ./launch_chffrplus.sh diff --git a/mkdocs.yml b/mkdocs.yml new file mode 100644 index 000000000000000..58527ea7ee021d5 --- /dev/null +++ b/mkdocs.yml @@ -0,0 +1,40 @@ +site_name: openpilot docs +repo_url: https://github.com/commaai/openpilot/ +site_url: https://docs.comma.ai + +exclude_docs: README.md + +strict: true +docs_dir: docs +site_dir: docs_site/ + +theme: + name: readthedocs + navigation_depth: 3 + +nav: + - Getting Started: + - What is openpilot?: getting-started/what-is-openpilot.md + - How-to: + - Turn the speed blue: how-to/turn-the-speed-blue.md + - Connect to a comma 3/3X: how-to/connect-to-comma.md + # - Make your first pull request: how-to/make-first-pr.md + #- Replay a drive: how-to/replay-a-drive.md + - Concepts: + - Logs: concepts/logs.md + - Safety: concepts/safety.md + - Glossary: concepts/glossary.md + - Car Porting: + - What is a car port?: car-porting/what-is-a-car-port.md + - Porting a car brand: car-porting/brand-port.md + - Porting a car model: car-porting/model-port.md + - Contributing: + - Roadmap: contributing/roadmap.md + #- Architecture: contributing/architecture.md + - Contributing Guide →: https://github.com/commaai/openpilot/blob/master/docs/CONTRIBUTING.md + - Links: + - Blog →: https://blog.comma.ai + - Bounties →: https://comma.ai/bounties + - GitHub →: https://github.com/commaai + - Discord →: https://discord.comma.ai + - X →: https://x.com/comma_ai diff --git a/msgq_repo/.gitignore b/msgq_repo/.gitignore index 6db3c7cd4673d05..0113da49a4a23ec 100644 --- a/msgq_repo/.gitignore +++ b/msgq_repo/.gitignore @@ -15,5 +15,4 @@ libmessaging.* libmessaging_shared.* services.h .sconsign.dblite -libcereal_shared.* .mypy_cache/ diff --git a/msgq_repo/SConstruct b/msgq_repo/SConstruct index c1e7fc52179ec10..476672be5c187a9 100644 --- a/msgq_repo/SConstruct +++ b/msgq_repo/SConstruct @@ -61,6 +61,7 @@ env = Environment( "-Werror", "-Wshadow", "-Wno-vla-cxx-extension", + "-Wno-unknown-warning-option", ] + ccflags, LDFLAGS=ldflags, LINKFLAGS=ldflags, diff --git a/msgq_repo/msgq/msgq.cc b/msgq_repo/msgq/msgq.cc index fed2959bd3b734d..5ce25a3bc2a97cc 100644 --- a/msgq_repo/msgq/msgq.cc +++ b/msgq_repo/msgq/msgq.cc @@ -108,7 +108,7 @@ int msgq_new_queue(msgq_queue_t * q, const char * path, size_t size){ char * mem = (char*)mmap(NULL, size + sizeof(msgq_header_t), PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0); close(fd); - if (mem == NULL){ + if (mem == MAP_FAILED){ return -1; } q->mmap_p = mem; diff --git a/msgq_repo/msgq/tests/test_fake.py b/msgq_repo/msgq/tests/test_fake.py index b5ed297ab1ba236..d2c51313ccf7e62 100644 --- a/msgq_repo/msgq/tests/test_fake.py +++ b/msgq_repo/msgq/tests/test_fake.py @@ -1,5 +1,5 @@ +import pytest import os -import unittest import multiprocessing import platform import msgq @@ -9,18 +9,18 @@ WAIT_TIMEOUT = 5 -@unittest.skipIf(platform.system() == "Darwin", "Events not supported on macOS") -class TestEvents(unittest.TestCase): +@pytest.mark.skipif(condition=platform.system() == "Darwin", reason="Events not supported on macOS") +class TestEvents: def test_mutation(self): handle = msgq.fake_event_handle("carState") event = handle.recv_called_event - self.assertFalse(event.peek()) + assert not event.peek() event.set() - self.assertTrue(event.peek()) + assert event.peek() event.clear() - self.assertFalse(event.peek()) + assert not event.peek() del event @@ -31,9 +31,9 @@ def test_wait(self): event.set() try: event.wait(WAIT_TIMEOUT) - self.assertTrue(event.peek()) + assert event.peek() except RuntimeError: - self.fail("event.wait() timed out") + pytest.fail("event.wait() timed out") def test_wait_multiprocess(self): handle = msgq.fake_event_handle("carState") @@ -46,9 +46,9 @@ def set_event_run(): p = multiprocessing.Process(target=set_event_run) p.start() event.wait(WAIT_TIMEOUT) - self.assertTrue(event.peek()) + assert event.peek() except RuntimeError: - self.fail("event.wait() timed out") + pytest.fail("event.wait() timed out") p.kill() @@ -58,34 +58,34 @@ def test_wait_zero_timeout(self): try: event.wait(0) - self.fail("event.wait() did not time out") + pytest.fail("event.wait() did not time out") except RuntimeError: - self.assertFalse(event.peek()) + assert not event.peek() -@unittest.skipIf(platform.system() == "Darwin", "FakeSockets not supported on macOS") -@unittest.skipIf("ZMQ" in os.environ, "FakeSockets not supported on ZMQ") +@pytest.mark.skipif(condition=platform.system() == "Darwin", reason="FakeSockets not supported on macOS") +@pytest.mark.skipif(condition="ZMQ" in os.environ, reason="FakeSockets not supported on ZMQ") @parameterized_class([{"prefix": None}, {"prefix": "test"}]) -class TestFakeSockets(unittest.TestCase): +class TestFakeSockets: prefix: Optional[str] = None - def setUp(self): + def setup_method(self): msgq.toggle_fake_events(True) if self.prefix is not None: msgq.set_fake_prefix(self.prefix) else: msgq.delete_fake_prefix() - def tearDown(self): + def teardown_method(self): msgq.toggle_fake_events(False) msgq.delete_fake_prefix() def test_event_handle_init(self): handle = msgq.fake_event_handle("controlsState", override=True) - self.assertFalse(handle.enabled) - self.assertGreaterEqual(handle.recv_called_event.fd, 0) - self.assertGreaterEqual(handle.recv_ready_event.fd, 0) + assert not handle.enabled + assert handle.recv_called_event.fd >= 0 + assert handle.recv_ready_event.fd >= 0 def test_non_managed_socket_state(self): # non managed socket should have zero state @@ -93,9 +93,9 @@ def test_non_managed_socket_state(self): handle = msgq.fake_event_handle("ubloxGnss", override=False) - self.assertFalse(handle.enabled) - self.assertEqual(handle.recv_called_event.fd, 0) - self.assertEqual(handle.recv_ready_event.fd, 0) + assert not handle.enabled + assert handle.recv_called_event.fd == 0 + assert handle.recv_ready_event.fd == 0 def test_managed_socket_state(self): # managed socket should not change anything about the state @@ -108,9 +108,9 @@ def test_managed_socket_state(self): _ = msgq.pub_sock("ubloxGnss") - self.assertEqual(handle.enabled, expected_enabled) - self.assertEqual(handle.recv_called_event.fd, expected_recv_called_fd) - self.assertEqual(handle.recv_ready_event.fd, expected_recv_ready_fd) + assert handle.enabled == expected_enabled + assert handle.recv_called_event.fd == expected_recv_called_fd + assert handle.recv_ready_event.fd == expected_recv_ready_fd def test_sockets_enable_disable(self): carState_handle = msgq.fake_event_handle("ubloxGnss", enable=True) @@ -125,16 +125,16 @@ def test_sockets_enable_disable(self): recv_ready.set() pub_sock.send(b"test") _ = sub_sock.receive() - self.assertTrue(recv_called.peek()) + assert recv_called.peek() recv_called.clear() carState_handle.enabled = False recv_ready.set() pub_sock.send(b"test") _ = sub_sock.receive() - self.assertFalse(recv_called.peek()) + assert not recv_called.peek() except RuntimeError: - self.fail("event.wait() timed out") + pytest.fail("event.wait() timed out") def test_synced_pub_sub(self): def daemon_repub_process_run(): @@ -177,16 +177,12 @@ def daemon_repub_process_run(): recv_called.wait(WAIT_TIMEOUT) msg = sub_sock.receive(non_blocking=True) - self.assertIsNotNone(msg) - self.assertEqual(len(msg), 8) + assert msg is not None + assert len(msg) == 8 frame = int.from_bytes(msg, 'little') - self.assertEqual(frame, i) + assert frame == i except RuntimeError: - self.fail("event.wait() timed out") + pytest.fail("event.wait() timed out") finally: p.kill() - - -if __name__ == "__main__": - unittest.main() diff --git a/msgq_repo/msgq/tests/test_messaging.py b/msgq_repo/msgq/tests/test_messaging.py old mode 100755 new mode 100644 index bbeeb3d848b528b..40dfd7f00ef0ea6 --- a/msgq_repo/msgq/tests/test_messaging.py +++ b/msgq_repo/msgq/tests/test_messaging.py @@ -1,10 +1,7 @@ -#!/usr/bin/env python3 import os import random -import threading import time import string -import unittest import msgq @@ -18,20 +15,9 @@ def zmq_sleep(t=1): if "ZMQ" in os.environ: time.sleep(t) -def zmq_expected_failure(func): - if "ZMQ" in os.environ: - return unittest.expectedFailure(func) - else: - return func - -def delayed_send(delay, sock, dat): - def send_func(): - sock.send(dat) - threading.Timer(delay, send_func).start() - -class TestPubSubSockets(unittest.TestCase): +class TestPubSubSockets: - def setUp(self): + def setup_method(self): # ZMQ pub socket takes too long to die # sleep to prevent multiple publishers error between tests zmq_sleep() @@ -46,7 +32,7 @@ def test_pub_sub(self): msg = random_bytes() pub_sock.send(msg) recvd = sub_sock.receive() - self.assertEqual(msg, recvd) + assert msg == recvd def test_conflate(self): sock = random_sock() @@ -65,10 +51,10 @@ def test_conflate(self): time.sleep(0.1) recvd_msgs = msgq.drain_sock_raw(sub_sock) if conflate: - self.assertEqual(len(recvd_msgs), 1) + assert len(recvd_msgs) == 1 else: # TODO: compare actual data - self.assertEqual(len(recvd_msgs), len(sent_msgs)) + assert len(recvd_msgs) == len(sent_msgs) def test_receive_timeout(self): sock = random_sock() @@ -79,9 +65,5 @@ def test_receive_timeout(self): start_time = time.monotonic() recvd = sub_sock.receive() - self.assertLess(time.monotonic() - start_time, 0.2) + assert (time.monotonic() - start_time) < 0.2 assert recvd is None - - -if __name__ == "__main__": - unittest.main() diff --git a/msgq_repo/msgq/tests/test_poller.py b/msgq_repo/msgq/tests/test_poller.py index a68ff4fe7d26e7a..6ef2c0423ed84ad 100644 --- a/msgq_repo/msgq/tests/test_poller.py +++ b/msgq_repo/msgq/tests/test_poller.py @@ -1,4 +1,4 @@ -import unittest +import pytest import time import msgq import concurrent.futures @@ -20,7 +20,7 @@ def poller(): return r -class TestPoller(unittest.TestCase): +class TestPoller: def test_poll_once(self): context = msgq.Context() @@ -41,7 +41,7 @@ def test_poll_once(self): del pub context.term() - self.assertEqual(result, [b"a"]) + assert result == [b"a"] def test_poll_and_create_many_subscribers(self): context = msgq.Context() @@ -68,12 +68,12 @@ def test_poll_and_create_many_subscribers(self): del pub context.term() - self.assertEqual(result, [b"a"]) + assert result == [b"a"] def test_multiple_publishers_exception(self): context = msgq.Context() - with self.assertRaises(msgq.MultiplePublishersError): + with pytest.raises(msgq.MultiplePublishersError): pub1 = msgq.PubSocket() pub1.connect(context, SERVICE_NAME) @@ -106,7 +106,7 @@ def test_multiple_messages(self): r = sub.receive(non_blocking=True) if r is not None: - self.assertEqual(b'a'*i, r) + assert b'a'*i == r msg_seen = True i += 1 @@ -131,12 +131,8 @@ def test_conflate(self): pub.send(b'a') pub.send(b'b') - self.assertEqual(b'b', sub.receive()) + assert b'b' == sub.receive() del pub del sub context.term() - - -if __name__ == "__main__": - unittest.main() diff --git a/msgq_repo/msgq/visionipc/tests/test_visionipc.py b/msgq_repo/msgq/visionipc/tests/test_visionipc.py old mode 100755 new mode 100644 index 1c34613ddec1e49..077a9aead43ca91 --- a/msgq_repo/msgq/visionipc/tests/test_visionipc.py +++ b/msgq_repo/msgq/visionipc/tests/test_visionipc.py @@ -1,8 +1,6 @@ -#!/usr/bin/env python3 import os import time import random -import unittest import numpy as np from msgq.visionipc import VisionIpcServer, VisionIpcClient, VisionStreamType @@ -11,17 +9,17 @@ def zmq_sleep(t=1): time.sleep(t) -class TestVisionIpc(unittest.TestCase): +class TestVisionIpc: - def setup_vipc(self, name, *stream_types, num_buffers=1, rgb=False, width=100, height=100, conflate=False): + def setup_vipc(self, name, *stream_types, num_buffers=1, width=100, height=100, conflate=False): self.server = VisionIpcServer(name) for stream_type in stream_types: - self.server.create_buffers(stream_type, num_buffers, rgb, width, height) + self.server.create_buffers(stream_type, num_buffers, width, height) self.server.start_listener() if len(stream_types): self.client = VisionIpcClient(name, stream_types[0], conflate) - self.assertTrue(self.client.connect(True)) + assert self.client.connect(True) else: self.client = None @@ -30,28 +28,28 @@ def setup_vipc(self, name, *stream_types, num_buffers=1, rgb=False, width=100, h def test_connect(self): self.setup_vipc("camerad", VisionStreamType.VISION_STREAM_ROAD) - self.assertTrue(self.client.is_connected) + assert self.client.is_connected + del self.client + del self.server def test_available_streams(self): for k in range(4): stream_types = set(random.choices([x.value for x in VisionStreamType], k=k)) self.setup_vipc("camerad", *stream_types) available_streams = VisionIpcClient.available_streams("camerad", True) - self.assertEqual(available_streams, stream_types) + assert available_streams == stream_types + del self.client + del self.server def test_buffers(self): width, height, num_buffers = 100, 200, 5 self.setup_vipc("camerad", VisionStreamType.VISION_STREAM_ROAD, num_buffers=num_buffers, width=width, height=height) - self.assertEqual(self.client.width, width) - self.assertEqual(self.client.height, height) - self.assertGreater(self.client.buffer_len, 0) - self.assertEqual(self.client.num_buffers, num_buffers) - - def test_yuv_rgb(self): - _, client_yuv = self.setup_vipc("camerad", VisionStreamType.VISION_STREAM_ROAD, rgb=False) - _, client_rgb = self.setup_vipc("navd", VisionStreamType.VISION_STREAM_MAP, rgb=True) - self.assertTrue(client_rgb.rgb) - self.assertFalse(client_yuv.rgb) + assert self.client.width == width + assert self.client.height == height + assert self.client.buffer_len > 0 + assert self.client.num_buffers == num_buffers + del self.client + del self.server def test_send_single_buffer(self): self.setup_vipc("camerad", VisionStreamType.VISION_STREAM_ROAD) @@ -61,9 +59,11 @@ def test_send_single_buffer(self): self.server.send(VisionStreamType.VISION_STREAM_ROAD, buf, frame_id=1337) recv_buf = self.client.recv() - self.assertIsNot(recv_buf, None) - self.assertEqual(recv_buf.data.view('rgb = true; - this->width = init_width; - this->height = init_height; - this->stride = init_stride; -} - void VisionBuf::init_yuv(size_t init_width, size_t init_height, size_t init_stride, size_t init_uv_offset){ - this->rgb = false; this->width = init_width; this->height = init_height; this->stride = init_stride; diff --git a/msgq_repo/msgq/visionipc/visionbuf.h b/msgq_repo/msgq/visionipc/visionbuf.h index 6b678a00419208b..52345ba08a09846 100644 --- a/msgq_repo/msgq/visionipc/visionbuf.h +++ b/msgq_repo/msgq/visionipc/visionbuf.h @@ -29,7 +29,6 @@ class VisionBuf { uint64_t *frame_id; int fd = 0; - bool rgb = false; size_t width = 0; size_t height = 0; size_t stride = 0; @@ -54,7 +53,6 @@ class VisionBuf { void allocate(size_t len); void import(); void init_cl(cl_device_id device_id, cl_context ctx); - void init_rgb(size_t width, size_t height, size_t stride); void init_yuv(size_t width, size_t height, size_t stride, size_t uv_offset); int sync(int dir); int free(); @@ -62,5 +60,3 @@ class VisionBuf { void set_frame_id(uint64_t id); uint64_t get_frame_id(); }; - -void visionbuf_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h); diff --git a/msgq_repo/msgq/visionipc/visionbuf_cl.cc b/msgq_repo/msgq/visionipc/visionbuf_cl.cc index db7df00dc1b373d..db1ca033479cc84 100644 --- a/msgq_repo/msgq/visionipc/visionbuf_cl.cc +++ b/msgq_repo/msgq/visionipc/visionbuf_cl.cc @@ -86,7 +86,7 @@ int VisionBuf::free() { if (err != 0) return err; } - err = munmap(this->addr, this->len); + err = munmap(this->addr, this->mmap_len); if (err != 0) return err; err = close(this->fd); diff --git a/msgq_repo/msgq/visionipc/visionipc.pxd b/msgq_repo/msgq/visionipc/visionipc.pxd index 645ab2208ffec4f..3716546fe652190 100644 --- a/msgq_repo/msgq/visionipc/visionipc.pxd +++ b/msgq_repo/msgq/visionipc/visionipc.pxd @@ -21,7 +21,6 @@ cdef extern from "msgq/visionipc/visionbuf.h": cdef cppclass VisionBuf: void * addr - bool rgb size_t len size_t width size_t height @@ -42,8 +41,8 @@ cdef extern from "msgq/visionipc/visionipc_server.h": cdef cppclass VisionIpcServer: VisionIpcServer(string, void*, void*) - void create_buffers(VisionStreamType, size_t, bool, size_t, size_t) - void create_buffers_with_sizes(VisionStreamType, size_t, bool, size_t, size_t, size_t, size_t, size_t) + void create_buffers(VisionStreamType, size_t, size_t, size_t) + void create_buffers_with_sizes(VisionStreamType, size_t, size_t, size_t, size_t, size_t, size_t) VisionBuf * get_buffer(VisionStreamType) void send(VisionBuf *, VisionIpcBufExtra *, bool) void start_listener() diff --git a/msgq_repo/msgq/visionipc/visionipc_client.cc b/msgq_repo/msgq/visionipc/visionipc_client.cc index 9b24da296db9ca5..9174044cd4d078d 100644 --- a/msgq_repo/msgq/visionipc/visionipc_client.cc +++ b/msgq_repo/msgq/visionipc/visionipc_client.cc @@ -63,11 +63,7 @@ bool VisionIpcClient::connect(bool blocking){ buffers[i] = bufs[i]; buffers[i].fd = fds[i]; buffers[i].import(); - if (buffers[i].rgb) { - buffers[i].init_rgb(buffers[i].width, buffers[i].height, buffers[i].stride); - } else { - buffers[i].init_yuv(buffers[i].width, buffers[i].height, buffers[i].stride, buffers[i].uv_offset); - } + buffers[i].init_yuv(buffers[i].width, buffers[i].height, buffers[i].stride, buffers[i].uv_offset); if (device_id) buffers[i].init_cl(device_id, ctx); } diff --git a/msgq_repo/msgq/visionipc/visionipc_pyx.pyx b/msgq_repo/msgq/visionipc/visionipc_pyx.pyx index 0ff270efd54dbde..7f8eadb67d34cfa 100644 --- a/msgq_repo/msgq/visionipc/visionipc_pyx.pyx +++ b/msgq_repo/msgq/visionipc/visionipc_pyx.pyx @@ -55,10 +55,6 @@ cdef class VisionBuf: def uv_offset(self): return self.buf.uv_offset - @property - def rgb(self): - return self.buf.rgb - cdef class VisionIpcServer: cdef cppVisionIpcServer * server @@ -66,11 +62,11 @@ cdef class VisionIpcServer: def __init__(self, string name): self.server = new cppVisionIpcServer(name, NULL, NULL) - def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): - self.server.create_buffers(tp, num_buffers, rgb, width, height) + def create_buffers(self, VisionStreamType tp, size_t num_buffers, size_t width, size_t height): + self.server.create_buffers(tp, num_buffers, width, height) - def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): - self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): + self.server.create_buffers_with_sizes(tp, num_buffers, width, height, size, stride, uv_offset) def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): cdef cppVisionBuf * buf = self.server.get_buffer(tp) @@ -123,10 +119,6 @@ cdef class VisionIpcClient: def uv_offset(self): return self.client.buffers[0].uv_offset if self.client.num_buffers else None - @property - def rgb(self): - return self.client.buffers[0].rgb if self.client.num_buffers else None - @property def buffer_len(self): return self.client.buffers[0].len if self.client.num_buffers else None diff --git a/msgq_repo/msgq/visionipc/visionipc_server.cc b/msgq_repo/msgq/visionipc/visionipc_server.cc index 611d10b2060955d..5f80d01c08f42a4 100644 --- a/msgq_repo/msgq/visionipc/visionipc_server.cc +++ b/msgq_repo/msgq/visionipc/visionipc_server.cc @@ -38,29 +38,22 @@ VisionIpcServer::VisionIpcServer(std::string name, cl_device_id device_id, cl_co server_id = distribution(rd); } -void VisionIpcServer::create_buffers(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height){ +void VisionIpcServer::create_buffers(VisionStreamType type, size_t num_buffers, size_t width, size_t height){ // TODO: assert that this type is not created yet assert(num_buffers < VISIONIPC_MAX_FDS); - int aligned_w = 0, aligned_h = 0; size_t size = 0; size_t stride = 0; size_t uv_offset = 0; - if (rgb) { - visionbuf_compute_aligned_width_and_height(width, height, &aligned_w, &aligned_h); - size = (size_t)aligned_w * (size_t)aligned_h * 3; - stride = aligned_w * 3; - } else { - size = width * height * 3 / 2; - stride = width; - uv_offset = width * height; - } + size = width * height * 3 / 2; + stride = width; + uv_offset = width * height; - create_buffers_with_sizes(type, num_buffers, rgb, width, height, size, stride, uv_offset); + create_buffers_with_sizes(type, num_buffers, width, height, size, stride, uv_offset); } -void VisionIpcServer::create_buffers_with_sizes(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset) { +void VisionIpcServer::create_buffers_with_sizes(VisionStreamType type, size_t num_buffers, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset) { // Create map + alloc requested buffers for (size_t i = 0; i < num_buffers; i++){ VisionBuf* buf = new VisionBuf(); @@ -70,7 +63,7 @@ void VisionIpcServer::create_buffers_with_sizes(VisionStreamType type, size_t nu if (device_id) buf->init_cl(device_id, ctx); - rgb ? buf->init_rgb(width, height, stride) : buf->init_yuv(width, height, stride, uv_offset); + buf->init_yuv(width, height, stride, uv_offset); buffers[type].push_back(buf); } @@ -167,11 +160,17 @@ void VisionIpcServer::listener(){ -VisionBuf * VisionIpcServer::get_buffer(VisionStreamType type){ +VisionBuf * VisionIpcServer::get_buffer(VisionStreamType type, int idx){ // Do we want to keep track if the buffer has been sent out yet and warn user? assert(buffers.count(type)); auto b = buffers[type]; - return b[cur_idx[type]++ % b.size()]; + if (idx < 0) { + idx = cur_idx[type]++ % b.size(); + } else { + assert(idx < b.size() && idx >= 0); + cur_idx[type] = idx; + } + return b[idx]; } void VisionIpcServer::send(VisionBuf * buf, VisionIpcBufExtra * extra, bool sync){ diff --git a/msgq_repo/msgq/visionipc/visionipc_server.h b/msgq_repo/msgq/visionipc/visionipc_server.h index feacc4d10d3309f..b96f49848535278 100644 --- a/msgq_repo/msgq/visionipc/visionipc_server.h +++ b/msgq_repo/msgq/visionipc/visionipc_server.h @@ -33,10 +33,10 @@ class VisionIpcServer { VisionIpcServer(std::string name, cl_device_id device_id=nullptr, cl_context ctx=nullptr); ~VisionIpcServer(); - VisionBuf * get_buffer(VisionStreamType type); + VisionBuf * get_buffer(VisionStreamType type, int idx = -1); - void create_buffers(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height); - void create_buffers_with_sizes(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset); + void create_buffers(VisionStreamType type, size_t num_buffers, size_t width, size_t height); + void create_buffers_with_sizes(VisionStreamType type, size_t num_buffers, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset); void send(VisionBuf * buf, VisionIpcBufExtra * extra, bool sync=true); void start_listener(); }; diff --git a/msgq_repo/msgq/visionipc/visionipc_tests.cc b/msgq_repo/msgq/visionipc/visionipc_tests.cc index 8c4e7fa3fcced53..ddf790df7614186 100644 --- a/msgq_repo/msgq/visionipc/visionipc_tests.cc +++ b/msgq_repo/msgq/visionipc/visionipc_tests.cc @@ -15,7 +15,7 @@ static void zmq_sleep(int milliseconds=1000){ TEST_CASE("Connecting"){ VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, false, 100, 100); + server.create_buffers(VISION_STREAM_ROAD, 1, 100, 100); server.start_listener(); VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); @@ -26,8 +26,8 @@ TEST_CASE("Connecting"){ TEST_CASE("getAvailableStreams"){ VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, false, 100, 100); - server.create_buffers(VISION_STREAM_WIDE_ROAD, 1, false, 100, 100); + server.create_buffers(VISION_STREAM_ROAD, 1, 100, 100); + server.create_buffers(VISION_STREAM_WIDE_ROAD, 1, 100, 100); server.start_listener(); auto available_streams = VisionIpcClient::getAvailableStreams("camerad"); REQUIRE(available_streams.size() == 2); @@ -38,7 +38,7 @@ TEST_CASE("getAvailableStreams"){ TEST_CASE("Check buffers"){ size_t width = 100, height = 200, num_buffers = 5; VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, num_buffers, false, width, height); + server.create_buffers(VISION_STREAM_ROAD, num_buffers, width, height); server.start_listener(); VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); @@ -50,24 +50,9 @@ TEST_CASE("Check buffers"){ REQUIRE(client.num_buffers == num_buffers); } -TEST_CASE("Check yuv/rgb"){ - VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, false, 100, 100); - server.create_buffers(VISION_STREAM_MAP, 1, true, 100, 100); - server.start_listener(); - - VisionIpcClient client_yuv = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); - VisionIpcClient client_rgb = VisionIpcClient("camerad", VISION_STREAM_MAP, false); - client_yuv.connect(); - client_rgb.connect(); - - REQUIRE(client_rgb.buffers[0].rgb == true); - REQUIRE(client_yuv.buffers[0].rgb == false); -} - TEST_CASE("Send single buffer"){ VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, true, 100, 100); + server.create_buffers(VISION_STREAM_ROAD, 1, 100, 100); server.start_listener(); VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); @@ -96,7 +81,7 @@ TEST_CASE("Send single buffer"){ TEST_CASE("Test no conflate"){ VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, true, 100, 100); + server.create_buffers(VISION_STREAM_ROAD, 1, 100, 100); server.start_listener(); VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); @@ -124,7 +109,7 @@ TEST_CASE("Test no conflate"){ TEST_CASE("Test conflate"){ VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, true, 100, 100); + server.create_buffers(VISION_STREAM_ROAD, 1, 100, 100); server.start_listener(); VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, true); diff --git a/msgq_repo/pyproject.toml b/msgq_repo/pyproject.toml index 73928614eb7b347..87fb21b84c8505d 100644 --- a/msgq_repo/pyproject.toml +++ b/msgq_repo/pyproject.toml @@ -7,7 +7,11 @@ lint.flake8-implicit-str-concat.allow-multiline=false line-length = 160 target-version="py311" -[mypy.tool] +[tool.ruff.lint.flake8-tidy-imports.banned-api] +"pytest.main".msg = "pytest.main requires special handling that is easy to mess up!" +"unittest".msg = "Use pytest" + +[tool.mypy] # third-party packages ignore_missing_imports=true @@ -19,3 +23,10 @@ warn_unused_ignores=true # restrict dynamic typing warn_return_any=true check_untyped_defs=true + +[tool.pytest.ini_options] +addopts = "--durations=10" +testpaths = [ + "msgq/tests", + "msgq/visionipc/tests", +] diff --git a/opendbc b/opendbc new file mode 120000 index 000000000000000..7cd9a5bd1ebf2e9 --- /dev/null +++ b/opendbc @@ -0,0 +1 @@ +opendbc_repo/opendbc \ No newline at end of file diff --git a/opendbc/.gitignore b/opendbc/.gitignore deleted file mode 100644 index d5c2eb4a3b2265b..000000000000000 --- a/opendbc/.gitignore +++ /dev/null @@ -1,18 +0,0 @@ -.mypy_cache/ -*.pyc -*.os -*.o -*.tmp -*.dylib -.*.swp -.DS_Store -.sconsign.dblite - -can/*.so -can/*.a -can/build/ -can/obj/ -can/packer_pyx.cpp -can/parser_pyx.cpp -can/packer_pyx.html -can/parser_pyx.html diff --git a/opendbc/SConstruct b/opendbc/SConstruct deleted file mode 100644 index 34e3061e78aac24..000000000000000 --- a/opendbc/SConstruct +++ /dev/null @@ -1,85 +0,0 @@ -import os -import subprocess -import sysconfig -import numpy as np - -zmq = 'zmq' -arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() - -cereal_dir = Dir('.') - -python_path = sysconfig.get_paths()['include'] -cpppath = [ - '#', - '/usr/lib/include', - python_path -] - -AddOption('--minimal', - action='store_false', - dest='extras', - default=True, - help='the minimum build. no tests, tools, etc.') - -AddOption('--asan', - action='store_true', - help='turn on ASAN') - -ccflags_asan = ["-fsanitize=address", "-fno-omit-frame-pointer"] if GetOption('asan') else [] -ldflags_asan = ["-fsanitize=address"] if GetOption('asan') else [] - -env = Environment( - ENV=os.environ, - CC='clang', - CXX='clang++', - CCFLAGS=[ - "-g", - "-fPIC", - "-O2", - "-Wunused", - "-Werror", - "-Wshadow", - "-Wno-vla-cxx-extension", - ] + ccflags_asan, - LDFLAGS=ldflags_asan, - LINKFLAGS=ldflags_asan, - LIBPATH=[ - "#opendbc/can/", - ], - CFLAGS="-std=gnu11", - CXXFLAGS=["-std=c++1z"], - CPPPATH=cpppath, - CYTHONCFILESUFFIX=".cpp", - tools=["default", "cython"] -) - -common = '' -Export('env', 'zmq', 'arch', 'common') - -cereal = [File('#cereal/libcereal.a')] -messaging = [File('#cereal/libmessaging.a')] -Export('cereal', 'messaging') - - -envCython = env.Clone() -envCython["CPPPATH"] += [np.get_include()] -envCython["CCFLAGS"] += ["-Wno-#warnings", "-Wno-shadow", "-Wno-deprecated-declarations"] -envCython["CCFLAGS"].remove("-Werror") - -python_libs = [] -if arch == "Darwin": - envCython["LINKFLAGS"] = ["-bundle", "-undefined", "dynamic_lookup"] -elif arch == "aarch64": - envCython["LINKFLAGS"] = ["-shared"] - - python_libs.append(os.path.basename(python_path)) -else: - envCython["LINKFLAGS"] = ["-pthread", "-shared"] - -envCython["LIBS"] = python_libs - -Export('envCython') - - -SConscript(['cereal/SConscript']) -SConscript(['opendbc/can/SConscript']) diff --git a/opendbc/__init__.py b/opendbc/__init__.py deleted file mode 100644 index a74a06029ff1918..000000000000000 --- a/opendbc/__init__.py +++ /dev/null @@ -1,2 +0,0 @@ -import os -DBC_PATH = os.path.dirname(os.path.abspath(__file__)) diff --git a/opendbc/can/SConscript b/opendbc/can/SConscript deleted file mode 100644 index 7e8fd270f6da04f..000000000000000 --- a/opendbc/can/SConscript +++ /dev/null @@ -1,28 +0,0 @@ -Import('env', 'envCython', 'cereal', 'common') - -import os - -envDBC = env.Clone() -dbc_file_path = '-DDBC_FILE_PATH=\'"%s"\'' % (envDBC.Dir("..").abspath) -envDBC['CXXFLAGS'] += [dbc_file_path] -src = ["dbc.cc", "parser.cc", "packer.cc", "common.cc"] -libs = [common, "capnp", "kj", "zmq"] - -# shared library for openpilot -libdbc = envDBC.SharedLibrary('libdbc', src, LIBS=libs) - -# static library for tools like cabana -envDBC.Library('libdbc_static', src, LIBS=libs) - -# Build packer and parser -lenv = envCython.Clone() -lenv["LINKFLAGS"] += [libdbc[0].get_labspath()] -parser = lenv.Program('parser_pyx.so', 'parser_pyx.pyx') -packer = lenv.Program('packer_pyx.so', 'packer_pyx.pyx') - -lenv.Depends(parser, libdbc) -lenv.Depends(packer, libdbc) - -opendbc_python = Alias("opendbc_python", [parser, packer]) - -Export('opendbc_python') \ No newline at end of file diff --git a/opendbc/can/common.cc b/opendbc/can/common.cc deleted file mode 100644 index bb7b2ee56d6985f..000000000000000 --- a/opendbc/can/common.cc +++ /dev/null @@ -1,250 +0,0 @@ -#include "opendbc/can/common.h" - - -unsigned int honda_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - int s = 0; - bool extended = address > 0x7FF; - while (address) { s += (address & 0xF); address >>= 4; } - for (int i = 0; i < d.size(); i++) { - uint8_t x = d[i]; - if (i == d.size()-1) x >>= 4; // remove checksum - s += (x & 0xF) + (x >> 4); - } - s = 8-s; - if (extended) s += 3; // extended can - - return s & 0xF; -} - -unsigned int toyota_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - unsigned int s = d.size(); - while (address) { s += address & 0xFF; address >>= 8; } - for (int i = 0; i < d.size() - 1; i++) { s += d[i]; } - - return s & 0xFF; -} - -unsigned int subaru_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - unsigned int s = 0; - while (address) { s += address & 0xFF; address >>= 8; } - - // skip checksum in first byte - for (int i = 1; i < d.size(); i++) { s += d[i]; } - - return s & 0xFF; -} - -unsigned int chrysler_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - // jeep chrysler canbus checksum from http://illmatics.com/Remote%20Car%20Hacking.pdf - uint8_t checksum = 0xFF; - for (int j = 0; j < (d.size() - 1); j++) { - uint8_t shift = 0x80; - uint8_t curr = d[j]; - for (int i = 0; i < 8; i++) { - uint8_t bit_sum = curr & shift; - uint8_t temp_chk = checksum & 0x80U; - if (bit_sum != 0U) { - bit_sum = 0x1C; - if (temp_chk != 0U) { - bit_sum = 1; - } - checksum = checksum << 1; - temp_chk = checksum | 1U; - bit_sum ^= temp_chk; - } else { - if (temp_chk != 0U) { - bit_sum = 0x1D; - } - checksum = checksum << 1; - bit_sum ^= checksum; - } - checksum = bit_sum; - shift = shift >> 1; - } - } - return ~checksum & 0xFF; -} - -// Static lookup table for fast computation of CRCs -uint8_t crc8_lut_8h2f[256]; // CRC8 poly 0x2F, aka 8H2F/AUTOSAR -uint16_t crc16_lut_xmodem[256]; // CRC16 poly 0x1021, aka XMODEM - -void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]) { - uint8_t crc; - int i, j; - - for (i = 0; i < 256; i++) { - crc = i; - for (j = 0; j < 8; j++) { - if ((crc & 0x80) != 0) - crc = (uint8_t)((crc << 1) ^ poly); - else - crc <<= 1; - } - crc_lut[i] = crc; - } -} - -void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) { - uint16_t crc; - int i, j; - - for (i = 0; i < 256; i++) { - crc = i << 8; - for (j = 0; j < 8; j++) { - if ((crc & 0x8000) != 0) { - crc = (uint16_t)((crc << 1) ^ poly); - } else { - crc <<= 1; - } - } - crc_lut[i] = crc; - } -} - -// Initializes CRC lookup tables at module initialization -struct CrcInitializer { - CrcInitializer() { - gen_crc_lookup_table_8(0x2F, crc8_lut_8h2f); // CRC-8 8H2F/AUTOSAR for Volkswagen - gen_crc_lookup_table_16(0x1021, crc16_lut_xmodem); // CRC-16 XMODEM for HKG CAN FD - } -}; - -static CrcInitializer crcInitializer; - -unsigned int volkswagen_mqb_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - // Volkswagen uses standard CRC8 8H2F/AUTOSAR, but they compute it with - // a magic variable padding byte tacked onto the end of the payload. - // https://www.autosar.org/fileadmin/user_upload/standards/classic/4-3/AUTOSAR_SWS_CRCLibrary.pdf - - uint8_t crc = 0xFF; // Standard init value for CRC8 8H2F/AUTOSAR - - // CRC the payload first, skipping over the first byte where the CRC lives. - for (int i = 1; i < d.size(); i++) { - crc ^= d[i]; - crc = crc8_lut_8h2f[crc]; - } - - // Look up and apply the magic final CRC padding byte, which permutes by CAN - // address, and additionally (for SOME addresses) by the message counter. - uint8_t counter = d[1] & 0x0F; - switch (address) { - case 0x86: // LWI_01 Steering Angle - crc ^= (uint8_t[]){0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86}[counter]; - break; - case 0x9F: // LH_EPS_03 Electric Power Steering - crc ^= (uint8_t[]){0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5}[counter]; - break; - case 0xAD: // Getriebe_11 Automatic Gearbox - crc ^= (uint8_t[]){0x3F, 0x69, 0x39, 0xDC, 0x94, 0xF9, 0x14, 0x64, 0xD8, 0x6A, 0x34, 0xCE, 0xA2, 0x55, 0xB5, 0x2C}[counter]; - break; - case 0xFD: // ESP_21 Electronic Stability Program - crc ^= (uint8_t[]){0xB4, 0xEF, 0xF8, 0x49, 0x1E, 0xE5, 0xC2, 0xC0, 0x97, 0x19, 0x3C, 0xC9, 0xF1, 0x98, 0xD6, 0x61}[counter]; - break; - case 0x106: // ESP_05 Electronic Stability Program - crc ^= (uint8_t[]){0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07}[counter]; - break; - case 0x117: // ACC_10 Automatic Cruise Control - crc ^= (uint8_t[]){0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16}[counter]; - break; - case 0x120: // TSK_06 Drivetrain Coordinator - crc ^= (uint8_t[]){0xC4, 0xE2, 0x4F, 0xE4, 0xF8, 0x2F, 0x56, 0x81, 0x9F, 0xE5, 0x83, 0x44, 0x05, 0x3F, 0x97, 0xDF}[counter]; - break; - case 0x121: // Motor_20 Driver Throttle Inputs - crc ^= (uint8_t[]){0xE9, 0x65, 0xAE, 0x6B, 0x7B, 0x35, 0xE5, 0x5F, 0x4E, 0xC7, 0x86, 0xA2, 0xBB, 0xDD, 0xEB, 0xB4}[counter]; - break; - case 0x122: // ACC_06 Automatic Cruise Control - crc ^= (uint8_t[]){0x37, 0x7D, 0xF3, 0xA9, 0x18, 0x46, 0x6D, 0x4D, 0x3D, 0x71, 0x92, 0x9C, 0xE5, 0x32, 0x10, 0xB9}[counter]; - break; - case 0x126: // HCA_01 Heading Control Assist - crc ^= (uint8_t[]){0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA}[counter]; - break; - case 0x12B: // GRA_ACC_01 Steering wheel controls for ACC - crc ^= (uint8_t[]){0x6A, 0x38, 0xB4, 0x27, 0x22, 0xEF, 0xE1, 0xBB, 0xF8, 0x80, 0x84, 0x49, 0xC7, 0x9E, 0x1E, 0x2B}[counter]; - break; - case 0x12E: // ACC_07 Automatic Cruise Control - crc ^= (uint8_t[]){0xF8, 0xE5, 0x97, 0xC9, 0xD6, 0x07, 0x47, 0x21, 0x66, 0xDD, 0xCF, 0x6F, 0xA1, 0x94, 0x74, 0x63}[counter]; - break; - case 0x187: // EV_Gearshift "Gear" selection data for EVs with no gearbox - crc ^= (uint8_t[]){0x7F, 0xED, 0x17, 0xC2, 0x7C, 0xEB, 0x44, 0x21, 0x01, 0xFA, 0xDB, 0x15, 0x4A, 0x6B, 0x23, 0x05}[counter]; - break; - case 0x30C: // ACC_02 Automatic Cruise Control - crc ^= (uint8_t[]){0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F}[counter]; - break; - case 0x30F: // SWA_01 Lane Change Assist (SpurWechselAssistent) - crc ^= (uint8_t[]){0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C}[counter]; - break; - case 0x324: // ACC_04 Automatic Cruise Control - crc ^= (uint8_t[]){0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27}[counter]; - break; - case 0x3C0: // Klemmen_Status_01 ignition and starting status - crc ^= (uint8_t[]){0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3}[counter]; - break; - case 0x65D: // ESP_20 Electronic Stability Program - crc ^= (uint8_t[]){0xAC, 0xB3, 0xAB, 0xEB, 0x7A, 0xE1, 0x3B, 0xF7, 0x73, 0xBA, 0x7C, 0x9E, 0x06, 0x5F, 0x02, 0xD9}[counter]; - break; - default: // As-yet undefined CAN message, CRC check expected to fail - printf("Attempt to CRC check undefined Volkswagen message 0x%02X\n", address); - crc ^= (uint8_t[]){0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}[counter]; - break; - } - crc = crc8_lut_8h2f[crc]; - - return crc ^ 0xFF; // Return after standard final XOR for CRC8 8H2F/AUTOSAR -} - -unsigned int xor_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - uint8_t checksum = 0; - int checksum_byte = sig.start_bit / 8; - - // Simple XOR over the payload, except for the byte where the checksum lives. - for (int i = 0; i < d.size(); i++) { - if (i != checksum_byte) { - checksum ^= d[i]; - } - } - - return checksum; -} - -unsigned int pedal_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - uint8_t crc = 0xFF; - uint8_t poly = 0xD5; // standard crc8 - - // skip checksum byte - for (int i = d.size()-2; i >= 0; i--) { - crc ^= d[i]; - for (int j = 0; j < 8; j++) { - if ((crc & 0x80) != 0) { - crc = (uint8_t)((crc << 1) ^ poly); - } else { - crc <<= 1; - } - } - } - return crc; -} - -unsigned int hkg_can_fd_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - uint16_t crc = 0; - - for (int i = 2; i < d.size(); i++) { - crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ d[i]]; - } - - // Add address to crc - crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ ((address >> 0) & 0xFF)]; - crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ ((address >> 8) & 0xFF)]; - - if (d.size() == 8) { - crc ^= 0x5f29; - } else if (d.size() == 16) { - crc ^= 0x041d; - } else if (d.size() == 24) { - crc ^= 0x819d; - } else if (d.size() == 32) { - crc ^= 0x9f5b; - } - - return crc; -} diff --git a/opendbc/can/parser.cc b/opendbc/can/parser.cc deleted file mode 100644 index d36ec75badc2bd6..000000000000000 --- a/opendbc/can/parser.cc +++ /dev/null @@ -1,315 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "opendbc/can/common.h" - -int64_t get_raw_value(const std::vector &msg, const Signal &sig) { - int64_t ret = 0; - - int i = sig.msb / 8; - int bits = sig.size; - while (i >= 0 && i < msg.size() && bits > 0) { - int lsb = (int)(sig.lsb / 8) == i ? sig.lsb : i*8; - int msb = (int)(sig.msb / 8) == i ? sig.msb : (i+1)*8 - 1; - int size = msb - lsb + 1; - - uint64_t d = (msg[i] >> (lsb - (i*8))) & ((1ULL << size) - 1); - ret |= d << (bits - size); - - bits -= size; - i = sig.is_little_endian ? i-1 : i+1; - } - return ret; -} - - -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]; - - int64_t tmp = get_raw_value(dat, sig); - if (sig.is_signed) { - tmp -= ((tmp >> (sig.size-1)) & 0x1) ? (1ULL << sig.size) : 0; - } - - //DEBUG("parse 0x%X %s -> %ld\n", address, sig.name, tmp); - - if (!ignore_checksum) { - if (sig.calc_checksum != nullptr && sig.calc_checksum(address, sig, dat) != tmp) { - checksum_failed = true; - } - } - - if (!ignore_counter) { - if (sig.type == SignalType::COUNTER && !update_counter_generic(tmp, sig.size)) { - counter_failed = true; - } - } - - tmp_vals[i] = tmp * sig.factor + sig.offset; - } - - // only update values if both checksum and counter are valid - if (checksum_failed || counter_failed) { - LOGE_100("0x%X message checks failed, checksum failed %d, counter failed %d", address, checksum_failed, counter_failed); - return false; - } - - for (int i = 0; i < parse_sigs.size(); i++) { - vals[i] = tmp_vals[i]; - all_vals[i].push_back(vals[i]); - } - last_seen_nanos = nanos; - - return true; -} - - -bool MessageState::update_counter_generic(int64_t v, int cnt_size) { - 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, counter, (int)v); - } - } else if (counter_fail > 0) { - counter_fail--; - } - counter = v; - return counter_fail < MAX_BAD_COUNTER; -} - - -CANParser::CANParser(int abus, const std::string& dbc_name, const std::vector> &messages) - : bus(abus), aligned_buf(kj::heapArray(1024)) { - dbc = dbc_lookup(dbc_name); - assert(dbc); - - bus_timeout_threshold = std::numeric_limits::max(); - - for (const auto& [address, frequency] : messages) { - // disallow duplicate message checks - if (message_states.find(address) != message_states.end()) { - std::stringstream is; - is << "Duplicate Message Check: " << address; - throw std::runtime_error(is.str()); - } - - MessageState &state = message_states[address]; - state.address = address; - // state.check_frequency = op.check_frequency, - - // msg is not valid if a message isn't received for 10 consecutive steps - if (frequency > 0) { - state.check_threshold = (1000000000ULL / frequency) * 10; - - // bus timeout threshold should be 10x the fastest msg - bus_timeout_threshold = std::min(bus_timeout_threshold, state.check_threshold); - } - - const Msg *msg = dbc->addr_to_msg.at(address); - state.name = msg->name; - state.size = msg->size; - assert(state.size <= 64); // max signal size is 64 bytes - - // track all signals for this message - state.parse_sigs = msg->sigs; - state.vals.resize(msg->sigs.size()); - state.all_vals.resize(msg->sigs.size()); - } -} - -CANParser::CANParser(int abus, const std::string& dbc_name, bool ignore_checksum, bool ignore_counter) - : bus(abus) { - // Add all messages and signals - - dbc = dbc_lookup(dbc_name); - assert(dbc); - - for (const auto& msg : dbc->msgs) { - MessageState state = { - .name = msg.name, - .address = msg.address, - .size = msg.size, - .ignore_checksum = ignore_checksum, - .ignore_counter = ignore_counter, - }; - - for (const auto& sig : msg.sigs) { - state.parse_sigs.push_back(sig); - state.vals.push_back(0); - state.all_vals.push_back({}); - } - - message_states[state.address] = state; - } -} - -#ifndef DYNAMIC_CAPNP -void CANParser::update_string(const std::string &data, bool sendcan) { - // format for board, make copy due to alignment issues. - const size_t buf_size = (data.length() / sizeof(capnp::word)) + 1; - if (aligned_buf.size() < buf_size) { - aligned_buf = kj::heapArray(buf_size); - } - memcpy(aligned_buf.begin(), data.data(), data.length()); - - // extract the messages - capnp::FlatArrayMessageReader cmsg(aligned_buf.slice(0, buf_size)); - cereal::Event::Reader event = cmsg.getRoot(); - - if (first_nanos == 0) { - first_nanos = event.getLogMonoTime(); - } - last_nanos = event.getLogMonoTime(); - - auto cans = sendcan ? event.getSendcan() : event.getCan(); - UpdateCans(last_nanos, cans); - - UpdateValid(last_nanos); -} - -void CANParser::update_strings(const std::vector &data, std::vector &vals, bool sendcan) { - uint64_t current_nanos = 0; - for (const auto &d : data) { - update_string(d, sendcan); - if (current_nanos == 0) { - current_nanos = last_nanos; - } - } - query_latest(vals, current_nanos); -} - -void CANParser::UpdateCans(uint64_t nanos, const capnp::List::Reader& cans) { - //DEBUG("got %d messages\n", cans.size()); - - bool bus_empty = true; - - // parse the messages - for (const auto cmsg : cans) { - if (cmsg.getSrc() != bus) { - // DEBUG("skip %d: wrong bus\n", cmsg.getAddress()); - continue; - } - bus_empty = false; - - auto state_it = message_states.find(cmsg.getAddress()); - if (state_it == message_states.end()) { - // DEBUG("skip %d: not specified\n", cmsg.getAddress()); - continue; - } - - auto dat = cmsg.getDat(); - - if (dat.size() > 64) { - DEBUG("got message longer than 64 bytes: 0x%X %zu\n", cmsg.getAddress(), dat.size()); - continue; - } - - // TODO: this actually triggers for some cars. fix and enable this - //if (dat.size() != state_it->second.size) { - // DEBUG("got message with unexpected length: expected %d, got %zu for %d", state_it->second.size, dat.size(), cmsg.getAddress()); - // continue; - //} - - // TODO: can remove when we ignore unexpected can msg lengths - // make sure the data_size is not less than state_it->second.size - size_t data_size = std::max(dat.size(), state_it->second.size); - std::vector data(data_size, 0); - memcpy(data.data(), dat.begin(), dat.size()); - state_it->second.parse(nanos, data); - } - - // update bus timeout - if (!bus_empty) { - last_nonempty_nanos = nanos; - } - bus_timeout = (nanos - last_nonempty_nanos) > bus_timeout_threshold; -} -#endif - -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")); - - if (cmsg.get("src").as() != bus) { - DEBUG("skip %d: wrong bus\n", cmsg.get("address").as()); - return; - } - - auto state_it = message_states.find(cmsg.get("address").as()); - if (state_it == message_states.end()) { - DEBUG("skip %d: not specified\n", cmsg.get("address").as()); - return; - } - - auto dat = cmsg.get("dat").as(); - 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(nanos, data); -} - -void CANParser::UpdateValid(uint64_t nanos) { - const bool show_missing = (last_nanos - first_nanos) > 8e9; - - bool _valid = true; - bool _counters_valid = true; - for (const auto& kv : message_states) { - const auto& state = kv.second; - - if (state.counter_fail >= MAX_BAD_COUNTER) { - _counters_valid = false; - } - - const bool missing = state.last_seen_nanos == 0; - 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) { - LOGE_100("0x%X '%s' NOT SEEN", state.address, state.name.c_str()); - } else if (timed_out) { - LOGE_100("0x%X '%s' TIMED OUT", state.address, state.name.c_str()); - } - } - _valid = false; - } - } - can_invalid_cnt = _valid ? 0 : (can_invalid_cnt + 1); - can_valid = (can_invalid_cnt < CAN_INVALID_CNT) && _counters_valid; -} - -void CANParser::query_latest(std::vector &vals, uint64_t last_ts) { - if (last_ts == 0) { - last_ts = last_nanos; - } - for (auto& kv : message_states) { - auto& state = kv.second; - if (last_ts != 0 && state.last_seen_nanos < last_ts) { - continue; - } - - for (int i = 0; i < state.parse_sigs.size(); i++) { - const Signal &sig = state.parse_sigs[i]; - SignalValue &v = vals.emplace_back(); - v.address = state.address; - v.ts_nanos = state.last_seen_nanos; - v.name = sig.name; - v.value = state.vals[i]; - v.all_values = state.all_vals[i]; - state.all_vals[i].clear(); - } - } -} diff --git a/opendbc/can/parser_pyx.pyx b/opendbc/can/parser_pyx.pyx deleted file mode 100644 index a5b802dfcef763b..000000000000000 --- a/opendbc/can/parser_pyx.pyx +++ /dev/null @@ -1,148 +0,0 @@ -# distutils: language = c++ -# cython: c_string_encoding=ascii, language_level=3 - -from cython.operator cimport dereference as deref, preincrement as preinc -from libcpp.pair cimport pair -from libcpp.string cimport string -from libcpp.vector cimport vector -from libc.stdint cimport uint32_t - -from .common cimport CANParser as cpp_CANParser -from .common cimport dbc_lookup, SignalValue, DBC - -import numbers -from collections import defaultdict - - -cdef class CANParser: - cdef: - cpp_CANParser *can - const DBC *dbc - vector[SignalValue] can_values - vector[uint32_t] addresses - - cdef readonly: - dict vl - dict vl_all - dict ts_nanos - string dbc_name - - def __init__(self, dbc_name, messages, bus=0): - self.dbc_name = dbc_name - self.dbc = dbc_lookup(dbc_name) - if not self.dbc: - raise RuntimeError(f"Can't find DBC: {dbc_name}") - - self.vl = {} - self.vl_all = {} - self.ts_nanos = {} - - # Convert message names into addresses and check existence in DBC - cdef vector[pair[uint32_t, int]] message_v - for i in range(len(messages)): - c = messages[i] - try: - m = self.dbc.addr_to_msg.at(c[0]) if isinstance(c[0], numbers.Number) else self.dbc.name_to_msg.at(c[0]) - except IndexError: - raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") - - address = m.address - message_v.push_back((address, c[1])) - self.addresses.push_back(address) - - name = m.name.decode("utf8") - self.vl[address] = {} - self.vl[name] = self.vl[address] - self.vl_all[address] = defaultdict(list) - self.vl_all[name] = self.vl_all[address] - self.ts_nanos[address] = {} - self.ts_nanos[name] = self.ts_nanos[address] - - 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 address in self.addresses: - self.vl_all[address].clear() - - cdef vector[SignalValue] new_vals - cur_address = -1 - vl = {} - vl_all = {} - ts_nanos = {} - updated_addrs = set() - - self.can.update_strings(strings, new_vals, sendcan) - cdef vector[SignalValue].iterator it = new_vals.begin() - cdef SignalValue* cv - while it != new_vals.end(): - cv = &deref(it) - - # Check if the address has changed - if cv.address != cur_address: - cur_address = cv.address - vl = self.vl[cur_address] - vl_all = self.vl_all[cur_address] - ts_nanos = self.ts_nanos[cur_address] - updated_addrs.add(cur_address) - - # Cast char * directly to unicode - cv_name = cv.name - vl[cv_name] = cv.value - vl_all[cv_name] = cv.all_values - ts_nanos[cv_name] = cv.ts_nanos - preinc(it) - - return updated_addrs - - @property - def can_valid(self): - return self.can.can_valid - - @property - def bus_timeout(self): - return self.can.bus_timeout - - -cdef class CANDefine(): - cdef: - const DBC *dbc - - cdef public: - dict dv - string dbc_name - - def __init__(self, dbc_name): - self.dbc_name = dbc_name - self.dbc = dbc_lookup(dbc_name) - if not self.dbc: - raise RuntimeError(f"Can't find DBC: '{dbc_name}'") - - dv = defaultdict(dict) - - for i in range(self.dbc[0].vals.size()): - val = self.dbc[0].vals[i] - - sgname = val.name.decode("utf8") - def_val = val.def_val.decode("utf8") - address = val.address - try: - m = self.dbc.addr_to_msg.at(address) - except IndexError: - raise KeyError(address) - msgname = m.name.decode("utf-8") - - # separate definition/value pairs - def_val = def_val.split() - values = [int(v) for v in def_val[::2]] - defs = def_val[1::2] - - # two ways to lookup: address or msg name - dv[address][sgname] = dict(zip(values, defs)) - dv[msgname][sgname] = dv[address][sgname] - - self.dv = dict(dv) diff --git a/opendbc/can/tests/test_checksums.py b/opendbc/can/tests/test_checksums.py deleted file mode 100755 index 93ddbe00747d4cc..000000000000000 --- a/opendbc/can/tests/test_checksums.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -from opendbc.can.parser import CANParser -from opendbc.can.packer import CANPacker -from opendbc.can.tests.test_packer_parser import can_list_to_can_capnp - - -class TestCanChecksums(unittest.TestCase): - - def test_honda_checksum(self): - """Test checksums for Honda standard and extended CAN ids""" - dbc_file = "honda_accord_2018_can_generated" - msgs = [("LKAS_HUD", 0), ("LKAS_HUD_A", 0)] - parser = CANParser(dbc_file, msgs, 0) - packer = CANPacker(dbc_file) - - values = { - 'SET_ME_X41': 0x41, - 'STEERING_REQUIRED': 1, - 'SOLID_LANES': 1, - 'BEEP': 0, - } - - # known correct checksums according to the above values - checksum_std = [11, 10, 9, 8] - checksum_ext = [4, 3, 2, 1] - - for std, ext in zip(checksum_std, checksum_ext): - msgs = [ - packer.make_can_msg("LKAS_HUD", 0, values), - packer.make_can_msg("LKAS_HUD_A", 0, values), - ] - can_strings = [can_list_to_can_capnp(msgs), ] - parser.update_strings(can_strings) - - self.assertEqual(parser.vl['LKAS_HUD']['CHECKSUM'], std) - self.assertEqual(parser.vl['LKAS_HUD_A']['CHECKSUM'], ext) - - -if __name__ == "__main__": - unittest.main() diff --git a/opendbc/can/tests/test_dbc_exceptions.py b/opendbc/can/tests/test_dbc_exceptions.py deleted file mode 100755 index 1f13f539273dff0..000000000000000 --- a/opendbc/can/tests/test_dbc_exceptions.py +++ /dev/null @@ -1,36 +0,0 @@ -#!/usr/bin/env python3 - -import unittest - -from opendbc.can.parser import CANParser, CANDefine -from opendbc.can.packer import CANPacker -from opendbc.can.tests import TEST_DBC - - -class TestCanParserPackerExceptions(unittest.TestCase): - def test_civic_exceptions(self): - dbc_file = "honda_civic_touring_2016_can_generated" - dbc_invalid = dbc_file + "abcdef" - msgs = [("STEERING_CONTROL", 50)] - with self.assertRaises(RuntimeError): - CANParser(dbc_invalid, msgs, 0) - with self.assertRaises(RuntimeError): - CANPacker(dbc_invalid) - with self.assertRaises(RuntimeError): - CANDefine(dbc_invalid) - with self.assertRaises(KeyError): - CANDefine(TEST_DBC) - - parser = CANParser(dbc_file, msgs, 0) - with self.assertRaises(RuntimeError): - parser.update_strings([b'']) - - # Everything is supposed to work below - CANParser(dbc_file, msgs, 0) - CANParser(dbc_file, [], 0) - CANPacker(dbc_file) - CANDefine(dbc_file) - - -if __name__ == "__main__": - unittest.main() diff --git a/opendbc/can/tests/test_dbc_parser.py b/opendbc/can/tests/test_dbc_parser.py deleted file mode 100755 index 5da41d49b7f2848..000000000000000 --- a/opendbc/can/tests/test_dbc_parser.py +++ /dev/null @@ -1,28 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -from opendbc.can.parser import CANParser -from opendbc.can.tests import ALL_DBCS - - -class TestDBCParser(unittest.TestCase): - def test_enough_dbcs(self): - # sanity check that we're running on the real DBCs - self.assertGreater(len(ALL_DBCS), 20) - - def test_parse_all_dbcs(self): - """ - Dynamic DBC parser checks: - - Checksum and counter length, start bit, endianness - - Duplicate message addresses and names - - Signal out of bounds - - All BO_, SG_, VAL_ lines for syntax errors - """ - - for dbc in ALL_DBCS: - with self.subTest(dbc=dbc): - CANParser(dbc, [], 0) - - -if __name__ == "__main__": - unittest.main() diff --git a/opendbc/can/tests/test_define.py b/opendbc/can/tests/test_define.py deleted file mode 100755 index 6387ef9cb0aff35..000000000000000 --- a/opendbc/can/tests/test_define.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -from opendbc.can.can_define import CANDefine -from opendbc.can.tests import ALL_DBCS - - -class TestCADNDefine(unittest.TestCase): - def test_civic(self): - - dbc_file = "honda_civic_touring_2016_can_generated" - defs = CANDefine(dbc_file) - - self.assertDictEqual(defs.dv[399], defs.dv['STEER_STATUS']) - self.assertDictEqual(defs.dv[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'} - } - ) - - def test_all_dbcs(self): - # Asserts no exceptions on all DBCs - for dbc in ALL_DBCS: - with self.subTest(dbc=dbc): - CANDefine(dbc) - - -if __name__ == "__main__": - unittest.main() diff --git a/opendbc/can/tests/test_packer_parser.py b/opendbc/can/tests/test_packer_parser.py deleted file mode 100755 index c313805c47308b4..000000000000000 --- a/opendbc/can/tests/test_packer_parser.py +++ /dev/null @@ -1,399 +0,0 @@ -#!/usr/bin/env python3 -import unittest -import random - -import cereal.messaging as messaging -from opendbc.can.parser import CANParser -from opendbc.can.packer import CANPacker -from opendbc.can.tests import TEST_DBC - -MAX_BAD_COUNTER = 5 - - -# Python implementation so we don't have to depend on boardd -def can_list_to_can_capnp(can_msgs, msgtype='can', logMonoTime=None): - dat = messaging.new_message(msgtype, len(can_msgs)) - - if logMonoTime is not None: - dat.logMonoTime = logMonoTime - - for i, can_msg in enumerate(can_msgs): - if msgtype == 'sendcan': - cc = dat.sendcan[i] - else: - cc = dat.can[i] - - cc.address = can_msg[0] - cc.busTime = can_msg[1] - cc.dat = bytes(can_msg[2]) - cc.src = can_msg[3] - - return dat.to_bytes() - - -class TestCanParserPacker(unittest.TestCase): - def test_packer(self): - packer = CANPacker(TEST_DBC) - - for b in range(6): - for i in range(256): - values = {"COUNTER": i} - addr, _, dat, bus = packer.make_can_msg("CAN_FD_MESSAGE", b, values) - self.assertEqual(addr, 245) - self.assertEqual(bus, b) - self.assertEqual(dat[0], i) - - def test_packer_counter(self): - msgs = [("CAN_FD_MESSAGE", 0), ] - packer = CANPacker(TEST_DBC) - parser = CANParser(TEST_DBC, msgs, 0) - - # packer should increment the counter - for i in range(1000): - msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) - dat = can_list_to_can_capnp([msg, ]) - parser.update_strings([dat]) - self.assertEqual(parser.vl["CAN_FD_MESSAGE"]["COUNTER"], i % 256) - - # setting COUNTER should override - for _ in range(100): - cnt = random.randint(0, 255) - msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, { - "COUNTER": cnt, - "SIGNED": 0 - }) - dat = can_list_to_can_capnp([msg, ]) - parser.update_strings([dat]) - self.assertEqual(parser.vl["CAN_FD_MESSAGE"]["COUNTER"], cnt) - - # then, should resume counting from the override value - cnt = parser.vl["CAN_FD_MESSAGE"]["COUNTER"] - for i in range(100): - msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) - dat = can_list_to_can_capnp([msg, ]) - parser.update_strings([dat]) - self.assertEqual(parser.vl["CAN_FD_MESSAGE"]["COUNTER"], (cnt + i) % 256) - - def test_parser_can_valid(self): - msgs = [("CAN_FD_MESSAGE", 10), ] - packer = CANPacker(TEST_DBC) - parser = CANParser(TEST_DBC, msgs, 0) - - # shouldn't be valid initially - self.assertFalse(parser.can_valid) - - # not valid until the message is seen - for _ in range(100): - dat = can_list_to_can_capnp([]) - parser.update_strings([dat]) - self.assertFalse(parser.can_valid) - - # valid once seen - for i in range(1, 100): - t = int(0.01 * i * 1e9) - msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) - dat = can_list_to_can_capnp([msg, ], logMonoTime=t) - parser.update_strings([dat]) - self.assertTrue(parser.can_valid) - - def test_parser_counter_can_valid(self): - """ - Tests number of allowed bad counters + ensures CAN stays invalid - while receiving invalid messages + that we can recover - """ - msgs = [ - ("STEERING_CONTROL", 0), - ] - packer = CANPacker("honda_civic_touring_2016_can_generated") - parser = CANParser("honda_civic_touring_2016_can_generated", msgs, 0) - - msg = packer.make_can_msg("STEERING_CONTROL", 0, {"COUNTER": 0}) - bts = can_list_to_can_capnp([msg]) - - # bad static counter, invalid once it's seen MAX_BAD_COUNTER messages - for idx in range(0x1000): - parser.update_strings([bts]) - self.assertEqual((idx + 1) < MAX_BAD_COUNTER, parser.can_valid) - - # one to recover - msg = packer.make_can_msg("STEERING_CONTROL", 0, {"COUNTER": 1}) - bts = can_list_to_can_capnp([msg]) - parser.update_strings([bts]) - self.assertTrue(parser.can_valid) - - def test_parser_no_partial_update(self): - """ - Ensure that the CANParser doesn't partially update messages with invalid signals (COUNTER/CHECKSUM). - Previously, the signal update loop would only break once it got to one of these invalid signals, - after already updating most/all of the signals. - """ - msgs = [ - ("STEERING_CONTROL", 0), - ] - packer = CANPacker("honda_civic_touring_2016_can_generated") - parser = CANParser("honda_civic_touring_2016_can_generated", msgs, 0) - - def rx_steering_msg(values, bad_checksum=False): - msg = packer.make_can_msg("STEERING_CONTROL", 0, values) - if bad_checksum: - # add 1 to checksum - msg[2] = bytearray(msg[2]) - msg[2][4] = (msg[2][4] & 0xF0) | ((msg[2][4] & 0x0F) + 1) - - bts = can_list_to_can_capnp([msg]) - parser.update_strings([bts]) - - rx_steering_msg({"STEER_TORQUE": 100}, bad_checksum=False) - self.assertEqual(parser.vl["STEERING_CONTROL"]["STEER_TORQUE"], 100) - self.assertEqual(parser.vl_all["STEERING_CONTROL"]["STEER_TORQUE"], [100]) - - for _ in range(5): - rx_steering_msg({"STEER_TORQUE": 200}, bad_checksum=True) - self.assertEqual(parser.vl["STEERING_CONTROL"]["STEER_TORQUE"], 100) - self.assertEqual(parser.vl_all["STEERING_CONTROL"]["STEER_TORQUE"], []) - - # Even if CANParser doesn't update instantaneous vl, make sure it didn't add invalid values to vl_all - rx_steering_msg({"STEER_TORQUE": 300}, bad_checksum=False) - self.assertEqual(parser.vl["STEERING_CONTROL"]["STEER_TORQUE"], 300) - self.assertEqual(parser.vl_all["STEERING_CONTROL"]["STEER_TORQUE"], [300]) - - def test_packer_parser(self): - msgs = [ - ("Brake_Status", 0), - ("CAN_FD_MESSAGE", 0), - ("STEERING_CONTROL", 0), - ] - packer = CANPacker(TEST_DBC) - parser = CANParser(TEST_DBC, msgs, 0) - - for steer in range(-256, 255): - for active in (1, 0): - values = { - "STEERING_CONTROL": { - "STEER_TORQUE": steer, - "STEER_TORQUE_REQUEST": active, - }, - "Brake_Status": { - "Signal1": 61042322657536.0, - }, - "CAN_FD_MESSAGE": { - "SIGNED": steer, - "64_BIT_LE": random.randint(0, 100), - "64_BIT_BE": random.randint(0, 100), - }, - } - - msgs = [packer.make_can_msg(k, 0, v) for k, v in values.items()] - bts = can_list_to_can_capnp(msgs) - parser.update_strings([bts]) - - for k, v in values.items(): - for key, val in v.items(): - self.assertAlmostEqual(parser.vl[k][key], val) - - # also check address - for sig in ("STEER_TORQUE", "STEER_TORQUE_REQUEST", "COUNTER", "CHECKSUM"): - self.assertEqual(parser.vl["STEERING_CONTROL"][sig], parser.vl[228][sig]) - - def test_scale_offset(self): - """Test that both scale and offset are correctly preserved""" - dbc_file = "honda_civic_touring_2016_can_generated" - msgs = [("VSA_STATUS", 50)] - parser = CANParser(dbc_file, msgs, 0) - packer = CANPacker(dbc_file) - - for brake in range(100): - values = {"USER_BRAKE": brake} - msgs = packer.make_can_msg("VSA_STATUS", 0, values) - bts = can_list_to_can_capnp([msgs]) - - parser.update_strings([bts]) - - self.assertAlmostEqual(parser.vl["VSA_STATUS"]["USER_BRAKE"], brake) - - def test_subaru(self): - # Subaru is little endian - - dbc_file = "subaru_global_2017_generated" - - msgs = [("ES_LKAS", 50)] - - parser = CANParser(dbc_file, msgs, 0) - packer = CANPacker(dbc_file) - - idx = 0 - for steer in range(-256, 255): - for active in [1, 0]: - values = { - "LKAS_Output": steer, - "LKAS_Request": active, - "SET_1": 1 - } - - msgs = packer.make_can_msg("ES_LKAS", 0, values) - bts = can_list_to_can_capnp([msgs]) - parser.update_strings([bts]) - - self.assertAlmostEqual(parser.vl["ES_LKAS"]["LKAS_Output"], steer) - self.assertAlmostEqual(parser.vl["ES_LKAS"]["LKAS_Request"], active) - self.assertAlmostEqual(parser.vl["ES_LKAS"]["SET_1"], 1) - self.assertAlmostEqual(parser.vl["ES_LKAS"]["COUNTER"], idx % 16) - idx += 1 - - def test_bus_timeout(self): - """Test CAN bus timeout detection""" - dbc_file = "honda_civic_touring_2016_can_generated" - - freq = 100 - msgs = [("VSA_STATUS", freq), ("STEER_MOTOR_TORQUE", freq/2)] - - parser = CANParser(dbc_file, msgs, 0) - packer = CANPacker(dbc_file) - - i = 0 - def send_msg(blank=False): - nonlocal i - i += 1 - t = i*((1 / freq) * 1e9) - - if blank: - msgs = [] - else: - msgs = [packer.make_can_msg("VSA_STATUS", 0, {}), ] - - can = can_list_to_can_capnp(msgs, logMonoTime=t) - parser.update_strings([can, ]) - - # all good, no timeout - for _ in range(1000): - send_msg() - self.assertFalse(parser.bus_timeout, str(_)) - - # timeout after 10 blank msgs - for n in range(200): - send_msg(blank=True) - self.assertEqual(n >= 10, parser.bus_timeout) - - # no timeout immediately after seen again - send_msg() - self.assertFalse(parser.bus_timeout) - - def test_updated(self): - """Test updated value dict""" - dbc_file = "honda_civic_touring_2016_can_generated" - msgs = [("VSA_STATUS", 50)] - parser = CANParser(dbc_file, msgs, 0) - packer = CANPacker(dbc_file) - - # Make sure nothing is updated - self.assertEqual(len(parser.vl_all["VSA_STATUS"]["USER_BRAKE"]), 0) - - idx = 0 - for _ in range(10): - # Ensure CANParser holds the values of any duplicate messages over multiple frames - user_brake_vals = [random.randrange(100) for _ in range(random.randrange(5, 10))] - half_idx = len(user_brake_vals) // 2 - can_msgs = [[], []] - for frame, brake_vals in enumerate((user_brake_vals[:half_idx], user_brake_vals[half_idx:])): - for user_brake in brake_vals: - values = {"USER_BRAKE": user_brake} - can_msgs[frame].append(packer.make_can_msg("VSA_STATUS", 0, values)) - idx += 1 - - can_strings = [can_list_to_can_capnp(msgs) for msgs in can_msgs] - parser.update_strings(can_strings) - vl_all = parser.vl_all["VSA_STATUS"]["USER_BRAKE"] - - self.assertEqual(vl_all, user_brake_vals) - if len(user_brake_vals): - self.assertEqual(vl_all[-1], parser.vl["VSA_STATUS"]["USER_BRAKE"]) - - def test_timestamp_nanos(self): - """Test message timestamp dict""" - dbc_file = "honda_civic_touring_2016_can_generated" - - msgs = [ - ("VSA_STATUS", 50), - ("POWERTRAIN_DATA", 100), - ] - - parser = CANParser(dbc_file, msgs, 0) - packer = CANPacker(dbc_file) - - # Check the default timestamp is zero - for msg in ("VSA_STATUS", "POWERTRAIN_DATA"): - ts_nanos = parser.ts_nanos[msg].values() - self.assertEqual(set(ts_nanos), {0}) - - # Check: - # - timestamp is only updated for correct messages - # - timestamp is correct for multiple runs - # - timestamp is from the latest message if updating multiple strings - for _ in range(10): - can_strings = [] - log_mono_time = 0 - for i in range(10): - log_mono_time = int(0.01 * i * 1e+9) - can_msg = packer.make_can_msg("VSA_STATUS", 0, {}) - can_strings.append(can_list_to_can_capnp([can_msg], logMonoTime=log_mono_time)) - parser.update_strings(can_strings) - - ts_nanos = parser.ts_nanos["VSA_STATUS"].values() - self.assertEqual(set(ts_nanos), {log_mono_time}) - ts_nanos = parser.ts_nanos["POWERTRAIN_DATA"].values() - self.assertEqual(set(ts_nanos), {0}) - - def test_nonexistent_messages(self): - # Ensure we don't allow messages not in the DBC - existing_messages = ("STEERING_CONTROL", 228, "CAN_FD_MESSAGE", 245) - - for msg in existing_messages: - CANParser(TEST_DBC, [(msg, 0)]) - with self.assertRaises(RuntimeError): - new_msg = msg + "1" if isinstance(msg, str) else msg + 1 - CANParser(TEST_DBC, [(new_msg, 0)]) - - def test_track_all_signals(self): - parser = CANParser("toyota_nodsu_pt_generated", [("ACC_CONTROL", 0)]) - self.assertEqual(parser.vl["ACC_CONTROL"], { - "ACCEL_CMD": 0, - "ALLOW_LONG_PRESS": 0, - "ACC_MALFUNCTION": 0, - "RADAR_DIRTY": 0, - "DISTANCE": 0, - "MINI_CAR": 0, - "ACC_TYPE": 0, - "CANCEL_REQ": 0, - "ACC_CUT_IN": 0, - "LEAD_VEHICLE_STOPPED": 0, - "PERMIT_BRAKING": 0, - "RELEASE_STANDSTILL": 0, - "ITS_CONNECT_LEAD": 0, - "ACCEL_CMD_ALT": 0, - "CHECKSUM": 0, - }) - - def test_disallow_duplicate_messages(self): - CANParser("toyota_nodsu_pt_generated", [("ACC_CONTROL", 5)]) - - with self.assertRaises(RuntimeError): - CANParser("toyota_nodsu_pt_generated", [("ACC_CONTROL", 5), ("ACC_CONTROL", 10)]) - - with self.assertRaises(RuntimeError): - CANParser("toyota_nodsu_pt_generated", [("ACC_CONTROL", 10), ("ACC_CONTROL", 10)]) - - def test_allow_undefined_msgs(self): - # TODO: we should throw an exception for these, but we need good - # discovery tests in openpilot first - packer = CANPacker("toyota_nodsu_pt_generated") - - self.assertEqual(packer.make_can_msg("ACC_CONTROL", 0, {"UNKNOWN_SIGNAL": 0}), - [835, 0, b'\x00\x00\x00\x00\x00\x00\x00N', 0]) - self.assertEqual(packer.make_can_msg("UNKNOWN_MESSAGE", 0, {"UNKNOWN_SIGNAL": 0}), - [0, 0, b'', 0]) - self.assertEqual(packer.make_can_msg(0, 0, {"UNKNOWN_SIGNAL": 0}), - [0, 0, b'', 0]) - - -if __name__ == "__main__": - unittest.main() diff --git a/opendbc/can/tests/test_parser_performance.py b/opendbc/can/tests/test_parser_performance.py deleted file mode 100755 index 2010fa4bf78e881..000000000000000 --- a/opendbc/can/tests/test_parser_performance.py +++ /dev/null @@ -1,55 +0,0 @@ -#!/usr/bin/env python3 -import time -import unittest - -from opendbc.can.parser import CANParser -from opendbc.can.packer import CANPacker -from opendbc.can.tests.test_packer_parser import can_list_to_can_capnp - - -@unittest.skip("TODO: varies too much between machines") -class TestParser(unittest.TestCase): - def _benchmark(self, checks, thresholds, n): - parser = CANParser('toyota_new_mc_pt_generated', checks, 0) - packer = CANPacker('toyota_new_mc_pt_generated') - - can_msgs = [] - for i in range(50000): - values = {"ACC_CONTROL": {"ACC_TYPE": 1, "ALLOW_LONG_PRESS": 3}} - msgs = [packer.make_can_msg(k, 0, v) for k, v in values.items()] - bts = can_list_to_can_capnp(msgs, logMonoTime=int(0.01 * i * 1e9)) - can_msgs.append(bts) - - ets = [] - for _ in range(25): - if n > 1: - strings = [] - for i in range(0, len(can_msgs), n): - strings.append(can_msgs[i:i + n]) - t1 = time.process_time_ns() - for m in strings: - parser.update_strings(m) - t2 = time.process_time_ns() - else: - t1 = time.process_time_ns() - for m in can_msgs: - parser.update_strings([m]) - t2 = time.process_time_ns() - - ets.append(t2 - t1) - - et = sum(ets) / len(ets) - avg_nanos = et / len(can_msgs) - print('%s: [%d] %.1fms to parse %s, avg: %dns' % (self._testMethodName, n, et/1e6, len(can_msgs), avg_nanos)) - - minn, maxx = thresholds - self.assertLess(avg_nanos, maxx) - self.assertGreater(avg_nanos, minn, "Performance seems to have improved, update test thresholds.") - - def test_performance_all_signals(self): - self._benchmark([('ACC_CONTROL', 10)], (10000, 19000), 1) - self._benchmark([('ACC_CONTROL', 10)], (1300, 5000), 10) - - -if __name__ == "__main__": - unittest.main() diff --git a/opendbc/pyproject.toml b/opendbc/pyproject.toml deleted file mode 100644 index 035775acc4d1cf2..000000000000000 --- a/opendbc/pyproject.toml +++ /dev/null @@ -1,20 +0,0 @@ -[tool.poetry] -name = "opendbc" -version = "1.0.0" -description = "CAN bus databases and tools" -license = "MIT" -authors = ["Vehicle Researcher "] -readme = "README.md" -repository = "https://github.com/commaai/opendbc" - -[tool.cython-lint] -max-line-length = 120 -ignore = ["E111", "E114"] - -# https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml -[tool.ruff] -select = ["E", "F", "W", "PIE", "C4", "ISC", "RUF100", "A"] -ignore = ["W292", "E741", "E402", "C408", "ISC003"] -line-length = 160 -target-version="py311" -flake8-implicit-str-concat.allow-multiline=false diff --git a/opendbc/requirements.txt b/opendbc/requirements.txt deleted file mode 100644 index 10f8414dda30d1d..000000000000000 --- a/opendbc/requirements.txt +++ /dev/null @@ -1,8 +0,0 @@ -ruff -Cython -Jinja2 -numpy -pycapnp -pyyaml -scons -pytest diff --git a/opendbc_repo/.gitignore b/opendbc_repo/.gitignore new file mode 100644 index 000000000000000..d66bd7dcb5ec9cb --- /dev/null +++ b/opendbc_repo/.gitignore @@ -0,0 +1,23 @@ +/build/ +.mypy_cache/ +*.pyc +*.os +*.o +*.tmp +*.dylib +.*.swp +.DS_Store +.sconsign.dblite +.hypothesis +*.egg-info/ +*.html +uv.lock + +opendbc/can/*.so +opendbc/can/*.a +opendbc/can/build/ +opendbc/can/obj/ +opendbc/can/packer_pyx.cpp +opendbc/can/parser_pyx.cpp +opendbc/can/packer_pyx.html +opendbc/can/parser_pyx.html diff --git a/opendbc_repo/README.md b/opendbc_repo/README.md new file mode 100644 index 000000000000000..5a91ab2ada10797 --- /dev/null +++ b/opendbc_repo/README.md @@ -0,0 +1,58 @@ +# opendbc + +opendbc is a Python API for your car. Read the speed, steering angle, and more. Send gas, braking, and steering commands. + +## Structure +* [`opendbc/dbc/`](opendbc/dbc/) is a repository of [DBC](https://en.wikipedia.org/wiki/CAN_bus#DBC) files +* [`opendbc/can/`](opendbc/can/) is a library for parsing and building CAN messages from DBC files +* [`opendbc/car/`](opendbc/car/) is a high-level library for interfacing with cars using Python + +## Quick start + +```bash +git clone https://github.com/commaai/opendbc.git + +cd opendbc + +# Install the dependencies +pip3 install -e .[testing,docs] + +# Build +scons -j8 + +# Run the tests +pytest . + +# Run the linter +pre-commit run --all-files + +# ./test.sh is the all-in-one that will install deps, build, lint, and test +./test.sh +``` + +[`examples/`](examples/) contains small example programs that can read state from the car and control the steering, gas, and brakes. +[`examples/joystick.py`](examples/joystick.py) allows you to control a car with a joystick. + +## Roadmap + +This project was pulled out from [openpilot](https://github.com/commaai/openpilot). +We're still figuring out the exact API between openpilot and opendbc, so some of these +may end up going in openpilot. + +* Extend support to every car with LKAS + ACC interfaces +* Automatic lateral and longitudinal control/tuning evaluation +* Auto-tuning for [lateral](https://blog.comma.ai/090release/#torqued-an-auto-tuner-for-lateral-control) and longitudinal control +* [Automatic Emergency Braking](https://en.wikipedia.org/wiki/Automated_emergency_braking_system) +* `pip install opendbc` +* 100% type coverage +* 100% line coverage +* Make car ports easier: refactors, tools, tests, and docs +* Expose the state of all supported cars better: https://github.com/commaai/opendbc/issues/1144 + +Contributions towards anything here is welcome. Join the [Discord](https://discord.comma.ai)! + +## FAQ + +* **How do I use this?** Depends on what you want to do. [openpilot](https://github.com/commaai/openpilot) is our development target, but you can also use a [panda](https://comma.ai/shop/panda) for basic control or just reading state from your car. +* **Can I add support for my car?** Yes, most car support comes from the community. Join the [Discord](https://discord.comma.ai) and watch this [talk](https://www.youtube.com/watch?v=XxPS5TpTUnI&t=142s&pp=ygUPY29tbWFfY29uIGphc29u) to get started. (We also offer [paid bounties](https://comma.ai/bounties) on car ports.) +* **Which cars are supported?** See the openpilot [supported cars list](https://github.com/commaai/openpilot/blob/master/docs/CARS.md) and `grep` around the codebase. diff --git a/opendbc_repo/SConstruct b/opendbc_repo/SConstruct new file mode 100644 index 000000000000000..932ff26e8b775aa --- /dev/null +++ b/opendbc_repo/SConstruct @@ -0,0 +1,76 @@ +import os +import subprocess +import sysconfig +import numpy as np + +arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() + +python_path = sysconfig.get_paths()['include'] +cpppath = [ + '#', + '/usr/lib/include', + python_path +] + +AddOption('--minimal', + action='store_false', + dest='extras', + default=True, + help='the minimum build. no tests, tools, etc.') + +AddOption('--asan', + action='store_true', + help='turn on ASAN') + +ccflags_asan = ["-fsanitize=address", "-fno-omit-frame-pointer"] if GetOption('asan') else [] +ldflags_asan = ["-fsanitize=address"] if GetOption('asan') else [] + +env = Environment( + ENV=os.environ, + CC='gcc', + CXX='g++', + CCFLAGS=[ + "-g", + "-fPIC", + "-O2", + "-Wunused", + "-Werror", + "-Wshadow", + "-Wno-vla-cxx-extension", + "-Wno-unknown-warning-option", # for compatibility across compiler versions + ] + ccflags_asan, + LDFLAGS=ldflags_asan, + LINKFLAGS=ldflags_asan, + LIBPATH=[ + "#opendbc/can/", + ], + CFLAGS="-std=gnu11", + CXXFLAGS=["-std=c++1z"], + CPPPATH=cpppath, + CYTHONCFILESUFFIX=".cpp", + tools=["default", "cython"] +) + +common = '' +Export('env', 'arch', 'common') + +envCython = env.Clone() +envCython["CPPPATH"] += [np.get_include()] +envCython["CCFLAGS"] += ["-Wno-#warnings", "-Wno-shadow", "-Wno-deprecated-declarations"] +envCython["CCFLAGS"].remove("-Werror") + +python_libs = [] +if arch == "Darwin": + envCython["LINKFLAGS"] = ["-bundle", "-undefined", "dynamic_lookup"] +elif arch == "aarch64": + envCython["LINKFLAGS"] = ["-shared"] + + python_libs.append(os.path.basename(python_path)) +else: + envCython["LINKFLAGS"] = ["-pthread", "-shared"] + +envCython["LIBS"] = python_libs + +Export('envCython') + +SConscript(['opendbc/can/SConscript']) diff --git a/opendbc_repo/docs/CARS.md b/opendbc_repo/docs/CARS.md new file mode 100644 index 000000000000000..1322bf949934967 --- /dev/null +++ b/opendbc_repo/docs/CARS.md @@ -0,0 +1,417 @@ + + +# Support Information for 343 Known Cars + +|Make|Model|Package|Support Level| +|---|---|---|:---:| +|Acura|ILX 2016-19|AcuraWatch Plus|[Upstream](#upstream)| +|Acura|Integra 2024|All|[Community](#community)| +|Acura|RDX 2016-18|AcuraWatch Plus|[Upstream](#upstream)| +|Acura|RDX 2019-22|All|[Upstream](#upstream)| +|Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Audi|A4 2016-24|All|[Not compatible](#flexray)| +|Audi|A5 2016-24|All|[Not compatible](#flexray)| +|Audi|Q2 2018|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Audi|Q3 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Audi|Q5 2017-24|All|[Not compatible](#flexray)| +|Audi|RS3 2018|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Audi|S3 2015-17|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Chevrolet|Bolt EUV 2022-23|Premier or Premier Redline Trim without Super Cruise Package|[Upstream](#upstream)| +|Chevrolet|Bolt EV 2022-23|2LT Trim with Adaptive Cruise Control Package|[Upstream](#upstream)| +|Chevrolet|Equinox 2019-22|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Chevrolet|Silverado 1500 2020-21|Safety Package II|[Upstream](#upstream)| +|Chevrolet|Trailblazer 2021-22|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Chrysler|Pacifica 2017-18|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Chrysler|Pacifica 2019-20|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Chrysler|Pacifica 2021-23|All|[Upstream](#upstream)| +|Chrysler|Pacifica Hybrid 2017-18|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Chrysler|Pacifica Hybrid 2019-24|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|comma|body|All|[Upstream](#upstream)| +|CUPRA|Ateca 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Dodge|Durango 2020-21|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Ford|Bronco Sport 2021-23|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|Escape 2020-22|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|Escape Hybrid 2020-22|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|Escape Plug-in Hybrid 2020-22|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|Explorer 2020-23|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|Explorer Hybrid 2020-23|Co-Pilot360 Assist+|[Upstream](#upstream)| +|Ford|F-150 2022-23|Co-Pilot360 Active 2.0|[Under review](#under-review)| +|Ford|F-150 Hybrid 2022-23|Co-Pilot360 Active 2.0|[Under review](#under-review)| +|Ford|F-150 Lightning 2021-23|Co-Pilot360 Active 2.0|[Under review](#under-review)| +|Ford|Focus 2018|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Focus Hybrid 2018|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Kuga 2020-22|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Kuga Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Kuga Plug-in Hybrid 2020-22|Adaptive Cruise Control with Lane Centering|[Upstream](#upstream)| +|Ford|Maverick 2022|LARIAT Luxury|[Upstream](#upstream)| +|Ford|Maverick 2023-24|Co-Pilot360 Assist|[Upstream](#upstream)| +|Ford|Maverick Hybrid 2022|LARIAT Luxury|[Upstream](#upstream)| +|Ford|Maverick Hybrid 2023-24|Co-Pilot360 Assist|[Upstream](#upstream)| +|Ford|Mustang Mach-E 2021-23|Co-Pilot360 Active 2.0|[Under review](#under-review)| +|Ford|Ranger 2024|Adaptive Cruise Control with Lane Centering|[Under review](#under-review)| +|Genesis|G70 2018|All|[Upstream](#upstream)| +|Genesis|G70 2019-21|All|[Upstream](#upstream)| +|Genesis|G70 2022-23|All|[Upstream](#upstream)| +|Genesis|G80 2017|All|[Upstream](#upstream)| +|Genesis|G80 2018-19|All|[Upstream](#upstream)| +|Genesis|G80 (2.5T Advanced Trim, with HDA II) 2024|Highway Driving Assist II|[Upstream](#upstream)| +|Genesis|G90 2017-20|All|[Upstream](#upstream)| +|Genesis|GV60 (Advanced Trim) 2023|All|[Upstream](#upstream)| +|Genesis|GV60 (Performance Trim) 2022-23|All|[Upstream](#upstream)| +|Genesis|GV70 (2.5T Trim, without HDA II) 2022-23|All|[Upstream](#upstream)| +|Genesis|GV70 (3.5T Trim, without HDA II) 2022-23|All|[Upstream](#upstream)| +|Genesis|GV70 Electrified (with HDA II) 2023|Highway Driving Assist II|[Upstream](#upstream)| +|Genesis|GV80 2023|All|[Upstream](#upstream)| +|GMC|Sierra 1500 2020-21|Driver Alert Package II|[Upstream](#upstream)| +|Honda|Accord 2018-22|All|[Upstream](#upstream)| +|Honda|Accord 2023-24|All|[Community](#community)| +|Honda|Accord Hybrid 2018-22|All|[Upstream](#upstream)| +|Honda|Civic 2016-18|Honda Sensing|[Upstream](#upstream)| +|Honda|Civic 2019-21|All|[Upstream](#upstream)| +|Honda|Civic 2022-24|All|[Upstream](#upstream)| +|Honda|Civic Hatchback 2017-21|Honda Sensing|[Upstream](#upstream)| +|Honda|Civic Hatchback 2022-24|All|[Upstream](#upstream)| +|Honda|Clarity 2018-21|All|[Community](#community)| +|Honda|CR-V 2015-16|Touring Trim|[Upstream](#upstream)| +|Honda|CR-V 2017-22|Honda Sensing|[Upstream](#upstream)| +|Honda|CR-V 2024|All|[Community](#community)| +|Honda|CR-V Hybrid 2017-21|Honda Sensing|[Upstream](#upstream)| +|Honda|CR-V Hybrid 2024|All|[Community](#community)| +|Honda|e 2020|All|[Upstream](#upstream)| +|Honda|Fit 2018-20|Honda Sensing|[Upstream](#upstream)| +|Honda|Freed 2020|Honda Sensing|[Upstream](#upstream)| +|Honda|HR-V 2019-22|Honda Sensing|[Upstream](#upstream)| +|Honda|HR-V 2023|All|[Upstream](#upstream)| +|Honda|Insight 2019-22|All|[Upstream](#upstream)| +|Honda|Inspire 2018|All|[Upstream](#upstream)| +|Honda|Odyssey 2018-20|Honda Sensing|[Upstream](#upstream)| +|Honda|Odyssey 2021-25|All|[Community](#community)| +|Honda|Passport 2019-23|All|[Upstream](#upstream)| +|Honda|Pilot 2016-22|Honda Sensing|[Upstream](#upstream)| +|Honda|Pilot 2023-24|All|[Community](#community)| +|Honda|Ridgeline 2017-24|Honda Sensing|[Upstream](#upstream)| +|Hyundai|Azera 2022|All|[Upstream](#upstream)| +|Hyundai|Azera Hybrid 2019|All|[Upstream](#upstream)| +|Hyundai|Azera Hybrid 2020|All|[Upstream](#upstream)| +|Hyundai|Custin 2023|All|[Upstream](#upstream)| +|Hyundai|Elantra 2017-18|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Elantra 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Elantra 2021-23|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Elantra GT 2017-19|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Elantra Hybrid 2021-23|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Genesis 2015-16|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|i30 2017-19|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Ioniq 5 (Non-US only) 2022-24|All|[Upstream](#upstream)| +|Hyundai|Ioniq 5 (with HDA II) 2022-24|Highway Driving Assist II|[Upstream](#upstream)| +|Hyundai|Ioniq 5 (without HDA II) 2022-24|Highway Driving Assist|[Upstream](#upstream)| +|Hyundai|Ioniq 6 (with HDA II) 2023-24|Highway Driving Assist II|[Upstream](#upstream)| +|Hyundai|Ioniq Electric 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Ioniq Electric 2020|All|[Upstream](#upstream)| +|Hyundai|Ioniq Hybrid 2017-19|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Ioniq Hybrid 2020-22|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Ioniq Plug-in Hybrid 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Ioniq Plug-in Hybrid 2020-22|All|[Upstream](#upstream)| +|Hyundai|Kona 2020|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Kona Electric 2018-21|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Kona Electric 2022-23|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Kona Electric (with HDA II, Korea only) 2023|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Kona Hybrid 2020|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Palisade 2020-22|All|[Upstream](#upstream)| +|Hyundai|Palisade 2023-24|HDA2|[Community](#community)| +|Hyundai|Santa Cruz 2022-24|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Santa Fe 2019-20|All|[Upstream](#upstream)| +|Hyundai|Santa Fe 2021-23|All|[Upstream](#upstream)| +|Hyundai|Santa Fe Hybrid 2022-23|All|[Upstream](#upstream)| +|Hyundai|Santa Fe Plug-in Hybrid 2022-23|All|[Upstream](#upstream)| +|Hyundai|Sonata 2018-19|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Sonata 2020-23|All|[Upstream](#upstream)| +|Hyundai|Sonata Hybrid 2020-23|All|[Upstream](#upstream)| +|Hyundai|Staria 2023|All|[Upstream](#upstream)| +|Hyundai|Tucson 2021|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Tucson 2022|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Tucson 2023-24|All|[Upstream](#upstream)| +|Hyundai|Tucson Diesel 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Hyundai|Tucson Hybrid 2022-24|All|[Upstream](#upstream)| +|Hyundai|Tucson Plug-in Hybrid 2024|All|[Upstream](#upstream)| +|Hyundai|Veloster 2019-20|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Jeep|Grand Cherokee 2016-18|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Jeep|Grand Cherokee 2019-21|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Kia|Carnival 2022-24|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Carnival (China only) 2023|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Ceed 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|EV6 (Southeast Asia only) 2022-24|All|[Upstream](#upstream)| +|Kia|EV6 (with HDA II) 2022-24|Highway Driving Assist II|[Upstream](#upstream)| +|Kia|EV6 (without HDA II) 2022-24|Highway Driving Assist|[Upstream](#upstream)| +|Kia|Forte 2019-21|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Forte 2022-23|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|K5 2021-24|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|K5 Hybrid 2020-22|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|K8 Hybrid (with HDA II) 2023|Highway Driving Assist II|[Upstream](#upstream)| +|Kia|Niro EV 2019|All|[Upstream](#upstream)| +|Kia|Niro EV 2020|All|[Upstream](#upstream)| +|Kia|Niro EV 2021|All|[Upstream](#upstream)| +|Kia|Niro EV 2022|All|[Upstream](#upstream)| +|Kia|Niro EV 2023|All|[Upstream](#upstream)| +|Kia|Niro Hybrid 2018|All|[Upstream](#upstream)| +|Kia|Niro Hybrid 2021|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Niro Hybrid 2022|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Niro Hybrid 2023|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Niro Plug-in Hybrid 2018-19|All|[Upstream](#upstream)| +|Kia|Niro Plug-in Hybrid 2020|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Niro Plug-in Hybrid 2021|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Niro Plug-in Hybrid 2022|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Optima 2017|Advanced Smart Cruise Control|[Upstream](#upstream)| +|Kia|Optima 2019-20|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Optima Hybrid 2017|Advanced Smart Cruise Control|[Dashcam mode](#dashcam)| +|Kia|Optima Hybrid 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Seltos 2021|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Sorento 2018|Advanced Smart Cruise Control & LKAS|[Upstream](#upstream)| +|Kia|Sorento 2019|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Sorento 2021-23|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Sorento Hybrid 2021-23|All|[Upstream](#upstream)| +|Kia|Sorento Plug-in Hybrid 2022-23|All|[Upstream](#upstream)| +|Kia|Sportage 2023-24|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Sportage Hybrid 2023|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Stinger 2018-20|Smart Cruise Control (SCC)|[Upstream](#upstream)| +|Kia|Stinger 2022-23|All|[Upstream](#upstream)| +|Kia|Telluride 2020-22|All|[Upstream](#upstream)| +|Kia|Telluride 2023-24|HDA2|[Community](#community)| +|Lexus|CT Hybrid 2017-18|Lexus Safety System+|[Upstream](#upstream)| +|Lexus|ES 2017-18|All|[Upstream](#upstream)| +|Lexus|ES 2019-24|All|[Upstream](#upstream)| +|Lexus|ES Hybrid 2017-18|All|[Upstream](#upstream)| +|Lexus|ES Hybrid 2019-24|All|[Upstream](#upstream)| +|Lexus|GS F 2016|All|[Upstream](#upstream)| +|Lexus|IS 2017-19|All|[Upstream](#upstream)| +|Lexus|IS 2022-23|All|[Upstream](#upstream)| +|Lexus|LC 2024|All|[Upstream](#upstream)| +|Lexus|NS 2022-25|Any|[Not compatible](#can-bus-security)| +|Lexus|NX 2018-19|All|[Upstream](#upstream)| +|Lexus|NX 2020-21|All|[Upstream](#upstream)| +|Lexus|NX Hybrid 2018-19|All|[Upstream](#upstream)| +|Lexus|NX Hybrid 2020-21|All|[Upstream](#upstream)| +|Lexus|RC 2018-20|All|[Upstream](#upstream)| +|Lexus|RX 2016|Lexus Safety System+|[Upstream](#upstream)| +|Lexus|RX 2017-19|All|[Upstream](#upstream)| +|Lexus|RX 2020-22|All|[Upstream](#upstream)| +|Lexus|RX Hybrid 2016|Lexus Safety System+|[Upstream](#upstream)| +|Lexus|RX Hybrid 2017-19|All|[Upstream](#upstream)| +|Lexus|RX Hybrid 2020-22|All|[Upstream](#upstream)| +|Lexus|UX Hybrid 2019-23|All|[Upstream](#upstream)| +|Lincoln|Aviator 2020-23|Co-Pilot360 Plus|[Upstream](#upstream)| +|Lincoln|Aviator Plug-in Hybrid 2020-23|Co-Pilot360 Plus|[Upstream](#upstream)| +|MAN|eTGE 2020-24|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|MAN|TGE 2017-24|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Mazda|3 2017-18|All|[Dashcam mode](#dashcam)| +|Mazda|6 2017-20|All|[Dashcam mode](#dashcam)| +|Mazda|CX-5 2017-21|All|[Dashcam mode](#dashcam)| +|Mazda|CX-5 2022-24|All|[Upstream](#upstream)| +|Mazda|CX-9 2016-20|All|[Dashcam mode](#dashcam)| +|Mazda|CX-9 2021-23|All|[Upstream](#upstream)| +|Nissan|Altima 2019-20|ProPILOT Assist|[Upstream](#upstream)| +|Nissan|Leaf 2018-23|ProPILOT Assist|[Upstream](#upstream)| +|Nissan|Rogue 2018-20|ProPILOT Assist|[Upstream](#upstream)| +|Nissan|X-Trail 2017|ProPILOT Assist|[Upstream](#upstream)| +|Ram|1500 2019-24|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| +|Ram|2500 2020-24|Adaptive Cruise Control (ACC)|[Dashcam mode](#dashcam)| +|Ram|3500 2019-22|Adaptive Cruise Control (ACC)|[Dashcam mode](#dashcam)| +|SEAT|Alhambra 2018-20|Adaptive Cruise Control (ACC) & Lane Assist|[Dashcam mode](#dashcam)| +|SEAT|Ateca 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|SEAT|Leon 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Subaru|Ascent 2019-21|All|[Upstream](#upstream)| +|Subaru|Ascent 2023|All|[Dashcam mode](#dashcam)| +|Subaru|Crosstrek 2018-19|EyeSight Driver Assistance|[Upstream](#upstream)| +|Subaru|Crosstrek 2020-23|EyeSight Driver Assistance|[Upstream](#upstream)| +|Subaru|Crosstrek Hybrid 2020|EyeSight Driver Assistance|[Dashcam mode](#dashcam)| +|Subaru|Forester 2017-18|EyeSight Driver Assistance|[Dashcam mode](#dashcam)| +|Subaru|Forester 2019-21|All|[Upstream](#upstream)| +|Subaru|Forester 2022-24|All|[Dashcam mode](#dashcam)| +|Subaru|Forester Hybrid 2020|EyeSight Driver Assistance|[Dashcam mode](#dashcam)| +|Subaru|Impreza 2017-19|EyeSight Driver Assistance|[Upstream](#upstream)| +|Subaru|Impreza 2020-22|EyeSight Driver Assistance|[Upstream](#upstream)| +|Subaru|Legacy 2015-18|EyeSight Driver Assistance|[Dashcam mode](#dashcam)| +|Subaru|Legacy 2020-22|All|[Upstream](#upstream)| +|Subaru|Outback 2015-17|EyeSight Driver Assistance|[Dashcam mode](#dashcam)| +|Subaru|Outback 2018-19|EyeSight Driver Assistance|[Dashcam mode](#dashcam)| +|Subaru|Outback 2020-22|All|[Upstream](#upstream)| +|Subaru|Outback 2023|All|[Dashcam mode](#dashcam)| +|Subaru|Solterra 2023-25|Any|[Not compatible](#can-bus-security)| +|Subaru|XV 2018-19|EyeSight Driver Assistance|[Upstream](#upstream)| +|Subaru|XV 2020-21|EyeSight Driver Assistance|[Upstream](#upstream)| +|Škoda|Fabia 2022-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Škoda|Kamiq 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Škoda|Karoq 2019-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Škoda|Kodiaq 2017-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Škoda|Octavia 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Škoda|Octavia RS 2016|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Škoda|Octavia Scout 2017-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Škoda|Scala 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Škoda|Superb 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Tesla|Model 3|All|[Dashcam mode](#dashcam)| +|Tesla|Model Y|All|[Dashcam mode](#dashcam)| +|Toyota|Alphard 2019-20|All|[Upstream](#upstream)| +|Toyota|Alphard Hybrid 2021|All|[Upstream](#upstream)| +|Toyota|Avalon 2016|Toyota Safety Sense P|[Upstream](#upstream)| +|Toyota|Avalon 2017-18|All|[Upstream](#upstream)| +|Toyota|Avalon 2019-21|All|[Upstream](#upstream)| +|Toyota|Avalon 2022|All|[Upstream](#upstream)| +|Toyota|Avalon Hybrid 2019-21|All|[Upstream](#upstream)| +|Toyota|Avalon Hybrid 2022|All|[Upstream](#upstream)| +|Toyota|bZ4x 2023-25|Any|[Not compatible](#can-bus-security)| +|Toyota|C-HR 2017-20|All|[Upstream](#upstream)| +|Toyota|C-HR 2021|All|[Upstream](#upstream)| +|Toyota|C-HR Hybrid 2017-20|All|[Upstream](#upstream)| +|Toyota|C-HR Hybrid 2021-22|All|[Upstream](#upstream)| +|Toyota|Camry 2018-20|All|[Upstream](#upstream)| +|Toyota|Camry 2021-24|All|[Upstream](#upstream)| +|Toyota|Camry 2025|Any|[Not compatible](#can-bus-security)| +|Toyota|Camry Hybrid 2018-20|All|[Upstream](#upstream)| +|Toyota|Camry Hybrid 2021-24|All|[Upstream](#upstream)| +|Toyota|Corolla 2017-19|All|[Upstream](#upstream)| +|Toyota|Corolla 2020-22|All|[Upstream](#upstream)| +|Toyota|Corolla Cross 2022-25|Any|[Not compatible](#can-bus-security)| +|Toyota|Corolla Cross (Non-US only) 2020-23|All|[Upstream](#upstream)| +|Toyota|Corolla Cross Hybrid (Non-US only) 2020-22|All|[Upstream](#upstream)| +|Toyota|Corolla Hatchback 2019-22|All|[Upstream](#upstream)| +|Toyota|Corolla Hybrid 2020-22|All|[Upstream](#upstream)| +|Toyota|Corolla Hybrid (South America only) 2020-23|All|[Upstream](#upstream)| +|Toyota|Highlander 2017-19|All|[Upstream](#upstream)| +|Toyota|Highlander 2020-23|All|[Upstream](#upstream)| +|Toyota|Highlander 2025|Any|[Not compatible](#can-bus-security)| +|Toyota|Highlander Hybrid 2017-19|All|[Upstream](#upstream)| +|Toyota|Highlander Hybrid 2020-23|All|[Upstream](#upstream)| +|Toyota|Mirai 2021|All|[Upstream](#upstream)| +|Toyota|Prius 2016|Toyota Safety Sense P|[Upstream](#upstream)| +|Toyota|Prius 2017-20|All|[Upstream](#upstream)| +|Toyota|Prius 2021-22|All|[Upstream](#upstream)| +|Toyota|Prius Prime 2017-20|All|[Upstream](#upstream)| +|Toyota|Prius Prime 2021-22|All|[Upstream](#upstream)| +|Toyota|Prius v 2017|Toyota Safety Sense P|[Upstream](#upstream)| +|Toyota|RAV4 2016|Toyota Safety Sense P|[Upstream](#upstream)| +|Toyota|RAV4 2017-18|All|[Upstream](#upstream)| +|Toyota|RAV4 2019-21|All|[Upstream](#upstream)| +|Toyota|RAV4 2022|All|[Upstream](#upstream)| +|Toyota|RAV4 2023-24|All|[Upstream](#upstream)| +|Toyota|RAV4 Hybrid 2016|Toyota Safety Sense P|[Upstream](#upstream)| +|Toyota|RAV4 Hybrid 2017-18|All|[Upstream](#upstream)| +|Toyota|RAV4 Hybrid 2019-21|All|[Upstream](#upstream)| +|Toyota|RAV4 Hybrid 2022|All|[Upstream](#upstream)| +|Toyota|RAV4 Hybrid 2023-24|All|[Upstream](#upstream)| +|Toyota|RAV4 Prime 2021-23|Any|[Community](#community)| +|Toyota|RAV4 Prime 2024-25|Any|[Not compatible](#can-bus-security)| +|Toyota|Sequoia 2023-25|Any|[Not compatible](#can-bus-security)| +|Toyota|Sienna 2018-20|All|[Upstream](#upstream)| +|Toyota|Sienna 2021-23|Any|[Community](#community)| +|Toyota|Sienna 2024-25|Any|[Not compatible](#can-bus-security)| +|Toyota|Tundra 2022-25|Any|[Not compatible](#can-bus-security)| +|Toyota|Venza 2021-25|Any|[Not compatible](#can-bus-security)| +|Volkswagen|Arteon 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Arteon eHybrid 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Arteon R 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Arteon Shooting Brake 2020-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Atlas 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Atlas Cross Sport 2020-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Caddy 2019|Adaptive Cruise Control (ACC) & Lane Assist|[Dashcam mode](#dashcam)| +|Volkswagen|Caddy Maxi 2019|Adaptive Cruise Control (ACC) & Lane Assist|[Dashcam mode](#dashcam)| +|Volkswagen|California 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Caravelle 2020|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|CC 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Crafter 2017-24|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|e-Crafter 2018-24|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|e-Golf 2014-20|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Golf 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Golf Alltrack 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Golf GTD 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Golf GTE 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Golf GTI 2015-21|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Golf R 2015-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Golf SportsVan 2015-20|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Grand California 2019-24|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Jetta 2015-18|Adaptive Cruise Control (ACC) & Lane Assist|[Dashcam mode](#dashcam)| +|Volkswagen|Jetta 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Jetta GLI 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Passat 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Passat Alltrack 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Passat GTE 2015-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Passat NMS 2017-22|Adaptive Cruise Control (ACC) & Lane Assist|[Dashcam mode](#dashcam)| +|Volkswagen|Polo 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Polo GTI 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Sharan 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|[Dashcam mode](#dashcam)| +|Volkswagen|T-Cross 2021|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|T-Roc 2018-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Taos 2022-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Teramont 2018-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Teramont Cross Sport 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Teramont X 2021-22|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Tiguan 2018-24|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Tiguan eHybrid 2021-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| +|Volkswagen|Touran 2016-23|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| + +# Types of Support + +**opendbc can support many more cars than it currently does.** There are a few reasons your car may not be supported. +If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! +We're adding support for new cars all the time. **We don't have a roadmap for car support**, and in fact, most car +support comes from users like you! + +## Upstream + +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. + +## Under Review + +A vehicle under review is one for which software support has been merged into upstream openpilot, but hasn't yet been +tested for drive quality and conformance with [comma safety guidelines](https://github.com/commaai/openpilot/blob/master/docs/SAFETY.md). +This is a normal part of the development and quality assurance process. This vehicle will not work when upstream +openpilot is installed, but custom forks may allow their use. + +## Custom + +Vehicles in this category are not considered plug-and-play. Software support is included in upstream openpilot, but +these vehicles might not have a harness in the comma store, or the physical install might be at an unusual or cumbersome +location, or they might need unusual configuration after install. + +## Dashcam + +Dashcam vehicles have software support in upstream openpilot, but will go into "dashcam mode" at startup and will not +engage. This may be due to known issues with driving safety or quality, or it may be a work in progress that isn't yet +ready for safety and quality review. + +## Community + +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/). + +Some notable works-in-progress: +* Honda + * 2024 Acura Integra, commaai/openpilot#32056 + * 2023-24 Honda Accord (CAN-FD), commaai/openpilot#32229 + * 2024 Honda CR-V (CAN-FD), commaai/openpilot#32806 + * 2024 Honda CR-V Hybrid (CAN-FD), commaai/openpilot#31527 + * Depends on commaai/opendbc#1100 + * 2021-25 Honda Odyssey, commaai/opendbc#1330 + * 2023-24 Honda Pilot (CAN-FD), commaai/openpilot#30324 + * Camera ACC stability improvements, commaai/openpilot#31022 + * Depends on commaai/panda#1814 + * Depends on commaai/opendbc#998 + * These are being reworked for full-time proxy through openpilot + * Manual transmission support (Civic, Integra) + * Depends on commaai/opendbc#1034 (merged) + * Car port support PR not yet filed + +## Incompatible + +### CAN Bus Security + +Vehicles with CAN security measures, such as AUTOSAR Secure Onboard Communication (SecOC) are not usable with openpilot +unless the owner can recover the message signing key and implement CAN message signing. Examples include certain newer +Toyota, and the GM Global B platform. + +### FlexRay + +All the cars that openpilot supports use a [CAN bus](https://en.wikipedia.org/wiki/CAN_bus) for communication between all the car's computers, however a +CAN bus isn't the only way that the computers in your car can communicate. Most, if not all, vehicles from the following +manufacturers use [FlexRay](https://en.wikipedia.org/wiki/FlexRay) instead of a CAN bus: **BMW, Mercedes, Audi, Land Rover, and some Volvo**. These cars +may one day be supported, but we have no immediate plans to support FlexRay. \ No newline at end of file diff --git a/opendbc_repo/examples/joystick.py b/opendbc_repo/examples/joystick.py new file mode 100755 index 000000000000000..0167c8d201281b1 --- /dev/null +++ b/opendbc_repo/examples/joystick.py @@ -0,0 +1,113 @@ +#!/usr/bin/env python3 +import time +import threading +import argparse +import numpy as np +from pprint import pprint +from inputs import get_gamepad + +from kbhit import KBHit + +from opendbc.car.structs import CarControl +from opendbc.car.panda_runner import PandaRunner + +class Keyboard: + def __init__(self): + self.kb = KBHit() + self.axis_increment = 0.05 # 5% of full actuation each key press + self.axes_map = {'w': 'gb', 's': 'gb', + 'a': 'steer', 'd': 'steer'} + self.axes_values = {'gb': 0., 'steer': 0.} + self.axes_order = ['gb', 'steer'] + self.cancel = False + + def update(self): + key = self.kb.getch().lower() + print(key) + self.cancel = False + if key == 'r': + self.axes_values = {ax: 0. for ax in self.axes_values} + elif key == 'c': + self.cancel = True + elif key in self.axes_map: + axis = self.axes_map[key] + incr = self.axis_increment if key in ['w', 'a'] else -self.axis_increment + self.axes_values[axis] = float(np.clip(self.axes_values[axis] + incr, -1, 1)) + else: + return False + return True + +class Joystick: + def __init__(self, gamepad=False): + # TODO: find a way to get this from API, perhaps "inputs" doesn't support it + if gamepad: + self.cancel_button = 'BTN_NORTH' # (BTN_NORTH=X, ABS_RZ=Right Trigger) + accel_axis = 'ABS_Y' + steer_axis = 'ABS_RX' + else: + self.cancel_button = 'BTN_TRIGGER' + accel_axis = 'ABS_Y' + steer_axis = 'ABS_RX' + self.min_axis_value = {accel_axis: 0., steer_axis: 0.} + self.max_axis_value = {accel_axis: 255., steer_axis: 255.} + self.axes_values = {accel_axis: 0., steer_axis: 0.} + self.axes_order = [accel_axis, steer_axis] + self.cancel = False + + def update(self): + joystick_event = get_gamepad()[0] + event = (joystick_event.code, joystick_event.state) + if event[0] == self.cancel_button: + if event[1] == 1: + self.cancel = True + elif event[1] == 0: # state 0 is falling edge + self.cancel = False + elif event[0] in self.axes_values: + self.max_axis_value[event[0]] = max(event[1], self.max_axis_value[event[0]]) + self.min_axis_value[event[0]] = min(event[1], self.min_axis_value[event[0]]) + + norm = -float(np.interp(event[1], [self.min_axis_value[event[0]], self.max_axis_value[event[0]]], [-1., 1.])) + self.axes_values[event[0]] = norm if abs(norm) > 0.05 else 0. # center can be noisy, deadzone of 5% + else: + return False + return True + +def joystick_thread(joystick): + while True: + joystick.update() + +def main(joystick): + threading.Thread(target=joystick_thread, args=(joystick,), daemon=True).start() + with PandaRunner() as p: + CC = CarControl(enabled=False) + while True: + CC.actuators.accel = float(4.0*np.clip(joystick.axes_values['gb'], -1, 1)) + CC.actuators.steer = float(np.clip(joystick.axes_values['steer'], -1, 1)) + pprint(CC) + + p.read() + p.write(CC) + + # 100Hz + time.sleep(0.01) + + +if __name__ == '__main__': + parser = argparse.ArgumentParser(description='Test the car interface with a joystick. Uses keyboard by default.', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument('--mode', choices=['keyboard', 'gamepad', 'joystick'], default='keyboard') + args = parser.parse_args() + + print() + joystick: Keyboard | Joystick + if args.mode == 'keyboard': + print('Gas/brake control: `W` and `S` keys') + print('Steering control: `A` and `D` keys') + print('Buttons') + print('- `R`: Resets axes') + print('- `C`: Cancel cruise control') + joystick = Keyboard() + else: + joystick = Joystick(gamepad=(args.mode == 'gamepad')) + main(joystick) \ No newline at end of file diff --git a/opendbc_repo/examples/kbhit.py b/opendbc_repo/examples/kbhit.py new file mode 100755 index 000000000000000..35f67b4771212b2 --- /dev/null +++ b/opendbc_repo/examples/kbhit.py @@ -0,0 +1,59 @@ +#!/usr/bin/env python3 +import sys +import termios +import atexit +from select import select + +STDIN_FD = sys.stdin.fileno() + +class KBHit: + def __init__(self) -> None: + self.set_kbhit_terminal() + + def set_kbhit_terminal(self) -> None: + # Save the terminal settings + self.old_term = termios.tcgetattr(STDIN_FD) + self.new_term = self.old_term.copy() + + # New terminal setting unbuffered + self.new_term[3] &= ~(termios.ICANON | termios.ECHO) + termios.tcsetattr(STDIN_FD, termios.TCSAFLUSH, self.new_term) + + # Support normal-terminal reset at exit + atexit.register(self.set_normal_term) + + def set_normal_term(self) -> None: + termios.tcsetattr(STDIN_FD, termios.TCSAFLUSH, self.old_term) + + @staticmethod + def getch() -> str: + return sys.stdin.read(1) + + @staticmethod + def getarrow() -> int: + c = sys.stdin.read(3)[2] + vals = [65, 67, 66, 68] + return vals.index(ord(c)) + + @staticmethod + def kbhit(): + ''' Returns True if keyboard character was hit, False otherwise. + ''' + return select([sys.stdin], [], [], 0)[0] != [] + + +if __name__ == "__main__": + + kb = KBHit() + + print('Hit any key, or ESC to exit') + + while True: + + if kb.kbhit(): + c = kb.getch() + if c == '\x1b': # ESC + break + print(c) + + kb.set_normal_term() diff --git a/opendbc_repo/opendbc/__init__.py b/opendbc_repo/opendbc/__init__.py new file mode 100644 index 000000000000000..a40e5dbfa8c7def --- /dev/null +++ b/opendbc_repo/opendbc/__init__.py @@ -0,0 +1,3 @@ +import os + +DBC_PATH = os.path.join(os.path.dirname(os.path.abspath(__file__)), 'dbc') diff --git a/opendbc_repo/opendbc/can/SConscript b/opendbc_repo/opendbc/can/SConscript new file mode 100644 index 000000000000000..9f6825a93f1cf2d --- /dev/null +++ b/opendbc_repo/opendbc/can/SConscript @@ -0,0 +1,23 @@ +Import('env', 'envCython', 'common', 'arch') + +envDBC = env.Clone() +dbc_file_path = '-DDBC_FILE_PATH=\'"%s"\'' % (envDBC.Dir("../dbc").abspath) +envDBC['CXXFLAGS'] += [dbc_file_path] +src = ["dbc.cc", "parser.cc", "packer.cc", "common.cc"] + +# shared library for openpilot +LINKFLAGS = envDBC["LINKFLAGS"] +if arch == "Darwin": + LINKFLAGS += ["-Wl,-install_name,@loader_path/libdbc.dylib"] +libdbc = envDBC.SharedLibrary('libdbc', src, LIBS=[common, ], LINKFLAGS=LINKFLAGS) + +# Build packer and parser +lenv = envCython.Clone() +lenv["LIBPATH"].append(Dir(".")) +lenv["RPATH"] = [libdbc[0].dir.abspath, ] +parser = lenv.Program('parser_pyx.so', 'parser_pyx.pyx', LIBS=[common, libdbc[0].name]) +packer = lenv.Program('packer_pyx.so', 'packer_pyx.pyx', LIBS=[common, libdbc[0].name]) + +opendbc_python = Alias("opendbc_python", [parser, packer]) + +Export('opendbc_python') diff --git a/opendbc/can/__init__.py b/opendbc_repo/opendbc/can/__init__.py similarity index 100% rename from opendbc/can/__init__.py rename to opendbc_repo/opendbc/can/__init__.py diff --git a/opendbc/can/can_define.py b/opendbc_repo/opendbc/can/can_define.py similarity index 100% rename from opendbc/can/can_define.py rename to opendbc_repo/opendbc/can/can_define.py diff --git a/opendbc_repo/opendbc/can/common.cc b/opendbc_repo/opendbc/can/common.cc new file mode 100644 index 000000000000000..1b6a114fd07235e --- /dev/null +++ b/opendbc_repo/opendbc/can/common.cc @@ -0,0 +1,245 @@ +#include +#include + +#include "opendbc/can/common.h" + +unsigned int honda_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + int s = 0; + bool extended = address > 0x7FF; + while (address) { s += (address & 0xF); address >>= 4; } + for (int i = 0; i < d.size(); i++) { + uint8_t x = d[i]; + if (i == d.size()-1) x >>= 4; // remove checksum + s += (x & 0xF) + (x >> 4); + } + s = 8-s; + if (extended) s += 3; // extended can + + return s & 0xF; +} + +unsigned int toyota_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + unsigned int s = d.size(); + while (address) { s += address & 0xFF; address >>= 8; } + for (int i = 0; i < d.size() - 1; i++) { s += d[i]; } + + return s & 0xFF; +} + +unsigned int subaru_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + unsigned int s = 0; + while (address) { s += address & 0xFF; address >>= 8; } + + // skip checksum in first byte + for (int i = 1; i < d.size(); i++) { s += d[i]; } + + return s & 0xFF; +} + +unsigned int chrysler_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + // jeep chrysler canbus checksum from http://illmatics.com/Remote%20Car%20Hacking.pdf + uint8_t checksum = 0xFF; + for (int j = 0; j < (d.size() - 1); j++) { + uint8_t shift = 0x80; + uint8_t curr = d[j]; + for (int i = 0; i < 8; i++) { + uint8_t bit_sum = curr & shift; + uint8_t temp_chk = checksum & 0x80U; + if (bit_sum != 0U) { + bit_sum = 0x1C; + if (temp_chk != 0U) { + bit_sum = 1; + } + checksum = checksum << 1; + temp_chk = checksum | 1U; + bit_sum ^= temp_chk; + } else { + if (temp_chk != 0U) { + bit_sum = 0x1D; + } + checksum = checksum << 1; + bit_sum ^= checksum; + } + checksum = bit_sum; + shift = shift >> 1; + } + } + return ~checksum & 0xFF; +} + +// Static lookup table for fast computation of CRCs +uint8_t crc8_lut_8h2f[256]; // CRC8 poly 0x2F, aka 8H2F/AUTOSAR +uint8_t crc8_lut_j1850[256]; // CRC8 poly 0x1D, aka SAE J1850 +uint16_t crc16_lut_xmodem[256]; // CRC16 poly 0x1021, aka XMODEM + +void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]) { + uint8_t crc; + int i, j; + + for (i = 0; i < 256; i++) { + crc = i; + for (j = 0; j < 8; j++) { + if ((crc & 0x80) != 0) + crc = (uint8_t)((crc << 1) ^ poly); + else + crc <<= 1; + } + crc_lut[i] = crc; + } +} + +void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) { + uint16_t crc; + int i, j; + + for (i = 0; i < 256; i++) { + crc = i << 8; + for (j = 0; j < 8; j++) { + if ((crc & 0x8000) != 0) { + crc = (uint16_t)((crc << 1) ^ poly); + } else { + crc <<= 1; + } + } + crc_lut[i] = crc; + } +} + +// Initializes CRC lookup tables at module initialization +struct CrcInitializer { + CrcInitializer() { + gen_crc_lookup_table_8(0x2F, crc8_lut_8h2f); // CRC-8 8H2F/AUTOSAR for Volkswagen + gen_crc_lookup_table_8(0x1D, crc8_lut_j1850); // CRC-8 SAE-J1850 + gen_crc_lookup_table_16(0x1021, crc16_lut_xmodem); // CRC-16 XMODEM for HKG CAN FD + } +}; + +static CrcInitializer crcInitializer; + +static const std::unordered_map> volkswagen_mqb_crc_constants { + {0x40, {0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40}}, // Airbag_01 + {0x86, {0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86}}, // LWI_01 + {0x9F, {0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5}}, // LH_EPS_03 + {0xAD, {0x3F, 0x69, 0x39, 0xDC, 0x94, 0xF9, 0x14, 0x64, 0xD8, 0x6A, 0x34, 0xCE, 0xA2, 0x55, 0xB5, 0x2C}}, // Getriebe_11 + {0xFD, {0xB4, 0xEF, 0xF8, 0x49, 0x1E, 0xE5, 0xC2, 0xC0, 0x97, 0x19, 0x3C, 0xC9, 0xF1, 0x98, 0xD6, 0x61}}, // ESP_21 + {0x101, {0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA, 0xAA}}, // ESP_02 + {0x106, {0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07}}, // ESP_05 + {0x116, {0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC, 0xAC}}, // ESP_10 + {0x117, {0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16}}, // ACC_10 + {0x120, {0xC4, 0xE2, 0x4F, 0xE4, 0xF8, 0x2F, 0x56, 0x81, 0x9F, 0xE5, 0x83, 0x44, 0x05, 0x3F, 0x97, 0xDF}}, // TSK_06 + {0x121, {0xE9, 0x65, 0xAE, 0x6B, 0x7B, 0x35, 0xE5, 0x5F, 0x4E, 0xC7, 0x86, 0xA2, 0xBB, 0xDD, 0xEB, 0xB4}}, // Motor_20 + {0x122, {0x37, 0x7D, 0xF3, 0xA9, 0x18, 0x46, 0x6D, 0x4D, 0x3D, 0x71, 0x92, 0x9C, 0xE5, 0x32, 0x10, 0xB9}}, // ACC_06 + {0x126, {0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA}}, // HCA_01 + {0x12B, {0x6A, 0x38, 0xB4, 0x27, 0x22, 0xEF, 0xE1, 0xBB, 0xF8, 0x80, 0x84, 0x49, 0xC7, 0x9E, 0x1E, 0x2B}}, // GRA_ACC_01 + {0x12E, {0xF8, 0xE5, 0x97, 0xC9, 0xD6, 0x07, 0x47, 0x21, 0x66, 0xDD, 0xCF, 0x6F, 0xA1, 0x94, 0x74, 0x63}}, // ACC_07 + {0x187, {0x7F, 0xED, 0x17, 0xC2, 0x7C, 0xEB, 0x44, 0x21, 0x01, 0xFA, 0xDB, 0x15, 0x4A, 0x6B, 0x23, 0x05}}, // Motor_EV_01 + {0x1AB, {0x13, 0x21, 0x9B, 0x6A, 0x9A, 0x62, 0xD4, 0x65, 0x18, 0xF1, 0xAB, 0x16, 0x32, 0x89, 0xE7, 0x26}}, // ESP_33 + {0x30C, {0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F}}, // ACC_02 + {0x30F, {0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C}}, // SWA_01 + {0x324, {0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27}}, // ACC_04 + {0x3C0, {0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3}}, // Klemmen_Status_01 + {0x3D5, {0xC5, 0x39, 0xC7, 0xF9, 0x92, 0xD8, 0x24, 0xCE, 0xF1, 0xB5, 0x7A, 0xC4, 0xBC, 0x60, 0xE3, 0xD1}}, // Licht_Anf_01 + {0x65D, {0xAC, 0xB3, 0xAB, 0xEB, 0x7A, 0xE1, 0x3B, 0xF7, 0x73, 0xBA, 0x7C, 0x9E, 0x06, 0x5F, 0x02, 0xD9}}, // ESP_20 +}; + +unsigned int volkswagen_mqb_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + // This is AUTOSAR E2E Profile 2, CRC-8H2F with a "data ID" (varying by message/counter) appended to the payload + + uint8_t crc = 0xFF; // CRC-8H2F initial value + + // CRC over payload first, skipping the first byte where the CRC lives + for (int i = 1; i < d.size(); i++) { + crc ^= d[i]; + crc = crc8_lut_8h2f[crc]; + } + + // Continue CRC over the "data ID" + uint8_t counter = d[1] & 0x0F; + auto crc_const = volkswagen_mqb_crc_constants.find(address); + if (crc_const != volkswagen_mqb_crc_constants.end()) { + crc ^= crc_const->second[counter]; + crc = crc8_lut_8h2f[crc]; + } else { + printf("Attempt to CRC check undefined Volkswagen message 0x%02X\n", address); + } + + return crc ^ 0xFF; // CRC-8H2F final XOR +} + +unsigned int xor_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + uint8_t checksum = 0; + int checksum_byte = sig.start_bit / 8; + + // Simple XOR over the payload, except for the byte where the checksum lives. + for (int i = 0; i < d.size(); i++) { + if (i != checksum_byte) { + checksum ^= d[i]; + } + } + + return checksum; +} + +unsigned int pedal_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + uint8_t crc = 0xFF; + uint8_t poly = 0xD5; // standard crc8 + + // skip checksum byte + for (int i = d.size()-2; i >= 0; i--) { + crc ^= d[i]; + for (int j = 0; j < 8; j++) { + if ((crc & 0x80) != 0) { + crc = (uint8_t)((crc << 1) ^ poly); + } else { + crc <<= 1; + } + } + } + return crc; +} + +unsigned int hkg_can_fd_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + uint16_t crc = 0; + + for (int i = 2; i < d.size(); i++) { + crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ d[i]]; + } + + // Add address to crc + crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ ((address >> 0) & 0xFF)]; + crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ ((address >> 8) & 0xFF)]; + + if (d.size() == 8) { + crc ^= 0x5f29; + } else if (d.size() == 16) { + crc ^= 0x041d; + } else if (d.size() == 24) { + crc ^= 0x819d; + } else if (d.size() == 32) { + crc ^= 0x9f5b; + } + + return crc; +} + +unsigned int fca_giorgio_checksum(uint32_t address, const Signal &sig, const std::vector &d) { + // CRC is in the last byte, poly is same as SAE J1850 but uses a different init value and final XOR + uint8_t crc = 0x00; + + for (int i = 0; i < d.size() - 1; i++) { + crc ^= d[i]; + crc = crc8_lut_j1850[crc]; + } + + // Final XOR varies for EPS messages, all others use a common value + if (address == 0xDE) { // EPS_1 + return crc ^ 0x10; + } else if (address == 0x106) { // EPS_2 + return crc ^ 0xF6; + } else if (address == 0x122) { // EPS_3 + return crc ^ 0xF1; + } else { + return crc ^ 0xA; + } + +} diff --git a/opendbc/can/common.h b/opendbc_repo/opendbc/can/common.h similarity index 80% rename from opendbc/can/common.h rename to opendbc_repo/opendbc/can/common.h index 46b3159b9f7acf0..247ac62aa2660c7 100644 --- a/opendbc/can/common.h +++ b/opendbc_repo/opendbc/can/common.h @@ -1,18 +1,12 @@ #pragma once #include +#include #include #include #include #include -#include -#include - -#ifndef DYNAMIC_CAPNP -#include "cereal/gen/cpp/log.capnp.h" -#endif - #include "opendbc/can/logger.h" #include "opendbc/can/common_dbc.h" @@ -32,8 +26,20 @@ unsigned int chrysler_checksum(uint32_t address, const Signal &sig, const std::v unsigned int volkswagen_mqb_checksum(uint32_t address, const Signal &sig, const std::vector &d); unsigned int xor_checksum(uint32_t address, const Signal &sig, const std::vector &d); unsigned int hkg_can_fd_checksum(uint32_t address, const Signal &sig, const std::vector &d); +unsigned int fca_giorgio_checksum(uint32_t address, const Signal &sig, const std::vector &d); unsigned int pedal_checksum(uint32_t address, const Signal &sig, const std::vector &d); +struct CanFrame { + long src; + uint32_t address; + std::vector dat; +}; + +struct CanData { + uint64_t nanos; + std::vector frames; +}; + class MessageState { public: std::string name; @@ -60,8 +66,6 @@ class MessageState { class CANParser { private: const int bus; - kj::Array aligned_buf; - const DBC *dbc = NULL; std::unordered_map message_states; @@ -69,7 +73,6 @@ class CANParser { bool can_valid = false; bool bus_timeout = false; 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; @@ -77,14 +80,12 @@ class CANParser { CANParser(int abus, const std::string& dbc_name, const std::vector> &messages); CANParser(int abus, const std::string& dbc_name, bool ignore_checksum, bool ignore_counter); - #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 nanos, const capnp::List::Reader& cans); - #endif - void UpdateCans(uint64_t nanos, const capnp::DynamicStruct::Reader& cans); + std::set update(const std::vector &can_data); + MessageState *getMessageState(uint32_t address) { return &message_states.at(address); } + +protected: + void UpdateCans(const CanData &can, std::set &updated_addresses); void UpdateValid(uint64_t nanos); - void query_latest(std::vector &vals, uint64_t last_ts = 0); }; class CANPacker { diff --git a/opendbc/can/common.pxd b/opendbc_repo/opendbc/can/common.pxd similarity index 76% rename from opendbc/can/common.pxd rename to opendbc_repo/opendbc/can/common.pxd index 4dab92cd5f12262..33e368a83989c9a 100644 --- a/opendbc/can/common.pxd +++ b/opendbc_repo/opendbc/can/common.pxd @@ -1,9 +1,10 @@ # distutils: language = c++ # cython: language_level=3 -from libc.stdint cimport uint8_t, uint16_t, uint32_t, uint64_t +from libc.stdint cimport uint8_t, uint32_t, uint64_t from libcpp cimport bool from libcpp.pair cimport pair +from libcpp.set cimport set from libcpp.string cimport string from libcpp.vector cimport vector from libcpp.unordered_map cimport unordered_map @@ -23,6 +24,7 @@ cdef extern from "common_dbc.h": SUBARU_CHECKSUM, CHRYSLER_CHECKSUM HKG_CAN_FD_CHECKSUM, + FCA_GIORGIO_CHECKSUM, cdef struct Signal: string name @@ -52,13 +54,6 @@ cdef extern from "common_dbc.h": unordered_map[uint32_t, const Msg*] addr_to_msg unordered_map[string, const Msg*] name_to_msg - cdef struct SignalValue: - uint32_t address - uint64_t ts_nanos - string name - double value - vector[double] all_values - cdef struct SignalPackValue: string name double value @@ -67,11 +62,27 @@ cdef extern from "common_dbc.h": cdef extern from "common.h": cdef const DBC* dbc_lookup(const string) except + + cdef cppclass MessageState: + vector[Signal] parse_sigs + vector[double] vals + vector[vector[double]] all_vals + uint64_t last_seen_nanos + + cdef struct CanFrame: + long src + uint32_t address + vector[uint8_t] dat + + cdef struct CanData: + uint64_t nanos + vector[CanFrame] frames + cdef cppclass CANParser: bool can_valid bool bus_timeout CANParser(int, string, vector[pair[uint32_t, int]]) except + - void update_strings(vector[string]&, vector[SignalValue]&, bool) except + + set[uint32_t] update(vector[CanData]&) except + + MessageState *getMessageState(uint32_t address) cdef cppclass CANPacker: CANPacker(string) diff --git a/opendbc/can/common_dbc.h b/opendbc_repo/opendbc/can/common_dbc.h similarity index 89% rename from opendbc/can/common_dbc.h rename to opendbc_repo/opendbc/can/common_dbc.h index 19507ecd4e510c1..0d2170ff5f9f4b7 100644 --- a/opendbc/can/common_dbc.h +++ b/opendbc_repo/opendbc/can/common_dbc.h @@ -10,14 +10,6 @@ struct SignalPackValue { double value; }; -struct SignalValue { - uint32_t address; - uint64_t ts_nanos; - std::string name; - double value; // latest value - std::vector all_values; // all values from this cycle -}; - enum SignalType { DEFAULT, COUNTER, @@ -29,6 +21,7 @@ enum SignalType { SUBARU_CHECKSUM, CHRYSLER_CHECKSUM, HKG_CAN_FD_CHECKSUM, + FCA_GIORGIO_CHECKSUM, }; struct Signal { diff --git a/opendbc/can/dbc.cc b/opendbc_repo/opendbc/can/dbc.cc similarity index 97% rename from opendbc/can/dbc.cc rename to opendbc_repo/opendbc/can/dbc.cc index 44454b15f826250..8f361af1fda1d81 100644 --- a/opendbc/can/dbc.cc +++ b/opendbc_repo/opendbc/can/dbc.cc @@ -57,7 +57,7 @@ ChecksumState* get_checksum(const std::string& dbc_name) { s = new ChecksumState({8, -1, 7, -1, false, TOYOTA_CHECKSUM, &toyota_checksum}); } else if (startswith(dbc_name, "hyundai_canfd")) { s = new ChecksumState({16, -1, 0, -1, true, HKG_CAN_FD_CHECKSUM, &hkg_can_fd_checksum}); - } else if (startswith(dbc_name, "vw_mqb_2010")) { + } else if (startswith(dbc_name, {"vw_mqb_2010", "vw_mqbevo"})) { s = new ChecksumState({8, 4, 0, 0, true, VOLKSWAGEN_MQB_CHECKSUM, &volkswagen_mqb_checksum}); } else if (startswith(dbc_name, "vw_golf_mk4")) { s = new ChecksumState({8, 4, 0, -1, true, XOR_CHECKSUM, &xor_checksum}); @@ -65,6 +65,8 @@ ChecksumState* get_checksum(const std::string& dbc_name) { s = new ChecksumState({8, -1, 0, -1, true, SUBARU_CHECKSUM, &subaru_checksum}); } else if (startswith(dbc_name, "chrysler_")) { s = new ChecksumState({8, -1, 7, -1, false, CHRYSLER_CHECKSUM, &chrysler_checksum}); + } else if (startswith(dbc_name, "fca_giorgio")) { + s = new ChecksumState({8, -1, 7, -1, false, FCA_GIORGIO_CHECKSUM, &fca_giorgio_checksum}); } else if (startswith(dbc_name, "comma_body")) { s = new ChecksumState({8, 4, 7, 3, false, PEDAL_CHECKSUM, &pedal_checksum}); } @@ -222,7 +224,7 @@ DBC* dbc_parse(const std::string& dbc_path) { const std::string get_dbc_root_path() { char *basedir = std::getenv("BASEDIR"); if (basedir != NULL) { - return std::string(basedir) + "/opendbc"; + return std::string(basedir) + "/opendbc/dbc"; } else { return DBC_FILE_PATH; } diff --git a/opendbc/can/logger.h b/opendbc_repo/opendbc/can/logger.h similarity index 100% rename from opendbc/can/logger.h rename to opendbc_repo/opendbc/can/logger.h diff --git a/opendbc/can/packer.cc b/opendbc_repo/opendbc/can/packer.cc similarity index 100% rename from opendbc/can/packer.cc rename to opendbc_repo/opendbc/can/packer.cc diff --git a/opendbc/can/packer.py b/opendbc_repo/opendbc/can/packer.py similarity index 100% rename from opendbc/can/packer.py rename to opendbc_repo/opendbc/can/packer.py diff --git a/opendbc/can/packer_pyx.pyx b/opendbc_repo/opendbc/can/packer_pyx.pyx similarity index 96% rename from opendbc/can/packer_pyx.pyx rename to opendbc_repo/opendbc/can/packer_pyx.pyx index 2e9a6f929255bde..4e8ae7d5647b5e5 100644 --- a/opendbc/can/packer_pyx.pyx +++ b/opendbc_repo/opendbc/can/packer_pyx.pyx @@ -50,4 +50,4 @@ cdef class CANPacker: pass cdef vector[uint8_t] val = self.pack(addr, values) - return [addr, 0, (&val[0])[:val.size()], bus] + return addr, (&val[0])[:val.size()], bus diff --git a/opendbc_repo/opendbc/can/parser.cc b/opendbc_repo/opendbc/can/parser.cc new file mode 100644 index 000000000000000..1607b092504fea2 --- /dev/null +++ b/opendbc_repo/opendbc/can/parser.cc @@ -0,0 +1,240 @@ +#include +#include +#include +#include +#include +#include + +#include "opendbc/can/common.h" + +int64_t get_raw_value(const std::vector &msg, const Signal &sig) { + int64_t ret = 0; + + int i = sig.msb / 8; + int bits = sig.size; + while (i >= 0 && i < msg.size() && bits > 0) { + int lsb = (int)(sig.lsb / 8) == i ? sig.lsb : i*8; + int msb = (int)(sig.msb / 8) == i ? sig.msb : (i+1)*8 - 1; + int size = msb - lsb + 1; + + uint64_t d = (msg[i] >> (lsb - (i*8))) & ((1ULL << size) - 1); + ret |= d << (bits - size); + + bits -= size; + i = sig.is_little_endian ? i-1 : i+1; + } + return ret; +} + + +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]; + + int64_t tmp = get_raw_value(dat, sig); + if (sig.is_signed) { + tmp -= ((tmp >> (sig.size-1)) & 0x1) ? (1ULL << sig.size) : 0; + } + + //DEBUG("parse 0x%X %s -> %ld\n", address, sig.name, tmp); + + if (!ignore_checksum) { + if (sig.calc_checksum != nullptr && sig.calc_checksum(address, sig, dat) != tmp) { + checksum_failed = true; + } + } + + if (!ignore_counter) { + if (sig.type == SignalType::COUNTER && !update_counter_generic(tmp, sig.size)) { + counter_failed = true; + } + } + + tmp_vals[i] = tmp * sig.factor + sig.offset; + } + + // only update values if both checksum and counter are valid + if (checksum_failed || counter_failed) { + LOGE_100("0x%X message checks failed, checksum failed %d, counter failed %d", address, checksum_failed, counter_failed); + return false; + } + + for (int i = 0; i < parse_sigs.size(); i++) { + vals[i] = tmp_vals[i]; + all_vals[i].push_back(vals[i]); + } + last_seen_nanos = nanos; + + return true; +} + + +bool MessageState::update_counter_generic(int64_t v, int cnt_size) { + 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, counter, (int)v); + } + } else if (counter_fail > 0) { + counter_fail--; + } + counter = v; + return counter_fail < MAX_BAD_COUNTER; +} + + +CANParser::CANParser(int abus, const std::string& dbc_name, const std::vector> &messages) + : bus(abus) { + dbc = dbc_lookup(dbc_name); + assert(dbc); + + bus_timeout_threshold = std::numeric_limits::max(); + + for (const auto& [address, frequency] : messages) { + // disallow duplicate message checks + if (message_states.find(address) != message_states.end()) { + std::stringstream is; + is << "Duplicate Message Check: " << address; + throw std::runtime_error(is.str()); + } + + MessageState &state = message_states[address]; + state.address = address; + // state.check_frequency = op.check_frequency, + + // msg is not valid if a message isn't received for 10 consecutive steps + if (frequency > 0) { + state.check_threshold = (1000000000ULL / frequency) * 10; + + // bus timeout threshold should be 10x the fastest msg + bus_timeout_threshold = std::min(bus_timeout_threshold, state.check_threshold); + } + + const Msg *msg = dbc->addr_to_msg.at(address); + state.name = msg->name; + state.size = msg->size; + assert(state.size <= 64); // max signal size is 64 bytes + + // track all signals for this message + state.parse_sigs = msg->sigs; + state.vals.resize(msg->sigs.size()); + state.all_vals.resize(msg->sigs.size()); + } +} + +CANParser::CANParser(int abus, const std::string& dbc_name, bool ignore_checksum, bool ignore_counter) + : bus(abus) { + // Add all messages and signals + + dbc = dbc_lookup(dbc_name); + assert(dbc); + + for (const auto& msg : dbc->msgs) { + MessageState state = { + .name = msg.name, + .address = msg.address, + .size = msg.size, + .ignore_checksum = ignore_checksum, + .ignore_counter = ignore_counter, + }; + + for (const auto& sig : msg.sigs) { + state.parse_sigs.push_back(sig); + state.vals.push_back(0); + state.all_vals.push_back({}); + } + + message_states[state.address] = state; + } +} + +std::set CANParser::update(const std::vector &can_data) { + // Clear all_values + for (auto &state : message_states) { + for (auto &vals : state.second.all_vals) vals.clear(); + } + + std::set updated_addresses; + for (const auto &c : can_data) { + if (first_nanos == 0) { + first_nanos = c.nanos; + } + + UpdateCans(c, updated_addresses); + UpdateValid(c.nanos); + } + return updated_addresses; +} + +void CANParser::UpdateCans(const CanData &can, std::set &updated_addresses) { + //DEBUG("got %zu messages\n", can.frames.size()); + + bool bus_empty = true; + + for (const auto &frame : can.frames) { + if (frame.src != bus) { + // DEBUG("skip %d: wrong bus\n", cmsg.getAddress()); + continue; + } + bus_empty = false; + + auto state_it = message_states.find(frame.address); + if (state_it == message_states.end()) { + // DEBUG("skip %d: not specified\n", cmsg.getAddress()); + continue; + } + if (frame.dat.size() > 64) { + DEBUG("got message longer than 64 bytes: 0x%X %zu\n", frame.address, frame.dat.size()); + continue; + } + + // TODO: this actually triggers for some cars. fix and enable this + //if (dat.size() != state_it->second.size) { + // DEBUG("got message with unexpected length: expected %d, got %zu for %d", state_it->second.size, dat.size(), cmsg.getAddress()); + // continue; + //} + + if (state_it->second.parse(can.nanos, frame.dat)) { + updated_addresses.insert(state_it->first); + } + } + + // update bus timeout + if (!bus_empty) { + last_nonempty_nanos = can.nanos; + } + bus_timeout = (can.nanos - last_nonempty_nanos) > bus_timeout_threshold; +} + +void CANParser::UpdateValid(uint64_t nanos) { + const bool show_missing = (nanos - first_nanos) > 8e9; + + bool _valid = true; + bool _counters_valid = true; + for (const auto& kv : message_states) { + const auto& state = kv.second; + + if (state.counter_fail >= MAX_BAD_COUNTER) { + _counters_valid = false; + } + + const bool missing = state.last_seen_nanos == 0; + 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) { + LOGE_100("0x%X '%s' NOT SEEN", state.address, state.name.c_str()); + } else if (timed_out) { + LOGE_100("0x%X '%s' TIMED OUT", state.address, state.name.c_str()); + } + } + _valid = false; + } + } + can_invalid_cnt = _valid ? 0 : (can_invalid_cnt + 1); + can_valid = (can_invalid_cnt < CAN_INVALID_CNT) && _counters_valid; +} diff --git a/opendbc/can/parser.py b/opendbc_repo/opendbc/can/parser.py similarity index 100% rename from opendbc/can/parser.py rename to opendbc_repo/opendbc/can/parser.py diff --git a/opendbc_repo/opendbc/can/parser_pyx.pyx b/opendbc_repo/opendbc/can/parser_pyx.pyx new file mode 100644 index 000000000000000..f35995cd7212087 --- /dev/null +++ b/opendbc_repo/opendbc/can/parser_pyx.pyx @@ -0,0 +1,159 @@ +# distutils: language = c++ +# cython: c_string_encoding=ascii, language_level=3 + +from libcpp.pair cimport pair +from libcpp.string cimport string +from libcpp.vector cimport vector +from libc.stdint cimport uint32_t + +from .common cimport CANParser as cpp_CANParser +from .common cimport dbc_lookup, Msg, DBC, CanData + +import numbers +from collections import defaultdict + + +cdef class CANParser: + cdef: + cpp_CANParser *can + const DBC *dbc + set addresses + + cdef readonly: + dict vl + dict vl_all + dict ts_nanos + string dbc_name + uint32_t bus + + def __init__(self, dbc_name, messages, bus=0): + self.dbc_name = dbc_name + self.bus = bus + self.dbc = dbc_lookup(dbc_name) + if not self.dbc: + raise RuntimeError(f"Can't find DBC: {dbc_name}") + + self.vl = {} + self.vl_all = {} + self.ts_nanos = {} + self.addresses = set() + + # Convert message names into addresses and check existence in DBC + cdef vector[pair[uint32_t, int]] message_v + for i in range(len(messages)): + c = messages[i] + try: + m = self.dbc.addr_to_msg.at(c[0]) if isinstance(c[0], numbers.Number) else self.dbc.name_to_msg.at(c[0]) + except IndexError: + raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + + address = m.address + message_v.push_back((address, c[1])) + self.addresses.add(address) + + name = m.name.decode("utf8") + signal_names = [sig.name.decode("utf-8") for sig in (m).sigs] + + self.vl[address] = {name: 0.0 for name in signal_names} + self.vl[name] = self.vl[address] + self.vl_all[address] = defaultdict(list) + self.vl_all[name] = self.vl_all[address] + self.ts_nanos[address] = {name: 0.0 for name in signal_names} + self.ts_nanos[name] = self.ts_nanos[address] + + self.can = new cpp_CANParser(bus, dbc_name, message_v) + + def __dealloc__(self): + if self.can: + del self.can + + def update_strings(self, strings, sendcan=False): + # input format: + # [nanos, [[address, data, src], ...]] + # [[nanos, [[address, data, src], ...], ...]] + for address in self.addresses: + self.vl_all[address].clear() + + cdef vector[CanData] can_data_array + + try: + if len(strings) and not isinstance(strings[0], (list, tuple)): + strings = [strings] + + can_data_array.reserve(len(strings)) + for s in strings: + can_data = &(can_data_array.emplace_back()) + can_data.nanos = s[0] + can_data.frames.reserve(len(s[1])) + for address, dat, src in s[1]: + source_bus = src + if source_bus == self.bus: + frame = &(can_data.frames.emplace_back()) + frame.address = address + frame.dat = dat + frame.src = source_bus + except TypeError: + raise RuntimeError("invalid parameter") + + updated_addrs = self.can.update(can_data_array) + for addr in updated_addrs: + vl = self.vl[addr] + vl_all = self.vl_all[addr] + ts_nanos = self.ts_nanos[addr] + + state = self.can.getMessageState(addr) + for i in range(state.parse_sigs.size()): + name = state.parse_sigs[i].name + vl[name] = state.vals[i] + vl_all[name] = state.all_vals[i] + ts_nanos[name] = state.last_seen_nanos + + return updated_addrs + + @property + def can_valid(self): + return self.can.can_valid + + @property + def bus_timeout(self): + return self.can.bus_timeout + + +cdef class CANDefine(): + cdef: + const DBC *dbc + + cdef public: + dict dv + string dbc_name + + def __init__(self, dbc_name): + self.dbc_name = dbc_name + self.dbc = dbc_lookup(dbc_name) + if not self.dbc: + raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + + dv = defaultdict(dict) + + for i in range(self.dbc[0].vals.size()): + val = self.dbc[0].vals[i] + + sgname = val.name.decode("utf8") + def_val = val.def_val.decode("utf8") + address = val.address + try: + m = self.dbc.addr_to_msg.at(address) + except IndexError: + raise KeyError(address) + msgname = m.name.decode("utf-8") + + # separate definition/value pairs + def_val = def_val.split() + values = [int(v) for v in def_val[::2]] + defs = def_val[1::2] + + # two ways to lookup: address or msg name + dv[address][sgname] = dict(zip(values, defs)) + dv[msgname][sgname] = dv[address][sgname] + + self.dv = dict(dv) diff --git a/opendbc/can/tests/.gitignore b/opendbc_repo/opendbc/can/tests/.gitignore similarity index 100% rename from opendbc/can/tests/.gitignore rename to opendbc_repo/opendbc/can/tests/.gitignore diff --git a/opendbc/can/tests/__init__.py b/opendbc_repo/opendbc/can/tests/__init__.py similarity index 100% rename from opendbc/can/tests/__init__.py rename to opendbc_repo/opendbc/can/tests/__init__.py diff --git a/opendbc_repo/opendbc/can/tests/test.dbc b/opendbc_repo/opendbc/can/tests/test.dbc new file mode 100644 index 000000000000000..05104fb0685ee88 --- /dev/null +++ b/opendbc_repo/opendbc/can/tests/test.dbc @@ -0,0 +1,27 @@ +CM_ "This DBC is used for the CAN parser and packer tests."; + +BO_ 228 STEERING_CONTROL: 5 EON + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ STEER_DOWN_TO_ZERO : 38|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 316 Brake_Status: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Signal1 : 12|46@1+ (1,0) [0|1] "" XXX + SG_ ES_Brake : 58|1@1+ (1,0) [0|1] "" XXX + SG_ Signal2 : 59|3@1+ (1,0) [0|1] "" XXX + SG_ Brake : 62|1@1+ (1,0) [0|1] "" XXX + SG_ Signal3 : 63|1@1+ (1,0) [0|1] "" XXX + +BO_ 245 CAN_FD_MESSAGE: 32 XXX + SG_ COUNTER : 7|8@0+ (1,0) [0|1] "" XXX + SG_ SIGNED : 22|16@0- (1,0) [0|1] "" XXX + SG_ 64_BIT_LE : 159|64@1+ (1,0) [0|1] "" XXX + SG_ 64_BIT_BE : 80|64@0+ (1,0) [0|1] "" XXX + +VAL_ 80 NON_EXISTENT_ADDR 0 "test"; diff --git a/opendbc_repo/opendbc/can/tests/test_checksums.py b/opendbc_repo/opendbc/can/tests/test_checksums.py new file mode 100644 index 000000000000000..b9a0a9ad6cee0b3 --- /dev/null +++ b/opendbc_repo/opendbc/can/tests/test_checksums.py @@ -0,0 +1,556 @@ +import copy +from opendbc.can.parser import CANParser +from opendbc.can.packer import CANPacker + + +class TestCanChecksums: + + def verify_checksum(self, subtests, dbc_file: str, msg_name: str, msg_addr: int, test_messages: list[bytes], + checksum_field: str = 'CHECKSUM', counter_field = 'COUNTER'): + """ + Verify that opendbc calculates payload CRCs/checksums matching those received in known-good sample messages + Depends on all non-zero bits in the sample message having a corresponding DBC signal, add UNKNOWN signals if needed + """ + parser = CANParser(dbc_file, [(msg_name, 0)], 0) + packer = CANPacker(dbc_file) + + for data in test_messages: + expected_msg = (msg_addr, data, 0) + parser.update_strings([0, [expected_msg]]) + expected = copy.deepcopy(parser.vl[msg_name]) + + modified = copy.deepcopy(expected) + modified.pop(checksum_field, None) + modified_msg = packer.make_can_msg(msg_name, 0, modified) + + parser.update_strings([0, [modified_msg]]) + tested = parser.vl[msg_name] + with subtests.test(counter=expected[counter_field]): + assert tested[checksum_field] == expected[checksum_field] + + def verify_fca_giorgio_crc(self, subtests, msg_name: str, msg_addr: int, test_messages: list[bytes]): + """Test modified SAE J1850 CRCs, with special final XOR cases for EPS messages""" + assert len(test_messages) == 3 + self.verify_checksum(subtests, "fca_giorgio", msg_name, msg_addr, test_messages) + + def test_fca_giorgio_eps_1(self, subtests): + self.verify_fca_giorgio_crc(subtests, "EPS_1", 0xDE, [ + b'\x17\x51\x97\xcc\x00\xdf', + b'\x17\x51\x97\xc9\x01\xa3', + b'\x17\x51\x97\xcc\x02\xe5', + ]) + + def test_fca_giorgio_eps_2(self, subtests): + self.verify_fca_giorgio_crc(subtests, "EPS_2", 0x106, [ + b'\x7c\x43\x57\x60\x00\x00\xa1', + b'\x7c\x63\x58\xe0\x00\x01\xd5', + b'\x7c\x63\x58\xe0\x00\x02\xf2', + ]) + + def test_fca_giorgio_eps_3(self, subtests): + self.verify_fca_giorgio_crc(subtests, "EPS_3", 0x122, [ + b'\x7b\x30\x00\xf8', + b'\x7b\x10\x01\x90', + b'\x7b\xf0\x02\x6e', + ]) + + def test_fca_giorgio_abs_2(self, subtests): + self.verify_fca_giorgio_crc(subtests, "ABS_2", 0xFE, [ + b'\x7e\x38\x00\x7d\x10\x31\x80\x32', + b'\x7e\x38\x00\x7d\x10\x31\x81\x2f', + b'\x7e\x38\x00\x7d\x20\x31\x82\x20', + ]) + + def test_honda_checksum(self): + """Test checksums for Honda standard and extended CAN ids""" + # TODO: refactor to use self.verify_checksum() + dbc_file = "honda_accord_2018_can_generated" + msgs = [("LKAS_HUD", 0), ("LKAS_HUD_A", 0)] + parser = CANParser(dbc_file, msgs, 0) + packer = CANPacker(dbc_file) + + values = { + 'SET_ME_X41': 0x41, + 'STEERING_REQUIRED': 1, + 'SOLID_LANES': 1, + 'BEEP': 0, + } + + # known correct checksums according to the above values + checksum_std = [11, 10, 9, 8] + checksum_ext = [4, 3, 2, 1] + + for std, ext in zip(checksum_std, checksum_ext, strict=True): + msgs = [ + packer.make_can_msg("LKAS_HUD", 0, values), + packer.make_can_msg("LKAS_HUD_A", 0, values), + ] + parser.update_strings([0, msgs]) + + assert parser.vl['LKAS_HUD']['CHECKSUM'] == std + assert parser.vl['LKAS_HUD_A']['CHECKSUM'] == ext + + def verify_volkswagen_mqb_crc(self, subtests, msg_name: str, msg_addr: int, test_messages: list[bytes], counter_field: str = 'COUNTER'): + """Test AUTOSAR E2E Profile 2 CRCs""" + assert len(test_messages) == 16 # All counter values must be tested + self.verify_checksum(subtests, "vw_mqb_2010", msg_name, msg_addr, test_messages, counter_field=counter_field) + + def test_volkswagen_mqb_crc_lwi_01(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "LWI_01", 0x86, [ + b'\x6b\x00\xbd\x00\x00\x00\x00\x00', + b'\xee\x01\x0a\x00\x00\x00\x00\x00', + b'\xd8\x02\xa9\x00\x00\x00\x00\x00', + b'\x03\x03\xbe\xa2\x12\x00\x00\x00', + b'\x7b\x04\x31\x20\x03\x00\x00\x00', + b'\x8b\x05\xe2\x85\x09\x00\x00\x00', + b'\x63\x06\x13\x21\x00\x00\x00\x00', + b'\x66\x07\x05\x00\x00\x00\x00\x00', + b'\x49\x08\x0d\x00\x00\x00\x00\x00', + b'\x5f\x09\x7e\x60\x01\x00\x00\x00', + b'\xaf\x0a\x72\x20\x00\x00\x00\x00', + b'\x59\x0b\x1b\x00\x00\x00\x00\x00', + b'\xa8\x0c\x06\x00\x00\x00\x00\x00', + b'\xbc\x0d\x72\x20\x00\x00\x00\x00', + b'\xf9\x0e\x0f\x00\x00\x00\x00\x00', + b'\x60\x0f\x62\xc0\x00\x00\x00\x00', + ]) + + def test_volkswagen_mqb_crc_airbag_01(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "Airbag_01", 0x40, [ + b'\xaf\x00\x00\x80\xc0\x00\x20\x3e', + b'\x54\x01\x00\x80\xc0\x00\x20\x1a', + b'\x54\x02\x00\x80\xc0\x00\x60\x00', + b'\x31\x03\x00\x80\xc0\x00\x60\xf2', + b'\xe0\x04\x00\x80\xc0\x00\x60\xcc', + b'\xb3\x05\x00\x80\xc0\x00\x40\xde', + b'\xa4\x06\x00\x80\xc0\x00\x40\x18', + b'\x94\x07\x00\x80\xc0\x00\x20\x38', + b'\x2d\x08\x00\x80\xc0\x00\x60\xae', + b'\xc2\x09\x00\x80\xc0\x00\x00\x1c', + b'\x1f\x0a\x00\x80\xc0\x00\x60\x2c', + b'\x7f\x0b\x00\x80\xc0\x00\x00\x00', + b'\x03\x0c\x00\x80\xc0\x00\x40\xd6', + b'\x56\x0d\x00\x80\xc0\x00\x20\x50', + b'\x4a\x0e\x00\x80\xc0\x00\x20\xf2', + b'\xe5\x0f\x00\x80\xc0\x00\x40\xf6', + ]) + + def test_volkswagen_mqb_crc_lh_eps_03(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "LH_EPS_03", 0x9F, [ + b'\x11\x30\x2e\x00\x05\x1c\x80\x30', + b'\x5b\x31\x8e\x03\x05\x53\x00\x30', + b'\xcb\x32\xd3\x06\x05\x73\x00\x30', + b'\xf2\x33\x28\x00\x05\x26\x00\x30', + b'\x0b\x34\x44\x00\x05\x5b\x80\x30', + b'\xed\x35\x80\x00\x03\x34\x00\x30', + b'\xf0\x36\x88\x00\x05\x3d\x80\x30', + b'\x9e\x37\x44\x03\x05\x41\x00\x30', + b'\x68\x38\x06\x01\x05\x18\x80\x30', + b'\x87\x39\x51\x00\x05\x11\x80\x30', + b'\x8c\x3a\x29\x00\x05\xac\x00\x30', + b'\x08\x3b\xbd\x00\x05\x8e\x00\x30', + b'\xd4\x3c\x19\x00\x05\x05\x80\x30', + b'\x29\x3d\x54\x00\x05\x5b\x00\x30', + b'\xa1\x3e\x49\x01\x03\x04\x80\x30', + b'\xe2\x3f\x05\x00\x05\x0a\x00\x30', + ]) + + def test_volkswagen_mqb_crc_getriebe_11(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "Getriebe_11", 0xAD, [ + b'\xf8\xe0\xbf\xff\x5f\x20\x20\x20', + b'\xb0\xe1\xbf\xff\xc6\x98\x21\x80', + b'\xd2\xe2\xbf\xff\x5f\x20\x20\x20', + b'\x00\xe3\xbf\xff\xaa\x20\x20\x10', + b'\xf1\xe4\xbf\xff\x5f\x20\x20\x20', + b'\xc4\xe5\xbf\xff\x5f\x20\x20\x20', + b'\xda\xe6\xbf\xff\x5f\x20\x20\x20', + b'\x85\xe7\xbf\xff\x5f\x20\x20\x20', + b'\x12\xe8\xbf\xff\x5f\x20\x20\x20', + b'\x45\xe9\xbf\xff\xaa\x20\x20\x10', + b'\x03\xea\xbf\xff\xcc\x20\x20\x10', + b'\xfc\xeb\xbf\xff\x5f\x20\x21\x20', + b'\xfe\xec\xbf\xff\xad\x20\x20\x10', + b'\xbd\xed\xbf\xff\xaa\x20\x20\x10', + b'\x67\xee\xbf\xff\xaa\x20\x20\x10', + b'\x36\xef\xbf\xff\xaa\x20\x20\x10', + ], counter_field="COUNTER_DISABLED") # see opendbc#1235 + + def test_volkswagen_mqb_crc_esp_21(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ESP_21", 0xFD, [ + b'\x66\xd0\x1f\x80\x45\x05\x00\x00', + b'\x87\xd1\x1f\x80\x52\x05\x00\x00', + b'\xcd\xd2\x1f\x80\x50\x06\x00\x00', + b'\xfd\xd3\x1f\x80\x35\x02\x00\x00', + b'\xfa\xd4\x1f\x80\x22\x05\x00\x00', + b'\xfd\xd5\x1f\x80\x84\x04\x00\x00', + b'\x2e\xd6\x1f\x80\xf0\x03\x00\x00', + b'\x9f\xd7\x1f\x80\x00\x00\x00\x00', + b'\x1e\xd8\x1f\x80\xb3\x03\x00\x00', + b'\x61\xd9\x1f\x80\x6d\x05\x00\x00', + b'\x44\xda\x1f\x80\x47\x02\x00\x00', + b'\x86\xdb\x1f\x80\x3a\x02\x00\x00', + b'\x39\xdc\x1f\x80\xcb\x01\x00\x00', + b'\x19\xdd\x1f\x80\x00\x00\x00\x00', + b'\x8c\xde\x1f\x80\xba\x04\x00\x00', + b'\xfb\xdf\x1f\x80\x46\x00\x00\x00', + ]) + + def test_volkswagen_mqb_crc_esp_02(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ESP_02", 0x101, [ + b'\xf2\x00\x7e\xff\xa1\x2a\x40\x00', + b'\xd3\x01\x7d\x00\xa2\x0c\x02\x00', + b'\x03\x02\x7a\x06\xa2\x49\x42\x00', + b'\xfd\x03\x70\xfb\xa1\xde\x00\x00', + b'\x8e\x04\x7b\xf7\xa1\xd2\x01\x00', + b'\x0f\x05\x7d\xfd\xa1\x31\x40\x00', + b'\xb6\x06\x7d\x01\xa2\x0a\x40\x00', + b'\xe8\x07\x7e\xfd\xa1\x12\x40\x00', + b'\x74\x08\x7a\x01\xa2\x40\x01\x00', + b'\xe3\x09\x81\x00\xa2\xb5\x01\x00', + b'\xab\x0a\x74\x09\xa2\x9f\x42\x00', + b'\xf3\x0b\x80\x12\xa2\x94\x00\x00', + b'\x88\x0c\x7f\x07\xa2\x46\x00\x00', + b'\x6f\x0d\x7f\xff\xa1\x53\x40\x00', + b'\x38\x0e\x73\xd6\xa1\x6a\x40\x00', + b'\x49\x0f\x85\x12\xa2\xf6\x01\x00', + ]) + + def test_volkswagen_mqb_crc_esp_05(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ESP_05", 0x106, [ + b'\x90\x80\x64\x00\x00\x00\xe7\x10', + b'\xf4\x81\x64\x00\x00\x00\xe7\x10', + b'\x90\x82\x63\x00\x00\x00\xe8\x10', + b'\xa0\x83\x63\x00\x00\x00\xe6\x10', + b'\xe7\x84\x63\x00\x00\x00\xe8\x10', + b'\x2e\x85\x78\x04\x00\x00\xea\x30', + b'\x7b\x86\x63\x00\x00\x00\xe6\x10', + b'\x71\x87\x79\x04\x00\x00\xd0\x30', + b'\x50\x88\x79\x04\x00\x00\xea\x30', + b'\x81\x89\x64\x00\x00\x00\xe1\x10', + b'\x6a\x8a\x68\x00\x00\x04\xd0\x10', + b'\x17\x8b\x6a\x04\x00\x00\xe6\x10', + b'\xc7\x8c\x63\x00\x00\x00\xd1\x10', + b'\x53\x8d\x64\x04\x00\x00\xe2\x10', + b'\x24\x8e\x63\x00\x00\x00\xe7\x10', + b'\x3f\x8f\x82\x04\x00\x00\xe6\x30', + ]) + + def test_volkswagen_mqb_crc_esp_10(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ESP_10", 0x116, [ + b'\x2d\x00\xd5\x98\x9f\x26\x25\x0f', + b'\x24\x01\x60\x63\x2c\x5e\x3b\x0f', + b'\x08\x02\xb2\x2f\xee\x9a\x29\x0f', + b'\x7c\x03\x17\x07\x1d\xe5\x8c\x0f', + b'\xaa\x04\xd6\xe3\xeb\x98\xe8\x0f', + b'\x4e\x05\xbb\xd9\x65\x43\xca\x0f', + b'\x59\x06\x78\xbd\x25\xc6\xf2\xff', + b'\xaf\x07\x42\x85\x53\xbe\xbe\x0f', + b'\x2a\x08\xa6\xcd\x95\x8c\x12\x0f', + b'\xce\x09\x6e\x17\x6d\x1b\x2f\x0f', + b'\x60\x0a\xd3\xe6\x3a\x8d\xf0\x0f', + b'\xc5\x0b\xfc\x69\x57\x50\x21\x0f', + b'\x70\x0c\xde\xf3\x9d\xe9\x6b\xff', + b'\x62\x0d\xc4\x1a\xdb\x61\x7a\x0f', + b'\x76\x0e\x79\x69\xe3\x32\x67\x0f', + b'\x15\x0f\x51\x59\x56\x35\xb1\x0f', + ]) + + def test_volkswagen_mqb_crc_acc_10(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ACC_10", 0x117, [ + b'\x9b\x00\x00\x40\x68\x00\x00\xff', + b'\xff\x01\x00\x40\x68\x00\x00\xff', + b'\x53\x02\x00\x40\x68\x00\x00\xff', + b'\x37\x03\x00\x40\x68\x00\x00\xff', + b'\x24\x04\x00\x40\x68\x00\x00\xff', + b'\x40\x05\x00\x40\x68\x00\x00\xff', + b'\xec\x06\x00\x40\x68\x00\x00\xff', + b'\x88\x07\x00\x40\x68\x00\x00\xff', + b'\xca\x08\x00\x40\x68\x00\x00\xff', + b'\xae\x09\x00\x40\x68\x00\x00\xff', + b'\x02\x0a\x00\x40\x68\x00\x00\xff', + b'\x66\x0b\x00\x40\x68\x00\x00\xff', + b'\x75\x0c\x00\x40\x68\x00\x00\xff', + b'\x11\x0d\x00\x40\x68\x00\x00\xff', + b'\xbd\x0e\x00\x40\x68\x00\x00\xff', + b'\xd9\x0f\x00\x40\x68\x00\x00\xff', + ]) + + def test_volkswagen_mqb_crc_tsk_06(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "TSK_06", 0x120, [ + b'\xc1\x00\x00\x02\x00\x08\xff\x21', + b'\x34\x01\x00\x02\x00\x08\xff\x21', + b'\xcc\x02\x00\x02\x00\x08\xff\x21', + b'\x1e\x03\x00\x02\x00\x08\xff\x21', + b'\x48\x04\x00\x02\x00\x08\xff\x21', + b'\x4a\x05\x00\x02\x00\x08\xff\x21', + b'\xa5\x06\x00\x02\x00\x08\xff\x21', + b'\xa7\x07\x00\x02\x00\x08\xff\x21', + b'\xfe\x08\x00\x02\x00\x08\xff\x21', + b'\xa8\x09\x00\x02\x00\x08\xff\x21', + b'\x73\x0a\x00\x02\x00\x08\xff\x21', + b'\xdf\x0b\x00\x02\x00\x08\xff\x21', + b'\x05\x0c\x00\x02\x00\x08\xff\x21', + b'\xb5\x0d\x00\x02\x00\x08\xff\x21', + b'\xde\x0e\x00\x02\x00\x08\xff\x21', + b'\x0b\x0f\x00\x02\x00\x08\xff\x21', + ]) + + def test_volkswagen_mqb_crc_motor_20(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "Motor_20", 0x121, [ + b'\xb9\x00\x00\xc0\x39\x46\x7e\xfe', + b'\x85\x31\x20\x00\x1a\x46\x7e\xfe', + b'\xc7\x12\x00\x40\x1a\x46\x7e\xfe', + b'\x53\x93\x00\x00\x19\x46\x7e\xfe', + b'\xa4\x34\x00\x80\x1a\x46\x7e\xfe', + b'\x0e\x55\x20\x60\x18\x46\x7e\xfe', + b'\x3f\x06\x00\xc0\x37\x4c\x7e\xfe', + b'\x0c\x07\x00\x40\x39\x46\x7e\xfe', + b'\x2a\x08\x00\x00\x3a\x46\x7e\xfe', + b'\x7f\x49\x20\x80\x1a\x46\x7e\xfe', + b'\x2f\x0a\x00\xc0\x39\x46\x7e\xfe', + b'\x70\xbb\x00\x00\x17\x46\x7e\xfe', + b'\x06\x0c\x00\x00\x39\x46\x7e\xfe', + b'\x4b\x9d\x20\xe0\x16\x4c\x7e\xfe', + b'\x73\xfe\x00\x40\x16\x46\x7e\xfe', + b'\xaf\x0f\x20\x80\x39\x4c\x7e\xfe', + ]) + + def test_volkswagen_mqb_crc_acc_06(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ACC_06", 0x122, [ + b'\x14\x80\x00\xfe\x07\x00\x00\x18', + b'\x9f\x81\x00\xfe\x07\x00\x00\x18', + b'\x0a\x82\x00\xfe\x07\x00\x00\x28', + b'\x40\x83\x00\xfe\x07\x00\x00\x18', + b'\x2d\x84\x00\xfe\x07\x00\x00\x28', + b'\xdb\x85\x00\xfe\x07\x00\x00\x18', + b'\x4d\x86\x00\xfe\x07\x00\x00\x28', + b'\x35\x87\x00\xfe\x07\x00\x00\x18', + b'\x23\x88\x00\xfe\x07\x00\x00\x28', + b'\x4a\x89\x00\xfe\x07\x00\x00\x28', + b'\xe1\x8a\x00\xfe\x07\x00\x00\x28', + b'\x30\x8b\x00\xfe\x07\x00\x00\x28', + b'\x60\x8c\x00\xfe\x07\x00\x00\x28', + b'\x0d\x8d\x00\xfe\x07\x00\x00\x18', + b'\x8c\x8e\x00\xfe\x07\x00\x00\x18', + b'\x6f\x8f\x00\xfe\x07\x00\x00\x28', + ]) + + def test_volkswagen_mqb_crc_hca_01(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "HCA_01", 0x126, [ + b'\x00\x30\x0d\xc0\x05\xfe\x07\x00', + b'\x3e\x31\x54\xc0\x05\xfe\x07\x00', + b'\xa7\x32\xbb\x40\x05\xfe\x07\x00', + b'\x96\x33\x29\xc0\x05\xfe\x07\x00', + b'\x5f\x34\x00\x00\x03\xfe\x07\x00', + b'\x3b\x35\xae\x40\x05\xfe\x07\x00', + b'\xc7\x36\x7a\x40\x05\xfe\x07\x00', + b'\x6f\x37\x76\x40\x05\xfe\x07\x00', + b'\xb1\x38\x00\x00\x03\xfe\x07\x00', + b'\xd5\x39\x00\x00\x03\xfe\x07\x00', + b'\xba\x3a\x69\xc0\x05\xfe\x07\x00', + b'\x65\x3b\x10\x40\x05\xfe\x07\x00', + b'\x49\x3c\x72\xc0\x05\xfe\x07\x00', + b'\xc6\x3d\xdf\x40\x05\xfe\x07\x00', + b'\x1d\x3e\x2c\xc1\x05\xfe\x07\x00', + b'\x9b\x3f\x20\x40\x05\xfe\x07\x00', + ]) + + def test_volkswagen_mqb_crc_gra_acc_01(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "GRA_ACC_01", 0x12B, [ + b'\x86\x40\x80\x2a\x00\x00\x00\x00', + b'\xf4\x41\x80\x2a\x00\x00\x00\x00', + b'\x50\x42\x80\x2a\x00\x00\x00\x00', + b'\x08\x43\x80\x2a\x00\x00\x00\x00', + b'\x88\x44\x80\x2a\x00\x00\x00\x00', + b'\x2d\x45\x80\x2a\x00\x00\x00\x00', + b'\x34\x46\x80\x2a\x00\x00\x00\x00', + b'\x11\x47\x80\x2a\x00\x00\x00\x00', + b'\xc4\x48\x80\x2a\x00\x00\x00\x00', + b'\xcc\x49\x80\x2a\x00\x00\x00\x00', + b'\xdc\x4a\x80\x2a\x00\x00\x00\x00', + b'\x79\x4b\x80\x2a\x00\x00\x00\x00', + b'\x3c\x4c\x80\x2a\x00\x00\x00\x00', + b'\x68\x4d\x80\x2a\x00\x00\x00\x00', + b'\x27\x4e\x80\x2a\x00\x00\x00\x00', + b'\x0d\x4f\x80\x2a\x00\x00\x00\x00', + ]) + + def test_volkswagen_mqb_crc_acc_07(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ACC_07", 0x12E, [ + b'\xac\xe0\x7f\x00\xfe\x00\xc0\xff', + b'\xa2\xe1\x7f\x00\xfe\x00\xc0\xff', + b'\x6b\xe2\x7f\x00\xfe\x00\xc0\xff', + b'\xf2\xe3\x7f\x00\xfe\x00\xc0\xff', + b'\xd5\xe4\x7f\x00\xfe\x00\xc0\xff', + b'\x35\xe5\x7f\x00\xfe\x00\xc0\xff', + b'\x7f\xe6\x7f\x00\xfe\x00\xc0\xff', + b'\x6c\xe7\x7f\x00\xfe\x00\xc0\xff', + b'\x05\xe8\x7f\x00\xfe\x00\xc0\xff', + b'\x79\xe9\x7f\x00\xfe\x00\xc0\xff', + b'\x25\xea\x7f\x00\xfe\x00\xc0\xff', + b'\xd1\xeb\x7f\x00\xfe\x00\xc0\xff', + b'\x72\xec\x7f\x00\xfe\x00\xc0\xff', + b'\x58\xed\x7f\x00\xfe\x00\xc0\xff', + b'\x82\xee\x7f\x00\xfe\x00\xc0\xff', + b'\x85\xef\x7f\x00\xfe\x00\xc0\xff', + ]) + + def test_volkswagen_mqb_crc_motor_ev_01(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "Motor_EV_01", 0x187, [ + b'\x70\x80\x15\x00\x00\x00\x00\xF0', + b'\x07\x81\x15\x00\x00\x00\x00\xF0', + b'\x7A\x82\x15\x00\x00\x00\x00\xF0', + b'\x26\x83\x15\x00\x00\x00\x00\xF0', + b'\xBE\x84\x15\x00\x00\x00\x00\xF0', + b'\x5A\x85\x15\x00\x00\x00\x00\xF0', + b'\xFC\x86\x15\x00\x00\x00\x00\xF0', + b'\x9E\x87\x15\x00\x00\x00\x00\xF0', + b'\xAF\x88\x15\x00\x00\x00\x00\xF0', + b'\x35\x89\x15\x00\x00\x00\x00\xF0', + b'\xC5\x8A\x15\x00\x00\x00\x00\xF0', + b'\x11\x8B\x15\x00\x00\x00\x00\xF0', + b'\xD0\x8C\x15\x00\x00\x00\x00\xF0', + b'\xE8\x8D\x15\x00\x00\x00\x00\xF0', + b'\xF5\x8E\x15\x00\x00\x00\x00\xF0', + b'\x00\x8F\x15\x00\x00\x00\x00\xF0', + ]) + + def test_volkswagen_mqb_crc_esp_33(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ESP_33", 0x1AB, [ + b'\x64\x00\x80\x02\x00\x00\x00\x00', + b'\x19\x01\x00\x00\x00\x00\x00\x00', + b'\xfc\x02\x00\x10\x01\x00\x00\x00', + b'\x8b\x03\x80\x02\x00\x00\x00\x00', + b'\xa4\x04\x00\x10\x01\x00\x00\x00', + b'\x97\x05\x00\x02\x00\x00\x01\x00', + b'\xd5\x06\x80\x02\x00\x00\x01\x00', + b'\xa0\x07\x80\x02\x00\x00\x01\x00', + b'\x89\x08\x00\x00\x00\x00\x00\x00', + b'\xe3\x09\x00\x00\x00\x00\x00\x00', + b'\x0e\x0a\x00\x00\x00\x00\x00\x00', + b'\x90\x0b\x00\x00\x00\x00\x00\x00', + b'\x32\x0c\x00\x10\x01\x00\x00\x00', + b'\x30\x0d\x00\x00\x00\x00\x00\x00', + b'\xc2\x0e\x00\x10\x01\x00\x00\x00', + b'\x68\x0f\x80\x02\x00\x00\x00\x00', + ]) + + def test_volkswagen_mqb_crc_acc_02(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ACC_02", 0x30C, [ + b'\x82\xf0\x3f\x00\x40\x30\x00\x40', + b'\xe6\xf1\x3f\x00\x40\x30\x00\x40', + b'\x4a\xf2\x3f\x00\x40\x30\x00\x40', + b'\x2e\xf3\x3f\x00\x40\x30\x00\x40', + b'\x3d\xf4\x3f\x00\x40\x30\x00\x40', + b'\x59\xf5\x3f\x00\x40\x30\x00\x40', + b'\xf5\xf6\x3f\x00\x40\x30\x00\x40', + b'\x91\xf7\x3f\x00\x40\x30\x00\x40', + b'\xd3\xf8\x3f\x00\x40\x30\x00\x40', + b'\xb7\xf9\x3f\x00\x40\x30\x00\x40', + b'\x1b\xfa\x3f\x00\x40\x30\x00\x40', + b'\x7f\xfb\x3f\x00\x40\x30\x00\x40', + b'\x6c\xfc\x3f\x00\x40\x30\x00\x40', + b'\x08\xfd\x3f\x00\x40\x30\x00\x40', + b'\xa4\xfe\x3f\x00\x40\x30\x00\x40', + b'\xc0\xff\x3f\x00\x40\x30\x00\x40', + ]) + + def test_volkswagen_mqb_crc_swa_01(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "SWA_01", 0x30F, [ + b'\x10\x00\x10\x00\x00\x00\x00\x00', + b'\x74\x01\x10\x00\x00\x00\x00\x00', + b'\xD8\x02\x10\x00\x00\x00\x00\x00', + b'\xBC\x03\x10\x00\x00\x00\x00\x00', + b'\xAF\x04\x10\x00\x00\x00\x00\x00', + b'\xCB\x05\x10\x00\x00\x00\x00\x00', + b'\x67\x06\x10\x00\x00\x00\x00\x00', + b'\x03\x07\x10\x00\x00\x00\x00\x00', + b'\x41\x08\x10\x00\x00\x00\x00\x00', + b'\x25\x09\x10\x00\x00\x00\x00\x00', + b'\x89\x0A\x10\x00\x00\x00\x00\x00', + b'\xED\x0B\x10\x00\x00\x00\x00\x00', + b'\xFE\x0C\x10\x00\x00\x00\x00\x00', + b'\x9A\x0D\x10\x00\x00\x00\x00\x00', + b'\x36\x0E\x10\x00\x00\x00\x00\x00', + b'\x52\x0F\x10\x00\x00\x00\x00\x00', + ]) + + def test_volkswagen_mqb_crc_acc_04(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ACC_04", 0x324, [ + b'\xba\x00\x00\x00\x00\x00\x00\x10', + b'\xde\x01\x00\x00\x00\x00\x00\x10', + b'\x72\x02\x00\x00\x00\x00\x00\x10', + b'\x16\x03\x00\x00\x00\x00\x00\x10', + b'\x05\x04\x00\x00\x00\x00\x00\x10', + b'\x44\x05\x00\x00\x00\x00\x00\x00', + b'\xe8\x06\x00\x00\x00\x00\x00\x00', + b'\xa9\x07\x00\x00\x00\x00\x00\x10', + b'\xeb\x08\x00\x00\x00\x00\x00\x10', + b'\x8f\x09\x00\x00\x00\x00\x00\x10', + b'\x06\x0a\x00\x00\x00\x00\x00\x00', + b'\x47\x0b\x00\x00\x00\x00\x00\x10', + b'\x71\x0c\x00\x00\x00\x00\x00\x00', + b'\x15\x0d\x00\x00\x00\x00\x00\x00', + b'\xb9\x0e\x00\x00\x00\x00\x00\x00', + b'\xdd\x0f\x00\x00\x00\x00\x00\x00', + ]) + + def test_volkswagen_mqb_crc_klemmen_status_01(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "Klemmen_Status_01", 0x3C0, [ + b'\x74\x00\x03\x00', + b'\xc1\x01\x03\x00', + b'\x31\x02\x03\x00', + b'\x84\x03\x03\x00', + b'\xfe\x04\x03\x00', + b'\x4b\x05\x03\x00', + b'\xbb\x06\x03\x00', + b'\x0e\x07\x03\x00', + b'\x4f\x08\x03\x00', + b'\xfa\x09\x03\x00', + b'\x0a\x0a\x03\x00', + b'\xbf\x0b\x03\x00', + b'\xc5\x0c\x03\x00', + b'\x70\x0d\x03\x00', + b'\x80\x0e\x03\x00', + b'\x35\x0f\x03\x00', + ]) + + def test_volkswagen_mqb_crc_licht_anf_01(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "Licht_Anf_01", 0x3D5, [ + b'\xc8\x00\x00\x04\x00\x00\x00\x00', + b'\x9f\x01\x00\x04\x00\x00\x00\x00', + b'\x5e\x02\x00\x04\x00\x00\x00\x00', + b'\x52\x03\x00\x04\x00\x00\x00\x00', + b'\xf2\x04\x00\x04\x00\x00\x00\x00', + b'\x79\x05\x00\x04\x00\x00\x00\x00', + b'\xe6\x06\x00\x04\x00\x00\x00\x00', + b'\xfd\x07\x00\x04\x00\x00\x00\x00', + b'\xf8\x08\x00\x04\x00\x00\x00\x00', + b'\xc6\x09\x00\x04\x00\x00\x00\x00', + b'\xf5\x0a\x00\x04\x00\x00\x00\x00', + b'\x1a\x0b\x00\x04\x00\x00\x00\x00', + b'\x65\x0c\x00\x04\x00\x00\x00\x00', + b'\x41\x0d\x00\x04\x00\x00\x00\x00', + b'\x7f\x0e\x00\x04\x00\x00\x00\x00', + b'\x98\x0f\x00\x04\x00\x00\x00\x00', + ]) + + def test_volkswagen_mqb_crc_esp_20(self, subtests): + self.verify_volkswagen_mqb_crc(subtests, "ESP_20", 0x65D, [ + b'\x98\x30\x2b\x10\x00\x00\x22\x81', + b'\xc8\x31\x2b\x10\x00\x00\x22\x81', + b'\x9d\x32\x2b\x10\x00\x00\x22\x81', + b'\x1f\x33\x2b\x10\x00\x00\x22\x81', + b'\x6e\x34\x2b\x10\x00\x00\x22\x81', + b'\x61\x35\x2b\x10\x00\x00\x22\x81', + b'\x6f\x36\x2b\x10\x00\x00\x22\x81', + b'\xe5\x37\x2b\x10\x00\x00\x22\x81', + b'\xf8\x38\x2b\x10\x00\x00\x22\x81', + b'\xe1\x39\x2b\x10\x00\x00\x22\x81', + b'\xaa\x3a\x2b\x10\x00\x00\x22\x81', + b'\xe6\x3b\x2b\x10\x00\x00\x22\x81', + b'\xef\x3c\x2b\x10\x00\x00\x22\x81', + b'\xbb\x3d\x2b\x10\x00\x00\x22\x81', + b'\x9b\x3e\x2b\x10\x00\x00\x22\x81', + b'\x72\x3f\x2b\x10\x00\x00\x22\x81', + ]) diff --git a/opendbc_repo/opendbc/can/tests/test_dbc_exceptions.py b/opendbc_repo/opendbc/can/tests/test_dbc_exceptions.py new file mode 100644 index 000000000000000..b765d27fb2d4c92 --- /dev/null +++ b/opendbc_repo/opendbc/can/tests/test_dbc_exceptions.py @@ -0,0 +1,30 @@ +import pytest + +from opendbc.can.parser import CANParser, CANDefine +from opendbc.can.packer import CANPacker +from opendbc.can.tests import TEST_DBC + + +class TestCanParserPackerExceptions: + def test_civic_exceptions(self): + dbc_file = "honda_civic_touring_2016_can_generated" + dbc_invalid = dbc_file + "abcdef" + msgs = [("STEERING_CONTROL", 50)] + with pytest.raises(RuntimeError): + CANParser(dbc_invalid, msgs, 0) + with pytest.raises(RuntimeError): + CANPacker(dbc_invalid) + with pytest.raises(RuntimeError): + CANDefine(dbc_invalid) + with pytest.raises(KeyError): + CANDefine(TEST_DBC) + + parser = CANParser(dbc_file, msgs, 0) + with pytest.raises(RuntimeError): + parser.update_strings([b'']) + + # Everything is supposed to work below + CANParser(dbc_file, msgs, 0) + CANParser(dbc_file, [], 0) + CANPacker(dbc_file) + CANDefine(dbc_file) diff --git a/opendbc_repo/opendbc/can/tests/test_dbc_parser.py b/opendbc_repo/opendbc/can/tests/test_dbc_parser.py new file mode 100644 index 000000000000000..4e9bb34f2036f7e --- /dev/null +++ b/opendbc_repo/opendbc/can/tests/test_dbc_parser.py @@ -0,0 +1,21 @@ +from opendbc.can.parser import CANParser +from opendbc.can.tests import ALL_DBCS + + +class TestDBCParser: + def test_enough_dbcs(self): + # sanity check that we're running on the real DBCs + assert len(ALL_DBCS) > 20 + + def test_parse_all_dbcs(self, subtests): + """ + Dynamic DBC parser checks: + - Checksum and counter length, start bit, endianness + - Duplicate message addresses and names + - Signal out of bounds + - All BO_, SG_, VAL_ lines for syntax errors + """ + + for dbc in ALL_DBCS: + with subtests.test(dbc=dbc): + CANParser(dbc, [], 0) diff --git a/opendbc_repo/opendbc/can/tests/test_define.py b/opendbc_repo/opendbc/can/tests/test_define.py new file mode 100644 index 000000000000000..ec29f4a59bd4eaa --- /dev/null +++ b/opendbc_repo/opendbc/can/tests/test_define.py @@ -0,0 +1,26 @@ +from opendbc.can.can_define import CANDefine +from opendbc.can.tests import ALL_DBCS + + +class TestCADNDefine: + def test_civic(self): + + dbc_file = "honda_civic_touring_2016_can_generated" + defs = CANDefine(dbc_file) + + assert defs.dv[399] == defs.dv['STEER_STATUS'] + assert defs.dv[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'} + } + + def test_all_dbcs(self, subtests): + # Asserts no exceptions on all DBCs + for dbc in ALL_DBCS: + with subtests.test(dbc=dbc): + CANDefine(dbc) diff --git a/opendbc_repo/opendbc/can/tests/test_packer_parser.py b/opendbc_repo/opendbc/can/tests/test_packer_parser.py new file mode 100644 index 000000000000000..1de0fd24ee179de --- /dev/null +++ b/opendbc_repo/opendbc/can/tests/test_packer_parser.py @@ -0,0 +1,368 @@ +import pytest +import random + +from opendbc.can.parser import CANParser +from opendbc.can.packer import CANPacker +from opendbc.can.tests import TEST_DBC + +MAX_BAD_COUNTER = 5 + + +class TestCanParserPacker: + def test_packer(self): + packer = CANPacker(TEST_DBC) + + for b in range(6): + for i in range(256): + values = {"COUNTER": i} + addr, dat, bus = packer.make_can_msg("CAN_FD_MESSAGE", b, values) + assert addr == 245 + assert bus == b + assert dat[0] == i + + def test_packer_counter(self): + msgs = [("CAN_FD_MESSAGE", 0), ] + packer = CANPacker(TEST_DBC) + parser = CANParser(TEST_DBC, msgs, 0) + + # packer should increment the counter + for i in range(1000): + msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) + parser.update_strings([0, [msg]]) + assert parser.vl["CAN_FD_MESSAGE"]["COUNTER"] == (i % 256) + + # setting COUNTER should override + for _ in range(100): + cnt = random.randint(0, 255) + msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, { + "COUNTER": cnt, + "SIGNED": 0 + }) + parser.update_strings([0, [msg]]) + assert parser.vl["CAN_FD_MESSAGE"]["COUNTER"] == cnt + + # then, should resume counting from the override value + cnt = parser.vl["CAN_FD_MESSAGE"]["COUNTER"] + for i in range(100): + msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) + parser.update_strings([0, [msg]]) + assert parser.vl["CAN_FD_MESSAGE"]["COUNTER"] == ((cnt + i) % 256) + + def test_parser_can_valid(self): + msgs = [("CAN_FD_MESSAGE", 10), ] + packer = CANPacker(TEST_DBC) + parser = CANParser(TEST_DBC, msgs, 0) + + # shouldn't be valid initially + assert not parser.can_valid + + # not valid until the message is seen + for _ in range(100): + parser.update_strings([0, []]) + assert not parser.can_valid + + # valid once seen + for i in range(1, 100): + t = int(0.01 * i * 1e9) + msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) + parser.update_strings([t, [msg]]) + assert parser.can_valid + + def test_parser_updated_list(self): + msgs = [("CAN_FD_MESSAGE", 10), ] + parser = CANParser(TEST_DBC, msgs, 0) + packer = CANPacker(TEST_DBC) + + msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) + ret = parser.update_strings([0, [msg]]) + assert ret == {245} + + ret = parser.update_strings([]) + assert len(ret) == 0 + + def test_parser_counter_can_valid(self): + """ + Tests number of allowed bad counters + ensures CAN stays invalid + while receiving invalid messages + that we can recover + """ + msgs = [ + ("STEERING_CONTROL", 0), + ] + packer = CANPacker("honda_civic_touring_2016_can_generated") + parser = CANParser("honda_civic_touring_2016_can_generated", msgs, 0) + + msg = packer.make_can_msg("STEERING_CONTROL", 0, {"COUNTER": 0}) + + # bad static counter, invalid once it's seen MAX_BAD_COUNTER messages + for idx in range(0x1000): + parser.update_strings([0, [msg]]) + assert ((idx + 1) < MAX_BAD_COUNTER) == parser.can_valid + + # one to recover + msg = packer.make_can_msg("STEERING_CONTROL", 0, {"COUNTER": 1}) + parser.update_strings([0, [msg]]) + assert parser.can_valid + + def test_parser_no_partial_update(self): + """ + Ensure that the CANParser doesn't partially update messages with invalid signals (COUNTER/CHECKSUM). + Previously, the signal update loop would only break once it got to one of these invalid signals, + after already updating most/all of the signals. + """ + msgs = [ + ("STEERING_CONTROL", 0), + ] + packer = CANPacker("honda_civic_touring_2016_can_generated") + parser = CANParser("honda_civic_touring_2016_can_generated", msgs, 0) + + def rx_steering_msg(values, bad_checksum=False): + msg = packer.make_can_msg("STEERING_CONTROL", 0, values) + if bad_checksum: + # add 1 to checksum + dat = bytearray(msg[1]) + dat[4] = (dat[4] & 0xF0) | ((dat[4] & 0x0F) + 1) + msg = (msg[0], bytes(dat), msg[2]) + + parser.update_strings([0, [msg]]) + + rx_steering_msg({"STEER_TORQUE": 100}, bad_checksum=False) + assert parser.vl["STEERING_CONTROL"]["STEER_TORQUE"] == 100 + assert parser.vl_all["STEERING_CONTROL"]["STEER_TORQUE"] == [100] + + for _ in range(5): + rx_steering_msg({"STEER_TORQUE": 200}, bad_checksum=True) + assert parser.vl["STEERING_CONTROL"]["STEER_TORQUE"] == 100 + assert parser.vl_all["STEERING_CONTROL"]["STEER_TORQUE"] == [] + + # Even if CANParser doesn't update instantaneous vl, make sure it didn't add invalid values to vl_all + rx_steering_msg({"STEER_TORQUE": 300}, bad_checksum=False) + assert parser.vl["STEERING_CONTROL"]["STEER_TORQUE"] == 300 + assert parser.vl_all["STEERING_CONTROL"]["STEER_TORQUE"] == [300] + + def test_packer_parser(self): + msgs = [ + ("Brake_Status", 0), + ("CAN_FD_MESSAGE", 0), + ("STEERING_CONTROL", 0), + ] + packer = CANPacker(TEST_DBC) + parser = CANParser(TEST_DBC, msgs, 0) + + for steer in range(-256, 255): + for active in (1, 0): + values = { + "STEERING_CONTROL": { + "STEER_TORQUE": steer, + "STEER_TORQUE_REQUEST": active, + }, + "Brake_Status": { + "Signal1": 61042322657536.0, + }, + "CAN_FD_MESSAGE": { + "SIGNED": steer, + "64_BIT_LE": random.randint(0, 100), + "64_BIT_BE": random.randint(0, 100), + }, + } + + msgs = [packer.make_can_msg(k, 0, v) for k, v in values.items()] + parser.update_strings([0, msgs]) + + for k, v in values.items(): + for key, val in v.items(): + assert parser.vl[k][key] == pytest.approx(val) + + # also check address + for sig in ("STEER_TORQUE", "STEER_TORQUE_REQUEST", "COUNTER", "CHECKSUM"): + assert parser.vl["STEERING_CONTROL"][sig] == parser.vl[228][sig] + + def test_scale_offset(self): + """Test that both scale and offset are correctly preserved""" + dbc_file = "honda_civic_touring_2016_can_generated" + msgs = [("VSA_STATUS", 50)] + parser = CANParser(dbc_file, msgs, 0) + packer = CANPacker(dbc_file) + + for brake in range(100): + values = {"USER_BRAKE": brake} + msgs = packer.make_can_msg("VSA_STATUS", 0, values) + parser.update_strings([0, [msgs]]) + + assert parser.vl["VSA_STATUS"]["USER_BRAKE"] == pytest.approx(brake) + + def test_subaru(self): + # Subaru is little endian + + dbc_file = "subaru_global_2017_generated" + + msgs = [("ES_LKAS", 50)] + + parser = CANParser(dbc_file, msgs, 0) + packer = CANPacker(dbc_file) + + idx = 0 + for steer in range(-256, 255): + for active in [1, 0]: + values = { + "LKAS_Output": steer, + "LKAS_Request": active, + "SET_1": 1 + } + + msgs = packer.make_can_msg("ES_LKAS", 0, values) + parser.update_strings([0, [msgs]]) + + assert parser.vl["ES_LKAS"]["LKAS_Output"] == pytest.approx(steer) + assert parser.vl["ES_LKAS"]["LKAS_Request"] == pytest.approx(active) + assert parser.vl["ES_LKAS"]["SET_1"] == pytest.approx(1) + assert parser.vl["ES_LKAS"]["COUNTER"] == pytest.approx(idx % 16) + idx += 1 + + def test_bus_timeout(self): + """Test CAN bus timeout detection""" + dbc_file = "honda_civic_touring_2016_can_generated" + + freq = 100 + msgs = [("VSA_STATUS", freq), ("STEER_MOTOR_TORQUE", freq/2)] + + parser = CANParser(dbc_file, msgs, 0) + packer = CANPacker(dbc_file) + + i = 0 + def send_msg(blank=False): + nonlocal i + i += 1 + t = i*((1 / freq) * 1e9) + + if blank: + msgs = [] + else: + msgs = [packer.make_can_msg("VSA_STATUS", 0, {}), ] + + parser.update_strings([t, msgs]) + + # all good, no timeout + for _ in range(1000): + send_msg() + assert not parser.bus_timeout, str(_) + + # timeout after 10 blank msgs + for n in range(200): + send_msg(blank=True) + assert (n >= 10) == parser.bus_timeout + + # no timeout immediately after seen again + send_msg() + assert not parser.bus_timeout + + def test_updated(self): + """Test updated value dict""" + dbc_file = "honda_civic_touring_2016_can_generated" + msgs = [("VSA_STATUS", 50)] + parser = CANParser(dbc_file, msgs, 0) + packer = CANPacker(dbc_file) + + # Make sure nothing is updated + assert len(parser.vl_all["VSA_STATUS"]["USER_BRAKE"]) == 0 + + idx = 0 + for _ in range(10): + # Ensure CANParser holds the values of any duplicate messages over multiple frames + user_brake_vals = [random.randrange(100) for _ in range(random.randrange(5, 10))] + half_idx = len(user_brake_vals) // 2 + can_msgs = [[], []] + for frame, brake_vals in enumerate((user_brake_vals[:half_idx], user_brake_vals[half_idx:])): + for user_brake in brake_vals: + values = {"USER_BRAKE": user_brake} + can_msgs[frame].append(packer.make_can_msg("VSA_STATUS", 0, values)) + idx += 1 + + parser.update_strings([[0, m] for m in can_msgs]) + vl_all = parser.vl_all["VSA_STATUS"]["USER_BRAKE"] + + assert vl_all == user_brake_vals + if len(user_brake_vals): + assert vl_all[-1] == parser.vl["VSA_STATUS"]["USER_BRAKE"] + + def test_timestamp_nanos(self): + """Test message timestamp dict""" + dbc_file = "honda_civic_touring_2016_can_generated" + + msgs = [ + ("VSA_STATUS", 50), + ("POWERTRAIN_DATA", 100), + ] + + parser = CANParser(dbc_file, msgs, 0) + packer = CANPacker(dbc_file) + + # Check the default timestamp is zero + for msg in ("VSA_STATUS", "POWERTRAIN_DATA"): + ts_nanos = parser.ts_nanos[msg].values() + assert set(ts_nanos) == {0} + + # Check: + # - timestamp is only updated for correct messages + # - timestamp is correct for multiple runs + # - timestamp is from the latest message if updating multiple strings + for _ in range(10): + can_strings = [] + log_mono_time = 0 + for i in range(10): + log_mono_time = int(0.01 * i * 1e+9) + can_msg = packer.make_can_msg("VSA_STATUS", 0, {}) + can_strings.append((log_mono_time, [can_msg])) + parser.update_strings(can_strings) + + ts_nanos = parser.ts_nanos["VSA_STATUS"].values() + assert set(ts_nanos) == {log_mono_time} + ts_nanos = parser.ts_nanos["POWERTRAIN_DATA"].values() + assert set(ts_nanos) == {0} + + def test_nonexistent_messages(self): + # Ensure we don't allow messages not in the DBC + existing_messages = ("STEERING_CONTROL", 228, "CAN_FD_MESSAGE", 245) + + for msg in existing_messages: + CANParser(TEST_DBC, [(msg, 0)]) + with pytest.raises(RuntimeError): + new_msg = msg + "1" if isinstance(msg, str) else msg + 1 + CANParser(TEST_DBC, [(new_msg, 0)]) + + def test_track_all_signals(self): + parser = CANParser("toyota_nodsu_pt_generated", [("ACC_CONTROL", 0)]) + assert parser.vl["ACC_CONTROL"] == { + "ACCEL_CMD": 0, + "ALLOW_LONG_PRESS": 0, + "ACC_MALFUNCTION": 0, + "RADAR_DIRTY": 0, + "DISTANCE": 0, + "MINI_CAR": 0, + "ACC_TYPE": 0, + "CANCEL_REQ": 0, + "ACC_CUT_IN": 0, + "LEAD_VEHICLE_STOPPED": 0, + "PERMIT_BRAKING": 0, + "RELEASE_STANDSTILL": 0, + "ITS_CONNECT_LEAD": 0, + "ACCEL_CMD_ALT": 0, + "CHECKSUM": 0, + } + + def test_disallow_duplicate_messages(self): + CANParser("toyota_nodsu_pt_generated", [("ACC_CONTROL", 5)]) + + with pytest.raises(RuntimeError): + CANParser("toyota_nodsu_pt_generated", [("ACC_CONTROL", 5), ("ACC_CONTROL", 10)]) + + with pytest.raises(RuntimeError): + CANParser("toyota_nodsu_pt_generated", [("ACC_CONTROL", 10), ("ACC_CONTROL", 10)]) + + def test_allow_undefined_msgs(self): + # TODO: we should throw an exception for these, but we need good + # discovery tests in openpilot first + packer = CANPacker("toyota_nodsu_pt_generated") + + assert packer.make_can_msg("ACC_CONTROL", 0, {"UNKNOWN_SIGNAL": 0}) == (835, b'\x00\x00\x00\x00\x00\x00\x00N', 0) + assert packer.make_can_msg("UNKNOWN_MESSAGE", 0, {"UNKNOWN_SIGNAL": 0}) == (0, b'', 0) + assert packer.make_can_msg(0, 0, {"UNKNOWN_SIGNAL": 0}) == (0, b'', 0) diff --git a/opendbc_repo/opendbc/can/tests/test_parser_performance.py b/opendbc_repo/opendbc/can/tests/test_parser_performance.py new file mode 100644 index 000000000000000..c4ca5a3c82f9475 --- /dev/null +++ b/opendbc_repo/opendbc/can/tests/test_parser_performance.py @@ -0,0 +1,48 @@ +import pytest +import time + +from opendbc.can.parser import CANParser +from opendbc.can.packer import CANPacker + + +@pytest.mark.skip("TODO: varies too much between machines") +class TestParser: + def _benchmark(self, checks, thresholds, n): + parser = CANParser('toyota_new_mc_pt_generated', checks, 0) + packer = CANPacker('toyota_new_mc_pt_generated') + + can_msgs = [] + for i in range(50000): + values = {"ACC_CONTROL": {"ACC_TYPE": 1, "ALLOW_LONG_PRESS": 3}} + msgs = [packer.make_can_msg(k, 0, v) for k, v in values.items()] + can_msgs.append([int(0.01 * i * 1e9), msgs]) + + ets = [] + for _ in range(25): + if n > 1: + strings = [] + for i in range(0, len(can_msgs), n): + strings.append(can_msgs[i:i + n]) + t1 = time.process_time_ns() + for m in strings: + parser.update_strings(m) + t2 = time.process_time_ns() + else: + t1 = time.process_time_ns() + for m in can_msgs: + parser.update_strings([m]) + t2 = time.process_time_ns() + + ets.append(t2 - t1) + + et = sum(ets) / len(ets) + avg_nanos = et / len(can_msgs) + print('%s: [%d] %.1fms to parse %s, avg: %dns' % (self._testMethodName, n, et/1e6, len(can_msgs), avg_nanos)) + + minn, maxx = thresholds + assert avg_nanos < maxx + assert avg_nanos > minn, "Performance seems to have improved, update test thresholds." + + def test_performance_all_signals(self): + self._benchmark([('ACC_CONTROL', 10)], (10000, 19000), 1) + self._benchmark([('ACC_CONTROL', 10)], (1300, 5000), 10) diff --git a/opendbc_repo/opendbc/car/CARS_template.md b/opendbc_repo/opendbc/car/CARS_template.md new file mode 100644 index 000000000000000..d13f3a4b764135a --- /dev/null +++ b/opendbc_repo/opendbc/car/CARS_template.md @@ -0,0 +1,78 @@ + + +# Support Information for {{car_docs_with_extras | length}} Known Cars + +|{{ExtraCarsColumn | map(attribute='value') | join('|') | replace(hardware_col_name, wide_hardware_col_name)}}| +|---|---|---|{% for _ in range((ExtraCarsColumn | length) - 3) %}{{':---:|'}}{% endfor +%} +{% for car_docs in car_docs_with_extras %} +|{% for column in ExtraCarsColumn %}{{car_docs.get_extra_cars_column(column)}}|{% endfor %} + +{% endfor %} + +# Types of Support + +**opendbc can support many more cars than it currently does.** There are a few reasons your car may not be supported. +If your car doesn't fit into any of the incompatibility criteria here, then there's a good chance it can be supported! +We're adding support for new cars all the time. **We don't have a roadmap for car support**, and in fact, most car +support comes from users like you! + +## Upstream + +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. + +## Under Review + +A vehicle under review is one for which software support has been merged into upstream openpilot, but hasn't yet been +tested for drive quality and conformance with [comma safety guidelines](https://github.com/commaai/openpilot/blob/master/docs/SAFETY.md). +This is a normal part of the development and quality assurance process. This vehicle will not work when upstream +openpilot is installed, but custom forks may allow their use. + +## Custom + +Vehicles in this category are not considered plug-and-play. Software support is included in upstream openpilot, but +these vehicles might not have a harness in the comma store, or the physical install might be at an unusual or cumbersome +location, or they might need unusual configuration after install. + +## Dashcam + +Dashcam vehicles have software support in upstream openpilot, but will go into "dashcam mode" at startup and will not +engage. This may be due to known issues with driving safety or quality, or it may be a work in progress that isn't yet +ready for safety and quality review. + +## Community + +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/). + +Some notable works-in-progress: +* Honda + * 2024 Acura Integra, commaai/openpilot#32056 + * 2023-24 Honda Accord (CAN-FD), commaai/openpilot#32229 + * 2024 Honda CR-V (CAN-FD), commaai/openpilot#32806 + * 2024 Honda CR-V Hybrid (CAN-FD), commaai/openpilot#31527 + * Depends on commaai/opendbc#1100 + * 2021-25 Honda Odyssey, commaai/opendbc#1330 + * 2023-24 Honda Pilot (CAN-FD), commaai/openpilot#30324 + * Camera ACC stability improvements, commaai/openpilot#31022 + * Depends on commaai/panda#1814 + * Depends on commaai/opendbc#998 + * These are being reworked for full-time proxy through openpilot + * Manual transmission support (Civic, Integra) + * Depends on commaai/opendbc#1034 (merged) + * Car port support PR not yet filed + +## Incompatible + +### CAN Bus Security + +Vehicles with CAN security measures, such as AUTOSAR Secure Onboard Communication (SecOC) are not usable with openpilot +unless the owner can recover the message signing key and implement CAN message signing. Examples include certain newer +Toyota, and the GM Global B platform. + +### FlexRay + +All the cars that openpilot supports use a [CAN bus](https://en.wikipedia.org/wiki/CAN_bus) for communication between all the car's computers, however a +CAN bus isn't the only way that the computers in your car can communicate. Most, if not all, vehicles from the following +manufacturers use [FlexRay](https://en.wikipedia.org/wiki/FlexRay) instead of a CAN bus: **BMW, Mercedes, Audi, Land Rover, and some Volvo**. These cars +may one day be supported, but we have no immediate plans to support FlexRay. diff --git a/opendbc_repo/opendbc/car/__init__.py b/opendbc_repo/opendbc/car/__init__.py new file mode 100644 index 000000000000000..5b24daad3a2523a --- /dev/null +++ b/opendbc_repo/opendbc/car/__init__.py @@ -0,0 +1,339 @@ +# functions common among cars +import logging +from collections import namedtuple +from dataclasses import dataclass, field +from enum import IntFlag, ReprEnum, EnumType +from dataclasses import replace + +from panda import uds +from opendbc.car import structs +from opendbc.car.can_definitions import CanData +from opendbc.car.docs_definitions import CarDocs, ExtraCarDocs +from opendbc.car.common.numpy_fast import clip, interp + +# set up logging +carlog = logging.getLogger('carlog') +carlog.setLevel(logging.INFO) +carlog.propagate = False + +DT_CTRL = 0.01 # car state and control loop timestep (s) + +# kg of standard extra cargo to count for drive, gas, etc... +STD_CARGO_KG = 136. + +ACCELERATION_DUE_TO_GRAVITY = 9.81 # m/s^2 + +ButtonType = structs.CarState.ButtonEvent.Type +AngleRateLimit = namedtuple('AngleRateLimit', ['speed_bp', 'angle_v']) + + +def apply_hysteresis(val: float, val_steady: float, hyst_gap: float) -> float: + if val > val_steady + hyst_gap: + val_steady = val - hyst_gap + elif val < val_steady - hyst_gap: + val_steady = val + hyst_gap + return val_steady + + +def create_button_events(cur_btn: int, prev_btn: int, buttons_dict: dict[int, structs.CarState.ButtonEvent.Type], + unpressed_btn: int = 0) -> list[structs.CarState.ButtonEvent]: + events: list[structs.CarState.ButtonEvent] = [] + + if cur_btn == prev_btn: + return events + + # Add events for button presses, multiple when a button switches without going to unpressed + for pressed, btn in ((False, prev_btn), (True, cur_btn)): + if btn != unpressed_btn: + events.append(structs.CarState.ButtonEvent(pressed=pressed, + type=buttons_dict.get(btn, ButtonType.unknown))) + return events + + +def gen_empty_fingerprint(): + return {i: {} for i in range(8)} + + +# these params were derived for the Civic and used to calculate params for other cars +class VehicleDynamicsParams: + MASS = 1326. + STD_CARGO_KG + WHEELBASE = 2.70 + CENTER_TO_FRONT = WHEELBASE * 0.4 + CENTER_TO_REAR = WHEELBASE - CENTER_TO_FRONT + ROTATIONAL_INERTIA = 2500 + TIRE_STIFFNESS_FRONT = 192150 + TIRE_STIFFNESS_REAR = 202500 + + +# TODO: get actual value, for now starting with reasonable value for +# civic and scaling by mass and wheelbase +def scale_rot_inertia(mass, wheelbase): + return VehicleDynamicsParams.ROTATIONAL_INERTIA * mass * wheelbase ** 2 / (VehicleDynamicsParams.MASS * VehicleDynamicsParams.WHEELBASE ** 2) + + +# TODO: start from empirically derived lateral slip stiffness for the civic and scale by +# mass and CG position, so all cars will have approximately similar dyn behaviors +def scale_tire_stiffness(mass, wheelbase, center_to_front, tire_stiffness_factor): + center_to_rear = wheelbase - center_to_front + tire_stiffness_front = (VehicleDynamicsParams.TIRE_STIFFNESS_FRONT * tire_stiffness_factor) * mass / VehicleDynamicsParams.MASS * \ + (center_to_rear / wheelbase) / (VehicleDynamicsParams.CENTER_TO_REAR / VehicleDynamicsParams.WHEELBASE) + + tire_stiffness_rear = (VehicleDynamicsParams.TIRE_STIFFNESS_REAR * tire_stiffness_factor) * mass / VehicleDynamicsParams.MASS * \ + (center_to_front / wheelbase) / (VehicleDynamicsParams.CENTER_TO_FRONT / VehicleDynamicsParams.WHEELBASE) + + return tire_stiffness_front, tire_stiffness_rear + + +DbcDict = dict[str, str] + + +def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None, body_dbc=None) -> DbcDict: + return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc, 'body': body_dbc} + + +def apply_driver_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): + + # limits due to driver torque + driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER + driver_min_torque = -LIMITS.STEER_MAX + (-LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER + max_steer_allowed = max(min(LIMITS.STEER_MAX, driver_max_torque), 0) + min_steer_allowed = min(max(-LIMITS.STEER_MAX, driver_min_torque), 0) + apply_torque = clip(apply_torque, min_steer_allowed, max_steer_allowed) + + # slow rate if steer torque increases in magnitude + if apply_torque_last > 0: + apply_torque = clip(apply_torque, max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP), + apply_torque_last + LIMITS.STEER_DELTA_UP) + else: + apply_torque = clip(apply_torque, apply_torque_last - LIMITS.STEER_DELTA_UP, + min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) + + return int(round(float(apply_torque))) + + +def apply_dist_to_meas_limits(val, val_last, val_meas, + STEER_DELTA_UP, STEER_DELTA_DOWN, + STEER_ERROR_MAX, STEER_MAX): + # limits due to comparison of commanded val VS measured val (torque/angle/curvature) + max_lim = min(max(val_meas + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX) + min_lim = max(min(val_meas - STEER_ERROR_MAX, -STEER_ERROR_MAX), -STEER_MAX) + + val = clip(val, min_lim, max_lim) + + # slow rate if val increases in magnitude + if val_last > 0: + val = clip(val, + max(val_last - STEER_DELTA_DOWN, -STEER_DELTA_UP), + val_last + STEER_DELTA_UP) + else: + val = clip(val, + val_last - STEER_DELTA_UP, + min(val_last + STEER_DELTA_DOWN, STEER_DELTA_UP)) + + return float(val) + + +def apply_meas_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS): + return int(round(apply_dist_to_meas_limits(apply_torque, apply_torque_last, motor_torque, + LIMITS.STEER_DELTA_UP, LIMITS.STEER_DELTA_DOWN, + LIMITS.STEER_ERROR_MAX, LIMITS.STEER_MAX))) + + +def apply_std_steer_angle_limits(apply_angle, apply_angle_last, v_ego, LIMITS): + # pick angle rate limits based on wind up/down + steer_up = apply_angle_last * apply_angle >= 0. and abs(apply_angle) > abs(apply_angle_last) + rate_limits = LIMITS.ANGLE_RATE_LIMIT_UP if steer_up else LIMITS.ANGLE_RATE_LIMIT_DOWN + + angle_rate_lim = interp(v_ego, rate_limits.speed_bp, rate_limits.angle_v) + return clip(apply_angle, apply_angle_last - angle_rate_lim, apply_angle_last + angle_rate_lim) + + +def common_fault_avoidance(fault_condition: bool, request: bool, above_limit_frames: int, + max_above_limit_frames: int, max_mismatching_frames: int = 1): + """ + Several cars have the ability to work around their EPS limits by cutting the + request bit of their LKAS message after a certain number of frames above the limit. + """ + + # Count up to max_above_limit_frames, at which point we need to cut the request for above_limit_frames to avoid a fault + if request and fault_condition: + above_limit_frames += 1 + else: + above_limit_frames = 0 + + # Once we cut the request bit, count additionally to max_mismatching_frames before setting the request bit high again. + # Some brands do not respect our workaround without multiple messages on the bus, for example + if above_limit_frames > max_above_limit_frames: + request = False + + if above_limit_frames >= max_above_limit_frames + max_mismatching_frames: + above_limit_frames = 0 + + return above_limit_frames, request + + +def apply_center_deadzone(error, deadzone): + if (error > - deadzone) and (error < deadzone): + error = 0. + return error + + +def rate_limit(new_value, last_value, dw_step, up_step): + return clip(new_value, last_value + dw_step, last_value + up_step) + + +def get_friction(lateral_accel_error: float, lateral_accel_deadzone: float, friction_threshold: float, + torque_params: structs.CarParams.LateralTorqueTuning, friction_compensation: bool) -> float: + friction_interp = interp( + apply_center_deadzone(lateral_accel_error, lateral_accel_deadzone), + [-friction_threshold, friction_threshold], + [-torque_params.friction, torque_params.friction] + ) + friction = float(friction_interp) if friction_compensation else 0.0 + return friction + + +def make_tester_present_msg(addr, bus, subaddr=None, suppress_response=False): + dat = [0x02, uds.SERVICE_TYPE.TESTER_PRESENT] + if subaddr is not None: + dat.insert(0, subaddr) + dat.append(0x80 if suppress_response else 0x0) # sub-function + + dat.extend([0x0] * (8 - len(dat))) + return CanData(addr, bytes(dat), bus) + + +def get_safety_config(safety_model: structs.CarParams.SafetyModel, safety_param: int = None) -> structs.CarParams.SafetyConfig: + ret = structs.CarParams.SafetyConfig() + ret.safetyModel = safety_model + if safety_param is not None: + ret.safetyParam = safety_param + return ret + + +class CanBusBase: + offset: int + + def __init__(self, CP, fingerprint: dict[int, dict[int, int]] | None) -> None: + if CP is None: + assert fingerprint is not None + num = max([k for k, v in fingerprint.items() if len(v)], default=0) // 4 + 1 + else: + num = len(CP.safetyConfigs) + self.offset = 4 * (num - 1) + + +class CanSignalRateCalculator: + """ + Calculates the instantaneous rate of a CAN signal by using the counter + variable and the known frequency of the CAN message that contains it. + """ + def __init__(self, frequency): + self.frequency = frequency + self.previous_counter = 0 + self.previous_value = 0 + self.rate = 0 + + def update(self, current_value, current_counter): + if current_counter != self.previous_counter: + self.rate = (current_value - self.previous_value) * self.frequency + + self.previous_counter = current_counter + self.previous_value = current_value + + return self.rate + + +@dataclass(frozen=True, kw_only=True) +class CarSpecs: + mass: float # kg, curb weight + wheelbase: float # meters + steerRatio: float + centerToFrontRatio: float = 0.5 + minSteerSpeed: float = 0.0 # m/s + minEnableSpeed: float = -1.0 # m/s + tireStiffnessFactor: float = 1.0 + + def override(self, **kwargs): + return replace(self, **kwargs) + + +class Freezable: + _frozen: bool = False + + def freeze(self): + if not self._frozen: + self._frozen = True + + def __setattr__(self, *args, **kwargs): + if self._frozen: + raise Exception("cannot modify frozen object") + super().__setattr__(*args, **kwargs) + + +@dataclass(order=True) +class PlatformConfigBase(Freezable): + car_docs: list[CarDocs] | list[ExtraCarDocs] + specs: CarSpecs + + dbc_dict: DbcDict + + flags: int = 0 + + platform_str: str | None = None + + def __hash__(self) -> int: + return hash(self.platform_str) + + def override(self, **kwargs): + return replace(self, **kwargs) + + def init(self): + pass + + def __post_init__(self): + self.init() + + +@dataclass(order=True) +class PlatformConfig(PlatformConfigBase): + car_docs: list[CarDocs] + specs: CarSpecs + dbc_dict: DbcDict + + +@dataclass(order=True) +class ExtraPlatformConfig(PlatformConfigBase): + car_docs: list[ExtraCarDocs] + specs: CarSpecs = CarSpecs(mass=0., wheelbase=0., steerRatio=0.) + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('unknown', None)) + + +class PlatformsType(EnumType): + def __new__(metacls, cls, bases, classdict, *, boundary=None, _simple=False, **kwds): + for key in classdict._member_names.keys(): + cfg: PlatformConfig = classdict[key] + cfg.platform_str = key + cfg.freeze() + return super().__new__(metacls, cls, bases, classdict, boundary=boundary, _simple=_simple, **kwds) + + +class Platforms(str, ReprEnum, metaclass=PlatformsType): + config: PlatformConfigBase + + def __new__(cls, platform_config: PlatformConfig): + member = str.__new__(cls, platform_config.platform_str) + member.config = platform_config + member._value_ = platform_config.platform_str + return member + + def __repr__(self): + return f"<{self.__class__.__name__}.{self.name}>" + + @classmethod + def create_dbc_map(cls) -> dict[str, DbcDict]: + return {p: p.config.dbc_dict for p in cls} + + @classmethod + def with_flags(cls, flags: IntFlag) -> set['Platforms']: + return {p for p in cls if p.config.flags & flags} diff --git a/selfdrive/car/body/__init__.py b/opendbc_repo/opendbc/car/body/__init__.py similarity index 100% rename from selfdrive/car/body/__init__.py rename to opendbc_repo/opendbc/car/body/__init__.py diff --git a/selfdrive/car/body/bodycan.py b/opendbc_repo/opendbc/car/body/bodycan.py similarity index 100% rename from selfdrive/car/body/bodycan.py rename to opendbc_repo/opendbc/car/body/bodycan.py diff --git a/opendbc_repo/opendbc/car/body/carcontroller.py b/opendbc_repo/opendbc/car/body/carcontroller.py new file mode 100644 index 000000000000000..020db5d5cff9249 --- /dev/null +++ b/opendbc_repo/opendbc/car/body/carcontroller.py @@ -0,0 +1,82 @@ +import numpy as np + +from opendbc.can.packer import CANPacker +from opendbc.car import DT_CTRL +from opendbc.car.common.pid import PIDController +from opendbc.car.body import bodycan +from opendbc.car.body.values import SPEED_FROM_RPM +from opendbc.car.interfaces import CarControllerBase + +MAX_TORQUE = 500 +MAX_TORQUE_RATE = 50 +MAX_ANGLE_ERROR = np.radians(7) +MAX_POS_INTEGRATOR = 0.2 # meters +MAX_TURN_INTEGRATOR = 0.1 # meters + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.packer = CANPacker(dbc_name) + + # PIDs + self.turn_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) + self.wheeled_speed_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) + + self.torque_r_filtered = 0. + self.torque_l_filtered = 0. + + @staticmethod + def deadband_filter(torque, deadband): + if torque > 0: + torque += deadband + else: + torque -= deadband + return torque + + def update(self, CC, CS, now_nanos): + + torque_l = 0 + torque_r = 0 + + if CC.enabled: + # Read these from the joystick + # TODO: this isn't acceleration, okay? + speed_desired = CC.actuators.accel / 5. + speed_diff_desired = -CC.actuators.steer / 2. + + speed_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl + CS.out.wheelSpeeds.fr) / 2. + speed_error = speed_desired - speed_measured + + torque = self.wheeled_speed_pid.update(speed_error, freeze_integrator=False) + + speed_diff_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl - CS.out.wheelSpeeds.fr) + turn_error = speed_diff_measured - speed_diff_desired + freeze_integrator = ((turn_error < 0 and self.turn_pid.error_integral <= -MAX_TURN_INTEGRATOR) or + (turn_error > 0 and self.turn_pid.error_integral >= MAX_TURN_INTEGRATOR)) + torque_diff = self.turn_pid.update(turn_error, freeze_integrator=freeze_integrator) + + # Combine 2 PIDs outputs + torque_r = torque + torque_diff + torque_l = torque - torque_diff + + # Torque rate limits + self.torque_r_filtered = np.clip(self.deadband_filter(torque_r, 10), + self.torque_r_filtered - MAX_TORQUE_RATE, + self.torque_r_filtered + MAX_TORQUE_RATE) + self.torque_l_filtered = np.clip(self.deadband_filter(torque_l, 10), + self.torque_l_filtered - MAX_TORQUE_RATE, + self.torque_l_filtered + MAX_TORQUE_RATE) + torque_r = int(np.clip(self.torque_r_filtered, -MAX_TORQUE, MAX_TORQUE)) + torque_l = int(np.clip(self.torque_l_filtered, -MAX_TORQUE, MAX_TORQUE)) + + can_sends = [] + can_sends.append(bodycan.create_control(self.packer, torque_l, torque_r)) + + new_actuators = CC.actuators.as_builder() + new_actuators.accel = torque_l + new_actuators.steer = torque_r + new_actuators.steerOutputCan = torque_r + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/body/carstate.py b/opendbc_repo/opendbc/car/body/carstate.py new file mode 100644 index 000000000000000..68cfb2072ffcdbf --- /dev/null +++ b/opendbc_repo/opendbc/car/body/carstate.py @@ -0,0 +1,39 @@ +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.interfaces import CarStateBase +from opendbc.car.body.values import DBC + + +class CarState(CarStateBase): + def update(self, cp, *_) -> structs.CarState: + ret = structs.CarState() + + ret.wheelSpeeds.fl = cp.vl['MOTORS_DATA']['SPEED_L'] + ret.wheelSpeeds.fr = cp.vl['MOTORS_DATA']['SPEED_R'] + + ret.vEgoRaw = ((ret.wheelSpeeds.fl + ret.wheelSpeeds.fr) / 2.) * self.CP.wheelSpeedFactor + + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = False + + ret.steerFaultPermanent = any([cp.vl['VAR_VALUES']['MOTOR_ERR_L'], cp.vl['VAR_VALUES']['MOTOR_ERR_R'], + cp.vl['VAR_VALUES']['FAULT']]) + + ret.charging = cp.vl["BODY_DATA"]["CHARGER_CONNECTED"] == 1 + ret.fuelGauge = cp.vl["BODY_DATA"]["BATT_PERCENTAGE"] / 100 + + # irrelevant for non-car + ret.gearShifter = structs.CarState.GearShifter.drive + ret.cruiseState.enabled = True + ret.cruiseState.available = True + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + ("MOTORS_DATA", 100), + ("VAR_VALUES", 10), + ("BODY_DATA", 1), + ] + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) diff --git a/opendbc_repo/opendbc/car/body/fingerprints.py b/opendbc_repo/opendbc/car/body/fingerprints.py new file mode 100644 index 000000000000000..3f5665029ba01fc --- /dev/null +++ b/opendbc_repo/opendbc/car/body/fingerprints.py @@ -0,0 +1,28 @@ +# ruff: noqa: E501 +from opendbc.car.structs import CarParams +from opendbc.car.body.values import CAR + +Ecu = CarParams.Ecu + +# debug ecu fw version is the git hash of the firmware + + +FINGERPRINTS = { + CAR.COMMA_BODY: [{ + 513: 8, 516: 8, 514: 3, 515: 4 + }], +} + +FW_VERSIONS = { + CAR.COMMA_BODY: { + (Ecu.engine, 0x720, None): [ + b'0.0.01', + b'0.3.00a', + b'02/27/2022', + ], + (Ecu.debug, 0x721, None): [ + b'166bd860', + b'dc780f85', + ], + }, +} diff --git a/opendbc_repo/opendbc/car/body/interface.py b/opendbc_repo/opendbc/car/body/interface.py new file mode 100644 index 000000000000000..f720c4a7d6e8738 --- /dev/null +++ b/opendbc_repo/opendbc/car/body/interface.py @@ -0,0 +1,25 @@ +import math +from opendbc.car import get_safety_config, structs +from opendbc.car.interfaces import CarInterfaceBase +from opendbc.car.body.values import SPEED_FROM_RPM + + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.notCar = True + ret.carName = "body" + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.body)] + + ret.minSteerSpeed = -math.inf + ret.maxLateralAccel = math.inf # TODO: set to a reasonable value + ret.steerLimitTimer = 1.0 + ret.steerActuatorDelay = 0. + + ret.wheelSpeedFactor = SPEED_FROM_RPM + + ret.radarUnavailable = True + ret.openpilotLongitudinalControl = True + ret.steerControlType = structs.CarParams.SteerControlType.angle + + return ret diff --git a/opendbc_repo/opendbc/car/body/radar_interface.py b/opendbc_repo/opendbc/car/body/radar_interface.py new file mode 100644 index 000000000000000..6e552bf618fda6f --- /dev/null +++ b/opendbc_repo/opendbc/car/body/radar_interface.py @@ -0,0 +1,4 @@ +from opendbc.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/opendbc_repo/opendbc/car/body/values.py b/opendbc_repo/opendbc/car/body/values.py new file mode 100644 index 000000000000000..3c221548c3749b8 --- /dev/null +++ b/opendbc_repo/opendbc/car/body/values.py @@ -0,0 +1,40 @@ +from opendbc.car import CarSpecs, PlatformConfig, Platforms, dbc_dict +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarDocs +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = CarParams.Ecu + +SPEED_FROM_RPM = 0.008587 + + +class CarControllerParams: + ANGLE_DELTA_BP = [0., 5., 15.] + ANGLE_DELTA_V = [5., .8, .15] # windup limit + ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit + LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower + STEER_THRESHOLD = 1.0 + + def __init__(self, CP): + pass + + +class CAR(Platforms): + COMMA_BODY = PlatformConfig( + [CarDocs("comma body", package="All")], + CarSpecs(mass=9, wheelbase=0.406, steerRatio=0.5, centerToFrontRatio=0.44), + dbc_dict('comma_body', None), + ) + + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + bus=0, + ), + ], +) + +DBC = CAR.create_dbc_map() diff --git a/opendbc_repo/opendbc/car/can_definitions.py b/opendbc_repo/opendbc/car/can_definitions.py new file mode 100644 index 000000000000000..2dba7f26a862af4 --- /dev/null +++ b/opendbc_repo/opendbc/car/can_definitions.py @@ -0,0 +1,15 @@ +from collections.abc import Callable +from typing import NamedTuple, Protocol + + +class CanData(NamedTuple): + address: int + dat: bytes + src: int + + +CanSendCallable = Callable[[list[CanData]], None] + + +class CanRecvCallable(Protocol): + def __call__(self, wait_for_one: bool = False) -> list[list[CanData]]: ... diff --git a/opendbc_repo/opendbc/car/car.capnp b/opendbc_repo/opendbc/car/car.capnp new file mode 100644 index 000000000000000..237ba2c26b8e214 --- /dev/null +++ b/opendbc_repo/opendbc/car/car.capnp @@ -0,0 +1,722 @@ +using Cxx = import "./include/c++.capnp"; +$Cxx.namespace("cereal"); + +@0x8e2af1e708af8b8d; + +# ******* events causing controls state machine transition ******* + +# IMPORTANT: This struct is to not be modified so old logs can be parsed +struct OnroadEventDEPRECATED @0x9b1657f34caf3ad3 { + name @0 :EventName; + + # event types + enable @1 :Bool; + noEntry @2 :Bool; + warning @3 :Bool; # alerts presented only when enabled or soft disabling + userDisable @4 :Bool; + softDisable @5 :Bool; + immediateDisable @6 :Bool; + preEnable @7 :Bool; + permanent @8 :Bool; # alerts presented regardless of openpilot state + overrideLateral @10 :Bool; + overrideLongitudinal @9 :Bool; + + enum EventName @0xbaa8c5d505f727de { + canError @0; + steerUnavailable @1; + wrongGear @4; + doorOpen @5; + seatbeltNotLatched @6; + espDisabled @7; + wrongCarMode @8; + steerTempUnavailable @9; + reverseGear @10; + buttonCancel @11; + buttonEnable @12; + pedalPressed @13; # exits active state + preEnableStandstill @73; # added during pre-enable state with brake + gasPressedOverride @108; # added when user is pressing gas with no disengage on gas + steerOverride @114; + cruiseDisabled @14; + speedTooLow @17; + outOfSpace @18; + overheat @19; + calibrationIncomplete @20; + calibrationInvalid @21; + calibrationRecalibrating @117; + controlsMismatch @22; + pcmEnable @23; + pcmDisable @24; + radarFault @26; + brakeHold @28; + parkBrake @29; + manualRestart @30; + joystickDebug @34; + longitudinalManeuver @124; + steerTempUnavailableSilent @35; + resumeRequired @36; + preDriverDistracted @37; + promptDriverDistracted @38; + driverDistracted @39; + preDriverUnresponsive @43; + promptDriverUnresponsive @44; + driverUnresponsive @45; + belowSteerSpeed @46; + lowBattery @48; + accFaulted @51; + sensorDataInvalid @52; + commIssue @53; + commIssueAvgFreq @109; + tooDistracted @54; + posenetInvalid @55; + soundsUnavailable @56; + preLaneChangeLeft @57; + preLaneChangeRight @58; + laneChange @59; + lowMemory @63; + stockAeb @64; + ldw @65; + carUnrecognized @66; + invalidLkasSetting @69; + speedTooHigh @70; + laneChangeBlocked @71; + relayMalfunction @72; + stockFcw @74; + startup @75; + startupNoCar @76; + startupNoControl @77; + startupNoSecOcKey @125; + startupMaster @78; + fcw @79; + steerSaturated @80; + belowEngageSpeed @84; + noGps @85; + wrongCruiseMode @87; + modeldLagging @89; + deviceFalling @90; + fanMalfunction @91; + cameraMalfunction @92; + cameraFrameRate @110; + processNotRunning @95; + dashcamMode @96; + selfdriveInitializing @98; + usbError @99; + cruiseMismatch @106; + canBusMissing @111; + selfdrivedLagging @112; + resumeBlocked @113; + steerTimeLimit @115; + vehicleSensorsInvalid @116; + locationdTemporaryError @103; + locationdPermanentError @118; + paramsdTemporaryError @50; + paramsdPermanentError @119; + actuatorsApiUnavailable @120; + espActive @121; + personalityChanged @122; + aeb @123; + + radarCanErrorDEPRECATED @15; + communityFeatureDisallowedDEPRECATED @62; + radarCommIssueDEPRECATED @67; + driverMonitorLowAccDEPRECATED @68; + gasUnavailableDEPRECATED @3; + dataNeededDEPRECATED @16; + modelCommIssueDEPRECATED @27; + ipasOverrideDEPRECATED @33; + geofenceDEPRECATED @40; + driverMonitorOnDEPRECATED @41; + driverMonitorOffDEPRECATED @42; + calibrationProgressDEPRECATED @47; + invalidGiraffeHondaDEPRECATED @49; + invalidGiraffeToyotaDEPRECATED @60; + internetConnectivityNeededDEPRECATED @61; + whitePandaUnsupportedDEPRECATED @81; + commIssueWarningDEPRECATED @83; + focusRecoverActiveDEPRECATED @86; + neosUpdateRequiredDEPRECATED @88; + modelLagWarningDEPRECATED @93; + startupOneplusDEPRECATED @82; + startupFuzzyFingerprintDEPRECATED @97; + noTargetDEPRECATED @25; + brakeUnavailableDEPRECATED @2; + plannerErrorDEPRECATED @32; + gpsMalfunctionDEPRECATED @94; + roadCameraErrorDEPRECATED @100; + driverCameraErrorDEPRECATED @101; + wideRoadCameraErrorDEPRECATED @102; + highCpuUsageDEPRECATED @105; + startupNoFwDEPRECATED @104; + lowSpeedLockoutDEPRECATED @31; + lkasDisabledDEPRECATED @107; + } +} + +# ******* main car state @ 100hz ******* +# all speeds in m/s + +struct CarState { + # CAN health + canValid @26 :Bool; # invalid counter/checksums + canTimeout @40 :Bool; # CAN bus dropped out + canErrorCounter @48 :UInt32; + + # car speed + vEgo @1 :Float32; # best estimate of speed + aEgo @16 :Float32; # best estimate of aCAN cceleration + vEgoRaw @17 :Float32; # unfiltered speed from wheel speed sensors + vEgoCluster @44 :Float32; # best estimate of speed shown on car's instrument cluster, used for UI + + vCruise @53 :Float32; # actual set speed + vCruiseCluster @54 :Float32; # set speed to display in the UI + + yawRate @22 :Float32; # best estimate of yaw rate + standstill @18 :Bool; + wheelSpeeds @2 :WheelSpeeds; + + # gas pedal, 0.0-1.0 + gas @3 :Float32; # this is user pedal only + gasPressed @4 :Bool; # this is user pedal only + + engineRpm @46 :Float32; + + # brake pedal, 0.0-1.0 + brake @5 :Float32; # this is user pedal only + brakePressed @6 :Bool; # this is user pedal only + regenBraking @45 :Bool; # this is user pedal only + parkingBrake @39 :Bool; + brakeHoldActive @38 :Bool; + + # steering wheel + steeringAngleDeg @7 :Float32; + steeringAngleOffsetDeg @37 :Float32; # Offset betweens sensors in case there multiple + steeringRateDeg @15 :Float32; + steeringTorque @8 :Float32; # TODO: standardize units + steeringTorqueEps @27 :Float32; # TODO: standardize units + steeringPressed @9 :Bool; # if the user is using the steering wheel + steerFaultTemporary @35 :Bool; # temporary EPS fault + steerFaultPermanent @36 :Bool; # permanent EPS fault + invalidLkasSetting @55 :Bool; # stock LKAS is incorrectly configured (i.e. on or off) + stockAeb @30 :Bool; + stockFcw @31 :Bool; + espDisabled @32 :Bool; + accFaulted @42 :Bool; + carFaultedNonCritical @47 :Bool; # some ECU is faulted, but car remains controllable + espActive @51 :Bool; + vehicleSensorsInvalid @52 :Bool; # invalid steering angle readings, etc. + lowSpeedAlert @56 :Bool; # lost steering control due to a dynamic min steering speed + + # cruise state + cruiseState @10 :CruiseState; + + # gear + gearShifter @14 :GearShifter; + + # button presses + buttonEvents @11 :List(ButtonEvent); + leftBlinker @20 :Bool; + rightBlinker @21 :Bool; + genericToggle @23 :Bool; + + # lock info + doorOpen @24 :Bool; + seatbeltUnlatched @25 :Bool; + + # clutch (manual transmission only) + clutchPressed @28 :Bool; + + # blindspot sensors + leftBlindspot @33 :Bool; # Is there something blocking the left lane change + rightBlindspot @34 :Bool; # Is there something blocking the right lane change + + fuelGauge @41 :Float32; # battery or fuel tank level from 0.0 to 1.0 + charging @43 :Bool; + + # process meta + cumLagMs @50 :Float32; + + struct WheelSpeeds { + # optional wheel speeds + fl @0 :Float32; + fr @1 :Float32; + rl @2 :Float32; + rr @3 :Float32; + } + + struct CruiseState { + enabled @0 :Bool; + speed @1 :Float32; + speedCluster @6 :Float32; # Set speed as shown on instrument cluster + available @2 :Bool; + speedOffset @3 :Float32; + standstill @4 :Bool; + nonAdaptive @5 :Bool; + } + + enum GearShifter { + unknown @0; + park @1; + drive @2; + neutral @3; + reverse @4; + sport @5; + low @6; + brake @7; + eco @8; + manumatic @9; + } + + # send on change + struct ButtonEvent { + pressed @0 :Bool; + type @1 :Type; + + enum Type { + unknown @0; + leftBlinker @1; + rightBlinker @2; + accelCruise @3; + decelCruise @4; + cancel @5; + lkas @6; + altButton2 @7; + mainCruise @8; + setCruise @9; + resumeCruise @10; + gapAdjustCruise @11; + } + } + + # deprecated + errorsDEPRECATED @0 :List(OnroadEventDEPRECATED.EventName); + brakeLightsDEPRECATED @19 :Bool; + steeringRateLimitedDEPRECATED @29 :Bool; + canMonoTimesDEPRECATED @12: List(UInt64); + canRcvTimeoutDEPRECATED @49 :Bool; + eventsDEPRECATED @13 :List(OnroadEventDEPRECATED); +} + +# ******* radar state @ 20hz ******* + +struct RadarData @0x888ad6581cf0aacb { + errors @0 :List(Error); + points @1 :List(RadarPoint); + + enum Error { + canError @0; + fault @1; + wrongConfig @2; + } + + # similar to LiveTracks + # is one timestamp valid for all? I think so + struct RadarPoint { + trackId @0 :UInt64; # no trackId reuse + + # these 3 are the minimum required + dRel @1 :Float32; # m from the front bumper of the car + yRel @2 :Float32; # m + vRel @3 :Float32; # m/s + + # these are optional and valid if they are not NaN + aRel @4 :Float32; # m/s^2 + yvRel @5 :Float32; # m/s + + # some radars flag measurements VS estimates + measured @6 :Bool; + } + + # deprecated + canMonoTimesDEPRECATED @2 :List(UInt64); +} + +# ******* car controls @ 100hz ******* + +struct CarControl { + # must be true for any actuator commands to work + enabled @0 :Bool; + latActive @11: Bool; + longActive @12: Bool; + + # Final actuator commands + actuators @6 :Actuators; + + # Blinker controls + leftBlinker @15: Bool; + rightBlinker @16: Bool; + + orientationNED @13 :List(Float32); + angularVelocity @14 :List(Float32); + + cruiseControl @4 :CruiseControl; + hudControl @5 :HUDControl; + + struct Actuators { + # lateral commands, mutually exclusive + steer @2: Float32; # [0.0, 1.0] + steeringAngleDeg @3: Float32; + curvature @7: Float32; + + # longitudinal commands + accel @4: Float32; # m/s^2 + longControlState @5: LongControlState; + + # these are only for logging the actual values sent to the car over CAN + gas @0: Float32; # [0.0, 1.0] + brake @1: Float32; # [0.0, 1.0] + steerOutputCan @8: Float32; # value sent over can to the car + speed @6: Float32; # m/s + + enum LongControlState @0xe40f3a917d908282{ + off @0; + pid @1; + stopping @2; + starting @3; + } + } + + struct CruiseControl { + cancel @0: Bool; + resume @1: Bool; + override @4: Bool; + speedOverrideDEPRECATED @2: Float32; + accelOverrideDEPRECATED @3: Float32; + } + + struct HUDControl { + speedVisible @0: Bool; + setSpeed @1: Float32; + lanesVisible @2: Bool; + leadVisible @3: Bool; + visualAlert @4: VisualAlert; + audibleAlert @5: AudibleAlert; + rightLaneVisible @6: Bool; + leftLaneVisible @7: Bool; + rightLaneDepart @8: Bool; + leftLaneDepart @9: Bool; + leadDistanceBars @10: Int8; # 1-3: 1 is closest, 3 is farthest. some ports may utilize 2-4 bars instead + + enum VisualAlert { + # these are the choices from the Honda + # map as good as you can for your car + none @0; + fcw @1; + steerRequired @2; + brakePressed @3; + wrongGear @4; + seatbeltUnbuckled @5; + speedTooHigh @6; + ldw @7; + } + + enum AudibleAlert { + none @0; + + engage @1; + disengage @2; + refuse @3; + + warningSoft @4; + warningImmediate @5; + + prompt @6; + promptRepeat @7; + promptDistracted @8; + } + } + + gasDEPRECATED @1 :Float32; + brakeDEPRECATED @2 :Float32; + steeringTorqueDEPRECATED @3 :Float32; + activeDEPRECATED @7 :Bool; + rollDEPRECATED @8 :Float32; + pitchDEPRECATED @9 :Float32; + actuatorsOutputDEPRECATED @10 :Actuators; +} + +struct CarOutput { + # Any car specific rate limits or quirks applied by + # the CarController are reflected in actuatorsOutput + # and matches what is sent to the car + actuatorsOutput @0 :CarControl.Actuators; +} + +# ****** car param ****** + +struct CarParams { + carName @0 :Text; + carFingerprint @1 :Text; + fuzzyFingerprint @55 :Bool; + + notCar @66 :Bool; # flag for non-car robotics platforms + + pcmCruise @3 :Bool; # is openpilot's state tied to the PCM's cruise state? + enableDsu @5 :Bool; # driving support unit + enableBsm @56 :Bool; # blind spot monitoring + flags @64 :UInt32; # flags for car specific quirks + experimentalLongitudinalAvailable @71 :Bool; + + minEnableSpeed @7 :Float32; + minSteerSpeed @8 :Float32; + safetyConfigs @62 :List(SafetyConfig); + alternativeExperience @65 :Int16; # panda flag for features like no disengage on gas + + # Car docs fields + maxLateralAccel @68 :Float32; + autoResumeSng @69 :Bool; # describes whether car can resume from a stop automatically + + # things about the car in the manual + mass @17 :Float32; # [kg] curb weight: all fluids no cargo + wheelbase @18 :Float32; # [m] distance from rear axle to front axle + centerToFront @19 :Float32; # [m] distance from center of mass to front axle + steerRatio @20 :Float32; # [] ratio of steering wheel angle to front wheel angle + steerRatioRear @21 :Float32; # [] ratio of steering wheel angle to rear wheel angle (usually 0) + + # things we can derive + rotationalInertia @22 :Float32; # [kg*m2] body rotational inertia + tireStiffnessFactor @72 :Float32; # scaling factor used in calculating tireStiffness[Front,Rear] + tireStiffnessFront @23 :Float32; # [N/rad] front tire coeff of stiff + tireStiffnessRear @24 :Float32; # [N/rad] rear tire coeff of stiff + + longitudinalTuning @25 :LongitudinalPIDTuning; + lateralParams @48 :LateralParams; + lateralTuning :union { + pid @26 :LateralPIDTuning; + indiDEPRECATED @27 :LateralINDITuning; + lqrDEPRECATED @40 :LateralLQRTuning; + torque @67 :LateralTorqueTuning; + } + + steerLimitAlert @28 :Bool; + steerLimitTimer @47 :Float32; # time before steerLimitAlert is issued + + vEgoStopping @29 :Float32; # Speed at which the car goes into stopping state + vEgoStarting @59 :Float32; # Speed at which the car goes into starting state + steerControlType @34 :SteerControlType; + radarUnavailable @35 :Bool; # True when radar objects aren't visible on CAN or aren't parsed out + stopAccel @60 :Float32; # Required acceleration to keep vehicle stationary + stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop + startAccel @32 :Float32; # Required acceleration to get car moving + startingState @70 :Bool; # Does this car make use of special starting state + + steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds + longitudinalActuatorDelay @58 :Float32; # Gas/Brake actuator delay in seconds + 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); + + radarDelay @74 :Float32; + fingerprintSource @49: FingerprintSource; + networkLocation @50 :NetworkLocation; # Where Panda/C2 is integrated into the car's CAN network + + wheelSpeedFactor @63 :Float32; # Multiplier on wheels speeds to computer actual speeds + + secOcRequired @75 :Bool; # Car requires SecOC message authentication to operate + secOcKeyAvailable @76 :Bool; # Stored SecOC key loaded from params + + struct SafetyConfig { + safetyModel @0 :SafetyModel; + safetyParam @3 :UInt16; + safetyParamDEPRECATED @1 :Int16; + safetyParam2DEPRECATED @2 :UInt32; + } + + struct LateralParams { + torqueBP @0 :List(Int32); + torqueV @1 :List(Int32); + } + + struct LateralPIDTuning { + kpBP @0 :List(Float32); + kpV @1 :List(Float32); + kiBP @2 :List(Float32); + kiV @3 :List(Float32); + kf @4 :Float32; + } + + struct LateralTorqueTuning { + useSteeringAngle @0 :Bool; + kp @1 :Float32; + ki @2 :Float32; + friction @3 :Float32; + kf @4 :Float32; + steeringAngleDeadzoneDeg @5 :Float32; + latAccelFactor @6 :Float32; + latAccelOffset @7 :Float32; + } + + struct LongitudinalPIDTuning { + kpBP @0 :List(Float32); + kpV @1 :List(Float32); + kiBP @2 :List(Float32); + kiV @3 :List(Float32); + kf @6 :Float32; + deadzoneBPDEPRECATED @4 :List(Float32); + deadzoneVDEPRECATED @5 :List(Float32); + } + + struct LateralINDITuning { + outerLoopGainBP @4 :List(Float32); + outerLoopGainV @5 :List(Float32); + innerLoopGainBP @6 :List(Float32); + innerLoopGainV @7 :List(Float32); + timeConstantBP @8 :List(Float32); + timeConstantV @9 :List(Float32); + actuatorEffectivenessBP @10 :List(Float32); + actuatorEffectivenessV @11 :List(Float32); + + outerLoopGainDEPRECATED @0 :Float32; + innerLoopGainDEPRECATED @1 :Float32; + timeConstantDEPRECATED @2 :Float32; + actuatorEffectivenessDEPRECATED @3 :Float32; + } + + struct LateralLQRTuning { + scale @0 :Float32; + ki @1 :Float32; + dcGain @2 :Float32; + + # State space system + a @3 :List(Float32); + b @4 :List(Float32); + c @5 :List(Float32); + + k @6 :List(Float32); # LQR gain + l @7 :List(Float32); # Kalman gain + } + + enum SafetyModel { + silent @0; + hondaNidec @1; + toyota @2; + elm327 @3; + gm @4; + hondaBoschGiraffe @5; + ford @6; + cadillac @7; + hyundai @8; + chrysler @9; + tesla @10; + subaru @11; + gmPassive @12; + mazda @13; + nissan @14; + volkswagen @15; + toyotaIpas @16; + allOutput @17; + gmAscm @18; + noOutput @19; # like silent but without silent CAN TXs + hondaBosch @20; + volkswagenPq @21; + subaruPreglobal @22; # pre-Global platform + hyundaiLegacy @23; + hyundaiCommunity @24; + volkswagenMlb @25; + hongqi @26; + body @27; + hyundaiCanfd @28; + volkswagenMqbEvo @29; + chryslerCusw @30; + psa @31; + fcaGiorgio @32; + } + + enum SteerControlType { + torque @0; + angle @1; + + curvatureDEPRECATED @2; + } + + enum TransmissionType { + unknown @0; + automatic @1; # Traditional auto, including DSG + manual @2; # True "stick shift" only + direct @3; # Electric vehicle or other direct drive + cvt @4; + } + + struct CarFw { + ecu @0 :Ecu; + fwVersion @1 :Data; + address @2 :UInt32; + subAddress @3 :UInt8; + responseAddress @4 :UInt32; + request @5 :List(Data); + brand @6 :Text; + bus @7 :UInt8; + logging @8 :Bool; + obdMultiplexing @9 :Bool; + } + + enum Ecu { + eps @0; + abs @1; + fwdRadar @2; + fwdCamera @3; + engine @4; + unknown @5; + transmission @8; # Transmission Control Module + hybrid @18; # hybrid control unit, e.g. Chrysler's HCP, Honda's IMA Control Unit, Toyota's hybrid control computer + srs @9; # airbag + gateway @10; # can gateway + hud @11; # heads up display + combinationMeter @12; # instrument cluster + electricBrakeBooster @15; + shiftByWire @16; + adas @19; + cornerRadar @21; + hvac @20; + parkingAdas @7; # parking assist system ECU, e.g. Toyota's IPAS, Hyundai's RSPA, etc. + epb @22; # electronic parking brake + telematics @23; + body @24; # body control module + + # Toyota only + dsu @6; + + # Honda only + vsa @13; # Vehicle Stability Assist + programmedFuelInjection @14; + + debug @17; + } + + enum FingerprintSource { + can @0; + fw @1; + fixed @2; + } + + enum NetworkLocation { + fwdCamera @0; # Standard/default integration at LKAS camera + gateway @1; # Integration at vehicle's CAN gateway + } + + enableGasInterceptorDEPRECATED @2 :Bool; + enableCameraDEPRECATED @4 :Bool; + enableApgsDEPRECATED @6 :Bool; + steerRateCostDEPRECATED @33 :Float32; + isPandaBlackDEPRECATED @39 :Bool; + hasStockCameraDEPRECATED @57 :Bool; + safetyParamDEPRECATED @10 :Int16; + safetyModelDEPRECATED @9 :SafetyModel; + safetyModelPassiveDEPRECATED @42 :SafetyModel = silent; + minSpeedCanDEPRECATED @51 :Float32; + communityFeatureDEPRECATED @46: Bool; + startingAccelRateDEPRECATED @53 :Float32; + steerMaxBPDEPRECATED @11 :List(Float32); + steerMaxVDEPRECATED @12 :List(Float32); + gasMaxBPDEPRECATED @13 :List(Float32); + gasMaxVDEPRECATED @14 :List(Float32); + brakeMaxBPDEPRECATED @15 :List(Float32); + brakeMaxVDEPRECATED @16 :List(Float32); + directAccelControlDEPRECATED @30 :Bool; + maxSteeringAngleDegDEPRECATED @54 :Float32; + longitudinalActuatorDelayLowerBoundDEPRECATED @61 :Float32; + stoppingControlDEPRECATED @31 :Bool; # Does the car allow full control even at lows speeds when stopping + radarTimeStepDEPRECATED @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard +} diff --git a/opendbc_repo/opendbc/car/car_helpers.py b/opendbc_repo/opendbc/car/car_helpers.py new file mode 100644 index 000000000000000..fb51515f6ba8913 --- /dev/null +++ b/opendbc_repo/opendbc/car/car_helpers.py @@ -0,0 +1,184 @@ +import os +import time + +from opendbc.car import carlog, gen_empty_fingerprint +from opendbc.car.can_definitions import CanRecvCallable, CanSendCallable +from opendbc.car.structs import CarParams, CarParamsT +from opendbc.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars +from opendbc.car.fw_versions import ObdCallback, get_fw_versions_ordered, get_present_ecus, match_fw_to_car +from opendbc.car.interfaces import get_interface_attr +from opendbc.car.mock.values import CAR as MOCK +from opendbc.car.vin import get_vin, is_valid_vin, VIN_UNKNOWN + +FRAME_FINGERPRINT = 100 # 1s + + +def load_interfaces(brand_names): + ret = {} + for brand_name in brand_names: + path = f'opendbc.car.{brand_name}' + CarInterface = __import__(path + '.interface', fromlist=['CarInterface']).CarInterface + CarState = __import__(path + '.carstate', fromlist=['CarState']).CarState + CarController = __import__(path + '.carcontroller', fromlist=['CarController']).CarController + RadarInterface = __import__(path + '.radar_interface', fromlist=['RadarInterface']).RadarInterface + for model_name in brand_names[brand_name]: + ret[model_name] = (CarInterface, CarController, CarState, RadarInterface) + return ret + + +def _get_interface_names() -> dict[str, list[str]]: + # returns a dict of brand name and its respective models + brand_names = {} + for brand_name, brand_models in get_interface_attr("CAR").items(): + brand_names[brand_name] = [model.value for model in brand_models] + + return brand_names + + +# imports from directory opendbc/car// +interface_names = _get_interface_names() +interfaces = load_interfaces(interface_names) + + +def can_fingerprint(can_recv: CanRecvCallable) -> tuple[str | None, dict[int, dict]]: + finger = gen_empty_fingerprint() + candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1 + frame = 0 + car_fingerprint = None + done = False + + while not done: + # can_recv(wait_for_one=True) may return zero or multiple packets, so we increment frame for each one we receive + can_packets = can_recv(wait_for_one=True) + for can_packet in can_packets: + for can in can_packet: + # The fingerprint dict is generated for all buses, this way the car interface + # can use it to detect a (valid) multipanda setup and initialize accordingly + if can.src < 128: + if can.src not in finger: + finger[can.src] = {} + finger[can.src][can.address] = len(can.dat) + + for b in candidate_cars: + # Ignore extended messages and VIN query response. + if can.src == b and can.address < 0x800 and can.address not in (0x7df, 0x7e0, 0x7e8): + candidate_cars[b] = eliminate_incompatible_cars(can, candidate_cars[b]) + + # if we only have one car choice and the time since we got our first + # message has elapsed, exit + for b in candidate_cars: + if len(candidate_cars[b]) == 1 and frame > FRAME_FINGERPRINT: + # fingerprint done + car_fingerprint = candidate_cars[b][0] + + # bail if no cars left or we've been waiting for more than 2s + failed = (all(len(cc) == 0 for cc in candidate_cars.values()) and frame > FRAME_FINGERPRINT) or frame > 200 + succeeded = car_fingerprint is not None + done = failed or succeeded + + frame += 1 + + return car_fingerprint, finger + + +# **** for use live only **** +def fingerprint(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, num_pandas: int, + cached_params: CarParamsT | None) -> tuple[str | None, dict, str, list[CarParams.CarFw], CarParams.FingerprintSource, bool]: + fixed_fingerprint = os.environ.get('FINGERPRINT', "") + skip_fw_query = os.environ.get('SKIP_FW_QUERY', False) + disable_fw_cache = os.environ.get('DISABLE_FW_CACHE', False) + ecu_rx_addrs = set() + + start_time = time.monotonic() + if not skip_fw_query: + if cached_params is not None and cached_params.carName != "mock" and len(cached_params.carFw) > 0 and \ + cached_params.carVin is not VIN_UNKNOWN and not disable_fw_cache: + carlog.warning("Using cached CarParams") + vin_rx_addr, vin_rx_bus, vin = -1, -1, cached_params.carVin + car_fw = list(cached_params.carFw) + cached = True + else: + carlog.warning("Getting VIN & FW versions") + # enable OBD multiplexing for VIN query + # NOTE: this takes ~0.1s and is relied on to allow sendcan subscriber to connect in time + set_obd_multiplexing(True) + # VIN query only reliably works through OBDII + vin_rx_addr, vin_rx_bus, vin = get_vin(can_recv, can_send, (0, 1)) + ecu_rx_addrs = get_present_ecus(can_recv, can_send, set_obd_multiplexing, num_pandas=num_pandas) + car_fw = get_fw_versions_ordered(can_recv, can_send, set_obd_multiplexing, vin, ecu_rx_addrs, num_pandas=num_pandas) + cached = False + + exact_fw_match, fw_candidates = match_fw_to_car(car_fw, vin) + else: + vin_rx_addr, vin_rx_bus, vin = -1, -1, VIN_UNKNOWN + exact_fw_match, fw_candidates, car_fw = True, set(), [] + cached = False + + if not is_valid_vin(vin): + carlog.error({"event": "Malformed VIN", "vin": vin}) + vin = VIN_UNKNOWN + carlog.warning("VIN %s", vin) + + # disable OBD multiplexing for CAN fingerprinting and potential ECU knockouts + set_obd_multiplexing(False) + + fw_query_time = time.monotonic() - start_time + + # CAN fingerprint + # drain CAN socket so we get the latest messages + can_recv() + car_fingerprint, finger = can_fingerprint(can_recv) + + exact_match = True + source = CarParams.FingerprintSource.can + + # If FW query returns exactly 1 candidate, use it + if len(fw_candidates) == 1: + car_fingerprint = list(fw_candidates)[0] + source = CarParams.FingerprintSource.fw + exact_match = exact_fw_match + + if fixed_fingerprint: + car_fingerprint = fixed_fingerprint + source = CarParams.FingerprintSource.fixed + + carlog.error({"event": "fingerprinted", "car_fingerprint": str(car_fingerprint), "source": source, "fuzzy": not exact_match, + "cached": cached, "fw_count": len(car_fw), "ecu_responses": list(ecu_rx_addrs), "vin_rx_addr": vin_rx_addr, + "vin_rx_bus": vin_rx_bus, "fingerprints": repr(finger), "fw_query_time": fw_query_time}) + + return car_fingerprint, finger, vin, car_fw, source, exact_match + + +def get_car_interface(CP: CarParams): + CarInterface, CarController, CarState, _ = interfaces[CP.carFingerprint] + return CarInterface(CP, CarController, CarState) + + +def get_radar_interface(CP: CarParams): + _, _, _, RadarInterface = interfaces[CP.carFingerprint] + return RadarInterface(CP) + + +def get_car(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, experimental_long_allowed: bool, + num_pandas: int = 1, cached_params: CarParamsT | None = None): + candidate, fingerprints, vin, car_fw, source, exact_match = fingerprint(can_recv, can_send, set_obd_multiplexing, num_pandas, cached_params) + + if candidate is None: + carlog.error({"event": "car doesn't match any fingerprints", "fingerprints": repr(fingerprints)}) + candidate = "MOCK" + + CarInterface, _, _, _ = interfaces[candidate] + CP: CarParams = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed, docs=False) + CP.carVin = vin + CP.carFw = car_fw + CP.fingerprintSource = source + CP.fuzzyFingerprint = not exact_match + + return get_car_interface(CP) + + +def get_demo_car_params(): + platform = MOCK.MOCK + CarInterface, _, _, _ = interfaces[platform] + CP = CarInterface.get_non_essential_params(platform) + return CP diff --git a/selfdrive/car/chrysler/__init__.py b/opendbc_repo/opendbc/car/chrysler/__init__.py similarity index 100% rename from selfdrive/car/chrysler/__init__.py rename to opendbc_repo/opendbc/car/chrysler/__init__.py diff --git a/opendbc_repo/opendbc/car/chrysler/carcontroller.py b/opendbc_repo/opendbc/car/chrysler/carcontroller.py new file mode 100644 index 000000000000000..fbdb79aa14b7416 --- /dev/null +++ b/opendbc_repo/opendbc/car/chrysler/carcontroller.py @@ -0,0 +1,83 @@ +from opendbc.can.packer import CANPacker +from opendbc.car import DT_CTRL, apply_meas_steer_torque_limits +from opendbc.car.chrysler import chryslercan +from opendbc.car.chrysler.values import RAM_CARS, CarControllerParams, ChryslerFlags +from opendbc.car.interfaces import CarControllerBase + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.apply_steer_last = 0 + + self.hud_count = 0 + self.last_lkas_falling_edge = 0 + self.lkas_control_bit_prev = False + self.last_button_frame = 0 + + self.packer = CANPacker(dbc_name) + self.params = CarControllerParams(CP) + + def update(self, CC, CS, now_nanos): + can_sends = [] + + lkas_active = CC.latActive and self.lkas_control_bit_prev + + # cruise buttons + if (self.frame - self.last_button_frame)*DT_CTRL > 0.05: + das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 + + # ACC cancellation + if CC.cruiseControl.cancel: + self.last_button_frame = self.frame + can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True)) + + # ACC resume from standstill + elif CC.cruiseControl.resume: + self.last_button_frame = self.frame + can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True)) + + # HUD alerts + if self.frame % 25 == 0: + if CS.lkas_car_model != -1: + can_sends.append(chryslercan.create_lkas_hud(self.packer, self.CP, lkas_active, CC.hudControl.visualAlert, + self.hud_count, CS.lkas_car_model, CS.auto_high_beam)) + self.hud_count += 1 + + # steering + if self.frame % self.params.STEER_STEP == 0: + + # TODO: can we make this more sane? why is it different for all the cars? + lkas_control_bit = self.lkas_control_bit_prev + if CS.out.vEgo > self.CP.minSteerSpeed: + lkas_control_bit = True + elif self.CP.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: + if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): + lkas_control_bit = False + elif self.CP.carFingerprint in RAM_CARS: + if CS.out.vEgo < (self.CP.minSteerSpeed - 0.5): + lkas_control_bit = False + + # EPS faults if LKAS re-enables too quickly + lkas_control_bit = lkas_control_bit and (self.frame - self.last_lkas_falling_edge > 200) + + if not lkas_control_bit and self.lkas_control_bit_prev: + self.last_lkas_falling_edge = self.frame + self.lkas_control_bit_prev = lkas_control_bit + + # steer torque + new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX)) + apply_steer = apply_meas_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) + if not lkas_active or not lkas_control_bit: + apply_steer = 0 + self.apply_steer_last = apply_steer + + can_sends.append(chryslercan.create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_control_bit)) + + self.frame += 1 + + new_actuators = CC.actuators.as_builder() + new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX + new_actuators.steerOutputCan = self.apply_steer_last + + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/chrysler/carstate.py b/opendbc_repo/opendbc/car/chrysler/carstate.py new file mode 100644 index 000000000000000..ab37008204d1ae5 --- /dev/null +++ b/opendbc_repo/opendbc/car/chrysler/carstate.py @@ -0,0 +1,159 @@ +from opendbc.can.parser import CANParser +from opendbc.can.can_define import CANDefine +from opendbc.car import create_button_events, structs +from opendbc.car.chrysler.values import DBC, STEER_THRESHOLD, RAM_CARS +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.interfaces import CarStateBase + +ButtonType = structs.CarState.ButtonEvent.Type + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + self.CP = CP + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + self.auto_high_beam = 0 + self.button_counter = 0 + self.lkas_car_model = -1 + + if CP.carFingerprint in RAM_CARS: + self.shifter_values = can_define.dv["Transmission_Status"]["Gear_State"] + else: + self.shifter_values = can_define.dv["GEAR"]["PRNDL"] + + self.distance_button = 0 + + def update(self, cp, cp_cam, *_) -> structs.CarState: + + ret = structs.CarState() + + prev_distance_button = self.distance_button + self.distance_button = cp.vl["CRUISE_BUTTONS"]["ACC_Distance_Dec"] + + # lock info + ret.doorOpen = any([cp.vl["BCM_1"]["DOOR_OPEN_FL"], + cp.vl["BCM_1"]["DOOR_OPEN_FR"], + cp.vl["BCM_1"]["DOOR_OPEN_RL"], + cp.vl["BCM_1"]["DOOR_OPEN_RR"]]) + ret.seatbeltUnlatched = cp.vl["ORC_1"]["SEATBELT_DRIVER_UNLATCHED"] == 1 + + # brake pedal + ret.brake = 0 + ret.brakePressed = cp.vl["ESP_1"]['Brake_Pedal_State'] == 1 # Physical brake pedal switch + + # gas pedal + ret.gas = cp.vl["ECM_5"]["Accelerator_Position"] + ret.gasPressed = ret.gas > 1e-5 + + # car speed + if self.CP.carFingerprint in RAM_CARS: + ret.vEgoRaw = cp.vl["ESP_8"]["Vehicle_Speed"] * CV.KPH_TO_MS + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["Transmission_Status"]["Gear_State"], None)) + else: + ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2. + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = not ret.vEgoRaw > 0.001 + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["ESP_6"]["WHEEL_SPEED_FL"], + cp.vl["ESP_6"]["WHEEL_SPEED_FR"], + cp.vl["ESP_6"]["WHEEL_SPEED_RL"], + cp.vl["ESP_6"]["WHEEL_SPEED_RR"], + unit=1, + ) + + # button presses + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(200, cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1, + cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2) + ret.genericToggle = cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"] == 1 + + # steering wheel + ret.steeringAngleDeg = cp.vl["STEERING"]["STEERING_ANGLE"] + cp.vl["STEERING"]["STEERING_ANGLE_HP"] + ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] + ret.steeringTorque = cp.vl["EPS_2"]["COLUMN_TORQUE"] + ret.steeringTorqueEps = cp.vl["EPS_2"]["EPS_TORQUE_MOTOR"] + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + + # cruise state + cp_cruise = cp_cam if self.CP.carFingerprint in RAM_CARS else cp + + ret.cruiseState.available = cp_cruise.vl["DAS_3"]["ACC_AVAILABLE"] == 1 + ret.cruiseState.enabled = cp_cruise.vl["DAS_3"]["ACC_ACTIVE"] == 1 + ret.cruiseState.speed = cp_cruise.vl["DAS_4"]["ACC_SET_SPEED_KPH"] * CV.KPH_TO_MS + ret.cruiseState.nonAdaptive = cp_cruise.vl["DAS_4"]["ACC_STATE"] in (1, 2) # 1 NormalCCOn and 2 NormalCCSet + ret.cruiseState.standstill = cp_cruise.vl["DAS_3"]["ACC_STANDSTILL"] == 1 + ret.accFaulted = cp_cruise.vl["DAS_3"]["ACC_FAULTED"] != 0 + + if self.CP.carFingerprint in RAM_CARS: + # Auto High Beam isn't Located in this message on chrysler or jeep currently located in 729 message + self.auto_high_beam = cp_cam.vl["DAS_6"]['AUTO_HIGH_BEAM_ON'] + ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1 + else: + ret.steerFaultTemporary = cp.vl["EPS_2"]["LKAS_TEMPORARY_FAULT"] == 1 + ret.steerFaultPermanent = cp.vl["EPS_2"]["LKAS_STATE"] == 4 + + # blindspot sensors + if self.CP.enableBsm: + ret.leftBlindspot = cp.vl["BSM_1"]["LEFT_STATUS"] == 1 + ret.rightBlindspot = cp.vl["BSM_1"]["RIGHT_STATUS"] == 1 + + self.lkas_car_model = cp_cam.vl["DAS_6"]["CAR_MODEL"] + self.button_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] + + ret.buttonEvents = create_button_events(self.distance_button, prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + return ret + + @staticmethod + def get_cruise_messages(): + messages = [ + ("DAS_3", 50), + ("DAS_4", 50), + ] + return messages + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("ESP_1", 50), + ("EPS_2", 100), + ("ESP_6", 50), + ("STEERING", 100), + ("ECM_5", 50), + ("CRUISE_BUTTONS", 50), + ("STEERING_LEVERS", 10), + ("ORC_1", 2), + ("BCM_1", 1), + ] + + if CP.enableBsm: + messages.append(("BSM_1", 2)) + + if CP.carFingerprint in RAM_CARS: + messages += [ + ("ESP_8", 50), + ("EPS_3", 50), + ("Transmission_Status", 50), + ] + else: + messages += [ + ("GEAR", 50), + ("SPEED_1", 100), + ] + messages += CarState.get_cruise_messages() + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_cam_can_parser(CP): + messages = [ + ("DAS_6", 4), + ] + + if CP.carFingerprint in RAM_CARS: + messages += CarState.get_cruise_messages() + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/chrysler/chryslercan.py b/opendbc_repo/opendbc/car/chrysler/chryslercan.py similarity index 90% rename from selfdrive/car/chrysler/chryslercan.py rename to opendbc_repo/opendbc/car/chrysler/chryslercan.py index 96439f35d8cf2a4..8a0755ac5d6945b 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/opendbc_repo/opendbc/car/chrysler/chryslercan.py @@ -1,8 +1,8 @@ -from cereal import car -from openpilot.selfdrive.car.chrysler.values import RAM_CARS +from opendbc.car import structs +from opendbc.car.chrysler.values import RAM_CARS -GearShifter = car.CarState.GearShifter -VisualAlert = car.CarControl.HUDControl.VisualAlert +GearShifter = structs.CarState.GearShifter +VisualAlert = structs.CarControl.HUDControl.VisualAlert def create_lkas_hud(packer, CP, lkas_active, hud_alert, hud_count, car_model, auto_high_beam): # LKAS_HUD - Controls what lane-keeping icon is displayed diff --git a/opendbc_repo/opendbc/car/chrysler/fingerprints.py b/opendbc_repo/opendbc/car/chrysler/fingerprints.py new file mode 100644 index 000000000000000..9748069e5ffe20d --- /dev/null +++ b/opendbc_repo/opendbc/car/chrysler/fingerprints.py @@ -0,0 +1,735 @@ +from opendbc.car.structs import CarParams +from opendbc.car.chrysler.values import CAR + +Ecu = CarParams.Ecu + +FW_VERSIONS = { + CAR.CHRYSLER_PACIFICA_2018: { + (Ecu.combinationMeter, 0x742, None): [ + b'68227902AF', + b'68227902AG', + b'68227902AH', + b'68227905AG', + b'68360252AC', + ], + (Ecu.srs, 0x744, None): [ + b'68211617AF', + b'68211617AG', + b'68358974AC', + b'68405937AA', + ], + (Ecu.abs, 0x747, None): [ + b'68222747AG', + b'68330876AA', + b'68330876AB', + b'68352227AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + b'04672758AB', + b'68226356AF', + b'68226356AH', + b'68226356AI', + ], + (Ecu.eps, 0x75a, None): [ + b'68288891AE', + b'68378884AA', + b'68525338AA', + b'68525338AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68267018AO ', + b'68267020AJ ', + b'68303534AG ', + b'68303534AJ ', + b'68340762AD ', + b'68340764AD ', + b'68352652AE ', + b'68352654AE ', + b'68366851AH ', + b'68366853AE ', + b'68366853AG ', + b'68372861AF ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'68277370AJ', + b'68277370AM', + b'68277372AD', + b'68277372AE', + b'68277372AN', + b'68277374AA', + b'68277374AB', + b'68277374AD', + b'68277374AN', + b'68367471AC', + b'68367471AD', + b'68380571AB', + ], + }, + CAR.CHRYSLER_PACIFICA_2020: { + (Ecu.combinationMeter, 0x742, None): [ + b'68405327AC', + b'68436233AB', + b'68436233AC', + b'68436234AB', + b'68436250AE', + b'68529067AA', + b'68594993AB', + b'68594994AB', + ], + (Ecu.srs, 0x744, None): [ + b'68405565AB', + b'68405565AC', + b'68444299AC', + b'68480707AC', + b'68480708AC', + b'68526663AB', + ], + (Ecu.abs, 0x747, None): [ + b'68397394AA', + b'68433480AB', + b'68453575AF', + b'68577676AA', + b'68593395AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + b'04672758AB', + b'68417813AF', + b'68540436AA', + b'68540436AC', + b'68540436AD', + b'68598670AB', + b'68598670AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68416742AA', + b'68460393AA', + b'68460393AB', + b'68494461AB', + b'68494461AC', + b'68524936AA', + b'68524936AB', + b'68525338AB', + b'68594337AB', + b'68594340AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68413871AD ', + b'68413871AE ', + b'68413871AH ', + b'68413871AI ', + b'68413873AH ', + b'68413873AI ', + b'68443120AE ', + b'68443123AC ', + b'68443125AC ', + b'68496647AI ', + b'68496647AJ ', + b'68496650AH ', + b'68496650AI ', + b'68496652AH ', + b'68526752AD ', + b'68526752AE ', + b'68526754AD ', + b'68526754AE ', + b'68536264AE ', + b'68700304AB ', + b'68700306AB ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'68414271AC', + b'68414271AD', + b'68414275AC', + b'68414275AD', + b'68443154AB', + b'68443155AC', + b'68443158AB', + b'68501050AD', + b'68501051AD', + b'68501055AD', + b'68527221AB', + b'68527223AB', + b'68586231AD', + b'68586233AD', + ], + }, + CAR.CHRYSLER_PACIFICA_2018_HYBRID: { + (Ecu.combinationMeter, 0x742, None): [ + b'68239262AH', + b'68239262AI', + b'68239262AJ', + b'68239263AH', + b'68239263AJ', + b'68358439AE', + b'68358439AG', + ], + (Ecu.srs, 0x744, None): [ + b'68238840AH', + b'68358990AC', + b'68405939AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + b'68226356AI', + ], + (Ecu.eps, 0x75a, None): [ + b'68288309AC', + b'68288309AD', + b'68525339AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'68277480AV ', + b'68277480AX ', + b'68277480AZ ', + b'68366580AI ', + b'68366580AK ', + b'68366580AM ', + ], + (Ecu.hybrid, 0x7e2, None): [ + b'05190175BF', + b'05190175BH', + b'05190226AI', + b'05190226AK', + b'05190226AM', + ], + }, + CAR.CHRYSLER_PACIFICA_2019_HYBRID: { + (Ecu.combinationMeter, 0x742, None): [ + b'68405292AC', + b'68434956AC', + b'68434956AD', + b'68434960AE', + b'68434960AF', + b'68529064AB', + b'68594990AB', + ], + (Ecu.srs, 0x744, None): [ + b'68405567AB', + b'68405567AC', + b'68453076AD', + b'68480710AC', + b'68526665AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AB', + b'68417813AF', + b'68540436AA', + b'68540436AB', + b'68540436AC', + b'68540436AD', + b'68598670AB', + b'68598670AC', + b'68645752AA', + ], + (Ecu.eps, 0x75a, None): [ + b'68416741AA', + b'68460392AA', + b'68525339AA', + b'68525339AB', + b'68594341AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68416680AE ', + b'68416680AF ', + b'68416680AG ', + b'68444228AC ', + b'68444228AD ', + b'68444228AE ', + b'68444228AF ', + b'68499122AD ', + b'68499122AE ', + b'68499122AF ', + b'68526772AD ', + b'68526772AH ', + b'68599493AC ', + b'68657433AA ', + ], + (Ecu.hybrid, 0x7e2, None): [ + b'05185116AF', + b'05185116AJ', + b'05185116AK', + b'05190240AP', + b'05190240AQ', + b'05190240AR', + b'05190265AG', + b'05190265AH', + b'05190289AE', + b'68540977AH', + b'68540977AK', + b'68597647AE', + b'68597647AF', + b'68632416AB', + ], + }, + CAR.JEEP_GRAND_CHEROKEE: { + (Ecu.combinationMeter, 0x742, None): [ + b'68243549AG', + b'68302211AC', + b'68302212AD', + b'68302223AC', + b'68302246AC', + b'68331511AC', + b'68331574AC', + b'68331687AC', + b'68331690AC', + b'68340272AD', + ], + (Ecu.srs, 0x744, None): [ + b'68309533AA', + b'68316742AB', + b'68355363AB', + ], + (Ecu.abs, 0x747, None): [ + b'68252642AG', + b'68306178AD', + b'68336275AB', + b'68336276AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672627AB', + b'68251506AF', + b'68332015AB', + ], + (Ecu.eps, 0x75a, None): [ + b'68276201AG', + b'68321644AB', + b'68321644AC', + b'68321646AC', + b'68321648AC', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035920AE ', + b'68252272AG ', + b'68284455AI ', + b'68284456AI ', + b'68284456AJ ', + b'68284477AF ', + b'68325564AH ', + b'68325564AI ', + b'68325565AH ', + b'68325565AI ', + b'68325565AJ ', + b'68325618AD ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035517AH', + b'68253222AF', + b'68311218AC', + b'68311218AD', + 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'68402707AB', + b'68402708AB', + b'68402714AB', + b'68402971AD', + b'68454144AD', + b'68454145AB', + b'68454152AB', + b'68454156AB', + b'68516650AB', + b'68516651AB', + b'68516669AB', + b'68516671AB', + b'68516683AB', + ], + (Ecu.srs, 0x744, None): [ + b'68355363AB', + b'68355364AB', + ], + (Ecu.abs, 0x747, None): [ + b'68408639AC', + b'68408639AD', + b'68499978AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672788AA', + b'68456722AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68417279AA', + b'68417280AA', + b'68417281AA', + b'68453431AA', + b'68453433AA', + b'68453435AA', + b'68499171AA', + b'68499171AB', + b'68501183AA', + b'68501186AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035674AB ', + b'68412635AE ', + b'68412635AG ', + b'68412660AD ', + b'68422860AB', + b'68449435AE ', + b'68496223AA ', + b'68504959AD ', + b'68504959AE ', + b'68504960AD ', + b'68504993AC ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035707AA', + b'68419672AC', + b'68419678AB', + b'68423905AB', + b'68449258AC', + b'68495807AA', + b'68495807AB', + b'68503641AC', + b'68503644AC', + b'68503664AC', + ], + }, + CAR.RAM_1500_5TH_GEN: { + (Ecu.combinationMeter, 0x742, None): [ + b'68294051AG', + b'68294051AI', + b'68294052AG', + b'68294052AH', + b'68294059AI', + b'68294063AG', + b'68294063AH', + b'68294063AI', + b'68434846AC', + b'68434847AC', + b'68434849AC', + b'68434856AC', + b'68434858AC', + b'68434859AC', + b'68434860AC', + b'68453471AD', + b'68453483AC', + b'68453483AD', + b'68453487AD', + b'68453491AC', + b'68453491AD', + b'68453499AD', + b'68453503AC', + b'68453503AD', + b'68453505AC', + b'68453505AD', + b'68453511AC', + b'68453513AC', + b'68453513AD', + b'68453514AD', + b'68505633AB', + b'68510277AG', + b'68510277AH', + b'68510280AG', + b'68510282AG', + b'68510282AH', + b'68510283AG', + b'68527346AE', + b'68527361AD', + b'68527375AD', + b'68527381AD', + b'68527381AE', + b'68527382AE', + b'68527383AD', + b'68527383AE', + b'68527387AE', + b'68527397AD', + b'68527403AC', + b'68527403AD', + b'68527404AD', + b'68546047AF', + b'68631938AA', + b'68631939AA', + b'68631940AA', + b'68631940AB', + b'68631942AA', + b'68631943AB', + ], + (Ecu.srs, 0x744, None): [ + b'68428609AB', + b'68441329AB', + b'68473844AB', + b'68490898AA', + b'68500728AA', + b'68615033AA', + b'68615034AA', + ], + (Ecu.abs, 0x747, None): [ + b'68292406AG', + b'68292406AH', + b'68432418AB', + b'68432418AC', + b'68432418AD', + b'68436004AD', + b'68436004AE', + b'68438454AC', + b'68438454AD', + b'68438456AE', + b'68438456AF', + b'68535469AB', + b'68535470AC', + b'68548900AB', + b'68548900AC', + b'68586307AB', + b'68586307AC', + ], + (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'22490101AB', + b'68273275AF', + b'68273275AG', + b'68273275AH', + b'68312176AE', + b'68312176AF', + b'68312176AG', + b'68440789AC', + b'68466110AA', + b'68466110AB', + b'68466113AA', + b'68469901AA', + b'68469907AA', + b'68522583AA', + b'68522583AB', + b'68522584AA', + b'68522585AB', + b'68552788AA', + b'68552789AA', + b'68552790AA', + b'68552791AB', + b'68552794AA', + b'68552794AD', + b'68585106AB', + b'68585107AB', + b'68585108AB', + b'68585109AB', + b'68585112AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035699AG ', + b'05035841AC ', + b'05035841AD ', + b'05036026AB ', + b'05036030AC ', + b'05036065AE ', + b'05036066AE ', + b'05036067AE ', + b'05036193AA ', + b'05149368AA ', + b'05149374AA ', + b'05149591AD ', + b'05149591AE ', + b'05149592AE ', + b'05149599AE ', + b'05149600AD ', + b'05149600AE ', + b'05149605AE ', + b'05149846AA ', + b'05149848AA ', + b'05149848AC ', + b'05190341AD', + b'68378695AJ ', + b'68378696AJ ', + b'68378696AK ', + b'68378701AI ', + b'68378702AI ', + b'68378710AL ', + b'68378742AI ', + b'68378742AK ', + b'68378743AI ', + b'68378743AM ', + b'68378748AL ', + b'68378758AM ', + b'68448163AJ', + b'68448163AK', + b'68448163AL', + b'68448165AG', + b'68448165AK', + b'68455111AC ', + b'68455119AC ', + b'68455145AC ', + b'68455145AE ', + b'68455146AC ', + b'68460927AA ', + b'68467909AB ', + b'68467915AC ', + b'68467916AC ', + b'68467936AC ', + b'68500630AD', + b'68500630AE', + b'68500631AE', + b'68502719AC ', + b'68502722AC ', + b'68502733AC ', + b'68502734AF ', + b'68502740AF ', + b'68502741AF ', + b'68502742AC ', + b'68502742AF ', + b'68539650AD', + b'68539650AF', + b'68539651AD', + b'68586101AA ', + b'68586102AA ', + b'68586105AB ', + b'68629919AC ', + b'68629922AC ', + b'68629925AC ', + b'68629926AC ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035706AD', + b'05035842AB', + b'05036069AA', + b'05036181AA', + b'05149536AC', + b'05149537AC', + b'05149543AC', + b'68360078AL', + b'68360080AL', + b'68360080AM', + b'68360081AM', + b'68360085AJ', + b'68360085AL', + b'68360085AO', + b'68360086AH', + b'68360086AK', + b'68360086AN', + b'68384328AD', + b'68384332AD', + b'68445531AC', + b'68445533AB', + b'68445536AB', + b'68445537AB', + b'68466081AB', + b'68466086AB', + b'68466087AB', + b'68484466AC', + b'68484467AC', + b'68484471AC', + b'68502994AD', + b'68502996AD', + b'68520867AE', + b'68520867AF', + b'68520870AC', + b'68520871AC', + b'68528325AE', + b'68540431AB', + b'68540433AB', + b'68551676AA', + b'68629935AB', + b'68629936AC', + ], + }, + CAR.RAM_HD_5TH_GEN: { + (Ecu.combinationMeter, 0x742, None): [ + b'68361606AH', + b'68437735AC', + b'68492693AD', + b'68525485AB', + b'68525487AB', + b'68525498AB', + b'68528791AF', + b'68628474AB', + ], + (Ecu.srs, 0x744, None): [ + b'68399794AC', + b'68428503AA', + b'68428505AA', + b'68428507AA', + ], + (Ecu.abs, 0x747, None): [ + b'68334977AH', + b'68455481AC', + b'68504022AA', + b'68504022AB', + b'68504022AC', + b'68530686AB', + b'68530686AC', + b'68544596AC', + b'68641704AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672895AB', + b'04672934AB', + b'56029827AG', + b'56029827AH', + b'68462657AE', + b'68484694AD', + b'68484694AE', + b'68615489AB', + ], + (Ecu.eps, 0x761, None): [ + b'68421036AC', + b'68507906AB', + b'68534023AC', + ], + (Ecu.engine, 0x7e0, None): [ + b'52370131AF', + b'52370231AF', + b'52370231AG', + b'52370491AA', + b'52370931CT', + b'52401032AE', + b'52421132AF', + b'52421332AF', + b'68527616AD ', + b'M2370131MB', + b'M2421132MB', + ], + }, + CAR.DODGE_DURANGO: { + (Ecu.combinationMeter, 0x742, None): [ + b'68454261AD', + b'68471535AE', + ], + (Ecu.srs, 0x744, None): [ + b'68355362AB', + b'68492238AD', + ], + (Ecu.abs, 0x747, None): [ + b'68408639AD', + b'68499978AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'68440581AE', + b'68456722AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68453435AA', + b'68498477AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035786AE ', + b'68449476AE ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035826AC', + b'68449265AC', + ], + }, +} diff --git a/opendbc_repo/opendbc/car/chrysler/interface.py b/opendbc_repo/opendbc/car/chrysler/interface.py new file mode 100755 index 000000000000000..a5c7f5bd2ca0e93 --- /dev/null +++ b/opendbc_repo/opendbc/car/chrysler/interface.py @@ -0,0 +1,74 @@ +#!/usr/bin/env python3 +from panda import Panda +from opendbc.car import get_safety_config, structs +from opendbc.car.chrysler.values import CAR, RAM_HD, RAM_DT, RAM_CARS, ChryslerFlags +from opendbc.car.interfaces import CarInterfaceBase + + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "chrysler" + ret.dashcamOnly = candidate in RAM_HD + + # radar parsing needs some work, see https://github.com/commaai/openpilot/issues/26842 + ret.radarUnavailable = True # DBC[candidate]['radar'] is None + ret.steerActuatorDelay = 0.1 + ret.steerLimitTimer = 0.4 + + # safety config + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.chrysler)] + if candidate in RAM_HD: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_HD + elif candidate in RAM_DT: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_DT + + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + if candidate not in RAM_CARS: + # Newer FW versions standard on the following platforms, or flashed by a dealer onto older platforms have a higher minimum steering speed. + new_eps_platform = candidate in (CAR.CHRYSLER_PACIFICA_2019_HYBRID, CAR.CHRYSLER_PACIFICA_2020, CAR.JEEP_GRAND_CHEROKEE_2019, CAR.DODGE_DURANGO) + new_eps_firmware = any(fw.ecu == 'eps' and fw.fwVersion[:4] >= b"6841" for fw in car_fw) + if new_eps_platform or new_eps_firmware: + ret.flags |= ChryslerFlags.HIGHER_MIN_STEERING_SPEED.value + + # Chrysler + if candidate in (CAR.CHRYSLER_PACIFICA_2018, CAR.CHRYSLER_PACIFICA_2018_HYBRID, CAR.CHRYSLER_PACIFICA_2019_HYBRID, + CAR.CHRYSLER_PACIFICA_2020, CAR.DODGE_DURANGO): + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] + ret.lateralTuning.pid.kf = 0.00006 + + # Jeep + elif candidate in (CAR.JEEP_GRAND_CHEROKEE, CAR.JEEP_GRAND_CHEROKEE_2019): + ret.steerActuatorDelay = 0.2 + + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] + ret.lateralTuning.pid.kf = 0.00006 + + # Ram + elif candidate == CAR.RAM_1500_5TH_GEN: + ret.steerActuatorDelay = 0.2 + ret.wheelbase = 3.88 + # Older EPS FW allow steer to zero + if any(fw.ecu == 'eps' and b"68" < fw.fwVersion[:4] <= b"6831" for fw in car_fw): + ret.minSteerSpeed = 0. + + elif candidate == CAR.RAM_HD_5TH_GEN: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, 1.0, False) + + else: + raise ValueError(f"Unsupported car: {candidate}") + + if ret.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: + # TODO: allow these cars to steer down to 13 m/s if already engaged. + # TODO: Durango 2020 may be able to steer to zero once above 38 kph + ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged. + + ret.centerToFront = ret.wheelbase * 0.44 + ret.enableBsm = 720 in fingerprint[0] + + return ret diff --git a/opendbc_repo/opendbc/car/chrysler/radar_interface.py b/opendbc_repo/opendbc/car/chrysler/radar_interface.py new file mode 100755 index 000000000000000..3528373f8d05e56 --- /dev/null +++ b/opendbc_repo/opendbc/car/chrysler/radar_interface.py @@ -0,0 +1,85 @@ +#!/usr/bin/env python3 +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.interfaces import RadarInterfaceBase +from opendbc.car.chrysler.values import DBC + +RADAR_MSGS_C = list(range(0x2c2, 0x2d4+2, 2)) # c_ messages 706,...,724 +RADAR_MSGS_D = list(range(0x2a2, 0x2b4+2, 2)) # d_ messages +LAST_MSG = max(RADAR_MSGS_C + RADAR_MSGS_D) +NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) + +def _create_radar_can_parser(car_fingerprint): + dbc = DBC[car_fingerprint]['radar'] + if dbc is None: + return None + + msg_n = len(RADAR_MSGS_C) + # list of [(signal name, message name or number), (...)] + # [('RADAR_STATE', 1024), + # ('LONG_DIST', 1072), + # ('LONG_DIST', 1073), + # ('LONG_DIST', 1074), + # ('LONG_DIST', 1075), + + messages = list(zip(RADAR_MSGS_C + + RADAR_MSGS_D, + [20] * msg_n + # 20Hz (0.05s) + [20] * msg_n, strict=True)) # 20Hz (0.05s) + + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) + +def _address_to_track(address): + if address in RADAR_MSGS_C: + return (address - RADAR_MSGS_C[0]) // 2 + if address in RADAR_MSGS_D: + return (address - RADAR_MSGS_D[0]) // 2 + raise ValueError("radar received unexpected address %d" % address) + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.rcp = _create_radar_can_parser(CP.carFingerprint) + self.updated_messages = set() + self.trigger_msg = LAST_MSG + + def update(self, can_strings): + if self.rcp is None or self.CP.radarUnavailable: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + ret = structs.RadarData() + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + ret.errors = errors + + for ii in self.updated_messages: # ii should be the message ID as a number + cpt = self.rcp.vl[ii] + trackId = _address_to_track(ii) + + if trackId not in self.pts: + self.pts[trackId] = structs.RadarData.RadarPoint() + self.pts[trackId].trackId = trackId + self.pts[trackId].aRel = float('nan') + self.pts[trackId].yvRel = float('nan') + self.pts[trackId].measured = True + + if 'LONG_DIST' in cpt: # c_* message + self.pts[trackId].dRel = cpt['LONG_DIST'] # from front of car + # our lat_dist is positive to the right in car's frame. + # TODO what does yRel want? + self.pts[trackId].yRel = cpt['LAT_DIST'] # in car frame's y axis, left is positive + else: # d_* message + self.pts[trackId].vRel = cpt['REL_SPEED'] + + # We want a list, not a dictionary. Filter out LONG_DIST==0 because that means it's not valid. + ret.points = [x for x in self.pts.values() if x.dRel != 0] + + self.updated_messages.clear() + return ret diff --git a/opendbc_repo/opendbc/car/chrysler/values.py b/opendbc_repo/opendbc/car/chrysler/values.py new file mode 100644 index 000000000000000..472b707f9d33d4f --- /dev/null +++ b/opendbc_repo/opendbc/car/chrysler/values.py @@ -0,0 +1,152 @@ +from enum import IntFlag +from dataclasses import dataclass, field + +from panda import uds +from opendbc.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, p16 + +Ecu = CarParams.Ecu + + +class ChryslerFlags(IntFlag): + # Detected flags + HIGHER_MIN_STEERING_SPEED = 1 + +@dataclass +class ChryslerCarDocs(CarDocs): + package: str = "Adaptive Cruise Control (ACC)" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.fca])) + + +@dataclass +class ChryslerPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion')) + + +@dataclass(frozen=True) +class ChryslerCarSpecs(CarSpecs): + minSteerSpeed: float = 3.8 # m/s + + +class CAR(Platforms): + # Chrysler + CHRYSLER_PACIFICA_2018_HYBRID = ChryslerPlatformConfig( + [ChryslerCarDocs("Chrysler Pacifica Hybrid 2017-18")], + ChryslerCarSpecs(mass=2242., wheelbase=3.089, steerRatio=16.2), + ) + CHRYSLER_PACIFICA_2019_HYBRID = ChryslerPlatformConfig( + [ChryslerCarDocs("Chrysler Pacifica Hybrid 2019-24")], + CHRYSLER_PACIFICA_2018_HYBRID.specs, + ) + CHRYSLER_PACIFICA_2018 = ChryslerPlatformConfig( + [ChryslerCarDocs("Chrysler Pacifica 2017-18")], + CHRYSLER_PACIFICA_2018_HYBRID.specs, + ) + CHRYSLER_PACIFICA_2020 = ChryslerPlatformConfig( + [ + ChryslerCarDocs("Chrysler Pacifica 2019-20"), + ChryslerCarDocs("Chrysler Pacifica 2021-23", package="All"), + ], + CHRYSLER_PACIFICA_2018_HYBRID.specs, + ) + + # Dodge + DODGE_DURANGO = ChryslerPlatformConfig( + [ChryslerCarDocs("Dodge Durango 2020-21")], + CHRYSLER_PACIFICA_2018_HYBRID.specs, + ) + + # Jeep + JEEP_GRAND_CHEROKEE = ChryslerPlatformConfig( # includes 2017 Trailhawk + [ChryslerCarDocs("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk")], + ChryslerCarSpecs(mass=1778., wheelbase=2.71, steerRatio=16.7), + ) + + JEEP_GRAND_CHEROKEE_2019 = ChryslerPlatformConfig( # includes 2020 Trailhawk + [ChryslerCarDocs("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4")], + JEEP_GRAND_CHEROKEE.specs, + ) + + # Ram + RAM_1500_5TH_GEN = ChryslerPlatformConfig( + [ChryslerCarDocs("Ram 1500 2019-24", car_parts=CarParts.common([CarHarness.ram]))], + ChryslerCarSpecs(mass=2493., wheelbase=3.88, steerRatio=16.3, minSteerSpeed=14.5), + dbc_dict('chrysler_ram_dt_generated', None), + ) + RAM_HD_5TH_GEN = ChryslerPlatformConfig( + [ + ChryslerCarDocs("Ram 2500 2020-24", car_parts=CarParts.common([CarHarness.ram])), + ChryslerCarDocs("Ram 3500 2019-22", car_parts=CarParts.common([CarHarness.ram])), + ], + ChryslerCarSpecs(mass=3405., wheelbase=3.785, steerRatio=15.61, minSteerSpeed=16.), + dbc_dict('chrysler_ram_hd_generated', None), + ) + + +class CarControllerParams: + def __init__(self, CP): + self.STEER_STEP = 2 # 50 Hz + self.STEER_ERROR_MAX = 80 + if CP.carFingerprint in RAM_HD: + self.STEER_DELTA_UP = 14 + self.STEER_DELTA_DOWN = 14 + self.STEER_MAX = 361 # higher than this faults the EPS + elif CP.carFingerprint in RAM_DT: + self.STEER_DELTA_UP = 6 + self.STEER_DELTA_DOWN = 6 + self.STEER_MAX = 261 # EPS allows more, up to 350? + else: + self.STEER_DELTA_UP = 3 + self.STEER_DELTA_DOWN = 3 + self.STEER_MAX = 261 # higher than this faults the EPS + + +STEER_THRESHOLD = 120 + +RAM_DT = {CAR.RAM_1500_5TH_GEN, } +RAM_HD = {CAR.RAM_HD_5TH_GEN, } +RAM_CARS = RAM_DT | RAM_HD + + +CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf132) +CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(0xf132) + +CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) +CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) + +CHRYSLER_RX_OFFSET = -0x280 + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [CHRYSLER_VERSION_REQUEST], + [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], + rx_offset=CHRYSLER_RX_OFFSET, + bus=0, + ), + Request( + [CHRYSLER_VERSION_REQUEST], + [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.hybrid, Ecu.engine, Ecu.transmission], + bus=0, + ), + Request( + [CHRYSLER_SOFTWARE_VERSION_REQUEST], + [CHRYSLER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], + bus=0, + ), + ], + extra_ecus=[ + (Ecu.abs, 0x7e4, None), # alt address for abs on hybrids, NOTE: not on all hybrid platforms + ], +) + +DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/ford/__init__.py b/opendbc_repo/opendbc/car/common/__init__.py similarity index 100% rename from selfdrive/car/ford/__init__.py rename to opendbc_repo/opendbc/car/common/__init__.py diff --git a/opendbc_repo/opendbc/car/common/basedir.py b/opendbc_repo/opendbc/car/common/basedir.py new file mode 100644 index 000000000000000..6b4811e53c3f89b --- /dev/null +++ b/opendbc_repo/opendbc/car/common/basedir.py @@ -0,0 +1,4 @@ +import os + + +BASEDIR = os.path.abspath(os.path.join(os.path.dirname(os.path.realpath(__file__)), "../")) diff --git a/opendbc_repo/opendbc/car/common/conversions.py b/opendbc_repo/opendbc/car/common/conversions.py new file mode 100644 index 000000000000000..b02b33c625a73f8 --- /dev/null +++ b/opendbc_repo/opendbc/car/common/conversions.py @@ -0,0 +1,19 @@ +import numpy as np + +class Conversions: + # Speed + MPH_TO_KPH = 1.609344 + KPH_TO_MPH = 1. / MPH_TO_KPH + MS_TO_KPH = 3.6 + KPH_TO_MS = 1. / MS_TO_KPH + MS_TO_MPH = MS_TO_KPH * KPH_TO_MPH + MPH_TO_MS = MPH_TO_KPH * KPH_TO_MS + MS_TO_KNOTS = 1.9438 + KNOTS_TO_MS = 1. / MS_TO_KNOTS + + # Angle + DEG_TO_RAD = np.pi / 180. + RAD_TO_DEG = 1. / DEG_TO_RAD + + # Mass + LB_TO_KG = 0.453592 diff --git a/opendbc_repo/opendbc/car/common/filter_simple.py b/opendbc_repo/opendbc/car/common/filter_simple.py new file mode 100644 index 000000000000000..0ec7a515621afbb --- /dev/null +++ b/opendbc_repo/opendbc/car/common/filter_simple.py @@ -0,0 +1,18 @@ +class FirstOrderFilter: + # first order filter + def __init__(self, x0, rc, dt, initialized=True): + self.x = x0 + self.dt = dt + self.update_alpha(rc) + self.initialized = initialized + + def update_alpha(self, rc): + self.alpha = self.dt / (rc + self.dt) + + def update(self, x): + if self.initialized: + self.x = (1. - self.alpha) * self.x + self.alpha * x + else: + self.initialized = True + self.x = x + return self.x diff --git a/opendbc_repo/opendbc/car/common/numpy_fast.py b/opendbc_repo/opendbc/car/common/numpy_fast.py new file mode 100644 index 000000000000000..81f6d6a6bcc07e2 --- /dev/null +++ b/opendbc_repo/opendbc/car/common/numpy_fast.py @@ -0,0 +1,22 @@ +def clip(x, lo, hi): + return max(lo, min(hi, x)) + + +def interp(x, xp, fp): + N = len(xp) + + def get_interp(xv): + hi = 0 + while hi < N and xv > xp[hi]: + hi += 1 + low = hi - 1 + return fp[-1] if hi == N and xv > xp[low] else ( + fp[0] if hi == 0 else + (xv - xp[low]) * (fp[hi] - fp[low]) / (xp[hi] - xp[low]) + fp[low]) + + return [get_interp(v) for v in x] if hasattr(x, '__iter__') else get_interp(x) + + +def mean(x): + return sum(x) / len(x) + diff --git a/opendbc_repo/opendbc/car/common/pid.py b/opendbc_repo/opendbc/car/common/pid.py new file mode 100644 index 000000000000000..7a376c86c309caf --- /dev/null +++ b/opendbc_repo/opendbc/car/common/pid.py @@ -0,0 +1,58 @@ +from numbers import Number +from opendbc.car.common.numpy_fast import clip, interp + + +class PIDController: + def __init__(self, k_p, k_i, pos_limit=1e308, neg_limit=-1e308, rate=100): + self._k_p = k_p + self._k_i = k_i + if isinstance(self._k_p, Number): + self._k_p = [[0], [self._k_p]] + if isinstance(self._k_i, Number): + self._k_i = [[0], [self._k_i]] + + self.pos_limit = pos_limit + self.neg_limit = neg_limit + + self.i_unwind_rate = 0.3 / rate + self.i_rate = 1.0 / rate + self.speed = 0.0 + + self.reset() + + @property + def k_p(self): + return interp(self.speed, self._k_p[0], self._k_p[1]) + + @property + def k_i(self): + return interp(self.speed, self._k_i[0], self._k_i[1]) + + @property + def error_integral(self): + return self.i/self.k_i + + def reset(self): + self.p = 0.0 + self.i = 0.0 + self.control = 0 + + def update(self, error, speed=0.0, freeze_integrator=False): + self.speed = speed + + self.p = float(error) * self.k_p + + i = self.i + error * self.k_i * self.i_rate + control = self.p + i + + # Update when changing i will move the control away from the limits + # or when i will move towards the sign of the error + if ((error >= 0 and (control <= self.pos_limit or i < 0.0)) or + (error <= 0 and (control >= self.neg_limit or i > 0.0))) and \ + not freeze_integrator: + self.i = i + + control = self.p + self.i + + self.control = clip(control, self.neg_limit, self.pos_limit) + return self.control diff --git a/opendbc_repo/opendbc/car/common/simple_kalman.py b/opendbc_repo/opendbc/car/common/simple_kalman.py new file mode 100644 index 000000000000000..194b27204bd511a --- /dev/null +++ b/opendbc_repo/opendbc/car/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/opendbc_repo/opendbc/car/disable_ecu.py b/opendbc_repo/opendbc/car/disable_ecu.py new file mode 100644 index 000000000000000..1e3f41244977237 --- /dev/null +++ b/opendbc_repo/opendbc/car/disable_ecu.py @@ -0,0 +1,36 @@ +from opendbc.car import carlog +from opendbc.car.isotp_parallel_query import IsoTpParallelQuery + +EXT_DIAG_REQUEST = b'\x10\x03' +EXT_DIAG_RESPONSE = b'\x50\x03' + +COM_CONT_RESPONSE = b'' + + +def disable_ecu(can_recv, can_send, bus=0, addr=0x7d0, sub_addr=None, com_cont_req=b'\x28\x83\x01', timeout=0.1, retry=10, debug=False): + """Silence an ECU by disabling sending and receiving messages using UDS 0x28. + The ECU will stay silent as long as openpilot keeps sending Tester Present. + + This is used to disable the radar in some cars. Openpilot will emulate the radar. + WARNING: THIS DISABLES AEB!""" + carlog.warning(f"ecu disable {hex(addr), sub_addr} ...") + + for i in range(retry): + try: + query = IsoTpParallelQuery(can_send, can_recv, bus, [(addr, sub_addr)], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug) + + for _, _ in query.get_data(timeout).items(): + carlog.warning("communication control disable tx/rx ...") + + query = IsoTpParallelQuery(can_send, can_recv, bus, [(addr, sub_addr)], [com_cont_req], [COM_CONT_RESPONSE], debug=debug) + query.get_data(0) + + carlog.warning("ecu disabled") + return True + + except Exception: + carlog.exception("ecu disable exception") + + carlog.error(f"ecu disable retry ({i + 1}) ...") + carlog.error("ecu disable failed") + return False diff --git a/opendbc_repo/opendbc/car/docs.py b/opendbc_repo/opendbc/car/docs.py new file mode 100755 index 000000000000000..26f4333083e6d6f --- /dev/null +++ b/opendbc_repo/opendbc/car/docs.py @@ -0,0 +1,115 @@ +#!/usr/bin/env python3 +import argparse +import os +from typing import get_args + +from collections import defaultdict +import jinja2 +from enum import Enum +from natsort import natsorted + +from opendbc.car.common.basedir import BASEDIR +from opendbc.car import gen_empty_fingerprint +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarDocs, ExtraCarDocs, Column, ExtraCarsColumn, CommonFootnote, PartType +from opendbc.car.car_helpers import interfaces, get_interface_attr +from opendbc.car.values import Platform, PLATFORMS +from opendbc.car.mock.values import CAR as MOCK +from opendbc.car.extra_cars import CAR as EXTRA + + +EXTRA_CARS_MD_OUT = os.path.join(BASEDIR, "../", "../", "docs", "CARS.md") +EXTRA_CARS_MD_TEMPLATE = os.path.join(BASEDIR, "CARS_template.md") + +ExtraPlatform = Platform | EXTRA +EXTRA_BRANDS = get_args(ExtraPlatform) +EXTRA_PLATFORMS: dict[str, ExtraPlatform] = {str(platform): platform for brand in EXTRA_BRANDS for platform in brand} + + +def get_params_for_docs(model, platform) -> CarParams: + cp_model, cp_platform = (model, platform) if model in interfaces else ("MOCK", MOCK.MOCK) + CP: CarParams = interfaces[cp_model][0].get_params(cp_platform, fingerprint=gen_empty_fingerprint(), + car_fw=[CarParams.CarFw(ecu=CarParams.Ecu.unknown)], + experimental_long=True, docs=True) + return CP + + +def get_all_footnotes() -> dict[Enum, int]: + all_footnotes = list(CommonFootnote) + for footnotes in get_interface_attr("Footnote", ignore_none=True).values(): + all_footnotes.extend(footnotes) + return {fn: idx + 1 for idx, fn in enumerate(all_footnotes)} + + +def build_sorted_car_docs_list(platforms, footnotes=None, include_dashcam=False, include_custom=False): + collected_car_docs: list[CarDocs | ExtraCarDocs] = [] + for model, platform in platforms.items(): + car_docs = platform.config.car_docs + CP = get_params_for_docs(model, platform) + + if (CP.dashcamOnly and not include_dashcam) or not len(car_docs): + continue + + # A platform can include multiple car models + for _car_docs in car_docs: + if not hasattr(_car_docs, "row"): + _car_docs.init_make(CP) + _car_docs.init(CP, footnotes) + collected_car_docs.append(_car_docs) + + # Sort cars by make and model + year + sorted_cars = natsorted(collected_car_docs, key=lambda car: car.name.lower()) + return sorted_cars + + +# CAUTION: This function is imported by shop.comma.ai and comma.ai/vehicles, test changes carefully +def get_all_car_docs() -> list[CarDocs]: + collected_footnotes = get_all_footnotes() + sorted_list: list[CarDocs] = build_sorted_car_docs_list(PLATFORMS, footnotes=collected_footnotes) + return sorted_list + + +def get_car_docs_with_extras() -> list[CarDocs | ExtraCarDocs]: + sorted_list: list[CarDocs] = build_sorted_car_docs_list(EXTRA_PLATFORMS, include_custom=True, include_dashcam=True) + return sorted_list + + +def group_by_make(all_car_docs: list[CarDocs]) -> dict[str, list[CarDocs]]: + sorted_car_docs = defaultdict(list) + for car_docs in all_car_docs: + sorted_car_docs[car_docs.make].append(car_docs) + return dict(sorted_car_docs) + + +# CAUTION: This function is imported by shop.comma.ai and comma.ai/vehicles, test changes carefully +def generate_cars_md(all_car_docs: list[CarDocs], template_fn: str) -> str: + with open(template_fn) as f: + template = jinja2.Template(f.read(), trim_blocks=True, lstrip_blocks=True) + + footnotes = [fn.value.text for fn in get_all_footnotes()] + cars_md: str = template.render(all_car_docs=all_car_docs, PartType=PartType, + group_by_make=group_by_make, footnotes=footnotes, + Column=Column) + return cars_md + + +def generate_cars_md_with_extras(car_docs_with_extras: list[CarDocs | ExtraCarDocs], template_fn: str) -> str: + with open(template_fn) as f: + template = jinja2.Template(f.read(), trim_blocks=True, lstrip_blocks=True) + + cars_md: str = template.render(car_docs_with_extras=car_docs_with_extras, PartType=PartType, + group_by_make=group_by_make, ExtraCarsColumn=ExtraCarsColumn) + return cars_md + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Auto generates supportability info docs for all known cars", + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + + parser.add_argument("--template", default=EXTRA_CARS_MD_TEMPLATE, help="Override default template filename") + parser.add_argument("--out", default=EXTRA_CARS_MD_OUT, help="Override default generated filename") + args = parser.parse_args() + + with open(args.out, 'w') as f: + f.write(generate_cars_md_with_extras(get_car_docs_with_extras(), args.template)) + print(f"Generated and written to {args.out}") diff --git a/selfdrive/car/docs_definitions.py b/opendbc_repo/opendbc/car/docs_definitions.py similarity index 84% rename from selfdrive/car/docs_definitions.py rename to opendbc_repo/opendbc/car/docs_definitions.py index 971338e9b57196f..3775e317d629cf1 100644 --- a/selfdrive/car/docs_definitions.py +++ b/opendbc_repo/opendbc/car/docs_definitions.py @@ -4,8 +4,8 @@ from dataclasses import dataclass, field from enum import Enum -from cereal import car -from openpilot.common.conversions import Conversions as CV +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.structs import CarParams GOOD_TORQUE_THRESHOLD = 1.0 # m/s^2 MODEL_YEARS_RE = r"(?<= )((\d{4}-\d{2})|(\d{4}))(,|$)" @@ -24,6 +24,22 @@ class Column(Enum): VIDEO = "Video" +class ExtraCarsColumn(Enum): + MAKE = "Make" + MODEL = "Model" + PACKAGE = "Package" + SUPPORT = "Support Level" + + +class SupportType(Enum): + UPSTREAM = "Upstream" # Actively maintained by comma, plug-and-play in release versions of openpilot + REVIEW = "Under review" # Dashcam, but planned for official support after safety validation + DASHCAM = "Dashcam mode" # Dashcam, but may be drivable in a community fork + COMMUNITY = "Community" # Not upstream, but available in a custom community fork, not validated by comma + CUSTOM = "Custom" # Upstream, but don't have a harness available or need an unusual custom install + INCOMPATIBLE = "Not compatible" # Known fundamental incompatibility such as Flexray or hydraulic power steering + + class Star(Enum): FULL = "full" HALF = "half" @@ -91,8 +107,8 @@ class CarHarness(EnumBase): subaru_d = BaseCarHarness("Subaru D connector") fca = BaseCarHarness("FCA connector") ram = BaseCarHarness("Ram connector") - vw = BaseCarHarness("VW connector") - j533 = BaseCarHarness("J533 connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) + vw_a = BaseCarHarness("VW A connector") + vw_j533 = BaseCarHarness("VW J533 connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) hyundai_a = BaseCarHarness("Hyundai A connector") hyundai_b = BaseCarHarness("Hyundai B connector") hyundai_c = BaseCarHarness("Hyundai C connector") @@ -114,6 +130,8 @@ class CarHarness(EnumBase): custom = BaseCarHarness("Developer connector") obd_ii = BaseCarHarness("OBD-II connector", parts=[Cable.long_obdc_cable, Cable.long_obdc_cable], has_connector=False) gm = BaseCarHarness("GM connector", parts=[Accessory.harness_box]) + gmsdgm = BaseCarHarness("GM SDGM connector", parts=[Accessory.harness_box, Cable.rj45_cable_7ft, Cable.long_obdc_cable, + Cable.usbc_coupler, Accessory.comma_power_v2]) nissan_a = BaseCarHarness("Nissan A connector", parts=[Accessory.harness_box, Cable.rj45_cable_7ft, Cable.long_obdc_cable, Cable.usbc_coupler]) nissan_b = BaseCarHarness("Nissan B connector", parts=[Accessory.harness_box, Cable.rj45_cable_7ft, Cable.long_obdc_cable, Cable.usbc_coupler]) mazda = BaseCarHarness("Mazda connector") @@ -244,14 +262,25 @@ class CarDocs: # all the parts needed for the supported car car_parts: CarParts = field(default_factory=CarParts) + merged: bool = True + support_type: SupportType = SupportType.UPSTREAM + support_link: str | None = "#upstream" + 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]): + def init(self, CP: CarParams, all_footnotes=None): self.car_name = CP.carName self.car_fingerprint = CP.carFingerprint + if self.merged and CP.dashcamOnly: + if self.support_type != SupportType.REVIEW: + self.support_type = SupportType.DASHCAM + self.support_link = "#dashcam" + else: + self.support_link = "#under-review" + # longitudinal column op_long = "Stock" if CP.experimentalLongitudinalAvailable or CP.enableDsu: @@ -306,6 +335,18 @@ def display_func(parts): Column.VIDEO: self.video_link if self.video_link is not None else "", # replaced with an image and link from template in get_column } + if self.support_link is not None: + support_info = f"[{self.support_type.value}]({self.support_link})" + else: + support_info = self.support_type.value + + self.extra_cars_row: dict[Enum, str] = { + ExtraCarsColumn.MAKE: self.make, + ExtraCarsColumn.MODEL: self.model, + ExtraCarsColumn.PACKAGE: self.package, + ExtraCarsColumn.SUPPORT: support_info, + } + # Set steering torque star from max lateral acceleration assert CP.maxLateralAccel > 0.1 if CP.maxLateralAccel >= GOOD_TORQUE_THRESHOLD: @@ -316,7 +357,7 @@ def display_func(parts): return self - def init_make(self, CP: car.CarParams): + def init_make(self, CP: CarParams): """CarDocs subclasses can add make-specific logic for harness selection, footnotes, etc.""" def get_detail_sentence(self, CP): @@ -366,3 +407,18 @@ def get_column(self, column: Column, star_icon: str, video_icon: str, footnote_t item += footnote_tag.format(f'{",".join(map(str, sups))}') return item + + def get_extra_cars_column(self, column: ExtraCarsColumn) -> str: + item: str = self.extra_cars_row[column] + if column == ExtraCarsColumn.MODEL and len(self.years): + item += f" {self.years}" + + return item + + +@dataclass +class ExtraCarDocs(CarDocs): + package: str = "Any" + merged: bool = False + support_type: SupportType = SupportType.INCOMPATIBLE + support_link: str | None = "#incompatible" diff --git a/opendbc_repo/opendbc/car/ecu_addrs.py b/opendbc_repo/opendbc/car/ecu_addrs.py new file mode 100644 index 000000000000000..3d1b83f0c6ca3da --- /dev/null +++ b/opendbc_repo/opendbc/car/ecu_addrs.py @@ -0,0 +1,56 @@ +import time + +from panda import uds +from opendbc.car import make_tester_present_msg, carlog +from opendbc.car.can_definitions import CanData, CanRecvCallable, CanSendCallable +from opendbc.car.fw_query_definitions import EcuAddrBusType + + +def _is_tester_present_response(msg: CanData, subaddr: int = None) -> bool: + # ISO-TP messages are always padded to 8 bytes + # tester present response is always a single frame + dat_offset = 1 if subaddr is not None else 0 + if len(msg.dat) == 8 and 1 <= msg.dat[dat_offset] <= 7: + # success response + if msg.dat[dat_offset + 1] == (uds.SERVICE_TYPE.TESTER_PRESENT + 0x40): + return True + # error response + if msg.dat[dat_offset + 1] == 0x7F and msg.dat[dat_offset + 2] == uds.SERVICE_TYPE.TESTER_PRESENT: + return True + return False + + +def get_all_ecu_addrs(can_recv: CanRecvCallable, can_send: CanSendCallable, bus: int, timeout: float = 1, debug: bool = True) -> set[EcuAddrBusType]: + addr_list = [0x700 + i for i in range(256)] + [0x18da00f1 + (i << 8) for i in range(256)] + queries: set[EcuAddrBusType] = {(addr, None, bus) for addr in addr_list} + responses = queries + return get_ecu_addrs(can_recv, can_send, queries, responses, timeout=timeout, debug=debug) + + +def get_ecu_addrs(can_recv: CanRecvCallable, can_send: CanSendCallable, queries: set[EcuAddrBusType], + responses: set[EcuAddrBusType], timeout: float = 1, debug: bool = False) -> set[EcuAddrBusType]: + ecu_responses: set[EcuAddrBusType] = set() # set((addr, subaddr, bus),) + try: + msgs = [make_tester_present_msg(addr, bus, subaddr) for addr, subaddr, bus in queries] + + can_recv() + can_send(msgs) + start_time = time.monotonic() + while time.monotonic() - start_time < timeout: + can_packets = can_recv(wait_for_one=True) + for packet in can_packets: + for msg in packet: + if not len(msg.dat): + carlog.warning("ECU addr scan: skipping empty remote frame") + continue + + subaddr = None if (msg.address, None, msg.src) in responses else msg.dat[0] + if (msg.address, subaddr, msg.src) in responses and _is_tester_present_response(msg, subaddr): + if debug: + print(f"CAN-RX: {hex(msg.address)} - 0x{bytes.hex(msg.dat)}") + if (msg.address, subaddr, msg.src) in ecu_responses: + print(f"Duplicate ECU address: {hex(msg.address)}") + ecu_responses.add((msg.address, subaddr, msg.src)) + except Exception: + carlog.exception("ECU addr scan exception") + return ecu_responses diff --git a/opendbc_repo/opendbc/car/extra_cars.py b/opendbc_repo/opendbc/car/extra_cars.py new file mode 100644 index 000000000000000..87e1f138192cc46 --- /dev/null +++ b/opendbc_repo/opendbc/car/extra_cars.py @@ -0,0 +1,74 @@ +from dataclasses import dataclass + +from opendbc.car import structs, Platforms, ExtraPlatformConfig +from opendbc.car.docs_definitions import ExtraCarDocs, SupportType + + +@dataclass +class CommunityCarDocs(ExtraCarDocs): + def init_make(self, CP: structs.CarParams): + self.support_type = SupportType.COMMUNITY + self.support_link = "#community" + + +@dataclass +class ToyotaSecurityCarDocs(ExtraCarDocs): + def init_make(self, CP: structs.CarParams): + self.support_type = SupportType.INCOMPATIBLE + self.support_link = "#can-bus-security" + + +@dataclass +class FlexRayCarDocs(ExtraCarDocs): + def init_make(self, CP: structs.CarParams): + self.support_type = SupportType.INCOMPATIBLE + self.support_link = "#flexray" + + +class CAR(Platforms): + config: ExtraPlatformConfig + + EXTRA_HONDA = ExtraPlatformConfig( + [ + CommunityCarDocs("Acura Integra 2024", "All"), + CommunityCarDocs("Honda Accord 2023-24", "All"), + CommunityCarDocs("Honda Clarity 2018-21", "All"), + CommunityCarDocs("Honda CR-V 2024", "All"), + CommunityCarDocs("Honda CR-V Hybrid 2024", "All"), + CommunityCarDocs("Honda Odyssey 2021-25", "All"), + CommunityCarDocs("Honda Pilot 2023-24", "All"), + ], + ) + + EXTRA_HYUNDAI = ExtraPlatformConfig( + [ + CommunityCarDocs("Hyundai Palisade 2023-24", package="HDA2"), + CommunityCarDocs("Kia Telluride 2023-24", package="HDA2"), + ], + ) + + EXTRA_TOYOTA = ExtraPlatformConfig( + [ + ToyotaSecurityCarDocs("Subaru Solterra 2023-25"), + ToyotaSecurityCarDocs("Lexus NS 2022-25"), + ToyotaSecurityCarDocs("Toyota bZ4x 2023-25"), + ToyotaSecurityCarDocs("Toyota Camry 2025"), + ToyotaSecurityCarDocs("Toyota Corolla Cross 2022-25"), + ToyotaSecurityCarDocs("Toyota Highlander 2025"), + CommunityCarDocs("Toyota RAV4 Prime 2021-23"), + ToyotaSecurityCarDocs("Toyota RAV4 Prime 2024-25"), + ToyotaSecurityCarDocs("Toyota Sequoia 2023-25"), + CommunityCarDocs("Toyota Sienna 2021-23"), + ToyotaSecurityCarDocs("Toyota Sienna 2024-25"), + ToyotaSecurityCarDocs("Toyota Tundra 2022-25"), + ToyotaSecurityCarDocs("Toyota Venza 2021-25"), + ], + ) + + EXTRA_VOLKSWAGEN = ExtraPlatformConfig( + [ + FlexRayCarDocs("Audi A4 2016-24", package="All"), + FlexRayCarDocs("Audi A5 2016-24", package="All"), + FlexRayCarDocs("Audi Q5 2017-24", package="All"), + ], + ) diff --git a/opendbc_repo/opendbc/car/fingerprints.py b/opendbc_repo/opendbc/car/fingerprints.py new file mode 100644 index 000000000000000..4619eb5443c3dcb --- /dev/null +++ b/opendbc_repo/opendbc/car/fingerprints.py @@ -0,0 +1,345 @@ +from opendbc.car.interfaces import get_interface_attr +from opendbc.car.body.values import CAR as BODY +from opendbc.car.chrysler.values import CAR as CHRYSLER +from opendbc.car.ford.values import CAR as FORD +from opendbc.car.gm.values import CAR as GM +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.hyundai.values import CAR as HYUNDAI +from opendbc.car.mazda.values import CAR as MAZDA +from opendbc.car.mock.values import CAR as MOCK +from opendbc.car.nissan.values import CAR as NISSAN +from opendbc.car.subaru.values import CAR as SUBARU +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.volkswagen.values import CAR as VW + +FW_VERSIONS = get_interface_attr('FW_VERSIONS', combine_brands=True, ignore_none=True) +_FINGERPRINTS = get_interface_attr('FINGERPRINTS', combine_brands=True, ignore_none=True) + +_DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes + + +def is_valid_for_fingerprint(msg, car_fingerprint: dict[int, int]): + adr = msg.address + # ignore addresses that are more than 11 bits + return (adr in car_fingerprint and car_fingerprint[adr] == len(msg.dat)) or adr >= 0x800 + + +def eliminate_incompatible_cars(msg, candidate_cars): + """Removes cars that could not have sent msg. + + Inputs: + msg: A cereal/log CanData message from the car. + candidate_cars: A list of cars to consider. + + Returns: + A list containing the subset of candidate_cars that could have sent msg. + """ + compatible_cars = [] + + for car_name in candidate_cars: + car_fingerprints = _FINGERPRINTS[car_name] + + for fingerprint in car_fingerprints: + # add alien debug address + if is_valid_for_fingerprint(msg, fingerprint | _DEBUG_ADDRESS): + compatible_cars.append(car_name) + break + + return compatible_cars + + +def all_known_cars(): + """Returns a list of all known car strings.""" + return list({*FW_VERSIONS.keys(), *_FINGERPRINTS.keys()}) + + +def all_legacy_fingerprint_cars(): + """Returns a list of all known car strings, FPv1 only.""" + return list(_FINGERPRINTS.keys()) + + +# A dict that maps old platform strings to their latest representations +MIGRATION = { + "ACURA ILX 2016 ACURAWATCH PLUS": HONDA.ACURA_ILX, + "ACURA RDX 2018 ACURAWATCH PLUS": HONDA.ACURA_RDX, + "ACURA RDX 2020 TECH": HONDA.ACURA_RDX_3G, + "AUDI A3": VW.AUDI_A3_MK3, + "HONDA ACCORD 2018 HYBRID TOURING": HONDA.HONDA_ACCORD, + "HONDA ACCORD 1.5T 2018": HONDA.HONDA_ACCORD, + "HONDA ACCORD 2018 LX 1.5T": HONDA.HONDA_ACCORD, + "HONDA ACCORD 2018 SPORT 2T": HONDA.HONDA_ACCORD, + "HONDA ACCORD 2T 2018": HONDA.HONDA_ACCORD, + "HONDA ACCORD HYBRID 2018": HONDA.HONDA_ACCORD, + "HONDA CIVIC 2016 TOURING": HONDA.HONDA_CIVIC, + "HONDA CIVIC HATCHBACK 2017 SEDAN/COUPE 2019": HONDA.HONDA_CIVIC_BOSCH, + "HONDA CIVIC SEDAN 1.6 DIESEL": HONDA.HONDA_CIVIC_BOSCH_DIESEL, + "HONDA CR-V 2016 EXECUTIVE": HONDA.HONDA_CRV_EU, + "HONDA CR-V 2016 TOURING": HONDA.HONDA_CRV, + "HONDA CR-V 2017 EX": HONDA.HONDA_CRV_5G, + "HONDA CR-V 2019 HYBRID": HONDA.HONDA_CRV_HYBRID, + "HONDA FIT 2018 EX": HONDA.HONDA_FIT, + "HONDA HRV 2019 TOURING": HONDA.HONDA_HRV, + "HONDA INSIGHT 2019 TOURING": HONDA.HONDA_INSIGHT, + "HONDA ODYSSEY 2018 EX-L": HONDA.HONDA_ODYSSEY, + "HONDA ODYSSEY 2019 EXCLUSIVE CHN": HONDA.HONDA_ODYSSEY_CHN, + "HONDA PILOT 2017 TOURING": HONDA.HONDA_PILOT, + "HONDA PILOT 2019 ELITE": HONDA.HONDA_PILOT, + "HONDA PILOT 2019": HONDA.HONDA_PILOT, + "HONDA PASSPORT 2021": HONDA.HONDA_PILOT, + "HONDA RIDGELINE 2017 BLACK EDITION": HONDA.HONDA_RIDGELINE, + "HYUNDAI ELANTRA LIMITED ULTIMATE 2017": HYUNDAI.HYUNDAI_ELANTRA, + "HYUNDAI SANTA FE LIMITED 2019": HYUNDAI.HYUNDAI_SANTA_FE, + "HYUNDAI TUCSON DIESEL 2019": HYUNDAI.HYUNDAI_TUCSON, + "KIA OPTIMA 2016": HYUNDAI.KIA_OPTIMA_G4, + "KIA OPTIMA 2019": HYUNDAI.KIA_OPTIMA_G4_FL, + "KIA OPTIMA SX 2019 & 2016": HYUNDAI.KIA_OPTIMA_G4_FL, + "LEXUS CT 200H 2018": TOYOTA.LEXUS_CTH, + "LEXUS ES 300H 2018": TOYOTA.LEXUS_ES, + "LEXUS ES 300H 2019": TOYOTA.LEXUS_ES_TSS2, + "LEXUS IS300 2018": TOYOTA.LEXUS_IS, + "LEXUS NX300 2018": TOYOTA.LEXUS_NX, + "LEXUS NX300H 2018": TOYOTA.LEXUS_NX, + "LEXUS RX 350 2016": TOYOTA.LEXUS_RX, + "LEXUS RX350 2020": TOYOTA.LEXUS_RX_TSS2, + "LEXUS RX450 HYBRID 2020": TOYOTA.LEXUS_RX_TSS2, + "TOYOTA SIENNA XLE 2018": TOYOTA.TOYOTA_SIENNA, + "TOYOTA C-HR HYBRID 2018": TOYOTA.TOYOTA_CHR, + "TOYOTA COROLLA HYBRID TSS2 2019": TOYOTA.TOYOTA_COROLLA_TSS2, + "TOYOTA RAV4 HYBRID 2019": TOYOTA.TOYOTA_RAV4_TSS2, + "LEXUS ES HYBRID 2019": TOYOTA.LEXUS_ES_TSS2, + "LEXUS NX HYBRID 2018": TOYOTA.LEXUS_NX, + "LEXUS NX HYBRID 2020": TOYOTA.LEXUS_NX_TSS2, + "LEXUS RX HYBRID 2020": TOYOTA.LEXUS_RX_TSS2, + "TOYOTA ALPHARD HYBRID 2021": TOYOTA.TOYOTA_ALPHARD_TSS2, + "TOYOTA AVALON HYBRID 2019": TOYOTA.TOYOTA_AVALON_2019, + "TOYOTA AVALON HYBRID 2022": TOYOTA.TOYOTA_AVALON_TSS2, + "TOYOTA CAMRY HYBRID 2018": TOYOTA.TOYOTA_CAMRY, + "TOYOTA CAMRY HYBRID 2021": TOYOTA.TOYOTA_CAMRY_TSS2, + "TOYOTA C-HR HYBRID 2022": TOYOTA.TOYOTA_CHR_TSS2, + "TOYOTA HIGHLANDER HYBRID 2020": TOYOTA.TOYOTA_HIGHLANDER_TSS2, + "TOYOTA RAV4 HYBRID 2022": TOYOTA.TOYOTA_RAV4_TSS2_2022, + "TOYOTA RAV4 HYBRID 2023": TOYOTA.TOYOTA_RAV4_TSS2_2023, + "TOYOTA HIGHLANDER HYBRID 2018": TOYOTA.TOYOTA_HIGHLANDER, + "LEXUS ES HYBRID 2018": TOYOTA.LEXUS_ES, + "LEXUS RX HYBRID 2017": TOYOTA.LEXUS_RX, + "HYUNDAI TUCSON HYBRID 4TH GEN": HYUNDAI.HYUNDAI_TUCSON_4TH_GEN, + "KIA SPORTAGE HYBRID 5TH GEN": HYUNDAI.KIA_SPORTAGE_5TH_GEN, + "KIA SORENTO PLUG-IN HYBRID 4TH GEN": HYUNDAI.KIA_SORENTO_HEV_4TH_GEN, + "CADILLAC ESCALADE ESV PLATINUM 2019": GM.CADILLAC_ESCALADE_ESV_2019, + + # Removal of platform_str, see https://github.com/commaai/openpilot/pull/31868/ + "COMMA BODY": BODY.COMMA_BODY, + "CHRYSLER PACIFICA HYBRID 2017": CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID, + "CHRYSLER_PACIFICA_2017_HYBRID": CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID, + "CHRYSLER PACIFICA HYBRID 2018": CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID, + "CHRYSLER PACIFICA HYBRID 2019": CHRYSLER.CHRYSLER_PACIFICA_2019_HYBRID, + "CHRYSLER PACIFICA 2018": CHRYSLER.CHRYSLER_PACIFICA_2018, + "CHRYSLER PACIFICA 2020": CHRYSLER.CHRYSLER_PACIFICA_2020, + "DODGE DURANGO 2021": CHRYSLER.DODGE_DURANGO, + "JEEP GRAND CHEROKEE V6 2018": CHRYSLER.JEEP_GRAND_CHEROKEE, + "JEEP GRAND CHEROKEE 2019": CHRYSLER.JEEP_GRAND_CHEROKEE_2019, + "RAM 1500 5TH GEN": CHRYSLER.RAM_1500_5TH_GEN, + "RAM HD 5TH GEN": CHRYSLER.RAM_HD_5TH_GEN, + "FORD BRONCO SPORT 1ST GEN": FORD.FORD_BRONCO_SPORT_MK1, + "FORD ESCAPE 4TH GEN": FORD.FORD_ESCAPE_MK4, + "FORD EXPLORER 6TH GEN": FORD.FORD_EXPLORER_MK6, + "FORD F-150 14TH GEN": FORD.FORD_F_150_MK14, + "FORD F-150 LIGHTNING 1ST GEN": FORD.FORD_F_150_LIGHTNING_MK1, + "FORD FOCUS 4TH GEN": FORD.FORD_FOCUS_MK4, + "FORD MAVERICK 1ST GEN": FORD.FORD_MAVERICK_MK1, + "FORD MUSTANG MACH-E 1ST GEN": FORD.FORD_MUSTANG_MACH_E_MK1, + "HOLDEN ASTRA RS-V BK 2017": GM.HOLDEN_ASTRA, + "CHEVROLET VOLT PREMIER 2017": GM.CHEVROLET_VOLT, + "CADILLAC ATS Premium Performance 2018": GM.CADILLAC_ATS, + "CHEVROLET MALIBU PREMIER 2017": GM.CHEVROLET_MALIBU, + "GMC ACADIA DENALI 2018": GM.GMC_ACADIA, + "BUICK LACROSSE 2017": GM.BUICK_LACROSSE, + "BUICK REGAL ESSENCE 2018": GM.BUICK_REGAL, + "CADILLAC ESCALADE 2017": GM.CADILLAC_ESCALADE, + "CADILLAC ESCALADE ESV 2016": GM.CADILLAC_ESCALADE_ESV, + "CADILLAC ESCALADE ESV 2019": GM.CADILLAC_ESCALADE_ESV_2019, + "CHEVROLET BOLT EUV 2022": GM.CHEVROLET_BOLT_EUV, + "CHEVROLET SILVERADO 1500 2020": GM.CHEVROLET_SILVERADO, + "CHEVROLET EQUINOX 2019": GM.CHEVROLET_EQUINOX, + "CHEVROLET TRAILBLAZER 2021": GM.CHEVROLET_TRAILBLAZER, + "HONDA ACCORD 2018": HONDA.HONDA_ACCORD, + "HONDA CIVIC (BOSCH) 2019": HONDA.HONDA_CIVIC_BOSCH, + "HONDA CIVIC SEDAN 1.6 DIESEL 2019": HONDA.HONDA_CIVIC_BOSCH_DIESEL, + "HONDA CIVIC 2022": HONDA.HONDA_CIVIC_2022, + "HONDA CR-V 2017": HONDA.HONDA_CRV_5G, + "HONDA CR-V HYBRID 2019": HONDA.HONDA_CRV_HYBRID, + "HONDA HR-V 2023": HONDA.HONDA_HRV_3G, + "ACURA RDX 2020": HONDA.ACURA_RDX_3G, + "HONDA INSIGHT 2019": HONDA.HONDA_INSIGHT, + "HONDA E 2020": HONDA.HONDA_E, + "ACURA ILX 2016": HONDA.ACURA_ILX, + "HONDA CR-V 2016": HONDA.HONDA_CRV, + "HONDA CR-V EU 2016": HONDA.HONDA_CRV_EU, + "HONDA FIT 2018": HONDA.HONDA_FIT, + "HONDA FREED 2020": HONDA.HONDA_FREED, + "HONDA HRV 2019": HONDA.HONDA_HRV, + "HONDA ODYSSEY 2018": HONDA.HONDA_ODYSSEY, + "HONDA ODYSSEY CHN 2019": HONDA.HONDA_ODYSSEY_CHN, + "ACURA RDX 2018": HONDA.ACURA_RDX, + "HONDA PILOT 2017": HONDA.HONDA_PILOT, + "HONDA RIDGELINE 2017": HONDA.HONDA_RIDGELINE, + "HONDA CIVIC 2016": HONDA.HONDA_CIVIC, + "HYUNDAI AZERA 6TH GEN": HYUNDAI.HYUNDAI_AZERA_6TH_GEN, + "HYUNDAI AZERA HYBRID 6TH GEN": HYUNDAI.HYUNDAI_AZERA_HEV_6TH_GEN, + "HYUNDAI ELANTRA 2017": HYUNDAI.HYUNDAI_ELANTRA, + "HYUNDAI I30 N LINE 2019 & GT 2018 DCT": HYUNDAI.HYUNDAI_ELANTRA_GT_I30, + "HYUNDAI ELANTRA 2021": HYUNDAI.HYUNDAI_ELANTRA_2021, + "HYUNDAI ELANTRA HYBRID 2021": HYUNDAI.HYUNDAI_ELANTRA_HEV_2021, + "HYUNDAI GENESIS 2015-2016": HYUNDAI.HYUNDAI_GENESIS, + "HYUNDAI IONIQ HYBRID 2017-2019": HYUNDAI.HYUNDAI_IONIQ, + "HYUNDAI IONIQ HYBRID 2020-2022": HYUNDAI.HYUNDAI_IONIQ_HEV_2022, + "HYUNDAI IONIQ ELECTRIC LIMITED 2019": HYUNDAI.HYUNDAI_IONIQ_EV_LTD, + "HYUNDAI IONIQ ELECTRIC 2020": HYUNDAI.HYUNDAI_IONIQ_EV_2020, + "HYUNDAI IONIQ PLUG-IN HYBRID 2019": HYUNDAI.HYUNDAI_IONIQ_PHEV_2019, + "HYUNDAI IONIQ PHEV 2020": HYUNDAI.HYUNDAI_IONIQ_PHEV, + "HYUNDAI KONA 2020": HYUNDAI.HYUNDAI_KONA, + "HYUNDAI KONA ELECTRIC 2019": HYUNDAI.HYUNDAI_KONA_EV, + "HYUNDAI KONA ELECTRIC 2022": HYUNDAI.HYUNDAI_KONA_EV_2022, + "HYUNDAI KONA ELECTRIC 2ND GEN": HYUNDAI.HYUNDAI_KONA_EV_2ND_GEN, + "HYUNDAI KONA HYBRID 2020": HYUNDAI.HYUNDAI_KONA_HEV, + "HYUNDAI SANTA FE 2019": HYUNDAI.HYUNDAI_SANTA_FE, + "HYUNDAI SANTA FE 2022": HYUNDAI.HYUNDAI_SANTA_FE_2022, + "HYUNDAI SANTA FE HYBRID 2022": HYUNDAI.HYUNDAI_SANTA_FE_HEV_2022, + "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": HYUNDAI.HYUNDAI_SANTA_FE_PHEV_2022, + "HYUNDAI SONATA 2020": HYUNDAI.HYUNDAI_SONATA, + "HYUNDAI SONATA 2019": HYUNDAI.HYUNDAI_SONATA_LF, + "HYUNDAI STARIA 4TH GEN": HYUNDAI.HYUNDAI_STARIA_4TH_GEN, + "HYUNDAI TUCSON 2019": HYUNDAI.HYUNDAI_TUCSON, + "HYUNDAI PALISADE 2020": HYUNDAI.HYUNDAI_PALISADE, + "HYUNDAI VELOSTER 2019": HYUNDAI.HYUNDAI_VELOSTER, + "HYUNDAI SONATA HYBRID 2021": HYUNDAI.HYUNDAI_SONATA_HYBRID, + "HYUNDAI IONIQ 5 2022": HYUNDAI.HYUNDAI_IONIQ_5, + "HYUNDAI IONIQ 6 2023": HYUNDAI.HYUNDAI_IONIQ_6, + "HYUNDAI TUCSON 4TH GEN": HYUNDAI.HYUNDAI_TUCSON_4TH_GEN, + "HYUNDAI SANTA CRUZ 1ST GEN": HYUNDAI.HYUNDAI_SANTA_CRUZ_1ST_GEN, + "HYUNDAI CUSTIN 1ST GEN": HYUNDAI.HYUNDAI_CUSTIN_1ST_GEN, + "KIA FORTE E 2018 & GT 2021": HYUNDAI.KIA_FORTE, + "KIA K5 2021": HYUNDAI.KIA_K5_2021, + "KIA K5 HYBRID 2020": HYUNDAI.KIA_K5_HEV_2020, + "KIA K8 HYBRID 1ST GEN": HYUNDAI.KIA_K8_HEV_1ST_GEN, + "KIA NIRO EV 2020": HYUNDAI.KIA_NIRO_EV, + "KIA NIRO EV 2ND GEN": HYUNDAI.KIA_NIRO_EV_2ND_GEN, + "KIA NIRO HYBRID 2019": HYUNDAI.KIA_NIRO_PHEV, + "KIA NIRO PLUG-IN HYBRID 2022": HYUNDAI.KIA_NIRO_PHEV_2022, + "KIA NIRO HYBRID 2021": HYUNDAI.KIA_NIRO_HEV_2021, + "KIA NIRO HYBRID 2ND GEN": HYUNDAI.KIA_NIRO_HEV_2ND_GEN, + "KIA OPTIMA 4TH GEN": HYUNDAI.KIA_OPTIMA_G4, + "KIA OPTIMA 4TH GEN FACELIFT": HYUNDAI.KIA_OPTIMA_G4_FL, + "KIA OPTIMA HYBRID 2017 & SPORTS 2019": HYUNDAI.KIA_OPTIMA_H, + "KIA OPTIMA HYBRID 4TH GEN FACELIFT": HYUNDAI.KIA_OPTIMA_H_G4_FL, + "KIA SELTOS 2021": HYUNDAI.KIA_SELTOS, + "KIA SPORTAGE 5TH GEN": HYUNDAI.KIA_SPORTAGE_5TH_GEN, + "KIA SORENTO GT LINE 2018": HYUNDAI.KIA_SORENTO, + "KIA SORENTO 4TH GEN": HYUNDAI.KIA_SORENTO_4TH_GEN, + "KIA SORENTO HYBRID 4TH GEN": HYUNDAI.KIA_SORENTO_HEV_4TH_GEN, + "KIA STINGER GT2 2018": HYUNDAI.KIA_STINGER, + "KIA STINGER 2022": HYUNDAI.KIA_STINGER_2022, + "KIA CEED INTRO ED 2019": HYUNDAI.KIA_CEED, + "KIA EV6 2022": HYUNDAI.KIA_EV6, + "KIA CARNIVAL 4TH GEN": HYUNDAI.KIA_CARNIVAL_4TH_GEN, + "GENESIS GV60 ELECTRIC 1ST GEN": HYUNDAI.GENESIS_GV60_EV_1ST_GEN, + "GENESIS G70 2018": HYUNDAI.GENESIS_G70, + "GENESIS G70 2020": HYUNDAI.GENESIS_G70_2020, + "GENESIS GV70 1ST GEN": HYUNDAI.GENESIS_GV70_1ST_GEN, + "GENESIS G80 2017": HYUNDAI.GENESIS_G80, + "GENESIS G90 2017": HYUNDAI.GENESIS_G90, + "GENESIS GV80 2023": HYUNDAI.GENESIS_GV80, + "MAZDA CX-5": MAZDA.MAZDA_CX5, + "MAZDA CX-9": MAZDA.MAZDA_CX9, + "MAZDA 3": MAZDA.MAZDA_3, + "MAZDA 6": MAZDA.MAZDA_6, + "MAZDA CX-9 2021": MAZDA.MAZDA_CX9_2021, + "MAZDA CX-5 2022": MAZDA.MAZDA_CX5_2022, + "NISSAN X-TRAIL 2017": NISSAN.NISSAN_XTRAIL, + "NISSAN LEAF 2018": NISSAN.NISSAN_LEAF, + "NISSAN LEAF 2018 Instrument Cluster": NISSAN.NISSAN_LEAF_IC, + "NISSAN ROGUE 2019": NISSAN.NISSAN_ROGUE, + "NISSAN ALTIMA 2020": NISSAN.NISSAN_ALTIMA, + "SUBARU ASCENT LIMITED 2019": SUBARU.SUBARU_ASCENT, + "SUBARU OUTBACK 6TH GEN": SUBARU.SUBARU_OUTBACK, + "SUBARU LEGACY 7TH GEN": SUBARU.SUBARU_LEGACY, + "SUBARU IMPREZA LIMITED 2019": SUBARU.SUBARU_IMPREZA, + "SUBARU IMPREZA SPORT 2020": SUBARU.SUBARU_IMPREZA_2020, + "SUBARU CROSSTREK HYBRID 2020": SUBARU.SUBARU_CROSSTREK_HYBRID, + "SUBARU FORESTER 2019": SUBARU.SUBARU_FORESTER, + "SUBARU FORESTER HYBRID 2020": SUBARU.SUBARU_FORESTER_HYBRID, + "SUBARU FORESTER 2017 - 2018": SUBARU.SUBARU_FORESTER_PREGLOBAL, + "SUBARU LEGACY 2015 - 2018": SUBARU.SUBARU_LEGACY_PREGLOBAL, + "SUBARU OUTBACK 2015 - 2017": SUBARU.SUBARU_OUTBACK_PREGLOBAL, + "SUBARU OUTBACK 2018 - 2019": SUBARU.SUBARU_OUTBACK_PREGLOBAL_2018, + "SUBARU FORESTER 2022": SUBARU.SUBARU_FORESTER_2022, + "SUBARU OUTBACK 7TH GEN": SUBARU.SUBARU_OUTBACK_2023, + "SUBARU ASCENT 2023": SUBARU.SUBARU_ASCENT_2023, + "TOYOTA ALPHARD 2020": TOYOTA.TOYOTA_ALPHARD_TSS2, + "TOYOTA AVALON 2016": TOYOTA.TOYOTA_AVALON, + "TOYOTA AVALON 2019": TOYOTA.TOYOTA_AVALON_2019, + "TOYOTA AVALON 2022": TOYOTA.TOYOTA_AVALON_TSS2, + "TOYOTA CAMRY 2018": TOYOTA.TOYOTA_CAMRY, + "TOYOTA CAMRY 2021": TOYOTA.TOYOTA_CAMRY_TSS2, + "TOYOTA C-HR 2018": TOYOTA.TOYOTA_CHR, + "TOYOTA C-HR 2021": TOYOTA.TOYOTA_CHR_TSS2, + "TOYOTA COROLLA 2017": TOYOTA.TOYOTA_COROLLA, + "TOYOTA COROLLA TSS2 2019": TOYOTA.TOYOTA_COROLLA_TSS2, + "TOYOTA HIGHLANDER 2017": TOYOTA.TOYOTA_HIGHLANDER, + "TOYOTA HIGHLANDER 2020": TOYOTA.TOYOTA_HIGHLANDER_TSS2, + "TOYOTA PRIUS 2017": TOYOTA.TOYOTA_PRIUS, + "TOYOTA PRIUS v 2017": TOYOTA.TOYOTA_PRIUS_V, + "TOYOTA PRIUS TSS2 2021": TOYOTA.TOYOTA_PRIUS_TSS2, + "TOYOTA RAV4 2017": TOYOTA.TOYOTA_RAV4, + "TOYOTA RAV4 HYBRID 2017": TOYOTA.TOYOTA_RAV4H, + "TOYOTA RAV4 2019": TOYOTA.TOYOTA_RAV4_TSS2, + "TOYOTA RAV4 2022": TOYOTA.TOYOTA_RAV4_TSS2_2022, + "TOYOTA RAV4 2023": TOYOTA.TOYOTA_RAV4_TSS2_2023, + "TOYOTA MIRAI 2021": TOYOTA.TOYOTA_MIRAI, + "TOYOTA SIENNA 2018": TOYOTA.TOYOTA_SIENNA, + "LEXUS CT HYBRID 2018": TOYOTA.LEXUS_CTH, + "LEXUS ES 2018": TOYOTA.LEXUS_ES, + "LEXUS ES 2019": TOYOTA.LEXUS_ES_TSS2, + "LEXUS IS 2018": TOYOTA.LEXUS_IS, + "LEXUS IS 2023": TOYOTA.LEXUS_IS_TSS2, + "LEXUS NX 2018": TOYOTA.LEXUS_NX, + "LEXUS NX 2020": TOYOTA.LEXUS_NX_TSS2, + "LEXUS LC 2024": TOYOTA.LEXUS_LC_TSS2, + "LEXUS RC 2020": TOYOTA.LEXUS_RC, + "LEXUS RX 2016": TOYOTA.LEXUS_RX, + "LEXUS RX 2020": TOYOTA.LEXUS_RX_TSS2, + "LEXUS GS F 2016": TOYOTA.LEXUS_GS_F, + "VOLKSWAGEN ARTEON 1ST GEN": VW.VOLKSWAGEN_ARTEON_MK1, + "VOLKSWAGEN ATLAS 1ST GEN": VW.VOLKSWAGEN_ATLAS_MK1, + "VOLKSWAGEN CADDY 3RD GEN": VW.VOLKSWAGEN_CADDY_MK3, + "VOLKSWAGEN CRAFTER 2ND GEN": VW.VOLKSWAGEN_CRAFTER_MK2, + "VOLKSWAGEN GOLF 7TH GEN": VW.VOLKSWAGEN_GOLF_MK7, + "VOLKSWAGEN JETTA 6TH GEN": VW.VOLKSWAGEN_JETTA_MK6, + "VOLKSWAGEN JETTA 7TH GEN": VW.VOLKSWAGEN_JETTA_MK7, + "VOLKSWAGEN PASSAT 8TH GEN": VW.VOLKSWAGEN_PASSAT_MK8, + "VOLKSWAGEN PASSAT NMS": VW.VOLKSWAGEN_PASSAT_NMS, + "VOLKSWAGEN POLO 6TH GEN": VW.VOLKSWAGEN_POLO_MK6, + "VOLKSWAGEN SHARAN 2ND GEN": VW.VOLKSWAGEN_SHARAN_MK2, + "VOLKSWAGEN TAOS 1ST GEN": VW.VOLKSWAGEN_TAOS_MK1, + "VOLKSWAGEN T-CROSS 1ST GEN": VW.VOLKSWAGEN_TCROSS_MK1, + "VOLKSWAGEN TIGUAN 2ND GEN": VW.VOLKSWAGEN_TIGUAN_MK2, + "VOLKSWAGEN TOURAN 2ND GEN": VW.VOLKSWAGEN_TOURAN_MK2, + "VOLKSWAGEN TRANSPORTER T6.1": VW.VOLKSWAGEN_TRANSPORTER_T61, + "VOLKSWAGEN T-ROC 1ST GEN": VW.VOLKSWAGEN_TROC_MK1, + "AUDI A3 3RD GEN": VW.AUDI_A3_MK3, + "AUDI Q2 1ST GEN": VW.AUDI_Q2_MK1, + "AUDI Q3 2ND GEN": VW.AUDI_Q3_MK2, + "SEAT ATECA 1ST GEN": VW.SEAT_ATECA_MK1, + "SEAT LEON 3RD GEN": VW.SEAT_ATECA_MK1, + "SEAT_LEON_MK3": VW.SEAT_ATECA_MK1, + "SKODA FABIA 4TH GEN": VW.SKODA_FABIA_MK4, + "SKODA KAMIQ 1ST GEN": VW.SKODA_KAMIQ_MK1, + "SKODA KAROQ 1ST GEN": VW.SKODA_KAROQ_MK1, + "SKODA KODIAQ 1ST GEN": VW.SKODA_KODIAQ_MK1, + "SKODA OCTAVIA 3RD GEN": VW.SKODA_OCTAVIA_MK3, + "SKODA SCALA 1ST GEN": VW.SKODA_KAMIQ_MK1, + "SKODA_SCALA_MK1": VW.SKODA_KAMIQ_MK1, + "SKODA SUPERB 3RD GEN": VW.SKODA_SUPERB_MK3, + + "mock": MOCK.MOCK, +} diff --git a/selfdrive/car/ford/tests/__init__.py b/opendbc_repo/opendbc/car/ford/__init__.py similarity index 100% rename from selfdrive/car/ford/tests/__init__.py rename to opendbc_repo/opendbc/car/ford/__init__.py diff --git a/opendbc_repo/opendbc/car/ford/carcontroller.py b/opendbc_repo/opendbc/car/ford/carcontroller.py new file mode 100644 index 000000000000000..72def7489cffd91 --- /dev/null +++ b/opendbc_repo/opendbc/car/ford/carcontroller.py @@ -0,0 +1,167 @@ +import math +from opendbc.can.packer import CANPacker +from opendbc.car import ACCELERATION_DUE_TO_GRAVITY, DT_CTRL, apply_std_steer_angle_limits, structs +from opendbc.car.ford import fordcan +from opendbc.car.ford.values import CarControllerParams, FordFlags +from opendbc.car.common.numpy_fast import clip, interp +from opendbc.car.interfaces import CarControllerBase, V_CRUISE_MAX + +LongCtrlState = structs.CarControl.Actuators.LongControlState +VisualAlert = structs.CarControl.HUDControl.VisualAlert + + +def apply_ford_curvature_limits(apply_curvature, apply_curvature_last, current_curvature, v_ego_raw): + # No blending at low speed due to lack of torque wind-up and inaccurate current curvature + if v_ego_raw > 9: + apply_curvature = clip(apply_curvature, current_curvature - CarControllerParams.CURVATURE_ERROR, + current_curvature + CarControllerParams.CURVATURE_ERROR) + + # Curvature rate limit after driver torque limit + apply_curvature = apply_std_steer_angle_limits(apply_curvature, apply_curvature_last, v_ego_raw, CarControllerParams) + + return clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX) + + +def apply_creep_compensation(accel: float, v_ego: float) -> float: + creep_accel = interp(v_ego, [1., 3.], [0.6, 0.]) + creep_accel = interp(accel, [0., 0.2], [creep_accel, 0.]) + accel -= creep_accel + return accel + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.packer = CANPacker(dbc_name) + self.CAN = fordcan.CanBus(CP) + + self.apply_curvature_last = 0 + self.accel = 0.0 + self.gas = 0.0 + self.brake_request = False + self.main_on_last = False + self.lkas_enabled_last = False + self.steer_alert_last = False + self.lead_distance_bars_last = None + self.distance_bar_frame = 0 + + def update(self, CC, CS, now_nanos): + can_sends = [] + + actuators = CC.actuators + hud_control = CC.hudControl + + main_on = CS.out.cruiseState.available + steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) + fcw_alert = hud_control.visualAlert == VisualAlert.fcw + + ### acc buttons ### + if CC.cruiseControl.cancel: + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, cancel=True)) + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, cancel=True)) + elif CC.cruiseControl.resume and (self.frame % CarControllerParams.BUTTONS_STEP) == 0: + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, resume=True)) + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, resume=True)) + # if stock lane centering isn't off, send a button press to toggle it off + # the stock system checks for steering pressed, and eventually disengages cruise control + elif CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0 and (self.frame % CarControllerParams.ACC_UI_STEP) == 0: + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, tja_toggle=True)) + + ### lateral control ### + # send steer msg at 20Hz + if (self.frame % CarControllerParams.STEER_STEP) == 0: + if CC.latActive: + # apply rate limits, curvature error limit, and clip to signal range + current_curvature = -CS.out.yawRate / max(CS.out.vEgoRaw, 0.1) + apply_curvature = apply_ford_curvature_limits(actuators.curvature, self.apply_curvature_last, current_curvature, CS.out.vEgoRaw) + else: + apply_curvature = 0. + + self.apply_curvature_last = apply_curvature + + if self.CP.flags & FordFlags.CANFD: + # TODO: extended mode + # Ford uses four individual signals to dictate how to drive to the car. Curvature alone (limited to 0.02m/s^2) + # can actuate the steering for a large portion of any lateral movements. However, in order to get further control on + # steer actuation, the other three signals are necessary. Ford controls vehicles differently than most other makes. + # A detailed explanation on ford control can be found here: + # https://www.f150gen14.com/forum/threads/introducing-bluepilot-a-ford-specific-fork-for-comma3x-openpilot.24241/#post-457706 + mode = 1 if CC.latActive else 0 + counter = (self.frame // CarControllerParams.STEER_STEP) % 0x10 + can_sends.append(fordcan.create_lat_ctl2_msg(self.packer, self.CAN, mode, 0., 0., -apply_curvature, 0., counter)) + else: + can_sends.append(fordcan.create_lat_ctl_msg(self.packer, self.CAN, CC.latActive, 0., 0., -apply_curvature, 0.)) + + # send lka msg at 33Hz + if (self.frame % CarControllerParams.LKA_STEP) == 0: + can_sends.append(fordcan.create_lka_msg(self.packer, self.CAN)) + + ### longitudinal control ### + # send acc msg at 50Hz + if self.CP.openpilotLongitudinalControl and (self.frame % CarControllerParams.ACC_CONTROL_STEP) == 0: + accel = actuators.accel + gas = accel + + if CC.longActive: + # Compensate for engine creep at low speed. + # Either the ABS does not account for engine creep, or the correction is very slow + # TODO: verify this applies to EV/hybrid + accel = apply_creep_compensation(accel, CS.out.vEgo) + + # The stock system has been seen rate limiting the brake accel to 5 m/s^3, + # however even 3.5 m/s^3 causes some overshoot with a step response. + accel = max(accel, self.accel - (3.5 * CarControllerParams.ACC_CONTROL_STEP * DT_CTRL)) + + accel = clip(accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + + # Both gas and accel are in m/s^2, accel is used solely for braking + if not CC.longActive or gas < CarControllerParams.MIN_GAS: + gas = CarControllerParams.INACTIVE_GAS + + # PCM applies pitch compensation to gas/accel, but we need to compensate for the brake/pre-charge bits + accel_due_to_pitch = 0.0 + if len(CC.orientationNED) == 3: + accel_due_to_pitch = math.sin(CC.orientationNED[1]) * ACCELERATION_DUE_TO_GRAVITY + + accel_pitch_compensated = accel + accel_due_to_pitch + if accel_pitch_compensated > 0.3 or not CC.longActive: + self.brake_request = False + elif accel_pitch_compensated < 0.0: + self.brake_request = True + + stopping = CC.actuators.longControlState == LongCtrlState.stopping + # TODO: look into using the actuators packet to send the desired speed + can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping, self.brake_request, v_ego_kph=V_CRUISE_MAX)) + + self.accel = accel + self.gas = gas + + ### ui ### + send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) + # send lkas ui msg at 1Hz or if ui state changes + if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: + can_sends.append(fordcan.create_lkas_ui_msg(self.packer, self.CAN, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values)) + + # send acc ui msg at 5Hz or if ui state changes + if hud_control.leadDistanceBars != self.lead_distance_bars_last: + send_ui = True + self.distance_bar_frame = self.frame + + if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: + show_distance_bars = self.frame - self.distance_bar_frame < 400 + can_sends.append(fordcan.create_acc_ui_msg(self.packer, self.CAN, self.CP, main_on, CC.latActive, + fcw_alert, CS.out.cruiseState.standstill, show_distance_bars, + hud_control, CS.acc_tja_status_stock_values)) + + self.main_on_last = main_on + self.lkas_enabled_last = CC.latActive + self.steer_alert_last = steer_alert + self.lead_distance_bars_last = hud_control.leadDistanceBars + + new_actuators = actuators.as_builder() + new_actuators.curvature = self.apply_curvature_last + new_actuators.accel = self.accel + new_actuators.gas = self.gas + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/ford/carstate.py b/opendbc_repo/opendbc/car/ford/carstate.py new file mode 100644 index 000000000000000..832d4b73215828b --- /dev/null +++ b/opendbc_repo/opendbc/car/ford/carstate.py @@ -0,0 +1,176 @@ +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from opendbc.car import create_button_events, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.ford.fordcan import CanBus +from opendbc.car.ford.values import DBC, CarControllerParams, FordFlags +from opendbc.car.interfaces import CarStateBase + +ButtonType = structs.CarState.ButtonEvent.Type +GearShifter = structs.CarState.GearShifter +TransmissionType = structs.CarParams.TransmissionType + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + if CP.transmissionType == TransmissionType.automatic: + self.shifter_values = can_define.dv["PowertrainData_10"]["TrnRng_D_Rq"] + + self.distance_button = 0 + + def update(self, cp, cp_cam, *_) -> structs.CarState: + ret = structs.CarState() + + # 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 + ret.vehicleSensorsInvalid = cp.vl["SteeringPinion_Data"]["StePinCompAnEst_D_Qf"] != 3 + + # car speed + ret.vEgoRaw = cp.vl["BrakeSysFeatures"]["Veh_V_ActlBrk"] * CV.KPH_TO_MS + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] + ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1 + + # gas pedal + ret.gas = cp.vl["EngVehicleSpThrottle"]["ApedPos_Pc_ActlArb"] / 100. + ret.gasPressed = ret.gas > 1e-6 + + # brake pedal + ret.brake = cp.vl["BrakeSnData_4"]["BrkTot_Tq_Actl"] / 32756. # torque in Nm + ret.brakePressed = cp.vl["EngBrakeData"]["BpedDrvAppl_D_Actl"] == 2 + ret.parkingBrake = cp.vl["DesiredTorqBrk"]["PrkBrkStatus"] in (1, 2) + + # steering wheel + ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"] + ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"] + ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE, 5) + ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1 + ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) + ret.espDisabled = cp.vl["Cluster_Info1_FD1"]["DrvSlipCtlMde_D_Rq"] != 0 # 0 is default mode + + if self.CP.flags & FordFlags.CANFD: + # this signal is always 0 on non-CAN FD cars + ret.steerFaultTemporary |= cp.vl["Lane_Assist_Data3_FD1"]["LatCtlSte_D_Stat"] not in (1, 2, 3) + + # cruise state + is_metric = cp.vl["INSTRUMENT_PANEL"]["METRIC_UNITS"] == 1 if not self.CP.flags & FordFlags.CANFD else False + ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * (CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS) + ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5) + ret.cruiseState.available = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (3, 4, 5) + ret.cruiseState.nonAdaptive = cp.vl["Cluster_Info1_FD1"]["AccEnbl_B_RqDrv"] == 0 + ret.cruiseState.standstill = cp.vl["EngBrakeData"]["AccStopMde_D_Rq"] == 3 + ret.accFaulted = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (1, 2) + if not self.CP.openpilotLongitudinalControl: + ret.accFaulted = ret.accFaulted or cp_cam.vl["ACCDATA"]["CmbbDeny_B_Actl"] == 1 + + # gear + if self.CP.transmissionType == TransmissionType.automatic: + gear = self.shifter_values.get(cp.vl["PowertrainData_10"]["TrnRng_D_Rq"]) + ret.gearShifter = self.parse_gear_shifter(gear) + elif self.CP.transmissionType == TransmissionType.manual: + ret.clutchPressed = cp.vl["Engine_Clutch_Data"]["CluPdlPos_Pc_Meas"] > 0 + if bool(cp.vl["BCM_Lamp_Stat_FD1"]["RvrseLghtOn_B_Stat"]): + ret.gearShifter = GearShifter.reverse + else: + ret.gearShifter = GearShifter.drive + + ret.engineRpm = cp.vl["EngVehicleSpThrottle"]["EngAout_N_Actl"] + + # safety + ret.stockFcw = bool(cp_cam.vl["ACCDATA_3"]["FcwVisblWarn_B_Rq"]) + ret.stockAeb = bool(cp_cam.vl["ACCDATA_2"]["CmbbBrkDecel_B_Rq"]) + + # button presses + ret.leftBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 1 + ret.rightBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 2 + # TODO: block this going to the camera otherwise it will enable stock TJA + ret.genericToggle = bool(cp.vl["Steering_Data_FD1"]["TjaButtnOnOffPress"]) + prev_distance_button = self.distance_button + self.distance_button = cp.vl["Steering_Data_FD1"]["AccButtnGapTogglePress"] + + # lock info + ret.doorOpen = any([cp.vl["BodyInfo_3_FD1"]["DrStatDrv_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatPsngr_B_Actl"], + cp.vl["BodyInfo_3_FD1"]["DrStatRl_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatRr_B_Actl"]]) + ret.seatbeltUnlatched = cp.vl["RCMStatusMessage2_FD1"]["FirstRowBuckleDriver"] == 2 + + # blindspot sensors + if self.CP.enableBsm: + cp_bsm = cp_cam if self.CP.flags & FordFlags.CANFD else cp + ret.leftBlindspot = cp_bsm.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 + ret.rightBlindspot = cp_bsm.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 + + # Stock steering buttons so that we can passthru blinkers etc. + self.buttons_stock_values = cp.vl["Steering_Data_FD1"] + # Stock values from IPMA so that we can retain some stock functionality + self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"] + self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"] + + ret.buttonEvents = create_button_events(self.distance_button, prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("VehicleOperatingModes", 100), + ("BrakeSysFeatures", 50), + ("Yaw_Data_FD1", 100), + ("DesiredTorqBrk", 50), + ("EngVehicleSpThrottle", 100), + ("BrakeSnData_4", 50), + ("EngBrakeData", 10), + ("Cluster_Info1_FD1", 10), + ("SteeringPinion_Data", 100), + ("EPAS_INFO", 50), + ("Steering_Data_FD1", 10), + ("BodyInfo_3_FD1", 2), + ("RCMStatusMessage2_FD1", 10), + ] + + if CP.flags & FordFlags.CANFD: + messages += [ + ("Lane_Assist_Data3_FD1", 33), + ] + else: + messages += [ + ("INSTRUMENT_PANEL", 1), + ] + + if CP.transmissionType == TransmissionType.automatic: + messages += [ + ("PowertrainData_10", 10), + ] + elif CP.transmissionType == TransmissionType.manual: + messages += [ + ("Engine_Clutch_Data", 33), + ("BCM_Lamp_Stat_FD1", 1), + ] + + if CP.enableBsm and not (CP.flags & FordFlags.CANFD): + messages += [ + ("Side_Detect_L_Stat", 5), + ("Side_Detect_R_Stat", 5), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).main) + + @staticmethod + def get_cam_can_parser(CP): + messages = [ + # sig_address, frequency + ("ACCDATA", 50), + ("ACCDATA_2", 50), + ("ACCDATA_3", 5), + ("IPMA_Data", 1), + ] + + if CP.enableBsm and CP.flags & FordFlags.CANFD: + messages += [ + ("Side_Detect_L_Stat", 5), + ("Side_Detect_R_Stat", 5), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) diff --git a/opendbc_repo/opendbc/car/ford/fingerprints.py b/opendbc_repo/opendbc/car/ford/fingerprints.py new file mode 100644 index 000000000000000..c14c836669b85a7 --- /dev/null +++ b/opendbc_repo/opendbc/car/ford/fingerprints.py @@ -0,0 +1,166 @@ +from opendbc.car.structs import CarParams +from opendbc.car.ford.values import CAR + +Ecu = CarParams.Ecu + +FW_VERSIONS = { + CAR.FORD_BRONCO_SPORT_MK1: { + (Ecu.eps, 0x730, None): [ + b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LX6C-2D053-RD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-RE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-RF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'M1PT-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1PT-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_ESCAPE_MK4: { + (Ecu.eps, 0x730, None): [ + b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-NT\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-SA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-SD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LV4T-14F397-GG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_EXPLORER_MK6: { + (Ecu.eps, 0x730, None): [ + b'L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1MC-14D003-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'P1MC-14D003-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'L1MC-2D053-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LC5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_F_150_MK14: { + (Ecu.eps, 0x730, None): [ + b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'ML3T-14H102-ABR\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_F_150_LIGHTNING_MK1: { + (Ecu.abs, 0x760, None): [ + b'PL38-2D053-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'ML3T-14H102-ABT\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_MUSTANG_MACH_E_MK1: { + (Ecu.eps, 0x730, None): [ + b'LJ9C-14D003-AM\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LJ9C-14D003-CC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LK9C-2D053-CK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'ML3T-14H102-ABS\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_FOCUS_MK4: { + (Ecu.eps, 0x730, None): [ + b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'JX7T-14D049-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'JX7T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_MAVERICK_MK1: { + (Ecu.eps, 0x730, None): [ + b'NZ6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'NZ6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'NZ6C-2D053-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-ED\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-EE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-EF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_RANGER_MK2: { + (Ecu.eps, 0x730, None): [ + b'NL14-14D003-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'PB3C-2D053-ZD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, +} diff --git a/selfdrive/car/ford/fordcan.py b/opendbc_repo/opendbc/car/ford/fordcan.py similarity index 91% rename from selfdrive/car/ford/fordcan.py rename to opendbc_repo/opendbc/car/ford/fordcan.py index 2cfd61a1919973e..2ac68c442751cd8 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/opendbc_repo/opendbc/car/ford/fordcan.py @@ -1,7 +1,6 @@ -from cereal import car -from openpilot.selfdrive.car import CanBusBase +from opendbc.car import CanBusBase, structs -HUDControl = car.CarControl.HUDControl +HUDControl = structs.CarControl.HUDControl class CanBus(CanBusBase): @@ -38,7 +37,7 @@ def create_lka_msg(packer, CAN: CanBus): """ Creates an empty CAN message for the Ford LKA Command. - This command can apply "Lane Keeping Aid" manoeuvres, which are subject to the PSCM lockout. + This command can apply "Lane Keeping Aid" maneuvers, which are subject to the PSCM lockout. Frequency is 33Hz. """ @@ -51,7 +50,7 @@ def create_lat_ctl_msg(packer, CAN: CanBus, lat_active: bool, path_offset: float """ Creates a CAN message for the Ford TJA/LCA Command. - This command can apply "Lane Centering" manoeuvres: continuous lane centering for traffic jam assist and highway + This command can apply "Lane Centering" maneuvers: continuous lane centering for traffic jam assist and highway driving. It is not subject to the PSCM lockout. Ford lane centering command uses a third order polynomial to describe the road centerline. The polynomial is defined @@ -112,13 +111,13 @@ def create_lat_ctl2_msg(packer, CAN: CanBus, mode: int, path_offset: float, path } # calculate checksum - dat = packer.make_can_msg("LateralMotionControl2", 0, values)[2] + dat = packer.make_can_msg("LateralMotionControl2", 0, values)[1] values["LatCtlPath_No_Cs"] = calculate_lat_ctl2_checksum(mode, counter, dat) return packer.make_can_msg("LateralMotionControl2", CAN.main, values) -def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool, v_ego_kph: float): +def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool, brake_request, v_ego_kph: float): """ Creates a CAN message for the Ford ACC Command. @@ -127,24 +126,27 @@ 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 + # No observed acceleration seen from this signal alone. During stock system operation, it appears to + # be the raw acceleration request (AccPrpl_A_Rq when positive, AccBrkTot_A_Rq when negative) "AccPrpl_A_Pred": -5.0, # Acceleration request: [-5|5.23] m/s^2 "AccResumEnbl_B_Rq": 1 if long_active else 0, + # No observed acceleration seen from this signal alone "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 + # When setting these two bits without AccBrkTot_A_Rq, an initial jerk is observed and car may be able to brake temporarily with AccPrpl_A_Rq + "AccBrkPrchg_B_Rq": 1 if brake_request else 0, # Pre-charge brake request: 0=No, 1=Yes + "AccBrkDecel_B_Rq": 1 if brake_request else 0, # Deceleration request: 0=Inactive, 1=Active "AccStopStat_B_Rq": 1 if stopping else 0, } return packer.make_can_msg("ACCDATA", CAN.main, values) def create_acc_ui_msg(packer, CAN: CanBus, CP, main_on: bool, enabled: bool, fcw_alert: bool, standstill: bool, - hud_control, stock_values: dict): + show_distance_bars: bool, hud_control, stock_values: dict): """ Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam assist status. @@ -208,7 +210,7 @@ def create_acc_ui_msg(packer, CAN: CanBus, CP, main_on: bool, enabled: bool, fcw values.update({ "AccStopStat_D_Dsply": 2 if standstill else 0, # Stopping status text "AccMsgTxt_D2_Rq": 0, # ACC text - "AccTGap_B_Dsply": 0, # Show time gap control UI + "AccTGap_B_Dsply": 1 if show_distance_bars else 0, # Show time gap control UI "AccFllwMde_B_Dsply": 1 if hud_control.leadVisible else 0, # Lead indicator "AccStopMde_B_Dsply": 1 if standstill else 0, "AccWarn_D_Dsply": 0, # ACC warning diff --git a/opendbc_repo/opendbc/car/ford/interface.py b/opendbc_repo/opendbc/car/ford/interface.py new file mode 100644 index 000000000000000..92c89f4f6d4cd2d --- /dev/null +++ b/opendbc_repo/opendbc/car/ford/interface.py @@ -0,0 +1,83 @@ +from panda import Panda +from opendbc.car.common.numpy_fast import interp +from opendbc.car import get_safety_config, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.ford.fordcan import CanBus +from opendbc.car.ford.values import CarControllerParams, DBC, Ecu, FordFlags, RADAR +from opendbc.car.interfaces import CarInterfaceBase + +TransmissionType = structs.CarParams.TransmissionType + + +class CarInterface(CarInterfaceBase): + @staticmethod + def get_pid_accel_limits(CP, current_speed, cruise_speed): + # PCM doesn't allow acceleration near cruise_speed, + # so limit limits of pid to prevent windup + ACCEL_MAX_VALS = [CarControllerParams.ACCEL_MAX, 0.2] + ACCEL_MAX_BP = [cruise_speed - 2., cruise_speed - .4] + return CarControllerParams.ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) + + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "ford" + ret.dashcamOnly = bool(ret.flags & FordFlags.CANFD) + + ret.radarUnavailable = DBC[candidate]['radar'] is None + ret.steerControlType = structs.CarParams.SteerControlType.angle + ret.steerActuatorDelay = 0.2 + ret.steerLimitTimer = 1.0 + + ret.longitudinalTuning.kiBP = [0.] + ret.longitudinalTuning.kiV = [0.5] + + if DBC[candidate]['radar'] == RADAR.DELPHI_MRR: + # average of 33.3 Hz radar timestep / 4 scan modes = 60 ms + # MRR_Header_Timestamps->CAN_DET_TIME_SINCE_MEAS reports 61.3 ms + ret.radarDelay = 0.06 + + CAN = CanBus(fingerprint=fingerprint) + cfgs = [get_safety_config(structs.CarParams.SafetyModel.ford)] + if CAN.main >= 4: + cfgs.insert(0, get_safety_config(structs.CarParams.SafetyModel.noOutput)) + ret.safetyConfigs = cfgs + + # TODO: verify stock AEB compatibility and longitudinal limit safety before shipping to release + ret.experimentalLongitudinalAvailable = ret.radarUnavailable + if experimental_long or not ret.radarUnavailable: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_LONG_CONTROL + ret.openpilotLongitudinalControl = True + + if ret.flags & FordFlags.CANFD: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_CANFD + else: + # Lock out if the car does not have needed lateral and longitudinal control APIs. + # Note that we also check CAN for adaptive cruise, but no known signal for LCA exists + pscm_config = next((fw for fw in car_fw if fw.ecu == Ecu.eps and b'\x22\xDE\x01' in fw.request), None) + if pscm_config: + if len(pscm_config.fwVersion) != 24: + ret.dashcamOnly = True + else: + config_tja = pscm_config.fwVersion[7] # Traffic Jam Assist + config_lca = pscm_config.fwVersion[8] # Lane Centering Assist + if config_tja != 0xFF or config_lca != 0xFF: + ret.dashcamOnly = True + + # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1 + found_ecus = [fw.ecu for fw in car_fw] + if Ecu.shiftByWire in found_ecus or 0x5A in fingerprint[CAN.main] or docs: + ret.transmissionType = TransmissionType.automatic + else: + ret.transmissionType = TransmissionType.manual + ret.minEnableSpeed = 20.0 * CV.MPH_TO_MS + + # BSM: Side_Detect_L_Stat, Side_Detect_R_Stat + # TODO: detect bsm in car_fw? + ret.enableBsm = 0x3A6 in fingerprint[CAN.main] and 0x3A7 in fingerprint[CAN.main] + + # LCA can steer down to zero + ret.minSteerSpeed = 0. + + ret.autoResumeSng = ret.minEnableSpeed == -1. + ret.centerToFront = ret.wheelbase * 0.44 + return ret diff --git a/opendbc_repo/opendbc/car/ford/radar_interface.py b/opendbc_repo/opendbc/car/ford/radar_interface.py new file mode 100644 index 000000000000000..b5e98867c969c5c --- /dev/null +++ b/opendbc_repo/opendbc/car/ford/radar_interface.py @@ -0,0 +1,253 @@ +import numpy as np +from typing import cast +from collections import defaultdict +from math import cos, sin +from dataclasses import dataclass +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.ford.fordcan import CanBus +from opendbc.car.ford.values import DBC, RADAR +from opendbc.car.interfaces import RadarInterfaceBase + +DELPHI_ESR_RADAR_MSGS = list(range(0x500, 0x540)) + +DELPHI_MRR_RADAR_START_ADDR = 0x120 +DELPHI_MRR_RADAR_HEADER_ADDR = 0x174 # MRR_Header_SensorCoverage +DELPHI_MRR_RADAR_MSG_COUNT = 64 + +DELPHI_MRR_RADAR_RANGE_COVERAGE = {0: 42, 1: 164, 2: 45, 3: 175} # scan index to detection range (m) +DELPHI_MRR_MIN_LONG_RANGE_DIST = 30 # meters +DELPHI_MRR_CLUSTER_THRESHOLD = 5 # meters, lateral distance and relative velocity are weighted + + +@dataclass +class Cluster: + dRel: float = 0.0 + yRel: float = 0.0 + vRel: float = 0.0 + trackId: int = 0 + + +def cluster_points(pts_l: list[list[float]], pts2_l: list[list[float]], max_dist: float) -> list[int]: + """ + Clusters a collection of points based on another collection of points. This is useful for correlating clusters through time. + Points in pts2 not close enough to any point in pts are assigned -1. + Args: + pts_l: List of points to base the new clusters on + pts2_l: List of points to cluster using pts + max_dist: Max distance from cluster center to candidate point + + Returns: + List of cluster indices for pts2 that correspond to pts + """ + + if not len(pts2_l): + return [] + + if not len(pts_l): + return [-1] * len(pts2_l) + + max_dist_sq = max_dist ** 2 + pts = np.array(pts_l) + pts2 = np.array(pts2_l) + + # Compute squared norms + pts_norm_sq = np.sum(pts ** 2, axis=1) + pts2_norm_sq = np.sum(pts2 ** 2, axis=1) + + # Compute squared Euclidean distances using the identity + # dist_sq[i, j] = ||pts2[i]||^2 + ||pts[j]||^2 - 2 * pts2[i] . pts[j] + dist_sq = pts2_norm_sq[:, np.newaxis] + pts_norm_sq[np.newaxis, :] - 2 * np.dot(pts2, pts.T) + dist_sq = np.maximum(dist_sq, 0.0) + + # Find the closest cluster for each point and assign its index + closest_clusters = np.argmin(dist_sq, axis=1) + closest_dist_sq = dist_sq[np.arange(len(pts2)), closest_clusters] + cluster_idxs = np.where(closest_dist_sq < max_dist_sq, closest_clusters, -1) + + return cast(list[int], cluster_idxs.tolist()) + + +def _create_delphi_esr_radar_can_parser(CP) -> CANParser: + msg_n = len(DELPHI_ESR_RADAR_MSGS) + messages = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n, strict=True)) + + return CANParser(RADAR.DELPHI_ESR, messages, CanBus(CP).radar) + + +def _create_delphi_mrr_radar_can_parser(CP) -> CANParser: + messages = [ + ("MRR_Header_InformationDetections", 33), + ("MRR_Header_SensorCoverage", 33), + ] + + for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): + msg = f"MRR_Detection_{i:03d}" + messages += [(msg, 33)] + + return CANParser(RADAR.DELPHI_MRR, messages, CanBus(CP).radar) + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + + self.points: list[list[float]] = [] + self.clusters: list[Cluster] = [] + + self.updated_messages = set() + self.track_id = 0 + self.radar = DBC[CP.carFingerprint]['radar'] + if CP.radarUnavailable: + self.rcp = None + elif self.radar == RADAR.DELPHI_ESR: + self.rcp = _create_delphi_esr_radar_can_parser(CP) + self.trigger_msg = DELPHI_ESR_RADAR_MSGS[-1] + self.valid_cnt = {key: 0 for key in DELPHI_ESR_RADAR_MSGS} + elif self.radar == RADAR.DELPHI_MRR: + self.rcp = _create_delphi_mrr_radar_can_parser(CP) + self.trigger_msg = DELPHI_MRR_RADAR_HEADER_ADDR + else: + raise ValueError(f"Unsupported radar: {self.radar}") + + def update(self, can_strings): + if self.rcp is None: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + self.updated_messages.clear() + + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + + if self.radar == RADAR.DELPHI_ESR: + self._update_delphi_esr() + elif self.radar == RADAR.DELPHI_MRR: + _update, _errors = self._update_delphi_mrr() + errors.extend(_errors) + if not _update: + return None + + ret = structs.RadarData() + ret.points = list(self.pts.values()) + ret.errors = errors + return ret + + def _update_delphi_esr(self): + for ii in sorted(self.updated_messages): + cpt = self.rcp.vl[ii] + + if cpt['X_Rel'] > 0.00001: + self.valid_cnt[ii] = 0 # reset counter + + if cpt['X_Rel'] > 0.00001: + self.valid_cnt[ii] += 1 + else: + self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) + #print ii, self.valid_cnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] + + # radar point only valid if there have been enough valid measurements + if self.valid_cnt[ii] > 0: + if ii not in self.pts: + self.pts[ii] = structs.RadarData.RadarPoint() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['X_Rel'] # from front of car + self.pts[ii].yRel = cpt['X_Rel'] * cpt['Angle'] * CV.DEG_TO_RAD # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['V_Rel'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = True + else: + if ii in self.pts: + del self.pts[ii] + + def _update_delphi_mrr(self): + headerScanIndex = int(self.rcp.vl["MRR_Header_InformationDetections"]['CAN_SCAN_INDEX']) & 0b11 + + # Use points with Doppler coverage of +-60 m/s, reduces similar points + if headerScanIndex in (0, 1): + return False, [] + + errors = [] + if DELPHI_MRR_RADAR_RANGE_COVERAGE[headerScanIndex] != int(self.rcp.vl["MRR_Header_SensorCoverage"]["CAN_RANGE_COVERAGE"]): + errors.append("wrongConfig") + + for ii in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): + msg = self.rcp.vl[f"MRR_Detection_{ii:03d}"] + + # SCAN_INDEX rotates through 0..3 on each message for different measurement modes + # Indexes 0 and 2 have a max range of ~40m, 1 and 3 are ~170m (MRR_Header_SensorCoverage->CAN_RANGE_COVERAGE) + # Indexes 0 and 1 have a Doppler coverage of +-71 m/s, 2 and 3 have +-60 m/s + scanIndex = msg[f"CAN_SCAN_INDEX_2LSB_{ii:02d}"] + + # Throw out old measurements. Very unlikely to happen, but is proper behavior + if scanIndex != headerScanIndex: + continue + + valid = bool(msg[f"CAN_DET_VALID_LEVEL_{ii:02d}"]) + + # Long range measurement mode is more sensitive and can detect the road surface + dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] + if scanIndex in (1, 3) and dist < DELPHI_MRR_MIN_LONG_RANGE_DIST: + valid = False + + if valid: + azimuth = msg[f"CAN_DET_AZIMUTH_{ii:02d}"] # rad [-3.1416|3.13964] + 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 + + self.points.append([dRel, yRel * 2, distRate * 2]) + + # Update once we've cycled through all 4 scan modes + if headerScanIndex != 3: + return False, [] + + # Cluster points from this cycle against the centroids from the previous cycle + prev_keys = [[p.dRel, p.yRel * 2, p.vRel * 2] for p in self.clusters] + labels = cluster_points(prev_keys, self.points, DELPHI_MRR_CLUSTER_THRESHOLD) + + points_by_track_id = defaultdict(list) + for idx, label in enumerate(labels): + if label != -1: + points_by_track_id[self.clusters[label].trackId].append(self.points[idx]) + else: + points_by_track_id[self.track_id].append(self.points[idx]) + self.track_id += 1 + + self.clusters = [] + for idx, (track_id, pts) in enumerate(points_by_track_id.items()): + dRel = [p[0] for p in pts] + min_dRel = min(dRel) + dRel = sum(dRel) / len(dRel) + + yRel = [p[1] for p in pts] + yRel = sum(yRel) / len(yRel) / 2 + + vRel = [p[2] for p in pts] + vRel = sum(vRel) / len(vRel) / 2 + + # FIXME: creating capnp RadarPoint and accessing attributes are both expensive, so we store a dataclass and reuse the RadarPoint + self.clusters.append(Cluster(dRel=dRel, yRel=yRel, vRel=vRel, trackId=track_id)) + + if idx not in self.pts: + self.pts[idx] = structs.RadarData.RadarPoint(measured=True, aRel=float('nan'), yvRel=float('nan')) + + self.pts[idx].dRel = min_dRel + self.pts[idx].yRel = yRel + self.pts[idx].vRel = vRel + self.pts[idx].trackId = track_id + + for idx in range(len(points_by_track_id), len(self.pts)): + del self.pts[idx] + + self.points = [] + + return True, errors diff --git a/selfdrive/car/gm/__init__.py b/opendbc_repo/opendbc/car/ford/tests/__init__.py similarity index 100% rename from selfdrive/car/gm/__init__.py rename to opendbc_repo/opendbc/car/ford/tests/__init__.py diff --git a/opendbc_repo/opendbc/car/ford/tests/print_platform_codes.py b/opendbc_repo/opendbc/car/ford/tests/print_platform_codes.py new file mode 100755 index 000000000000000..dfb93c06fdd7c33 --- /dev/null +++ b/opendbc_repo/opendbc/car/ford/tests/print_platform_codes.py @@ -0,0 +1,28 @@ +#!/usr/bin/env python3 +from collections import defaultdict + +from opendbc.car.structs import CarParams +from opendbc.car.ford.values import get_platform_codes +from opendbc.car.ford.fingerprints import FW_VERSIONS + +Ecu = CarParams.Ecu + +if __name__ == "__main__": + cars_for_code: defaultdict = defaultdict(lambda: defaultdict(set)) + + for car_model, ecus in FW_VERSIONS.items(): + print(car_model) + for ecu in sorted(ecus): + platform_codes = get_platform_codes(ecus[ecu]) + for code in platform_codes: + cars_for_code[ecu][code].add(car_model) + + print(f' (Ecu.{ecu[0]}, {hex(ecu[1])}, {ecu[2]}):') + print(f' Codes: {sorted(platform_codes)}') + print() + + print('\nCar models vs. platform codes:') + for ecu, codes in cars_for_code.items(): + print(f' (Ecu.{ecu[0]}, {hex(ecu[1])}, {ecu[2]}):') + for code, cars in codes.items(): + print(f' {code!r}: {sorted(map(str, cars))}') diff --git a/selfdrive/car/ford/tests/test_ford.py b/opendbc_repo/opendbc/car/ford/tests/test_ford.py similarity index 90% rename from selfdrive/car/ford/tests/test_ford.py rename to opendbc_repo/opendbc/car/ford/tests/test_ford.py index b1a19017d401b09..5e3cc420b4f0104 100644 --- a/selfdrive/car/ford/tests/test_ford.py +++ b/opendbc_repo/opendbc/car/ford/tests/test_ford.py @@ -1,16 +1,15 @@ import random from collections.abc import Iterable -import capnp from hypothesis import settings, given, strategies as st from parameterized import parameterized -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.ford.values import CAR, FW_QUERY_CONFIG, FW_PATTERN, get_platform_codes -from openpilot.selfdrive.car.ford.fingerprints import FW_VERSIONS +from opendbc.car.structs import CarParams +from opendbc.car.fw_versions import build_fw_dict +from opendbc.car.ford.values import CAR, FW_QUERY_CONFIG, FW_PATTERN, get_platform_codes +from opendbc.car.ford.fingerprints import FW_VERSIONS -Ecu = car.CarParams.Ecu +Ecu = CarParams.Ecu ECU_ADDRESSES = { @@ -49,7 +48,7 @@ def test_fw_query_config(self): assert subaddr is None, "Unexpected ECU subaddress" @parameterized.expand(FW_VERSIONS.items()) - def test_fw_versions(self, car_model: str, fw_versions: dict[tuple[capnp.lib.capnp._EnumModule, int, int | None], Iterable[bytes]]): + def test_fw_versions(self, car_model: str, fw_versions: dict[tuple[int, int, int | None], Iterable[bytes]]): for (ecu, addr, subaddr), fws in fw_versions.items(): assert ecu in ECU_PART_NUMBER, "Unexpected ECU" assert addr == ECU_ADDRESSES[ecu], "ECU address mismatch" @@ -93,10 +92,10 @@ def test_fuzzy_match(self): for ecu, fw_versions in fw_by_addr.items(): ecu_name, addr, sub_addr = ecu fw = random.choice(fw_versions) - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) + car_fw.append(CarParams.CarFw(ecu=ecu_name, fwVersion=fw, address=addr, + subAddress=0 if sub_addr is None else sub_addr)) - CP = car.CarParams.new_message(carFw=car_fw) + CP = CarParams(carFw=car_fw) matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) assert matches == {platform} diff --git a/opendbc_repo/opendbc/car/ford/values.py b/opendbc_repo/opendbc/car/ford/values.py new file mode 100644 index 000000000000000..20cd4d6774a301b --- /dev/null +++ b/opendbc_repo/opendbc/car/ford/values.py @@ -0,0 +1,280 @@ +import copy +import re +from dataclasses import dataclass, field, replace +from enum import Enum, IntFlag + +from panda import uds +from opendbc.car import AngleRateLimit, CarSpecs, dbc_dict, DbcDict, PlatformConfig, Platforms +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ + Device, SupportType +from opendbc.car.fw_query_definitions import FwQueryConfig, LiveFwVersions, OfflineFwVersions, Request, StdQueries, p16 + +Ecu = CarParams.Ecu + + +class CarControllerParams: + STEER_STEP = 5 # LateralMotionControl, 20Hz + LKA_STEP = 3 # Lane_Assist_Data1, 33Hz + ACC_CONTROL_STEP = 2 # ACCDATA, 50Hz + LKAS_UI_STEP = 100 # IPMA_Data, 1Hz + ACC_UI_STEP = 20 # ACCDATA_3, 5Hz + BUTTONS_STEP = 5 # Steering_Data_FD1, 10Hz, but send twice as fast + + CURVATURE_MAX = 0.02 # Max curvature for steering command, m^-1 + STEER_DRIVER_ALLOWANCE = 1.0 # Driver intervention threshold, Nm + + # Curvature rate limits + # Max curvature is limited by the EPS to an equivalent of ~2.0 m/s^2 at all speeds, + # however max curvature rate linearly decreases as speed increases: + # ~0.009 m^-1/sec at 7 m/s, ~0.002 m^-1/sec at 35 m/s + # Limit to ~2 m/s^3 up, ~3.3 m/s^3 down at 75 mph and match EPS limit at low speed + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.00045, 0.0001]) + ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.00045, 0.00015]) + CURVATURE_ERROR = 0.002 # ~6 degrees at 10 m/s, ~10 degrees at 35 m/s + + ACCEL_MAX = 2.0 # m/s^2 max acceleration + ACCEL_MIN = -3.5 # m/s^2 max deceleration + MIN_GAS = -0.5 + INACTIVE_GAS = -5.0 + + def __init__(self, CP): + pass + + +class FordFlags(IntFlag): + # Static flags + CANFD = 1 + + +class RADAR: + DELPHI_ESR = 'ford_fusion_2018_adas' + DELPHI_MRR = 'FORD_CADS' + + +class Footnote(Enum): + FOCUS = CarFootnote( + "Refers only to the Focus Mk4 (C519) available in Europe/China/Taiwan/Australasia, not the Focus Mk3 (C346) in " + + "North and South America/Southeast Asia.", + Column.MODEL, + ) + + +@dataclass +class FordCarDocs(CarDocs): + package: str = "Co-Pilot360 Assist+" + hybrid: bool = False + plug_in_hybrid: bool = False + + def init_make(self, CP: CarParams): + harness = CarHarness.ford_q4 if CP.flags & FordFlags.CANFD else CarHarness.ford_q3 + if CP.carFingerprint in (CAR.FORD_BRONCO_SPORT_MK1, CAR.FORD_MAVERICK_MK1, CAR.FORD_F_150_MK14, CAR.FORD_F_150_LIGHTNING_MK1): + self.car_parts = CarParts([Device.threex_angled_mount, harness]) + else: + self.car_parts = CarParts([Device.threex, harness]) + + +@dataclass +class FordPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR)) + + def init(self): + for car_docs in list(self.car_docs): + if car_docs.hybrid: + name = f"{car_docs.make} {car_docs.model} Hybrid {car_docs.years}" + self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) + if car_docs.plug_in_hybrid: + name = f"{car_docs.make} {car_docs.model} Plug-in Hybrid {car_docs.years}" + self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) + + +@dataclass +class FordCANFDPlatformConfig(FordPlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', None)) + + def init(self): + super().init() + self.flags |= FordFlags.CANFD + + +class CAR(Platforms): + FORD_BRONCO_SPORT_MK1 = FordPlatformConfig( + [FordCarDocs("Ford Bronco Sport 2021-24")], + CarSpecs(mass=1625, wheelbase=2.67, steerRatio=17.7), + ) + FORD_ESCAPE_MK4 = FordPlatformConfig( + [ + FordCarDocs("Ford Escape 2020-22", hybrid=True, plug_in_hybrid=True), + FordCarDocs("Ford Kuga 2020-22", "Adaptive Cruise Control with Lane Centering", hybrid=True, plug_in_hybrid=True), + ], + CarSpecs(mass=1750, wheelbase=2.71, steerRatio=16.7), + ) + FORD_EXPLORER_MK6 = FordPlatformConfig( + [ + FordCarDocs("Ford Explorer 2020-24", hybrid=True), # Hybrid: Limited and Platinum only + FordCarDocs("Lincoln Aviator 2020-24", "Co-Pilot360 Plus", plug_in_hybrid=True), # Hybrid: Grand Touring only + ], + CarSpecs(mass=2050, wheelbase=3.025, steerRatio=16.8), + ) + FORD_F_150_MK14 = FordCANFDPlatformConfig( + [FordCarDocs("Ford F-150 2022-23", "Co-Pilot360 Active 2.0", hybrid=True, support_type=SupportType.REVIEW)], + CarSpecs(mass=2000, wheelbase=3.69, steerRatio=17.0), + ) + FORD_F_150_LIGHTNING_MK1 = FordCANFDPlatformConfig( + [FordCarDocs("Ford F-150 Lightning 2021-23", "Co-Pilot360 Active 2.0", support_type=SupportType.REVIEW)], + CarSpecs(mass=2948, wheelbase=3.70, steerRatio=16.9), + ) + FORD_FOCUS_MK4 = FordPlatformConfig( + [FordCarDocs("Ford Focus 2018", "Adaptive Cruise Control with Lane Centering", footnotes=[Footnote.FOCUS], hybrid=True)], # mHEV only + CarSpecs(mass=1350, wheelbase=2.7, steerRatio=15.0), + ) + FORD_MAVERICK_MK1 = FordPlatformConfig( + [ + FordCarDocs("Ford Maverick 2022", "LARIAT Luxury", hybrid=True), + FordCarDocs("Ford Maverick 2023-24", "Co-Pilot360 Assist", hybrid=True), + ], + CarSpecs(mass=1650, wheelbase=3.076, steerRatio=17.0), + ) + FORD_MUSTANG_MACH_E_MK1 = FordCANFDPlatformConfig( + [FordCarDocs("Ford Mustang Mach-E 2021-23", "Co-Pilot360 Active 2.0", support_type=SupportType.REVIEW)], + CarSpecs(mass=2200, wheelbase=2.984, steerRatio=17.0), # TODO: check steer ratio + ) + FORD_RANGER_MK2 = FordCANFDPlatformConfig( + [FordCarDocs("Ford Ranger 2024", "Adaptive Cruise Control with Lane Centering", support_type=SupportType.REVIEW)], + CarSpecs(mass=2000, wheelbase=3.27, steerRatio=17.0), + ) + + +# FW response contains a combined software and part number +# A-Z except no I, O or W +# e.g. NZ6A-14C204-AAA +# 1222-333333-444 +# 1 = Model year hint (approximates model year/generation) +# 2 = Platform hint +# 3 = Part number +# 4 = Software version +FW_ALPHABET = b'A-HJ-NP-VX-Z' +FW_PATTERN = re.compile(b'^(?P[' + FW_ALPHABET + b'])' + + b'(?P[0-9' + FW_ALPHABET + b']{3})-' + + b'(?P[0-9' + FW_ALPHABET + b']{5,6})-' + + b'(?P[' + FW_ALPHABET + b']{2,})\x00*$') + + +def get_platform_codes(fw_versions: list[bytes] | set[bytes]) -> set[tuple[bytes, bytes]]: + codes = set() + for fw in fw_versions: + match = FW_PATTERN.match(fw) + if match is not None: + codes.add((match.group('platform_hint'), match.group('model_year_hint'))) + + return codes + + +def match_fw_to_car_fuzzy(live_fw_versions: LiveFwVersions, vin: str, offline_fw_versions: OfflineFwVersions) -> set[str]: + candidates: set[str] = set() + + for candidate, fws in offline_fw_versions.items(): + # Keep track of ECUs which pass all checks (platform hint, within model year hint range) + valid_found_ecus = set() + valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} + for ecu, expected_versions in fws.items(): + addr = ecu[1:] + # Only check ECUs expected to have platform codes + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + # Expected platform codes & model year hints + codes = get_platform_codes(expected_versions) + expected_platform_codes = {code for code, _ in codes} + expected_model_year_hints = {model_year_hint for _, model_year_hint in codes} + + # Found platform codes & model year hints + codes = get_platform_codes(live_fw_versions.get(addr, set())) + found_platform_codes = {code for code, _ in codes} + found_model_year_hints = {model_year_hint for _, model_year_hint in codes} + + # Check platform code matches for any found versions + if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): + break + + # Check any model year hint within range in the database. Note that some models have more than one + # platform code per ECU which we don't consider as separate ranges + if not any(min(expected_model_year_hints) <= found_model_year_hint <= max(expected_model_year_hints) for + found_model_year_hint in found_model_year_hints): + break + + valid_found_ecus.add(addr) + + # If all live ECUs pass all checks for candidate, add it as a match + if valid_expected_ecus.issubset(valid_found_ecus): + candidates.add(candidate) + + return candidates + + +# All of these ECUs must be present and are expected to have platform codes we can match +PLATFORM_CODE_ECUS = (Ecu.abs, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps) + +DATA_IDENTIFIER_FORD_ASBUILT = 0xDE00 + +ASBUILT_BLOCKS: list[tuple[int, list]] = [ + (1, [Ecu.debug, Ecu.fwdCamera, Ecu.eps]), + (2, [Ecu.abs, Ecu.debug, Ecu.eps]), + (3, [Ecu.abs, Ecu.debug, Ecu.eps]), + (4, [Ecu.debug, Ecu.fwdCamera]), + (5, [Ecu.debug]), + (6, [Ecu.debug]), + (7, [Ecu.debug]), + (8, [Ecu.debug]), + (9, [Ecu.debug]), + (16, [Ecu.debug, Ecu.fwdCamera]), + (18, [Ecu.fwdCamera]), + (20, [Ecu.fwdCamera]), + (21, [Ecu.fwdCamera]), +] + + +def ford_asbuilt_block_request(block_id: int): + return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) + + +def ford_asbuilt_block_response(block_id: int): + return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) + + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + # CAN and CAN FD queries are combined. + # FIXME: For CAN FD, ECUs respond with frames larger than 8 bytes on the powertrain bus + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], + logging=True, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], + bus=0, + auxiliary=True, + ), + *[Request( + [StdQueries.TESTER_PRESENT_REQUEST, ford_asbuilt_block_request(block_id)], + [StdQueries.TESTER_PRESENT_RESPONSE, ford_asbuilt_block_response(block_id)], + whitelist_ecus=ecus, + bus=0, + logging=True, + ) for block_id, ecus in ASBUILT_BLOCKS], + ], + extra_ecus=[ + (Ecu.engine, 0x7e0, None), # Powertrain Control Module + # Note: We are unlikely to get a response from behind the gateway + (Ecu.shiftByWire, 0x732, None), # Gear Shift Module + (Ecu.debug, 0x7d0, None), # Accessory Protocol Interface Module + ], + # Custom fuzzy fingerprinting function using platform and model year hints + match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, +) + +DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/fw_query_definitions.py b/opendbc_repo/opendbc/car/fw_query_definitions.py old mode 100755 new mode 100644 similarity index 92% rename from selfdrive/car/fw_query_definitions.py rename to opendbc_repo/opendbc/car/fw_query_definitions.py index bb2827571cd7711..f32da6dd9390593 --- a/selfdrive/car/fw_query_definitions.py +++ b/opendbc_repo/opendbc/car/fw_query_definitions.py @@ -1,15 +1,15 @@ -#!/usr/bin/env python3 -import capnp import copy from dataclasses import dataclass, field import struct from collections.abc import Callable -import panda.python.uds as uds +from panda import uds + +from opendbc.car.structs import CarParams AddrType = tuple[int, int | None] EcuAddrBusType = tuple[int, int | None, int] -EcuAddrSubAddr = tuple[int, int, int | None] +EcuAddrSubAddr = tuple[CarParams.Ecu, int, int | None] LiveFwVersions = dict[AddrType, set[bytes]] OfflineFwVersions = dict[str, dict[EcuAddrSubAddr, list[bytes]]] @@ -78,7 +78,7 @@ class StdQueries: class Request: request: list[bytes] response: list[bytes] - whitelist_ecus: list[int] = field(default_factory=list) + whitelist_ecus: list[CarParams.Ecu] = field(default_factory=list) rx_offset: int = 0x8 bus: int = 1 # Whether this query should be run on the first auxiliary panda (CAN FD cars for example) @@ -94,9 +94,9 @@ class FwQueryConfig: requests: list[Request] # TODO: make this automatic and remove hardcoded lists, or do fingerprinting with ecus # Overrides and removes from essential ecus for specific models and ecus (exact matching) - non_essential_ecus: dict[capnp.lib.capnp._EnumModule, list[str]] = field(default_factory=dict) + non_essential_ecus: dict[CarParams.Ecu, list[str]] = field(default_factory=dict) # Ecus added for data collection, not to be fingerprinted on - extra_ecus: list[tuple[capnp.lib.capnp._EnumModule, int, int | None]] = field(default_factory=list) + extra_ecus: list[tuple[CarParams.Ecu, int, int | None]] = field(default_factory=list) # Function a brand can implement to provide better fuzzy matching. Takes in FW versions and VIN, # returns set of candidates. Only will match if one candidate is returned match_fw_to_car_fuzzy: Callable[[LiveFwVersions, str, OfflineFwVersions], set[str]] | None = None diff --git a/opendbc_repo/opendbc/car/fw_versions.py b/opendbc_repo/opendbc/car/fw_versions.py new file mode 100644 index 000000000000000..3962ec63282f580 --- /dev/null +++ b/opendbc_repo/opendbc/car/fw_versions.py @@ -0,0 +1,327 @@ +from collections import defaultdict +from collections.abc import Callable, Iterator +from typing import Protocol, TypeVar + +from tqdm import tqdm + +from panda import uds +from opendbc.car import carlog +from opendbc.car.can_definitions import CanRecvCallable, CanSendCallable +from opendbc.car.structs import CarParams +from opendbc.car.ecu_addrs import get_ecu_addrs +from opendbc.car.fingerprints import FW_VERSIONS +from opendbc.car.fw_query_definitions import AddrType, EcuAddrBusType, FwQueryConfig, LiveFwVersions, OfflineFwVersions +from opendbc.car.interfaces import get_interface_attr +from opendbc.car.isotp_parallel_query import IsoTpParallelQuery + +Ecu = CarParams.Ecu +ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] +FUZZY_EXCLUDE_ECUS = [Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps, Ecu.debug] + +FW_QUERY_CONFIGS: dict[str, FwQueryConfig] = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True) +VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True) + +MODEL_TO_BRAND = {c: b for b, e in VERSIONS.items() for c in e} +REQUESTS = [(brand, config, r) for brand, config in FW_QUERY_CONFIGS.items() for r in config.requests] + +T = TypeVar('T') +ObdCallback = Callable[[bool], None] + + +def chunks(l: list[T], n: int = 128) -> Iterator[list[T]]: + for i in range(0, len(l), n): + yield l[i:i + n] + + +def is_brand(brand: str, filter_brand: str | None) -> bool: + """Returns if brand matches filter_brand or no brand filter is specified""" + return filter_brand is None or brand == filter_brand + + +def build_fw_dict(fw_versions: list[CarParams.CarFw], filter_brand: str = None) -> dict[AddrType, set[bytes]]: + fw_versions_dict: defaultdict[AddrType, set[bytes]] = defaultdict(set) + for fw in fw_versions: + if is_brand(fw.brand, filter_brand) and not fw.logging: + sub_addr = fw.subAddress if fw.subAddress != 0 else None + fw_versions_dict[(fw.address, sub_addr)].add(fw.fwVersion) + return dict(fw_versions_dict) + + +class MatchFwToCar(Protocol): + def __call__(self, live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True) -> set[str]: + ... + + +def match_fw_to_car_fuzzy(live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True, exclude: str = None) -> set[str]: + """Do a fuzzy FW match. This function will return a match, and the number of firmware version + that were matched uniquely to that specific car. If multiple ECUs uniquely match to different cars + the match is rejected.""" + + # Build lookup table from (addr, sub_addr, fw) to list of candidate cars + all_fw_versions = defaultdict(list) + for candidate, fw_by_addr in FW_VERSIONS.items(): + if not is_brand(MODEL_TO_BRAND[candidate], match_brand): + continue + + if candidate == exclude: + continue + + for addr, fws in fw_by_addr.items(): + # These ECUs are known to be shared between models (EPS only between hybrid/ICE version) + # Getting this exactly right isn't crucial, but excluding camera and radar makes it almost + # impossible to get 3 matching versions, even if two models with shared parts are released at the same + # time and only one is in our database. + if addr[0] in FUZZY_EXCLUDE_ECUS: + continue + for f in fws: + all_fw_versions[(addr[1], addr[2], f)].append(candidate) + + matched_ecus = set() + match: str | None = None + for addr, versions in live_fw_versions.items(): + ecu_key = (addr[0], addr[1]) + for version in versions: + # All cars that have this FW response on the specified address + candidates = all_fw_versions[(*ecu_key, version)] + + if len(candidates) == 1: + matched_ecus.add(ecu_key) + if match is None: + match = candidates[0] + # We uniquely matched two different cars. No fuzzy match possible + elif match != candidates[0]: + return set() + + # Note that it is possible to match to a candidate without all its ECUs being present + # if there are enough matches. FIXME: parameterize this or require all ECUs to exist like exact matching + if match and len(matched_ecus) >= 2: + if log: + carlog.error(f"Fingerprinted {match} using fuzzy match. {len(matched_ecus)} matching ECUs") + return {match} + else: + return set() + + +def match_fw_to_car_exact(live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True, extra_fw_versions: dict = None) -> set[str]: + """Do an exact FW match. Returns all cars that match the given + FW versions for a list of "essential" ECUs. If an ECU is not considered + essential the FW version can be missing to get a fingerprint, but if it's present it + needs to match the database.""" + if extra_fw_versions is None: + extra_fw_versions = {} + + invalid = set() + candidates = {c: f for c, f in FW_VERSIONS.items() if + is_brand(MODEL_TO_BRAND[c], match_brand)} + + for candidate, fws in candidates.items(): + config = FW_QUERY_CONFIGS[MODEL_TO_BRAND[candidate]] + for ecu, expected_versions in fws.items(): + expected_versions = expected_versions + extra_fw_versions.get(candidate, {}).get(ecu, []) + ecu_type = ecu[0] + addr = ecu[1:] + + found_versions = live_fw_versions.get(addr, set()) + if not len(found_versions): + # Some models can sometimes miss an ecu, or show on two different addresses + # FIXME: this logic can be improved to be more specific, should require one of the two addresses + if candidate in config.non_essential_ecus.get(ecu_type, []): + continue + + # Ignore non essential ecus + if ecu_type not in ESSENTIAL_ECUS: + continue + + # Virtual debug ecu doesn't need to match the database + if ecu_type == Ecu.debug: + continue + + if not any(found_version in expected_versions for found_version in found_versions): + invalid.add(candidate) + break + + return set(candidates.keys()) - invalid + + +def match_fw_to_car(fw_versions: list[CarParams.CarFw], vin: str, allow_exact: bool = True, + allow_fuzzy: bool = True, log: bool = True) -> tuple[bool, set[str]]: + # Try exact matching first + exact_matches: list[tuple[bool, MatchFwToCar]] = [] + if allow_exact: + exact_matches = [(True, match_fw_to_car_exact)] + if allow_fuzzy: + exact_matches.append((False, match_fw_to_car_fuzzy)) + + for exact_match, match_func in exact_matches: + # For each brand, attempt to fingerprint using all FW returned from its queries + matches: set[str] = set() + for brand in VERSIONS.keys(): + fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) + matches |= match_func(fw_versions_dict, match_brand=brand, log=log) + + # If specified and no matches so far, fall back to brand's fuzzy fingerprinting function + config = FW_QUERY_CONFIGS[brand] + if not exact_match and not len(matches) and config.match_fw_to_car_fuzzy is not None: + matches |= config.match_fw_to_car_fuzzy(fw_versions_dict, vin, VERSIONS[brand]) + + if len(matches): + return exact_match, matches + + return True, set() + + +def get_present_ecus(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, num_pandas: int = 1) -> set[EcuAddrBusType]: + # queries are split by OBD multiplexing mode + queries: dict[bool, list[list[EcuAddrBusType]]] = {True: [], False: []} + parallel_queries: dict[bool, list[EcuAddrBusType]] = {True: [], False: []} + responses: set[EcuAddrBusType] = set() + + for brand, config, r in REQUESTS: + # Skip query if no panda available + if r.bus > num_pandas * 4 - 1: + continue + + for ecu_type, addr, sub_addr in config.get_all_ecus(VERSIONS[brand]): + # Only query ecus in whitelist if whitelist is not empty + if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus: + a = (addr, sub_addr, r.bus) + # Build set of queries + if sub_addr is None: + if a not in parallel_queries[r.obd_multiplexing]: + parallel_queries[r.obd_multiplexing].append(a) + else: # subaddresses must be queried one by one + if [a] not in queries[r.obd_multiplexing]: + queries[r.obd_multiplexing].append([a]) + + # Build set of expected responses to filter + response_addr = uds.get_rx_addr_for_tx_addr(addr, r.rx_offset) + responses.add((response_addr, sub_addr, r.bus)) + + for obd_multiplexing in queries: + queries[obd_multiplexing].insert(0, parallel_queries[obd_multiplexing]) + + ecu_responses = set() + for obd_multiplexing in queries: + set_obd_multiplexing(obd_multiplexing) + for query in queries[obd_multiplexing]: + ecu_responses.update(get_ecu_addrs(can_recv, can_send, set(query), responses, timeout=0.1)) + return ecu_responses + + +def get_brand_ecu_matches(ecu_rx_addrs: set[EcuAddrBusType]) -> dict[str, set[AddrType]]: + """Returns dictionary of brands and matches with ECUs in their FW versions""" + + brand_addrs = {brand: {(addr, subaddr) for _, addr, subaddr in config.get_all_ecus(VERSIONS[brand])} for + brand, config in FW_QUERY_CONFIGS.items()} + brand_matches: dict[str, set[AddrType]] = {brand: set() for brand, _, _ in REQUESTS} + + brand_rx_offsets = {(brand, r.rx_offset) for brand, _, r in REQUESTS} + for addr, sub_addr, _ in ecu_rx_addrs: + # Since we can't know what request an ecu responded to, add matches for all possible rx offsets + for brand, rx_offset in brand_rx_offsets: + a = (uds.get_rx_addr_for_tx_addr(addr, -rx_offset), sub_addr) + if a in brand_addrs[brand]: + brand_matches[brand].add(a) + + return brand_matches + + +def get_fw_versions_ordered(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, vin: str, + ecu_rx_addrs: set[EcuAddrBusType], timeout: float = 0.1, num_pandas: int = 1, debug: bool = False, + progress: bool = False) -> list[CarParams.CarFw]: + """Queries for FW versions ordering brands by likelihood, breaks when exact match is found""" + + all_car_fw = [] + brand_matches = get_brand_ecu_matches(ecu_rx_addrs) + + for brand in sorted(brand_matches, key=lambda b: len(brand_matches[b]), reverse=True): + # Skip this brand if there are no matching present ECUs + if not len(brand_matches[brand]): + continue + + car_fw = get_fw_versions(can_recv, can_send, set_obd_multiplexing, query_brand=brand, timeout=timeout, num_pandas=num_pandas, debug=debug, + progress=progress) + all_car_fw.extend(car_fw) + + # If there is a match using this brand's FW alone, finish querying early + _, matches = match_fw_to_car(car_fw, vin, log=False) + if len(matches) == 1: + break + + return all_car_fw + + +def get_fw_versions(can_recv: CanRecvCallable, can_send: CanSendCallable, set_obd_multiplexing: ObdCallback, query_brand: str = None, + extra: OfflineFwVersions = None, timeout: float = 0.1, num_pandas: int = 1, debug: bool = False, + progress: bool = False) -> list[CarParams.CarFw]: + versions = VERSIONS.copy() + + if query_brand is not None: + versions = {query_brand: versions[query_brand]} + + if extra is not None: + versions.update(extra) + + # Extract ECU addresses to query from fingerprints + # ECUs using a subaddress need be queried one by one, the rest can be done in parallel + addrs = [] + parallel_addrs = [] + ecu_types = {} + + for brand, brand_versions in versions.items(): + config = FW_QUERY_CONFIGS[brand] + for ecu_type, addr, sub_addr in config.get_all_ecus(brand_versions): + a = (brand, addr, sub_addr) + if a not in ecu_types: + ecu_types[a] = ecu_type + + if sub_addr is None: + if a not in parallel_addrs: + parallel_addrs.append(a) + else: + if [a] not in addrs: + addrs.append([a]) + + addrs.insert(0, parallel_addrs) + + # Get versions and build capnp list to put into CarParams + car_fw = [] + requests = [(brand, config, r) for brand, config, r in REQUESTS if is_brand(brand, query_brand)] + for addr_group in tqdm(addrs, disable=not progress): # split by subaddr, if any + for addr_chunk in chunks(addr_group): + for brand, config, r in requests: + # Skip query if no panda available + if r.bus > num_pandas * 4 - 1: + continue + + # Toggle OBD multiplexing for each request + if r.bus % 4 == 1: + set_obd_multiplexing(r.obd_multiplexing) + + try: + query_addrs = [(a, s) for (b, a, s) in addr_chunk if b in (brand, 'any') and + (len(r.whitelist_ecus) == 0 or ecu_types[(b, a, s)] in r.whitelist_ecus)] + + if query_addrs: + query = IsoTpParallelQuery(can_send, can_recv, r.bus, query_addrs, r.request, r.response, r.rx_offset, debug=debug) + for (tx_addr, sub_addr), version in query.get_data(timeout).items(): + f = CarParams.CarFw() + + f.ecu = ecu_types.get((brand, tx_addr, sub_addr), Ecu.unknown) + f.fwVersion = version + f.address = tx_addr + f.responseAddress = uds.get_rx_addr_for_tx_addr(tx_addr, r.rx_offset) + f.request = r.request + f.brand = brand + f.bus = r.bus + f.logging = r.logging or (f.ecu, tx_addr, sub_addr) in config.extra_ecus + f.obdMultiplexing = r.obd_multiplexing + + if sub_addr is not None: + f.subAddress = sub_addr + + car_fw.append(f) + except Exception: + carlog.exception("FW query exception") + + return car_fw diff --git a/selfdrive/car/gm/tests/__init__.py b/opendbc_repo/opendbc/car/gm/__init__.py similarity index 100% rename from selfdrive/car/gm/tests/__init__.py rename to opendbc_repo/opendbc/car/gm/__init__.py diff --git a/opendbc_repo/opendbc/car/gm/carcontroller.py b/opendbc_repo/opendbc/car/gm/carcontroller.py new file mode 100644 index 000000000000000..a38bc73e09db4cf --- /dev/null +++ b/opendbc_repo/opendbc/car/gm/carcontroller.py @@ -0,0 +1,162 @@ +from opendbc.can.packer import CANPacker +from opendbc.car import DT_CTRL, apply_driver_steer_torque_limits, structs +from opendbc.car.gm import gmcan +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.gm.values import DBC, CanBus, CarControllerParams, CruiseButtons +from opendbc.car.common.numpy_fast import interp +from opendbc.car.interfaces import CarControllerBase + +VisualAlert = structs.CarControl.HUDControl.VisualAlert +NetworkLocation = structs.CarParams.NetworkLocation +LongCtrlState = structs.CarControl.Actuators.LongControlState + +# Camera cancels up to 0.1s after brake is pressed, ECM allows 0.5s +CAMERA_CANCEL_DELAY_FRAMES = 10 +# Enforce a minimum interval between steering messages to avoid a fault +MIN_STEER_MSG_INTERVAL_MS = 15 + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.start_time = 0. + self.apply_steer_last = 0 + self.apply_gas = 0 + self.apply_brake = 0 + self.last_steer_frame = 0 + self.last_button_frame = 0 + self.cancel_counter = 0 + + self.lka_steering_cmd_counter = 0 + self.lka_icon_status_last = (False, False) + + self.params = CarControllerParams(self.CP) + + self.packer_pt = CANPacker(DBC[self.CP.carFingerprint]['pt']) + self.packer_obj = CANPacker(DBC[self.CP.carFingerprint]['radar']) + self.packer_ch = CANPacker(DBC[self.CP.carFingerprint]['chassis']) + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + hud_alert = hud_control.visualAlert + hud_v_cruise = hud_control.setSpeed + if hud_v_cruise > 70: + hud_v_cruise = 0 + + # Send CAN commands. + can_sends = [] + + # Steering (Active: 50Hz, inactive: 10Hz) + steer_step = self.params.STEER_STEP if CC.latActive else self.params.INACTIVE_STEER_STEP + + if self.CP.networkLocation == NetworkLocation.fwdCamera: + # Also send at 50Hz: + # - on startup, first few msgs are blocked + # - until we're in sync with camera so counters align when relay closes, preventing a fault. + # openpilot can subtly drift, so this is activated throughout a drive to stay synced + out_of_sync = self.lka_steering_cmd_counter % 4 != (CS.cam_lka_steering_cmd_counter + 1) % 4 + if CS.loopback_lka_steering_cmd_ts_nanos == 0 or out_of_sync: + steer_step = self.params.STEER_STEP + + self.lka_steering_cmd_counter += 1 if CS.loopback_lka_steering_cmd_updated else 0 + + # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we + # received the ASCMLKASteeringCmd loopback confirmation too recently + last_lka_steer_msg_ms = (now_nanos - CS.loopback_lka_steering_cmd_ts_nanos) * 1e-6 + if (self.frame - self.last_steer_frame) >= steer_step and last_lka_steer_msg_ms > MIN_STEER_MSG_INTERVAL_MS: + # Initialize ASCMLKASteeringCmd counter using the camera until we get a msg on the bus + if CS.loopback_lka_steering_cmd_ts_nanos == 0: + self.lka_steering_cmd_counter = CS.pt_lka_steering_cmd_counter + 1 + + if CC.latActive: + new_steer = int(round(actuators.steer * self.params.STEER_MAX)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) + else: + apply_steer = 0 + + self.last_steer_frame = self.frame + self.apply_steer_last = apply_steer + idx = self.lka_steering_cmd_counter % 4 + can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, CC.latActive)) + + if self.CP.openpilotLongitudinalControl: + # Gas/regen, brakes, and UI commands - all at 25Hz + if self.frame % 4 == 0: + stopping = actuators.longControlState == LongCtrlState.stopping + if not CC.longActive: + # ASCM sends max regen when not enabled + self.apply_gas = self.params.INACTIVE_REGEN + self.apply_brake = 0 + else: + self.apply_gas = int(round(interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) + self.apply_brake = int(round(interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) + # Don't allow any gas above inactive regen while stopping + # FIXME: brakes aren't applied immediately when enabling at a stop + if stopping: + self.apply_gas = self.params.INACTIVE_REGEN + + idx = (self.frame // 4) % 4 + + at_full_stop = CC.longActive and CS.out.standstill + near_stop = CC.longActive and (abs(CS.out.vEgo) < self.params.NEAR_STOP_BRAKE_PHASE) + friction_brake_bus = CanBus.CHASSIS + # GM Camera exceptions + # TODO: can we always check the longControlState? + if self.CP.networkLocation == NetworkLocation.fwdCamera: + at_full_stop = at_full_stop and stopping + friction_brake_bus = CanBus.POWERTRAIN + + # GasRegenCmdActive needs to be 1 to avoid cruise faults. It describes the ACC state, not actuation + can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, self.apply_gas, idx, CC.enabled, at_full_stop)) + can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, friction_brake_bus, self.apply_brake, + idx, CC.enabled, near_stop, at_full_stop, self.CP)) + + # Send dashboard UI commands (ACC status) + send_fcw = hud_alert == VisualAlert.fcw + can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, CC.enabled, + hud_v_cruise * CV.MS_TO_KPH, hud_control, send_fcw)) + + # Radar needs to know current speed and yaw rate (50hz), + # and that ADAS is alive (10hz) + if not self.CP.radarUnavailable: + tt = self.frame * DT_CTRL + time_and_headlights_step = 10 + if self.frame % time_and_headlights_step == 0: + idx = (self.frame // time_and_headlights_step) % 4 + can_sends.append(gmcan.create_adas_time_status(CanBus.OBSTACLE, int((tt - self.start_time) * 60), idx)) + can_sends.append(gmcan.create_adas_headlights_status(self.packer_obj, CanBus.OBSTACLE)) + + speed_and_accelerometer_step = 2 + if self.frame % speed_and_accelerometer_step == 0: + idx = (self.frame // speed_and_accelerometer_step) % 4 + can_sends.append(gmcan.create_adas_steering_status(CanBus.OBSTACLE, idx)) + can_sends.append(gmcan.create_adas_accelerometer_speed_status(CanBus.OBSTACLE, abs(CS.out.vEgo), idx)) + + if self.CP.networkLocation == NetworkLocation.gateway and self.frame % self.params.ADAS_KEEPALIVE_STEP == 0: + can_sends += gmcan.create_adas_keepalive(CanBus.POWERTRAIN) + + else: + # While car is braking, cancel button causes ECM to enter a soft disable state with a fault status. + # A delayed cancellation allows camera to cancel and avoids a fault when user depresses brake quickly + self.cancel_counter = self.cancel_counter + 1 if CC.cruiseControl.cancel else 0 + + # Stock longitudinal, integrated at camera + if (self.frame - self.last_button_frame) * DT_CTRL > 0.04: + if self.cancel_counter > CAMERA_CANCEL_DELAY_FRAMES: + self.last_button_frame = self.frame + can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CS.buttons_counter, CruiseButtons.CANCEL)) + + if self.CP.networkLocation == NetworkLocation.fwdCamera: + # Silence "Take Steering" alert sent by camera, forward PSCMStatus with HandsOffSWlDetectionStatus=1 + if self.frame % 10 == 0: + can_sends.append(gmcan.create_pscm_status(self.packer_pt, CanBus.CAMERA, CS.pscm_status)) + + new_actuators = actuators.as_builder() + new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX + new_actuators.steerOutputCan = self.apply_steer_last + new_actuators.gas = self.apply_gas + new_actuators.brake = self.apply_brake + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/gm/carstate.py b/opendbc_repo/opendbc/car/gm/carstate.py new file mode 100644 index 000000000000000..ea04a50a8a36130 --- /dev/null +++ b/opendbc_repo/opendbc/car/gm/carstate.py @@ -0,0 +1,198 @@ +import copy +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from opendbc.car import create_button_events, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.common.numpy_fast import mean +from opendbc.car.interfaces import CarStateBase +from opendbc.car.gm.values import DBC, AccState, CanBus, CruiseButtons, STEER_THRESHOLD, SDGM_CAR + +ButtonType = structs.CarState.ButtonEvent.Type +TransmissionType = structs.CarParams.TransmissionType +NetworkLocation = structs.CarParams.NetworkLocation + +STANDSTILL_THRESHOLD = 10 * 0.0311 * CV.KPH_TO_MS + +BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, + CruiseButtons.MAIN: ButtonType.mainCruise, CruiseButtons.CANCEL: ButtonType.cancel} + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] + self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. + self.cluster_min_speed = CV.KPH_TO_MS / 2. + + self.loopback_lka_steering_cmd_updated = False + self.loopback_lka_steering_cmd_ts_nanos = 0 + self.pt_lka_steering_cmd_counter = 0 + self.cam_lka_steering_cmd_counter = 0 + self.buttons_counter = 0 + + self.distance_button = 0 + + def update(self, pt_cp, cam_cp, _, __, loopback_cp) -> structs.CarState: + ret = structs.CarState() + + prev_cruise_buttons = self.cruise_buttons + prev_distance_button = self.distance_button + self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] + self.distance_button = pt_cp.vl["ASCMSteeringButton"]["DistanceButton"] + self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] + self.pscm_status = copy.copy(pt_cp.vl["PSCMStatus"]) + + # Variables used for avoiding LKAS faults + self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]["RollingCounter"]) > 0 + if self.loopback_lka_steering_cmd_updated: + self.loopback_lka_steering_cmd_ts_nanos = loopback_cp.ts_nanos["ASCMLKASteeringCmd"]["RollingCounter"] + if self.CP.networkLocation == NetworkLocation.fwdCamera: + self.pt_lka_steering_cmd_counter = pt_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] + self.cam_lka_steering_cmd_counter = cam_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] + + # 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) + left_whl_sign = -1 if pt_cp.vl["EBCMWheelSpdRear"]["RLWheelDir"] == 2 else 1 + right_whl_sign = -1 if pt_cp.vl["EBCMWheelSpdRear"]["RRWheelDir"] == 2 else 1 + ret.wheelSpeeds = self.get_wheel_speeds( + left_whl_sign * pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"], + right_whl_sign * pt_cp.vl["EBCMWheelSpdFront"]["FRWheelSpd"], + left_whl_sign * pt_cp.vl["EBCMWheelSpdRear"]["RLWheelSpd"], + right_whl_sign * pt_cp.vl["EBCMWheelSpdRear"]["RRWheelSpd"], + ) + ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]) + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + # sample rear wheel speeds, standstill=True if ECM allows engagement with brake + ret.standstill = abs(ret.wheelSpeeds.rl) <= STANDSTILL_THRESHOLD and abs(ret.wheelSpeeds.rr) <= STANDSTILL_THRESHOLD + + if pt_cp.vl["ECMPRDNL2"]["ManualMode"] == 1: + ret.gearShifter = self.parse_gear_shifter("T") + else: + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL2"]["PRNDL2"], None)) + + ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] + if self.CP.networkLocation == NetworkLocation.fwdCamera: + ret.brakePressed = pt_cp.vl["ECMEngineStatus"]["BrakePressed"] != 0 + else: + # Some Volt 2016-17 have loose brake pedal push rod retainers which causes the ECM to believe + # that the brake is being intermittently pressed without user interaction. + # To avoid a cruise fault we need to use a conservative brake position threshold + # https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf + ret.brakePressed = ret.brake >= 8 + + # Regen braking is braking + if self.CP.transmissionType == TransmissionType.direct: + ret.regenBraking = pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0 + + ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254. + ret.gasPressed = ret.gas > 1e-5 + + ret.steeringAngleDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelAngle"] + ret.steeringRateDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelRate"] + ret.steeringTorque = pt_cp.vl["PSCMStatus"]["LKADriverAppldTrq"] + ret.steeringTorqueEps = pt_cp.vl["PSCMStatus"]["LKATorqueDelivered"] + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + + # 0 inactive, 1 active, 2 temporarily limited, 3 failed + self.lkas_status = pt_cp.vl["PSCMStatus"]["LKATorqueDeliveredStatus"] + ret.steerFaultTemporary = self.lkas_status == 2 + ret.steerFaultPermanent = self.lkas_status == 3 + + # 1 - open, 0 - closed + ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]["FrontLeftDoor"] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]["FrontRightDoor"] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]["RearLeftDoor"] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]["RearRightDoor"] == 1) + + # 1 - latched + ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]["LeftSeatBelt"] == 0 + ret.leftBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 1 + ret.rightBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 2 + + ret.parkingBrake = pt_cp.vl["BCMGeneralPlatformStatus"]["ParkBrakeSwActive"] == 1 + ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0 + ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1 + ret.accFaulted = (pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED or + pt_cp.vl["EBCMFrictionBrakeStatus"]["FrictionBrakeUnavailable"] == 1) + + ret.cruiseState.enabled = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] != AccState.OFF + ret.cruiseState.standstill = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.STANDSTILL + if self.CP.networkLocation == NetworkLocation.fwdCamera: + ret.cruiseState.speed = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCSpeedSetpoint"] * CV.KPH_TO_MS + if self.CP.carFingerprint not in SDGM_CAR: + ret.stockAeb = cam_cp.vl["AEBCmd"]["AEBCmdActive"] != 0 + # openpilot controls nonAdaptive when not pcmCruise + if self.CP.pcmCruise: + ret.cruiseState.nonAdaptive = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCCruiseState"] not in (2, 3) + + if self.CP.enableBsm: + ret.leftBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["LeftBSM"] == 1 + ret.rightBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["RightBSM"] == 1 + + # Don't add event if transitioning from INIT, unless it's to an actual button + if self.cruise_buttons != CruiseButtons.UNPRESS or prev_cruise_buttons != CruiseButtons.INIT: + ret.buttonEvents = [ + *create_button_events(self.cruise_buttons, prev_cruise_buttons, BUTTONS_DICT, + unpressed_btn=CruiseButtons.UNPRESS), + *create_button_events(self.distance_button, prev_distance_button, + {1: ButtonType.gapAdjustCruise}) + ] + + return ret + + @staticmethod + def get_cam_can_parser(CP): + messages = [] + if CP.networkLocation == NetworkLocation.fwdCamera: + messages += [ + ("ASCMLKASteeringCmd", 10), + ("ASCMActiveCruiseControlStatus", 25), + ] + if CP.carFingerprint not in SDGM_CAR: + messages += [ + ("AEBCmd", 10), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.CAMERA) + + @staticmethod + def get_can_parser(CP): + messages = [ + ("BCMTurnSignals", 1), + ("ECMPRDNL2", 10), + ("PSCMStatus", 10), + ("ESPStatus", 10), + ("BCMDoorBeltStatus", 10), + ("BCMGeneralPlatformStatus", 10), + ("EBCMWheelSpdFront", 20), + ("EBCMWheelSpdRear", 20), + ("EBCMFrictionBrakeStatus", 20), + ("AcceleratorPedal2", 33), + ("ASCMSteeringButton", 33), + ("ECMEngineStatus", 100), + ("PSCMSteeringAngle", 100), + ("ECMAcceleratorPos", 80), + ] + + if CP.enableBsm: + messages.append(("BCMBlindSpotMonitor", 10)) + + # Used to read back last counter sent to PT by camera + if CP.networkLocation == NetworkLocation.fwdCamera: + messages += [ + ("ASCMLKASteeringCmd", 0), + ] + + if CP.transmissionType == TransmissionType.direct: + messages.append(("EBCMRegenPaddle", 50)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.POWERTRAIN) + + @staticmethod + def get_loopback_can_parser(CP): + messages = [ + ("ASCMLKASteeringCmd", 0), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.LOOPBACK) diff --git a/opendbc_repo/opendbc/car/gm/fingerprints.py b/opendbc_repo/opendbc/car/gm/fingerprints.py new file mode 100644 index 000000000000000..9a55b22705dff84 --- /dev/null +++ b/opendbc_repo/opendbc/car/gm/fingerprints.py @@ -0,0 +1,72 @@ +# ruff: noqa: E501 +from opendbc.car.gm.values import CAR + +# Trailblazer also matches as a SILVERADO, TODO: split with fw versions +# FIXME: There are Equinox users with different message lengths, specifically 304 and 320 + + +FINGERPRINTS = { + CAR.HOLDEN_ASTRA: [{ + 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 715: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7 + }], + CAR.CHEVROLET_VOLT: [{ + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 715: 8, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 + }, + { + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 578: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1516: 8, 1601: 8, 1618: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2018: 8, 2020: 8, 2024: 8, 2028: 8 + }, + { + 170: 8, 171: 8, 189: 7, 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 209: 7, 211: 2, 241: 6, 288: 5, 289: 1, 290: 1, 298: 2, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 368: 8, 381: 2, 384: 8, 386: 5, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 458: 8, 479: 3, 481: 7, 485: 8, 489: 5, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 3, 508: 8, 512: 3, 528: 4, 530: 8, 532: 6, 537: 5, 539: 8, 542: 7, 546: 7, 550: 8, 554: 3, 558: 8, 560: 6, 562: 4, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 821: 4, 823: 7, 832: 8, 840: 5, 842: 5, 844: 8, 853: 8, 866: 4, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 5, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7 + }], + CAR.BUICK_LACROSSE: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 353: 3, 381: 6, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 503: 1, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 5, 707: 8, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 872: 1, 882: 8, 890: 1, 892: 2, 893: 1, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1022: 1, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1243: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1913: 7, 1914: 7, 1916: 7, 1918: 7, 1919: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 + }], + CAR.BUICK_REGAL: [{ + 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 8, 419: 8, 422: 4, 426: 8, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 463: 3, 479: 8, 481: 7, 485: 8, 487: 8, 489: 8, 495: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 578: 8, 579: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 884: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 8, 969: 8, 977: 8, 979: 8, 985: 8, 1001: 8, 1005: 6, 1009: 8, 1011: 8, 1013: 3, 1017: 8, 1020: 8, 1024: 8, 1025: 8, 1026: 8, 1027: 8, 1028: 8, 1029: 8, 1030: 8, 1031: 8, 1032: 2, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 8, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 8, 1263: 8, 1265: 8, 1267: 8, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1602: 8, 1603: 7, 1611: 8, 1618: 8, 1906: 8, 1907: 7, 1912: 7, 1914: 7, 1916: 7, 1919: 7, 1930: 7, 2016: 8, 2018: 8, 2019: 8, 2024: 8, 2026: 8 + }], + CAR.CADILLAC_ATS: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.CHEVROLET_MALIBU: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.GMC_ACADIA: [{ + 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 1, 290: 1, 298: 8, 304: 8, 309: 8, 313: 8, 320: 8, 322: 7, 328: 1, 352: 7, 368: 8, 381: 8, 384: 8, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 458: 8, 460: 4, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 5, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 512: 3, 530: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 568: 2, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 801: 8, 803: 8, 804: 3, 805: 8, 832: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7 + }, + { + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.CADILLAC_ESCALADE: [{ + 170: 8, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 4, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 + }], + CAR.CADILLAC_ESCALADE_ESV: [{ + 309: 1, 848: 8, 849: 8, 850: 8, 851: 8, 852: 8, 853: 8, 854: 3, 1056: 6, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1061: 8, 1062: 8, 1063: 8, 1064: 8, 1065: 8, 1066: 8, 1067: 8, 1068: 8, 1120: 8, 1121: 8, 1122: 8, 1123: 8, 1124: 8, 1125: 8, 1126: 8, 1127: 8, 1128: 8, 1129: 8, 1130: 8, 1131: 8, 1132: 8, 1133: 8, 1134: 8, 1135: 8, 1136: 8, 1137: 8, 1138: 8, 1139: 8, 1140: 8, 1141: 8, 1142: 8, 1143: 8, 1146: 8, 1147: 8, 1148: 8, 1149: 8, 1150: 8, 1151: 8, 1216: 8, 1217: 8, 1218: 8, 1219: 8, 1220: 8, 1221: 8, 1222: 8, 1223: 8, 1224: 8, 1225: 8, 1226: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1240: 8, 1241: 8, 1242: 8, 1787: 8, 1788: 8 + }], + CAR.CADILLAC_ESCALADE_ESV_2019: [{ + 715: 8, 840: 5, 717: 5, 869: 4, 880: 6, 289: 8, 454: 8, 842: 5, 460: 5, 463: 3, 801: 8, 170: 8, 190: 6, 241: 6, 201: 8, 417: 7, 211: 2, 419: 1, 398: 8, 426: 7, 487: 8, 442: 8, 451: 8, 452: 8, 453: 6, 479: 3, 311: 8, 500: 6, 647: 6, 193: 8, 707: 8, 197: 8, 209: 7, 199: 4, 455: 7, 313: 8, 481: 7, 485: 8, 489: 8, 249: 8, 393: 7, 407: 7, 413: 8, 422: 4, 431: 8, 501: 8, 499: 3, 810: 8, 508: 8, 381: 8, 462: 4, 532: 6, 562: 8, 386: 8, 761: 7, 573: 1, 554: 3, 719: 5, 560: 8, 1279: 4, 388: 8, 288: 5, 1005: 6, 497: 8, 844: 8, 961: 8, 967: 4, 977: 8, 979: 8, 985: 5, 1001: 8, 1017: 8, 1019: 2, 1020: 8, 1217: 8, 510: 8, 866: 4, 304: 1, 969: 8, 384: 4, 1033: 7, 1009: 8, 1034: 7, 1296: 4, 1930: 7, 1105: 5, 1013: 5, 1225: 7, 1919: 7, 320: 3, 534: 2, 352: 5, 298: 8, 1223: 2, 1233: 8, 608: 8, 1265: 8, 609: 6, 1267: 1, 1417: 8, 610: 6, 1906: 7, 611: 6, 612: 8, 613: 8, 208: 8, 564: 5, 309: 8, 1221: 5, 1280: 4, 1249: 8, 1907: 7, 1257: 6, 1300: 8, 1920: 7, 563: 5, 1322: 6, 1323: 4, 1328: 4, 1917: 7, 328: 1, 1912: 7, 1914: 7, 804: 3, 1918: 7 + }], + CAR.CHEVROLET_BOLT_EUV: [{ + 189: 7, 190: 7, 193: 8, 197: 8, 201: 8, 209: 7, 211: 3, 241: 6, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 451: 8, 452: 8, 453: 6, 458: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 566: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1265: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }], + CAR.CHEVROLET_SILVERADO: [{ + 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }], + CAR.CHEVROLET_EQUINOX: [{ + 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }, + { + 190: 6, 201: 8, 211: 2, 717: 5, 241: 6, 451: 8, 298: 8, 452: 8, 453: 6, 479: 3, 485: 8, 249: 8, 500: 6, 587: 8, 1611: 8, 289: 8, 481: 7, 193: 8, 197: 8, 209: 7, 455: 7, 489: 8, 309: 8, 413: 8, 501: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 311: 8, 510: 8, 528: 5, 532: 6, 715: 8, 560: 8, 562: 8, 707: 8, 789: 5, 869: 4, 880: 6, 761: 7, 840: 5, 842: 5, 844: 8, 313: 8, 381: 8, 386: 8, 810: 8, 322: 7, 384: 4, 800: 6, 1033: 7, 1034: 7, 1296: 4, 753: 5, 388: 8, 288: 5, 497: 8, 463: 3, 304: 3, 977: 8, 1001: 8, 1280: 4, 320: 4, 352: 5, 563: 5, 565: 5, 1221: 5, 1011: 6, 1017: 8, 1020: 8, 1249: 8, 1300: 8, 328: 1, 1217: 8, 1233: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1930: 7, 1271: 8 + }], + CAR.CADILLAC_XT4: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 292: 2, 298: 8, 304: 3, 309: 8, 313: 8, 320: 4, 322: 7, 328: 1, 331: 3, 352: 5, 353: 3, 368: 3, 381: 8, 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, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 503: 2, 508: 8, 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, 719: 5, 761: 7, 806: 1, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 872: 1, 880: 6, 961: 8, 969: 8, 975: 2, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 5, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1037: 5, 1105: 5, 1187: 5, 1195: 3, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1236: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1268: 2, 1271: 8, 1273: 3, 1276: 2, 1277: 7, 1278: 4, 1279: 4, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1345: 8, 1417: 8, 1512: 8, 1517: 8, 1601: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1793: 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, 1919: 7, 1920: 8, 1924: 8, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 1969: 8, 1971: 8, 1975: 8, 1984: 8, 1988: 8, 2000: 8, 2001: 8, 2002: 8, 2016: 8, 2017: 8, 2018: 8, 2020: 8, 2021: 8, 2024: 8, 2026: 8 + }], + CAR.CHEVROLET_VOLT_2019: [{ + 170: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 257: 8, 288: 5, 289: 8, 292: 2, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 331: 3, 352: 5, 368: 3, 381: 8, 384: 4, 386: 8, 388: 8, 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: 5, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 7, 567: 5, 573: 1, 577: 8, 587: 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, 975: 2, 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: 5, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1236: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1268: 2, 1273: 3, 1275: 3, 1279: 4, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1345: 8, 1417: 8, 1512: 8, 1513: 8, 1516: 8, 1517: 8, 1601: 8, 1609: 8, 1611: 8, 1618: 8, 1613: 8, 1649: 8, 1792: 8, 1793: 8, 1798: 8, 1799: 8, 1810: 8, 1813: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1856: 8, 1858: 8, 1859: 8, 1860: 8, 1862: 8, 1863: 8, 1871: 8, 1872: 8, 1875: 8, 1879: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1920: 8, 1922: 7, 1927: 7, 1930: 7, 1937: 8, 1953: 8, 1954: 8, 1955: 8, 1968: 8, 1969: 8, 1971: 8, 1975: 8, 1988: 8, 1990: 8, 2000: 8, 2001: 8, 2004: 8, 2017: 8, 2018: 8, 2020: 8, 2021: 8, 2023: 8, 2025: 8, 2028: 8, 2031: 8 + }], + CAR.CHEVROLET_TRAVERSE: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 292: 2, 298: 8, 304: 3, 309: 8, 313: 8, 320: 4, 322: 7, 328: 1, 331: 3, 352: 5, 368: 3, 381: 8, 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, 454: 8, 455: 7, 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, 578: 8, 579: 8, 587: 8, 603: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 723: 4, 730: 4, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 975: 2, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 5, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 5, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1236: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1268: 2, 1271: 8, 1279: 4, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1345: 8, 1346: 8, 1347: 8, 1355: 8, 1362: 8, 1417: 8, 1512: 8, 1514: 8, 1601: 8, 1602: 8, 1603: 7, 1609: 8, 1611: 8, 1613: 8, 1618: 8, 1649: 8, 1792: 8, 1793: 8, 1798: 8, 1799: 8, 1810: 8, 1813: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1856: 8, 1858: 8, 1859: 8, 1860: 8, 1862: 8, 1863: 8, 1871: 8, 1872: 8, 1875: 8, 1879: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1920: 7, 1927: 8, 1930: 7, 1937: 8, 1953: 8, 1954: 8, 1955: 8, 1968: 8, 1969: 8, 1971: 8, 1975: 8, 1988: 8, 1990: 8, 2000: 8, 2001: 8, 2004: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2024: 8, 2026: 8 + }], +} + +FW_VERSIONS: dict[str, dict[tuple, list[bytes]]] = { +} diff --git a/selfdrive/car/gm/gmcan.py b/opendbc_repo/opendbc/car/gm/gmcan.py similarity index 92% rename from selfdrive/car/gm/gmcan.py rename to opendbc_repo/opendbc/car/gm/gmcan.py index e833e77636a5516..6c583fe336d4c60 100644 --- a/selfdrive/car/gm/gmcan.py +++ b/opendbc_repo/opendbc/car/gm/gmcan.py @@ -1,5 +1,5 @@ -from openpilot.selfdrive.car import make_can_msg -from openpilot.selfdrive.car.gm.values import CAR +from opendbc.car.can_definitions import CanData +from opendbc.car.gm.values import CAR def create_buttons(packer, bus, idx, button): @@ -49,7 +49,7 @@ def create_steering_control(packer, bus, apply_steer, idx, lkas_active): def create_adas_keepalive(bus): dat = b"\x00\x00\x00\x00\x00\x00\x00" - return [make_can_msg(0x409, dat, bus), make_can_msg(0x40a, dat, bus)] + return [CanData(0x409, dat, bus), CanData(0x40a, dat, bus)] def create_gas_regen_command(packer, bus, throttle, idx, enabled, at_full_stop): @@ -64,7 +64,7 @@ def create_gas_regen_command(packer, bus, throttle, idx, enabled, at_full_stop): "GasRegenAlwaysOne3": 1, } - dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[2] + dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[1] values["GasRegenChecksum"] = (((0xff - dat[1]) & 0xff) << 16) | \ (((0xff - dat[2]) & 0xff) << 8) | \ ((0x100 - dat[3] - idx) & 0xff) @@ -125,14 +125,14 @@ def create_adas_time_status(bus, tt, idx): chksum = 0x1000 - dat[0] - dat[1] - dat[2] - dat[3] chksum = chksum & 0xfff dat += [0x40 + (chksum >> 8), chksum & 0xff, 0x12] - return make_can_msg(0xa1, bytes(dat), bus) + return CanData(0xa1, bytes(dat), bus) def create_adas_steering_status(bus, idx): dat = [idx << 6, 0xf0, 0x20, 0, 0, 0] chksum = 0x60 + sum(dat) dat += [chksum >> 8, chksum & 0xff] - return make_can_msg(0x306, bytes(dat), bus) + return CanData(0x306, bytes(dat), bus) def create_adas_accelerometer_speed_status(bus, speed_ms, idx): @@ -146,7 +146,7 @@ def create_adas_accelerometer_speed_status(bus, speed_ms, idx): dat = [0x08, spd >> 4, ((spd & 0xf) << 4) | (accel >> 8), accel & 0xff, 0] chksum = 0x62 + far_range_mode + (idx << 2) + dat[0] + dat[1] + dat[2] + dat[3] + dat[4] dat += [(idx << 5) + (far_range_mode << 4) + (near_range_mode << 3) + (chksum >> 8), chksum & 0xff] - return make_can_msg(0x308, bytes(dat), bus) + return CanData(0x308, bytes(dat), bus) def create_adas_headlights_status(packer, bus): @@ -170,4 +170,4 @@ def create_lka_icon_command(bus, active, critical, steer): dat = b"\x40\x40\x18" else: dat = b"\x00\x00\x00" - return make_can_msg(0x104c006c, dat, bus) + return CanData(0x104c006c, dat, bus) diff --git a/opendbc_repo/opendbc/car/gm/interface.py b/opendbc_repo/opendbc/car/gm/interface.py new file mode 100755 index 000000000000000..f3953c0eb9e95e8 --- /dev/null +++ b/opendbc_repo/opendbc/car/gm/interface.py @@ -0,0 +1,206 @@ +#!/usr/bin/env python3 +import os +from math import fabs, exp +from panda import Panda + +from opendbc.car import get_safety_config, get_friction, structs +from opendbc.car.common.basedir import BASEDIR +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.gm.radar_interface import RADAR_HEADER_MSG +from opendbc.car.gm.values import CAR, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, SDGM_CAR, CanBus +from opendbc.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs, NanoFFModel + +TransmissionType = structs.CarParams.TransmissionType +NetworkLocation = structs.CarParams.NetworkLocation + +NON_LINEAR_TORQUE_PARAMS = { + CAR.CHEVROLET_BOLT_EUV: [2.6531724862969748, 1.0, 0.1919764879840985, 0.009054123646805178], + CAR.GMC_ACADIA: [4.78003305, 1.0, 0.3122, 0.05591772], + CAR.CHEVROLET_SILVERADO: [3.29974374, 1.0, 0.25571356, 0.0465122] +} + +NEURAL_PARAMS_PATH = os.path.join(BASEDIR, 'torque_data/neural_ff_weights.json') + + +class CarInterface(CarInterfaceBase): + @staticmethod + def get_pid_accel_limits(CP, current_speed, cruise_speed): + return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX + + # Determined by iteratively plotting and minimizing error for f(angle, speed) = steer. + @staticmethod + def get_steer_feedforward_volt(desired_angle, v_ego): + desired_angle *= 0.02904609 + sigmoid = desired_angle / (1 + fabs(desired_angle)) + return 0.10006696 * sigmoid * (v_ego + 3.12485927) + + def get_steer_feedforward_function(self): + if self.CP.carFingerprint == CAR.CHEVROLET_VOLT: + return self.get_steer_feedforward_volt + else: + return CarInterfaceBase.get_steer_feedforward_default + + def torque_from_lateral_accel_siglin(self, latcontrol_inputs: LatControlInputs, torque_params: structs.CarParams.LateralTorqueTuning, + lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: + friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) + + def sig(val): + # https://timvieira.github.io/blog/post/2014/02/11/exp-normalize-trick + if val >= 0: + return 1 / (1 + exp(-val)) - 0.5 + else: + z = exp(val) + return z / (1 + z) - 0.5 + + # The "lat_accel vs torque" relationship is assumed to be the sum of "sigmoid + linear" curves + # An important thing to consider is that the slope at 0 should be > 0 (ideally >1) + # This has big effect on the stability about 0 (noise when going straight) + # ToDo: To generalize to other GMs, explore tanh function as the nonlinear + non_linear_torque_params = NON_LINEAR_TORQUE_PARAMS.get(self.CP.carFingerprint) + assert non_linear_torque_params, "The params are not defined" + a, b, c, _ = non_linear_torque_params + steer_torque = (sig(latcontrol_inputs.lateral_acceleration * a) * b) + (latcontrol_inputs.lateral_acceleration * c) + return float(steer_torque) + friction + + def torque_from_lateral_accel_neural(self, latcontrol_inputs: LatControlInputs, torque_params: structs.CarParams.LateralTorqueTuning, + lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: + friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) + inputs = list(latcontrol_inputs) + if gravity_adjusted: + inputs[0] += inputs[1] + return float(self.neural_ff_model.predict(inputs)) + friction + + def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: + if self.CP.carFingerprint == CAR.CHEVROLET_BOLT_EUV: + self.neural_ff_model = NanoFFModel(NEURAL_PARAMS_PATH, self.CP.carFingerprint) + return self.torque_from_lateral_accel_neural + elif self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: + return self.torque_from_lateral_accel_siglin + else: + return self.torque_from_lateral_accel_linear + + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "gm" + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.gm)] + ret.autoResumeSng = False + ret.enableBsm = 0x142 in fingerprint[CanBus.POWERTRAIN] + + if candidate in EV_CAR: + ret.transmissionType = TransmissionType.direct + else: + ret.transmissionType = TransmissionType.automatic + + ret.longitudinalTuning.kiBP = [5., 35.] + + if candidate in (CAMERA_ACC_CAR | SDGM_CAR): + ret.experimentalLongitudinalAvailable = candidate not in SDGM_CAR + ret.networkLocation = NetworkLocation.fwdCamera + ret.radarUnavailable = True # no radar + ret.pcmCruise = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM + ret.minEnableSpeed = -1 if candidate in SDGM_CAR else 5 * CV.KPH_TO_MS + ret.minSteerSpeed = 10 * CV.KPH_TO_MS + + # Tuning for experimental long + ret.longitudinalTuning.kiV = [2.0, 1.5] + ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling + ret.vEgoStopping = 0.25 + ret.vEgoStarting = 0.25 + + if experimental_long: + ret.pcmCruise = False + ret.openpilotLongitudinalControl = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM_LONG + + else: # ASCM, OBD-II harness + ret.openpilotLongitudinalControl = True + ret.networkLocation = NetworkLocation.gateway + ret.radarUnavailable = RADAR_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and not docs + ret.pcmCruise = False # stock non-adaptive cruise control is kept off + # supports stop and go, but initial engage must (conservatively) be above 18mph + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + ret.minSteerSpeed = 7 * CV.MPH_TO_MS + + # Tuning + ret.longitudinalTuning.kiV = [2.4, 1.5] + + # These cars have been put into dashcam only due to both a lack of users and test coverage. + # These cars likely still work fine. Once a user confirms each car works and a test route is + # added to opendbc/car/tests/routes.py, we can remove it from this list. + ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.CHEVROLET_MALIBU, CAR.BUICK_REGAL} or \ + (ret.networkLocation == NetworkLocation.gateway and ret.radarUnavailable) + + # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] + ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 + ret.steerActuatorDelay = 0.1 # Default delay, not measured yet + + ret.steerLimitTimer = 0.4 + ret.longitudinalActuatorDelay = 0.5 # large delay to initially start braking + + if candidate == CAR.CHEVROLET_VOLT: + ret.lateralTuning.pid.kpBP = [0., 40.] + ret.lateralTuning.pid.kpV = [0., 0.17] + ret.lateralTuning.pid.kiBP = [0.] + ret.lateralTuning.pid.kiV = [0.] + ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_volt() + ret.steerActuatorDelay = 0.2 + + elif candidate == CAR.GMC_ACADIA: + ret.minEnableSpeed = -1. # engage speed is decided by pcm + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.BUICK_LACROSSE: + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CADILLAC_ESCALADE: + ret.minEnableSpeed = -1. # engage speed is decided by pcm + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate in (CAR.CADILLAC_ESCALADE_ESV, CAR.CADILLAC_ESCALADE_ESV_2019): + ret.minEnableSpeed = -1. # engage speed is decided by pcm + + if candidate == CAR.CADILLAC_ESCALADE_ESV: + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[10., 41.0], [10., 41.0]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.13, 0.24], [0.01, 0.02]] + ret.lateralTuning.pid.kf = 0.000045 + else: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_BOLT_EUV: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_SILVERADO: + # On the Bolt, the ECM and camera independently check that you are either above 5 kph or at a stop + # with foot on brake to allow engagement, but this platform only has that check in the camera. + # TODO: check if this is split by EV/ICE with more platforms in the future + if ret.openpilotLongitudinalControl: + ret.minEnableSpeed = -1. + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_EQUINOX: + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_TRAILBLAZER: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CADILLAC_XT4: + ret.steerActuatorDelay = 0.2 + ret.minSteerSpeed = 30 * CV.MPH_TO_MS + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_VOLT_2019: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_TRAVERSE: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + return ret diff --git a/opendbc_repo/opendbc/car/gm/radar_interface.py b/opendbc_repo/opendbc/car/gm/radar_interface.py new file mode 100755 index 000000000000000..e79d26533b5355d --- /dev/null +++ b/opendbc_repo/opendbc/car/gm/radar_interface.py @@ -0,0 +1,100 @@ +#!/usr/bin/env python3 +import math +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.gm.values import DBC, CanBus +from opendbc.car.interfaces import RadarInterfaceBase + +RADAR_HEADER_MSG = 1120 +SLOT_1_MSG = RADAR_HEADER_MSG + 1 +NUM_SLOTS = 20 + +# Actually it's 0x47f, but can parser only reports +# messages that are present in DBC +LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS + + +def create_radar_can_parser(car_fingerprint): + # C1A-ARS3-A by Continental + radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)) + signals = list(zip(['FLRRNumValidTargets', + 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', + 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', + 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + + ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + + ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + + ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, + [RADAR_HEADER_MSG] * 7 + radar_targets * 6, strict=True)) + + messages = list({(s[1], 14) for s in signals}) + + return CANParser(DBC[car_fingerprint]['radar'], messages, CanBus.OBSTACLE) + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + + self.rcp = None if CP.radarUnavailable else create_radar_can_parser(CP.carFingerprint) + + self.trigger_msg = LAST_RADAR_MSG + self.updated_messages = set() + + def update(self, can_strings): + if self.rcp is None: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + ret = structs.RadarData() + header = self.rcp.vl[RADAR_HEADER_MSG] + fault = header['FLRRSnsrBlckd'] or header['FLRRSnstvFltPrsntInt'] or \ + header['FLRRYawRtPlsblityFlt'] or header['FLRRHWFltPrsntInt'] or \ + header['FLRRAntTngFltPrsnt'] or header['FLRRAlgnFltPrsnt'] + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + if fault: + errors.append("fault") + ret.errors = errors + + currentTargets = set() + num_targets = header['FLRRNumValidTargets'] + + # Not all radar messages describe targets, + # no need to monitor all of the self.rcp.msgs_upd + for ii in self.updated_messages: + if ii == RADAR_HEADER_MSG: + continue + + if num_targets == 0: + break + + cpt = self.rcp.vl[ii] + # Zero distance means it's an empty target slot + if cpt['TrkRange'] > 0.0: + targetId = cpt['TrkObjectID'] + currentTargets.add(targetId) + if targetId not in self.pts: + self.pts[targetId] = structs.RadarData.RadarPoint() + self.pts[targetId].trackId = targetId + distance = cpt['TrkRange'] + self.pts[targetId].dRel = distance # from front of car + # From driver's pov, left is positive + self.pts[targetId].yRel = math.sin(cpt['TrkAzimuth'] * CV.DEG_TO_RAD) * distance + self.pts[targetId].vRel = cpt['TrkRangeRate'] + self.pts[targetId].aRel = float('nan') + self.pts[targetId].yvRel = float('nan') + + for oldTarget in list(self.pts.keys()): + if oldTarget not in currentTargets: + del self.pts[oldTarget] + + ret.points = list(self.pts.values()) + self.updated_messages.clear() + return ret diff --git a/selfdrive/car/honda/__init__.py b/opendbc_repo/opendbc/car/gm/tests/__init__.py similarity index 100% rename from selfdrive/car/honda/__init__.py rename to opendbc_repo/opendbc/car/gm/tests/__init__.py diff --git a/selfdrive/car/gm/tests/test_gm.py b/opendbc_repo/opendbc/car/gm/tests/test_gm.py similarity index 80% rename from selfdrive/car/gm/tests/test_gm.py rename to opendbc_repo/opendbc/car/gm/tests/test_gm.py index a0a4a94ffa04552..c14b9bd243fa6e1 100644 --- a/selfdrive/car/gm/tests/test_gm.py +++ b/opendbc_repo/opendbc/car/gm/tests/test_gm.py @@ -1,7 +1,7 @@ from parameterized import parameterized -from openpilot.selfdrive.car.gm.fingerprints import FINGERPRINTS -from openpilot.selfdrive.car.gm.values import CAMERA_ACC_CAR, GM_RX_OFFSET +from opendbc.car.gm.fingerprints import FINGERPRINTS +from opendbc.car.gm.values import CAMERA_ACC_CAR, GM_RX_OFFSET CAMERA_DIAGNOSTIC_ADDRESS = 0x24b diff --git a/opendbc_repo/opendbc/car/gm/values.py b/opendbc_repo/opendbc/car/gm/values.py new file mode 100644 index 000000000000000..852a6fbf8585649 --- /dev/null +++ b/opendbc_repo/opendbc/car/gm/values.py @@ -0,0 +1,259 @@ +from dataclasses import dataclass, field + +from opendbc.car import dbc_dict, PlatformConfig, DbcDict, Platforms, CarSpecs +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = CarParams.Ecu + + +class CarControllerParams: + STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output + STEER_STEP = 3 # Active control frames per command (~33hz) + INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz) + STEER_DELTA_UP = 10 # Delta rates require review due to observed EPS weakness + STEER_DELTA_DOWN = 15 + STEER_DRIVER_ALLOWANCE = 65 + STEER_DRIVER_MULTIPLIER = 4 + STEER_DRIVER_FACTOR = 100 + NEAR_STOP_BRAKE_PHASE = 0.5 # m/s + + # Heartbeat for dash "Service Adaptive Cruise" and "Service Front Camera" + ADAS_KEEPALIVE_STEP = 100 + CAMERA_KEEPALIVE_STEP = 100 + + # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we + # perform the closed loop control, and might need some + # to apply some more braking if we're on a downhill slope. + # Our controller should still keep the 2 second average above + # -3.5 m/s^2 as per planner limits + ACCEL_MAX = 2. # m/s^2 + ACCEL_MIN = -4. # m/s^2 + + def __init__(self, CP): + # Gas/brake lookups + self.ZERO_GAS = 2048 # Coasting + self.MAX_BRAKE = 400 # ~ -4.0 m/s^2 with regen + + if CP.carFingerprint in (CAMERA_ACC_CAR | SDGM_CAR): + self.MAX_GAS = 3400 + self.MAX_ACC_REGEN = 1514 + self.INACTIVE_REGEN = 1554 + # Camera ACC vehicles have no regen while enabled. + # Camera transitions to MAX_ACC_REGEN from ZERO_GAS and uses friction brakes instantly + max_regen_acceleration = 0. + + else: + self.MAX_GAS = 3072 # Safety limit, not ACC max. Stock ACC >4096 from standstill. + self.MAX_ACC_REGEN = 1404 # Max ACC regen is slightly less than max paddle regen + self.INACTIVE_REGEN = 1404 + # ICE has much less engine braking force compared to regen in EVs, + # lower threshold removes some braking deadzone + max_regen_acceleration = -1. if CP.carFingerprint in EV_CAR else -0.1 + + self.GAS_LOOKUP_BP = [max_regen_acceleration, 0., self.ACCEL_MAX] + self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, self.ZERO_GAS, self.MAX_GAS] + + self.BRAKE_LOOKUP_BP = [self.ACCEL_MIN, max_regen_acceleration] + self.BRAKE_LOOKUP_V = [self.MAX_BRAKE, 0.] + + +@dataclass +class GMCarDocs(CarDocs): + package: str = "Adaptive Cruise Control (ACC)" + + def init_make(self, CP: CarParams): + if CP.networkLocation == CarParams.NetworkLocation.fwdCamera: + if CP.carFingerprint in SDGM_CAR: + self.car_parts = CarParts.common([CarHarness.gmsdgm]) + else: + self.car_parts = CarParts.common([CarHarness.gm]) + else: + self.car_parts = CarParts.common([CarHarness.obd_ii]) + + +@dataclass(frozen=True, kw_only=True) +class GMCarSpecs(CarSpecs): + tireStiffnessFactor: float = 0.444 # not optimized yet + + +@dataclass +class GMPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) + + +@dataclass +class GMASCMPlatformConfig(GMPlatformConfig): + def init(self): + # ASCM is supported, but due to a janky install and hardware configuration, we are not showing in the car docs + self.car_docs = [] + +@dataclass +class GMSDGMPlatformConfig(GMPlatformConfig): + def init(self): + # Don't show in docs until the harness is sold. See https://github.com/commaai/openpilot/issues/32471 + self.car_docs = [] + + +class CAR(Platforms): + HOLDEN_ASTRA = GMASCMPlatformConfig( + [GMCarDocs("Holden Astra 2017")], + GMCarSpecs(mass=1363, wheelbase=2.662, steerRatio=15.7, centerToFrontRatio=0.4), + ) + CHEVROLET_VOLT = GMASCMPlatformConfig( + [GMCarDocs("Chevrolet Volt 2017-18", min_enable_speed=0, video_link="https://youtu.be/QeMCN_4TFfQ")], + GMCarSpecs(mass=1607, wheelbase=2.69, steerRatio=17.7, centerToFrontRatio=0.45, tireStiffnessFactor=0.469), + ) + CADILLAC_ATS = GMASCMPlatformConfig( + [GMCarDocs("Cadillac ATS Premium Performance 2018")], + GMCarSpecs(mass=1601, wheelbase=2.78, steerRatio=15.3), + ) + CHEVROLET_MALIBU = GMASCMPlatformConfig( + [GMCarDocs("Chevrolet Malibu Premier 2017")], + GMCarSpecs(mass=1496, wheelbase=2.83, steerRatio=15.8, centerToFrontRatio=0.4), + ) + GMC_ACADIA = GMASCMPlatformConfig( + [GMCarDocs("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo")], + GMCarSpecs(mass=1975, wheelbase=2.86, steerRatio=14.4, centerToFrontRatio=0.4), + ) + BUICK_LACROSSE = GMASCMPlatformConfig( + [GMCarDocs("Buick LaCrosse 2017-19", "Driver Confidence Package 2")], + GMCarSpecs(mass=1712, wheelbase=2.91, steerRatio=15.8, centerToFrontRatio=0.4), + ) + BUICK_REGAL = GMASCMPlatformConfig( + [GMCarDocs("Buick Regal Essence 2018")], + GMCarSpecs(mass=1714, wheelbase=2.83, steerRatio=14.4, centerToFrontRatio=0.4), + ) + CADILLAC_ESCALADE = GMASCMPlatformConfig( + [GMCarDocs("Cadillac Escalade 2017", "Driver Assist Package")], + GMCarSpecs(mass=2564, wheelbase=2.95, steerRatio=17.3), + ) + CADILLAC_ESCALADE_ESV = GMASCMPlatformConfig( + [GMCarDocs("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS")], + GMCarSpecs(mass=2739, wheelbase=3.302, steerRatio=17.3, tireStiffnessFactor=1.0), + ) + CADILLAC_ESCALADE_ESV_2019 = GMASCMPlatformConfig( + [GMCarDocs("Cadillac Escalade ESV 2019", "Adaptive Cruise Control (ACC) & LKAS")], + CADILLAC_ESCALADE_ESV.specs, + ) + CHEVROLET_BOLT_EUV = GMPlatformConfig( + [ + GMCarDocs("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210"), + GMCarDocs("Chevrolet Bolt EV 2022-23", "2LT Trim with Adaptive Cruise Control Package"), + ], + GMCarSpecs(mass=1669, wheelbase=2.63779, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), + ) + CHEVROLET_SILVERADO = GMPlatformConfig( + [ + GMCarDocs("Chevrolet Silverado 1500 2020-21", "Safety Package II"), + GMCarDocs("GMC Sierra 1500 2020-21", "Driver Alert Package II", video_link="https://youtu.be/5HbNoBLzRwE"), + ], + GMCarSpecs(mass=2450, wheelbase=3.75, steerRatio=16.3, tireStiffnessFactor=1.0), + ) + CHEVROLET_EQUINOX = GMPlatformConfig( + [GMCarDocs("Chevrolet Equinox 2019-22")], + GMCarSpecs(mass=1588, wheelbase=2.72, steerRatio=14.4, centerToFrontRatio=0.4), + ) + CHEVROLET_TRAILBLAZER = GMPlatformConfig( + [GMCarDocs("Chevrolet Trailblazer 2021-22")], + GMCarSpecs(mass=1345, wheelbase=2.64, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), + ) + CADILLAC_XT4 = GMSDGMPlatformConfig( + [GMCarDocs("Cadillac XT4 2023", "Driver Assist Package")], + CarSpecs(mass=1660, wheelbase=2.78, steerRatio=14.4, centerToFrontRatio=0.4), + ) + CHEVROLET_VOLT_2019 = GMSDGMPlatformConfig( + [GMCarDocs("Chevrolet Volt 2019", "Adaptive Cruise Control (ACC) & LKAS")], + GMCarSpecs(mass=1607, wheelbase=2.69, steerRatio=15.7, centerToFrontRatio=0.45), + ) + CHEVROLET_TRAVERSE = GMSDGMPlatformConfig( + [GMCarDocs("Chevrolet Traverse 2022-23", "RS, Premier, or High Country Trim")], + CarSpecs(mass=1955, wheelbase=3.07, steerRatio=17.9, centerToFrontRatio=0.4), + ) + + +class CruiseButtons: + INIT = 0 + UNPRESS = 1 + RES_ACCEL = 2 + DECEL_SET = 3 + MAIN = 5 + CANCEL = 6 + +class AccState: + OFF = 0 + ACTIVE = 1 + FAULTED = 3 + STANDSTILL = 4 + +class CanBus: + POWERTRAIN = 0 + OBSTACLE = 1 + CAMERA = 2 + CHASSIS = 2 + LOOPBACK = 128 + DROPPED = 192 + + +# In a Data Module, an identifier is a string used to recognize an object, +# either by itself or together with the identifiers of parent objects. +# Each returns a 4 byte hex representation of the decimal part number. `b"\x02\x8c\xf0'"` -> 42790951 +GM_BOOT_SOFTWARE_PART_NUMER_REQUEST = b'\x1a\xc0' # likely does not contain anything useful +GM_SOFTWARE_MODULE_1_REQUEST = b'\x1a\xc1' +GM_SOFTWARE_MODULE_2_REQUEST = b'\x1a\xc2' +GM_SOFTWARE_MODULE_3_REQUEST = b'\x1a\xc3' + +# Part number of XML data file that is used to configure ECU +GM_XML_DATA_FILE_PART_NUMBER = b'\x1a\x9c' +GM_XML_CONFIG_COMPAT_ID = b'\x1a\x9b' # used to know if XML file is compatible with the ECU software/hardware + +# This DID is for identifying the part number that reflects the mix of hardware, +# software, and calibrations in the ECU when it first arrives at the vehicle assembly plant. +# If there's an Alpha Code, it's associated with this part number and stored in the DID $DB. +GM_END_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcb' +GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdb' +GM_BASE_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcc' +GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdc' +GM_FW_RESPONSE = b'\x5a' + +GM_FW_REQUESTS = [ + GM_BOOT_SOFTWARE_PART_NUMER_REQUEST, + GM_SOFTWARE_MODULE_1_REQUEST, + GM_SOFTWARE_MODULE_2_REQUEST, + GM_SOFTWARE_MODULE_3_REQUEST, + GM_XML_DATA_FILE_PART_NUMBER, + GM_XML_CONFIG_COMPAT_ID, + GM_END_MODEL_PART_NUMBER_REQUEST, + GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, + GM_BASE_MODEL_PART_NUMBER_REQUEST, + GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, +] + +GM_RX_OFFSET = 0x400 + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[request for req in GM_FW_REQUESTS for request in [ + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, req], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, GM_FW_RESPONSE + bytes([req[-1]])], + rx_offset=GM_RX_OFFSET, + bus=0, + logging=True, + ), + ]], + extra_ecus=[(Ecu.fwdCamera, 0x24b, None)], +) + +# TODO: detect most of these sets live +EV_CAR = {CAR.CHEVROLET_VOLT, CAR.CHEVROLET_VOLT_2019, CAR.CHEVROLET_BOLT_EUV} + +# We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) +CAMERA_ACC_CAR = {CAR.CHEVROLET_BOLT_EUV, CAR.CHEVROLET_SILVERADO, CAR.CHEVROLET_EQUINOX, CAR.CHEVROLET_TRAILBLAZER} + +# We're integrated at the Safety Data Gateway Module on these cars +SDGM_CAR = {CAR.CADILLAC_XT4, CAR.CHEVROLET_VOLT_2019, CAR.CHEVROLET_TRAVERSE} + +STEER_THRESHOLD = 1.0 + +DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/honda/tests/__init__.py b/opendbc_repo/opendbc/car/honda/__init__.py similarity index 100% rename from selfdrive/car/honda/tests/__init__.py rename to opendbc_repo/opendbc/car/honda/__init__.py diff --git a/opendbc_repo/opendbc/car/honda/carcontroller.py b/opendbc_repo/opendbc/car/honda/carcontroller.py new file mode 100644 index 000000000000000..6239898b754b0f7 --- /dev/null +++ b/opendbc_repo/opendbc/car/honda/carcontroller.py @@ -0,0 +1,249 @@ +from collections import namedtuple + +from opendbc.can.packer import CANPacker +from opendbc.car import DT_CTRL, rate_limit, make_tester_present_msg, structs +from opendbc.car.common.numpy_fast import clip, interp +from opendbc.car.honda import hondacan +from opendbc.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams +from opendbc.car.interfaces import CarControllerBase + +VisualAlert = structs.CarControl.HUDControl.VisualAlert +LongCtrlState = structs.CarControl.Actuators.LongControlState + + +def compute_gb_honda_bosch(accel, speed): + # TODO returns 0s, is unused + return 0.0, 0.0 + + +def compute_gb_honda_nidec(accel, speed): + creep_brake = 0.0 + creep_speed = 2.3 + creep_brake_value = 0.15 + if speed < creep_speed: + creep_brake = (creep_speed - speed) / creep_speed * creep_brake_value + gb = float(accel) / 4.8 - creep_brake + return clip(gb, 0.0, 1.0), clip(-gb, 0.0, 1.0) + + +def compute_gas_brake(accel, speed, fingerprint): + if fingerprint in HONDA_BOSCH: + return compute_gb_honda_bosch(accel, speed) + else: + return compute_gb_honda_nidec(accel, speed) + + +# TODO not clear this does anything useful +def actuator_hysteresis(brake, braking, brake_steady, v_ego, car_fingerprint): + # hyst params + brake_hyst_on = 0.02 # to activate brakes exceed this value + brake_hyst_off = 0.005 # to deactivate brakes below this value + brake_hyst_gap = 0.01 # don't change brake command for small oscillations within this value + + # *** hysteresis logic to avoid brake blinking. go above 0.1 to trigger + if (brake < brake_hyst_on and not braking) or brake < brake_hyst_off: + brake = 0. + braking = brake > 0. + + # for small brake oscillations within brake_hyst_gap, don't change the brake command + if brake == 0.: + brake_steady = 0. + elif brake > brake_steady + brake_hyst_gap: + brake_steady = brake - brake_hyst_gap + elif brake < brake_steady - brake_hyst_gap: + brake_steady = brake + brake_hyst_gap + brake = brake_steady + + return brake, braking, brake_steady + + +def brake_pump_hysteresis(apply_brake, apply_brake_last, last_pump_ts, ts): + pump_on = False + + # reset pump timer if: + # - there is an increment in brake request + # - we are applying steady state brakes and we haven't been running the pump + # for more than 20s (to prevent pressure bleeding) + if apply_brake > apply_brake_last or (ts - last_pump_ts > 20. and apply_brake > 0): + last_pump_ts = ts + + # once the pump is on, run it for at least 0.2s + if ts - last_pump_ts < 0.2 and apply_brake > 0: + pump_on = True + + return pump_on, last_pump_ts + + +def process_hud_alert(hud_alert): + # initialize to no alert + fcw_display = 0 + steer_required = 0 + acc_alert = 0 + + # priority is: FCW, steer required, all others + if hud_alert == VisualAlert.fcw: + fcw_display = VISUAL_HUD[hud_alert.raw] + elif hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw): + steer_required = VISUAL_HUD[hud_alert.raw] + else: + acc_alert = VISUAL_HUD[hud_alert.raw] + + return fcw_display, steer_required, acc_alert + + +HUDData = namedtuple("HUDData", + ["pcm_accel", "v_cruise", "lead_visible", + "lanes_visible", "fcw", "acc_alert", "steer_required", "lead_distance_bars"]) + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.packer = CANPacker(dbc_name) + self.params = CarControllerParams(CP) + self.CAN = hondacan.CanBus(CP) + + self.braking = False + self.brake_steady = 0. + self.brake_last = 0. + self.apply_brake_last = 0 + self.last_pump_ts = 0. + self.stopping_counter = 0 + + self.accel = 0.0 + self.speed = 0.0 + self.gas = 0.0 + self.brake = 0.0 + self.last_steer = 0.0 + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + conversion = hondacan.get_cruise_speed_conversion(self.CP.carFingerprint, CS.is_metric) + hud_v_cruise = hud_control.setSpeed / conversion if hud_control.speedVisible else 255 + pcm_cancel_cmd = CC.cruiseControl.cancel + + if CC.longActive: + accel = actuators.accel + gas, brake = compute_gas_brake(actuators.accel, CS.out.vEgo, self.CP.carFingerprint) + else: + accel = 0.0 + gas, brake = 0.0, 0.0 + + # *** rate limit steer *** + limited_steer = rate_limit(actuators.steer, self.last_steer, -self.params.STEER_DELTA_DOWN * DT_CTRL, + self.params.STEER_DELTA_UP * DT_CTRL) + self.last_steer = limited_steer + + # *** apply brake hysteresis *** + pre_limit_brake, self.braking, self.brake_steady = actuator_hysteresis(brake, self.braking, self.brake_steady, + CS.out.vEgo, self.CP.carFingerprint) + + # *** rate limit after the enable check *** + self.brake_last = rate_limit(pre_limit_brake, self.brake_last, -2., DT_CTRL) + + # vehicle hud display, wait for one update from 10Hz 0x304 msg + fcw_display, steer_required, acc_alert = process_hud_alert(hud_control.visualAlert) + + # **** process the car messages **** + + # steer torque is converted back to CAN reference (positive when steering right) + apply_steer = int(interp(-limited_steer * self.params.STEER_MAX, + self.params.STEER_LOOKUP_BP, self.params.STEER_LOOKUP_V)) + + # Send CAN commands + can_sends = [] + + # tester present - w/ no response (keeps radar disabled) + if self.CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and self.CP.openpilotLongitudinalControl: + if self.frame % 10 == 0: + can_sends.append(make_tester_present_msg(0x18DAB0F1, 1, suppress_response=True)) + + # Send steering command. + can_sends.append(hondacan.create_steering_control(self.packer, self.CAN, apply_steer, CC.latActive, self.CP.carFingerprint, + CS.CP.openpilotLongitudinalControl)) + + # wind brake from air resistance decel at high speed + wind_brake = interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15]) + # all of this is only relevant for HONDA NIDEC + max_accel = interp(CS.out.vEgo, self.params.NIDEC_MAX_ACCEL_BP, self.params.NIDEC_MAX_ACCEL_V) + # TODO this 1.44 is just to maintain previous behavior + pcm_speed_BP = [-wind_brake, + -wind_brake * (3 / 4), + 0.0, + 0.5] + # The Honda ODYSSEY seems to have different PCM_ACCEL + # msgs, is it other cars too? + if not CC.longActive: + pcm_speed = 0.0 + pcm_accel = int(0.0) + elif self.CP.carFingerprint in HONDA_NIDEC_ALT_PCM_ACCEL: + pcm_speed_V = [0.0, + clip(CS.out.vEgo - 3.0, 0.0, 100.0), + clip(CS.out.vEgo + 0.0, 0.0, 100.0), + clip(CS.out.vEgo + 5.0, 0.0, 100.0)] + pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) + pcm_accel = int(1.0 * self.params.NIDEC_GAS_MAX) + else: + pcm_speed_V = [0.0, + clip(CS.out.vEgo - 2.0, 0.0, 100.0), + clip(CS.out.vEgo + 2.0, 0.0, 100.0), + clip(CS.out.vEgo + 5.0, 0.0, 100.0)] + pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) + pcm_accel = int(clip((accel / 1.44) / max_accel, 0.0, 1.0) * self.params.NIDEC_GAS_MAX) + + if not self.CP.openpilotLongitudinalControl: + if self.frame % 2 == 0 and self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: # radarless cars don't have supplemental message + can_sends.append(hondacan.create_bosch_supplemental_1(self.packer, self.CAN, self.CP.carFingerprint)) + # If using stock ACC, spam cancel command to kill gas when OP disengages. + if pcm_cancel_cmd: + can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.CANCEL, self.CP.carFingerprint)) + elif CC.cruiseControl.resume: + can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.RES_ACCEL, self.CP.carFingerprint)) + + else: + # Send gas and brake commands. + if self.frame % 2 == 0: + ts = self.frame * DT_CTRL + + if self.CP.carFingerprint in HONDA_BOSCH: + self.accel = clip(accel, self.params.BOSCH_ACCEL_MIN, self.params.BOSCH_ACCEL_MAX) + self.gas = interp(accel, self.params.BOSCH_GAS_LOOKUP_BP, self.params.BOSCH_GAS_LOOKUP_V) + + stopping = actuators.longControlState == LongCtrlState.stopping + self.stopping_counter = self.stopping_counter + 1 if stopping else 0 + can_sends.extend(hondacan.create_acc_commands(self.packer, self.CAN, CC.enabled, CC.longActive, self.accel, self.gas, + self.stopping_counter, self.CP.carFingerprint)) + else: + apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0) + apply_brake = int(clip(apply_brake * self.params.NIDEC_BRAKE_MAX, 0, self.params.NIDEC_BRAKE_MAX - 1)) + pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) + + pcm_override = True + can_sends.append(hondacan.create_brake_command(self.packer, self.CAN, apply_brake, pump_on, + pcm_override, pcm_cancel_cmd, fcw_display, + self.CP.carFingerprint, CS.stock_brake)) + self.apply_brake_last = apply_brake + self.brake = apply_brake / self.params.NIDEC_BRAKE_MAX + + # Send dashboard UI commands. + # On Nidec, this controls longitudinal positive acceleration + if self.frame % 10 == 0: + hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_control.leadVisible, + hud_control.lanesVisible, fcw_display, acc_alert, steer_required, hud_control.leadDistanceBars) + can_sends.extend(hondacan.create_ui_commands(self.packer, self.CAN, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, CS.acc_hud, CS.lkas_hud)) + + if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint not in HONDA_BOSCH: + self.speed = pcm_speed + self.gas = pcm_accel / self.params.NIDEC_GAS_MAX + + new_actuators = actuators.as_builder() + new_actuators.speed = self.speed + new_actuators.accel = self.accel + new_actuators.gas = self.gas + new_actuators.brake = self.brake + new_actuators.steer = self.last_steer + new_actuators.steerOutputCan = apply_steer + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/honda/carstate.py b/opendbc_repo/opendbc/car/honda/carstate.py new file mode 100644 index 000000000000000..91409d7f45d116f --- /dev/null +++ b/opendbc_repo/opendbc/car/honda/carstate.py @@ -0,0 +1,307 @@ +from collections import defaultdict + +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from opendbc.car import create_button_events, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.common.numpy_fast import interp +from opendbc.car.honda.hondacan import CanBus, get_cruise_speed_conversion +from opendbc.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, \ + HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS, \ + HondaFlags, CruiseButtons, CruiseSettings +from opendbc.car.interfaces import CarStateBase + +TransmissionType = structs.CarParams.TransmissionType +ButtonType = structs.CarState.ButtonEvent.Type + +BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, + CruiseButtons.MAIN: ButtonType.mainCruise, CruiseButtons.CANCEL: ButtonType.cancel} +SETTINGS_BUTTONS_DICT = {CruiseSettings.DISTANCE: ButtonType.gapAdjustCruise, CruiseSettings.LKAS: ButtonType.lkas} + + +def get_can_messages(CP, gearbox_msg): + messages = [ + ("ENGINE_DATA", 100), + ("WHEEL_SPEEDS", 50), + ("STEERING_SENSORS", 100), + ("SEATBELT_STATUS", 10), + ("CRUISE", 10), + ("POWERTRAIN_DATA", 100), + ("CAR_SPEED", 10), + ("VSA_STATUS", 50), + ("STEER_STATUS", 100), + ("STEER_MOTOR_TORQUE", 0), # TODO: not on every car + ] + + if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: + messages += [ + ("SCM_FEEDBACK", 25), + ("SCM_BUTTONS", 50), + ] + else: + messages += [ + ("SCM_FEEDBACK", 10), + ("SCM_BUTTONS", 25), + ] + + if CP.carFingerprint in (CAR.HONDA_CRV_HYBRID, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E): + messages.append((gearbox_msg, 50)) + else: + messages.append((gearbox_msg, 100)) + + if CP.flags & HondaFlags.BOSCH_ALT_BRAKE: + messages.append(("BRAKE_MODULE", 50)) + + if CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): + messages.append(("EPB_STATUS", 50)) + + if CP.carFingerprint in HONDA_BOSCH: + # these messages are on camera bus on radarless cars + if not CP.openpilotLongitudinalControl and CP.carFingerprint not in HONDA_BOSCH_RADARLESS: + messages += [ + ("ACC_HUD", 10), + ("ACC_CONTROL", 50), + ] + else: # Nidec signals + if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: + messages.append(("CRUISE_PARAMS", 10)) + else: + messages.append(("CRUISE_PARAMS", 50)) + + # TODO: clean this up + if CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, + CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): + pass + elif CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): + pass + else: + messages.append(("DOORS_STATUS", 3)) + + if CP.carFingerprint in HONDA_BOSCH_RADARLESS: + messages.append(("CRUISE_FAULT_STATUS", 50)) + elif CP.openpilotLongitudinalControl: + messages.append(("STANDSTILL", 50)) + + return messages + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.gearbox_msg = "GEARBOX" + if CP.carFingerprint == CAR.HONDA_ACCORD and CP.transmissionType == TransmissionType.cvt: + self.gearbox_msg = "GEARBOX_15T" + + self.main_on_sig_msg = "SCM_FEEDBACK" + if CP.carFingerprint in HONDA_NIDEC_ALT_SCM_MESSAGES: + self.main_on_sig_msg = "SCM_BUTTONS" + + self.shifter_values = can_define.dv[self.gearbox_msg]["GEAR_SHIFTER"] + self.steer_status_values = defaultdict(lambda: "UNKNOWN", can_define.dv["STEER_STATUS"]["STEER_STATUS"]) + + self.brake_switch_prev = False + self.brake_switch_active = False + self.cruise_setting = 0 + self.v_cruise_pcm_prev = 0 + + # When available we use cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] to populate vEgoCluster + # However, on cars without a digital speedometer this is not always present (HRV, FIT, CRV 2016, ILX and RDX) + self.dash_speed_seen = False + + def update(self, cp, cp_cam, _, cp_body, __) -> structs.CarState: + ret = structs.CarState() + + # car params + v_weight_v = [0., 1.] # don't trust smooth speed at low values to avoid premature zero snapping + v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero + + # update prevs, update must run once per loop + prev_cruise_buttons = self.cruise_buttons + prev_cruise_setting = self.cruise_setting + self.cruise_setting = cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] + self.cruise_buttons = cp.vl["SCM_BUTTONS"]["CRUISE_BUTTONS"] + + # used for car hud message + self.is_metric = not cp.vl["CAR_SPEED"]["IMPERIAL_UNIT"] + + # ******************* parse out can ******************* + # STANDSTILL->WHEELS_MOVING bit can be noisy around zero, so use XMISSION_SPEED + # panda checks if the signal is non-zero + ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 1e-5 + # TODO: find a common signal across all cars + if self.CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, + CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): + ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) + elif self.CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): + ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"]) + else: + ret.doorOpen = any([cp.vl["DOORS_STATUS"]["DOOR_OPEN_FL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_FR"], + cp.vl["DOORS_STATUS"]["DOOR_OPEN_RL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_RR"]]) + ret.seatbeltUnlatched = bool(cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LAMP"] or not cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LATCHED"]) + + steer_status = self.steer_status_values[cp.vl["STEER_STATUS"]["STEER_STATUS"]] + ret.steerFaultPermanent = steer_status not in ("NORMAL", "NO_TORQUE_ALERT_1", "NO_TORQUE_ALERT_2", "LOW_SPEED_LOCKOUT", "TMP_FAULT") + # LOW_SPEED_LOCKOUT is not worth a warning + # NO_TORQUE_ALERT_2 can be caused by bump or steering nudge from driver + ret.steerFaultTemporary = steer_status not in ("NORMAL", "LOW_SPEED_LOCKOUT", "NO_TORQUE_ALERT_2") + + if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: + ret.accFaulted = bool(cp.vl["CRUISE_FAULT_STATUS"]["CRUISE_FAULT"]) + else: + # On some cars, these two signals are always 1, this flag is masking a bug in release + # FIXME: find and set the ACC faulted signals on more platforms + if self.CP.openpilotLongitudinalControl: + ret.accFaulted = bool(cp.vl["STANDSTILL"]["BRAKE_ERROR_1"] or cp.vl["STANDSTILL"]["BRAKE_ERROR_2"]) + + # Log non-critical stock ACC/LKAS faults if Nidec (camera) + if self.CP.carFingerprint not in HONDA_BOSCH: + ret.carFaultedNonCritical = bool(cp_cam.vl["ACC_HUD"]["ACC_PROBLEM"] or cp_cam.vl["LKAS_HUD"]["LKAS_PROBLEM"]) + + ret.espDisabled = cp.vl["VSA_STATUS"]["ESP_DISABLED"] != 0 + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], + ) + v_wheel = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.0 + + # blend in transmission speed at low speed, since it has more low speed accuracy + v_weight = interp(v_wheel, v_weight_bp, v_weight_v) + ret.vEgoRaw = (1. - v_weight) * cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] * CV.KPH_TO_MS * self.CP.wheelSpeedFactor + v_weight * v_wheel + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + + self.dash_speed_seen = self.dash_speed_seen or cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] > 1e-3 + if self.dash_speed_seen: + conversion = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS + ret.vEgoCluster = cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] * conversion + + ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE"] + ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE_RATE"] + + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk( + 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) + ret.brakeHoldActive = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] == 1 + + # TODO: set for all cars + if self.CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): + ret.parkingBrake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0 + + gear = int(cp.vl[self.gearbox_msg]["GEAR_SHIFTER"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear, None)) + + ret.gas = cp.vl["POWERTRAIN_DATA"]["PEDAL_GAS"] + ret.gasPressed = ret.gas > 1e-5 + + ret.steeringTorque = cp.vl["STEER_STATUS"]["STEER_TORQUE_SENSOR"] + ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]["MOTOR_TORQUE"] + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD.get(self.CP.carFingerprint, 1200) + + if self.CP.carFingerprint in HONDA_BOSCH: + # The PCM always manages its own cruise control state, but doesn't publish it + if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: + ret.cruiseState.nonAdaptive = cp_cam.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"] != 0 + + if not self.CP.openpilotLongitudinalControl: + # ACC_HUD is on camera bus on radarless cars + acc_hud = cp_cam.vl["ACC_HUD"] if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS else cp.vl["ACC_HUD"] + ret.cruiseState.nonAdaptive = acc_hud["CRUISE_CONTROL_LABEL"] != 0 + ret.cruiseState.standstill = acc_hud["CRUISE_SPEED"] == 252. + + conversion = get_cruise_speed_conversion(self.CP.carFingerprint, self.is_metric) + # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. + ret.cruiseState.speed = self.v_cruise_pcm_prev if acc_hud["CRUISE_SPEED"] > 160.0 else acc_hud["CRUISE_SPEED"] * conversion + self.v_cruise_pcm_prev = ret.cruiseState.speed + else: + ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS + + if self.CP.flags & HondaFlags.BOSCH_ALT_BRAKE: + ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 + else: + # brake switch has shown some single time step noise, so only considered when + # switch is on for at least 2 consecutive CAN samples + # brake switch rises earlier than brake pressed but is never 1 when in park + brake_switch_vals = cp.vl_all["POWERTRAIN_DATA"]["BRAKE_SWITCH"] + if len(brake_switch_vals): + brake_switch = cp.vl["POWERTRAIN_DATA"]["BRAKE_SWITCH"] != 0 + if len(brake_switch_vals) > 1: + self.brake_switch_prev = brake_switch_vals[-2] != 0 + self.brake_switch_active = brake_switch and self.brake_switch_prev + self.brake_switch_prev = brake_switch + ret.brakePressed = (cp.vl["POWERTRAIN_DATA"]["BRAKE_PRESSED"] != 0) or self.brake_switch_active + + ret.brake = cp.vl["VSA_STATUS"]["USER_BRAKE"] + ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0 + ret.cruiseState.available = bool(cp.vl[self.main_on_sig_msg]["MAIN_ON"]) + + # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models + if self.CP.carFingerprint in (CAR.HONDA_PILOT, CAR.HONDA_RIDGELINE): + if ret.brake > 0.1: + ret.brakePressed = True + + if self.CP.carFingerprint in HONDA_BOSCH: + # TODO: find the radarless AEB_STATUS bit and make sure ACCEL_COMMAND is correct to enable AEB alerts + if self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: + ret.stockAeb = (not self.CP.openpilotLongitudinalControl) and bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) + else: + ret.stockAeb = bool(cp_cam.vl["BRAKE_COMMAND"]["AEB_REQ_1"] and cp_cam.vl["BRAKE_COMMAND"]["COMPUTER_BRAKE"] > 1e-5) + + self.acc_hud = False + self.lkas_hud = False + if self.CP.carFingerprint not in HONDA_BOSCH: + ret.stockFcw = cp_cam.vl["BRAKE_COMMAND"]["FCW"] != 0 + self.acc_hud = cp_cam.vl["ACC_HUD"] + self.stock_brake = cp_cam.vl["BRAKE_COMMAND"] + if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: + self.lkas_hud = cp_cam.vl["LKAS_HUD"] + + if self.CP.enableBsm: + # BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0 + # more info here: https://github.com/commaai/openpilot/pull/1867 + ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]["BSM_ALERT"] == 1 + ret.rightBlindspot = cp_body.vl["BSM_STATUS_RIGHT"]["BSM_ALERT"] == 1 + + ret.buttonEvents = [ + *create_button_events(self.cruise_buttons, prev_cruise_buttons, BUTTONS_DICT), + *create_button_events(self.cruise_setting, prev_cruise_setting, SETTINGS_BUTTONS_DICT), + ] + + return ret + + def get_can_parser(self, CP): + messages = get_can_messages(CP, self.gearbox_msg) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).pt) + + @staticmethod + def get_cam_can_parser(CP): + messages = [ + ("STEERING_CONTROL", 100), + ] + + if CP.carFingerprint in HONDA_BOSCH_RADARLESS: + messages += [ + ("ACC_HUD", 10), + ("LKAS_HUD", 10), + ] + + elif CP.carFingerprint not in HONDA_BOSCH: + messages += [ + ("ACC_HUD", 10), + ("LKAS_HUD", 10), + ("BRAKE_COMMAND", 50), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) + + @staticmethod + def get_body_can_parser(CP): + if CP.enableBsm: + messages = [ + ("BSM_STATUS_LEFT", 3), + ("BSM_STATUS_RIGHT", 3), + ] + bus_body = CanBus(CP).radar # B-CAN is forwarded to ACC-CAN radar side (CAN 0 on fake ethernet port) + return CANParser(DBC[CP.carFingerprint]["body"], messages, bus_body) + return None diff --git a/opendbc_repo/opendbc/car/honda/fingerprints.py b/opendbc_repo/opendbc/car/honda/fingerprints.py new file mode 100644 index 000000000000000..663bf6510748340 --- /dev/null +++ b/opendbc_repo/opendbc/car/honda/fingerprints.py @@ -0,0 +1,901 @@ +from opendbc.car.structs import CarParams +from opendbc.car.honda.values import CAR + +Ecu = CarParams.Ecu + +# Modified FW can be identified by the second dash being replaced by a comma +# For example: `b'39990-TVA,A150\x00\x00'` +# +# TODO: vsa is "essential" for fpv2 but doesn't appear on some CAR.FREED models + + +FW_VERSIONS = { + CAR.HONDA_ACCORD: { + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TVC-A910\x00\x00', + b'54008-TWA-A910\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-6A7-A220\x00\x00', + b'28101-6A7-A230\x00\x00', + b'28101-6A7-A320\x00\x00', + b'28101-6A7-A330\x00\x00', + b'28101-6A7-A410\x00\x00', + b'28101-6A7-A510\x00\x00', + b'28101-6A7-A610\x00\x00', + b'28101-6A7-A710\x00\x00', + b'28101-6A9-H140\x00\x00', + b'28101-6A9-H420\x00\x00', + b'28102-6B8-A560\x00\x00', + b'28102-6B8-A570\x00\x00', + b'28102-6B8-A700\x00\x00', + b'28102-6B8-A800\x00\x00', + b'28102-6B8-C560\x00\x00', + b'28102-6B8-C570\x00\x00', + b'28102-6B8-M520\x00\x00', + b'28102-6B8-R700\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TVA-A050\x00\x00', + b'46114-TVA-A060\x00\x00', + b'46114-TVA-A080\x00\x00', + b'46114-TVA-A120\x00\x00', + b'46114-TVA-A320\x00\x00', + b'46114-TVA-A410\x00\x00', + b'46114-TVE-H550\x00\x00', + b'46114-TVE-H560\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TVA-B040\x00\x00', + b'57114-TVA-B050\x00\x00', + b'57114-TVA-B060\x00\x00', + b'57114-TVA-B530\x00\x00', + b'57114-TVA-C040\x00\x00', + b'57114-TVA-C050\x00\x00', + b'57114-TVA-C060\x00\x00', + b'57114-TVA-C530\x00\x00', + b'57114-TVA-E520\x00\x00', + b'57114-TVE-H250\x00\x00', + b'57114-TWA-A040\x00\x00', + b'57114-TWA-A050\x00\x00', + b'57114-TWA-A530\x00\x00', + b'57114-TWA-B520\x00\x00', + b'57114-TWA-C510\x00\x00', + b'57114-TWB-H030\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBX-H120\x00\x00', + b'39990-TVA,A150\x00\x00', + b'39990-TVA-A140\x00\x00', + b'39990-TVA-A150\x00\x00', + b'39990-TVA-A160\x00\x00', + b'39990-TVA-A340\x00\x00', + b'39990-TVA-X030\x00\x00', + b'39990-TVA-X040\x00\x00', + b'39990-TVE-H130\x00\x00', + b'39990-TWB-H120\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBX-H230\x00\x00', + b'77959-TVA-A460\x00\x00', + b'77959-TVA-F330\x00\x00', + b'77959-TVA-H230\x00\x00', + b'77959-TVA-L420\x00\x00', + b'77959-TVA-X330\x00\x00', + b'77959-TWA-A440\x00\x00', + b'77959-TWA-L420\x00\x00', + b'77959-TWB-H220\x00\x00', + ], + (Ecu.hud, 0x18da61f1, None): [ + b'78209-TVA-A010\x00\x00', + b'78209-TVA-A110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TBX-H140\x00\x00', + b'36802-TVA-A150\x00\x00', + b'36802-TVA-A160\x00\x00', + b'36802-TVA-A170\x00\x00', + b'36802-TVA-A180\x00\x00', + b'36802-TVA-A330\x00\x00', + b'36802-TVC-A330\x00\x00', + b'36802-TVE-H070\x00\x00', + b'36802-TWA-A070\x00\x00', + b'36802-TWA-A080\x00\x00', + b'36802-TWA-A210\x00\x00', + b'36802-TWA-A330\x00\x00', + b'36802-TWB-H060\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TBX-H130\x00\x00', + b'36161-TVA-A060\x00\x00', + b'36161-TVA-A330\x00\x00', + b'36161-TVC-A330\x00\x00', + b'36161-TVE-H050\x00\x00', + b'36161-TWA-A070\x00\x00', + b'36161-TWA-A330\x00\x00', + b'36161-TWB-H040\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TVA-A010\x00\x00', + b'38897-TVA-A020\x00\x00', + b'38897-TVA-A230\x00\x00', + b'38897-TVA-A240\x00\x00', + b'38897-TWA-A120\x00\x00', + b'38897-TWD-J020\x00\x00', + ], + }, + CAR.HONDA_CIVIC: { + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5CG-A040\x00\x00', + b'28101-5CG-A050\x00\x00', + b'28101-5CG-A070\x00\x00', + b'28101-5CG-A080\x00\x00', + b'28101-5CG-A320\x00\x00', + b'28101-5CG-A810\x00\x00', + b'28101-5CG-A820\x00\x00', + b'28101-5DJ-A040\x00\x00', + b'28101-5DJ-A060\x00\x00', + b'28101-5DJ-A510\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TBA-A540\x00\x00', + b'57114-TBA-A550\x00\x00', + b'57114-TBA-A560\x00\x00', + b'57114-TBA-A570\x00\x00', + b'57114-TEA-Q220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBA,A030\x00\x00', + b'39990-TBA-A030\x00\x00', + b'39990-TBG-A030\x00\x00', + b'39990-TEA-T020\x00\x00', + b'39990-TEG-A010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBA-A030\x00\x00', + b'77959-TBA-A040\x00\x00', + b'77959-TBG-A020\x00\x00', + b'77959-TBG-A030\x00\x00', + b'77959-TEA-Q820\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TBA-A020\x00\x00', + b'36161-TBA-A030\x00\x00', + b'36161-TBA-A040\x00\x00', + b'36161-TBC-A020\x00\x00', + b'36161-TBC-A030\x00\x00', + b'36161-TED-Q320\x00\x00', + b'36161-TEG-A010\x00\x00', + b'36161-TEG-A020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A010\x00\x00', + b'38897-TBA-A020\x00\x00', + ], + }, + CAR.HONDA_CIVIC_BOSCH: { + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5CG-A920\x00\x00', + b'28101-5CG-AB10\x00\x00', + b'28101-5CG-C110\x00\x00', + b'28101-5CG-C220\x00\x00', + b'28101-5CG-C320\x00\x00', + b'28101-5CG-G020\x00\x00', + b'28101-5CG-L020\x00\x00', + b'28101-5CK-A130\x00\x00', + b'28101-5CK-A140\x00\x00', + b'28101-5CK-A150\x00\x00', + b'28101-5CK-C130\x00\x00', + b'28101-5CK-C140\x00\x00', + b'28101-5CK-C150\x00\x00', + b'28101-5CK-G210\x00\x00', + b'28101-5CK-J710\x00\x00', + b'28101-5CK-Q610\x00\x00', + b'28101-5DJ-A610\x00\x00', + b'28101-5DJ-A710\x00\x00', + b'28101-5DV-E330\x00\x00', + b'28101-5DV-E610\x00\x00', + b'28101-5DV-E820\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TBG-A330\x00\x00', + b'57114-TBG-A340\x00\x00', + b'57114-TBG-A350\x00\x00', + b'57114-TGG-A340\x00\x00', + b'57114-TGG-C320\x00\x00', + b'57114-TGG-G320\x00\x00', + b'57114-TGG-L320\x00\x00', + b'57114-TGG-L330\x00\x00', + b'57114-TGH-L130\x00\x00', + b'57114-TGK-T320\x00\x00', + b'57114-TGL-G330\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBA-C020\x00\x00', + b'39990-TBA-C120\x00\x00', + b'39990-TEA-T820\x00\x00', + b'39990-TEZ-T020\x00\x00', + b'39990-TGG,A020\x00\x00', + b'39990-TGG,A120\x00\x00', + b'39990-TGG-A020\x00\x00', + b'39990-TGG-A120\x00\x00', + b'39990-TGG-J510\x00\x00', + b'39990-TGH-J530\x00\x00', + b'39990-TGL-E130\x00\x00', + b'39990-TGN-E120\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBA-A060\x00\x00', + b'77959-TBG-A050\x00\x00', + b'77959-TEA-G020\x00\x00', + b'77959-TGG-A020\x00\x00', + b'77959-TGG-A030\x00\x00', + b'77959-TGG-E010\x00\x00', + b'77959-TGG-G010\x00\x00', + b'77959-TGG-G110\x00\x00', + b'77959-TGG-J320\x00\x00', + b'77959-TGG-Z820\x00\x00', + b'77959-TGH-J110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TBA-A150\x00\x00', + b'36802-TBA-A160\x00\x00', + b'36802-TFJ-G060\x00\x00', + b'36802-TGG-A050\x00\x00', + b'36802-TGG-A060\x00\x00', + b'36802-TGG-A070\x00\x00', + b'36802-TGG-A130\x00\x00', + b'36802-TGG-G040\x00\x00', + b'36802-TGG-G130\x00\x00', + b'36802-TGH-A140\x00\x00', + b'36802-TGK-Q120\x00\x00', + b'36802-TGL-G040\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TBA-A130\x00\x00', + b'36161-TBA-A140\x00\x00', + b'36161-TFJ-G070\x00\x00', + b'36161-TGG-A060\x00\x00', + b'36161-TGG-A080\x00\x00', + b'36161-TGG-A120\x00\x00', + b'36161-TGG-G050\x00\x00', + b'36161-TGG-G070\x00\x00', + b'36161-TGG-G130\x00\x00', + b'36161-TGG-G140\x00\x00', + b'36161-TGH-A140\x00\x00', + b'36161-TGK-Q120\x00\x00', + b'36161-TGL-G050\x00\x00', + b'36161-TGL-G070\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A020\x00\x00', + b'38897-TBA-A110\x00\x00', + b'38897-TGH-A010\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'39494-TGL-G030\x00\x00', + ], + }, + CAR.HONDA_CIVIC_BOSCH_DIESEL: { + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-59Y-G220\x00\x00', + b'28101-59Y-G620\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TGN-E320\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TFK-G020\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TFK-G210\x00\x00', + b'77959-TGN-G220\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TFK-G130\x00\x00', + b'36802-TGN-G130\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TGN-E010\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TFK-G130\x00\x00', + b'36161-TGN-G130\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A020\x00\x00', + ], + }, + CAR.HONDA_CRV: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T1W-A230\x00\x00', + b'57114-T1W-A240\x00\x00', + b'57114-TFF-A940\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T0A-A230\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T1W-A830\x00\x00', + b'36161-T1W-C830\x00\x00', + b'36161-T1X-A830\x00\x00', + ], + }, + CAR.HONDA_CRV_5G: { + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5RG-A020\x00\x00', + b'28101-5RG-A030\x00\x00', + b'28101-5RG-A040\x00\x00', + b'28101-5RG-A120\x00\x00', + b'28101-5RG-A220\x00\x00', + b'28101-5RH-A020\x00\x00', + b'28101-5RH-A030\x00\x00', + b'28101-5RH-A040\x00\x00', + b'28101-5RH-A120\x00\x00', + b'28101-5RH-A220\x00\x00', + b'28101-5RL-Q010\x00\x00', + b'28101-5RM-F010\x00\x00', + b'28101-5RM-K010\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TLA-A040\x00\x00', + b'57114-TLA-A050\x00\x00', + b'57114-TLA-A060\x00\x00', + b'57114-TLB-A830\x00\x00', + b'57114-TMC-Z040\x00\x00', + b'57114-TMC-Z050\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TLA,A040\x00\x00', + b'39990-TLA-A040\x00\x00', + b'39990-TLA-A110\x00\x00', + b'39990-TLA-A220\x00\x00', + b'39990-TME-T030\x00\x00', + b'39990-TME-T120\x00\x00', + b'39990-TMT-T010\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TLA-A040\x00\x00', + b'46114-TLA-A050\x00\x00', + b'46114-TLA-A930\x00\x00', + b'46114-TMC-U020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TLA-A010\x00\x00', + b'38897-TLA-A110\x00\x00', + b'38897-TNY-G010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TLA-A040\x00\x00', + b'36802-TLA-A050\x00\x00', + b'36802-TLA-A060\x00\x00', + b'36802-TLA-A070\x00\x00', + b'36802-TMC-Q040\x00\x00', + b'36802-TMC-Q070\x00\x00', + b'36802-TNY-A030\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TLA-A060\x00\x00', + b'36161-TLA-A070\x00\x00', + b'36161-TLA-A080\x00\x00', + b'36161-TMC-Q020\x00\x00', + b'36161-TMC-Q030\x00\x00', + b'36161-TMC-Q040\x00\x00', + b'36161-TNY-A020\x00\x00', + b'36161-TNY-A030\x00\x00', + b'36161-TNY-A040\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TLA-A240\x00\x00', + b'77959-TLA-A250\x00\x00', + b'77959-TLA-A320\x00\x00', + b'77959-TLA-A410\x00\x00', + b'77959-TLA-A420\x00\x00', + b'77959-TLA-Q040\x00\x00', + b'77959-TLA-Z040\x00\x00', + b'77959-TMM-F040\x00\x00', + ], + }, + CAR.HONDA_CRV_EU: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T1V-G920\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T1V-G520\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-T1V-G010\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5LH-E120\x00\x00', + b'28103-5LH-E100\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T1G-G940\x00\x00', + ], + }, + CAR.HONDA_CRV_HYBRID: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TMB-H030\x00\x00', + b'57114-TPA-G020\x00\x00', + b'57114-TPG-A020\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TMA-H020\x00\x00', + b'39990-TPA-G030\x00\x00', + b'39990-TPG-A020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TMA-H110\x00\x00', + b'38897-TPG-A110\x00\x00', + b'38897-TPG-A210\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TMB-H510\x00\x00', + b'54008-TMB-H610\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TMB-H040\x00\x00', + b'36161-TPA-E050\x00\x00', + b'36161-TPG-A030\x00\x00', + b'36161-TPG-A040\x00\x00', + b'36161-TPG-A050\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TMB-H040\x00\x00', + b'36802-TPA-E040\x00\x00', + b'36802-TPG-A020\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TLA-C320\x00\x00', + b'77959-TLA-C410\x00\x00', + b'77959-TLA-C420\x00\x00', + b'77959-TLA-G220\x00\x00', + b'77959-TLA-H240\x00\x00', + ], + }, + CAR.HONDA_FIT: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T5R-L020\x00\x00', + b'57114-T5R-L220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T5R-C020\x00\x00', + b'39990-T5R-C030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T5A-J010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T5R-A040\x00\x00', + b'36161-T5R-A240\x00\x00', + b'36161-T5R-A520\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T5R-A230\x00\x00', + ], + }, + CAR.HONDA_FREED: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TDK-J010\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TDK-J050\x00\x00', + b'39990-TDK-N020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TDK-J120\x00\x00', + b'57114-TDK-J330\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TDK-J070\x00\x00', + b'36161-TDK-J080\x00\x00', + b'36161-TDK-J530\x00\x00', + ], + }, + CAR.HONDA_ODYSSEY: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-THR-A010\x00\x00', + b'38897-THR-A020\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-THR-A020\x00\x00', + b'39990-THR-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-THR-A010\x00\x00', + b'77959-THR-A110\x00\x00', + b'77959-THR-X010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-THR-A020\x00\x00', + b'36161-THR-A030\x00\x00', + b'36161-THR-A110\x00\x00', + b'36161-THR-A720\x00\x00', + b'36161-THR-A730\x00\x00', + b'36161-THR-A810\x00\x00', + b'36161-THR-A910\x00\x00', + b'36161-THR-C010\x00\x00', + b'36161-THR-D110\x00\x00', + b'36161-THR-K020\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5NZ-A110\x00\x00', + b'28101-5NZ-A310\x00\x00', + b'28101-5NZ-C310\x00\x00', + b'28102-5MX-A001\x00\x00', + b'28102-5MX-A600\x00\x00', + b'28102-5MX-A610\x00\x00', + b'28102-5MX-A700\x00\x00', + b'28102-5MX-A710\x00\x00', + b'28102-5MX-A900\x00\x00', + b'28102-5MX-A910\x00\x00', + b'28102-5MX-C001\x00\x00', + b'28102-5MX-C610\x00\x00', + b'28102-5MX-C910\x00\x00', + b'28102-5MX-D001\x00\x00', + b'28102-5MX-D710\x00\x00', + b'28102-5MX-K610\x00\x00', + b'28103-5NZ-A100\x00\x00', + b'28103-5NZ-A300\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-THR-A040\x00\x00', + b'57114-THR-A110\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-THR-A020\x00\x00', + ], + }, + CAR.HONDA_ODYSSEY_CHN: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T6D-H220\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T6A-J010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T6A-P040\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T6A-P110\x00\x00', + ], + }, + CAR.HONDA_PILOT: { + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TG7-A520\x00\x00', + b'54008-TG7-A530\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5EY-A040\x00\x00', + b'28101-5EY-A050\x00\x00', + b'28101-5EY-A100\x00\x00', + b'28101-5EY-A430\x00\x00', + b'28101-5EY-A500\x00\x00', + b'28101-5EZ-A050\x00\x00', + b'28101-5EZ-A060\x00\x00', + b'28101-5EZ-A100\x00\x00', + b'28101-5EZ-A210\x00\x00', + b'28101-5EZ-A330\x00\x00', + b'28101-5EZ-A430\x00\x00', + b'28101-5EZ-A500\x00\x00', + b'28101-5EZ-A600\x00\x00', + b'28101-5EZ-A700\x00\x00', + b'28103-5EY-A110\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TG7-A030\x00\x00', + b'38897-TG7-A040\x00\x00', + b'38897-TG7-A110\x00\x00', + b'38897-TG7-A210\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TG7-A030\x00\x00', + b'39990-TG7-A040\x00\x00', + b'39990-TG7-A060\x00\x00', + b'39990-TG7-A070\x00\x00', + b'39990-TGS-A230\x00\x00', + b'39990-TGS-A320\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TG7-A310\x00\x00', + b'36161-TG7-A520\x00\x00', + b'36161-TG7-A630\x00\x00', + b'36161-TG7-A720\x00\x00', + b'36161-TG7-A820\x00\x00', + b'36161-TG7-A930\x00\x00', + b'36161-TG7-C520\x00\x00', + b'36161-TG7-D520\x00\x00', + b'36161-TG7-D630\x00\x00', + b'36161-TG7-Y630\x00\x00', + b'36161-TG8-A410\x00\x00', + b'36161-TG8-A520\x00\x00', + b'36161-TG8-A630\x00\x00', + b'36161-TG8-A720\x00\x00', + b'36161-TG8-A830\x00\x00', + b'36161-TGS-A030\x00\x00', + b'36161-TGS-A130\x00\x00', + b'36161-TGS-A220\x00\x00', + b'36161-TGS-A320\x00\x00', + b'36161-TGT-A030\x00\x00', + b'36161-TGT-A130\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TG7-A020\x00\x00', + b'77959-TG7-A110\x00\x00', + b'77959-TG7-A210\x00\x00', + b'77959-TG7-Y210\x00\x00', + b'77959-TGS-A010\x00\x00', + b'77959-TGS-A110\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TG7-A130\x00\x00', + b'57114-TG7-A140\x00\x00', + b'57114-TG7-A230\x00\x00', + b'57114-TG7-A240\x00\x00', + b'57114-TG7-A630\x00\x00', + b'57114-TG7-A730\x00\x00', + b'57114-TG8-A140\x00\x00', + b'57114-TG8-A230\x00\x00', + b'57114-TG8-A240\x00\x00', + b'57114-TG8-A630\x00\x00', + b'57114-TG8-A730\x00\x00', + b'57114-TGS-A530\x00\x00', + b'57114-TGT-A530\x00\x00', + ], + }, + CAR.ACURA_RDX: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TX4-A220\x00\x00', + b'57114-TX5-A220\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TX4-A030\x00\x00', + b'36161-TX5-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TX4-B010\x00\x00', + b'77959-TX4-C010\x00\x00', + b'77959-TX4-C020\x00\x00', + ], + }, + CAR.ACURA_RDX_3G: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TJB-A030\x00\x00', + b'57114-TJB-A040\x00\x00', + b'57114-TJB-A120\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TJB-A040\x00\x00', + b'36802-TJB-A050\x00\x00', + b'36802-TJB-A540\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TJB-A040\x00\x00', + b'36161-TJB-A530\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TJB-A520\x00\x00', + b'54008-TJB-A530\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28102-5YK-A610\x00\x00', + b'28102-5YK-A620\x00\x00', + b'28102-5YK-A630\x00\x00', + b'28102-5YK-A700\x00\x00', + b'28102-5YK-A711\x00\x00', + b'28102-5YK-A800\x00\x00', + b'28102-5YL-A620\x00\x00', + b'28102-5YL-A700\x00\x00', + b'28102-5YL-A711\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TJB-A040\x00\x00', + b'77959-TJB-A120\x00\x00', + b'77959-TJB-A210\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TJB-A040\x00\x00', + b'46114-TJB-A050\x00\x00', + b'46114-TJB-A060\x00\x00', + b'46114-TJB-A120\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TJB-A040\x00\x00', + b'38897-TJB-A110\x00\x00', + b'38897-TJB-A120\x00\x00', + b'38897-TJB-A220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TJB-A030\x00\x00', + b'39990-TJB-A040\x00\x00', + b'39990-TJB-A070\x00\x00', + b'39990-TJB-A130\x00\x00', + ], + }, + CAR.HONDA_RIDGELINE: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T6Z-A020\x00\x00', + b'39990-T6Z-A030\x00\x00', + b'39990-T6Z-A050\x00\x00', + b'39990-T6Z-A110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T6Z-A020\x00\x00', + b'36161-T6Z-A310\x00\x00', + b'36161-T6Z-A420\x00\x00', + b'36161-T6Z-A520\x00\x00', + b'36161-T6Z-A620\x00\x00', + b'36161-T6Z-A720\x00\x00', + b'36161-TJZ-A120\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T6Z-A010\x00\x00', + b'38897-T6Z-A110\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T6Z-A020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T6Z-A120\x00\x00', + b'57114-T6Z-A130\x00\x00', + b'57114-T6Z-A520\x00\x00', + b'57114-T6Z-A610\x00\x00', + b'57114-TJZ-A520\x00\x00', + ], + }, + CAR.HONDA_INSIGHT: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TXM-A040\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TXM-A070\x00\x00', + b'36802-TXM-A080\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TXM-A050\x00\x00', + b'36161-TXM-A060\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TXM-A230\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TXM-A030\x00\x00', + b'57114-TXM-A040\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TWA-A910\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TXM-A020\x00\x00', + ], + }, + CAR.HONDA_HRV: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T7A-A010\x00\x00', + b'38897-T7A-A110\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-THX-A020\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T7A-A040\x00\x00', + b'36161-T7A-A140\x00\x00', + b'36161-T7A-A240\x00\x00', + b'36161-T7A-C440\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T7A-A230\x00\x00', + ], + }, + CAR.HONDA_HRV_3G: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-3M0-G110\x00\x00', + b'39990-3W0-A030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-3M0-M110\x00\x00', + b'38897-3W1-A010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-3M0-K840\x00\x00', + b'77959-3V0-A820\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'8S102-3M6-P030\x00\x00', + b'8S102-3W0-A060\x00\x00', + b'8S102-3W0-AB10\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-3M6-M010\x00\x00', + b'57114-3W0-A040\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-6EH-A010\x00\x00', + b'28101-6JC-M310\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-3W0-A020\x00\x00', + ], + }, + CAR.ACURA_ILX: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TX6-A010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TV9-A140\x00\x00', + b'36161-TX6-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TX6-A230\x00\x00', + b'77959-TX6-C210\x00\x00', + ], + }, + CAR.HONDA_E: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TYF-N030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TYF-E140\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TYF-E010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TYF-G430\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TYF-E030\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TYF-E020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TYF-E030\x00\x00', + ], + }, + CAR.HONDA_CIVIC_2022: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T24-T120\x00\x00', + b'39990-T39-A130\x00\x00', + b'39990-T43-J020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T20-A020\x00\x00', + b'38897-T20-A210\x00\x00', + b'38897-T20-A310\x00\x00', + b'38897-T20-A510\x00\x00', + b'38897-T21-A010\x00\x00', + b'38897-T24-Z120\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T20-A970\x00\x00', + b'77959-T20-A980\x00\x00', + b'77959-T20-M820\x00\x00', + b'77959-T47-A940\x00\x00', + b'77959-T47-A950\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T20-A060\x00\x00', + b'36161-T20-A070\x00\x00', + b'36161-T20-A080\x00\x00', + b'36161-T24-T070\x00\x00', + b'36161-T47-A050\x00\x00', + b'36161-T47-A070\x00\x00', + b'8S102-T20-AA10\x00\x00', + b'8S102-T47-AA10\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T20-AB40\x00\x00', + b'57114-T24-TB30\x00\x00', + b'57114-T43-JB30\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-65D-A020\x00\x00', + b'28101-65D-A120\x00\x00', + b'28101-65H-A020\x00\x00', + b'28101-65H-A120\x00\x00', + b'28101-65J-N010\x00\x00', + ], + }, +} diff --git a/selfdrive/car/honda/hondacan.py b/opendbc_repo/opendbc/car/honda/hondacan.py similarity index 95% rename from selfdrive/car/honda/hondacan.py rename to opendbc_repo/opendbc/car/honda/hondacan.py index 1be496d95116124..2a9465b65bbbb2c 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/opendbc_repo/opendbc/car/honda/hondacan.py @@ -1,6 +1,6 @@ -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import CanBusBase -from openpilot.selfdrive.car.honda.values import HondaFlags, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, CAR, CarControllerParams +from opendbc.car import CanBusBase +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.honda.values import HondaFlags, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, CAR, CarControllerParams # CAN bus layout with relay # 0 = ACC-CAN - radar side @@ -144,7 +144,7 @@ def create_ui_commands(packer, CAN, CP, enabled, pcm_speed, hud, is_metric, acc_ 'CRUISE_SPEED': hud.v_cruise, 'ENABLE_MINI_CAR': 1 if enabled else 0, # only moves the lead car without ACC_ON - 'HUD_DISTANCE': (hud.lead_distance_bars + 1) % 4, # wraps to 0 at 4 bars + 'HUD_DISTANCE': hud.lead_distance_bars, # wraps to 0 at 4 bars 'IMPERIAL_UNIT': int(not is_metric), 'HUD_LEAD': 2 if enabled and hud.lead_visible else 1 if enabled else 0, 'SET_ME_X01_2': 1, diff --git a/opendbc_repo/opendbc/car/honda/interface.py b/opendbc_repo/opendbc/car/honda/interface.py new file mode 100755 index 000000000000000..4e8ce829e8055c5 --- /dev/null +++ b/opendbc_repo/opendbc/car/honda/interface.py @@ -0,0 +1,216 @@ +#!/usr/bin/env python3 +from panda import Panda +from opendbc.car import get_safety_config, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.common.numpy_fast import interp +from opendbc.car.honda.hondacan import CanBus +from opendbc.car.honda.values import CarControllerParams, HondaFlags, CAR, HONDA_BOSCH, \ + HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS +from opendbc.car.interfaces import CarInterfaceBase +from opendbc.car.disable_ecu import disable_ecu + +TransmissionType = structs.CarParams.TransmissionType + + +class CarInterface(CarInterfaceBase): + @staticmethod + def get_pid_accel_limits(CP, current_speed, cruise_speed): + if CP.carFingerprint in HONDA_BOSCH: + return CarControllerParams.BOSCH_ACCEL_MIN, CarControllerParams.BOSCH_ACCEL_MAX + else: + # NIDECs don't allow acceleration near cruise_speed, + # so limit limits of pid to prevent windup + ACCEL_MAX_VALS = [CarControllerParams.NIDEC_ACCEL_MAX, 0.2] + ACCEL_MAX_BP = [cruise_speed - 2., cruise_speed - .2] + return CarControllerParams.NIDEC_ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) + + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "honda" + + CAN = CanBus(ret, fingerprint) + + if candidate in HONDA_BOSCH: + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.hondaBosch)] + ret.radarUnavailable = True + # Disable the radar and let openpilot control longitudinal + # WARNING: THIS DISABLES AEB! + # If Bosch radarless, this blocks ACC messages from the camera + ret.experimentalLongitudinalAvailable = True + ret.openpilotLongitudinalControl = experimental_long + ret.pcmCruise = not ret.openpilotLongitudinalControl + else: + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.hondaNidec)] + ret.openpilotLongitudinalControl = True + + ret.pcmCruise = True + + if candidate == CAR.HONDA_CRV_5G: + ret.enableBsm = 0x12f8bfa7 in fingerprint[CAN.radar] + + # Detect Bosch cars with new HUD msgs + if any(0x33DA in f for f in fingerprint.values()): + ret.flags |= HondaFlags.BOSCH_EXT_HUD.value + + # Accord ICE 1.5T CVT has different gearbox message + if candidate == CAR.HONDA_ACCORD and 0x191 in fingerprint[CAN.pt]: + ret.transmissionType = TransmissionType.cvt + + # Certain Hondas have an extra steering sensor at the bottom of the steering rack, + # which improves controls quality as it removes the steering column torsion from feedback. + # Tire stiffness factor fictitiously lower if it includes the steering column torsion effect. + # For modeling details, see p.198-200 in "The Science of Vehicle Dynamics (2014), M. Guiggiani" + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0], [0]] + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward + + if candidate in HONDA_BOSCH: + ret.longitudinalActuatorDelay = 0.5 # s + if candidate in HONDA_BOSCH_RADARLESS: + ret.stopAccel = CarControllerParams.BOSCH_ACCEL_MIN # stock uses -4.0 m/s^2 once stopped but limited by safety model + else: + # default longitudinal tuning for all hondas + ret.longitudinalTuning.kiBP = [0., 5., 35.] + ret.longitudinalTuning.kiV = [1.2, 0.8, 0.5] + + eps_modified = False + for fw in car_fw: + if fw.ecu == "eps" and b"," in fw.fwVersion: + eps_modified = True + + if candidate == CAR.HONDA_CIVIC: + if eps_modified: + # stock request input values: 0x0000, 0x00DE, 0x014D, 0x01EF, 0x0290, 0x0377, 0x0454, 0x0610, 0x06EE + # stock request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x1680, 0x1680 + # modified request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x2880, 0x3180 + # stock filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108 + # modified filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0400, 0x0480 + # note: max request allowed is 4096, but request is capped at 3840 in firmware, so modifications result in 2x max + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 8000], [0, 2560, 3840]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.1]] + else: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] + + elif candidate in (CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CIVIC_2022): + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + + elif candidate == CAR.HONDA_ACCORD: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + + if eps_modified: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] + else: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] + + elif candidate == CAR.ACURA_ILX: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + + elif candidate in (CAR.HONDA_CRV, CAR.HONDA_CRV_EU): + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + ret.wheelSpeedFactor = 1.025 + + elif candidate == CAR.HONDA_CRV_5G: + if eps_modified: + # stock request input values: 0x0000, 0x00DB, 0x01BB, 0x0296, 0x0377, 0x0454, 0x0532, 0x0610, 0x067F + # stock request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x129A, 0x134D, 0x1400 + # modified request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x1ACD, 0x239A, 0x2800 + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 10000], [0, 2560, 3840]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] + else: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] + ret.wheelSpeedFactor = 1.025 + + elif candidate == CAR.HONDA_CRV_HYBRID: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] + ret.wheelSpeedFactor = 1.025 + + elif candidate == CAR.HONDA_FIT: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] + + elif candidate == CAR.HONDA_FREED: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] + + elif candidate in (CAR.HONDA_HRV, CAR.HONDA_HRV_3G): + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] + if candidate == CAR.HONDA_HRV: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.025]] + ret.wheelSpeedFactor = 1.025 + else: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] # TODO: can probably use some tuning + + elif candidate == CAR.ACURA_RDX: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + + elif candidate == CAR.ACURA_RDX_3G: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] + + elif candidate in (CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN): + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] + if candidate == CAR.HONDA_ODYSSEY_CHN: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end + else: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + + elif candidate == CAR.HONDA_PILOT: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] + + elif candidate == CAR.HONDA_RIDGELINE: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] + + elif candidate == CAR.HONDA_INSIGHT: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] + + elif candidate == CAR.HONDA_E: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] # TODO: can probably use some tuning + + else: + raise ValueError(f"unsupported car {candidate}") + + # These cars use alternate user brake msg (0x1BE) + # TODO: Only detect feature for Accord/Accord Hybrid, not all Bosch DBCs have BRAKE_MODULE + if 0x1BE in fingerprint[CAN.pt] and candidate in (CAR.HONDA_ACCORD, CAR.HONDA_HRV_3G): + ret.flags |= HondaFlags.BOSCH_ALT_BRAKE.value + + if ret.flags & HondaFlags.BOSCH_ALT_BRAKE: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_ALT_BRAKE + + # These cars use alternate SCM messages (SCM_FEEDBACK AND SCM_BUTTON) + if candidate in HONDA_NIDEC_ALT_SCM_MESSAGES: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_NIDEC_ALT + + if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_BOSCH_LONG + + if candidate in HONDA_BOSCH_RADARLESS: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_RADARLESS + + # min speed to enable ACC. if car can do stop and go, then set enabling speed + # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not + # conflict with PCM acc + ret.autoResumeSng = candidate in (HONDA_BOSCH | {CAR.HONDA_CIVIC}) + ret.minEnableSpeed = -1. if ret.autoResumeSng else 25.51 * CV.MPH_TO_MS + + ret.steerActuatorDelay = 0.1 + ret.steerLimitTimer = 0.8 + ret.radarDelay = 0.1 + + return ret + + @staticmethod + def init(CP, can_recv, can_send): + if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl: + disable_ecu(can_recv, can_send, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03') diff --git a/opendbc_repo/opendbc/car/honda/radar_interface.py b/opendbc_repo/opendbc/car/honda/radar_interface.py new file mode 100755 index 000000000000000..97c6664d0e5d0af --- /dev/null +++ b/opendbc_repo/opendbc/car/honda/radar_interface.py @@ -0,0 +1,81 @@ +#!/usr/bin/env python3 +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.interfaces import RadarInterfaceBase +from opendbc.car.honda.values import DBC + + +def _create_nidec_can_parser(car_fingerprint): + radar_messages = [0x400] + list(range(0x430, 0x43A)) + list(range(0x440, 0x446)) + messages = [(m, 20) for m in radar_messages] + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.track_id = 0 + self.radar_fault = False + self.radar_wrong_config = False + self.radar_off_can = CP.radarUnavailable + + # Nidec + if self.radar_off_can: + self.rcp = None + else: + self.rcp = _create_nidec_can_parser(CP.carFingerprint) + self.trigger_msg = 0x445 + self.updated_messages = set() + + def update(self, can_strings): + # in Bosch radar and we are only steering for now, so sleep 0.05s to keep + # radard at 20Hz and return no points + if self.radar_off_can: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + rr = self._update(self.updated_messages) + self.updated_messages.clear() + return rr + + def _update(self, updated_messages): + ret = structs.RadarData() + + for ii in sorted(updated_messages): + cpt = self.rcp.vl[ii] + if ii == 0x400: + # check for radar faults + self.radar_fault = cpt['RADAR_STATE'] != 0x79 + self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 + elif cpt['LONG_DIST'] < 255: + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = structs.RadarData.RadarPoint() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = True + else: + if ii in self.pts: + del self.pts[ii] + + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + if self.radar_fault: + errors.append("fault") + if self.radar_wrong_config: + errors.append("wrongConfig") + ret.errors = errors + + ret.points = list(self.pts.values()) + + return ret diff --git a/selfdrive/car/hyundai/__init__.py b/opendbc_repo/opendbc/car/honda/tests/__init__.py similarity index 100% rename from selfdrive/car/hyundai/__init__.py rename to opendbc_repo/opendbc/car/honda/tests/__init__.py diff --git a/selfdrive/car/honda/tests/test_honda.py b/opendbc_repo/opendbc/car/honda/tests/test_honda.py similarity index 85% rename from selfdrive/car/honda/tests/test_honda.py rename to opendbc_repo/opendbc/car/honda/tests/test_honda.py index b8ad7872b29fa31..946f496d105cd22 100644 --- a/selfdrive/car/honda/tests/test_honda.py +++ b/opendbc_repo/opendbc/car/honda/tests/test_honda.py @@ -1,6 +1,6 @@ import re -from openpilot.selfdrive.car.honda.fingerprints import FW_VERSIONS +from opendbc.car.honda.fingerprints import FW_VERSIONS HONDA_FW_VERSION_RE = br"[A-Z0-9]{5}-[A-Z0-9]{3}(-|,)[A-Z0-9]{4}(\x00){2}$" diff --git a/opendbc_repo/opendbc/car/honda/values.py b/opendbc_repo/opendbc/car/honda/values.py new file mode 100644 index 000000000000000..30f84361c288594 --- /dev/null +++ b/opendbc_repo/opendbc/car/honda/values.py @@ -0,0 +1,334 @@ +from dataclasses import dataclass +from enum import Enum, IntFlag + +from panda import uds +from opendbc.car import CarSpecs, PlatformConfig, Platforms, dbc_dict, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 + +Ecu = structs.CarParams.Ecu +VisualAlert = structs.CarControl.HUDControl.VisualAlert + + +class CarControllerParams: + # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we + # perform the closed loop control, and might need some + # to apply some more braking if we're on a downhill slope. + # Our controller should still keep the 2 second average above + # -3.5 m/s^2 as per planner limits + NIDEC_ACCEL_MIN = -4.0 # m/s^2 + NIDEC_ACCEL_MAX = 1.6 # m/s^2, lower than 2.0 m/s^2 for tuning reasons + + NIDEC_ACCEL_LOOKUP_BP = [-1., 0., .6] + NIDEC_ACCEL_LOOKUP_V = [-4.8, 0., 2.0] + + NIDEC_MAX_ACCEL_V = [0.5, 2.4, 1.4, 0.6] + NIDEC_MAX_ACCEL_BP = [0.0, 4.0, 10., 20.] + + NIDEC_GAS_MAX = 198 # 0xc6 + NIDEC_BRAKE_MAX = 1024 // 4 + + BOSCH_ACCEL_MIN = -3.5 # m/s^2 + BOSCH_ACCEL_MAX = 2.0 # m/s^2 + + BOSCH_GAS_LOOKUP_BP = [-0.2, 2.0] # 2m/s^2 + BOSCH_GAS_LOOKUP_V = [0, 1600] + + STEER_STEP = 1 # 100 Hz + STEER_DELTA_UP = 3 # min/max in 0.33s for all Honda + STEER_DELTA_DOWN = 3 + + def __init__(self, CP): + self.STEER_MAX = CP.lateralParams.torqueBP[-1] + # mirror of list (assuming first item is zero) for interp of signed request values + assert(CP.lateralParams.torqueBP[0] == 0) + assert(CP.lateralParams.torqueBP[0] == 0) + self.STEER_LOOKUP_BP = [v * -1 for v in CP.lateralParams.torqueBP][1:][::-1] + list(CP.lateralParams.torqueBP) + self.STEER_LOOKUP_V = [v * -1 for v in CP.lateralParams.torqueV][1:][::-1] + list(CP.lateralParams.torqueV) + + +class HondaFlags(IntFlag): + # Detected flags + # Bosch models with alternate set of LKAS_HUD messages + BOSCH_EXT_HUD = 1 + BOSCH_ALT_BRAKE = 2 + + # Static flags + BOSCH = 4 + BOSCH_RADARLESS = 8 + + NIDEC = 16 + NIDEC_ALT_PCM_ACCEL = 32 + NIDEC_ALT_SCM_MESSAGES = 64 + + +# Car button codes +class CruiseButtons: + RES_ACCEL = 4 + DECEL_SET = 3 + CANCEL = 2 + MAIN = 1 + + +class CruiseSettings: + DISTANCE = 3 + LKAS = 1 + + +# See dbc files for info on values +VISUAL_HUD = { + VisualAlert.none: 0, + VisualAlert.fcw: 1, + VisualAlert.steerRequired: 1, + VisualAlert.ldw: 1, + VisualAlert.brakePressed: 10, + VisualAlert.wrongGear: 6, + VisualAlert.seatbeltUnbuckled: 5, + VisualAlert.speedTooHigh: 8 +} + + +@dataclass +class HondaCarDocs(CarDocs): + package: str = "Honda Sensing" + + def init_make(self, CP: structs.CarParams): + if CP.flags & HondaFlags.BOSCH: + self.car_parts = CarParts.common([CarHarness.bosch_b]) if CP.flags & HondaFlags.BOSCH_RADARLESS else CarParts.common([CarHarness.bosch_a]) + else: + self.car_parts = CarParts.common([CarHarness.nidec]) + + +class Footnote(Enum): + CIVIC_DIESEL = CarFootnote( + "2019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.", + Column.FSR_STEERING) + + +class HondaBoschPlatformConfig(PlatformConfig): + def init(self): + self.flags |= HondaFlags.BOSCH + + +class HondaNidecPlatformConfig(PlatformConfig): + def init(self): + self.flags |= HondaFlags.NIDEC + + +class CAR(Platforms): + # Bosch Cars + HONDA_ACCORD = HondaBoschPlatformConfig( + [ + HondaCarDocs("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarDocs("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarDocs("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), + ], + # steerRatio: 11.82 is spec end-to-end + CarSpecs(mass=3279 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=16.33, centerToFrontRatio=0.39, tireStiffnessFactor=0.8467), + dbc_dict('honda_accord_2018_can_generated', None), + ) + HONDA_CIVIC_BOSCH = HondaBoschPlatformConfig( + [ + HondaCarDocs("Honda Civic 2019-21", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", + footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), + HondaCarDocs("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS), + ], + CarSpecs(mass=1326, wheelbase=2.7, steerRatio=15.38, centerToFrontRatio=0.4), # steerRatio: 10.93 is end-to-end spec + dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), + ) + HONDA_CIVIC_BOSCH_DIESEL = HondaBoschPlatformConfig( + [], # don't show in docs + HONDA_CIVIC_BOSCH.specs, + dbc_dict('honda_accord_2018_can_generated', None), + ) + HONDA_CIVIC_2022 = HondaBoschPlatformConfig( + [ + HondaCarDocs("Honda Civic 2022-24", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), + HondaCarDocs("Honda Civic Hatchback 2022-24", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), + ], + HONDA_CIVIC_BOSCH.specs, + dbc_dict('honda_civic_ex_2022_can_generated', None), + flags=HondaFlags.BOSCH_RADARLESS, + ) + HONDA_CRV_5G = HondaBoschPlatformConfig( + [HondaCarDocs("Honda CR-V 2017-22", min_steer_speed=12. * CV.MPH_TO_MS)], + # steerRatio: 12.3 is spec end-to-end + CarSpecs(mass=3410 * CV.LB_TO_KG, wheelbase=2.66, steerRatio=16.0, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), + dbc_dict('honda_crv_ex_2017_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), + flags=HondaFlags.BOSCH_ALT_BRAKE, + ) + HONDA_CRV_HYBRID = HondaBoschPlatformConfig( + [HondaCarDocs("Honda CR-V Hybrid 2017-22", min_steer_speed=12. * CV.MPH_TO_MS)], + # mass: mean of 4 models in kg, steerRatio: 12.3 is spec end-to-end + CarSpecs(mass=1667, wheelbase=2.66, steerRatio=16, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), + dbc_dict('honda_accord_2018_can_generated', None), + ) + HONDA_HRV_3G = HondaBoschPlatformConfig( + [HondaCarDocs("Honda HR-V 2023", "All")], + CarSpecs(mass=3125 * CV.LB_TO_KG, wheelbase=2.61, steerRatio=15.2, centerToFrontRatio=0.41, tireStiffnessFactor=0.5), + dbc_dict('honda_civic_ex_2022_can_generated', None), + flags=HondaFlags.BOSCH_RADARLESS, + ) + ACURA_RDX_3G = HondaBoschPlatformConfig( + [HondaCarDocs("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], + CarSpecs(mass=4068 * CV.LB_TO_KG, wheelbase=2.75, steerRatio=11.95, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), # as spec + dbc_dict('acura_rdx_2020_can_generated', None), + flags=HondaFlags.BOSCH_ALT_BRAKE, + ) + HONDA_INSIGHT = HondaBoschPlatformConfig( + [HondaCarDocs("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], + CarSpecs(mass=2987 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.0, centerToFrontRatio=0.39, tireStiffnessFactor=0.82), # as spec + dbc_dict('honda_insight_ex_2019_can_generated', None), + ) + HONDA_E = HondaBoschPlatformConfig( + [HondaCarDocs("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS)], + CarSpecs(mass=3338.8 * CV.LB_TO_KG, wheelbase=2.5, centerToFrontRatio=0.5, steerRatio=16.71, tireStiffnessFactor=0.82), + dbc_dict('acura_rdx_2020_can_generated', None), + ) + + # Nidec Cars + ACURA_ILX = HondaNidecPlatformConfig( + [HondaCarDocs("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS)], + CarSpecs(mass=3095 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=18.61, centerToFrontRatio=0.37, tireStiffnessFactor=0.72), # 15.3 is spec end-to-end + dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_CRV = HondaNidecPlatformConfig( + [HondaCarDocs("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=3572 * CV.LB_TO_KG, wheelbase=2.62, steerRatio=16.89, centerToFrontRatio=0.41, tireStiffnessFactor=0.444), # as spec + dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_CRV_EU = HondaNidecPlatformConfig( + [], # Euro version of CRV Touring, don't show in docs + HONDA_CRV.specs, + dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_FIT = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Fit 2018-20", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=2644 * CV.LB_TO_KG, wheelbase=2.53, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), + dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_FREED = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Freed 2020", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=3086. * CV.LB_TO_KG, wheelbase=2.74, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), # mostly copied from FIT + dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_HRV = HondaNidecPlatformConfig( + [HondaCarDocs("Honda HR-V 2019-22", min_steer_speed=12. * CV.MPH_TO_MS)], + HONDA_HRV_3G.specs, + dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_ODYSSEY = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Odyssey 2018-20")], + CarSpecs(mass=1900, wheelbase=3.0, steerRatio=14.35, centerToFrontRatio=0.41, tireStiffnessFactor=0.82), + dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_PCM_ACCEL, + ) + HONDA_ODYSSEY_CHN = HondaNidecPlatformConfig( + [], # Chinese version of Odyssey, don't show in docs + HONDA_ODYSSEY.specs, + dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + ACURA_RDX = HondaNidecPlatformConfig( + [HondaCarDocs("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=3925 * CV.LB_TO_KG, wheelbase=2.68, steerRatio=15.0, centerToFrontRatio=0.38, tireStiffnessFactor=0.444), # as spec + dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_PILOT = HondaNidecPlatformConfig( + [ + HondaCarDocs("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS), + HondaCarDocs("Honda Passport 2019-23", "All", min_steer_speed=12. * CV.MPH_TO_MS), + ], + CarSpecs(mass=4278 * CV.LB_TO_KG, wheelbase=2.86, centerToFrontRatio=0.428, steerRatio=16.0, tireStiffnessFactor=0.444), # as spec + dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_RIDGELINE = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Ridgeline 2017-24", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=4515 * CV.LB_TO_KG, wheelbase=3.18, centerToFrontRatio=0.41, steerRatio=15.59, tireStiffnessFactor=0.444), # as spec + dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_CIVIC = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video_link="https://youtu.be/-IkImTe1NYE")], + CarSpecs(mass=1326, wheelbase=2.70, centerToFrontRatio=0.4, steerRatio=15.38), # 10.93 is end-to-end spec + dbc_dict('honda_civic_touring_2016_can_generated', 'acura_ilx_2016_nidec'), + ) + + +HONDA_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xF112) +HONDA_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(0xF112) + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + # Currently used to fingerprint + Request( + [StdQueries.UDS_VERSION_REQUEST], + [StdQueries.UDS_VERSION_RESPONSE], + bus=1, + ), + + # Data collection requests: + # Log manufacturer-specific identifier for current ECUs + Request( + [HONDA_ALT_VERSION_REQUEST], + [HONDA_ALT_VERSION_RESPONSE], + bus=1, + logging=True, + ), + # Nidec PT bus + Request( + [StdQueries.UDS_VERSION_REQUEST], + [StdQueries.UDS_VERSION_RESPONSE], + bus=0, + ), + # Bosch PT bus + Request( + [StdQueries.UDS_VERSION_REQUEST], + [StdQueries.UDS_VERSION_RESPONSE], + bus=1, + obd_multiplexing=False, + ), + ], + # We lose these ECUs without the comma power on these cars. + # Note that we still attempt to match with them when they are present + # This is or'd with (ALL_ECUS - ESSENTIAL_ECUS) from fw_versions.py + non_essential_ecus={ + Ecu.eps: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_2022, CAR.HONDA_E, CAR.HONDA_HRV_3G], + Ecu.vsa: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_2022, CAR.HONDA_CRV_5G, CAR.HONDA_CRV_HYBRID, + CAR.HONDA_E, CAR.HONDA_HRV_3G, CAR.HONDA_INSIGHT], + }, + extra_ecus=[ + (Ecu.combinationMeter, 0x18da60f1, None), + (Ecu.programmedFuelInjection, 0x18da10f1, None), + # The only other ECU on PT bus accessible by camera on radarless Civic + # This is likely a manufacturer-specific sub-address implementation: the camera responds to this and 0x18dab0f1 + # Unclear what the part number refers to: 8S103 is 'Camera Set Mono', while 36160 is 'Camera Monocular - Honda' + # TODO: add query back, camera does not support querying both in parallel and 0x18dab0f1 often fails to respond + # (Ecu.unknown, 0x18DAB3F1, None), + ], +) + +STEER_THRESHOLD = { + # default is 1200, overrides go here + CAR.ACURA_RDX: 400, + CAR.HONDA_CRV_EU: 400, +} + +HONDA_NIDEC_ALT_PCM_ACCEL = CAR.with_flags(HondaFlags.NIDEC_ALT_PCM_ACCEL) +HONDA_NIDEC_ALT_SCM_MESSAGES = CAR.with_flags(HondaFlags.NIDEC_ALT_SCM_MESSAGES) +HONDA_BOSCH = CAR.with_flags(HondaFlags.BOSCH) +HONDA_BOSCH_RADARLESS = CAR.with_flags(HondaFlags.BOSCH_RADARLESS) + + +DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/hyundai/tests/__init__.py b/opendbc_repo/opendbc/car/hyundai/__init__.py similarity index 100% rename from selfdrive/car/hyundai/tests/__init__.py rename to opendbc_repo/opendbc/car/hyundai/__init__.py diff --git a/opendbc_repo/opendbc/car/hyundai/carcontroller.py b/opendbc_repo/opendbc/car/hyundai/carcontroller.py new file mode 100644 index 000000000000000..cfb8c25163198cf --- /dev/null +++ b/opendbc_repo/opendbc/car/hyundai/carcontroller.py @@ -0,0 +1,206 @@ +from opendbc.can.packer import CANPacker +from opendbc.car import DT_CTRL, apply_driver_steer_torque_limits, common_fault_avoidance, make_tester_present_msg, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.common.numpy_fast import clip +from opendbc.car.hyundai import hyundaicanfd, hyundaican +from opendbc.car.hyundai.carstate import CarState +from opendbc.car.hyundai.hyundaicanfd import CanBus +from opendbc.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CAR +from opendbc.car.interfaces import CarControllerBase + +VisualAlert = structs.CarControl.HUDControl.VisualAlert +LongCtrlState = structs.CarControl.Actuators.LongControlState + +# EPS faults if you apply torque while the steering angle is above 90 degrees for more than 1 second +# All slightly below EPS thresholds to avoid fault +MAX_ANGLE = 85 +MAX_ANGLE_FRAMES = 89 +MAX_ANGLE_CONSECUTIVE_FRAMES = 2 + + +def process_hud_alert(enabled, fingerprint, hud_control): + sys_warning = (hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)) + + # initialize to no line visible + # TODO: this is not accurate for all cars + sys_state = 1 + if hud_control.leftLaneVisible and hud_control.rightLaneVisible or sys_warning: # HUD alert only display when LKAS status is active + sys_state = 3 if enabled or sys_warning else 4 + elif hud_control.leftLaneVisible: + sys_state = 5 + elif hud_control.rightLaneVisible: + sys_state = 6 + + # initialize to no warnings + left_lane_warning = 0 + right_lane_warning = 0 + if hud_control.leftLaneDepart: + left_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 + if hud_control.rightLaneDepart: + right_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 + + return sys_warning, sys_state, left_lane_warning, right_lane_warning + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.CAN = CanBus(CP) + self.params = CarControllerParams(CP) + self.packer = CANPacker(dbc_name) + self.angle_limit_counter = 0 + + self.accel_last = 0 + self.apply_steer_last = 0 + self.car_fingerprint = CP.carFingerprint + self.last_button_frame = 0 + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + + # steering torque + new_steer = int(round(actuators.steer * self.params.STEER_MAX)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) + + # >90 degree steering fault prevention + self.angle_limit_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringAngleDeg) >= MAX_ANGLE, CC.latActive, + self.angle_limit_counter, MAX_ANGLE_FRAMES, + MAX_ANGLE_CONSECUTIVE_FRAMES) + + if not CC.latActive: + apply_steer = 0 + + # Hold torque with induced temporary fault when cutting the actuation bit + torque_fault = CC.latActive and not apply_steer_req + + self.apply_steer_last = apply_steer + + # accel + longitudinal + accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + stopping = actuators.longControlState == LongCtrlState.stopping + set_speed_in_units = hud_control.setSpeed * (CV.MS_TO_KPH if CS.is_metric else CV.MS_TO_MPH) + + # HUD messages + sys_warning, sys_state, left_lane_warning, right_lane_warning = process_hud_alert(CC.enabled, self.car_fingerprint, + hud_control) + + can_sends = [] + + # *** common hyundai stuff *** + + # tester present - w/ no response (keeps relevant ECU disabled) + if self.frame % 100 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and self.CP.openpilotLongitudinalControl: + # for longitudinal control, either radar or ADAS driving ECU + addr, bus = 0x7d0, 0 + if self.CP.flags & HyundaiFlags.CANFD_HDA2.value: + addr, bus = 0x730, self.CAN.ECAN + can_sends.append(make_tester_present_msg(addr, bus, suppress_response=True)) + + # for blinkers + if self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: + can_sends.append(make_tester_present_msg(0x7b1, self.CAN.ECAN, suppress_response=True)) + + # CAN-FD platforms + if self.CP.flags & HyundaiFlags.CANFD: + hda2 = self.CP.flags & HyundaiFlags.CANFD_HDA2 + hda2_long = hda2 and self.CP.openpilotLongitudinalControl + + # steering control + can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.enabled, apply_steer_req, apply_steer)) + + # prevent LFA from activating on HDA2 by sending "no lane lines detected" to ADAS ECU + if self.frame % 5 == 0 and hda2: + can_sends.append(hyundaicanfd.create_suppress_lfa(self.packer, self.CAN, CS.hda2_lfa_block_msg, + self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING)) + + # LFA and HDA icons + if self.frame % 5 == 0 and (not hda2 or hda2_long): + can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CAN, CC.enabled)) + + # blinkers + if hda2 and self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: + can_sends.extend(hyundaicanfd.create_spas_messages(self.packer, self.CAN, self.frame, CC.leftBlinker, CC.rightBlinker)) + + if self.CP.openpilotLongitudinalControl: + if hda2: + can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.CAN, self.frame)) + if self.frame % 2 == 0: + can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CAN, CC.enabled, self.accel_last, accel, stopping, CC.cruiseControl.override, + set_speed_in_units, hud_control)) + self.accel_last = accel + else: + # button presses + can_sends.extend(self.create_button_messages(CC, CS, use_clu11=False)) + else: + can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.CP, apply_steer, apply_steer_req, + torque_fault, CS.lkas11, sys_warning, sys_state, CC.enabled, + hud_control.leftLaneVisible, hud_control.rightLaneVisible, + left_lane_warning, right_lane_warning)) + + if not self.CP.openpilotLongitudinalControl: + can_sends.extend(self.create_button_messages(CC, CS, use_clu11=True)) + + if self.frame % 2 == 0 and self.CP.openpilotLongitudinalControl: + # TODO: unclear if this is needed + jerk = 3.0 if actuators.longControlState == LongCtrlState.pid else 1.0 + use_fca = self.CP.flags & HyundaiFlags.USE_FCA.value + can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2), + hud_control, set_speed_in_units, stopping, + CC.cruiseControl.override, use_fca)) + + # 20 Hz LFA MFA message + if self.frame % 5 == 0 and self.CP.flags & HyundaiFlags.SEND_LFA.value: + can_sends.append(hyundaican.create_lfahda_mfc(self.packer, CC.enabled)) + + # 5 Hz ACC options + if self.frame % 20 == 0 and self.CP.openpilotLongitudinalControl: + can_sends.extend(hyundaican.create_acc_opt(self.packer)) + + # 2 Hz front radar options + if self.frame % 50 == 0 and self.CP.openpilotLongitudinalControl: + can_sends.append(hyundaican.create_frt_radar_opt(self.packer)) + + new_actuators = actuators.as_builder() + new_actuators.steer = apply_steer / self.params.STEER_MAX + new_actuators.steerOutputCan = apply_steer + new_actuators.accel = accel + + self.frame += 1 + return new_actuators, can_sends + + def create_button_messages(self, CC: structs.CarControl, CS: CarState, use_clu11: bool): + can_sends = [] + if use_clu11: + if CC.cruiseControl.cancel: + can_sends.append(hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.CANCEL, self.CP)) + elif CC.cruiseControl.resume: + # send resume at a max freq of 10Hz + if (self.frame - self.last_button_frame) * DT_CTRL > 0.1: + # send 25 messages at a time to increases the likelihood of resume being accepted + can_sends.extend([hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.RES_ACCEL, self.CP)] * 25) + if (self.frame - self.last_button_frame) * DT_CTRL >= 0.15: + self.last_button_frame = self.frame + else: + if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: + # cruise cancel + if CC.cruiseControl.cancel: + if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + can_sends.append(hyundaicanfd.create_acc_cancel(self.packer, self.CP, self.CAN, CS.cruise_info)) + self.last_button_frame = self.frame + else: + for _ in range(20): + can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.CANCEL)) + self.last_button_frame = self.frame + + # cruise standstill resume + elif CC.cruiseControl.resume: + if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + # TODO: resume for alt button cars + pass + else: + for _ in range(20): + can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.RES_ACCEL)) + self.last_button_frame = self.frame + + return can_sends diff --git a/opendbc_repo/opendbc/car/hyundai/carstate.py b/opendbc_repo/opendbc/car/hyundai/carstate.py new file mode 100644 index 000000000000000..9406d858fba390f --- /dev/null +++ b/opendbc_repo/opendbc/car/hyundai/carstate.py @@ -0,0 +1,386 @@ +from collections import deque +import copy +import math + +from opendbc.can.parser import CANParser +from opendbc.can.can_define import CANDefine +from opendbc.car import create_button_events, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.hyundai.hyundaicanfd import CanBus +from opendbc.car.hyundai.values import HyundaiFlags, CAR, DBC, Buttons, CarControllerParams +from opendbc.car.interfaces import CarStateBase + +ButtonType = structs.CarState.ButtonEvent.Type + +PREV_BUTTON_SAMPLES = 8 +CLUSTER_SAMPLE_RATE = 20 # frames +STANDSTILL_THRESHOLD = 12 * 0.03125 * CV.KPH_TO_MS + +BUTTONS_DICT = {Buttons.RES_ACCEL: ButtonType.accelCruise, Buttons.SET_DECEL: ButtonType.decelCruise, + Buttons.GAP_DIST: ButtonType.gapAdjustCruise, Buttons.CANCEL: ButtonType.cancel} + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + self.cruise_buttons: deque = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) + self.main_buttons: deque = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) + + self.gear_msg_canfd = "ACCELERATOR" if CP.flags & HyundaiFlags.EV else \ + "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \ + "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \ + "GEAR_SHIFTER" + if CP.flags & HyundaiFlags.CANFD: + self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"] + elif self.CP.flags & HyundaiFlags.CLUSTER_GEARS: + self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] + elif self.CP.flags & HyundaiFlags.TCU_GEARS: + self.shifter_values = can_define.dv["TCU12"]["CUR_GR"] + else: # preferred and elect gear methods use same definition + self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] + + self.accelerator_msg_canfd = "ACCELERATOR" if CP.flags & HyundaiFlags.EV else \ + "ACCELERATOR_ALT" if CP.flags & HyundaiFlags.HYBRID else \ + "ACCELERATOR_BRAKE_ALT" + self.cruise_btns_msg_canfd = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else \ + "CRUISE_BUTTONS" + self.is_metric = False + self.buttons_counter = 0 + + self.cruise_info = {} + + # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz + self.cluster_speed = 0 + self.cluster_speed_counter = CLUSTER_SAMPLE_RATE + + self.params = CarControllerParams(CP) + + def update(self, cp, cp_cam, *_) -> structs.CarState: + if self.CP.flags & HyundaiFlags.CANFD: + return self.update_canfd(cp, cp_cam) + + ret = structs.CarState() + cp_cruise = cp_cam if self.CP.flags & HyundaiFlags.CAMERA_SCC else cp + self.is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0 + speed_conv = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS + + ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"], + cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]]) + + ret.seatbeltUnlatched = cp.vl["CGW1"]["CF_Gway_DrvSeatBeltSw"] == 0 + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHL_SPD11"]["WHL_SPD_FL"], + cp.vl["WHL_SPD11"]["WHL_SPD_FR"], + cp.vl["WHL_SPD11"]["WHL_SPD_RL"], + cp.vl["WHL_SPD11"]["WHL_SPD_RR"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD + + self.cluster_speed_counter += 1 + if self.cluster_speed_counter > CLUSTER_SAMPLE_RATE: + self.cluster_speed = cp.vl["CLU15"]["CF_Clu_VehicleSpeed"] + self.cluster_speed_counter = 0 + + # Mimic how dash converts to imperial. + # Sorento is the only platform where CF_Clu_VehicleSpeed is already imperial when not is_metric + # TODO: CGW_USM1->CF_Gway_DrLockSoundRValue may describe this + if not self.is_metric and self.CP.carFingerprint not in (CAR.KIA_SORENTO,): + self.cluster_speed = math.floor(self.cluster_speed * CV.KPH_TO_MPH + CV.KPH_TO_MPH) + + ret.vEgoCluster = self.cluster_speed * speed_conv + + ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"] + ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"] + ret.yawRate = cp.vl["ESP12"]["YAW_RATE"] + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp( + 50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) + ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"] + ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"] + ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) + ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0 + + # cruise state + if self.CP.openpilotLongitudinalControl: + # These are not used for engage/disengage since openpilot keeps track of state using the buttons + ret.cruiseState.available = cp.vl["TCS13"]["ACCEnable"] == 0 + ret.cruiseState.enabled = cp.vl["TCS13"]["ACC_REQ"] == 1 + ret.cruiseState.standstill = False + ret.cruiseState.nonAdaptive = False + else: + ret.cruiseState.available = cp_cruise.vl["SCC11"]["MainMode_ACC"] == 1 + ret.cruiseState.enabled = cp_cruise.vl["SCC12"]["ACCMode"] != 0 + ret.cruiseState.standstill = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 4. + ret.cruiseState.nonAdaptive = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 2. # Shows 'Cruise Control' on dash + ret.cruiseState.speed = cp_cruise.vl["SCC11"]["VSetDis"] * speed_conv + + # TODO: Find brake pressure + ret.brake = 0 + ret.brakePressed = cp.vl["TCS13"]["DriverOverride"] == 2 # 2 includes regen braking by user on HEV/EV + ret.brakeHoldActive = cp.vl["TCS15"]["AVH_LAMP"] == 2 # 0 OFF, 1 ERROR, 2 ACTIVE, 3 READY + ret.parkingBrake = cp.vl["TCS13"]["PBRAKE_ACT"] == 1 + ret.espDisabled = cp.vl["TCS11"]["TCS_PAS"] == 1 + ret.espActive = cp.vl["TCS11"]["ABS_ACT"] == 1 + ret.accFaulted = cp.vl["TCS13"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED + + if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + if self.CP.flags & HyundaiFlags.HYBRID: + ret.gas = cp.vl["E_EMS11"]["CR_Vcu_AccPedDep_Pos"] / 254. + else: + ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 254. + ret.gasPressed = ret.gas > 0 + else: + ret.gas = cp.vl["EMS12"]["PV_AV_CAN"] / 100. + ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) + + # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, + # as this seems to be standard over all cars, but is not the preferred method. + if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] + elif self.CP.flags & HyundaiFlags.CLUSTER_GEARS: + gear = cp.vl["CLU15"]["CF_Clu_Gear"] + elif self.CP.flags & HyundaiFlags.TCU_GEARS: + gear = cp.vl["TCU12"]["CUR_GR"] + else: + gear = cp.vl["LVR12"]["CF_Lvr_Gear"] + + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) + + if not self.CP.openpilotLongitudinalControl: + aeb_src = "FCA11" if self.CP.flags & HyundaiFlags.USE_FCA.value else "SCC12" + aeb_sig = "FCA_CmdAct" if self.CP.flags & HyundaiFlags.USE_FCA.value else "AEB_CmdAct" + aeb_warning = cp_cruise.vl[aeb_src]["CF_VSM_Warn"] != 0 + scc_warning = cp_cruise.vl["SCC12"]["TakeOverReq"] == 1 # sometimes only SCC system shows an FCW + aeb_braking = cp_cruise.vl[aeb_src]["CF_VSM_DecCmdAct"] != 0 or cp_cruise.vl[aeb_src][aeb_sig] != 0 + ret.stockFcw = (aeb_warning or scc_warning) and not aeb_braking + ret.stockAeb = aeb_warning and aeb_braking + + if self.CP.enableBsm: + ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 + ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 + + # save the entire LKAS11 and CLU11 + self.lkas11 = copy.copy(cp_cam.vl["LKAS11"]) + self.clu11 = copy.copy(cp.vl["CLU11"]) + self.steer_state = cp.vl["MDPS12"]["CF_Mdps_ToiActive"] # 0 NOT ACTIVE, 1 ACTIVE + prev_cruise_buttons = self.cruise_buttons[-1] + prev_main_buttons = self.main_buttons[-1] + self.cruise_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwState"]) + self.main_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwMain"]) + + ret.buttonEvents = [*create_button_events(self.cruise_buttons[-1], prev_cruise_buttons, BUTTONS_DICT), + *create_button_events(self.main_buttons[-1], prev_main_buttons, {1: ButtonType.mainCruise})] + + return ret + + def update_canfd(self, cp, cp_cam) -> structs.CarState: + ret = structs.CarState() + + self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1 + speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS + + if self.CP.flags & (HyundaiFlags.EV | HyundaiFlags.HYBRID): + offset = 255. if self.CP.flags & HyundaiFlags.EV else 1023. + ret.gas = cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL"] / offset + ret.gasPressed = ret.gas > 1e-5 + else: + ret.gasPressed = bool(cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL_PRESSED"]) + + ret.brakePressed = cp.vl["TCS"]["DriverBraking"] == 1 + + ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR"] == 1 + ret.seatbeltUnlatched = cp.vl["DOORS_SEATBELTS"]["DRIVER_SEATBELT"] == 0 + + gear = cp.vl[self.gear_msg_canfd]["GEAR"] + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) + + # TODO: figure out positions + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_1"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_2"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_3"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_4"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD + + ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEERING_RATE"] + ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEERING_ANGLE"] * -1 + ret.steeringTorque = cp.vl["MDPS"]["STEERING_COL_TORQUE"] + ret.steeringTorqueEps = cp.vl["MDPS"]["STEERING_OUT_TORQUE"] + ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) + ret.steerFaultTemporary = cp.vl["MDPS"]["LKA_FAULT"] != 0 + + # TODO: alt signal usage may be described by cp.vl['BLINKERS']['USE_ALT_LAMP'] + left_blinker_sig, right_blinker_sig = "LEFT_LAMP", "RIGHT_LAMP" + if self.CP.carFingerprint == CAR.HYUNDAI_KONA_EV_2ND_GEN: + left_blinker_sig, right_blinker_sig = "LEFT_LAMP_ALT", "RIGHT_LAMP_ALT" + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"][left_blinker_sig], + cp.vl["BLINKERS"][right_blinker_sig]) + if self.CP.enableBsm: + ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0 + ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0 + + # cruise state + # CAN FD cars enable on main button press, set available if no TCS faults preventing engagement + ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0 + if self.CP.openpilotLongitudinalControl: + # These are not used for engage/disengage since openpilot keeps track of state using the buttons + ret.cruiseState.enabled = cp.vl["TCS"]["ACC_REQ"] == 1 + ret.cruiseState.standstill = False + else: + cp_cruise_info = cp_cam if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp + ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2) + ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1 + ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor + self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"]) + + # Manual Speed Limit Assist is a feature that replaces non-adaptive cruise control on EV CAN FD platforms. + # It limits the vehicle speed, overridable by pressing the accelerator past a certain point. + # The car will brake, but does not respect positive acceleration commands in this mode + # TODO: find this message on ICE & HYBRID cars + cruise control signals (if exists) + if self.CP.flags & HyundaiFlags.EV: + ret.cruiseState.nonAdaptive = cp.vl["MANUAL_SPEED_LIMIT_ASSIST"]["MSLA_ENABLED"] == 1 + + prev_cruise_buttons = self.cruise_buttons[-1] + prev_main_buttons = self.main_buttons[-1] + self.cruise_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["CRUISE_BUTTONS"]) + self.main_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["ADAPTIVE_CRUISE_MAIN_BTN"]) + self.buttons_counter = cp.vl[self.cruise_btns_msg_canfd]["COUNTER"] + ret.accFaulted = cp.vl["TCS"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED + + if self.CP.flags & HyundaiFlags.CANFD_HDA2: + self.hda2_lfa_block_msg = copy.copy(cp_cam.vl["CAM_0x362"] if self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING + else cp_cam.vl["CAM_0x2a4"]) + + ret.buttonEvents = [*create_button_events(self.cruise_buttons[-1], prev_cruise_buttons, BUTTONS_DICT), + *create_button_events(self.main_buttons[-1], prev_main_buttons, {1: ButtonType.mainCruise})] + + return ret + + def get_can_parser(self, CP): + if CP.flags & HyundaiFlags.CANFD: + return self.get_can_parser_canfd(CP) + + messages = [ + # address, frequency + ("MDPS12", 50), + ("TCS11", 100), + ("TCS13", 50), + ("TCS15", 10), + ("CLU11", 50), + ("CLU15", 5), + ("ESP12", 100), + ("CGW1", 10), + ("CGW2", 5), + ("CGW4", 5), + ("WHL_SPD11", 50), + ("SAS11", 100), + ] + + if not CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CAMERA_SCC): + messages += [ + ("SCC11", 50), + ("SCC12", 50), + ] + if CP.flags & HyundaiFlags.USE_FCA.value: + messages.append(("FCA11", 50)) + + if CP.enableBsm: + messages.append(("LCA11", 50)) + + if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + messages.append(("E_EMS11", 50)) + else: + messages += [ + ("EMS12", 100), + ("EMS16", 100), + ] + + if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + messages.append(("ELECT_GEAR", 20)) + elif CP.flags & HyundaiFlags.CLUSTER_GEARS: + pass + elif CP.flags & HyundaiFlags.TCU_GEARS: + messages.append(("TCU12", 100)) + else: + messages.append(("LVR12", 100)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_cam_can_parser(CP): + if CP.flags & HyundaiFlags.CANFD: + return CarState.get_cam_can_parser_canfd(CP) + + messages = [ + ("LKAS11", 100) + ] + + if not CP.openpilotLongitudinalControl and CP.flags & HyundaiFlags.CAMERA_SCC: + messages += [ + ("SCC11", 50), + ("SCC12", 50), + ] + + if CP.flags & HyundaiFlags.USE_FCA.value: + messages.append(("FCA11", 50)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) + + def get_can_parser_canfd(self, CP): + messages = [ + ("WHEEL_SPEEDS", 100), + ("STEERING_SENSORS", 100), + ("MDPS", 100), + ("TCS", 50), + ("CRUISE_BUTTONS_ALT", 50), + ("BLINKERS", 4), + ("DOORS_SEATBELTS", 4), + ] + + if CP.flags & HyundaiFlags.EV: + messages += [ + ("ACCELERATOR", 100), + ("MANUAL_SPEED_LIMIT_ASSIST", 10), + ] + else: + messages += [ + (self.gear_msg_canfd, 100), + (self.accelerator_msg_canfd, 100), + ] + + if not (CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): + messages += [ + ("CRUISE_BUTTONS", 50) + ] + + if CP.enableBsm: + messages += [ + ("BLINDSPOTS_REAR_CORNERS", 20), + ] + + if not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and not CP.openpilotLongitudinalControl: + messages += [ + ("SCC_CONTROL", 50), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).ECAN) + + @staticmethod + def get_cam_can_parser_canfd(CP): + messages = [] + if CP.flags & HyundaiFlags.CANFD_HDA2: + block_lfa_msg = "CAM_0x362" if CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING else "CAM_0x2a4" + messages += [(block_lfa_msg, 20)] + elif CP.flags & HyundaiFlags.CANFD_CAMERA_SCC: + messages += [ + ("SCC_CONTROL", 50), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).CAM) diff --git a/opendbc_repo/opendbc/car/hyundai/fingerprints.py b/opendbc_repo/opendbc/car/hyundai/fingerprints.py new file mode 100644 index 000000000000000..63c6e3502a1b340 --- /dev/null +++ b/opendbc_repo/opendbc/car/hyundai/fingerprints.py @@ -0,0 +1,1173 @@ +from opendbc.car.structs import CarParams +from opendbc.car.hyundai.values import CAR + +Ecu = CarParams.Ecu + +# The existence of SCC or RDR in the fwdRadar FW usually determines the radar's function, +# i.e. if it sends the SCC messages or if another ECU like the camera or ADAS Driving ECU does + + +FW_VERSIONS = { + CAR.HYUNDAI_AZERA_6TH_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IG__ SCC F-CU- 1.00 1.00 99110-G8100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IG MDPS C 1.00 1.02 56310G8510\x00 4IGSC103', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IG MFC AT MES LHD 1.00 1.04 99211-G8100 200511', + ], + }, + CAR.HYUNDAI_AZERA_HEV_6TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.00 99211-G8000 180903', + b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.01 99211-G8000 181109', + b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.02 99211-G8100 191029', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IG MDPS C 1.00 1.00 56310M9600\x00 4IHSC100', + b'\xf1\x00IG MDPS C 1.00 1.01 56310M9350\x00 4IH8C101', + b'\xf1\x00IG MDPS C 1.00 1.02 56310M9350\x00 4IH8C102', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IGhe SCC FHCUP 1.00 1.00 99110-M9100 ', + b'\xf1\x00IGhe SCC FHCUP 1.00 1.01 99110-M9000 ', + b'\xf1\x00IGhe SCC FHCUP 1.00 1.02 99110-M9000 ', + ], + }, + CAR.HYUNDAI_GENESIS: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DH LKAS 1.1 -150210', + b'\xf1\x00DH LKAS 1.4 -140110', + b'\xf1\x00DH LKAS 1.5 -140425', + ], + }, + CAR.HYUNDAI_IONIQ: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.05 56310/G2501 4AEHC105', + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', + b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + ], + }, + CAR.HYUNDAI_IONIQ_PHEV_2019: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2551 4AEHC107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEP MFC AT AUS RHD 1.00 1.00 95740-G2400 180222', + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + ], + }, + CAR.HYUNDAI_IONIQ_PHEV: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2200 ', + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC F-CUP 1.00 1.02 99110-G2100 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.02 99110-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2210 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2310 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2510 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2560 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEP MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEP MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2700 201027', + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819', + ], + }, + CAR.HYUNDAI_IONIQ_EV_2020: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7200 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7500 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7000 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7100 ', + b'\xf1\x00AEev SCC FHCUP 1.00 1.01 99110-G7100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7310 4APEC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7510 4APEC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7560 4APEC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2600 190730', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2700 201027', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.03 95740-G2500 190516', + b'\xf1\x00AEE MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEE MFC AT USA LHD 1.00 1.01 95740-G2600 190819', + ], + }, + CAR.HYUNDAI_IONIQ_EV_LTD: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7000 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.02 56310G7300\x00 4AEEC102', + b'\xf1\x00AE MDPS C 1.00 1.03 56310/G7300 4AEEC103', + b'\xf1\x00AE MDPS C 1.00 1.03 56310G7300\x00 4AEEC103', + b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7301 4AEEC104', + b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7501 4AEEC104', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2300 170703', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', + b'\xf1\x00AEE MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + ], + }, + CAR.HYUNDAI_IONIQ_HEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2700 201027', + ], + }, + CAR.HYUNDAI_SONATA: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DN8_ SCC F-CU- 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC F-CUP 1.00 1.02 99110-L1000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.02 99110-L1000 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', + b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', + b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', + b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', + b'\xf1\x00DN ESC \x06 107 \x07\x03 58910-L1300', + b'\xf1\x00DN ESC \x06 107"\x08\x07 58910-L0100', + b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', + b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', + b'\xf1\x00DN ESC \x07 107"\x08\x07 58910-L0100', + b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0200 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1010 4DNDC103', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1030 4DNDC103', + b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', + b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', + b'\xf1\x00DN8 MDPS R 1.00 1.02 57700-L1000 4DNDP105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', + b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.04 99211-L1000 191016', + b'\xf1\x00DN8 MFC AT RUS LHD 1.00 1.03 99211-L1000 190705', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223', + ], + }, + CAR.HYUNDAI_SONATA_LF: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', + b'\xf1\x00LF ESC \x0c 11 \x17\x01\x13 58920-C2610', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51', + b'\xf1\x00LFF LKAS AT USA LHD 1.01 1.02 95740-C1000 E52', + ], + }, + CAR.HYUNDAI_TUCSON: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TL__ FCA F-CUP 1.00 1.01 99110-D3500 ', + b'\xf1\x00TL__ FCA F-CUP 1.00 1.02 99110-D3510 ', + b'\xf1\x00TL__ FCA FHCUP 1.00 1.02 99110-D3500 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TL MFC AT KOR LHD 1.00 1.02 95895-D3800 180719', + b'\xf1\x00TL MFC AT KOR LHD 1.00 1.06 95895-D3800 190107', + b'\xf1\x00TL MFC AT USA LHD 1.00 1.06 95895-D3800 190107', + ], + }, + CAR.HYUNDAI_SANTA_FE: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1210 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S2000 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600', + b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600', + b'\xf1\x00TM ESC \x02 103\x18\x11\x05 58910-S2500', + b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600', + b'\xf1\x00TM ESC \x02 104\x19\x07\x07 58910-S2600', + b'\xf1\x00TM ESC \x03 103\x18\x11\x07 58910-S2600', + b'\xf1\x00TM ESC \x0c 103\x18\x11\x08 58910-S2650', + b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', + b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', + b'\xf1\x00TM ESC \r 104\x19\x07\x08 58910-S2650', + b'\xf1\x00TM ESC \r 105\x19\x05# 58910-S1500', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409', + b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8A12', + b'\xf1\x00TM MDPS C 1.00 1.01 56340-S2000 9129', + b'\xf1\x00TM MDPS R 1.00 1.02 57700-S1100 4TMDP102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TM MFC AT EUR LHD 1.00 1.01 99211-S1010 181207', + b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409', + ], + }, + CAR.HYUNDAI_SANTA_FE_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S1500 ', + b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', + b'\xf1\x00TM__ SCC FHCUP 1.00 1.01 99110-S1500 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00TM ESC \x01 102!\x04\x03 58910-S2DA0', + b'\xf1\x00TM ESC \x01 104"\x10\x07 58910-S2DA0', + b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', + b'\xf1\x00TM ESC \x02 103"\x07\x08 58910-S2GA0', + b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', + b'\xf1\x00TM ESC \x03 102!\x04\x03 58910-S2DA0', + b'\xf1\x00TM ESC \x03 103"\x07\x06 58910-S2DA0', + b'\xf1\x00TM ESC \x04 101 \x08\x04 58910-S2GA0', + b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', + b'\xf1\x00TM ESC \x04 103"\x07\x08 58910-S2GA0', + b'\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', + b'\xf1\x00TM ESC 103!\x030 58910-S1MA0', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', + b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1EB0 4TSDC101', + b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TM MFC AT MES LHD 1.00 1.05 99211-S1500 220126', + b'\xf1\x00TMA MFC AT MEX LHD 1.00 1.01 99211-S2500 210205', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.00 99211-S2500 200720', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.01 99211-S2500 210205', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', + ], + }, + CAR.HYUNDAI_SANTA_FE_HEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', + b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100', + b'\xf1\x00TM MDPS C 1.00 1.02 56310GA000\x00 4TSHA100', + b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105', + b'\xf1\x00TM MDPS R 1.00 1.06 57700-CL000 4TSHP106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', + b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727', + b'\xf1\x00TMH MFC AT KOR LHD 1.00 1.06 99211-S1500 220727', + b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TMH MFC AT USA LHD 1.00 1.05 99211-S1500 220126', + b'\xf1\x00TMH MFC AT USA LHD 1.00 1.06 99211-S1500 220727', + ], + }, + CAR.HYUNDAI_SANTA_FE_PHEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TMhe SCC F-CUP 1.00 1.00 99110-CL500 ', + b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', + b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310CLEC0\x00 4TSHC102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.05 99211-S1500 220126', + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.06 99211-S1500 220727', + ], + }, + CAR.HYUNDAI_CUSTIN_1ST_GEN: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00KU ESC \x01 101!\x02\x03 58910-O3200', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00KU__ SCC F-CUP 1.00 1.01 99110-O3000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00KU MDPS C 1.00 1.01 56310/O3100 4KUCC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00KU2 MFC AT CHN LHD 1.00 1.02 99211-O3000 220923', + ], + }, + CAR.KIA_STINGER: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104', + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5220 4C2VL104', + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104', + b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106', + b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106', + b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.04 95740-J5000 180504', + ], + }, + CAR.KIA_STINGER_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5500 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5600 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.01 99110-J5100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5300 4C2CL503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5320 4C2VL503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5520 4C4VL503', + b'\xf1\x00CK MDPS R 1.00 5.04 57700-J5520 4C4VL504', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT KOR LHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 99211-J5000 201209', + ], + }, + CAR.HYUNDAI_PALISADE: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC F-CUP 1.00 1.05 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCU- 1.00 1.05 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.00 99110-S8110 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.03 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.00 99110-S9110 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.01 99110-S9110 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.03 99110-S9100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x01 104 \x10\x15 58910-S8350', + b'\xf1\x00LX ESC \x01 104 \x10\x16 58910-S8360', + b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', + b'\xf1\x00LX ESC \x0b 101\x19\x03 58910-S8360', + b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', + b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', + b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', + b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x0b 104 \x10\x13 58910-S8330', + b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', + b'\xf1\x00ON ESC \x01 101\x19\t\x08 58910-S9360', + b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360', + b'\xf1\x00ON ESC \x0b 101\x19\t\x05 58910-S9320', + b'\xf1\x00ON ESC \x0b 101\x19\t\x08 58910-S9360', + b'\xf1\x00ON ESC \x0b 103$\x04\x08 58910-S9360', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00LX2 MDPS C 1,00 1,03 56310-S8020 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8000 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-XX000 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8020 4LXDC104', + b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8420 4LXDC104', + b'\xf1\x00LX2 MDPS R 1.00 1.02 56370-S8300 9318', + b'\xf1\x00ON MDPS C 1.00 1.00 56340-S9000 8B13', + b'\xf1\x00ON MDPS C 1.00 1.01 56340-S9000 9201', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00LX2 MFC AT KOR LHD 1.00 1.08 99211-S8100 200903', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.00 99211-S8110 210226', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.05 99211-S8100 190909', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 200422', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 200903', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 181105', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 200720', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.04 99211-S9100 211227', + ], + }, + CAR.HYUNDAI_VELOSTER: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', + b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JS LKAS AT KOR LHD 1.00 1.03 95740-J3000 K33', + b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', + ], + }, + CAR.GENESIS_G70: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', + ], + }, + CAR.GENESIS_G70_2020: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9220 4I2VL106', + b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9220 4I2VL107', + b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9420 4I4VL107', + b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9200 4I2CL108', + b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9420 4I4VL108', + b'\xf1\x00IK MDPS R 1.00 5.09 57700-G9520 4I4VL509', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 \xf1\xa01.02', + b'\xf1\x00IK__ SCC FHCUP 1.00 1.00 99110-G9300 ', + b'\xf1\x00IK__ SCC FHCUP 1.00 1.02 96400-G9000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IK MFC AT KOR LHD 1.00 1.01 95740-G9000 170920', + b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', + b'\xf1\x00IK MFC AT USA LHD 1.00 1.04 99211-G9000 220401', + ], + }, + CAR.GENESIS_G80: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DH__ SCC F-CU- 1.00 1.01 96400-B1110 ', + b'\xf1\x00DH__ SCC F-CUP 1.00 1.01 96400-B1120 ', + b'\xf1\x00DH__ SCC F-CUP 1.00 1.02 96400-B1120 ', + b'\xf1\x00DH__ SCC FHCUP 1.00 1.01 96400-B1110 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DH LKAS AT EUR LHD 1.01 1.01 95895-B1500 161014', + b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.01 95895-B1500 161014', + b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.02 95895-B1500 170810', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.01 95895-B1500 161014', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.02 95895-B1500 170810', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.03 95895-B1500 180713', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.04 95895-B1500 181213', + ], + }, + CAR.GENESIS_G80_2ND_GEN_FL: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00RG3_ SCC ----- 1.00 1.02 99110-T1120 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00RG3 MFC AT USA LHD 1.00 1.01 99211-T1200 230607', + ], + }, + CAR.GENESIS_G90: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00HI__ SCC F-CUP 1.00 1.01 96400-D2100 ', + b'\xf1\x00HI__ SCC FHCUP 1.00 1.02 99110-D2100 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2020 160302', + b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2030 170208', + b'\xf1\x00HI LKAS AT USA LHD 1.00 1.01 95895-D2030 170811', + b'\xf1\x00HI MFC AT USA LHD 1.00 1.03 99211-D2000 190831', + ], + }, + CAR.HYUNDAI_KONA: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', + ], + }, + CAR.KIA_CEED: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CD__ SCC F-CUP 1.00 1.02 99110-J7000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CD MDPS C 1.00 1.06 56310-XX000 4CDEC106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CD LKAS AT EUR LHD 1.00 1.01 99211-J7000 B40', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00CD ESC \x03 102\x18\x08\x05 58920-J7350', + ], + }, + CAR.KIA_FORTE: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00BD MDPS C 1.00 1.02 56310-XX000 4BD2C102', + b'\xf1\x00BD MDPS C 1.00 1.08 56310/M6300 4BDDC108', + b'\xf1\x00BD MDPS C 1.00 1.08 56310M6300\x00 4BDDC108', + b'\xf1\x00BDm MDPS C A.01 1.01 56310M7800\x00 4BPMC101', + b'\xf1\x00BDm MDPS C A.01 1.03 56310M7800\x00 4BPMC103', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00BD LKAS AT USA LHD 1.00 1.04 95740-M6000 J33', + b'\xf1\x00BDP LKAS AT USA LHD 1.00 1.05 99211-M6500 744', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00BDPE_SCC FHCUPC 1.00 1.04 99110-M6500\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x00BD__ SCC H-CUP 1.00 1.02 99110-M6000 ', + ], + }, + CAR.KIA_K5_2021: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.04 99110-L2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3110 4DLAC101', + b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L2220 4DLDC102', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310L3220\x00 4DLAC102', + b'\xf1\x00DL3 MDPS R 1.00 1.02 57700-L3000 4DLAP102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DL3 MFC AT KOR LHD 1.00 1.04 99210-L2000 210527', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.05 99210-L3000 211222', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00DL ESC \x01 104 \x07\x12 58910-L2200', + b'\xf1\x00DL ESC \x03 100 \x08\x02 58910-L3600', + b'\xf1\x00DL ESC \x06 101 \x04\x02 58910-L3200', + b'\xf1\x00DL ESC \x06 102 \x07\x02 58910-L3200', + b'\xf1\x00DL ESC \x06 103"\x08\x06 58910-L3200', + b'\xf1\x00DL ESC \t 100 \x06\x02 58910-L3800', + b'\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', + b'\xf1\x00DL ESC \t 102"\x08\x10 58910-L3800', + ], + }, + CAR.KIA_K5_HEV_2020: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DLhe SCC FHCUP 1.00 1.02 99110-L7000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7000 4DLHC102', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7220 4DLHC102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.01 99210-L2000 191022', + b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.02 99210-L2000 200309', + b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.04 99210-L2000 210527', + ], + }, + CAR.HYUNDAI_KONA_EV: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \x02 210 \x02\x14 58520-K4000', + b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \x03 210 \x02\x14 58520-K4000', + b'\xf1\x00OS IEB \x03 211 \x04\x02 58520-K4000', + b'\xf1\x00OS IEB \x03 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \x04 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 AUS RHD 1.00 1.00 95740-K4300 W50', + b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4300 W50', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103', + b'\xf1\x00OS MDPS C 1.00 1.04 56310-XX000 4OEDC104', + b'\xf1\x00OS MDPS C 1.00 1.04 56310/K4550 4OEDC104', + b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104', + b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4000 ', + b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4100 ', + b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 ', + b'\xf1\x00OSev SCC FNCUP 1.00 1.01 99110-K4000 ', + ], + }, + CAR.HYUNDAI_KONA_EV_2022: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x02 102"\x05\x16 58520-K4010', + b'\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', + b'\xf1\x00OS IEB \x03 102"\x05\x16 58520-K4010', + b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802', + b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.02 99211-J9110 802', + b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT USA LHD 1.00 1.04 99211-J9200 904', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OSP MDPS C 1.00 1.02 56310-K4271 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4261\x00 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4971\x00 4OEPC102', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00', + ], + }, + CAR.HYUNDAI_KONA_EV_2ND_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SXev RDR ----- 1.00 1.00 99110-BF000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SX2EMFC AT KOR LHD 1.00 1.00 99211-BF000 230410', + ], + }, + CAR.KIA_NIRO_EV: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4600 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4000 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', + b'\xf1\x00DEev SCC FHCUP 1.00 1.00 99110-Q4600 ', + b'\xf1\x00DEev SCC FHCUP 1.00 1.03 96400-Q4000 ', + b'\xf1\x00DEev SCC FNCUP 1.00 1.00 99110-Q4600 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.04 56310Q4100\x00 4DEEC104', + b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105', + b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4100\x00 4DEEC105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4000 191211', + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.03 95740-Q4000 180821', + b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.02 95740-Q4000 180705', + b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.00 99211-Q4000 191211', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.02 99211-Q4100 201218', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', + ], + }, + CAR.KIA_NIRO_EV_2ND_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', + b'\xf1\x00SG2EMFC AT USA LHD 1.01 1.09 99211-AT000 220801', + ], + }, + CAR.KIA_NIRO_PHEV: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 95740-G5010 170117', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 95740-G5010 170117', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.05 99211-G5000 190826', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC F-CUP 1.00 1.02 99110-G5100 ', + b'\xf1\x00DEhe SCC FHCUP 1.00 1.02 99110-G5100 ', + b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', + ], + }, + CAR.KIA_NIRO_PHEV_2022: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 99211-G5500 210428', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.06 99211-G5000 201028', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC F-CUP 1.00 1.00 99110-G5600 ', + b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', + ], + }, + CAR.KIA_NIRO_HEV_2021: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEH MFC AT KOR LHD 1.00 1.04 99211-G5000 190516', + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 99211-G5500 210428', + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.07 99211-G5000 201221', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', + b'\xf1\x00DEhe SCC FHCUP 1.00 1.01 99110-G5000 ', + ], + }, + CAR.KIA_SELTOS: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00SP ESC \x07 101\x19\t\x05 58910-Q5450', + b'\xf1\x00SP ESC \t 101\x19\t\x05 58910-Q5450', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00SP2 MDPS C 1.00 1.04 56300Q5200 ', + b'\xf1\x00SP2 MDPS C 1.01 1.05 56300Q5200 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114', + b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.05 99210-Q5000 201012', + ], + }, + CAR.KIA_OPTIMA_G4: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00JF ESC \t 17 \x16\x06# 58920-D4180', + b'\xf1\x00JF ESC \x0f 16 \x16\x06\x17 58920-D5080', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFWGN LDWS AT USA LHD 1.00 1.02 95895-D4100 G21', + b'\xf1\x00JFWGN LKAS AT EUR LHD 1.00 1.01 95895-D4100 G20', + ], + }, + CAR.KIA_OPTIMA_G4_FL: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', + ], + (Ecu.abs, 0x7d1, None): [ + b"\xf1\x00JF ESC \t 11 \x18\x03' 58920-D5260", + b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5001 h32', + b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5100 h32', + ], + }, + CAR.KIA_OPTIMA_H: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JFhe SCC FNCUP 1.00 1.00 96400-A8000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFP LKAS AT EUR LHD 1.00 1.03 95895-A8100 160711', + ], + }, + CAR.KIA_OPTIMA_H_G4_FL: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JFhe SCC FHCUP 1.00 1.01 99110-A8500 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFH MFC AT KOR LHD 1.00 1.01 95895-A8200 180323', + ], + }, + CAR.HYUNDAI_ELANTRA: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AD LKAS AT USA LHD 1.01 1.01 95895-F2000 251', + b'\xf1\x00ADP LKAS AT USA LHD 1.00 1.03 99211-F2000 X31', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00AD ESC \x11 11 \x18\x05\x06 58910-F2840', + b'\xf1\x00AD ESC \x11 12 \x15\t\t 58920-F2810', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AD__ SCC H-CUP 1.00 1.00 99110-F2100 ', + b'\xf1\x00AD__ SCC H-CUP 1.00 1.01 96400-F2100 ', + ], + }, + CAR.HYUNDAI_ELANTRA_GT_I30: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00PD LKAS AT KOR LHD 1.00 1.02 95740-G3000 A51', + b'\xf1\x00PD LKAS AT USA LHD 1.00 1.02 95740-G3000 A51', + b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00PD MDPS C 1.00 1.00 56310G3300\x00 4PDDC100', + b'\xf1\x00PD MDPS C 1.00 1.03 56310/G3300 4PDDC103', + b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00PD ESC \t 104\x18\t\x03 58920-G3350', + b'\xf1\x00PD ESC \x0b 103\x17\x110 58920-G3350', + b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', + b'\xf1\x00PD__ SCC F-CUP 1.01 1.00 96400-G3100 ', + b'\xf1\x00PD__ SCC FNCUP 1.01 1.00 96400-G3000 ', + ], + }, + CAR.HYUNDAI_ELANTRA_2021: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', + b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', + b'\xf1\x00CN7_ SCC FNCUP 1.00 1.01 99110-AA000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA050 4CNDC106', + b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA070 4CNDC106', + b'\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106', + b'\xf1\x00CN7 MDPS C 1.00 1.07 56310AA050\x00 4CNDC107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.02 99210-AB000 220111', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AB000 220426', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.07 99210-AA000 220426', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.08 99210-AA000 220728', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', + b'\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', + b'\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800', + ], + }, + CAR.HYUNDAI_ELANTRA_HEV_2021: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.05 99210-AA000 210930', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.07 99210-AA000 220426', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.08 99210-AA000 220728', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.09 99210-AA000 221108', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102', + b'\xf1\x00CN7 MDPS C 1.00 1.03 56310/BY050 4CNHC103', + b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY050\x00 4CNHC103', + b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY0500 4CNHC103', + b'\xf1\x00CN7 MDPS C 1.00 1.04 56310BY050\x00 4CNHC104', + ], + }, + CAR.HYUNDAI_KONA_HEV: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OShe SCC FNCUP 1.00 1.01 99110-CM000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.00 56310CM030\x00 4OHDC100', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OSH LKAS AT KOR LHD 1.00 1.01 95740-CM000 l31', + ], + }, + CAR.HYUNDAI_SONATA_HYBRID: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', + b'\xf1\x00DNhe SCC FHCUP 1.00 1.00 99110-L5000 ', + b'\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L5000 4DNHC101', + b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', + b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L5450 4DNHC103', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DN8HMFC AT KOR LHD 1.00 1.03 99211-L1000 190705', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.05 99211-L1000 201109', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.06 99211-L1000 210325', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.07 99211-L1000 211223', + ], + }, + CAR.KIA_SORENTO: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00UMP LKAS AT KOR LHD 1.00 1.00 95740-C5550 S30', + b'\xf1\x00UMP LKAS AT USA LHD 1.00 1.00 95740-C6550 d00', + b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00UM ESC \x02 12 \x18\x05\x05 58910-C6300', + b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330', + b'\xf1\x00UM ESC \x13 12 \x17\x07\x05 58910-C5320', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C5500 ', + b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C6500 ', + ], + }, + CAR.KIA_EV6: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328', + b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.00 99210-CV100 220630', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.00 99210-CV200 230510', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.04 99210-CV000 210823', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.06 99210-CV000 220328', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV200 230510', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328', + ], + }, + CAR.HYUNDAI_IONIQ_5: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.05 99211-GI010 220614', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.00 99211-GI100 230915', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.01 99211-GI100 240110', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI010 230110', + b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.00 99211-GI020 230719', + b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.05 99211-GI010 220614', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.00 99211-GI020 230719', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.00 99211-GI100 230915', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.05 99211-GI010 220614', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.06 99211-GI010 230110', + ], + }, + CAR.HYUNDAI_IONIQ_6: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CE__ RDR ----- 1.00 1.01 99110-KL000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CE MFC AT CAN LHD 1.00 1.04 99211-KL000 221213', + b'\xf1\x00CE MFC AT EUR LHD 1.00 1.03 99211-KL000 221011', + b'\xf1\x00CE MFC AT EUR LHD 1.00 1.04 99211-KL000 221213', + b'\xf1\x00CE MFC AT USA LHD 1.00 1.04 99211-KL000 221213', + ], + }, + CAR.HYUNDAI_TUCSON_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.00 99211-N9260 14Y', + b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.01 99211-N9100 14A', + b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 1.00 99211-N9220 14K', + b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 2.02 99211-N9000 14E', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9250 14W', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9260 14Y', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9100 14A', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', + b'\xf1\x00NX4__ 1.00 1.01 99110-N9000 ', + b'\xf1\x00NX4__ 1.00 1.02 99110-N9000 ', + b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ', + ], + }, + CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW020 14Z', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ', + b'\xf1\x00NX4__ 1.01 1.00 99110-K5000 ', + ], + }, + CAR.KIA_SPORTAGE_5TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NQ5 FR_CMR AT AUS RHD 1.00 1.00 99211-P1040 663', + b'\xf1\x00NQ5 FR_CMR AT EUR LHD 1.00 1.00 99211-P1040 663', + b'\xf1\x00NQ5 FR_CMR AT GEN LHD 1.00 1.00 99211-P1060 665', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1030 662', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1040 663', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1060 665', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1070 690', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NQ5__ 1.00 1.02 99110-P1000 ', + b'\xf1\x00NQ5__ 1.00 1.03 99110-CH000 ', + b'\xf1\x00NQ5__ 1.00 1.03 99110-P1000 ', + b'\xf1\x00NQ5__ 1.01 1.03 99110-CH000 ', + b'\xf1\x00NQ5__ 1.01 1.03 99110-P1000 ', + ], + }, + CAR.GENESIS_GV70_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125', + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR300 220125', + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ', + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR300 ', + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ', + ], + }, + CAR.GENESIS_GV70_ELECTRIFIED_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JK1EMFC AT USA LHD 1.00 1.00 99211-IT100 220919', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JKev SCC ----- 1.00 1.01 99110-DS000 ', + ], + }, + CAR.GENESIS_GV60_EV_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JW1 MFC AT AUS RHD 1.00 1.03 99211-CU100 221118', + 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', + b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.06 99210-R5000 211216', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00MQ4_ SCC F-CUP 1.00 1.06 99110-P2000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.00 99110-R5000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.08 99110-P2000 ', + ], + }, + CAR.KIA_SORENTO_HEV_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.04 99210-P2000 200330', + b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.12 99210-P2000 230331', + b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.10 99210-P2000 210406', + b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.11 99210-P2000 211217', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00MQhe SCC FHCUP 1.00 1.04 99110-P4000 ', + b'\xf1\x00MQhe SCC FHCUP 1.00 1.06 99110-P4000 ', + b'\xf1\x00MQhe SCC FHCUP 1.00 1.07 99110-P4000 ', + ], + }, + CAR.KIA_NIRO_HEV_2ND_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.08 99211-AT000 220531', + b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.09 99211-AT000 220801', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', + ], + }, + CAR.GENESIS_GV80: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JX1 MFC AT USA LHD 1.00 1.02 99211-T6110 220513', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JX1_ SCC FHCUP 1.00 1.01 99110-T6100 ', + ], + }, + CAR.KIA_CARNIVAL_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00KA4 MFC AT EUR LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4 MFC AT KOR LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.00 99210-R0100 230105', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.01 99210-R0100 230710', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.05 99210-R0000 201221', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4CMFC AT CHN LHD 1.00 1.01 99211-I4000 210525', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00KA4_ SCC F-CUP 1.00 1.03 99110-R0000 ', + b'\xf1\x00KA4_ SCC FHCUP 1.00 1.00 99110-R0100 ', + b'\xf1\x00KA4_ SCC FHCUP 1.00 1.02 99110-R0000 ', + b'\xf1\x00KA4_ SCC FHCUP 1.00 1.03 99110-R0000 ', + b'\xf1\x00KA4c SCC FHCUP 1.00 1.01 99110-I4000 ', + ], + }, + CAR.KIA_K8_HEV_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.03 99211-L8000 210907', + b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.04 99211-L8000 230207', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00GL3_ RDR ----- 1.00 1.02 99110-L8000 ', + ], + }, + CAR.HYUNDAI_STARIA_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00US4 MFC AT KOR LHD 1.00 1.06 99211-CG000 230524', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00US4_ RDR ----- 1.00 1.00 99110-CG000 ', + ], + }, +} diff --git a/selfdrive/car/hyundai/hyundaican.py b/opendbc_repo/opendbc/car/hyundai/hyundaican.py similarity index 94% rename from selfdrive/car/hyundai/hyundaican.py rename to opendbc_repo/opendbc/car/hyundai/hyundaican.py index b4b951f89e173bf..644de8148abf8a9 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/opendbc_repo/opendbc/car/hyundai/hyundaican.py @@ -1,5 +1,5 @@ import crcmod -from openpilot.selfdrive.car.hyundai.values import CAR, HyundaiFlags +from opendbc.car.hyundai.values import CAR, HyundaiFlags hyundai_checksum = crcmod.mkCrcFun(0x11D, initCrc=0xFD, rev=False, xorOut=0xdf) @@ -77,7 +77,7 @@ def create_lkas11(packer, frame, CP, apply_steer, steer_req, # Genesis and Optima fault when forwarding while engaged values["CF_Lkas_LdwsActivemode"] = 2 - dat = packer.make_can_msg("LKAS11", 0, values)[2] + dat = packer.make_can_msg("LKAS11", 0, values)[1] if CP.flags & HyundaiFlags.CHECKSUM_CRC8: # CRC Checksum as seen on 2019 Hyundai Santa Fe @@ -117,12 +117,9 @@ def create_clu11(packer, frame, clu11, button, CP): return packer.make_can_msg("CLU11", bus, values) -def create_lfahda_mfc(packer, enabled, hda_set_speed=0): +def create_lfahda_mfc(packer, enabled): values = { "LFA_Icon_State": 2 if enabled else 0, - "HDA_Active": 1 if hda_set_speed else 0, - "HDA_Icon_State": 2 if hda_set_speed else 0, - "HDA_VSetReq": hda_set_speed, } return packer.make_can_msg("LFAHDA_MFC", 0, values) @@ -156,7 +153,7 @@ def create_acc_commands(packer, enabled, accel, upper_jerk, idx, hud_control, se scc12_values["CF_VSM_ConfMode"] = 1 scc12_values["AEB_Status"] = 1 # AEB disabled - scc12_dat = packer.make_can_msg("SCC12", 0, scc12_values)[2] + scc12_dat = packer.make_can_msg("SCC12", 0, scc12_values)[1] scc12_values["CR_VSM_ChkSum"] = 0x10 - sum(sum(divmod(i, 16)) for i in scc12_dat) % 0x10 commands.append(packer.make_can_msg("SCC12", 0, scc12_values)) @@ -181,7 +178,7 @@ def create_acc_commands(packer, enabled, accel, upper_jerk, idx, hud_control, se "FCA_DrvSetStatus": 1, "FCA_Status": 1, # AEB disabled } - fca11_dat = packer.make_can_msg("FCA11", 0, fca11_values)[2] + fca11_dat = packer.make_can_msg("FCA11", 0, fca11_values)[1] fca11_values["CR_FCA_ChkSum"] = hyundai_checksum(fca11_dat[:7]) commands.append(packer.make_can_msg("FCA11", 0, fca11_values)) diff --git a/selfdrive/car/hyundai/hyundaicanfd.py b/opendbc_repo/opendbc/car/hyundai/hyundaicanfd.py similarity index 94% rename from selfdrive/car/hyundai/hyundaicanfd.py rename to opendbc_repo/opendbc/car/hyundai/hyundaicanfd.py index 54804f94fd1461c..d3488ff53139cf3 100644 --- a/selfdrive/car/hyundai/hyundaicanfd.py +++ b/opendbc_repo/opendbc/car/hyundai/hyundaicanfd.py @@ -1,15 +1,14 @@ -from openpilot.common.numpy_fast import clip -from openpilot.selfdrive.car import CanBusBase -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags +from opendbc.car import CanBusBase +from opendbc.car.common.numpy_fast import clip +from opendbc.car.hyundai.values import HyundaiFlags class CanBus(CanBusBase): - def __init__(self, CP, hda2=None, fingerprint=None) -> None: + def __init__(self, CP, fingerprint=None, hda2=None) -> None: super().__init__(CP, fingerprint) if hda2 is None: - assert CP is not None - hda2 = CP.flags & HyundaiFlags.CANFD_HDA2.value + hda2 = CP.flags & HyundaiFlags.CANFD_HDA2.value if CP is not None else False # On the CAN-FD platforms, the LKAS camera is on both A-CAN and E-CAN. HDA2 cars # have a different harness than the HDA1 and non-HDA variants in order to split diff --git a/opendbc_repo/opendbc/car/hyundai/interface.py b/opendbc_repo/opendbc/car/hyundai/interface.py new file mode 100644 index 000000000000000..fedcd2d4897928e --- /dev/null +++ b/opendbc_repo/opendbc/car/hyundai/interface.py @@ -0,0 +1,139 @@ +from panda import Panda +from opendbc.car import get_safety_config, structs +from opendbc.car.hyundai.hyundaicanfd import CanBus +from opendbc.car.hyundai.values import HyundaiFlags, CAR, DBC, CAMERA_SCC_CAR, CANFD_RADAR_SCC_CAR, \ + CANFD_UNSUPPORTED_LONGITUDINAL_CAR, \ + UNSUPPORTED_LONGITUDINAL_CAR +from opendbc.car.hyundai.radar_interface import RADAR_START_ADDR +from opendbc.car.interfaces import CarInterfaceBase +from opendbc.car.disable_ecu import disable_ecu + +ButtonType = structs.CarState.ButtonEvent.Type +Ecu = structs.CarParams.Ecu + +# Cancel button can sometimes be ACC pause/resume button, main button can also enable on some cars +ENABLE_BUTTONS = (ButtonType.accelCruise, ButtonType.decelCruise, ButtonType.cancel, ButtonType.mainCruise) + + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "hyundai" + + cam_can = CanBus(None, fingerprint).CAM + hda2 = 0x50 in fingerprint[cam_can] or 0x110 in fingerprint[cam_can] + CAN = CanBus(None, fingerprint, hda2) + + if ret.flags & HyundaiFlags.CANFD: + # Shared configuration for CAN-FD cars + ret.experimentalLongitudinalAvailable = candidate not in (CANFD_UNSUPPORTED_LONGITUDINAL_CAR | CANFD_RADAR_SCC_CAR) + ret.enableBsm = 0x1e5 in fingerprint[CAN.ECAN] + + if 0x105 in fingerprint[CAN.ECAN]: + ret.flags |= HyundaiFlags.HYBRID.value + + # detect HDA2 with ADAS Driving ECU + if hda2: + ret.flags |= HyundaiFlags.CANFD_HDA2.value + if 0x110 in fingerprint[CAN.CAM]: + ret.flags |= HyundaiFlags.CANFD_HDA2_ALT_STEERING.value + else: + # non-HDA2 + if 0x1cf not in fingerprint[CAN.ECAN]: + ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value + if not ret.flags & HyundaiFlags.RADAR_SCC: + ret.flags |= HyundaiFlags.CANFD_CAMERA_SCC.value + + # Some HDA2 cars have alternative messages for gear checks + # ICE cars do not have 0x130; GEARS message on 0x40 or 0x70 instead + if 0x130 not in fingerprint[CAN.ECAN]: + if 0x40 not in fingerprint[CAN.ECAN]: + ret.flags |= HyundaiFlags.CANFD_ALT_GEARS_2.value + else: + ret.flags |= HyundaiFlags.CANFD_ALT_GEARS.value + + cfgs = [get_safety_config(structs.CarParams.SafetyModel.hyundaiCanfd), ] + if CAN.ECAN >= 4: + cfgs.insert(0, get_safety_config(structs.CarParams.SafetyModel.noOutput)) + ret.safetyConfigs = cfgs + + if ret.flags & HyundaiFlags.CANFD_HDA2: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 + if ret.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2_ALT_STEERING + if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS + if ret.flags & HyundaiFlags.CANFD_CAMERA_SCC: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC + + else: + # Shared configuration for non CAN-FD cars + ret.experimentalLongitudinalAvailable = candidate not in (UNSUPPORTED_LONGITUDINAL_CAR | CAMERA_SCC_CAR) + ret.enableBsm = 0x58b in fingerprint[0] + + # Send LFA message on cars with HDA + if 0x485 in fingerprint[2]: + ret.flags |= HyundaiFlags.SEND_LFA.value + + # These cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 + if 0x38d in fingerprint[0] or 0x38d in fingerprint[2]: + ret.flags |= HyundaiFlags.USE_FCA.value + + if ret.flags & HyundaiFlags.LEGACY: + # these cars require a special panda safety mode due to missing counters and checksums in the messages + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.hyundaiLegacy)] + else: + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.hyundai, 0)] + + if ret.flags & HyundaiFlags.CAMERA_SCC: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC + + # Common lateral control setup + + ret.centerToFront = ret.wheelbase * 0.4 + ret.steerActuatorDelay = 0.1 + ret.steerLimitTimer = 0.4 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + if ret.flags & HyundaiFlags.ALT_LIMITS: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_ALT_LIMITS + + # Common longitudinal control setup + + ret.radarUnavailable = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None + ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable + ret.pcmCruise = not ret.openpilotLongitudinalControl + ret.startingState = True + ret.vEgoStarting = 0.1 + ret.startAccel = 1.0 + ret.longitudinalActuatorDelay = 0.5 + + if ret.openpilotLongitudinalControl: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_LONG + if ret.flags & HyundaiFlags.HYBRID: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_HYBRID_GAS + elif ret.flags & HyundaiFlags.EV: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_EV_GAS + + # Car specific configuration overrides + + if candidate == CAR.KIA_OPTIMA_G4_FL: + ret.steerActuatorDelay = 0.2 + + # Dashcam cars are missing a test route, or otherwise need validation + # TODO: Optima Hybrid 2017 uses a different SCC12 checksum + ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, } + + return ret + + @staticmethod + def init(CP, can_recv, can_send): + if CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value): + addr, bus = 0x7d0, 0 + if CP.flags & HyundaiFlags.CANFD_HDA2.value: + addr, bus = 0x730, CanBus(CP).ECAN + disable_ecu(can_recv, can_send, bus=bus, addr=addr, com_cont_req=b'\x28\x83\x01') + + # for blinkers + if CP.flags & HyundaiFlags.ENABLE_BLINKERS: + disable_ecu(can_recv, can_send, bus=CanBus(CP).ECAN, addr=0x7B1, com_cont_req=b'\x28\x83\x01') diff --git a/opendbc_repo/opendbc/car/hyundai/radar_interface.py b/opendbc_repo/opendbc/car/hyundai/radar_interface.py new file mode 100644 index 000000000000000..a9078749d656f8b --- /dev/null +++ b/opendbc_repo/opendbc/car/hyundai/radar_interface.py @@ -0,0 +1,79 @@ +import math + +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.interfaces import RadarInterfaceBase +from opendbc.car.hyundai.values import DBC + +RADAR_START_ADDR = 0x500 +RADAR_MSG_COUNT = 32 + +# POC for parsing corner radars: https://github.com/commaai/openpilot/pull/24221/ + +def get_radar_can_parser(CP): + if DBC[CP.carFingerprint]['radar'] is None: + return None + + messages = [(f"RADAR_TRACK_{addr:x}", 50) for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT)] + return CANParser(DBC[CP.carFingerprint]['radar'], messages, 1) + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.updated_messages = set() + self.trigger_msg = RADAR_START_ADDR + RADAR_MSG_COUNT - 1 + self.track_id = 0 + + self.radar_off_can = CP.radarUnavailable + self.rcp = get_radar_can_parser(CP) + + def update(self, can_strings): + if self.radar_off_can or (self.rcp is None): + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + rr = self._update(self.updated_messages) + self.updated_messages.clear() + + return rr + + def _update(self, updated_messages): + ret = structs.RadarData() + if self.rcp is None: + return ret + + errors = [] + + if not self.rcp.can_valid: + errors.append("canError") + ret.errors = errors + + for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT): + msg = self.rcp.vl[f"RADAR_TRACK_{addr:x}"] + + if addr not in self.pts: + self.pts[addr] = structs.RadarData.RadarPoint() + self.pts[addr].trackId = self.track_id + self.track_id += 1 + + valid = msg['STATE'] in (3, 4) + if valid: + azimuth = math.radians(msg['AZIMUTH']) + self.pts[addr].measured = True + self.pts[addr].dRel = math.cos(azimuth) * msg['LONG_DIST'] + self.pts[addr].yRel = 0.5 * -math.sin(azimuth) * msg['LONG_DIST'] + self.pts[addr].vRel = msg['REL_SPEED'] + self.pts[addr].aRel = msg['REL_ACCEL'] + self.pts[addr].yvRel = float('nan') + + else: + del self.pts[addr] + + ret.points = list(self.pts.values()) + return ret diff --git a/selfdrive/car/mazda/__init__.py b/opendbc_repo/opendbc/car/hyundai/tests/__init__.py similarity index 100% rename from selfdrive/car/mazda/__init__.py rename to opendbc_repo/opendbc/car/hyundai/tests/__init__.py diff --git a/opendbc_repo/opendbc/car/hyundai/tests/print_platform_codes.py b/opendbc_repo/opendbc/car/hyundai/tests/print_platform_codes.py new file mode 100755 index 000000000000000..325b020f9b9eb4d --- /dev/null +++ b/opendbc_repo/opendbc/car/hyundai/tests/print_platform_codes.py @@ -0,0 +1,21 @@ +#!/usr/bin/env python3 +from opendbc.car.structs import CarParams +from opendbc.car.hyundai.values import PLATFORM_CODE_ECUS, get_platform_codes +from opendbc.car.hyundai.fingerprints import FW_VERSIONS + +Ecu = CarParams.Ecu + +if __name__ == "__main__": + for car_model, ecus in FW_VERSIONS.items(): + print() + print(car_model) + for ecu in sorted(ecus): + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + platform_codes = get_platform_codes(ecus[ecu]) + codes = {code for code, _ in platform_codes} + dates = {date for _, date in platform_codes if date is not None} + print(f' (Ecu.{ecu[0]}, {hex(ecu[1])}, {ecu[2]}):') + print(f' Codes: {codes}') + print(f' Dates: {dates}') diff --git a/selfdrive/car/hyundai/tests/test_hyundai.py b/opendbc_repo/opendbc/car/hyundai/tests/test_hyundai.py similarity index 82% rename from selfdrive/car/hyundai/tests/test_hyundai.py rename to opendbc_repo/opendbc/car/hyundai/tests/test_hyundai.py index 4d31d7d15e8c684..ece152d4a4da27f 100644 --- a/selfdrive/car/hyundai/tests/test_hyundai.py +++ b/opendbc_repo/opendbc/car/hyundai/tests/test_hyundai.py @@ -2,16 +2,20 @@ import pytest -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.hyundai.values import CAMERA_SCC_CAR, CANFD_CAR, CAN_GEARS, CAR, CHECKSUM, DATE_FW_ECUS, \ +from panda import Panda +from opendbc.car import gen_empty_fingerprint +from opendbc.car.structs import CarParams +from opendbc.car.fw_versions import build_fw_dict +from opendbc.car.hyundai.interface import CarInterface +from opendbc.car.hyundai.hyundaicanfd import CanBus +from opendbc.car.hyundai.radar_interface import RADAR_START_ADDR +from opendbc.car.hyundai.values import CAMERA_SCC_CAR, CANFD_CAR, CAN_GEARS, CAR, CHECKSUM, DATE_FW_ECUS, \ HYBRID_CAR, EV_CAR, FW_QUERY_CONFIG, LEGACY_SAFETY_MODE_CAR, CANFD_FUZZY_WHITELIST, \ UNSUPPORTED_LONGITUDINAL_CAR, PLATFORM_CODE_ECUS, HYUNDAI_VERSION_REQUEST_LONG, \ - get_platform_codes -from openpilot.selfdrive.car.hyundai.fingerprints import FW_VERSIONS + HyundaiFlags, get_platform_codes +from opendbc.car.hyundai.fingerprints import FW_VERSIONS -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} +Ecu = CarParams.Ecu # Some platforms have date codes in a different format we don't yet parse (or are missing). # For now, assert list of expected missing date cars @@ -40,6 +44,31 @@ class TestHyundaiFingerprint: + def test_feature_detection(self): + # HDA2 + for hda2 in (True, False): + fingerprint = gen_empty_fingerprint() + if hda2: + cam_can = CanBus(None, fingerprint).CAM + fingerprint[cam_can] = [0x50, 0x110] # HDA2 steering messages + CP = CarInterface.get_params(CAR.KIA_EV6, fingerprint, [], False, False) + assert bool(CP.flags & HyundaiFlags.CANFD_HDA2) == hda2 + + # radar available + for radar in (True, False): + fingerprint = gen_empty_fingerprint() + if radar: + fingerprint[1][RADAR_START_ADDR] = 8 + CP = CarInterface.get_params(CAR.HYUNDAI_SONATA, fingerprint, [], False, False) + assert CP.radarUnavailable != radar + + def test_alternate_limits(self): + # Alternate lateral control limits, for high torque cars, verify Panda safety mode flag is set + fingerprint = gen_empty_fingerprint() + for car_model in CAR: + CP = CarInterface.get_params(car_model, fingerprint, [], False, False) + assert bool(CP.flags & HyundaiFlags.ALT_LIMITS) == bool(CP.safetyConfigs[-1].safetyParam & Panda.FLAG_HYUNDAI_ALT_LIMITS) + def test_can_features(self): # Test no EV/HEV in any gear lists (should all use ELECT_GEAR) assert set.union(*CAN_GEARS.values()) & (HYBRID_CAR | EV_CAR) == set() @@ -58,7 +87,7 @@ def test_canfd_ecu_whitelist(self): for car_model in CANFD_CAR: ecus = {fw[0] for fw in FW_VERSIONS[car_model].keys()} ecus_not_in_whitelist = ecus - CANFD_EXPECTED_ECUS - ecu_strings = ", ".join([f"Ecu.{ECU_NAME[ecu]}" for ecu in ecus_not_in_whitelist]) + ecu_strings = ", ".join([f"Ecu.{ecu}" for ecu in ecus_not_in_whitelist]) assert len(ecus_not_in_whitelist) == 0, \ f"{car_model}: Car model has unexpected ECUs: {ecu_strings}" @@ -205,10 +234,10 @@ def test_fuzzy_excluded_platforms(self): for ecu, fw_versions in fw_by_addr.items(): ecu_name, addr, sub_addr = ecu for fw in fw_versions: - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) + car_fw.append(CarParams.CarFw(ecu=ecu_name, fwVersion=fw, address=addr, + subAddress=0 if sub_addr is None else sub_addr)) - CP = car.CarParams.new_message(carFw=car_fw) + CP = CarParams(carFw=car_fw) matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) if len(matches) == 1: assert list(matches)[0] == platform diff --git a/opendbc_repo/opendbc/car/hyundai/values.py b/opendbc_repo/opendbc/car/hyundai/values.py new file mode 100644 index 000000000000000..2eeb3376361f879 --- /dev/null +++ b/opendbc_repo/opendbc/car/hyundai/values.py @@ -0,0 +1,765 @@ +import re +from dataclasses import dataclass, field +from enum import Enum, IntFlag + +from panda import uds +from opendbc.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, p16 + +Ecu = CarParams.Ecu + + +class CarControllerParams: + ACCEL_MIN = -3.5 # m/s + ACCEL_MAX = 2.0 # m/s + + def __init__(self, CP): + self.STEER_DELTA_UP = 3 + self.STEER_DELTA_DOWN = 7 + self.STEER_DRIVER_ALLOWANCE = 50 + self.STEER_DRIVER_MULTIPLIER = 2 + self.STEER_DRIVER_FACTOR = 1 + self.STEER_THRESHOLD = 150 + self.STEER_STEP = 1 # 100 Hz + + if CP.flags & HyundaiFlags.CANFD: + self.STEER_MAX = 270 + self.STEER_DRIVER_ALLOWANCE = 250 + self.STEER_DRIVER_MULTIPLIER = 2 + self.STEER_THRESHOLD = 250 + self.STEER_DELTA_UP = 2 + self.STEER_DELTA_DOWN = 3 + + # To determine the limit for your car, find the maximum value that the stock LKAS will request. + # If the max stock LKAS request is <384, add your car to this list. + elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.HYUNDAI_ELANTRA, CAR.HYUNDAI_ELANTRA_GT_I30, CAR.HYUNDAI_IONIQ, + CAR.HYUNDAI_IONIQ_EV_LTD, CAR.HYUNDAI_SANTA_FE_PHEV_2022, CAR.HYUNDAI_SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV, + CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA_H_G4_FL, CAR.KIA_SORENTO): + self.STEER_MAX = 255 + + # these cars have significantly more torque than most HKG; limit to 70% of max + elif CP.flags & HyundaiFlags.ALT_LIMITS: + self.STEER_MAX = 270 + self.STEER_DELTA_UP = 2 + self.STEER_DELTA_DOWN = 3 + + # Default for most HKG + else: + self.STEER_MAX = 384 + + +class HyundaiFlags(IntFlag): + # Dynamic Flags + CANFD_HDA2 = 1 + CANFD_ALT_BUTTONS = 2 + CANFD_ALT_GEARS = 2 ** 2 + CANFD_CAMERA_SCC = 2 ** 3 + + ALT_LIMITS = 2 ** 4 + ENABLE_BLINKERS = 2 ** 5 + CANFD_ALT_GEARS_2 = 2 ** 6 + SEND_LFA = 2 ** 7 + USE_FCA = 2 ** 8 + CANFD_HDA2_ALT_STEERING = 2 ** 9 + + # these cars use a different gas signal + HYBRID = 2 ** 10 + EV = 2 ** 11 + + # Static flags + + # If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points. + # If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py + MANDO_RADAR = 2 ** 12 + CANFD = 2 ** 13 + + # The radar does SCC on these cars when HDA I, rather than the camera + RADAR_SCC = 2 ** 14 + # The camera does SCC on these cars, rather than the radar + CAMERA_SCC = 2 ** 15 + CHECKSUM_CRC8 = 2 ** 16 + CHECKSUM_6B = 2 ** 17 + + # these cars require a special panda safety mode due to missing counters and checksums in the messages + LEGACY = 2 ** 18 + + # these cars have not been verified to work with longitudinal yet - radar disable, sending correct messages, etc. + UNSUPPORTED_LONGITUDINAL = 2 ** 19 + + # These CAN FD cars do not accept communication control to disable the ADAS ECU, + # responds with 0x7F2822 - 'conditions not correct' + CANFD_NO_RADAR_DISABLE = 2 ** 20 + + CLUSTER_GEARS = 2 ** 21 + TCU_GEARS = 2 ** 22 + + MIN_STEER_32_MPH = 2 ** 23 + + +class Footnote(Enum): + CANFD = CarFootnote( + "Requires a CAN FD panda kit if not using " + + "comma 3X for this CAN FD car.", + Column.MODEL, shop_footnote=False) + + +@dataclass +class HyundaiCarDocs(CarDocs): + package: str = "Smart Cruise Control (SCC)" + + def init_make(self, CP: CarParams): + if CP.flags & HyundaiFlags.CANFD: + self.footnotes.insert(0, Footnote.CANFD) + + +@dataclass +class HyundaiPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_kia_generic", None)) + + def init(self): + if self.flags & HyundaiFlags.MANDO_RADAR: + self.dbc_dict = dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated') + + if self.flags & HyundaiFlags.MIN_STEER_32_MPH: + self.specs = self.specs.override(minSteerSpeed=32 * CV.MPH_TO_MS) + + +@dataclass +class HyundaiCanFDPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_canfd", None)) + + def init(self): + self.flags |= HyundaiFlags.CANFD + + +class CAR(Platforms): + # Hyundai + HYUNDAI_AZERA_6TH_GEN = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Azera 2022", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=1600, wheelbase=2.885, steerRatio=14.5), + ) + HYUNDAI_AZERA_HEV_6TH_GEN = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Hyundai Azera Hybrid 2019", "All", car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Hyundai Azera Hybrid 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), + ], + CarSpecs(mass=1675, wheelbase=2.885, steerRatio=14.5), + flags=HyundaiFlags.HYBRID, + ) + HYUNDAI_ELANTRA = HyundaiPlatformConfig( + [ + # TODO: 2017-18 could be Hyundai G + HyundaiCarDocs("Hyundai Elantra 2017-18", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b])), + HyundaiCarDocs("Hyundai Elantra 2019", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), + ], + # steerRatio: 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535, stiffnessFactor settled on 1.0081302973865127 + CarSpecs(mass=1275, wheelbase=2.7, steerRatio=15.4, tireStiffnessFactor=0.385), + flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_ELANTRA_GT_I30 = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Hyundai Elantra GT 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), + HyundaiCarDocs("Hyundai i30 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), + ], + HYUNDAI_ELANTRA.specs, + flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_ELANTRA_2021 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Elantra 2021-23", video_link="https://youtu.be/_EdYQtV52-c", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=2800 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_ELANTRA_HEV_2021 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", + car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=3017 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), + flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + HYUNDAI_GENESIS = HyundaiPlatformConfig( + [ + # TODO: check 2015 packages + HyundaiCarDocs("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), + HyundaiCarDocs("Genesis G80 2017", "All", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), + ], + CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5, minSteerSpeed=60 * CV.KPH_TO_MS), + flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.LEGACY, + ) + HYUNDAI_IONIQ = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Hybrid 2017-19", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_IONIQ_HEV_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_h]))], # TODO: confirm 2020-21 harness, + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, + ) + HYUNDAI_IONIQ_EV_LTD = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Electric 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV | HyundaiFlags.LEGACY | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_IONIQ_EV_2020 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Electric 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.EV, + ) + HYUNDAI_IONIQ_PHEV_2019 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_IONIQ_PHEV = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID, + ) + HYUNDAI_KONA = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Kona 2020", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b]))], + CarSpecs(mass=1275, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), + flags=HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.ALT_LIMITS, + ) + HYUNDAI_KONA_EV = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Kona Electric 2018-21", car_parts=CarParts.common([CarHarness.hyundai_g]))], + CarSpecs(mass=1685, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), + flags=HyundaiFlags.EV | HyundaiFlags.ALT_LIMITS, + ) + HYUNDAI_KONA_EV_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Kona Electric 2022-23", car_parts=CarParts.common([CarHarness.hyundai_o]))], + CarSpecs(mass=1743, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), + flags=HyundaiFlags.CAMERA_SCC | HyundaiFlags.EV | HyundaiFlags.ALT_LIMITS, + ) + HYUNDAI_KONA_EV_2ND_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Hyundai Kona Electric (with HDA II, Korea only) 2023", video_link="https://www.youtube.com/watch?v=U2fOCmcQ8hw", + car_parts=CarParts.common([CarHarness.hyundai_r]))], + CarSpecs(mass=1740, wheelbase=2.66, steerRatio=13.6, tireStiffnessFactor=0.385), + flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, + ) + HYUNDAI_KONA_HEV = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Kona Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_i]))], # TODO: check packages, + CarSpecs(mass=1425, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID | HyundaiFlags.ALT_LIMITS, + ) + HYUNDAI_SANTA_FE = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Fe 2019-20", "All", video_link="https://youtu.be/bjDR0YjM__s", + car_parts=CarParts.common([CarHarness.hyundai_d]))], + CarSpecs(mass=3982 * CV.LB_TO_KG, wheelbase=2.766, steerRatio=16.55, tireStiffnessFactor=0.82), + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_SANTA_FE_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Fe 2021-23", "All", video_link="https://youtu.be/VnHzSTygTS4", + car_parts=CarParts.common([CarHarness.hyundai_l]))], + HYUNDAI_SANTA_FE.specs, + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_SANTA_FE_HEV_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Fe Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], + HYUNDAI_SANTA_FE.specs, + flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + HYUNDAI_SANTA_FE_PHEV_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Fe Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], + HYUNDAI_SANTA_FE.specs, + flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + HYUNDAI_SONATA = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Sonata 2020-23", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", + car_parts=CarParts.common([CarHarness.hyundai_a]))], + CarSpecs(mass=1513, wheelbase=2.84, steerRatio=13.27 * 1.15, tireStiffnessFactor=0.65), # 15% higher at the center seems reasonable + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_SONATA_LF = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Sonata 2018-19", car_parts=CarParts.common([CarHarness.hyundai_e]))], + CarSpecs(mass=1536, wheelbase=2.804, steerRatio=13.27 * 1.15), # 15% higher at the center seems reasonable + + flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, + ) + HYUNDAI_STARIA_4TH_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Hyundai Staria 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=2205, wheelbase=3.273, steerRatio=11.94), # https://www.hyundai.com/content/dam/hyundai/au/en/models/staria-load/premium-pip-update-2023/spec-sheet/STARIA_Load_Spec-Table_March_2023_v3.1.pdf + ) + HYUNDAI_TUCSON = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_l])), + HyundaiCarDocs("Hyundai Tucson Diesel 2019", car_parts=CarParts.common([CarHarness.hyundai_l])), + ], + CarSpecs(mass=3520 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=16.1, tireStiffnessFactor=0.385), + flags=HyundaiFlags.TCU_GEARS, + ) + HYUNDAI_PALISADE = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Hyundai Palisade 2020-22", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456", car_parts=CarParts.common([CarHarness.hyundai_h])), + HyundaiCarDocs("Kia Telluride 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h])), + ], + CarSpecs(mass=1999, wheelbase=2.9, steerRatio=15.6 * 1.15, tireStiffnessFactor=0.63), + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_VELOSTER = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_e]))], + CarSpecs(mass=2917 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75 * 1.15, tireStiffnessFactor=0.5), + flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS, + ) + HYUNDAI_SONATA_HYBRID = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Sonata Hybrid 2020-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], + HYUNDAI_SONATA.specs, + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + HYUNDAI_IONIQ_5 = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Hyundai Ioniq 5 (Non-US only) 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_q])), + HyundaiCarDocs("Hyundai Ioniq 5 (without HDA II) 2022-24", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_k])), + HyundaiCarDocs("Hyundai Ioniq 5 (with HDA II) 2022-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q])), + ], + CarSpecs(mass=1948, wheelbase=2.97, steerRatio=14.26, tireStiffnessFactor=0.65), + flags=HyundaiFlags.EV, + ) + HYUNDAI_IONIQ_6 = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq 6 (with HDA II) 2023-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p]))], + HYUNDAI_IONIQ_5.specs, + flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, + ) + HYUNDAI_TUCSON_4TH_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Hyundai Tucson 2022", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarDocs("Hyundai Tucson 2023-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarDocs("Hyundai Tucson Hybrid 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarDocs("Hyundai Tucson Plug-in Hybrid 2024", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), + ], + CarSpecs(mass=1630, wheelbase=2.756, steerRatio=13.7, tireStiffnessFactor=0.385), + ) + HYUNDAI_SANTA_CRUZ_1ST_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Cruz 2022-24", car_parts=CarParts.common([CarHarness.hyundai_n]))], + # weight from Limited trim - the only supported trim, steering ratio according to Hyundai News https://www.hyundainews.com/assets/documents/original/48035-2022SantaCruzProductGuideSpecsv2081521.pdf + CarSpecs(mass=1870, wheelbase=3, steerRatio=14.2), + ) + HYUNDAI_CUSTIN_1ST_GEN = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Custin 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=1690, wheelbase=3.055, steerRatio=17), # mass: from https://www.hyundai-motor.com.tw/clicktobuy/custin#spec_0, steerRatio: from learner + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + + # Kia + KIA_FORTE = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Forte 2019-21", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), + HyundaiCarDocs("Kia Forte 2022-23", car_parts=CarParts.common([CarHarness.hyundai_e])), + ], + CarSpecs(mass=2878 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5) + ) + KIA_K5_2021 = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia K5 2021-24", car_parts=CarParts.common([CarHarness.hyundai_a]))], + CarSpecs(mass=3381 * CV.LB_TO_KG, wheelbase=2.85, steerRatio=13.27, tireStiffnessFactor=0.5), # 2021 Kia K5 Steering Ratio (all trims) + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + KIA_K5_HEV_2020 = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia K5 Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_a]))], + KIA_K5_2021.specs, + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + KIA_K8_HEV_1ST_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Kia K8 Hybrid (with HDA II) 2023", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q]))], + # mass: https://carprices.ae/brands/kia/2023/k8/1.6-turbo-hybrid, steerRatio: guesstimate from K5 platform + CarSpecs(mass=1630, wheelbase=2.895, steerRatio=13.27) + ) + KIA_NIRO_EV = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), + HyundaiCarDocs("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_f])), + HyundaiCarDocs("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), + ], + CarSpecs(mass=3543 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=13.6, tireStiffnessFactor=0.385), # average of all the cars + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV, + ) + KIA_NIRO_EV_2ND_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Kia Niro EV 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], + KIA_NIRO_EV.specs, + flags=HyundaiFlags.EV, + ) + KIA_NIRO_PHEV = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Niro Hybrid 2018", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Kia Niro Plug-in Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_d])), + ], + KIA_NIRO_EV.specs, + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.MIN_STEER_32_MPH, + ) + KIA_NIRO_PHEV_2022 = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Niro Plug-in Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), + HyundaiCarDocs("Kia Niro Plug-in Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), + ], + KIA_NIRO_EV.specs, + flags=HyundaiFlags.HYBRID | HyundaiFlags.MANDO_RADAR, + ) + KIA_NIRO_HEV_2021 = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Niro Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), + HyundaiCarDocs("Kia Niro Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), + ], + KIA_NIRO_EV.specs, + flags=HyundaiFlags.HYBRID, + ) + KIA_NIRO_HEV_2ND_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Kia Niro Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_a]))], + KIA_NIRO_EV.specs, + ) + KIA_OPTIMA_G4 = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Optima 2017", "Advanced Smart Cruise Control", + car_parts=CarParts.common([CarHarness.hyundai_b]))], # TODO: may support 2016, 2018 + CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS | HyundaiFlags.MIN_STEER_32_MPH, + ) + KIA_OPTIMA_G4_FL = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Optima 2019-20", car_parts=CarParts.common([CarHarness.hyundai_g]))], + CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, + ) + # TODO: may support adjacent years. may have a non-zero minimum steering speed + KIA_OPTIMA_H = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, + ) + KIA_OPTIMA_H_G4_FL = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Optima Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_h]))], + CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, + ) + KIA_SELTOS = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Seltos 2021", car_parts=CarParts.common([CarHarness.hyundai_a]))], + CarSpecs(mass=1337, wheelbase=2.63, steerRatio=14.56), + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + KIA_SPORTAGE_5TH_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Kia Sportage 2023-24", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarDocs("Kia Sportage Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), + ], + # weight from SX and above trims, average of FWD and AWD version, steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sportage/2023/specifications + CarSpecs(mass=1725, wheelbase=2.756, steerRatio=13.6), + ) + KIA_SORENTO = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Sorento 2018", "Advanced Smart Cruise Control & LKAS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", + car_parts=CarParts.common([CarHarness.hyundai_e])), + HyundaiCarDocs("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), + ], + CarSpecs(mass=1985, wheelbase=2.78, steerRatio=14.4 * 1.1), # 10% higher at the center seems reasonable + flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, + ) + KIA_SORENTO_4TH_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Kia Sorento 2021-23", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=3957 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms + flags=HyundaiFlags.RADAR_SCC, + ) + KIA_SORENTO_HEV_4TH_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Kia Sorento Hybrid 2021-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarDocs("Kia Sorento Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + ], + CarSpecs(mass=4395 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms + flags=HyundaiFlags.RADAR_SCC, + ) + KIA_STINGER = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", + car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=1825, wheelbase=2.78, steerRatio=14.4 * 1.15) # 15% higher at the center seems reasonable + ) + KIA_STINGER_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Stinger 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], + KIA_STINGER.specs, + ) + KIA_CEED = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Ceed 2019", car_parts=CarParts.common([CarHarness.hyundai_e]))], + CarSpecs(mass=1450, wheelbase=2.65, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.LEGACY, + ) + KIA_EV6 = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Kia EV6 (Southeast Asia only) 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_p])), + HyundaiCarDocs("Kia EV6 (without HDA II) 2022-24", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_l])), + HyundaiCarDocs("Kia EV6 (with HDA II) 2022-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p])) + ], + CarSpecs(mass=2055, wheelbase=2.9, steerRatio=16, tireStiffnessFactor=0.65), + flags=HyundaiFlags.EV, + ) + KIA_CARNIVAL_4TH_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Kia Carnival 2022-24", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarDocs("Kia Carnival (China only) 2023", car_parts=CarParts.common([CarHarness.hyundai_k])) + ], + CarSpecs(mass=2087, wheelbase=3.09, steerRatio=14.23), + flags=HyundaiFlags.RADAR_SCC, + ) + + # Genesis + GENESIS_GV60_EV_1ST_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Genesis GV60 (Advanced Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarDocs("Genesis GV60 (Performance Trim) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), + ], + CarSpecs(mass=2205, wheelbase=2.9, steerRatio=17.6), + flags=HyundaiFlags.EV, + ) + GENESIS_G70 = HyundaiPlatformConfig( + [HyundaiCarDocs("Genesis G70 2018", "All", car_parts=CarParts.common([CarHarness.hyundai_f]))], + CarSpecs(mass=1640, wheelbase=2.84, steerRatio=13.56), + flags=HyundaiFlags.LEGACY, + ) + GENESIS_G70_2020 = HyundaiPlatformConfig( + [ + # TODO: 2021 MY harness is unknown + HyundaiCarDocs("Genesis G70 2019-21", "All", car_parts=CarParts.common([CarHarness.hyundai_f])), + # TODO: From 3.3T Sport Advanced 2022 & Prestige 2023 Trim, 2.0T is unknown + HyundaiCarDocs("Genesis G70 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), + ], + GENESIS_G70.specs, + flags=HyundaiFlags.MANDO_RADAR, + ) + GENESIS_GV70_1ST_GEN = HyundaiCanFDPlatformConfig( + [ + # TODO: Hyundai P is likely the correct harness for HDA II for 2.5T (unsupported due to missing ADAS ECU, is that the radar?) + HyundaiCarDocs("Genesis GV70 (2.5T Trim, without HDA II) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), + HyundaiCarDocs("Genesis GV70 (3.5T Trim, without HDA II) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_m])), + ], + CarSpecs(mass=1950, wheelbase=2.87, steerRatio=14.6), + flags=HyundaiFlags.RADAR_SCC, + ) + GENESIS_GV70_ELECTRIFIED_1ST_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Genesis GV70 Electrified (with HDA II) 2023", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q])), + ], + CarSpecs(mass=2260, wheelbase=2.87, steerRatio=17.1), + flags=HyundaiFlags.EV, + ) + GENESIS_G80 = HyundaiPlatformConfig( + [HyundaiCarDocs("Genesis G80 2018-19", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], + CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5), + flags=HyundaiFlags.LEGACY, + ) + GENESIS_G80_2ND_GEN_FL = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Genesis G80 (2.5T Advanced Trim, with HDA II) 2024", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p]))], + CarSpecs(mass=2060, wheelbase=3.00, steerRatio=14.0), + ) + GENESIS_G90 = HyundaiPlatformConfig( + [HyundaiCarDocs("Genesis G90 2017-20", "All", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=2200, wheelbase=3.15, steerRatio=12.069), + ) + GENESIS_GV80 = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Genesis GV80 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_m]))], + CarSpecs(mass=2258, wheelbase=2.95, steerRatio=14.14), + flags=HyundaiFlags.RADAR_SCC, + ) + + +class Buttons: + NONE = 0 + RES_ACCEL = 1 + SET_DECEL = 2 + GAP_DIST = 3 + CANCEL = 4 # on newer models, this is a pause/resume button + + +def get_platform_codes(fw_versions: list[bytes]) -> set[tuple[bytes, bytes | None]]: + # Returns unique, platform-specific identification codes for a set of versions + codes = set() # (code-Optional[part], date) + for fw in fw_versions: + code_match = PLATFORM_CODE_FW_PATTERN.search(fw) + part_match = PART_NUMBER_FW_PATTERN.search(fw) + date_match = DATE_FW_PATTERN.search(fw) + if code_match is not None: + code: bytes = code_match.group() + part = part_match.group() if part_match else None + date = date_match.group() if date_match else None + if part is not None: + # part number starts with generic ECU part type, add what is specific to platform + code += b"-" + part[-5:] + + codes.add((code, date)) + return codes + + +def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: + # Non-electric CAN FD platforms often do not have platform code specifiers needed + # to distinguish between hybrid and ICE. All EVs so far are either exclusively + # electric or specify electric in the platform code. + fuzzy_platform_blacklist = {str(c) for c in (CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST)} + candidates: set[str] = set() + + for candidate, fws in offline_fw_versions.items(): + # Keep track of ECUs which pass all checks (platform codes, within date range) + valid_found_ecus = set() + valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} + for ecu, expected_versions in fws.items(): + addr = ecu[1:] + # Only check ECUs expected to have platform codes + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + # Expected platform codes & dates + codes = get_platform_codes(expected_versions) + expected_platform_codes = {code for code, _ in codes} + expected_dates = {date for _, date in codes if date is not None} + + # Found platform codes & dates + codes = get_platform_codes(live_fw_versions.get(addr, set())) + found_platform_codes = {code for code, _ in codes} + found_dates = {date for _, date in codes if date is not None} + + # Check platform code + part number matches for any found versions + if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): + break + + if ecu[0] in DATE_FW_ECUS: + # If ECU can have a FW date, require it to exist + # (this excludes candidates in the database without dates) + if not len(expected_dates) or not len(found_dates): + break + + # Check any date within range in the database, format is %y%m%d + if not any(min(expected_dates) <= found_date <= max(expected_dates) for found_date in found_dates): + break + + valid_found_ecus.add(addr) + + # If all live ECUs pass all checks for candidate, add it as a match + if valid_expected_ecus.issubset(valid_found_ecus): + candidates.add(candidate) + + return candidates - fuzzy_platform_blacklist + + +HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf100) # Long description + +HYUNDAI_VERSION_REQUEST_ALT = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf110) # Alt long description + +HYUNDAI_ECU_MANUFACTURING_DATE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.ECU_MANUFACTURING_DATE) + +HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + +# Regex patterns for parsing platform code, FW date, and part number from FW versions +PLATFORM_CODE_FW_PATTERN = re.compile(b'((?<=' + HYUNDAI_VERSION_REQUEST_LONG[1:] + + b')[A-Z]{2}[A-Za-z0-9]{0,2})') +DATE_FW_PATTERN = re.compile(b'(?<=[ -])([0-9]{6}$)') +PART_NUMBER_FW_PATTERN = re.compile(b'(?<=[0-9][.,][0-9]{2} )([0-9]{5}[-/]?[A-Z][A-Z0-9]{3}[0-9])') + +# We've seen both ICE and hybrid for these platforms, and they have hybrid descriptors (e.g. MQ4 vs MQ4H) +CANFD_FUZZY_WHITELIST = {CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KIA_K8_HEV_1ST_GEN, + # TODO: the hybrid variant is not out yet + CAR.KIA_CARNIVAL_4TH_GEN} + +# List of ECUs expected to have platform codes, camera and radar should exist on all cars +# TODO: use abs, it has the platform code and part number on many platforms +PLATFORM_CODE_ECUS = [Ecu.fwdRadar, Ecu.fwdCamera, Ecu.eps] +# So far we've only seen dates in fwdCamera +# TODO: there are date codes in the ABS firmware versions in hex +DATE_FW_ECUS = [Ecu.fwdCamera] + +# Note: an ECU on CAN FD cars may sometimes send 0x30080aaaaaaaaaaa (flow control continue) while we +# are attempting to query ECUs. This currently does not seem to affect fingerprinting from the camera +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + # TODO: add back whitelists + # CAN queries (OBD-II port) + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + ), + + # CAN & CAN-FD queries (from camera) + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + bus=0, + auxiliary=True, + ), + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + bus=1, + auxiliary=True, + obd_multiplexing=False, + ), + + # CAN & CAN FD query to understand the three digit date code + # HDA2 cars usually use 6 digit date codes, so skip bus 1 + Request( + [HYUNDAI_ECU_MANUFACTURING_DATE], + [HYUNDAI_VERSION_RESPONSE], + bus=0, + auxiliary=True, + logging=True, + ), + + # CAN-FD alt request logging queries for hvac and parkingAdas + Request( + [HYUNDAI_VERSION_REQUEST_ALT], + [HYUNDAI_VERSION_RESPONSE], + bus=0, + auxiliary=True, + logging=True, + ), + Request( + [HYUNDAI_VERSION_REQUEST_ALT], + [HYUNDAI_VERSION_RESPONSE], + bus=1, + auxiliary=True, + logging=True, + obd_multiplexing=False, + ), + ], + # We lose these ECUs without the comma power on these cars. + # Note that we still attempt to match with them when they are present + non_essential_ecus={ + Ecu.abs: [CAR.HYUNDAI_PALISADE, CAR.HYUNDAI_SONATA, CAR.HYUNDAI_SANTA_FE_2022, CAR.KIA_K5_2021, CAR.HYUNDAI_ELANTRA_2021, + CAR.HYUNDAI_SANTA_FE, CAR.HYUNDAI_KONA_EV_2022, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_CUSTIN_1ST_GEN, CAR.KIA_SORENTO, + CAR.KIA_CEED, CAR.KIA_SELTOS], + }, + extra_ecus=[ + (Ecu.adas, 0x730, None), # ADAS Driving ECU on HDA2 platforms + (Ecu.parkingAdas, 0x7b1, None), # ADAS Parking ECU (may exist on all platforms) + (Ecu.hvac, 0x7b3, None), # HVAC Control Assembly + (Ecu.cornerRadar, 0x7b7, None), + (Ecu.combinationMeter, 0x7c6, None), # CAN FD Instrument cluster + ], + # Custom fuzzy fingerprinting function using platform codes, part numbers + FW dates: + match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, +) + +CHECKSUM = { + "crc8": CAR.with_flags(HyundaiFlags.CHECKSUM_CRC8), + "6B": CAR.with_flags(HyundaiFlags.CHECKSUM_6B), +} + +CAN_GEARS = { + # which message has the gear. hybrid and EV use ELECT_GEAR + "use_cluster_gears": CAR.with_flags(HyundaiFlags.CLUSTER_GEARS), + "use_tcu_gears": CAR.with_flags(HyundaiFlags.TCU_GEARS), +} + +CANFD_CAR = CAR.with_flags(HyundaiFlags.CANFD) +CANFD_RADAR_SCC_CAR = CAR.with_flags(HyundaiFlags.RADAR_SCC) # TODO: merge with UNSUPPORTED_LONGITUDINAL_CAR + +CANFD_UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.CANFD_NO_RADAR_DISABLE) # TODO: merge with UNSUPPORTED_LONGITUDINAL_CAR + +CAMERA_SCC_CAR = CAR.with_flags(HyundaiFlags.CAMERA_SCC) + +HYBRID_CAR = CAR.with_flags(HyundaiFlags.HYBRID) + +EV_CAR = CAR.with_flags(HyundaiFlags.EV) + +LEGACY_SAFETY_MODE_CAR = CAR.with_flags(HyundaiFlags.LEGACY) + +# TODO: another PR with (HyundaiFlags.LEGACY | HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.CAMERA_SCC | +# HyundaiFlags.CANFD_RADAR_SCC | HyundaiFlags.CANFD_NO_RADAR_DISABLE | ) +UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.LEGACY) | CAR.with_flags(HyundaiFlags.UNSUPPORTED_LONGITUDINAL) + +DBC = CAR.create_dbc_map() diff --git a/opendbc_repo/opendbc/car/include/c++.capnp b/opendbc_repo/opendbc/car/include/c++.capnp new file mode 100644 index 000000000000000..2bda54717920ab9 --- /dev/null +++ b/opendbc_repo/opendbc/car/include/c++.capnp @@ -0,0 +1,26 @@ +# Copyright (c) 2013-2014 Sandstorm Development Group, Inc. and contributors +# Licensed under the MIT License: +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +@0xbdf87d7bb8304e81; +$namespace("capnp::annotations"); + +annotation namespace(file): Text; +annotation name(field, enumerant, struct, enum, interface, method, param, group, union): Text; diff --git a/opendbc_repo/opendbc/car/interfaces.py b/opendbc_repo/opendbc/car/interfaces.py new file mode 100644 index 000000000000000..f5644a5cff9facc --- /dev/null +++ b/opendbc_repo/opendbc/car/interfaces.py @@ -0,0 +1,453 @@ +import json +import os +import numpy as np +import time +import tomllib +from abc import abstractmethod, ABC +from enum import StrEnum +from typing import Any, NamedTuple +from collections.abc import Callable +from functools import cache + +from opendbc.car import DT_CTRL, apply_hysteresis, gen_empty_fingerprint, scale_rot_inertia, scale_tire_stiffness, get_friction, STD_CARGO_KG +from opendbc.car import structs +from opendbc.car.can_definitions import CanData, CanRecvCallable, CanSendCallable +from opendbc.car.common.basedir import BASEDIR +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.common.simple_kalman import KF1D, get_kalman_gain +from opendbc.car.common.numpy_fast import clip +from opendbc.car.values import PLATFORMS + +GearShifter = structs.CarState.GearShifter + +V_CRUISE_MAX = 145 +MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS +ACCEL_MAX = 2.0 +ACCEL_MIN = -3.5 +FRICTION_THRESHOLD = 0.3 + +TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'torque_data/params.toml') +TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'torque_data/override.toml') +TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'torque_data/substitute.toml') + +GEAR_SHIFTER_MAP: dict[str, structs.CarState.GearShifter] = { + 'P': GearShifter.park, 'PARK': GearShifter.park, + 'R': GearShifter.reverse, 'REVERSE': GearShifter.reverse, + 'N': GearShifter.neutral, 'NEUTRAL': GearShifter.neutral, + 'E': GearShifter.eco, 'ECO': GearShifter.eco, + 'T': GearShifter.manumatic, 'MANUAL': GearShifter.manumatic, + 'D': GearShifter.drive, 'DRIVE': GearShifter.drive, + 'S': GearShifter.sport, 'SPORT': GearShifter.sport, + 'L': GearShifter.low, 'LOW': GearShifter.low, + 'B': GearShifter.brake, 'BRAKE': GearShifter.brake, +} + + +class LatControlInputs(NamedTuple): + lateral_acceleration: float + roll_compensation: float + vego: float + aego: float + + +TorqueFromLateralAccelCallbackType = Callable[[LatControlInputs, structs.CarParams.LateralTorqueTuning, float, float, bool, bool], float] + + +@cache +def get_torque_params(): + with open(TORQUE_SUBSTITUTE_PATH, 'rb') as f: + sub = tomllib.load(f) + with open(TORQUE_PARAMS_PATH, 'rb') as f: + params = tomllib.load(f) + with open(TORQUE_OVERRIDE_PATH, 'rb') as f: + override = tomllib.load(f) + + torque_params = {} + for candidate in (sub.keys() | params.keys() | override.keys()) - {'legend'}: + if sum([candidate in x for x in [sub, params, override]]) > 1: + raise RuntimeError(f'{candidate} is defined twice in torque config') + + sub_candidate = sub.get(candidate, candidate) + + if sub_candidate in override: + out = override[sub_candidate] + elif sub_candidate in params: + out = params[sub_candidate] + else: + raise NotImplementedError(f"Did not find torque params for {sub_candidate}") + + torque_params[sub_candidate] = {key: out[i] for i, key in enumerate(params['legend'])} + if candidate in sub: + torque_params[candidate] = torque_params[sub_candidate] + + return torque_params + +# generic car and radar interfaces + +class CarInterfaceBase(ABC): + def __init__(self, CP: structs.CarParams, CarController, CarState): + self.CP = CP + + self.frame = 0 + self.v_ego_cluster_seen = False + + self.CS: CarStateBase = CarState(CP) + self.cp = self.CS.get_can_parser(CP) + self.cp_cam = self.CS.get_cam_can_parser(CP) + self.cp_adas = self.CS.get_adas_can_parser(CP) + self.cp_body = self.CS.get_body_can_parser(CP) + self.cp_loopback = self.CS.get_loopback_can_parser(CP) + self.can_parsers = (self.cp, self.cp_cam, self.cp_adas, self.cp_body, self.cp_loopback) + + dbc_name = "" if self.cp is None else self.cp.dbc_name + self.CC: CarControllerBase = CarController(dbc_name, CP) + + def apply(self, c: structs.CarControl, now_nanos: int | None = None) -> tuple[structs.CarControl.Actuators, list[CanData]]: + if now_nanos is None: + now_nanos = int(time.monotonic() * 1e9) + return self.CC.update(c, self.CS, now_nanos) + + @staticmethod + def get_pid_accel_limits(CP, current_speed, cruise_speed): + return ACCEL_MIN, ACCEL_MAX + + @classmethod + def get_non_essential_params(cls, candidate: str) -> structs.CarParams: + """ + Parameters essential to controlling the car may be incomplete or wrong without FW versions or fingerprints. + """ + return cls.get_params(candidate, gen_empty_fingerprint(), list(), False, False) + + @classmethod + def get_params(cls, candidate: str, fingerprint: dict[int, dict[int, int]], car_fw: list[structs.CarParams.CarFw], + experimental_long: bool, docs: bool) -> structs.CarParams: + ret = CarInterfaceBase.get_std_params(candidate) + + platform = PLATFORMS[candidate] + ret.mass = platform.config.specs.mass + ret.wheelbase = platform.config.specs.wheelbase + ret.steerRatio = platform.config.specs.steerRatio + ret.centerToFront = ret.wheelbase * platform.config.specs.centerToFrontRatio + ret.minEnableSpeed = platform.config.specs.minEnableSpeed + ret.minSteerSpeed = platform.config.specs.minSteerSpeed + ret.tireStiffnessFactor = platform.config.specs.tireStiffnessFactor + ret.flags |= int(platform.config.flags) + + ret = cls._get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs) + + # Vehicle mass is published curb weight plus assumed payload such as a human driver; notCars have no assumed payload + if not ret.notCar: + ret.mass = ret.mass + STD_CARGO_KG + + # Set params dependent on values set by the car interface + ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) + ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, ret.tireStiffnessFactor) + + return ret + + @staticmethod + @abstractmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint: dict[int, dict[int, int]], + car_fw: list[structs.CarParams.CarFw], experimental_long: bool, docs: bool) -> structs.CarParams: + raise NotImplementedError + + @staticmethod + def init(CP: structs.CarParams, can_recv: CanRecvCallable, can_send: CanSendCallable): + pass + + @staticmethod + def get_steer_feedforward_default(desired_angle, v_ego): + # Proportional to realigning tire momentum: lateral acceleration. + return desired_angle * (v_ego**2) + + def get_steer_feedforward_function(self): + return self.get_steer_feedforward_default + + def torque_from_lateral_accel_linear(self, latcontrol_inputs: LatControlInputs, torque_params: structs.CarParams.LateralTorqueTuning, + lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: + # The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction) + friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) + return (latcontrol_inputs.lateral_acceleration / float(torque_params.latAccelFactor)) + friction + + def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: + return self.torque_from_lateral_accel_linear + + # returns a set of default params to avoid repetition in car specific params + @staticmethod + def get_std_params(candidate: str) -> structs.CarParams: + ret = structs.CarParams() + ret.carFingerprint = candidate + + # Car docs fields + ret.maxLateralAccel = get_torque_params()[candidate]['MAX_LAT_ACCEL_MEASURED'] + ret.autoResumeSng = True # describes whether car can resume from a stop automatically + + # standard ALC params + ret.tireStiffnessFactor = 1.0 + ret.steerControlType = structs.CarParams.SteerControlType.torque + ret.minSteerSpeed = 0. + ret.wheelSpeedFactor = 1.0 + + ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars + ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this + ret.steerRatioRear = 0. # no rear steering, at least on the listed cars aboveA + ret.openpilotLongitudinalControl = False + ret.stopAccel = -2.0 + ret.stoppingDecelRate = 0.8 # brake_travel/s while trying to stop + ret.vEgoStopping = 0.5 + ret.vEgoStarting = 0.5 + ret.longitudinalTuning.kf = 1. + ret.longitudinalTuning.kpBP = [0.] + ret.longitudinalTuning.kpV = [0.] + ret.longitudinalTuning.kiBP = [0.] + ret.longitudinalTuning.kiV = [0.] + # TODO estimate car specific lag, use .15s for now + ret.longitudinalActuatorDelay = 0.15 + ret.steerLimitTimer = 1.0 + return ret + + @staticmethod + def configure_torque_tune(candidate: str, tune: structs.CarParams.LateralTuning, steering_angle_deadzone_deg: float = 0.0, use_steering_angle: bool = True): + params = get_torque_params()[candidate] + + tune.init('torque') + tune.torque.useSteeringAngle = use_steering_angle + tune.torque.kp = 1.0 + tune.torque.kf = 1.0 + tune.torque.ki = 0.1 + tune.torque.friction = params['FRICTION'] + tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR'] + tune.torque.latAccelOffset = 0.0 + tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg + + def _update(self) -> structs.CarState: + return self.CS.update(*self.can_parsers) + + def update(self, can_packets: list[tuple[int, list[CanData]]]) -> structs.CarState: + # parse can + for cp in self.can_parsers: + if cp is not None: + cp.update_strings(can_packets) + + # get CarState + ret = self._update() + + ret.canValid = all(cp.can_valid for cp in self.can_parsers if cp is not None) + ret.canTimeout = any(cp.bus_timeout for cp in self.can_parsers if cp is not None) + + if ret.vEgoCluster == 0.0 and not self.v_ego_cluster_seen: + ret.vEgoCluster = ret.vEgo + else: + self.v_ego_cluster_seen = True + + # Many cars apply hysteresis to the ego dash speed + ret.vEgoCluster = apply_hysteresis(ret.vEgoCluster, self.CS.out.vEgoCluster, self.CS.cluster_speed_hyst_gap) + if abs(ret.vEgo) < self.CS.cluster_min_speed: + ret.vEgoCluster = 0.0 + + if ret.cruiseState.speedCluster == 0: + ret.cruiseState.speedCluster = ret.cruiseState.speed + + # save for next iteration + self.CS.out = ret + + return ret + + +class RadarInterfaceBase(ABC): + def __init__(self, CP: structs.CarParams): + self.CP = CP + self.rcp = None + self.pts: dict[int, structs.RadarData.RadarPoint] = {} + self.frame = 0 + + def update(self, can_packets: list[tuple[int, list[CanData]]]) -> structs.RadarDataT | None: + self.frame += 1 + if (self.frame % 5) == 0: # 20 Hz is very standard + return structs.RadarData() + return None + + +class CarStateBase(ABC): + def __init__(self, CP: structs.CarParams): + self.CP = CP + self.car_fingerprint = CP.carFingerprint + self.out = structs.CarState() + + self.cruise_buttons = 0 + self.left_blinker_cnt = 0 + self.right_blinker_cnt = 0 + self.steering_pressed_cnt = 0 + self.left_blinker_prev = False + self.right_blinker_prev = False + self.cluster_speed_hyst_gap = 0.0 + self.cluster_min_speed = 0.0 # min speed before dropping to 0 + self.secoc_key: bytes = b"00" * 16 + + Q = [[0.0, 0.0], [0.0, 100.0]] + R = 0.3 + A = [[1.0, DT_CTRL], [0.0, 1.0]] + C = [[1.0, 0.0]] + x0=[[0.0], [0.0]] + K = get_kalman_gain(DT_CTRL, np.array(A), np.array(C), np.array(Q), R) + self.v_ego_kf = KF1D(x0=x0, A=A, C=C[0], K=K) + + @abstractmethod + def update(self, cp, cp_cam, cp_adas, cp_body, cp_loopback) -> structs.CarState: + pass + + def update_speed_kf(self, v_ego_raw): + if abs(v_ego_raw - self.v_ego_kf.x[0][0]) > 2.0: # Prevent large accelerations when car starts at non zero speed + self.v_ego_kf.set_x([[v_ego_raw], [0.0]]) + + v_ego_x = self.v_ego_kf.update(v_ego_raw) + return float(v_ego_x[0]), float(v_ego_x[1]) + + def get_wheel_speeds(self, fl, fr, rl, rr, unit=CV.KPH_TO_MS): + factor = unit * self.CP.wheelSpeedFactor + + wheelSpeeds = structs.CarState.WheelSpeeds() + wheelSpeeds.fl = fl * factor + wheelSpeeds.fr = fr * factor + wheelSpeeds.rl = rl * factor + wheelSpeeds.rr = rr * factor + return wheelSpeeds + + def update_blinker_from_lamp(self, blinker_time: int, left_blinker_lamp: bool, right_blinker_lamp: bool): + """Update blinkers from lights. Enable output when light was seen within the last `blinker_time` + iterations""" + # TODO: Handle case when switching direction. Now both blinkers can be on at the same time + self.left_blinker_cnt = blinker_time if left_blinker_lamp else max(self.left_blinker_cnt - 1, 0) + self.right_blinker_cnt = blinker_time if right_blinker_lamp else max(self.right_blinker_cnt - 1, 0) + return self.left_blinker_cnt > 0, self.right_blinker_cnt > 0 + + def update_steering_pressed(self, steering_pressed, steering_pressed_min_count): + """Applies filtering on steering pressed for noisy driver torque signals.""" + self.steering_pressed_cnt += 1 if steering_pressed else -1 + self.steering_pressed_cnt = clip(self.steering_pressed_cnt, 0, steering_pressed_min_count * 2) + return self.steering_pressed_cnt > steering_pressed_min_count + + def update_blinker_from_stalk(self, blinker_time: int, left_blinker_stalk: bool, right_blinker_stalk: bool): + """Update blinkers from stalk position. When stalk is seen the blinker will be on for at least blinker_time, + or until the stalk is turned off, whichever is longer. If the opposite stalk direction is seen the blinker + is forced to the other side. On a rising edge of the stalk the timeout is reset.""" + + if left_blinker_stalk: + self.right_blinker_cnt = 0 + if not self.left_blinker_prev: + self.left_blinker_cnt = blinker_time + + if right_blinker_stalk: + self.left_blinker_cnt = 0 + if not self.right_blinker_prev: + self.right_blinker_cnt = blinker_time + + self.left_blinker_cnt = max(self.left_blinker_cnt - 1, 0) + self.right_blinker_cnt = max(self.right_blinker_cnt - 1, 0) + + self.left_blinker_prev = left_blinker_stalk + self.right_blinker_prev = right_blinker_stalk + + return bool(left_blinker_stalk or self.left_blinker_cnt > 0), bool(right_blinker_stalk or self.right_blinker_cnt > 0) + + @staticmethod + def parse_gear_shifter(gear: str | None) -> structs.CarState.GearShifter: + if gear is None: + return GearShifter.unknown + return GEAR_SHIFTER_MAP.get(gear.upper(), GearShifter.unknown) + + @staticmethod + def get_can_parser(CP): + return None + + @staticmethod + def get_cam_can_parser(CP): + return None + + @staticmethod + def get_adas_can_parser(CP): + return None + + @staticmethod + def get_body_can_parser(CP): + return None + + @staticmethod + def get_loopback_can_parser(CP): + return None + + +class CarControllerBase(ABC): + def __init__(self, dbc_name: str, CP: structs.CarParams): + self.CP = CP + self.frame = 0 + self.secoc_key: bytes = b"00" * 16 + + @abstractmethod + def update(self, CC: structs.CarControl, CS: CarStateBase, now_nanos: int) -> tuple[structs.CarControl.Actuators, list[CanData]]: + pass + + +INTERFACE_ATTR_FILE = { + "FINGERPRINTS": "fingerprints", + "FW_VERSIONS": "fingerprints", +} + +# interface-specific helpers + +def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: bool = False) -> dict[str | StrEnum, Any]: + # read all the folders in opendbc/car and return a dict where: + # - keys are all the car models or brand names + # - values are attr values from all car folders + result = {} + for car_folder in sorted([x[0] for x in os.walk(BASEDIR)]): + try: + brand_name = car_folder.split('/')[-1] + brand_values = __import__(f'opendbc.car.{brand_name}.{INTERFACE_ATTR_FILE.get(attr, "values")}', fromlist=[attr]) + if hasattr(brand_values, attr) or not ignore_none: + attr_data = getattr(brand_values, attr, None) + else: + continue + + if combine_brands: + if isinstance(attr_data, dict): + for f, v in attr_data.items(): + result[f] = v + else: + result[brand_name] = attr_data + except (ImportError, OSError): + pass + + return result + + +class NanoFFModel: + def __init__(self, weights_loc: str, platform: str): + self.weights_loc = weights_loc + self.platform = platform + self.load_weights(platform) + + def load_weights(self, platform: str): + with open(self.weights_loc) as fob: + self.weights = {k: np.array(v) for k, v in json.load(fob)[platform].items()} + + def relu(self, x: np.ndarray): + return np.maximum(0.0, x) + + def forward(self, x: np.ndarray): + assert x.ndim == 1 + x = (x - self.weights['input_norm_mat'][:, 0]) / (self.weights['input_norm_mat'][:, 1] - self.weights['input_norm_mat'][:, 0]) + x = self.relu(np.dot(x, self.weights['w_1']) + self.weights['b_1']) + x = self.relu(np.dot(x, self.weights['w_2']) + self.weights['b_2']) + x = self.relu(np.dot(x, self.weights['w_3']) + self.weights['b_3']) + x = np.dot(x, self.weights['w_4']) + self.weights['b_4'] + return x + + def predict(self, x: list[float], do_sample: bool = False): + x = self.forward(np.array(x)) + if do_sample: + pred = np.random.laplace(x[0], np.exp(x[1]) / self.weights['temperature']) + else: + pred = x[0] + pred = pred * (self.weights['output_norm_mat'][1] - self.weights['output_norm_mat'][0]) + self.weights['output_norm_mat'][0] + return pred diff --git a/opendbc_repo/opendbc/car/isotp_parallel_query.py b/opendbc_repo/opendbc/car/isotp_parallel_query.py new file mode 100644 index 000000000000000..68f5b0ac27e5bee --- /dev/null +++ b/opendbc_repo/opendbc/car/isotp_parallel_query.py @@ -0,0 +1,172 @@ +import time +from collections import defaultdict +from functools import partial + +from opendbc.car import carlog +from opendbc.car.can_definitions import CanData, CanRecvCallable, CanSendCallable +from opendbc.car.fw_query_definitions import AddrType +from panda import uds + + +class IsoTpParallelQuery: + def __init__(self, can_send: CanSendCallable, can_recv: CanRecvCallable, bus: int, addrs: list[int] | list[AddrType], + request: list[bytes], response: list[bytes], response_offset: int = 0x8, + functional_addrs: list[int] = None, debug: bool = False, response_pending_timeout: float = 10) -> None: + self.can_send = can_send + self.can_recv = can_recv + self.bus = bus + self.request = request + self.response = response + self.functional_addrs = functional_addrs or [] + self.debug = debug + self.response_pending_timeout = response_pending_timeout + + real_addrs = [a if isinstance(a, tuple) else (a, None) for a in addrs] + for tx_addr, _ in real_addrs: + assert tx_addr not in uds.FUNCTIONAL_ADDRS, f"Functional address should be defined in functional_addrs: {hex(tx_addr)}" + + self.msg_addrs = {tx_addr: uds.get_rx_addr_for_tx_addr(tx_addr[0], rx_offset=response_offset) for tx_addr in real_addrs} + self.msg_buffer: dict[int, list[CanData]] = defaultdict(list) + + def rx(self) -> None: + """Drain can socket and sort messages into buffers based on address""" + can_packets = self.can_recv(wait_for_one=True) + + for packet in can_packets: + for msg in packet: + if msg.src == self.bus and msg.address in self.msg_addrs.values(): + self.msg_buffer[msg.address].append(CanData(msg.address, msg.dat, msg.src)) + + def _can_tx(self, tx_addr: int, dat: bytes, bus: int): + """Helper function to send single message""" + msg = CanData(tx_addr, dat, bus) + self.can_send([msg]) + + def _can_rx(self, addr, sub_addr=None): + """Helper function to retrieve message with specified address and subadress from buffer""" + keep_msgs = [] + + if sub_addr is None: + msgs = self.msg_buffer[addr] + else: + # Filter based on subadress + msgs = [] + for m in self.msg_buffer[addr]: + first_byte = m[1][0] + if first_byte == sub_addr: + msgs.append(m) + else: + keep_msgs.append(m) + + self.msg_buffer[addr] = keep_msgs + return msgs + + def _drain_rx(self) -> None: + self.can_recv() + self.msg_buffer = defaultdict(list) + + def _create_isotp_msg(self, tx_addr: int, sub_addr: int | None, rx_addr: int): + can_client = uds.CanClient(self._can_tx, partial(self._can_rx, rx_addr, sub_addr=sub_addr), tx_addr, rx_addr, + self.bus, sub_addr=sub_addr, debug=self.debug) + + max_len = 8 if sub_addr is None else 7 + # uses iso-tp frame separation time of 10 ms + # TODO: use single_frame_mode so ECUs can send as fast as they want, + # as well as reduces chances we process messages from previous queries + return uds.IsoTpMessage(can_client, timeout=0, separation_time=0.01, debug=self.debug, max_len=max_len) + + def get_data(self, timeout: float, total_timeout: float = 60.) -> dict[AddrType, bytes]: + self._drain_rx() + + # Create message objects + msgs = {} + request_counter = {} + request_done = {} + for tx_addr, rx_addr in self.msg_addrs.items(): + msgs[tx_addr] = self._create_isotp_msg(*tx_addr, rx_addr) + request_counter[tx_addr] = 0 + request_done[tx_addr] = False + + # Send first request to functional addrs, subsequent responses are handled on physical addrs + if len(self.functional_addrs): + for addr in self.functional_addrs: + self._create_isotp_msg(addr, None, -1).send(self.request[0]) + + # Send first frame (single or first) to all addresses and receive asynchronously in the loop below. + # If querying functional addrs, only set up physical IsoTpMessages to send consecutive frames + for msg in msgs.values(): + msg.send(self.request[0], setup_only=len(self.functional_addrs) > 0) + + results = {} + start_time = time.monotonic() + addrs_responded = set() # track addresses that have ever sent a valid iso-tp frame for timeout logging + response_timeouts = {tx_addr: start_time + timeout for tx_addr in self.msg_addrs} + while True: + self.rx() + + for tx_addr, msg in msgs.items(): + try: + dat, rx_in_progress = msg.recv() + except Exception: + carlog.exception(f"Error processing UDS response: {tx_addr}") + request_done[tx_addr] = True + continue + + # Extend timeout for each consecutive ISO-TP frame to avoid timing out on long responses + if rx_in_progress: + addrs_responded.add(tx_addr) + response_timeouts[tx_addr] = time.monotonic() + timeout + + if dat is None: + continue + + # Log unexpected empty responses + if len(dat) == 0: + carlog.error(f"iso-tp query empty response: {tx_addr}") + request_done[tx_addr] = True + continue + + counter = request_counter[tx_addr] + expected_response = self.response[counter] + response_valid = dat.startswith(expected_response) + + if response_valid: + if counter + 1 < len(self.request): + response_timeouts[tx_addr] = time.monotonic() + timeout + msg.send(self.request[counter + 1]) + request_counter[tx_addr] += 1 + else: + results[tx_addr] = dat[len(expected_response):] + request_done[tx_addr] = True + else: + error_code = dat[2] if len(dat) > 2 else -1 + if error_code == 0x78: + response_timeouts[tx_addr] = time.monotonic() + self.response_pending_timeout + carlog.error(f"iso-tp query response pending: {tx_addr}") + else: + request_done[tx_addr] = True + carlog.error(f"iso-tp query bad response: {tx_addr} - 0x{dat.hex()}") + + # Mark request done if address timed out + cur_time = time.monotonic() + for tx_addr in response_timeouts: + if cur_time - response_timeouts[tx_addr] > 0: + if not request_done[tx_addr]: + if request_counter[tx_addr] > 0: + carlog.error(f"iso-tp query timeout after receiving partial response: {tx_addr}") + elif tx_addr in addrs_responded: + carlog.error(f"iso-tp query timeout while receiving response: {tx_addr}") + # TODO: handle functional addresses + # else: + # carlog.error(f"iso-tp query timeout with no response: {tx_addr}") + request_done[tx_addr] = True + + # Break if all requests are done (finished or timed out) + if all(request_done.values()): + break + + if cur_time - start_time > total_timeout: + carlog.error("iso-tp query timeout while receiving data") + break + + return results diff --git a/selfdrive/car/mock/__init__.py b/opendbc_repo/opendbc/car/mazda/__init__.py similarity index 100% rename from selfdrive/car/mock/__init__.py rename to opendbc_repo/opendbc/car/mazda/__init__.py diff --git a/opendbc_repo/opendbc/car/mazda/carcontroller.py b/opendbc_repo/opendbc/car/mazda/carcontroller.py new file mode 100644 index 000000000000000..61efbe44e73e3b7 --- /dev/null +++ b/opendbc_repo/opendbc/car/mazda/carcontroller.py @@ -0,0 +1,64 @@ +from opendbc.can.packer import CANPacker +from opendbc.car import apply_driver_steer_torque_limits, structs +from opendbc.car.interfaces import CarControllerBase +from opendbc.car.mazda import mazdacan +from opendbc.car.mazda.values import CarControllerParams, Buttons + +VisualAlert = structs.CarControl.HUDControl.VisualAlert + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.apply_steer_last = 0 + self.packer = CANPacker(dbc_name) + self.brake_counter = 0 + + def update(self, CC, CS, now_nanos): + can_sends = [] + + apply_steer = 0 + + if CC.latActive: + # calculate steer and also set limits due to driver torque + new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, + CS.out.steeringTorque, CarControllerParams) + + if CC.cruiseControl.cancel: + # If brake is pressed, let us wait >70ms before trying to disable crz to avoid + # a race condition with the stock system, where the second cancel from openpilot + # will disable the crz 'main on'. crz ctrl msg runs at 50hz. 70ms allows us to + # read 3 messages and most likely sync state before we attempt cancel. + self.brake_counter = self.brake_counter + 1 + if self.frame % 10 == 0 and not (CS.out.brakePressed and self.brake_counter < 7): + # Cancel Stock ACC if it's enabled while OP is disengaged + # Send at a rate of 10hz until we sync with stock ACC state + can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.CANCEL)) + else: + self.brake_counter = 0 + if CC.cruiseControl.resume and self.frame % 5 == 0: + # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds + # Send Resume button when planner wants car to move + can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.RESUME)) + + self.apply_steer_last = apply_steer + + # send HUD alerts + if self.frame % 50 == 0: + ldw = CC.hudControl.visualAlert == VisualAlert.ldw + steer_required = CC.hudControl.visualAlert == VisualAlert.steerRequired + # TODO: find a way to silence audible warnings so we can add more hud alerts + steer_required = steer_required and CS.lkas_allowed_speed + can_sends.append(mazdacan.create_alert_command(self.packer, CS.cam_laneinfo, ldw, steer_required)) + + # send steering command + can_sends.append(mazdacan.create_steering_control(self.packer, self.CP, + self.frame, apply_steer, CS.cam_lkas)) + + new_actuators = CC.actuators.as_builder() + new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX + new_actuators.steerOutputCan = apply_steer + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/mazda/carstate.py b/opendbc_repo/opendbc/car/mazda/carstate.py new file mode 100644 index 000000000000000..c8682d2d0dfc420 --- /dev/null +++ b/opendbc_repo/opendbc/car/mazda/carstate.py @@ -0,0 +1,161 @@ +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from opendbc.car import create_button_events, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.interfaces import CarStateBase +from opendbc.car.mazda.values import DBC, LKAS_LIMITS, MazdaFlags + +ButtonType = structs.CarState.ButtonEvent.Type + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.shifter_values = can_define.dv["GEAR"]["GEAR"] + + self.crz_btns_counter = 0 + self.acc_active_last = False + self.low_speed_alert = False + self.lkas_allowed_speed = False + + self.distance_button = 0 + + def update(self, cp, cp_cam, *_) -> structs.CarState: + + ret = structs.CarState() + + prev_distance_button = self.distance_button + self.distance_button = cp.vl["CRZ_BTNS"]["DISTANCE_LESS"] + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS"]["FL"], + cp.vl["WHEEL_SPEEDS"]["FR"], + cp.vl["WHEEL_SPEEDS"]["RL"], + cp.vl["WHEEL_SPEEDS"]["RR"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + + # Match panda speed reading + speed_kph = cp.vl["ENGINE_DATA"]["SPEED"] + ret.standstill = speed_kph <= .1 + + can_gear = int(cp.vl["GEAR"]["GEAR"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + + ret.genericToggle = bool(cp.vl["BLINK_INFO"]["HIGH_BEAMS"]) + ret.leftBlindspot = cp.vl["BSM"]["LEFT_BS_STATUS"] != 0 + ret.rightBlindspot = cp.vl["BSM"]["RIGHT_BS_STATUS"] != 0 + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(40, cp.vl["BLINK_INFO"]["LEFT_BLINK"] == 1, + cp.vl["BLINK_INFO"]["RIGHT_BLINK"] == 1) + + ret.steeringAngleDeg = cp.vl["STEER"]["STEER_ANGLE"] + ret.steeringTorque = cp.vl["STEER_TORQUE"]["STEER_TORQUE_SENSOR"] + ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD + + ret.steeringTorqueEps = cp.vl["STEER_TORQUE"]["STEER_TORQUE_MOTOR"] + ret.steeringRateDeg = cp.vl["STEER_RATE"]["STEER_ANGLE_RATE"] + + # TODO: this should be from 0 - 1. + ret.brakePressed = cp.vl["PEDALS"]["BRAKE_ON"] == 1 + ret.brake = cp.vl["BRAKE"]["BRAKE_PRESSURE"] + + ret.seatbeltUnlatched = cp.vl["SEATBELT"]["DRIVER_SEATBELT"] == 0 + ret.doorOpen = any([cp.vl["DOORS"]["FL"], cp.vl["DOORS"]["FR"], + cp.vl["DOORS"]["BL"], cp.vl["DOORS"]["BR"]]) + + # TODO: this should be from 0 - 1. + ret.gas = cp.vl["ENGINE_DATA"]["PEDAL_GAS"] + ret.gasPressed = ret.gas > 0 + + # Either due to low speed or hands off + lkas_blocked = cp.vl["STEER_RATE"]["LKAS_BLOCK"] == 1 + + if self.CP.minSteerSpeed > 0: + # LKAS is enabled at 52kph going up and disabled at 45kph going down + # wait for LKAS_BLOCK signal to clear when going up since it lags behind the speed sometimes + if speed_kph > LKAS_LIMITS.ENABLE_SPEED and not lkas_blocked: + self.lkas_allowed_speed = True + elif speed_kph < LKAS_LIMITS.DISABLE_SPEED: + self.lkas_allowed_speed = False + else: + self.lkas_allowed_speed = True + + # TODO: the signal used for available seems to be the adaptive cruise signal, instead of the main on + # it should be used for carState.cruiseState.nonAdaptive instead + ret.cruiseState.available = cp.vl["CRZ_CTRL"]["CRZ_AVAILABLE"] == 1 + ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]["CRZ_ACTIVE"] == 1 + ret.cruiseState.standstill = cp.vl["PEDALS"]["STANDSTILL"] == 1 + ret.cruiseState.speed = cp.vl["CRZ_EVENTS"]["CRZ_SPEED"] * CV.KPH_TO_MS + + # stock lkas should be on + # TODO: is this needed? + ret.invalidLkasSetting = cp_cam.vl["CAM_LANEINFO"]["LANE_LINES"] == 0 + + if ret.cruiseState.enabled: + if not self.lkas_allowed_speed and self.acc_active_last: + self.low_speed_alert = True + else: + self.low_speed_alert = False + ret.lowSpeedAlert = self.low_speed_alert + + # Check if LKAS is disabled due to lack of driver torque when all other states indicate + # it should be enabled (steer lockout). Don't warn until we actually get lkas active + # and lose it again, i.e, after initial lkas activation + ret.steerFaultTemporary = self.lkas_allowed_speed and lkas_blocked + + self.acc_active_last = ret.cruiseState.enabled + + self.crz_btns_counter = cp.vl["CRZ_BTNS"]["CTR"] + + # camera signals + self.cam_lkas = cp_cam.vl["CAM_LKAS"] + self.cam_laneinfo = cp_cam.vl["CAM_LANEINFO"] + ret.steerFaultPermanent = cp_cam.vl["CAM_LKAS"]["ERR_BIT_1"] == 1 + + # TODO: add button types for inc and dec + ret.buttonEvents = create_button_events(self.distance_button, prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("BLINK_INFO", 10), + ("STEER", 67), + ("STEER_RATE", 83), + ("STEER_TORQUE", 83), + ("WHEEL_SPEEDS", 100), + ] + + if CP.flags & MazdaFlags.GEN1: + messages += [ + ("ENGINE_DATA", 100), + ("CRZ_CTRL", 50), + ("CRZ_EVENTS", 50), + ("CRZ_BTNS", 10), + ("PEDALS", 50), + ("BRAKE", 50), + ("SEATBELT", 10), + ("DOORS", 10), + ("GEAR", 20), + ("BSM", 10), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_cam_can_parser(CP): + messages = [] + + if CP.flags & MazdaFlags.GEN1: + messages += [ + # sig_address, frequency + ("CAM_LANEINFO", 2), + ("CAM_LKAS", 16), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/opendbc_repo/opendbc/car/mazda/fingerprints.py b/opendbc_repo/opendbc/car/mazda/fingerprints.py new file mode 100644 index 000000000000000..d7c430bc78db922 --- /dev/null +++ b/opendbc_repo/opendbc/car/mazda/fingerprints.py @@ -0,0 +1,266 @@ +from opendbc.car.structs import CarParams +from opendbc.car.mazda.values import CAR + +Ecu = CarParams.Ecu + +FW_VERSIONS = { + CAR.MAZDA_CX5_2022: { + (Ecu.eps, 0x730, None): [ + b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PEW5-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PW67-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2D-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'KGWD-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PG69-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PW66-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYJ3-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_CX5: { + (Ecu.eps, 0x730, None): [ + b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KCB8-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PA53-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PAR4-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2E-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2F-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2K-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFA-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SHKT-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PA66-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX39-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_CX9: { + (Ecu.eps, 0x730, None): [ + b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXN8-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PXM4-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD6-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_3: { + (Ecu.eps, 0x730, None): [ + b'BHN1-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYJW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-Q\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PY2S-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKA-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_6: { + (Ecu.eps, 0x730, None): [ + b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GBEF-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GFBC-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PA34-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX4F-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GBVH-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GDDM-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PA28-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH3-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_CX9_2021: { + (Ecu.eps, 0x730, None): [ + b'TC3M-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PXGW-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXGW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, +} diff --git a/opendbc_repo/opendbc/car/mazda/interface.py b/opendbc_repo/opendbc/car/mazda/interface.py new file mode 100755 index 000000000000000..b9a6932bb7695ae --- /dev/null +++ b/opendbc_repo/opendbc/car/mazda/interface.py @@ -0,0 +1,29 @@ +#!/usr/bin/env python3 +from opendbc.car import get_safety_config, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.mazda.values import CAR, LKAS_LIMITS +from opendbc.car.interfaces import CarInterfaceBase + + + +class CarInterface(CarInterfaceBase): + + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "mazda" + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.mazda)] + ret.radarUnavailable = True + + ret.dashcamOnly = candidate not in (CAR.MAZDA_CX5_2022, CAR.MAZDA_CX9_2021) + + ret.steerActuatorDelay = 0.1 + ret.steerLimitTimer = 0.8 + + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + if candidate not in (CAR.MAZDA_CX5_2022,): + ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS + + ret.centerToFront = ret.wheelbase * 0.41 + + return ret diff --git a/selfdrive/car/mazda/mazdacan.py b/opendbc_repo/opendbc/car/mazda/mazdacan.py similarity index 97% rename from selfdrive/car/mazda/mazdacan.py rename to opendbc_repo/opendbc/car/mazda/mazdacan.py index 74f6af04c56631e..0605d980f83a2fc 100644 --- a/selfdrive/car/mazda/mazdacan.py +++ b/opendbc_repo/opendbc/car/mazda/mazdacan.py @@ -1,4 +1,4 @@ -from openpilot.selfdrive.car.mazda.values import Buttons, MazdaFlags +from opendbc.car.mazda.values import Buttons, MazdaFlags def create_steering_control(packer, CP, frame, apply_steer, lkas): diff --git a/opendbc_repo/opendbc/car/mazda/radar_interface.py b/opendbc_repo/opendbc/car/mazda/radar_interface.py new file mode 100755 index 000000000000000..56bda583e2e5ecd --- /dev/null +++ b/opendbc_repo/opendbc/car/mazda/radar_interface.py @@ -0,0 +1,5 @@ +#!/usr/bin/env python3 +from opendbc.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/opendbc_repo/opendbc/car/mazda/values.py b/opendbc_repo/opendbc/car/mazda/values.py new file mode 100644 index 000000000000000..47cf43ca069c04b --- /dev/null +++ b/opendbc_repo/opendbc/car/mazda/values.py @@ -0,0 +1,104 @@ +from dataclasses import dataclass, field +from enum import IntFlag + +from opendbc.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = CarParams.Ecu + + +# Steer torque limits + +class CarControllerParams: + STEER_MAX = 800 # theoretical max_steer 2047 + STEER_DELTA_UP = 10 # torque increase per refresh + STEER_DELTA_DOWN = 25 # torque decrease per refresh + STEER_DRIVER_ALLOWANCE = 15 # allowed driver torque before start limiting + STEER_DRIVER_MULTIPLIER = 1 # weight driver torque + STEER_DRIVER_FACTOR = 1 # from dbc + STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor + STEER_STEP = 1 # 100 Hz + + def __init__(self, CP): + pass + + +@dataclass +class MazdaCarDocs(CarDocs): + package: str = "All" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.mazda])) + + +@dataclass(frozen=True, kw_only=True) +class MazdaCarSpecs(CarSpecs): + tireStiffnessFactor: float = 0.7 # not optimized yet + + +class MazdaFlags(IntFlag): + # Static flags + # Gen 1 hardware: same CAN messages and same camera + GEN1 = 1 + + +@dataclass +class MazdaPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('mazda_2017', None)) + flags: int = MazdaFlags.GEN1 + + +class CAR(Platforms): + MAZDA_CX5 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda CX-5 2017-21")], + MazdaCarSpecs(mass=3655 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.5) + ) + MAZDA_CX9 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda CX-9 2016-20")], + MazdaCarSpecs(mass=4217 * CV.LB_TO_KG, wheelbase=3.1, steerRatio=17.6) + ) + MAZDA_3 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda 3 2017-18")], + MazdaCarSpecs(mass=2875 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=14.0) + ) + MAZDA_6 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda 6 2017-20")], + MazdaCarSpecs(mass=3443 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=15.5) + ) + MAZDA_CX9_2021 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda CX-9 2021-23", video_link="https://youtu.be/dA3duO4a0O4")], + MAZDA_CX9.specs + ) + MAZDA_CX5_2022 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda CX-5 2022-24")], + MAZDA_CX5.specs, + ) + + +class LKAS_LIMITS: + STEER_THRESHOLD = 15 + DISABLE_SPEED = 45 # kph + ENABLE_SPEED = 52 # kph + + +class Buttons: + NONE = 0 + SET_PLUS = 1 + SET_MINUS = 2 + RESUME = 3 + CANCEL = 4 + + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + # TODO: check data to ensure ABS does not skip ISO-TP frames on bus 0 + Request( + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + bus=0, + ), + ], +) + +DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/nissan/__init__.py b/opendbc_repo/opendbc/car/mock/__init__.py similarity index 100% rename from selfdrive/car/nissan/__init__.py rename to opendbc_repo/opendbc/car/mock/__init__.py diff --git a/opendbc_repo/opendbc/car/mock/carcontroller.py b/opendbc_repo/opendbc/car/mock/carcontroller.py new file mode 100644 index 000000000000000..6336dcfcbe3f389 --- /dev/null +++ b/opendbc_repo/opendbc/car/mock/carcontroller.py @@ -0,0 +1,6 @@ +from opendbc.car.interfaces import CarControllerBase + + +class CarController(CarControllerBase): + def update(self, CC, CS, now_nanos): + return CC.actuators.as_builder(), [] diff --git a/opendbc_repo/opendbc/car/mock/carstate.py b/opendbc_repo/opendbc/car/mock/carstate.py new file mode 100644 index 000000000000000..9cbdf99e9116f90 --- /dev/null +++ b/opendbc_repo/opendbc/car/mock/carstate.py @@ -0,0 +1,7 @@ +from opendbc.car import structs +from opendbc.car.interfaces import CarStateBase + + +class CarState(CarStateBase): + def update(self, *_) -> structs.CarState: + return structs.CarState() diff --git a/opendbc_repo/opendbc/car/mock/interface.py b/opendbc_repo/opendbc/car/mock/interface.py new file mode 100755 index 000000000000000..f7c755c22bb043d --- /dev/null +++ b/opendbc_repo/opendbc/car/mock/interface.py @@ -0,0 +1,17 @@ +#!/usr/bin/env python3 +from opendbc.car import structs +from opendbc.car.interfaces import CarInterfaceBase + + +# mocked car interface for dashcam mode +class CarInterface(CarInterfaceBase): + + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "mock" + ret.mass = 1700. + ret.wheelbase = 2.70 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 13. + ret.dashcamOnly = True + return ret diff --git a/opendbc_repo/opendbc/car/mock/radar_interface.py b/opendbc_repo/opendbc/car/mock/radar_interface.py new file mode 100644 index 000000000000000..6e552bf618fda6f --- /dev/null +++ b/opendbc_repo/opendbc/car/mock/radar_interface.py @@ -0,0 +1,4 @@ +from opendbc.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/opendbc_repo/opendbc/car/mock/values.py b/opendbc_repo/opendbc/car/mock/values.py new file mode 100644 index 000000000000000..aa844de4c5a0774 --- /dev/null +++ b/opendbc_repo/opendbc/car/mock/values.py @@ -0,0 +1,9 @@ +from opendbc.car import CarSpecs, PlatformConfig, Platforms + + +class CAR(Platforms): + MOCK = PlatformConfig( + [], + CarSpecs(mass=1700, wheelbase=2.7, steerRatio=13), + {} + ) diff --git a/selfdrive/car/subaru/__init__.py b/opendbc_repo/opendbc/car/nissan/__init__.py similarity index 100% rename from selfdrive/car/subaru/__init__.py rename to opendbc_repo/opendbc/car/nissan/__init__.py diff --git a/opendbc_repo/opendbc/car/nissan/carcontroller.py b/opendbc_repo/opendbc/car/nissan/carcontroller.py new file mode 100644 index 000000000000000..fa1004c3ba6198f --- /dev/null +++ b/opendbc_repo/opendbc/car/nissan/carcontroller.py @@ -0,0 +1,82 @@ +from opendbc.can.packer import CANPacker +from opendbc.car.common.numpy_fast import clip +from opendbc.car import apply_std_steer_angle_limits, structs +from opendbc.car.interfaces import CarControllerBase +from opendbc.car.nissan import nissancan +from opendbc.car.nissan.values import CAR, CarControllerParams + +VisualAlert = structs.CarControl.HUDControl.VisualAlert + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.car_fingerprint = CP.carFingerprint + + self.lkas_max_torque = 0 + self.apply_angle_last = 0 + + self.packer = CANPacker(dbc_name) + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + pcm_cancel_cmd = CC.cruiseControl.cancel + + can_sends = [] + + ### STEER ### + steer_hud_alert = 1 if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) else 0 + + if CC.latActive: + # windup slower + apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgoRaw, CarControllerParams) + + # Max torque from driver before EPS will give up and not apply torque + if not bool(CS.out.steeringPressed): + self.lkas_max_torque = CarControllerParams.LKAS_MAX_TORQUE + else: + # Scale max torque based on how much torque the driver is applying to the wheel + self.lkas_max_torque = max( + # Scale max torque down to half LKAX_MAX_TORQUE as a minimum + CarControllerParams.LKAS_MAX_TORQUE * 0.5, + # Start scaling torque at STEER_THRESHOLD + CarControllerParams.LKAS_MAX_TORQUE - 0.6 * max(0, abs(CS.out.steeringTorque) - CarControllerParams.STEER_THRESHOLD) + ) + + else: + apply_angle = CS.out.steeringAngleDeg + self.lkas_max_torque = 0 + + apply_angle = clip(apply_angle, -CarControllerParams.MAX_STEER_ANGLE, CarControllerParams.MAX_STEER_ANGLE) + self.apply_angle_last = apply_angle + + if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA) and pcm_cancel_cmd: + can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, self.car_fingerprint, CS.cruise_throttle_msg)) + + # TODO: Find better way to cancel! + # For some reason spamming the cancel button is unreliable on the Leaf + # We now cancel by making propilot think the seatbelt is unlatched, + # this generates a beep and a warning message every time you disengage + if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC) and self.frame % 2 == 0: + can_sends.append(nissancan.create_cancel_msg(self.packer, CS.cancel_msg, pcm_cancel_cmd)) + + can_sends.append(nissancan.create_steering_control( + self.packer, apply_angle, self.frame, CC.latActive, self.lkas_max_torque)) + + # Below are the HUD messages. We copy the stock message and modify + if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: + if self.frame % 2 == 0: + can_sends.append(nissancan.create_lkas_hud_msg(self.packer, CS.lkas_hud_msg, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible, + hud_control.leftLaneDepart, hud_control.rightLaneDepart)) + + if self.frame % 50 == 0: + can_sends.append(nissancan.create_lkas_hud_info_msg( + self.packer, CS.lkas_hud_info_msg, steer_hud_alert + )) + + new_actuators = actuators.as_builder() + new_actuators.steeringAngleDeg = apply_angle + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/nissan/carstate.py b/opendbc_repo/opendbc/car/nissan/carstate.py new file mode 100644 index 000000000000000..09fa0e216947e57 --- /dev/null +++ b/opendbc_repo/opendbc/car/nissan/carstate.py @@ -0,0 +1,203 @@ +import copy +from collections import deque +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from opendbc.car import create_button_events, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.interfaces import CarStateBase +from opendbc.car.nissan.values import CAR, DBC, CarControllerParams + +ButtonType = structs.CarState.ButtonEvent.Type + +TORQUE_SAMPLES = 12 + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + self.lkas_hud_msg = {} + self.lkas_hud_info_msg = {} + + self.steeringTorqueSamples = deque(TORQUE_SAMPLES*[0], TORQUE_SAMPLES) + self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"] + + self.distance_button = 0 + + def update(self, cp, cp_cam, cp_adas, *_) -> structs.CarState: + ret = structs.CarState() + + prev_distance_button = self.distance_button + self.distance_button = cp.vl["CRUISE_THROTTLE"]["FOLLOW_DISTANCE_BUTTON"] + + if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): + ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"] + elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + ret.gas = cp.vl["CRUISE_THROTTLE"]["GAS_PEDAL"] + + ret.gasPressed = bool(ret.gas > 3) + + if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): + ret.brakePressed = bool(cp.vl["DOORS_LIGHTS"]["USER_BRAKE_PRESSED"]) + elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + ret.brakePressed = bool(cp.vl["CRUISE_THROTTLE"]["USER_BRAKE_PRESSED"]) + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FL"], + cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FR"], + cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"], + cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"] == 0.0 and cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"] == 0.0 + + if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + ret.cruiseState.enabled = bool(cp.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) + else: + ret.cruiseState.enabled = bool(cp_adas.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) + + if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): + ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 + ret.cruiseState.available = bool(cp_cam.vl["PRO_PILOT"]["CRUISE_ON"]) + elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + if self.CP.carFingerprint == CAR.NISSAN_LEAF: + ret.seatbeltUnlatched = cp.vl["SEATBELT"]["SEATBELT_DRIVER_LATCHED"] == 0 + elif self.CP.carFingerprint == CAR.NISSAN_LEAF_IC: + ret.seatbeltUnlatched = cp.vl["CANCEL_MSG"]["CANCEL_SEATBELT"] == 1 + ret.cruiseState.available = bool(cp.vl["CRUISE_THROTTLE"]["CRUISE_AVAILABLE"]) + elif self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 + ret.cruiseState.available = bool(cp_adas.vl["PRO_PILOT"]["CRUISE_ON"]) + + if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + speed = cp.vl["PROPILOT_HUD"]["SET_SPEED"] + else: + speed = cp_adas.vl["PROPILOT_HUD"]["SET_SPEED"] + + if speed != 255: + if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + conversion = CV.MPH_TO_MS if cp.vl["HUD_SETTINGS"]["SPEED_MPH"] else CV.KPH_TO_MS + else: + conversion = CV.MPH_TO_MS if cp.vl["HUD"]["SPEED_MPH"] else CV.KPH_TO_MS + ret.cruiseState.speed = speed * conversion + ret.cruiseState.speedCluster = (speed - 1) * conversion # Speed on HUD is always 1 lower than actually sent on can bus + + if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + ret.steeringTorque = cp_cam.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] + else: + ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] + + self.steeringTorqueSamples.append(ret.steeringTorque) + # Filtering driver torque to prevent steeringPressed false positives + ret.steeringPressed = bool(abs(sum(self.steeringTorqueSamples) / TORQUE_SAMPLES) > CarControllerParams.STEER_THRESHOLD) + + ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] + + ret.leftBlinker = bool(cp.vl["LIGHTS"]["LEFT_BLINKER"]) + ret.rightBlinker = bool(cp.vl["LIGHTS"]["RIGHT_BLINKER"]) + + ret.doorOpen = any([cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RR"], + cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RL"], + cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FR"], + cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FL"]]) + + ret.espDisabled = bool(cp.vl["ESP"]["ESP_DISABLED"]) + + can_gear = int(cp.vl["GEARBOX"]["GEAR_SHIFTER"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + + # stock lkas should be off + # TODO: is this needed? + if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + ret.invalidLkasSetting = bool(cp.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) + else: + ret.invalidLkasSetting = bool(cp_adas.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) + + self.cruise_throttle_msg = copy.copy(cp.vl["CRUISE_THROTTLE"]) + + if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + self.cancel_msg = copy.copy(cp.vl["CANCEL_MSG"]) + + if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: + self.lkas_hud_msg = copy.copy(cp_adas.vl["PROPILOT_HUD"]) + self.lkas_hud_info_msg = copy.copy(cp_adas.vl["PROPILOT_HUD_INFO_MSG"]) + + ret.buttonEvents = create_button_events(self.distance_button, prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("STEER_ANGLE_SENSOR", 100), + ("WHEEL_SPEEDS_REAR", 50), + ("WHEEL_SPEEDS_FRONT", 50), + ("ESP", 25), + ("GEARBOX", 25), + ("DOORS_LIGHTS", 10), + ("LIGHTS", 10), + ] + + if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): + messages += [ + ("GAS_PEDAL", 100), + ("CRUISE_THROTTLE", 50), + ("HUD", 25), + ] + + elif CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + messages += [ + ("BRAKE_PEDAL", 100), + ("CRUISE_THROTTLE", 50), + ("CANCEL_MSG", 50), + ("HUD_SETTINGS", 25), + ("SEATBELT", 10), + ] + + if CP.carFingerprint == CAR.NISSAN_ALTIMA: + messages += [ + ("CRUISE_STATE", 10), + ("LKAS_SETTINGS", 10), + ("PROPILOT_HUD", 50), + ] + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) + + messages.append(("STEER_TORQUE_SENSOR", 100)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_adas_can_parser(CP): + # this function generates lists for signal, messages and initial values + + if CP.carFingerprint == CAR.NISSAN_ALTIMA: + messages = [ + ("LKAS", 100), + ("PRO_PILOT", 100), + ] + else: + messages = [ + ("PROPILOT_HUD_INFO_MSG", 2), + ("LKAS_SETTINGS", 10), + ("CRUISE_STATE", 50), + ("PROPILOT_HUD", 50), + ("LKAS", 100), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) + + @staticmethod + def get_cam_can_parser(CP): + messages = [] + + if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): + messages.append(("PRO_PILOT", 100)) + elif CP.carFingerprint == CAR.NISSAN_ALTIMA: + messages.append(("STEER_TORQUE_SENSOR", 100)) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) diff --git a/opendbc_repo/opendbc/car/nissan/fingerprints.py b/opendbc_repo/opendbc/car/nissan/fingerprints.py new file mode 100644 index 000000000000000..9cef01cec461fe8 --- /dev/null +++ b/opendbc_repo/opendbc/car/nissan/fingerprints.py @@ -0,0 +1,119 @@ +# ruff: noqa: E501 +from opendbc.car.structs import CarParams +from opendbc.car.nissan.values import CAR + +Ecu = CarParams.Ecu + +FINGERPRINTS = { + CAR.NISSAN_XTRAIL: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837: 8, 2015: 8, 2016: 8, 2024: 8 + }, + { + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3, 1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 + }], + CAR.NISSAN_LEAF: [{ + 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8, 643: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8 + }, + { + 2: 5, 42: 8, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 976: 6, 1008: 7, 1009: 8, 1010: 8, 1011: 7, 1012: 8, 1013: 8, 1019: 8, 1020: 8, 1021: 8, 1022: 8, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1402: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8 + }], + CAR.NISSAN_LEAF_IC: [{ + 2: 5, 42: 6, 264: 3, 282: 8, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 756: 5, 758: 3, 761: 2, 783: 3, 830: 2, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 1001: 6, 1057: 3, 1227: 8, 1228: 8, 1229: 8, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1514: 6, 1549: 8, 1573: 6, 1792: 8, 1821: 8, 1822: 8, 1837: 8, 1838: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8 + }], + CAR.NISSAN_ROGUE: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 634: 7, 643: 5, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1042: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1534: 7, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1839: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], + CAR.NISSAN_ALTIMA: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], +} + +FW_VERSIONS = { + CAR.NISSAN_ALTIMA: { + (Ecu.fwdCamera, 0x707, None): [ + b'284N86CA1D', + ], + (Ecu.eps, 0x742, None): [ + b'6CA2B\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', + ], + (Ecu.engine, 0x7e0, None): [ + b'237109HE2B', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U29HE0A', + ], + }, + CAR.NISSAN_LEAF: { + (Ecu.abs, 0x740, None): [ + b'476605SA1C', + b'476605SA7D', + b'476605SC2D', + b'476606WK7B', + b'476606WK9B', + ], + (Ecu.eps, 0x742, None): [ + b'5SA2A\x99A\x05\x02N123F\x15b\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SA2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SN2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SN2A\xb7A\x05\x02N126F\x15\xb2\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.fwdCamera, 0x707, None): [ + b'5SA0ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', + b'5SA2ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', + b'6WK2ADB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', + b'6WK2BDB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', + b'6WK2CDB\x04\x18\x00\x00\x00\x00\x00R=1\x18\x99\x10\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U25SA3C', + b'284U25SP0C', + b'284U25SP1C', + b'284U26WK0A', + b'284U26WK0C', + ], + }, + CAR.NISSAN_LEAF_IC: { + (Ecu.fwdCamera, 0x707, None): [ + b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', + b'5SH4BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', + b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', + ], + (Ecu.abs, 0x740, None): [ + b'476605SD2E', + b'476605SH1D', + b'476605SK2A', + ], + (Ecu.eps, 0x742, None): [ + b'5SH2A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SH2C\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SK3A\x99A\x05\x02N123F\x15u\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U25SF0C', + b'284U25SH3A', + b'284U25SK2D', + ], + }, + CAR.NISSAN_XTRAIL: { + (Ecu.fwdCamera, 0x707, None): [ + b'284N86FR2A', + ], + (Ecu.abs, 0x740, None): [ + b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', + b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', + ], + (Ecu.eps, 0x742, None): [ + b'6FP2A\x99A\x05\x02N123F\x18\x02\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.combinationMeter, 0x743, None): [ + b'6FR2A\x18B\x05\x17\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.engine, 0x7e0, None): [ + b'6FR9A\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + b'6FU9B\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U26FR0E', + ], + }, +} diff --git a/opendbc_repo/opendbc/car/nissan/interface.py b/opendbc_repo/opendbc/car/nissan/interface.py new file mode 100644 index 000000000000000..14255338b996ac1 --- /dev/null +++ b/opendbc_repo/opendbc/car/nissan/interface.py @@ -0,0 +1,26 @@ +from panda import Panda +from opendbc.car import get_safety_config, structs +from opendbc.car.interfaces import CarInterfaceBase +from opendbc.car.nissan.values import CAR + + +class CarInterface(CarInterfaceBase): + + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "nissan" + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.nissan)] + ret.autoResumeSng = False + + ret.steerLimitTimer = 1.0 + + ret.steerActuatorDelay = 0.1 + + ret.steerControlType = structs.CarParams.SteerControlType.angle + ret.radarUnavailable = True + + if candidate == CAR.NISSAN_ALTIMA: + # Altima has EPS on C-CAN unlike the others that have it on V-CAN + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_NISSAN_ALT_EPS_BUS + + return ret diff --git a/selfdrive/car/nissan/nissancan.py b/opendbc_repo/opendbc/car/nissan/nissancan.py similarity index 97% rename from selfdrive/car/nissan/nissancan.py rename to opendbc_repo/opendbc/car/nissan/nissancan.py index b9a1b4f843217e8..555020d858bf4e6 100644 --- a/selfdrive/car/nissan/nissancan.py +++ b/opendbc_repo/opendbc/car/nissan/nissancan.py @@ -1,5 +1,5 @@ import crcmod -from openpilot.selfdrive.car.nissan.values import CAR +from opendbc.car.nissan.values import CAR # TODO: add this checksum to the CANPacker nissan_checksum = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) @@ -15,7 +15,7 @@ def create_steering_control(packer, apply_steer, frame, steer_on, lkas_max_torqu "LKA_ACTIVE": steer_on, } - dat = packer.make_can_msg("LKAS", 0, values)[2] + dat = packer.make_can_msg("LKAS", 0, values)[1] values["CHECKSUM"] = nissan_checksum(dat[:7]) return packer.make_can_msg("LKAS", 0, values) diff --git a/opendbc_repo/opendbc/car/nissan/radar_interface.py b/opendbc_repo/opendbc/car/nissan/radar_interface.py new file mode 100644 index 000000000000000..6e552bf618fda6f --- /dev/null +++ b/opendbc_repo/opendbc/car/nissan/radar_interface.py @@ -0,0 +1,4 @@ +from opendbc.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/opendbc_repo/opendbc/car/nissan/values.py b/opendbc_repo/opendbc/car/nissan/values.py new file mode 100644 index 000000000000000..a8755e52cffb6bc --- /dev/null +++ b/opendbc_repo/opendbc/car/nissan/values.py @@ -0,0 +1,111 @@ +from dataclasses import dataclass, field + +from panda import uds +from opendbc.car import AngleRateLimit, CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarDocs, CarHarness, CarParts +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = CarParams.Ecu + + +class CarControllerParams: + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., .8, .15]) + ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., 3.5, 0.4]) + LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower + STEER_THRESHOLD = 1.0 + + # When output steering Angle not within range -1311 and 1310, + # CANPacker packs wrong angle output to be decoded by panda + MAX_STEER_ANGLE = 1310 + + def __init__(self, CP): + pass + + +@dataclass +class NissanCarDocs(CarDocs): + package: str = "ProPILOT Assist" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.nissan_a])) + + +@dataclass(frozen=True) +class NissanCarSpecs(CarSpecs): + centerToFrontRatio: float = 0.44 + steerRatio: float = 17. + + +@dataclass +class NissanPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('nissan_x_trail_2017_generated', None)) + + +class CAR(Platforms): + NISSAN_XTRAIL = NissanPlatformConfig( + [NissanCarDocs("Nissan X-Trail 2017")], + NissanCarSpecs(mass=1610, wheelbase=2.705) + ) + NISSAN_LEAF = NissanPlatformConfig( + [NissanCarDocs("Nissan Leaf 2018-23", video_link="https://youtu.be/vaMbtAh_0cY")], + NissanCarSpecs(mass=1610, wheelbase=2.705), + dbc_dict('nissan_leaf_2018_generated', None), + ) + # Leaf with ADAS ECU found behind instrument cluster instead of glovebox + # Currently the only known difference between them is the inverted seatbelt signal. + NISSAN_LEAF_IC = NISSAN_LEAF.override(car_docs=[]) + NISSAN_ROGUE = NissanPlatformConfig( + [NissanCarDocs("Nissan Rogue 2018-20")], + NissanCarSpecs(mass=1610, wheelbase=2.705) + ) + NISSAN_ALTIMA = NissanPlatformConfig( + [NissanCarDocs("Nissan Altima 2019-20", car_parts=CarParts.common([CarHarness.nissan_b]))], + NissanCarSpecs(mass=1492, wheelbase=2.824) + ) + + +DBC = CAR.create_dbc_map() + +# Default diagnostic session +NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0x81]) +NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0x81]) + +# Manufacturer specific +NISSAN_DIAGNOSTIC_REQUEST_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xda]) +NISSAN_DIAGNOSTIC_RESPONSE_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xda]) + +NISSAN_VERSION_REQUEST_KWP = b'\x21\x83' +NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' + +NISSAN_RX_OFFSET = 0x20 + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[request for bus, logging in ((0, False), (1, True)) for request in [ + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + bus=bus, + logging=logging, + ), + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + rx_offset=NISSAN_RX_OFFSET, + bus=bus, + logging=logging, + ), + # Rogue's engine solely responds to this + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP_2, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP_2, NISSAN_VERSION_RESPONSE_KWP], + bus=bus, + logging=logging, + ), + Request( + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + rx_offset=NISSAN_RX_OFFSET, + bus=bus, + logging=logging, + ), + ]], +) diff --git a/opendbc_repo/opendbc/car/panda_runner.py b/opendbc_repo/opendbc/car/panda_runner.py new file mode 100644 index 000000000000000..598ff51e4a823f4 --- /dev/null +++ b/opendbc_repo/opendbc/car/panda_runner.py @@ -0,0 +1,57 @@ +import time +from contextlib import AbstractContextManager + +from panda import Panda +from opendbc.car.car_helpers import get_car +from opendbc.car.can_definitions import CanData +from opendbc.car.structs import CarParams, CarControl + +class PandaRunner(AbstractContextManager): + def __enter__(self): + self.p = Panda() + self.p.reset() + + # setup + fingerprinting + self.p.set_safety_mode(Panda.SAFETY_ELM327, 1) + self.CI = get_car(self._can_recv, self.p.can_send_many, self.p.set_obd, True) + assert self.CI.CP.carFingerprint.lower() != "mock", "Unable to identify car. Check connections and ensure car is supported." + + safety_model = list(CarParams.SafetyModel).index(self.CI.CP.safetyConfigs[0].safetyModel) + self.p.set_safety_mode(Panda.SAFETY_ELM327, 1) + self.CI.init(self.CI.CP, self._can_recv, self.p.can_send_many) + self.p.set_safety_mode(safety_model, self.CI.CP.safetyConfigs[0].safetyParam) + + return self + + def __exit__(self, exc_type, exc_value, traceback): + self.p.set_safety_mode(Panda.SAFETY_NOOUTPUT) + self.p.reset() # avoid siren + return super().__exit__(exc_type, exc_value, traceback) + + @property + def panda(self) -> Panda: + return self.p + + def _can_recv(self, wait_for_one: bool = False) -> list[list[CanData]]: + recv = self.p.can_recv() + while len(recv) == 0 and wait_for_one: + recv = self.p.can_recv() + return [[CanData(addr, dat, bus) for addr, dat, bus in recv], ] + + def read(self, strict: bool = True): + cs = self.CI.update([int(time.monotonic()*1e9), self._can_recv()[0]]) + if strict: + assert cs.canValid, "CAN went invalid, check connections" + return cs + + def write(self, cc: CarControl) -> None: + if cc.enabled and not self.p.health()['controls_allowed']: + # prevent the car from faulting. print a warning? + cc = CarControl(enabled=False) + _, can_sends = self.CI.apply(cc) + self.p.can_send_many(can_sends, timeout=25) + self.p.send_heartbeat() + +if __name__ == "__main__": + with PandaRunner() as p: + print(p.read()) diff --git a/opendbc_repo/opendbc/car/secoc.py b/opendbc_repo/opendbc/car/secoc.py new file mode 100644 index 000000000000000..971ea36a192a907 --- /dev/null +++ b/opendbc_repo/opendbc/car/secoc.py @@ -0,0 +1,47 @@ +import struct + +from Crypto.Hash import CMAC +from Crypto.Cipher import AES + +def add_mac(key, trip_cnt, reset_cnt, msg_cnt, msg): + # TODO: clean up conversion to and from hex + + addr, payload, bus = msg + reset_flag = reset_cnt & 0b11 + msg_cnt_flag = msg_cnt & 0b11 + payload = payload[:4] + + # Step 1: Build Freshness Value (48 bits) + # [Trip Counter (16 bit)][[Reset Counter (20 bit)][Message Counter (8 bit)][Reset Flag (2 bit)][Padding (2 bit)] + freshness_value = struct.pack('>HI', trip_cnt, (reset_cnt << 12) | ((msg_cnt & 0xff) << 4) | (reset_flag << 2)) + + # Step 2: Build data to authenticate (96 bits) + # [Message ID (16 bits)][Payload (32 bits)][Freshness Value (48 bits)] + to_auth = struct.pack('>H', addr) + payload + freshness_value + + # Step 3: Calculate CMAC (28 bit) + cmac = CMAC.new(key, ciphermod=AES) + cmac.update(to_auth) + mac = cmac.digest().hex()[:7] # truncated MAC + + # Step 4: Build message + # [Payload (32 bit)][Message Counter Flag (2 bit)][Reset Flag (2 bit)][Authenticator (28 bit)] + msg_cnt_rst_flag = struct.pack('>B', (msg_cnt_flag << 2) | reset_flag).hex()[1] + msg = payload.hex() + msg_cnt_rst_flag + mac + payload = bytes.fromhex(msg) + + return (addr, payload, bus) + +def build_sync_mac(key, trip_cnt, reset_cnt, id_=0xf): + id_ = struct.pack('>H', id_) # 16 + trip_cnt = struct.pack('>H', trip_cnt) # 16 + reset_cnt = struct.pack('>I', reset_cnt << 12)[:-1] # 20 + 4 padding + + to_auth = id_ + trip_cnt + reset_cnt # SecOC 11.4.1.1 page 138 + + cmac = CMAC.new(key, ciphermod=AES) + cmac.update(to_auth) + + msg = "0" + cmac.digest().hex()[:7] + msg = bytes.fromhex(msg) + return struct.unpack('>I', msg)[0] diff --git a/opendbc_repo/opendbc/car/structs.py b/opendbc_repo/opendbc/car/structs.py new file mode 100644 index 000000000000000..a5628c7e00097ea --- /dev/null +++ b/opendbc_repo/opendbc/car/structs.py @@ -0,0 +1,20 @@ +import os +import capnp +from opendbc.car.common.basedir import BASEDIR + +# TODO: remove car from cereal/__init__.py and always import from opendbc +try: + from cereal import car +except ImportError: + capnp.remove_import_hook() + car = capnp.load(os.path.join(BASEDIR, "car.capnp")) + +CarState = car.CarState +RadarData = car.RadarData +CarControl = car.CarControl +CarParams = car.CarParams + +CarStateT = capnp.lib.capnp._StructModule +RadarDataT = capnp.lib.capnp._StructModule +CarControlT = capnp.lib.capnp._StructModule +CarParamsT = capnp.lib.capnp._StructModule diff --git a/selfdrive/car/tesla/__init__.py b/opendbc_repo/opendbc/car/subaru/__init__.py similarity index 100% rename from selfdrive/car/tesla/__init__.py rename to opendbc_repo/opendbc/car/subaru/__init__.py diff --git a/opendbc_repo/opendbc/car/subaru/carcontroller.py b/opendbc_repo/opendbc/car/subaru/carcontroller.py new file mode 100644 index 000000000000000..5bef600b38f0b5b --- /dev/null +++ b/opendbc_repo/opendbc/car/subaru/carcontroller.py @@ -0,0 +1,143 @@ +from opendbc.can.packer import CANPacker +from opendbc.car import apply_driver_steer_torque_limits, common_fault_avoidance, make_tester_present_msg +from opendbc.car.common.numpy_fast import clip, interp +from opendbc.car.interfaces import CarControllerBase +from opendbc.car.subaru import subarucan +from opendbc.car.subaru.values import DBC, GLOBAL_ES_ADDR, CanBus, CarControllerParams, SubaruFlags + +# FIXME: These limits aren't exact. The real limit is more than likely over a larger time period and +# involves the total steering angle change rather than rate, but these limits work well for now +MAX_STEER_RATE = 25 # deg/s +MAX_STEER_RATE_FRAMES = 7 # tx control frames needed before torque can be cut + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.apply_steer_last = 0 + + self.cruise_button_prev = 0 + self.steer_rate_counter = 0 + + self.p = CarControllerParams(CP) + self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + pcm_cancel_cmd = CC.cruiseControl.cancel + + can_sends = [] + + # *** steering *** + if (self.frame % self.p.STEER_STEP) == 0: + apply_steer = int(round(actuators.steer * self.p.STEER_MAX)) + + # limits due to driver torque + + new_steer = int(round(apply_steer)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) + + if not CC.latActive: + apply_steer = 0 + + if self.CP.flags & SubaruFlags.PREGLOBAL: + can_sends.append(subarucan.create_preglobal_steering_control(self.packer, self.frame // self.p.STEER_STEP, apply_steer, CC.latActive)) + else: + apply_steer_req = CC.latActive + + if self.CP.flags & SubaruFlags.STEER_RATE_LIMITED: + # Steering rate fault prevention + self.steer_rate_counter, apply_steer_req = \ + common_fault_avoidance(abs(CS.out.steeringRateDeg) > MAX_STEER_RATE, apply_steer_req, + self.steer_rate_counter, MAX_STEER_RATE_FRAMES) + + can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, apply_steer_req)) + + self.apply_steer_last = apply_steer + + # *** longitudinal *** + + if CC.longActive: + apply_throttle = int(round(interp(actuators.accel, CarControllerParams.THROTTLE_LOOKUP_BP, CarControllerParams.THROTTLE_LOOKUP_V))) + apply_rpm = int(round(interp(actuators.accel, CarControllerParams.RPM_LOOKUP_BP, CarControllerParams.RPM_LOOKUP_V))) + apply_brake = int(round(interp(actuators.accel, CarControllerParams.BRAKE_LOOKUP_BP, CarControllerParams.BRAKE_LOOKUP_V))) + + # limit min and max values + cruise_throttle = clip(apply_throttle, CarControllerParams.THROTTLE_MIN, CarControllerParams.THROTTLE_MAX) + cruise_rpm = clip(apply_rpm, CarControllerParams.RPM_MIN, CarControllerParams.RPM_MAX) + cruise_brake = clip(apply_brake, CarControllerParams.BRAKE_MIN, CarControllerParams.BRAKE_MAX) + else: + cruise_throttle = CarControllerParams.THROTTLE_INACTIVE + cruise_rpm = CarControllerParams.RPM_MIN + cruise_brake = CarControllerParams.BRAKE_MIN + + # *** alerts and pcm cancel *** + if self.CP.flags & SubaruFlags.PREGLOBAL: + if self.frame % 5 == 0: + # 1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 = resume deep + # disengage ACC when OP is disengaged + if pcm_cancel_cmd: + cruise_button = 1 + # turn main on if off and past start-up state + elif not CS.out.cruiseState.available and CS.ready: + cruise_button = 1 + else: + cruise_button = CS.cruise_button + + # unstick previous mocked button press + if cruise_button == 1 and self.cruise_button_prev == 1: + cruise_button = 0 + self.cruise_button_prev = cruise_button + + can_sends.append(subarucan.create_preglobal_es_distance(self.packer, cruise_button, CS.es_distance_msg)) + + else: + if self.frame % 10 == 0: + can_sends.append(subarucan.create_es_dashstatus(self.packer, self.frame // 10, CS.es_dashstatus_msg, CC.enabled, + self.CP.openpilotLongitudinalControl, CC.longActive, hud_control.leadVisible)) + + can_sends.append(subarucan.create_es_lkas_state(self.packer, self.frame // 10, CS.es_lkas_state_msg, CC.enabled, hud_control.visualAlert, + hud_control.leftLaneVisible, hud_control.rightLaneVisible, + hud_control.leftLaneDepart, hud_control.rightLaneDepart)) + + if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: + can_sends.append(subarucan.create_es_infotainment(self.packer, self.frame // 10, CS.es_infotainment_msg, hud_control.visualAlert)) + + if self.CP.openpilotLongitudinalControl: + if self.frame % 5 == 0: + can_sends.append(subarucan.create_es_status(self.packer, self.frame // 5, CS.es_status_msg, + self.CP.openpilotLongitudinalControl, CC.longActive, cruise_rpm)) + + can_sends.append(subarucan.create_es_brake(self.packer, self.frame // 5, CS.es_brake_msg, + self.CP.openpilotLongitudinalControl, CC.longActive, cruise_brake)) + + can_sends.append(subarucan.create_es_distance(self.packer, self.frame // 5, CS.es_distance_msg, 0, pcm_cancel_cmd, + self.CP.openpilotLongitudinalControl, cruise_brake > 0, cruise_throttle)) + else: + if pcm_cancel_cmd: + if not (self.CP.flags & SubaruFlags.HYBRID): + bus = CanBus.alt if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else CanBus.main + can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg["COUNTER"] + 1, CS.es_distance_msg, bus, pcm_cancel_cmd)) + + if self.CP.flags & SubaruFlags.DISABLE_EYESIGHT: + # Tester present (keeps eyesight disabled) + if self.frame % 100 == 0: + can_sends.append(make_tester_present_msg(GLOBAL_ES_ADDR, CanBus.camera, suppress_response=True)) + + # Create all of the other eyesight messages to keep the rest of the car happy when eyesight is disabled + if self.frame % 5 == 0: + can_sends.append(subarucan.create_es_highbeamassist(self.packer)) + + if self.frame % 10 == 0: + can_sends.append(subarucan.create_es_static_1(self.packer)) + + if self.frame % 2 == 0: + can_sends.append(subarucan.create_es_static_2(self.packer)) + + new_actuators = actuators.as_builder() + new_actuators.steer = self.apply_steer_last / self.p.STEER_MAX + new_actuators.steerOutputCan = self.apply_steer_last + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/subaru/carstate.py b/opendbc_repo/opendbc/car/subaru/carstate.py new file mode 100644 index 000000000000000..84fa21581594a38 --- /dev/null +++ b/opendbc_repo/opendbc/car/subaru/carstate.py @@ -0,0 +1,228 @@ +import copy +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.interfaces import CarStateBase +from opendbc.car.subaru.values import DBC, CanBus, SubaruFlags +from opendbc.car import CanSignalRateCalculator + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.shifter_values = can_define.dv["Transmission"]["Gear"] + + self.angle_rate_calulator = CanSignalRateCalculator(50) + + def update(self, cp, cp_cam, _, cp_body, __) -> structs.CarState: + ret = structs.CarState() + + throttle_msg = cp.vl["Throttle"] if not (self.CP.flags & SubaruFlags.HYBRID) else cp_body.vl["Throttle_Hybrid"] + ret.gas = throttle_msg["Throttle_Pedal"] / 255. + + ret.gasPressed = ret.gas > 1e-5 + if self.CP.flags & SubaruFlags.PREGLOBAL: + ret.brakePressed = cp.vl["Brake_Pedal"]["Brake_Pedal"] > 0 + else: + cp_brakes = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp + ret.brakePressed = cp_brakes.vl["Brake_Status"]["Brake"] == 1 + + cp_es_distance = cp_body if self.CP.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.HYBRID) else cp_cam + if not (self.CP.flags & SubaruFlags.HYBRID): + eyesight_fault = bool(cp_es_distance.vl["ES_Distance"]["Cruise_Fault"]) + + # if openpilot is controlling long, an eyesight fault is a non-critical fault. otherwise it's an ACC fault + if self.CP.openpilotLongitudinalControl: + ret.carFaultedNonCritical = eyesight_fault + else: + ret.accFaulted = eyesight_fault + + cp_wheels = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp + ret.wheelSpeeds = self.get_wheel_speeds( + cp_wheels.vl["Wheel_Speeds"]["FL"], + cp_wheels.vl["Wheel_Speeds"]["FR"], + cp_wheels.vl["Wheel_Speeds"]["RL"], + cp_wheels.vl["Wheel_Speeds"]["RR"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.vEgoRaw == 0 + + # continuous blinker signals for assisted lane change + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["Dashlights"]["LEFT_BLINKER"], + cp.vl["Dashlights"]["RIGHT_BLINKER"]) + + if self.CP.enableBsm: + ret.leftBlindspot = (cp.vl["BSD_RCTA"]["L_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["L_APPROACHING"] == 1) + ret.rightBlindspot = (cp.vl["BSD_RCTA"]["R_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["R_APPROACHING"] == 1) + + cp_transmission = cp_body if self.CP.flags & SubaruFlags.HYBRID else cp + can_gear = int(cp_transmission.vl["Transmission"]["Gear"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + + ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"] + + if not (self.CP.flags & SubaruFlags.PREGLOBAL): + # ideally we get this from the car, but unclear if it exists. diagnostic software doesn't even have it + ret.steeringRateDeg = self.angle_rate_calulator.update(ret.steeringAngleDeg, cp.vl["Steering_Torque"]["COUNTER"]) + + ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"] + ret.steeringTorqueEps = cp.vl["Steering_Torque"]["Steer_Torque_Output"] + + steer_threshold = 75 if self.CP.flags & SubaruFlags.PREGLOBAL else 80 + ret.steeringPressed = abs(ret.steeringTorque) > steer_threshold + + cp_cruise = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp + if self.CP.flags & SubaruFlags.HYBRID: + ret.cruiseState.enabled = cp_cam.vl["ES_DashStatus"]['Cruise_Activated'] != 0 + ret.cruiseState.available = cp_cam.vl["ES_DashStatus"]['Cruise_On'] != 0 + else: + ret.cruiseState.enabled = cp_cruise.vl["CruiseControl"]["Cruise_Activated"] != 0 + ret.cruiseState.available = cp_cruise.vl["CruiseControl"]["Cruise_On"] != 0 + ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.KPH_TO_MS + + if (self.CP.flags & SubaruFlags.PREGLOBAL and cp.vl["Dash_State2"]["UNITS"] == 1) or \ + (not (self.CP.flags & SubaruFlags.PREGLOBAL) and cp.vl["Dashlights"]["UNITS"] == 1): + ret.cruiseState.speed *= CV.MPH_TO_KPH + + ret.seatbeltUnlatched = cp.vl["Dashlights"]["SEATBELT_FL"] == 1 + ret.doorOpen = any([cp.vl["BodyInfo"]["DOOR_OPEN_RR"], + cp.vl["BodyInfo"]["DOOR_OPEN_RL"], + cp.vl["BodyInfo"]["DOOR_OPEN_FR"], + cp.vl["BodyInfo"]["DOOR_OPEN_FL"]]) + ret.steerFaultPermanent = cp.vl["Steering_Torque"]["Steer_Error_1"] == 1 + + if self.CP.flags & SubaruFlags.PREGLOBAL: + self.cruise_button = cp_cam.vl["ES_Distance"]["Cruise_Button"] + self.ready = not cp_cam.vl["ES_DashStatus"]["Not_Ready_Startup"] + else: + ret.steerFaultTemporary = cp.vl["Steering_Torque"]["Steer_Warning"] == 1 + ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]["Conventional_Cruise"] == 1 + ret.cruiseState.standstill = cp_cam.vl["ES_DashStatus"]["Cruise_State"] == 3 + ret.stockFcw = (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 1) or \ + (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 2) + + self.es_lkas_state_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) + cp_es_brake = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam + self.es_brake_msg = copy.copy(cp_es_brake.vl["ES_Brake"]) + cp_es_status = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam + + # TODO: Hybrid cars don't have ES_Distance, need a replacement + if not (self.CP.flags & SubaruFlags.HYBRID): + # 8 is known AEB, there are a few other values related to AEB we ignore + ret.stockAeb = (cp_es_distance.vl["ES_Brake"]["AEB_Status"] == 8) and \ + (cp_es_distance.vl["ES_Brake"]["Brake_Pressure"] != 0) + + self.es_status_msg = copy.copy(cp_es_status.vl["ES_Status"]) + self.cruise_control_msg = copy.copy(cp_cruise.vl["CruiseControl"]) + + if not (self.CP.flags & SubaruFlags.HYBRID): + self.es_distance_msg = copy.copy(cp_es_distance.vl["ES_Distance"]) + + self.es_dashstatus_msg = copy.copy(cp_cam.vl["ES_DashStatus"]) + if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: + self.es_infotainment_msg = copy.copy(cp_cam.vl["ES_Infotainment"]) + + return ret + + @staticmethod + def get_common_global_body_messages(CP): + messages = [ + ("Wheel_Speeds", 50), + ("Brake_Status", 50), + ] + + if not (CP.flags & SubaruFlags.HYBRID): + messages.append(("CruiseControl", 20)) + + return messages + + @staticmethod + def get_common_global_es_messages(CP): + messages = [ + ("ES_Brake", 20), + ] + + if not (CP.flags & SubaruFlags.HYBRID): + messages += [ + ("ES_Distance", 20), + ("ES_Status", 20) + ] + + return messages + + @staticmethod + def get_common_preglobal_body_messages(): + messages = [ + ("CruiseControl", 50), + ("Wheel_Speeds", 50), + ("Dash_State2", 1), + ] + + return messages + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("Dashlights", 10), + ("Steering_Torque", 50), + ("BodyInfo", 1), + ("Brake_Pedal", 50), + ] + + if not (CP.flags & SubaruFlags.HYBRID): + messages += [ + ("Throttle", 100), + ("Transmission", 100) + ] + + if CP.enableBsm: + messages.append(("BSD_RCTA", 17)) + + if not (CP.flags & SubaruFlags.PREGLOBAL): + if not (CP.flags & SubaruFlags.GLOBAL_GEN2): + messages += CarState.get_common_global_body_messages(CP) + else: + messages += CarState.get_common_preglobal_body_messages() + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.main) + + @staticmethod + def get_cam_can_parser(CP): + if CP.flags & SubaruFlags.PREGLOBAL: + messages = [ + ("ES_DashStatus", 20), + ("ES_Distance", 20), + ] + else: + messages = [ + ("ES_DashStatus", 10), + ("ES_LKAS_State", 10), + ] + + if not (CP.flags & SubaruFlags.GLOBAL_GEN2): + messages += CarState.get_common_global_es_messages(CP) + + if CP.flags & SubaruFlags.SEND_INFOTAINMENT: + messages.append(("ES_Infotainment", 10)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.camera) + + @staticmethod + def get_body_can_parser(CP): + messages = [] + + if CP.flags & SubaruFlags.GLOBAL_GEN2: + messages += CarState.get_common_global_body_messages(CP) + messages += CarState.get_common_global_es_messages(CP) + + if CP.flags & SubaruFlags.HYBRID: + messages += [ + ("Throttle_Hybrid", 40), + ("Transmission", 100) + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.alt) diff --git a/opendbc_repo/opendbc/car/subaru/fingerprints.py b/opendbc_repo/opendbc/car/subaru/fingerprints.py new file mode 100644 index 000000000000000..1b6971bbd35f2bb --- /dev/null +++ b/opendbc_repo/opendbc/car/subaru/fingerprints.py @@ -0,0 +1,564 @@ +from opendbc.car.structs import CarParams +from opendbc.car.subaru.values import CAR + +Ecu = CarParams.Ecu + +FW_VERSIONS = { + CAR.SUBARU_ASCENT: { + (Ecu.abs, 0x7b0, None): [ + b'\xa5 \x19\x02\x00', + b'\xa5 !\x02\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\x05\xc0\xd0\x00', + b'\x85\xc0\xd0\x00', + b'\x95\xc0\xd0\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00d\xb9\x00\x00\x00\x00', + b'\x00\x00d\xb9\x1f@ \x10', + b'\x00\x00e@\x00\x00\x00\x00', + b'\x00\x00e@\x1f@ $', + b"\x00\x00e~\x1f@ '", + ], + (Ecu.engine, 0x7e0, None): [ + b'\xbb,\xa0t\x07', + b'\xd1,\xa0q\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x00>\xf0\x00\x00', + b'\x00\xfe\xf7\x00\x00', + b'\x01\xfe\xf7\x00\x00', + b'\x01\xfe\xf9\x00\x00', + b'\x01\xfe\xfa\x00\x00', + ], + }, + CAR.SUBARU_ASCENT_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\xa5 #\x03\x00', + ], + (Ecu.eps, 0x746, None): [ + b'%\xc0\xd0\x11', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x05!\x08\x1dK\x05!\x08\x01/', + ], + (Ecu.engine, 0x7a2, None): [ + b'\xe5,\xa0P\x07', + ], + (Ecu.transmission, 0x7a3, None): [ + b'\x04\xfe\xf3\x00\x00', + ], + }, + CAR.SUBARU_LEGACY: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 \x02\x01', + b'\xa1 \x02\x02', + b'\xa1 \x03\x03', + b'\xa1 \x04\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x9b\xc0\x11\x00', + b'\x9b\xc0\x11\x02', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00e\x80\x00\x1f@ \x19\x00', + b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xde"a0\x07', + b'\xde,\xa0@\x07', + b'\xe2"aq\x07', + b'\xe2,\xa0@\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xa5\xf6\x05@\x00', + b'\xa5\xfe\xc7@\x00', + b'\xa7\xf6\x04@\x00', + b'\xa7\xfe\xc4@\x00', + ], + }, + CAR.SUBARU_IMPREZA: { + (Ecu.abs, 0x7b0, None): [ + b'z\x84\x19\x90\x00', + b'z\x94\x08\x90\x00', + b'z\x94\x08\x90\x01', + b'z\x94\x0c\x90\x00', + b'z\x94\x0c\x90\x01', + b'z\x94.\x90\x00', + b'z\x94?\x90\x00', + b'z\x9c\x19\x80\x01', + b'\xa2 \x185\x00', + b'\xa2 \x193\x00', + b'\xa2 \x194\x00', + b'\xa2 \x19`\x00', + ], + (Ecu.eps, 0x746, None): [ + b'z\xc0\x00\x00', + b'z\xc0\x04\x00', + b'z\xc0\x08\x00', + b'z\xc0\n\x00', + b'z\xc0\x0c\x00', + b'\x8a\xc0\x00\x00', + b'\x8a\xc0\x10\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\xf4\x00\x00\x00\x00', + b'\x00\x00c\xf4\x1f@ \x07', + b'\x00\x00d)\x00\x00\x00\x00', + b'\x00\x00d)\x1f@ \x07', + b'\x00\x00dd\x00\x00\x00\x00', + b'\x00\x00dd\x1f@ \x0e', + b'\x00\x00d\xb5\x1f@ \x0e', + b'\x00\x00d\xdc\x00\x00\x00\x00', + b'\x00\x00d\xdc\x1f@ \x0e', + b'\x00\x00e\x02\x1f@ \x14', + b'\x00\x00e\x1c\x00\x00\x00\x00', + b'\x00\x00e\x1c\x1f@ \x14', + b'\x00\x00e+\x00\x00\x00\x00', + b'\x00\x00e+\x1f@ \x14', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xaa\x00Bu\x07', + b'\xaa\x01bt\x07', + b'\xaa!`u\x07', + b'\xaa!au\x07', + b'\xaa!av\x07', + b'\xaa!aw\x07', + b'\xaa!dq\x07', + b'\xaa!ds\x07', + b'\xaa!dt\x07', + b'\xaaafs\x07', + b'\xbe!as\x07', + b'\xbe!at\x07', + b'\xbeacr\x07', + b'\xc5!`r\x07', + b'\xc5!`s\x07', + b'\xc5!ap\x07', + b'\xc5!ar\x07', + b'\xc5!as\x07', + b'\xc5!dr\x07', + b'\xc5!ds\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xe3\xd0\x081\x00', + b'\xe3\xd5\x161\x00', + b'\xe3\xe5F1\x00', + b'\xe3\xf5\x06\x00\x00', + b'\xe3\xf5\x07\x00\x00', + b'\xe3\xf5C\x00\x00', + b'\xe3\xf5F\x00\x00', + b'\xe3\xf5G\x00\x00', + b'\xe4\xe5\x021\x00', + b'\xe4\xe5\x061\x00', + b'\xe4\xf5\x02\x00\x00', + b'\xe4\xf5\x07\x00\x00', + b'\xe5\xf5\x04\x00\x00', + b'\xe5\xf5$\x00\x00', + b'\xe5\xf5B\x00\x00', + ], + }, + CAR.SUBARU_IMPREZA_2020: { + (Ecu.abs, 0x7b0, None): [ + b'\xa2 \x193\x00', + b'\xa2 \x194\x00', + b'\xa2 `\x00', + b'\xa2 !3\x00', + b'\xa2 !6\x00', + b'\xa2 !`\x00', + b'\xa2 !i\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\n\xc0\x04\x00', + b'\n\xc0\x04\x01', + b'\x9a\xc0\x00\x00', + b'\x9a\xc0\x04\x00', + b'\x9a\xc0\n\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eb\x1f@ "', + b'\x00\x00eq\x00\x00\x00\x00', + b'\x00\x00eq\x1f@ "', + b'\x00\x00e\x8f\x00\x00\x00\x00', + b'\x00\x00e\x8f\x1f@ )', + b'\x00\x00e\x92\x00\x00\x00\x00', + b'\x00\x00e\xa4\x00\x00\x00\x00', + b'\x00\x00e\xa4\x1f@ (', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xca!`0\x07', + b'\xca!`p\x07', + b'\xca!`t\x07', + b'\xca!ap\x07', + b'\xca!f@\x07', + b'\xca!fp\x07', + b'\xcaacp\x07', + b'\xcc!`p\x07', + b'\xcc!fp\x07', + b'\xcc"f0\x07', + b'\xe6!`@\x07', + b'\xe6!fp\x07', + b'\xe6"f0\x07', + b'\xe6"fp\x07', + b'\xf3"f@\x07', + b'\xf3"fp\x07', + b'\xf3"fr\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xe6\x15\x042\x00', + b'\xe6\xf5\x04\x00\x00', + b'\xe6\xf5$\x00\x00', + b'\xe6\xf5D0\x00', + b'\xe7\xf5\x04\x00\x00', + b'\xe7\xf5D0\x00', + b'\xe7\xf6B0\x00', + b'\xe9\xf5"\x00\x00', + b'\xe9\xf5B0\x00', + b'\xe9\xf6B0\x00', + b'\xe9\xf6F0\x00', + ], + }, + CAR.SUBARU_CROSSTREK_HYBRID: { + (Ecu.abs, 0x7b0, None): [ + b'\xa2 \x19e\x01', + b'\xa2 !e\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\n\xc2\x01\x00', + b'\x9a\xc2\x01\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00el\x1f@ #', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd7!`@\x07', + b'\xd7!`p\x07', + b'\xf4!`0\x07', + ], + }, + CAR.SUBARU_FORESTER: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 \x18\x14\x00', + b'\xa3 \x18&\x00', + b'\xa3 \x19\x14\x00', + b'\xa3 \x19&\x00', + b'\xa3 \x19h\x00', + b'\xa3 \x14\x00', + b'\xa3 \x14\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x8d\xc0\x00\x00', + b'\x8d\xc0\x04\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00e!\x00\x00\x00\x00', + b'\x00\x00e!\x1f@ \x11', + b'\x00\x00e^\x00\x00\x00\x00', + b'\x00\x00e^\x1f@ !', + b'\x00\x00e`\x00\x00\x00\x00', + b'\x00\x00e`\x1f@ ', + b'\x00\x00e\x97\x00\x00\x00\x00', + b'\x00\x00e\x97\x1f@ 0', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb6"`A\x07', + b'\xb6\xa2`A\x07', + b'\xcb"`@\x07', + b'\xcb"`p\x07', + b'\xcf"`0\x07', + b'\xcf"`p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1a\xe6B1\x00', + b'\x1a\xe6F1\x00', + b'\x1a\xf6B0\x00', + b'\x1a\xf6B`\x00', + b'\x1a\xf6F`\x00', + b'\x1a\xf6b0\x00', + b'\x1a\xf6b`\x00', + b'\x1a\xf6f`\x00', + ], + }, + CAR.SUBARU_FORESTER_HYBRID: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 \x19T\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\x8d\xc2\x00\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eY\x1f@ !', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd2\xa1`r\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1b\xa7@a\x00', + ], + }, + CAR.SUBARU_FORESTER_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'm\x97\x14@', + b'}\x97\x14@', + ], + (Ecu.eps, 0x746, None): [ + b'm\xc0\x10\x00', + b'}\xc0\x10\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\xe9\x00\x00\x00\x00', + b'\x00\x00c\xe9\x1f@ \x03', + b'\x00\x00d5\x1f@ \t', + b'\x00\x00d\xd3\x1f@ \t', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa7"@0\x07', + b'\xa7"@p\x07', + b'\xa7)\xa0q\x07', + b'\xba"@@\x07', + b'\xba"@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1a\xf6F`\x00', + b'\xda\xf2`p\x00', + b'\xda\xf2`\x80\x00', + b'\xda\xfd\xe0\x80\x00', + b'\xdc\xf2@`\x00', + b'\xdc\xf2``\x00', + b'\xdc\xf2`\x80\x00', + b'\xdc\xf2`\x81\x00', + ], + }, + CAR.SUBARU_LEGACY_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'[\x97D\x00', + b'[\xba\xc4\x03', + b'k\x97D\x00', + b'k\x9aD\x00', + b'{\x97D\x00', + ], + (Ecu.eps, 0x746, None): [ + b'K\xb0\x00\x01', + b'[\xb0\x00\x01', + b'k\xb0\x00\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\x94\x1f@\x10\x08', + b'\x00\x00c\xb7\x1f@\x10\x16', + b'\x00\x00c\xec\x1f@ \x04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa0"@q\x07', + b'\xa0+@p\x07', + b'\xab*@r\x07', + b'\xab+@p\x07', + b'\xb4"@0\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbd\xf2\x00`\x00', + b'\xbe\xf2\x00p\x00', + b'\xbe\xfb\xc0p\x00', + b'\xbf\xf2\x00\x80\x00', + b'\xbf\xfb\xc0\x80\x00', + ], + }, + CAR.SUBARU_OUTBACK_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'[\xba\xac\x03', + b'[\xf7\xac\x00', + b'[\xf7\xac\x03', + b'[\xf7\xbc\x03', + b'k\x97\xac\x00', + b'k\x9a\xac\x00', + b'{\x97\xac\x00', + b'{\x9a\xac\x00', + ], + (Ecu.eps, 0x746, None): [ + b'K\xb0\x00\x00', + b'K\xb0\x00\x02', + b'[\xb0\x00\x00', + b'k\xb0\x00\x00', + b'{\xb0\x00\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\x90\x1f@\x10\x0e', + b'\x00\x00c\x94\x00\x00\x00\x00', + b'\x00\x00c\x94\x1f@\x10\x08', + b'\x00\x00c\xb7\x1f@\x10\x16', + b'\x00\x00c\xd1\x1f@\x10\x17', + b'\x00\x00c\xec\x1f@ \x04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa0"@\x80\x07', + b'\xa0*@q\x07', + b'\xa0*@u\x07', + b'\xa0+@@\x07', + b'\xa0bAq\x07', + b'\xab"@@\x07', + b'\xab"@s\x07', + b'\xab*@@\x07', + b'\xab+@@\x07', + b'\xb4"@0\x07', + b'\xb4"@p\x07', + b'\xb4"@r\x07', + b'\xb4+@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbd\xf2@`\x00', + b'\xbd\xf2@\x81\x00', + b'\xbd\xfb\xe0\x80\x00', + b'\xbe\xf2@p\x00', + b'\xbe\xf2@\x80\x00', + b'\xbe\xfb\xe0p\x00', + b'\xbf\xe2@\x80\x00', + b'\xbf\xf2@\x80\x00', + b'\xbf\xfb\xe0b\x00', + ], + }, + CAR.SUBARU_OUTBACK_PREGLOBAL_2018: { + (Ecu.abs, 0x7b0, None): [ + b'\x8b\x97\xac\x00', + b'\x8b\x97\xbc\x00', + b'\x8b\x99\xac\x00', + b'\x8b\x9a\xac\x00', + b'\x9b\x97\xac\x00', + b'\x9b\x97\xbe\x10', + b'\x9b\x9a\xac\x00', + ], + (Ecu.eps, 0x746, None): [ + b'{\xb0\x00\x00', + b'{\xb0\x00\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00df\x1f@ \n', + b'\x00\x00d\x95\x00\x00\x00\x00', + b'\x00\x00d\x95\x1f@ \x0f', + b'\x00\x00d\xfe\x00\x00\x00\x00', + b'\x00\x00d\xfe\x1f@ \x15', + b'\x00\x00e\x19\x1f@ \x15', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb5"@P\x07', + b'\xb5"@p\x07', + b'\xb5+@@\x07', + b'\xb5b@1\x07', + b'\xb5q\xe0@\x07', + b'\xc4"@0\x07', + b'\xc4+@0\x07', + b'\xc4b@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbb\xf2@`\x00', + b'\xbb\xfb\xe0`\x00', + b'\xbc\xaf\xe0`\x00', + b'\xbc\xe2@\x80\x00', + b'\xbc\xf2@\x80\x00', + b'\xbc\xf2@\x81\x00', + b'\xbc\xfb\xe0`\x00', + b'\xbc\xfb\xe0\x80\x00', + ], + }, + CAR.SUBARU_OUTBACK: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 \x06\x00', + b'\xa1 \x06\x01', + b'\xa1 \x06\x02', + b'\xa1 \x07\x00', + b'\xa1 \x07\x02', + b'\xa1 \x07\x03', + b'\xa1 \x08\x00', + b'\xa1 \x08\x01', + b'\xa1 \x08\x02', + b'\xa1 "\t\x00', + b'\xa1 "\t\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x1b\xc0\x10\x00', + b'\x9b\xc0\x10\x00', + b'\x9b\xc0\x10\x02', + b'\x9b\xc0 \x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eJ\x00\x00\x00\x00\x00\x00', + b'\x00\x00eJ\x00\x1f@ \x19\x00', + b'\x00\x00e\x80\x00\x1f@ \x19\x00', + b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', + b'\x00\x00e\x9a\x00\x1f@ 1\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xbc"`@\x07', + b'\xbc"`q\x07', + b'\xbc,\xa0q\x07', + b'\xbc,\xa0u\x07', + b'\xde"`0\x07', + b'\xde,\xa0@\x07', + b'\xe2"`0\x07', + b'\xe2"`p\x07', + b'\xe2"`q\x07', + b'\xe3,\xa0@\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xa5\xf6D@\x00', + b'\xa5\xfe\xf6@\x00', + b'\xa5\xfe\xf7@\x00', + b'\xa5\xfe\xf8@\x00', + b'\xa7\x8e\xf40\x00', + b'\xa7\xf6D@\x00', + b'\xa7\xfe\xf4@\x00', + ], + }, + CAR.SUBARU_FORESTER_2022: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 !v\x00', + b'\xa3 !x\x00', + b'\xa3 "v\x00', + b'\xa3 "x\x00', + ], + (Ecu.eps, 0x746, None): [ + b'-\xc0\x040', + b'-\xc0%0', + b'=\xc0%\x02', + b'=\xc04\x02', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x04!\x01\x1eD\x07!\x00\x04,', + b'\x04!\x08\x01.\x07!\x08\x022', + b'\r!\x08\x017\n!\x08\x003', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd5"`0\x07', + b'\xd5"a0\x07', + b'\xf1"`q\x07', + b'\xf1"aq\x07', + b'\xfa"ap\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1d\x86B0\x00', + b'\x1d\xf6B0\x00', + b'\x1e\x86B0\x00', + b'\x1e\x86F0\x00', + b'\x1e\xf6D0\x00', + ], + }, + CAR.SUBARU_OUTBACK_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 #\x14\x00', + b'\xa1 #\x17\x00', + ], + (Ecu.eps, 0x746, None): [ + b'+\xc0\x10\x11\x00', + b'+\xc0\x12\x11\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\t!\x08\x046\x05!\x08\x01/', + ], + (Ecu.engine, 0x7a2, None): [ + b'\xed,\xa0q\x07', + b'\xed,\xa2q\x07', + ], + (Ecu.transmission, 0x7a3, None): [ + b'\xa8\x8e\xf41\x00', + b'\xa8\xfe\xf41\x00', + ], + }, +} diff --git a/opendbc_repo/opendbc/car/subaru/interface.py b/opendbc_repo/opendbc/car/subaru/interface.py new file mode 100644 index 000000000000000..f16192cebc862fc --- /dev/null +++ b/opendbc_repo/opendbc/car/subaru/interface.py @@ -0,0 +1,100 @@ +from panda import Panda +from opendbc.car import get_safety_config, structs +from opendbc.car.disable_ecu import disable_ecu +from opendbc.car.interfaces import CarInterfaceBase +from opendbc.car.subaru.values import CAR, GLOBAL_ES_ADDR, SubaruFlags + + +class CarInterface(CarInterfaceBase): + + @staticmethod + def _get_params(ret: structs.CarParams, candidate: CAR, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "subaru" + ret.radarUnavailable = True + # for HYBRID CARS to be upstreamed, we need: + # - replacement for ES_Distance so we can cancel the cruise control + # - to find the Cruise_Activated bit from the car + # - proper panda safety setup (use the correct cruise_activated bit, throttle from Throttle_Hybrid, etc) + ret.dashcamOnly = bool(ret.flags & (SubaruFlags.PREGLOBAL | SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) + ret.autoResumeSng = False + + # Detect infotainment message sent from the camera + if not (ret.flags & SubaruFlags.PREGLOBAL) and 0x323 in fingerprint[2]: + ret.flags |= SubaruFlags.SEND_INFOTAINMENT.value + + if ret.flags & SubaruFlags.PREGLOBAL: + ret.enableBsm = 0x25c in fingerprint[0] + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.subaruPreglobal)] + else: + ret.enableBsm = 0x228 in fingerprint[0] + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.subaru)] + if ret.flags & SubaruFlags.GLOBAL_GEN2: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_GEN2 + + ret.steerLimitTimer = 0.4 + ret.steerActuatorDelay = 0.1 + + if ret.flags & SubaruFlags.LKAS_ANGLE: + ret.steerControlType = structs.CarParams.SteerControlType.angle + else: + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + if candidate in (CAR.SUBARU_ASCENT, CAR.SUBARU_ASCENT_2023): + ret.steerActuatorDelay = 0.3 # end-to-end angle controller + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kf = 0.00003 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.0025, 0.1], [0.00025, 0.01]] + + elif candidate == CAR.SUBARU_IMPREZA: + ret.steerActuatorDelay = 0.4 # end-to-end angle controller + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kf = 0.00005 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.3], [0.02, 0.03]] + + elif candidate == CAR.SUBARU_IMPREZA_2020: + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kf = 0.00005 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] + + elif candidate == CAR.SUBARU_CROSSTREK_HYBRID: + ret.steerActuatorDelay = 0.1 + + elif candidate in (CAR.SUBARU_FORESTER, CAR.SUBARU_FORESTER_2022, CAR.SUBARU_FORESTER_HYBRID): + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kf = 0.000038 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] + + elif candidate in (CAR.SUBARU_OUTBACK, CAR.SUBARU_LEGACY, CAR.SUBARU_OUTBACK_2023): + ret.steerActuatorDelay = 0.1 + + elif candidate in (CAR.SUBARU_FORESTER_PREGLOBAL, CAR.SUBARU_OUTBACK_PREGLOBAL_2018): + ret.safetyConfigs[0].safetyParam = Panda.FLAG_SUBARU_PREGLOBAL_REVERSED_DRIVER_TORQUE # Outback 2018-2019 and Forester have reversed driver torque signal + + elif candidate == CAR.SUBARU_LEGACY_PREGLOBAL: + ret.steerActuatorDelay = 0.15 + + elif candidate == CAR.SUBARU_OUTBACK_PREGLOBAL: + pass + else: + raise ValueError(f"unknown car: {candidate}") + + ret.experimentalLongitudinalAvailable = not (ret.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.PREGLOBAL | + SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) + ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable + + if ret.flags & SubaruFlags.GLOBAL_GEN2 and ret.openpilotLongitudinalControl: + ret.flags |= SubaruFlags.DISABLE_EYESIGHT.value + + if ret.openpilotLongitudinalControl: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_LONG + + return ret + + @staticmethod + def init(CP, can_recv, can_send): + if CP.flags & SubaruFlags.DISABLE_EYESIGHT: + disable_ecu(can_recv, can_send, bus=2, addr=GLOBAL_ES_ADDR, com_cont_req=b'\x28\x03\x01') diff --git a/opendbc_repo/opendbc/car/subaru/radar_interface.py b/opendbc_repo/opendbc/car/subaru/radar_interface.py new file mode 100644 index 000000000000000..6e552bf618fda6f --- /dev/null +++ b/opendbc_repo/opendbc/car/subaru/radar_interface.py @@ -0,0 +1,4 @@ +from opendbc.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/selfdrive/car/subaru/subarucan.py b/opendbc_repo/opendbc/car/subaru/subarucan.py similarity index 97% rename from selfdrive/car/subaru/subarucan.py rename to opendbc_repo/opendbc/car/subaru/subarucan.py index 86d39ff885f74ae..83340dc1f8d4d5d 100644 --- a/selfdrive/car/subaru/subarucan.py +++ b/opendbc_repo/opendbc/car/subaru/subarucan.py @@ -1,7 +1,7 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.values import CanBus +from opendbc.car import structs +from opendbc.car.subaru.values import CanBus -VisualAlert = car.CarControl.HUDControl.VisualAlert +VisualAlert = structs.CarControl.HUDControl.VisualAlert def create_steering_control(packer, apply_steer, steer_req): @@ -279,7 +279,7 @@ def create_es_static_2(packer): # *** Subaru Pre-global *** def subaru_preglobal_checksum(packer, values, addr, checksum_byte=7): - dat = packer.make_can_msg(addr, 0, values)[2] + dat = packer.make_can_msg(addr, 0, values)[1] return (sum(dat[:checksum_byte]) + sum(dat[checksum_byte+1:])) % 256 diff --git a/selfdrive/car/toyota/__init__.py b/opendbc_repo/opendbc/car/subaru/tests/__init__.py similarity index 100% rename from selfdrive/car/toyota/__init__.py rename to opendbc_repo/opendbc/car/subaru/tests/__init__.py diff --git a/opendbc_repo/opendbc/car/subaru/tests/test_subaru.py b/opendbc_repo/opendbc/car/subaru/tests/test_subaru.py new file mode 100644 index 000000000000000..7f3d9bb3c5b2c64 --- /dev/null +++ b/opendbc_repo/opendbc/car/subaru/tests/test_subaru.py @@ -0,0 +1,10 @@ +from opendbc.car.subaru.fingerprints import FW_VERSIONS + + +class TestSubaruFingerprint: + def test_fw_version_format(self): + for platform, fws_per_ecu in FW_VERSIONS.items(): + for (ecu, _, _), fws in fws_per_ecu.items(): + fw_size = len(fws[0]) + for fw in fws: + assert len(fw) == fw_size, f"{platform} {ecu}: {len(fw)} {fw_size}" diff --git a/opendbc_repo/opendbc/car/subaru/values.py b/opendbc_repo/opendbc/car/subaru/values.py new file mode 100644 index 000000000000000..c7f93f9fae55c58 --- /dev/null +++ b/opendbc_repo/opendbc/car/subaru/values.py @@ -0,0 +1,277 @@ +from dataclasses import dataclass, field +from enum import Enum, IntFlag + +from panda import uds +from opendbc.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Tool, Column +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 + +Ecu = CarParams.Ecu + + +class CarControllerParams: + def __init__(self, CP): + self.STEER_STEP = 2 # how often we update the steer cmd + self.STEER_DELTA_UP = 50 # torque increase per refresh, 0.8s to max + self.STEER_DELTA_DOWN = 70 # torque decrease per refresh + self.STEER_DRIVER_ALLOWANCE = 60 # allowed driver torque before start limiting + self.STEER_DRIVER_MULTIPLIER = 50 # weight driver torque heavily + self.STEER_DRIVER_FACTOR = 1 # from dbc + + if CP.flags & SubaruFlags.GLOBAL_GEN2: + # TODO: lower rate limits, this reaches min/max in 0.5s which negatively affects tuning + self.STEER_MAX = 1000 + self.STEER_DELTA_UP = 40 + self.STEER_DELTA_DOWN = 40 + elif CP.carFingerprint == CAR.SUBARU_IMPREZA_2020: + self.STEER_DELTA_UP = 35 + self.STEER_MAX = 1439 + else: + self.STEER_MAX = 2047 + + THROTTLE_MIN = 808 + THROTTLE_MAX = 3400 + + THROTTLE_INACTIVE = 1818 # corresponds to zero acceleration + THROTTLE_ENGINE_BRAKE = 808 # while braking, eyesight sets throttle to this, probably for engine braking + + BRAKE_MIN = 0 + BRAKE_MAX = 600 # about -3.5m/s2 from testing + + RPM_MIN = 0 + RPM_MAX = 3600 + + RPM_INACTIVE = 600 # a good base rpm for zero acceleration + + THROTTLE_LOOKUP_BP = [0, 2] + THROTTLE_LOOKUP_V = [THROTTLE_INACTIVE, THROTTLE_MAX] + + RPM_LOOKUP_BP = [0, 2] + RPM_LOOKUP_V = [RPM_INACTIVE, RPM_MAX] + + BRAKE_LOOKUP_BP = [-3.5, 0] + BRAKE_LOOKUP_V = [BRAKE_MAX, BRAKE_MIN] + + +class SubaruFlags(IntFlag): + # Detected flags + SEND_INFOTAINMENT = 1 + DISABLE_EYESIGHT = 2 + + # Static flags + GLOBAL_GEN2 = 4 + + # Cars that temporarily fault when steering angle rate is greater than some threshold. + # Appears to be all torque-based cars produced around 2019 - present + STEER_RATE_LIMITED = 8 + PREGLOBAL = 16 + HYBRID = 32 + LKAS_ANGLE = 64 + + +GLOBAL_ES_ADDR = 0x787 +GEN2_ES_BUTTONS_DID = b'\x11\x30' + + +class CanBus: + main = 0 + alt = 1 + camera = 2 + + +class Footnote(Enum): + GLOBAL = CarFootnote( + "In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.", + Column.PACKAGE) + EXP_LONG = CarFootnote( + "Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.", + Column.LONGITUDINAL) + + +@dataclass +class SubaruCarDocs(CarDocs): + package: str = "EyeSight Driver Assistance" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.subaru_a])) + footnotes: list[Enum] = field(default_factory=lambda: [Footnote.GLOBAL]) + + def init_make(self, CP: CarParams): + self.car_parts.parts.extend([Tool.socket_8mm_deep, Tool.pry_tool]) + + if CP.experimentalLongitudinalAvailable: + self.footnotes.append(Footnote.EXP_LONG) + + +@dataclass +class SubaruPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('subaru_global_2017_generated', None)) + + def init(self): + if self.flags & SubaruFlags.HYBRID: + self.dbc_dict = dbc_dict('subaru_global_2020_hybrid_generated', None) + + +@dataclass +class SubaruGen2PlatformConfig(SubaruPlatformConfig): + def init(self): + super().init() + self.flags |= SubaruFlags.GLOBAL_GEN2 + if not (self.flags & SubaruFlags.LKAS_ANGLE): + self.flags |= SubaruFlags.STEER_RATE_LIMITED + + +class CAR(Platforms): + # Global platform + SUBARU_ASCENT = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Ascent 2019-21", "All")], + CarSpecs(mass=2031, wheelbase=2.89, steerRatio=13.5), + ) + SUBARU_OUTBACK = SubaruGen2PlatformConfig( + [SubaruCarDocs("Subaru Outback 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), + ) + SUBARU_LEGACY = SubaruGen2PlatformConfig( + [SubaruCarDocs("Subaru Legacy 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], + SUBARU_OUTBACK.specs, + ) + SUBARU_IMPREZA = SubaruPlatformConfig( + [ + SubaruCarDocs("Subaru Impreza 2017-19"), + SubaruCarDocs("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), + SubaruCarDocs("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), + ], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=15), + ) + SUBARU_IMPREZA_2020 = SubaruPlatformConfig( + [ + SubaruCarDocs("Subaru Impreza 2020-22"), + SubaruCarDocs("Subaru Crosstrek 2020-23"), + SubaruCarDocs("Subaru XV 2020-21"), + ], + CarSpecs(mass=1480, wheelbase=2.67, steerRatio=17), + flags=SubaruFlags.STEER_RATE_LIMITED, + ) + # TODO: is there an XV and Impreza too? + SUBARU_CROSSTREK_HYBRID = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Crosstrek Hybrid 2020", car_parts=CarParts.common([CarHarness.subaru_b]))], + CarSpecs(mass=1668, wheelbase=2.67, steerRatio=17), + flags=SubaruFlags.HYBRID, + ) + SUBARU_FORESTER = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Forester 2019-21", "All")], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), + flags=SubaruFlags.STEER_RATE_LIMITED, + ) + SUBARU_FORESTER_HYBRID = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Forester Hybrid 2020")], + SUBARU_FORESTER.specs, + flags=SubaruFlags.HYBRID, + ) + # Pre-global + SUBARU_FORESTER_PREGLOBAL = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Forester 2017-18")], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=20), + dbc_dict('subaru_forester_2017_generated', None), + flags=SubaruFlags.PREGLOBAL, + ) + SUBARU_LEGACY_PREGLOBAL = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Legacy 2015-18")], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=12.5), + dbc_dict('subaru_outback_2015_generated', None), + flags=SubaruFlags.PREGLOBAL, + ) + SUBARU_OUTBACK_PREGLOBAL = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Outback 2015-17")], + SUBARU_FORESTER_PREGLOBAL.specs, + dbc_dict('subaru_outback_2015_generated', None), + flags=SubaruFlags.PREGLOBAL, + ) + SUBARU_OUTBACK_PREGLOBAL_2018 = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Outback 2018-19")], + SUBARU_FORESTER_PREGLOBAL.specs, + dbc_dict('subaru_outback_2019_generated', None), + flags=SubaruFlags.PREGLOBAL, + ) + # Angle LKAS + SUBARU_FORESTER_2022 = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Forester 2022-24", "All", car_parts=CarParts.common([CarHarness.subaru_c]))], + SUBARU_FORESTER.specs, + flags=SubaruFlags.LKAS_ANGLE, + ) + SUBARU_OUTBACK_2023 = SubaruGen2PlatformConfig( + [SubaruCarDocs("Subaru Outback 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], + SUBARU_OUTBACK.specs, + flags=SubaruFlags.LKAS_ANGLE, + ) + SUBARU_ASCENT_2023 = SubaruGen2PlatformConfig( + [SubaruCarDocs("Subaru Ascent 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], + SUBARU_ASCENT.specs, + flags=SubaruFlags.LKAS_ANGLE, + ) + + +SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) +SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) + +# The EyeSight ECU takes 10s to respond to SUBARU_VERSION_REQUEST properly, +# log this alternate manufacturer-specific query +SUBARU_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf100) +SUBARU_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(0xf100) + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], + logging=True, + ), + # Non-OBD requests + # Some Eyesight modules fail on TESTER_PRESENT_REQUEST + # TODO: check if this resolves the fingerprinting issue for the 2023 Ascent and other new Subaru cars + Request( + [SUBARU_VERSION_REQUEST], + [SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera], + bus=0, + ), + Request( + [SUBARU_ALT_VERSION_REQUEST], + [SUBARU_ALT_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera], + bus=0, + logging=True, + ), + Request( + [StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera], + bus=0, + logging=True, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], + bus=0, + ), + # GEN2 powertrain bus query + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], + bus=1, + obd_multiplexing=False, + ), + ], + # We don't get the EPS from non-OBD queries on GEN2 cars. Note that we still attempt to match when it exists + non_essential_ecus={ + Ecu.eps: list(CAR.with_flags(SubaruFlags.GLOBAL_GEN2)), + } +) + +DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/toyota/tests/__init__.py b/opendbc_repo/opendbc/car/tesla/__init__.py similarity index 100% rename from selfdrive/car/toyota/tests/__init__.py rename to opendbc_repo/opendbc/car/tesla/__init__.py diff --git a/opendbc_repo/opendbc/car/tesla/carcontroller.py b/opendbc_repo/opendbc/car/tesla/carcontroller.py new file mode 100644 index 000000000000000..a0396f48609aef2 --- /dev/null +++ b/opendbc_repo/opendbc/car/tesla/carcontroller.py @@ -0,0 +1,59 @@ +from opendbc.car.common.numpy_fast import clip +from opendbc.can.packer import CANPacker +from opendbc.car import apply_std_steer_angle_limits +from opendbc.car.interfaces import CarControllerBase +from opendbc.car.tesla.teslacan import TeslaCAN +from opendbc.car.tesla.values import CarControllerParams + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + self.CP = CP + self.frame = 0 + self.apply_angle_last = 0 + self.packer = CANPacker(dbc_name) + self.tesla_can = TeslaCAN(self.packer) + + def update(self, CC, CS, now_nanos): + + actuators = CC.actuators + can_sends = [] + + # Disengage and allow for user override + hands_on_fault = CS.hands_on_level >= 3 + lkas_enabled = CC.latActive and not hands_on_fault + + if self.frame % 2 == 0: + if lkas_enabled: + # Angular rate limit based on speed + apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo, CarControllerParams) + + # To not fault the EPS + apply_angle = clip(apply_angle, CS.out.steeringAngleDeg - 20, CS.out.steeringAngleDeg + 20) + else: + apply_angle = CS.out.steeringAngleDeg + + self.apply_angle_last = apply_angle + can_sends.append(self.tesla_can.create_steering_control(apply_angle, lkas_enabled, (self.frame // 2) % 16)) + + if self.frame % 10 == 0: + can_sends.append(self.tesla_can.create_steering_allowed((self.frame // 10) % 16)) + + # Longitudinal control + if self.CP.openpilotLongitudinalControl and self.frame % 4 == 0: + state = 4 if not hands_on_fault else 13 # 4=ACC_ON, 13=ACC_CANCEL_GENERIC_SILENT + accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + cntr = (self.frame // 4) % 8 + can_sends.append(self.tesla_can.create_longitudinal_command(state, accel, cntr, CC.longActive)) + + # Increment counter so cancel is prioritized even without openpilot longitudinal + if hands_on_fault and not self.CP.openpilotLongitudinalControl: + cntr = (CS.das_control["DAS_controlCounter"] + 1) % 8 + can_sends.append(self.tesla_can.create_longitudinal_command(13, 0, cntr, False)) + + # TODO: HUD control + new_actuators = actuators.as_builder() + new_actuators.steeringAngleDeg = self.apply_angle_last + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/tesla/carstate.py b/opendbc_repo/opendbc/car/tesla/carstate.py new file mode 100644 index 000000000000000..8cc1a8237f2ce36 --- /dev/null +++ b/opendbc_repo/opendbc/car/tesla/carstate.py @@ -0,0 +1,109 @@ +import copy +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.interfaces import CarStateBase +from opendbc.car.tesla.values import DBC, CANBUS, GEAR_MAP + +ButtonType = structs.CarState.ButtonEvent.Type + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + self.can_define = CANDefine(DBC[CP.carFingerprint]['pt']) + + self.hands_on_level = 0 + self.das_control = None + + def update(self, cp, cp_cam, *_) -> structs.CarState: + ret = structs.CarState() + + # Vehicle speed + ret.vEgoRaw = cp.vl["DI_speed"]["DI_vehicleSpeed"] * CV.KPH_TO_MS + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + + # Gas pedal + pedal_status = cp.vl["DI_systemStatus"]["DI_accelPedalPos"] + ret.gas = pedal_status / 100.0 + ret.gasPressed = (pedal_status > 0) + + # Brake pedal + ret.brake = 0 + ret.brakePressed = cp.vl["IBST_status"]["IBST_driverBrakeApply"] == 2 + + # Steering wheel + epas_status = cp.vl["EPAS3S_sysStatus"] + self.hands_on_level = epas_status["EPAS3S_handsOnLevel"] + ret.steeringAngleDeg = -epas_status["EPAS3S_internalSAS"] + ret.steeringRateDeg = -cp_cam.vl["SCCM_steeringAngleSensor"]["SCCM_steeringAngleSpeed"] + ret.steeringTorque = -epas_status["EPAS3S_torsionBarTorque"] + + ret.steeringPressed = self.hands_on_level > 0 + eac_status = self.can_define.dv["EPAS3S_sysStatus"]["EPAS3S_eacStatus"].get(int(epas_status["EPAS3S_eacStatus"]), None) + ret.steerFaultPermanent = eac_status == "EAC_FAULT" + ret.steerFaultTemporary = eac_status == "EAC_INHIBITED" + + # Cruise state + cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp.vl["DI_state"]["DI_cruiseState"]), None) + speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp.vl["DI_state"]["DI_speedUnits"]), None) + + ret.cruiseState.enabled = cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL") + if speed_units == "KPH": + ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.KPH_TO_MS + elif speed_units == "MPH": + ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.MPH_TO_MS + ret.cruiseState.available = cruise_state == "STANDBY" or ret.cruiseState.enabled + ret.cruiseState.standstill = False # This needs to be false, since we can resume from stop without sending anything special + ret.standstill = cruise_state == "STANDSTILL" + + # Gear + ret.gearShifter = GEAR_MAP[self.can_define.dv["DI_systemStatus"]["DI_gear"].get(int(cp.vl["DI_systemStatus"]["DI_gear"]), "DI_GEAR_INVALID")] + + # Doors + ret.doorOpen = cp.vl["UI_warning"]["anyDoorOpen"] == 1 + + # Blinkers + ret.leftBlinker = cp.vl["UI_warning"]["leftBlinkerOn"] != 0 + ret.rightBlinker = cp.vl["UI_warning"]["rightBlinkerOn"] != 0 + + # Seatbelt + ret.seatbeltUnlatched = cp.vl["UI_warning"]["buckleStatus"] != 1 + + # Blindspot + ret.leftBlindspot = cp_cam.vl["DAS_status"]["DAS_blindSpotRearLeft"] != 0 + ret.rightBlindspot = cp_cam.vl["DAS_status"]["DAS_blindSpotRearRight"] != 0 + + # AEB + ret.stockAeb = cp_cam.vl["DAS_control"]["DAS_aebEvent"] == 1 + + # Buttons # ToDo: add Gap adjust button + + # Messages needed by carcontroller + self.das_control = copy.copy(cp_cam.vl["DAS_control"]) + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("DI_speed", 50), + ("DI_systemStatus", 100), + ("IBST_status", 25), + ("DI_state", 10), + ("EPAS3S_sysStatus", 100), + ("UI_warning", 10) + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], messages, CANBUS.party) + + @staticmethod + def get_cam_can_parser(CP): + messages = [ + ("DAS_control", 25), + ("DAS_status", 2), + ("SCCM_steeringAngleSensor", 100), + ] + + return CANParser(DBC[CP.carFingerprint]['pt'], messages, CANBUS.autopilot_party) diff --git a/opendbc_repo/opendbc/car/tesla/fingerprints.py b/opendbc_repo/opendbc/car/tesla/fingerprints.py new file mode 100644 index 000000000000000..81cb49a2c886dd4 --- /dev/null +++ b/opendbc_repo/opendbc/car/tesla/fingerprints.py @@ -0,0 +1,28 @@ +from opendbc.car.structs import CarParams +from opendbc.car.tesla.values import CAR + +Ecu = CarParams.Ecu + +FW_VERSIONS = { + CAR.TESLA_MODEL_3: { + (Ecu.eps, 0x730, None): [ + b'TeM3_E014p10_0.0.0 (16),E014.17.00', + b'TeM3_E014p10_0.0.0 (16),EL014.17.00', + b'TeMYG4_DCS_Update_0.0.0 (13),E4014.28.1', + b'TeMYG4_DCS_Update_0.0.0 (9),E4014.26.0', + b'TeMYG4_Main_0.0.0 (59),E4H014.29.0', + b'TeMYG4_SingleECU_0.0.0 (33),E4S014.27', + ], + }, + CAR.TESLA_MODEL_Y: { + (Ecu.eps, 0x730, None): [ + b'TeM3_E014p10_0.0.0 (16),Y002.18.00', + b'TeM3_ES014p11_0.0.0 (16),YS002.17', + b'TeM3_ES014p11_0.0.0 (25),YS002.19.0', + b'TeMYG4_DCS_Update_0.0.0 (13),Y4002.27.1', + b'TeMYG4_DCS_Update_0.0.0 (13),Y4P002.27.1', + b'TeMYG4_DCS_Update_0.0.0 (9),Y4P002.25.0', + b'TeMYG4_SingleECU_0.0.0 (33),Y4S002.26', + ], + }, +} diff --git a/opendbc_repo/opendbc/car/tesla/interface.py b/opendbc_repo/opendbc/car/tesla/interface.py new file mode 100755 index 000000000000000..70bca37b9cf95ac --- /dev/null +++ b/opendbc_repo/opendbc/car/tesla/interface.py @@ -0,0 +1,27 @@ +#!/usr/bin/env python3 +from opendbc.car import structs +from opendbc.car.interfaces import CarInterfaceBase + + +class CarInterface(CarInterfaceBase): + + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "tesla" + + # Needs safety validation and final testing before pulling out of dashcam + ret.dashcamOnly = True + + # Not merged yet + #ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.tesla)] + #ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TESLA_LONG_CONTROL + + ret.steerLimitTimer = 1.0 + ret.steerActuatorDelay = 0.25 + + ret.steerControlType = structs.CarParams.SteerControlType.angle + ret.radarUnavailable = True + + ret.openpilotLongitudinalControl = True + + return ret diff --git a/opendbc_repo/opendbc/car/tesla/radar_interface.py b/opendbc_repo/opendbc/car/tesla/radar_interface.py new file mode 100644 index 000000000000000..6e552bf618fda6f --- /dev/null +++ b/opendbc_repo/opendbc/car/tesla/radar_interface.py @@ -0,0 +1,4 @@ +from opendbc.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/opendbc_repo/opendbc/car/tesla/teslacan.py b/opendbc_repo/opendbc/car/tesla/teslacan.py new file mode 100644 index 000000000000000..f71043bde0b11e7 --- /dev/null +++ b/opendbc_repo/opendbc/car/tesla/teslacan.py @@ -0,0 +1,51 @@ +from opendbc.car.interfaces import V_CRUISE_MAX +from opendbc.car.tesla.values import CANBUS, CarControllerParams + + +class TeslaCAN: + def __init__(self, packer): + self.packer = packer + + @staticmethod + def checksum(msg_id, dat): + ret = (msg_id & 0xFF) + ((msg_id >> 8) & 0xFF) + ret += sum(dat) + return ret & 0xFF + + def create_steering_control(self, angle, enabled, counter): + values = { + "DAS_steeringAngleRequest": -angle, + "DAS_steeringHapticRequest": 0, + "DAS_steeringControlType": 1 if enabled else 0, + "DAS_steeringControlCounter": counter, + } + + data = self.packer.make_can_msg("DAS_steeringControl", CANBUS.party, values)[1] + values["DAS_steeringControlChecksum"] = self.checksum(0x488, data[:3]) + return self.packer.make_can_msg("DAS_steeringControl", CANBUS.party, values) + + def create_longitudinal_command(self, acc_state, accel, cntr, active): + values = { + "DAS_setSpeed": 0 if (accel < 0 or not active) else V_CRUISE_MAX, + "DAS_accState": acc_state, + "DAS_aebEvent": 0, + "DAS_jerkMin": CarControllerParams.JERK_LIMIT_MIN, + "DAS_jerkMax": CarControllerParams.JERK_LIMIT_MAX, + "DAS_accelMin": accel, + "DAS_accelMax": max(accel, 0), + "DAS_controlCounter": cntr, + "DAS_controlChecksum": 0, + } + data = self.packer.make_can_msg("DAS_control", CANBUS.party, values)[1] + values["DAS_controlChecksum"] = self.checksum(0x2b9, data[:7]) + return self.packer.make_can_msg("DAS_control", CANBUS.party, values) + + def create_steering_allowed(self, counter): + values = { + "APS_eacAllow": 1, + "APS_eacMonitorCounter": counter, + } + + data = self.packer.make_can_msg("APS_eacMonitor", CANBUS.party, values)[1] + values["APS_eacMonitorChecksum"] = self.checksum(0x27d, data[:2]) + return self.packer.make_can_msg("APS_eacMonitor", CANBUS.party, values) diff --git a/opendbc_repo/opendbc/car/tesla/values.py b/opendbc_repo/opendbc/car/tesla/values.py new file mode 100644 index 000000000000000..10c8fcd066fc52f --- /dev/null +++ b/opendbc_repo/opendbc/car/tesla/values.py @@ -0,0 +1,63 @@ +from enum import IntFlag +from opendbc.car.structs import CarParams +from opendbc.car import structs +from opendbc.car import AngleRateLimit, CarSpecs, PlatformConfig, Platforms, dbc_dict +from opendbc.car.docs_definitions import CarDocs +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = CarParams.Ecu + +class CAR(Platforms): + TESLA_MODEL_3 = PlatformConfig( + [CarDocs("Tesla Model 3", "All")], + CarSpecs(mass=1899., wheelbase=2.875, steerRatio=12.0), + dbc_dict('tesla_model3_party', None) + ) + TESLA_MODEL_Y = PlatformConfig( + [CarDocs("Tesla Model Y", "All")], + CarSpecs(mass=2072., wheelbase=2.890, steerRatio=12.0), + dbc_dict('tesla_model3_party', None) + ) + + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.SUPPLIER_SOFTWARE_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.SUPPLIER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.eps], + rx_offset=0x08, + bus=0, + ) + ] +) + +class CANBUS: + party = 0 + vehicle = 1 + autopilot_party = 2 + + +GEAR_MAP = { + "DI_GEAR_INVALID": structs.CarState.GearShifter.unknown, + "DI_GEAR_P": structs.CarState.GearShifter.park, + "DI_GEAR_R": structs.CarState.GearShifter.reverse, + "DI_GEAR_N": structs.CarState.GearShifter.neutral, + "DI_GEAR_D": structs.CarState.GearShifter.drive, + "DI_GEAR_SNA": structs.CarState.GearShifter.unknown, +} + +class CarControllerParams: + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 1.6, .3]) + ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 7.0, 0.8]) + ACCEL_MIN = -3.48 # m/s^2 + ACCEL_MAX = 2.0 # m/s^2 + JERK_LIMIT_MAX = 5 + JERK_LIMIT_MIN = -5 + + +class TeslaFlags(IntFlag): + FLAG_TESLA_LONG_CONTROL = 1 + + +DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/volkswagen/__init__.py b/opendbc_repo/opendbc/car/tests/__init__.py similarity index 100% rename from selfdrive/car/volkswagen/__init__.py rename to opendbc_repo/opendbc/car/tests/__init__.py diff --git a/selfdrive/car/tests/routes.py b/opendbc_repo/opendbc/car/tests/routes.py old mode 100755 new mode 100644 similarity index 92% rename from selfdrive/car/tests/routes.py rename to opendbc_repo/opendbc/car/tests/routes.py index dd3a8f633d26935..2e1eca29a0d9860 --- a/selfdrive/car/tests/routes.py +++ b/opendbc_repo/opendbc/car/tests/routes.py @@ -1,22 +1,23 @@ -#!/usr/bin/env python3 from typing import NamedTuple -from openpilot.selfdrive.car.chrysler.values import CAR as CHRYSLER -from openpilot.selfdrive.car.gm.values import CAR as GM -from openpilot.selfdrive.car.ford.values import CAR as FORD -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.hyundai.values import CAR as HYUNDAI -from openpilot.selfdrive.car.nissan.values import CAR as NISSAN -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA -from openpilot.selfdrive.car.subaru.values import CAR as SUBARU -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.values import Platform -from openpilot.selfdrive.car.volkswagen.values import CAR as VOLKSWAGEN -from openpilot.selfdrive.car.tesla.values import CAR as TESLA -from openpilot.selfdrive.car.body.values import CAR as COMMA +from opendbc.car.chrysler.values import CAR as CHRYSLER +from opendbc.car.gm.values import CAR as GM +from opendbc.car.ford.values import CAR as FORD +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.hyundai.values import CAR as HYUNDAI +from opendbc.car.nissan.values import CAR as NISSAN +from opendbc.car.mazda.values import CAR as MAZDA +from opendbc.car.mock.values import CAR as MOCK +from opendbc.car.subaru.values import CAR as SUBARU +from opendbc.car.tesla.values import CAR as TESLA +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.values import Platform +from opendbc.car.volkswagen.values import CAR as VOLKSWAGEN +from opendbc.car.body.values import CAR as COMMA -# TODO: add routes for these cars +# FIXME: add routes for these cars non_tested_cars = [ + MOCK.MOCK, FORD.FORD_F_150_MK14, GM.CADILLAC_ATS, GM.HOLDEN_ASTRA, @@ -25,6 +26,8 @@ HONDA.HONDA_ODYSSEY_CHN, VOLKSWAGEN.VOLKSWAGEN_CRAFTER_MK2, # need a route from an ACC-equipped Crafter SUBARU.SUBARU_FORESTER_HYBRID, + TESLA.TESLA_MODEL_3, + TESLA.TESLA_MODEL_Y, ] @@ -39,7 +42,7 @@ class CarTestRoute(NamedTuple): CarTestRoute("0c94aa1e1296d7c6|2021-05-05--19-48-37", CHRYSLER.JEEP_GRAND_CHEROKEE), CarTestRoute("91dfedae61d7bd75|2021-05-22--20-07-52", CHRYSLER.JEEP_GRAND_CHEROKEE_2019), - CarTestRoute("420a8e183f1aed48|2020-03-05--07-15-29", CHRYSLER.CHRYSLER_PACIFICA_2017_HYBRID), + CarTestRoute("420a8e183f1aed48|2020-03-05--07-15-29", CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID), # 2017 CarTestRoute("43a685a66291579b|2021-05-27--19-47-29", CHRYSLER.CHRYSLER_PACIFICA_2018), CarTestRoute("378472f830ee7395|2021-05-28--07-38-43", CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID), CarTestRoute("8190c7275a24557b|2020-01-29--08-33-58", CHRYSLER.CHRYSLER_PACIFICA_2019_HYBRID), @@ -70,6 +73,9 @@ class CarTestRoute(NamedTuple): CarTestRoute("555d4087cf86aa91|2022-12-02--12-15-07", GM.CHEVROLET_BOLT_EUV, segment=14), # Bolt EV CarTestRoute("38aa7da107d5d252|2022-08-15--16-01-12", GM.CHEVROLET_SILVERADO), CarTestRoute("5085c761395d1fe6|2023-04-07--18-20-06", GM.CHEVROLET_TRAILBLAZER), + CarTestRoute("162796f1469f2f1b/00000005--6f334eda14", GM.CADILLAC_XT4), + CarTestRoute("477dd485611d1e6e/00000009--85fc06e10a", GM.CHEVROLET_VOLT_2019), + CarTestRoute("a40976dc9f28ba62/0000001f--160e210119", GM.CHEVROLET_TRAVERSE), CarTestRoute("0e7a2ba168465df5|2020-10-18--14-14-22", HONDA.ACURA_RDX_3G), CarTestRoute("a74b011b32b51b56|2020-07-26--17-09-36", HONDA.HONDA_CIVIC), @@ -105,7 +111,10 @@ class CarTestRoute(NamedTuple): CarTestRoute("b5d6dc830ad63071|2022-12-12--21-28-25", HYUNDAI.GENESIS_GV60_EV_1ST_GEN, segment=12), CarTestRoute("70c5bec28ec8e345|2020-08-08--12-22-23", HYUNDAI.GENESIS_G70), CarTestRoute("ca4de5b12321bd98|2022-10-18--21-15-59", HYUNDAI.GENESIS_GV70_1ST_GEN), + CarTestRoute("afe09b9f5d3f3548/00000011--15fefe1c50", HYUNDAI.GENESIS_GV70_ELECTRIFIED_1ST_GEN), + CarTestRoute("afe09b9f5d3f3548/0000001b--a1129a4a15", HYUNDAI.GENESIS_GV70_ELECTRIFIED_1ST_GEN), # openpilot longitudinal enabled CarTestRoute("6b301bf83f10aa90|2020-11-22--16-45-07", HYUNDAI.GENESIS_G80), + CarTestRoute("66eaa6c3b6b2afc6/00000009--3a5199aabe", HYUNDAI.GENESIS_G80_2ND_GEN_FL), # HDA2 CarTestRoute("0bbe367c98fa1538|2023-09-16--00-16-49", HYUNDAI.HYUNDAI_CUSTIN_1ST_GEN), CarTestRoute("f0709d2bc6ca451f|2022-10-15--08-13-54", HYUNDAI.HYUNDAI_SANTA_CRUZ_1ST_GEN), CarTestRoute("4dbd55df87507948|2022-03-01--09-45-38", HYUNDAI.HYUNDAI_SANTA_FE), @@ -197,6 +206,8 @@ class CarTestRoute(NamedTuple): CarTestRoute("ad5a3fa719bc2f83|2023-10-17--19-48-42", TOYOTA.TOYOTA_RAV4_TSS2_2023), CarTestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.TOYOTA_RAV4_TSS2), # hybrid CarTestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.TOYOTA_RAV4_TSS2_2022), # hybrid + CarTestRoute("20ba9ade056a8c7b|2021-02-08--21-57-35", TOYOTA.TOYOTA_RAV4_PRIME), # SecOC + CarTestRoute("8bfb000e03b2a257/00000004--f9eee5f52e", TOYOTA.TOYOTA_SIENNA_4TH_GEN), # SecOC CarTestRoute("7a31f030957b9c85|2023-04-01--14-12-51", TOYOTA.LEXUS_ES), CarTestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ES), # hybrid CarTestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), @@ -225,7 +236,6 @@ class CarTestRoute(NamedTuple): CarTestRoute("cd9cff4b0b26c435|2021-05-13--15-12-39", TOYOTA.TOYOTA_CHR), CarTestRoute("57858ede0369a261|2021-05-18--20-34-20", TOYOTA.TOYOTA_CHR), # hybrid CarTestRoute("ea8fbe72b96a185c|2023-02-08--15-11-46", TOYOTA.TOYOTA_CHR_TSS2), - CarTestRoute("ea8fbe72b96a185c|2023-02-22--09-20-34", TOYOTA.TOYOTA_CHR_TSS2), # openpilot longitudinal, with smartDSU CarTestRoute("6719965b0e1d1737|2023-02-09--22-44-05", TOYOTA.TOYOTA_CHR_TSS2), # hybrid CarTestRoute("6719965b0e1d1737|2023-08-29--06-40-05", TOYOTA.TOYOTA_CHR_TSS2), # hybrid, openpilot longitudinal, radar disabled CarTestRoute("14623aae37e549f3|2021-10-24--01-20-49", TOYOTA.TOYOTA_PRIUS_V), @@ -235,6 +245,7 @@ class CarTestRoute(NamedTuple): CarTestRoute("ffcd23abbbd02219|2024-02-28--14-59-38", VOLKSWAGEN.VOLKSWAGEN_CADDY_MK3), CarTestRoute("cae14e88932eb364|2021-03-26--14-43-28", VOLKSWAGEN.VOLKSWAGEN_GOLF_MK7), # Stock ACC CarTestRoute("3cfdec54aa035f3f|2022-10-13--14-58-58", VOLKSWAGEN.VOLKSWAGEN_GOLF_MK7), # openpilot longitudinal + CarTestRoute("578742b26807f756|00000010--41ee3e5bec", VOLKSWAGEN.VOLKSWAGEN_JETTA_MK6), CarTestRoute("58a7d3b707987d65|2021-03-25--17-26-37", VOLKSWAGEN.VOLKSWAGEN_JETTA_MK7), CarTestRoute("4d134e099430fba2|2021-03-26--00-26-06", VOLKSWAGEN.VOLKSWAGEN_PASSAT_MK8), CarTestRoute("3cfdec54aa035f3f|2022-07-19--23-45-10", VOLKSWAGEN.VOLKSWAGEN_PASSAT_NMS), @@ -290,9 +301,7 @@ class CarTestRoute(NamedTuple): CarTestRoute("f6d5b1a9d7a1c92e|2021-07-08--06-56-59", MAZDA.MAZDA_CX9_2021), CarTestRoute("a4af1602d8e668ac|2022-02-03--12-17-07", MAZDA.MAZDA_CX5_2022), - CarTestRoute("6c14ee12b74823ce|2021-06-30--11-49-02", TESLA.TESLA_AP1_MODELS), - CarTestRoute("bb50caf5f0945ab1|2021-06-19--17-20-18", TESLA.TESLA_AP2_MODELS), - CarTestRoute("66c1699b7697267d/2024-03-03--13-09-53", TESLA.TESLA_MODELS_RAVEN), + #CarTestRoute("46cdc864ec865f4b/00000007--42f94db730", TESLA.TESLA_MODEL_Y), # Segments that test specific issues # Controls mismatch due to standstill threshold diff --git a/opendbc_repo/opendbc/car/tests/test_can_fingerprint.py b/opendbc_repo/opendbc/car/tests/test_can_fingerprint.py new file mode 100644 index 000000000000000..79863378f5c6222 --- /dev/null +++ b/opendbc_repo/opendbc/car/tests/test_can_fingerprint.py @@ -0,0 +1,56 @@ +from parameterized import parameterized + +from opendbc.car.can_definitions import CanData +from opendbc.car.car_helpers import FRAME_FINGERPRINT, can_fingerprint +from opendbc.car.fingerprints import _FINGERPRINTS as FINGERPRINTS + + +class TestCanFingerprint: + @parameterized.expand(list(FINGERPRINTS.items())) + def test_can_fingerprint(self, car_model, fingerprints): + """Tests online fingerprinting function on offline fingerprints""" + + for fingerprint in fingerprints: # can have multiple fingerprints for each platform + can = [CanData(address=address, dat=b'\x00' * length, src=src) + for address, length in fingerprint.items() for src in (0, 1)] + + fingerprint_iter = iter([can]) + car_fingerprint, finger = can_fingerprint(lambda **kwargs: [next(fingerprint_iter, [])]) # noqa: B023 + + assert car_fingerprint == car_model + assert finger[0] == fingerprint + assert finger[1] == fingerprint + assert finger[2] == {} + + def test_timing(self, subtests): + # just pick any CAN fingerprinting car + car_model = "CHEVROLET_BOLT_EUV" + fingerprint = FINGERPRINTS[car_model][0] + + cases = [] + + # case 1 - one match, make sure we keep going for 100 frames + can = [CanData(address=address, dat=b'\x00' * length, src=src) + for address, length in fingerprint.items() for src in (0, 1)] + cases.append((FRAME_FINGERPRINT, car_model, can)) + + # case 2 - no matches, make sure we keep going for 100 frames + can = [CanData(address=1, dat=b'\x00' * 1, src=src) for src in (0, 1)] # uncommon address + cases.append((FRAME_FINGERPRINT, None, can)) + + # case 3 - multiple matches, make sure we keep going for 200 frames to try to eliminate some + can = [CanData(address=2016, dat=b'\x00' * 8, src=src) for src in (0, 1)] # common address + cases.append((FRAME_FINGERPRINT * 2, None, can)) + + for expected_frames, car_model, can in cases: + with subtests.test(expected_frames=expected_frames, car_model=car_model): + frames = 0 + + def can_recv(**kwargs): + nonlocal frames + frames += 1 + return [can] # noqa: B023 + + car_fingerprint, _ = can_fingerprint(can_recv) + assert car_fingerprint == car_model + assert frames == expected_frames + 2 # TODO: fix extra frames diff --git a/opendbc_repo/opendbc/car/tests/test_car_interfaces.py b/opendbc_repo/opendbc/car/tests/test_car_interfaces.py new file mode 100644 index 000000000000000..7c00a306f7db681 --- /dev/null +++ b/opendbc_repo/opendbc/car/tests/test_car_interfaces.py @@ -0,0 +1,145 @@ +import os +import math +import hypothesis.strategies as st +from hypothesis import Phase, given, settings +from parameterized import parameterized +from collections.abc import Callable +from typing import Any + +from opendbc.car import DT_CTRL, CanData, gen_empty_fingerprint, structs +from opendbc.car.car_helpers import interfaces +from opendbc.car.fingerprints import all_known_cars +from opendbc.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS +from opendbc.car.interfaces import get_interface_attr +from opendbc.car.mock.values import CAR as MOCK + +DrawType = Callable[[st.SearchStrategy], Any] + +ALL_ECUS = {ecu for ecus in FW_VERSIONS.values() for ecu in ecus.keys()} +ALL_ECUS |= {ecu for config in FW_QUERY_CONFIGS.values() for ecu in config.extra_ecus} + +ALL_REQUESTS = {tuple(r.request) for config in FW_QUERY_CONFIGS.values() for r in config.requests} + +MAX_EXAMPLES = int(os.environ.get('MAX_EXAMPLES', '5')) + + +def get_fuzzy_car_interface_args(draw: DrawType) -> dict: + # Fuzzy CAN fingerprints and FW versions to test more states of the CarInterface + fingerprint_strategy = st.fixed_dictionaries({key: st.dictionaries(st.integers(min_value=0, max_value=0x800), + st.integers(min_value=0, max_value=64)) for key in + gen_empty_fingerprint()}) + + # only pick from possible ecus to reduce search space + car_fw_strategy = st.lists(st.sampled_from(sorted(ALL_ECUS))) + + params_strategy = st.fixed_dictionaries({ + 'fingerprints': fingerprint_strategy, + 'car_fw': car_fw_strategy, + 'experimental_long': st.booleans(), + }) + + params: dict = draw(params_strategy) + params['car_fw'] = [structs.CarParams.CarFw(ecu=fw[0], address=fw[1], subAddress=fw[2] or 0, + request=draw(st.sampled_from(sorted(ALL_REQUESTS)))) + for fw in params['car_fw']] + return params + + +class TestCarInterfaces: + # FIXME: Due to the lists used in carParams, Phase.target is very slow and will cause + # many generated examples to overrun when max_examples > ~20, don't use it + @parameterized.expand([(car,) for car in sorted(all_known_cars())] + [MOCK.MOCK]) + @settings(max_examples=MAX_EXAMPLES, deadline=None, + phases=(Phase.reuse, Phase.generate, Phase.shrink)) + @given(data=st.data()) + def test_car_interfaces(self, car_name, data): + CarInterface, CarController, CarState, RadarInterface = interfaces[car_name] + + args = get_fuzzy_car_interface_args(data.draw) + + car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], + experimental_long=args['experimental_long'], docs=False) + car_interface = CarInterface(car_params, CarController, CarState) + assert car_params + assert car_interface + + assert car_params.mass > 1 + assert car_params.wheelbase > 0 + # centerToFront is center of gravity to front wheels, assert a reasonable range + assert car_params.wheelbase * 0.3 < car_params.centerToFront < car_params.wheelbase * 0.7 + assert car_params.maxLateralAccel > 0 + + # Longitudinal sanity checks + assert len(car_params.longitudinalTuning.kpV) == len(car_params.longitudinalTuning.kpBP) + assert len(car_params.longitudinalTuning.kiV) == len(car_params.longitudinalTuning.kiBP) + + # Lateral sanity checks + if car_params.steerControlType != structs.CarParams.SteerControlType.angle: + tune = car_params.lateralTuning + if tune.which() == 'pid': + if car_name != MOCK.MOCK: + assert not math.isnan(tune.pid.kf) and tune.pid.kf > 0 + assert len(tune.pid.kpV) > 0 and len(tune.pid.kpV) == len(tune.pid.kpBP) + assert len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP) + + elif tune.which() == 'torque': + assert not math.isnan(tune.torque.kf) and tune.torque.kf > 0 + assert not math.isnan(tune.torque.friction) and tune.torque.friction > 0 + + # Run car interface + # TODO: use hypothesis to generate random messages + now_nanos = 0 + CC = structs.CarControl().as_reader() + for _ in range(10): + car_interface.update([]) + car_interface.apply(CC, now_nanos) + now_nanos += DT_CTRL * 1e9 # 10 ms + + CC = structs.CarControl() + CC.enabled = True + CC = CC.as_reader() + for _ in range(10): + car_interface.update([]) + car_interface.apply(CC, now_nanos) + now_nanos += DT_CTRL * 1e9 # 10ms + + # Test radar interface + radar_interface = RadarInterface(car_params) + assert radar_interface + + # Run radar interface once + radar_interface.update([]) + if not car_params.radarUnavailable and radar_interface.rcp is not None and \ + hasattr(radar_interface, '_update') and hasattr(radar_interface, 'trigger_msg'): + radar_interface._update([radar_interface.trigger_msg]) + + # Test radar fault + if not car_params.radarUnavailable and radar_interface.rcp is not None: + cans = [(0, [CanData(0, b'', 0) for _ in range(5)])] + rr = radar_interface.update(cans) + assert rr is None or len(rr.errors) > 0 + + def test_interface_attrs(self): + """Asserts basic behavior of interface attribute getter""" + num_brands = len(get_interface_attr('CAR')) + assert num_brands >= 12 + + # Should return value for all brands when not combining, even if attribute doesn't exist + ret = get_interface_attr('FAKE_ATTR') + assert len(ret) == num_brands + + # Make sure we can combine dicts + ret = get_interface_attr('DBC', combine_brands=True) + assert len(ret) >= 160 + + # We don't support combining non-dicts + ret = get_interface_attr('CAR', combine_brands=True) + assert len(ret) == 0 + + # If brand has None value, it shouldn't return when ignore_none=True is specified + none_brands = {b for b, v in get_interface_attr('FINGERPRINTS').items() if v is None} + assert len(none_brands) >= 1 + + ret = get_interface_attr('FINGERPRINTS', ignore_none=True) + none_brands_in_ret = none_brands.intersection(ret) + assert len(none_brands_in_ret) == 0, f'Brands with None values in ignore_none=True result: {none_brands_in_ret}' diff --git a/opendbc_repo/opendbc/car/tests/test_docs.py b/opendbc_repo/opendbc/car/tests/test_docs.py new file mode 100644 index 000000000000000..9e6e7b632d881a7 --- /dev/null +++ b/opendbc_repo/opendbc/car/tests/test_docs.py @@ -0,0 +1,74 @@ +from collections import defaultdict +import pytest +import re + +from opendbc.car.car_helpers import interfaces +from opendbc.car.docs import get_all_car_docs +from opendbc.car.docs_definitions import Cable, Column, PartType, Star +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.values import PLATFORMS + + +class TestCarDocs: + @classmethod + def setup_class(cls): + cls.all_cars = get_all_car_docs() + + def test_duplicate_years(self, subtests): + make_model_years = defaultdict(list) + for car in self.all_cars: + with subtests.test(car_docs_name=car.name): + make_model = (car.make, car.model) + for year in car.year_list: + assert year not in make_model_years[make_model], f"{car.name}: Duplicate model year" + make_model_years[make_model].append(year) + + def test_missing_car_docs(self, subtests): + all_car_docs_platforms = [name for name, config in PLATFORMS.items()] + for platform in sorted(interfaces.keys()): + with subtests.test(platform=platform): + assert platform in all_car_docs_platforms, f"Platform: {platform} doesn't have a CarDocs entry" + + def test_naming_conventions(self, subtests): + # Asserts market-standard car naming conventions by brand + for car in self.all_cars: + with subtests.test(car=car.name): + tokens = car.model.lower().split(" ") + if car.car_name == "hyundai": + assert "phev" not in tokens, "Use `Plug-in Hybrid`" + assert "hev" not in tokens, "Use `Hybrid`" + if "plug-in hybrid" in car.model.lower(): + assert "Plug-in Hybrid" in car.model, "Use correct capitalization" + if car.make != "Kia": + assert "ev" not in tokens, "Use `Electric`" + elif car.car_name == "toyota": + if "rav4" in tokens: + assert "RAV4" in car.model, "Use correct capitalization" + + def test_torque_star(self, subtests): + # Asserts brand-specific assumptions around steering torque star + for car in self.all_cars: + with subtests.test(car=car.name): + # honda sanity check, it's the definition of a no torque star + if car.car_fingerprint in (HONDA.HONDA_ACCORD, HONDA.HONDA_CIVIC, HONDA.HONDA_CRV, HONDA.HONDA_ODYSSEY, HONDA.HONDA_PILOT): + assert car.row[Column.STEERING_TORQUE] == Star.EMPTY, f"{car.name} has full torque star" + elif car.car_name in ("toyota", "hyundai"): + assert car.row[Column.STEERING_TORQUE] != Star.EMPTY, f"{car.name} has no torque star" + + def test_year_format(self, subtests): + for car in self.all_cars: + with subtests.test(car=car.name): + assert re.search(r"\d{4}-\d{4}", car.name) is None, f"Format years correctly: {car.name}" + + def test_harnesses(self, subtests): + for car in self.all_cars: + with subtests.test(car=car.name): + if car.name == "comma body": + pytest.skip() + + car_part_type = [p.part_type for p in car.car_parts.all_parts()] + car_parts = list(car.car_parts.all_parts()) + assert len(car_parts) > 0, f"Need to specify car parts: {car.name}" + assert car_part_type.count(PartType.connector) == 1, f"Need to specify one harness connector: {car.name}" + assert car_part_type.count(PartType.mount) == 1, f"Need to specify one mount: {car.name}" + assert Cable.right_angle_obd_c_cable_1_5ft in car_parts, f"Need to specify a right angle OBD-C cable (1.5ft): {car.name}" diff --git a/selfdrive/car/tests/test_fw_fingerprint.py b/opendbc_repo/opendbc/car/tests/test_fw_fingerprint.py similarity index 78% rename from selfdrive/car/tests/test_fw_fingerprint.py rename to opendbc_repo/opendbc/car/tests/test_fw_fingerprint.py index f87297254225071..d36355134239c91 100644 --- a/selfdrive/car/tests/test_fw_fingerprint.py +++ b/opendbc_repo/opendbc/car/tests/test_fw_fingerprint.py @@ -4,25 +4,16 @@ from collections import defaultdict from parameterized import parameterized -from cereal import car -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.fingerprints import FW_VERSIONS -from openpilot.selfdrive.car.fw_versions import ESSENTIAL_ECUS, FW_QUERY_CONFIGS, FUZZY_EXCLUDE_ECUS, VERSIONS, build_fw_dict, \ +from opendbc.car.can_definitions import CanData +from opendbc.car.car_helpers import interfaces +from opendbc.car.structs import CarParams +from opendbc.car.fingerprints import FW_VERSIONS +from opendbc.car.fw_versions import ESSENTIAL_ECUS, FW_QUERY_CONFIGS, FUZZY_EXCLUDE_ECUS, VERSIONS, build_fw_dict, \ match_fw_to_car, get_brand_ecu_matches, get_fw_versions, get_present_ecus -from openpilot.selfdrive.car.vin import get_vin +from opendbc.car.vin import get_vin -CarFw = car.CarParams.CarFw -Ecu = car.CarParams.Ecu - -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -class FakeSocket: - def receive(self, non_blocking=False): - pass - - def send(self, msg): - pass +CarFw = CarParams.CarFw +Ecu = CarParams.Ecu class TestFwFingerprint: @@ -34,8 +25,8 @@ def assertFingerprints(self, candidates, expected): @parameterized.expand([(b, c, e[c], n) for b, e in VERSIONS.items() for c in e for n in (True, False)]) def test_exact_match(self, brand, car_model, ecus, test_non_essential): config = FW_QUERY_CONFIGS[brand] - CP = car.CarParams.new_message() - for _ in range(100): + CP = CarParams() + for _ in range(20): fw = [] for ecu, fw_versions in ecus.items(): # Assume non-essential ECUs apply to all cars, so we catch cases where Car A with @@ -44,8 +35,8 @@ def test_exact_match(self, brand, car_model, ecus, test_non_essential): continue ecu_name, addr, sub_addr = ecu - fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), 'brand': brand, - "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) + fw.append(CarFw(ecu=ecu_name, fwVersion=random.choice(fw_versions), brand=brand, + address=addr, subAddress=0 if sub_addr is None else sub_addr)) CP.carFw = fw _, matches = match_fw_to_car(CP.carFw, CP.carVin, allow_fuzzy=False) if not test_non_essential: @@ -62,13 +53,13 @@ def test_custom_fuzzy_match(self, brand, car_model, ecus): if config.match_fw_to_car_fuzzy is None: pytest.skip("Brand does not implement custom fuzzy fingerprinting function") - CP = car.CarParams.new_message() + CP = CarParams() for _ in range(5): fw = [] for ecu, fw_versions in ecus.items(): ecu_name, addr, sub_addr = ecu - fw.append({"ecu": ecu_name, "fwVersion": random.choice(fw_versions), 'brand': brand, - "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) + fw.append(CarFw(ecu=ecu_name, fwVersion=random.choice(fw_versions), brand=brand, + address=addr, subAddress=0 if sub_addr is None else sub_addr)) CP.carFw = fw _, matches = match_fw_to_car(CP.carFw, CP.carVin, allow_exact=False, log=False) brand_matches = config.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, VERSIONS[brand]) @@ -89,13 +80,13 @@ def test_fuzzy_match_ecu_count(self, brand, car_model, ecus): ecu_name, addr, sub_addr = ecu for _ in range(5): # Add multiple FW versions to simulate ECU returning to multiple queries in a brand - fw.append({"ecu": ecu_name, "fwVersion": random.choice(ecus[ecu]), 'brand': brand, - "address": addr, "subAddress": 0 if sub_addr is None else sub_addr}) - CP = car.CarParams.new_message(carFw=fw) + fw.append(CarFw(ecu=ecu_name, fwVersion=random.choice(ecus[ecu]), brand=brand, + address=addr, subAddress=0 if sub_addr is None else sub_addr)) + CP = CarParams(carFw=fw) _, matches = match_fw_to_car(CP.carFw, CP.carVin, allow_exact=False, log=False) # Assert no match if there are not enough unique ECUs - unique_ecus = {(f['address'], f['subAddress']) for f in fw} + unique_ecus = {(f.address, f.subAddress) for f in fw} if len(unique_ecus) < 2: assert len(matches) == 0, car_model # There won't always be a match due to shared FW, but if there is it should be correct @@ -108,8 +99,8 @@ def test_fw_version_lists(self, subtests): for ecu, ecu_fw in ecus.items(): with subtests.test(ecu): duplicates = {fw for fw in ecu_fw if ecu_fw.count(fw) > 1} - assert not len(duplicates), f'{car_model}: Duplicate FW versions: Ecu.{ECU_NAME[ecu[0]]}, {duplicates}' - assert len(ecu_fw) > 0, f'{car_model}: No FW versions: Ecu.{ECU_NAME[ecu[0]]}' + assert not len(duplicates), f'{car_model}: Duplicate FW versions: Ecu.{ecu[0]}, {duplicates}' + assert len(ecu_fw) > 0, f'{car_model}: No FW versions: Ecu.{ecu[0]}' def test_all_addrs_map_to_one_ecu(self): for brand, cars in VERSIONS.items(): @@ -118,7 +109,7 @@ def test_all_addrs_map_to_one_ecu(self): for ecu_type, addr, sub_addr in ecus.keys(): addr_to_ecu[(addr, sub_addr)].add(ecu_type) ecus_for_addr = addr_to_ecu[(addr, sub_addr)] - ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_for_addr]) + ecu_strings = ", ".join([f'Ecu.{ecu}' for ecu in ecus_for_addr]) assert len(ecus_for_addr) <= 1, f"{brand} has multiple ECUs that map to one address: {ecu_strings} -> ({hex(addr)}, {sub_addr})" def test_data_collection_ecus(self, subtests): @@ -136,13 +127,13 @@ def test_blacklisted_ecus(self, subtests): CP = interfaces[car_model][0].get_non_essential_params(car_model) if CP.carName == 'subaru': for ecu in ecus.keys(): - assert ecu[1] not in blacklisted_addrs, f'{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})' + assert ecu[1] not in blacklisted_addrs, f'{car_model}: Blacklisted ecu: (Ecu.{ecu[0]}, {hex(ecu[1])})' elif CP.carName == "chrysler": # Some HD trucks have a combined TCM and ECM - if CP.carFingerprint.startswith("RAM HD"): + if CP.carFingerprint.startswith("RAM_HD"): for ecu in ecus.keys(): - assert ecu[0] != Ecu.transmission, f"{car_model}: Blacklisted ecu: (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])})" + assert ecu[0] != Ecu.transmission, f"{car_model}: Blacklisted ecu: (Ecu.{ecu[0]}, {hex(ecu[1])})" def test_non_essential_ecus(self, subtests): for brand, config in FW_QUERY_CONFIGS.items(): @@ -150,7 +141,7 @@ def test_non_essential_ecus(self, subtests): # These ECUs are already not in ESSENTIAL_ECUS which the fingerprint functions give a pass if missing unnecessary_non_essential_ecus = set(config.non_essential_ecus) - set(ESSENTIAL_ECUS) assert unnecessary_non_essential_ecus == set(), "Declaring non-essential ECUs non-essential is not required: " + \ - f"{', '.join([f'Ecu.{ECU_NAME[ecu]}' for ecu in unnecessary_non_essential_ecus])}" + f"{', '.join([f'Ecu.{ecu}' for ecu in unnecessary_non_essential_ecus])}" def test_missing_versions_and_configs(self, subtests): brand_versions = set(VERSIONS.keys()) @@ -179,7 +170,7 @@ def test_fw_request_ecu_whitelist(self, subtests): # each ecu in brand's fw versions + extra ecus needs to be whitelisted at least once ecus_not_whitelisted = brand_ecus - whitelisted_ecus - ecu_strings = ", ".join([f'Ecu.{ECU_NAME[ecu]}' for ecu in ecus_not_whitelisted]) + ecu_strings = ", ".join([f'Ecu.{ecu}' for ecu in ecus_not_whitelisted]) assert not (len(whitelisted_ecus) and len(ecus_not_whitelisted)), \ f'{brand.title()}: ECUs not in any FW query whitelists: {ecu_strings}' @@ -211,7 +202,16 @@ class TestFwFingerprintTiming: current_obd_multiplexing: bool total_time: float - def fake_set_obd_multiplexing(self, _, obd_multiplexing): + @staticmethod + def fake_can_send(msgs): + pass + + @staticmethod + def fake_can_recv(wait_for_one: bool = False) -> list[list[CanData]]: + return ([[CanData(random.randint(0x600, 0x800), b'\x00' * 8, 0)]] + if random.uniform(0, 1) > 0.5 else []) + + def fake_set_obd_multiplexing(self, obd_multiplexing): """The 10Hz blocking params loop adds on average 50ms to the query time for each OBD multiplexing change""" if obd_multiplexing != self.current_obd_multiplexing: self.current_obd_multiplexing = obd_multiplexing @@ -222,16 +222,14 @@ def fake_get_data(self, timeout): return {} def _benchmark_brand(self, brand, num_pandas, mocker): - fake_socket = FakeSocket() self.total_time = 0 - mocker.patch("openpilot.selfdrive.car.fw_versions.set_obd_multiplexing", self.fake_set_obd_multiplexing) - mocker.patch("openpilot.selfdrive.car.isotp_parallel_query.IsoTpParallelQuery.get_data", self.fake_get_data) + mocker.patch("opendbc.car.isotp_parallel_query.IsoTpParallelQuery.get_data", self.fake_get_data) for _ in range(self.N): # Treat each brand as the most likely (aka, the first) brand with OBD multiplexing initially on self.current_obd_multiplexing = True t = time.perf_counter() - get_fw_versions(fake_socket, fake_socket, brand, num_pandas=num_pandas) + get_fw_versions(self.fake_can_recv, self.fake_can_send, self.fake_set_obd_multiplexing, brand, num_pandas=num_pandas) self.total_time += time.perf_counter() - t return self.total_time / self.N @@ -249,27 +247,25 @@ def fake_get_ecu_addrs(*_, timeout): self.total_time += timeout return set() - fake_socket = FakeSocket() self.total_time = 0.0 - mocker.patch("openpilot.selfdrive.car.fw_versions.set_obd_multiplexing", self.fake_set_obd_multiplexing) - mocker.patch("openpilot.selfdrive.car.fw_versions.get_ecu_addrs", fake_get_ecu_addrs) + mocker.patch("opendbc.car.fw_versions.get_ecu_addrs", fake_get_ecu_addrs) for _ in range(self.N): self.current_obd_multiplexing = True - get_present_ecus(fake_socket, fake_socket, num_pandas=2) + get_present_ecus(self.fake_can_recv, self.fake_can_send, self.fake_set_obd_multiplexing, num_pandas=2) self._assert_timing(self.total_time / self.N, present_ecu_ref_time) print(f'get_present_ecus, query time={self.total_time / self.N} seconds') for name, args in (('worst', {}), ('best', {'retry': 1})): with subtests.test(name=name): self.total_time = 0.0 - mocker.patch("openpilot.selfdrive.car.isotp_parallel_query.IsoTpParallelQuery.get_data", self.fake_get_data) + mocker.patch("opendbc.car.isotp_parallel_query.IsoTpParallelQuery.get_data", self.fake_get_data) for _ in range(self.N): - get_vin(fake_socket, fake_socket, (0, 1), **args) + get_vin(self.fake_can_recv, self.fake_can_send, (0, 1), **args) self._assert_timing(self.total_time / self.N, vin_ref_times[name]) print(f'get_vin {name} case, query time={self.total_time / self.N} seconds') def test_fw_query_timing(self, subtests, mocker): - total_ref_time = {1: 7.2, 2: 7.8} + total_ref_time = {1: 7.0, 2: 7.6} brand_ref_times = { 1: { 'gm': 1.0, @@ -281,14 +277,13 @@ def test_fw_query_timing(self, subtests, mocker): 'mazda': 0.1, 'nissan': 0.8, 'subaru': 0.65, - 'tesla': 0.3, + 'tesla': 0.1, 'toyota': 0.7, 'volkswagen': 0.65, }, 2: { 'ford': 1.6, 'hyundai': 1.15, - 'tesla': 0.3, } } @@ -313,3 +308,24 @@ def test_fw_query_timing(self, subtests, mocker): total_time = round(total_times[num_pandas], 2) self._assert_timing(total_time, total_ref_time[num_pandas]) print(f'all brands, total FW query time={total_time} seconds') + + def test_get_fw_versions(self, subtests, mocker): + # some coverage on IsoTpParallelQuery and panda UDS library + # TODO: replace this with full fingerprint simulation testing + # https://github.com/commaai/panda/pull/1329 + + def fake_carlog_exception(*args, **kwargs): + raise + + t = 0 + + def fake_monotonic(): + nonlocal t + t += 0.0001 + return t + + mocker.patch("opendbc.car.carlog.exception", fake_carlog_exception) + mocker.patch("time.monotonic", fake_monotonic) + for brand in FW_QUERY_CONFIGS.keys(): + with subtests.test(brand=brand): + get_fw_versions(self.fake_can_recv, self.fake_can_send, lambda obd: None, brand) diff --git a/selfdrive/car/tests/test_lateral_limits.py b/opendbc_repo/opendbc/car/tests/test_lateral_limits.py similarity index 88% rename from selfdrive/car/tests/test_lateral_limits.py rename to opendbc_repo/opendbc/car/tests/test_lateral_limits.py index e61d197f4b7085b..2a0b7eb90a3f81c 100755 --- a/selfdrive/car/tests/test_lateral_limits.py +++ b/opendbc_repo/opendbc/car/tests/test_lateral_limits.py @@ -5,10 +5,10 @@ import pytest import sys -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.fingerprints import all_known_cars -from openpilot.selfdrive.car.interfaces import get_torque_params +from opendbc.car import DT_CTRL +from opendbc.car.car_helpers import interfaces +from opendbc.car.fingerprints import all_known_cars +from opendbc.car.interfaces import get_torque_params CAR_MODELS = all_known_cars() @@ -28,20 +28,20 @@ class TestLateralLimits: @classmethod def setup_class(cls): - CarInterface, _, _ = interfaces[cls.car_model] + CarInterface, _, _, _ = interfaces[cls.car_model] CP = CarInterface.get_non_essential_params(cls.car_model) if CP.dashcamOnly: pytest.skip("Platform is behind dashcamOnly") # TODO: test all platforms - if CP.lateralTuning.which() != 'torque': + if CP.steerControlType != 'torque': pytest.skip() if CP.notCar: pytest.skip() - CarControllerParams = importlib.import_module(f'selfdrive.car.{CP.carName}.values').CarControllerParams + CarControllerParams = importlib.import_module(f'opendbc.car.{CP.carName}.values').CarControllerParams cls.control_params = CarControllerParams(CP) cls.torque_params = get_torque_params()[cls.car_model] diff --git a/selfdrive/car/tests/test_platform_configs.py b/opendbc_repo/opendbc/car/tests/test_platform_configs.py similarity index 89% rename from selfdrive/car/tests/test_platform_configs.py rename to opendbc_repo/opendbc/car/tests/test_platform_configs.py index 31e4be4fe6b0e2b..1be10a50f9a2745 100644 --- a/selfdrive/car/tests/test_platform_configs.py +++ b/opendbc_repo/opendbc/car/tests/test_platform_configs.py @@ -1,4 +1,4 @@ -from openpilot.selfdrive.car.values import PLATFORMS +from opendbc.car.values import PLATFORMS class TestPlatformConfigs: diff --git a/opendbc_repo/opendbc/car/tests/test_routes.py b/opendbc_repo/opendbc/car/tests/test_routes.py new file mode 100644 index 000000000000000..5c7ab12e8358f56 --- /dev/null +++ b/opendbc_repo/opendbc/car/tests/test_routes.py @@ -0,0 +1,11 @@ +from parameterized import parameterized + +from opendbc.car.values import PLATFORMS +from opendbc.car.tests.routes import non_tested_cars, routes + + +@parameterized.expand(PLATFORMS.keys()) +def test_test_route_present(platform): + tested_platforms = [r.car_model for r in routes] + assert platform in set(tested_platforms) | set(non_tested_cars), \ + f"Missing test route for {platform}. Add a route to opendbc/car/tests/routes.py" diff --git a/selfdrive/car/torque_data/neural_ff_weights.json b/opendbc_repo/opendbc/car/torque_data/neural_ff_weights.json similarity index 100% rename from selfdrive/car/torque_data/neural_ff_weights.json rename to opendbc_repo/opendbc/car/torque_data/neural_ff_weights.json diff --git a/selfdrive/car/torque_data/override.toml b/opendbc_repo/opendbc/car/torque_data/override.toml similarity index 87% rename from selfdrive/car/torque_data/override.toml rename to opendbc_repo/opendbc/car/torque_data/override.toml index 993eb3fb3c0fa5d..aad06e8e3e596dc 100644 --- a/selfdrive/car/torque_data/override.toml +++ b/opendbc_repo/opendbc/car/torque_data/override.toml @@ -15,10 +15,9 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] # Toyota LTA also has torque "TOYOTA_RAV4_TSS2_2023" = [nan, 3.0, nan] -# Tesla has high torque -"TESLA_AP1_MODELS" = [nan, 2.5, nan] -"TESLA_AP2_MODELS" = [nan, 2.5, nan] -"TESLA_MODELS_RAVEN" = [nan, 2.5, nan] +# Tesla angle based controllers +"TESLA_MODEL_3" = [nan, 2.5, nan] +"TESLA_MODEL_Y" = [nan, 2.5, nan] # Guess "FORD_BRONCO_SPORT_MK1" = [nan, 1.5, nan] @@ -41,10 +40,13 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "SUBARU_OUTBACK" = [2.0, 1.5, 0.2] "CADILLAC_ESCALADE" = [1.899999976158142, 1.842270016670227, 0.1120000034570694] "CADILLAC_ESCALADE_ESV_2019" = [1.15, 1.3, 0.2] +"CADILLAC_XT4" = [1.45, 1.6, 0.2] "CHEVROLET_BOLT_EUV" = [2.0, 2.0, 0.05] "CHEVROLET_SILVERADO" = [1.9, 1.9, 0.112] "CHEVROLET_TRAILBLAZER" = [1.33, 1.9, 0.16] +"CHEVROLET_TRAVERSE" = [1.33, 1.33, 0.18] "CHEVROLET_EQUINOX" = [2.5, 2.5, 0.05] +"CHEVROLET_VOLT_2019" = [1.4, 1.4, 0.16] "VOLKSWAGEN_CADDY_MK3" = [1.2, 1.2, 0.1] "VOLKSWAGEN_PASSAT_NMS" = [2.5, 2.5, 0.1] "VOLKSWAGEN_SHARAN_MK2" = [2.5, 2.5, 0.1] @@ -68,6 +70,8 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "HYUNDAI_CUSTIN_1ST_GEN" = [2.5, 2.5, 0.1] "LEXUS_GS_F" = [2.5, 2.5, 0.08] "HYUNDAI_STARIA_4TH_GEN" = [1.8, 2.0, 0.15] +"GENESIS_GV70_ELECTRIFIED_1ST_GEN" = [1.9, 1.9, 0.09] +"GENESIS_G80_2ND_GEN_FL" = [2.5819356441497803, 2.5, 0.11244568973779678] # Dashcam or fallback configured as ideal car "MOCK" = [10.0, 10, 0.0] diff --git a/selfdrive/car/torque_data/params.toml b/opendbc_repo/opendbc/car/torque_data/params.toml similarity index 98% rename from selfdrive/car/torque_data/params.toml rename to opendbc_repo/opendbc/car/torque_data/params.toml index 34cfd0e0660b07e..4bb8d45c537e19d 100644 --- a/selfdrive/car/torque_data/params.toml +++ b/opendbc_repo/opendbc/car/torque_data/params.toml @@ -7,7 +7,6 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "CHEVROLET_VOLT" = [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_2017_HYBRID" = [1.79422, 1.06831764583744, 0.116237] "CHRYSLER_PACIFICA_2018_HYBRID" = [2.08887, 1.2943025830995154, 0.114818] "CHRYSLER_PACIFICA_2019_HYBRID" = [1.90120, 1.1958788168371808, 0.131520] "GENESIS_G70" = [3.8520195946707947, 2.354697063349854, 0.06830285485626221] diff --git a/selfdrive/car/torque_data/substitute.toml b/opendbc_repo/opendbc/car/torque_data/substitute.toml similarity index 95% rename from selfdrive/car/torque_data/substitute.toml rename to opendbc_repo/opendbc/car/torque_data/substitute.toml index 8724a08010e3b08..456f823dfa24389 100644 --- a/selfdrive/car/torque_data/substitute.toml +++ b/opendbc_repo/opendbc/car/torque_data/substitute.toml @@ -9,6 +9,8 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "TOYOTA_ALPHARD_TSS2" = "TOYOTA_SIENNA" "TOYOTA_PRIUS_V" = "TOYOTA_PRIUS" +"TOYOTA_RAV4_PRIME" = "TOYOTA_RAV4_TSS2" +"TOYOTA_SIENNA_4TH_GEN" = "TOYOTA_RAV4_TSS2" "LEXUS_IS" = "LEXUS_NX" "LEXUS_CTH" = "LEXUS_NX" "LEXUS_ES" = "TOYOTA_CAMRY" @@ -70,6 +72,7 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "VOLKSWAGEN_TAOS_MK1" = "VOLKSWAGEN_TIGUAN_MK2" "VOLKSWAGEN_POLO_MK6" = "VOLKSWAGEN_GOLF_MK7" "SEAT_ATECA_MK1" = "VOLKSWAGEN_GOLF_MK7" +"VOLKSWAGEN_JETTA_MK6" = "VOLKSWAGEN_PASSAT_NMS" "SUBARU_CROSSTREK_HYBRID" = "SUBARU_IMPREZA_2020" "SUBARU_FORESTER_HYBRID" = "SUBARU_IMPREZA_2020" diff --git a/selfdrive/navd/__init__.py b/opendbc_repo/opendbc/car/toyota/__init__.py similarity index 100% rename from selfdrive/navd/__init__.py rename to opendbc_repo/opendbc/car/toyota/__init__.py diff --git a/opendbc_repo/opendbc/car/toyota/carcontroller.py b/opendbc_repo/opendbc/car/toyota/carcontroller.py new file mode 100644 index 000000000000000..a042554a81f0a21 --- /dev/null +++ b/opendbc_repo/opendbc/car/toyota/carcontroller.py @@ -0,0 +1,256 @@ +import math +from opendbc.car import carlog, apply_meas_steer_torque_limits, apply_std_steer_angle_limits, common_fault_avoidance, \ + make_tester_present_msg, rate_limit, structs, ACCELERATION_DUE_TO_GRAVITY +from opendbc.car.can_definitions import CanData +from opendbc.car.common.numpy_fast import clip +from opendbc.car.secoc import add_mac, build_sync_mac +from opendbc.car.interfaces import CarControllerBase +from opendbc.car.toyota import toyotacan +from opendbc.car.toyota.values import CAR, STATIC_DSU_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \ + CarControllerParams, ToyotaFlags, \ + UNSUPPORTED_DSU_CAR +from opendbc.can.packer import CANPacker + +LongCtrlState = structs.CarControl.Actuators.LongControlState +SteerControlType = structs.CarParams.SteerControlType +VisualAlert = structs.CarControl.HUDControl.VisualAlert + +ACCEL_WINDUP_LIMIT = 0.5 # m/s^2 / frame + +# LKA limits +# EPS faults if you apply torque while the steering rate is above 100 deg/s for too long +MAX_STEER_RATE = 100 # deg/s +MAX_STEER_RATE_FRAMES = 18 # tx control frames needed before torque can be cut + +# EPS allows user torque above threshold for 50 frames before permanently faulting +MAX_USER_TORQUE = 500 + +# LTA limits +# EPS ignores commands above this angle and causes PCS to fault +MAX_LTA_ANGLE = 94.9461 # deg +MAX_LTA_DRIVER_TORQUE_ALLOWANCE = 150 # slightly above steering pressed allows some resistance when changing lanes + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.params = CarControllerParams(self.CP) + self.last_steer = 0 + self.last_angle = 0 + self.alert_active = False + self.last_standstill = False + self.standstill_req = False + self.steer_rate_counter = 0 + self.distance_button = 0 + + self.pcm_accel_compensation = 0.0 + self.permit_braking = True + + self.packer = CANPacker(dbc_name) + self.accel = 0 + + self.secoc_lka_message_counter = 0 + self.secoc_lta_message_counter = 0 + self.secoc_prev_reset_counter = 0 + self.secoc_mismatch_counter = 0 + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + stopping = actuators.longControlState == LongCtrlState.stopping + hud_control = CC.hudControl + pcm_cancel_cmd = CC.cruiseControl.cancel + lat_active = CC.latActive and abs(CS.out.steeringTorque) < MAX_USER_TORQUE + + # *** control msgs *** + can_sends = [] + + # *** handle secoc reset counter increase *** + if self.CP.flags & ToyotaFlags.SECOC.value: + if CS.secoc_synchronization['RESET_CNT'] != self.secoc_prev_reset_counter: + self.secoc_lka_message_counter = 0 + self.secoc_lta_message_counter = 0 + self.secoc_prev_reset_counter = CS.secoc_synchronization['RESET_CNT'] + + expected_mac = build_sync_mac(self.secoc_key, int(CS.secoc_synchronization['TRIP_CNT']), int(CS.secoc_synchronization['RESET_CNT'])) + if int(CS.secoc_synchronization['AUTHENTICATOR']) != expected_mac and self.secoc_mismatch_counter < 100: + carlog.error("SecOC synchronization MAC mismatch, wrong key?") + self.secoc_mismatch_counter += 1 + + # *** steer torque *** + new_steer = int(round(actuators.steer * self.params.STEER_MAX)) + 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, lat_active, + self.steer_rate_counter, MAX_STEER_RATE_FRAMES) + + if not lat_active: + apply_steer = 0 + + # *** steer angle *** + if self.CP.steerControlType == SteerControlType.angle: + # If using LTA control, disable LKA and set steering angle command + apply_steer = 0 + apply_steer_req = False + if self.frame % 2 == 0: + # EPS uses the torque sensor angle to control with, offset to compensate + 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.vEgoRaw, self.params) + + if not lat_active: + apply_angle = CS.out.steeringAngleDeg + CS.out.steeringAngleOffsetDeg + + self.last_angle = clip(apply_angle, -MAX_LTA_ANGLE, MAX_LTA_ANGLE) + + self.last_steer = apply_steer + + # 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 + steer_command = toyotacan.create_steer_command(self.packer, apply_steer, apply_steer_req) + if self.CP.flags & ToyotaFlags.SECOC.value: + # TODO: check if this slow and needs to be done by the CANPacker + steer_command = add_mac(self.secoc_key, + int(CS.secoc_synchronization['TRIP_CNT']), + int(CS.secoc_synchronization['RESET_CNT']), + self.secoc_lka_message_counter, + steer_command) + self.secoc_lka_message_counter += 1 + can_sends.append(steer_command) + + # 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_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)) + + if self.CP.flags & ToyotaFlags.SECOC.value: + lta_steer_2 = toyotacan.create_lta_steer_command_2(self.packer, self.frame // 2) + lta_steer_2 = add_mac(self.secoc_key, + int(CS.secoc_synchronization['TRIP_CNT']), + int(CS.secoc_synchronization['RESET_CNT']), + self.secoc_lta_message_counter, + lta_steer_2) + self.secoc_lta_message_counter += 1 + can_sends.append(lta_steer_2) + + # *** gas and brake *** + + # on entering standstill, send standstill request + if CS.out.standstill and not self.last_standstill and (self.CP.carFingerprint not in NO_STOP_TIMER_CAR): + self.standstill_req = True + if CS.pcm_acc_status != 8: + # pcm entered standstill or it's disabled + self.standstill_req = False + + self.last_standstill = CS.out.standstill + + # handle UI messages + fcw_alert = hud_control.visualAlert == VisualAlert.fcw + steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) + lead = hud_control.leadVisible or CS.out.vEgo < 12. # at low speed we always assume the lead is present so ACC can be engaged + + if self.CP.openpilotLongitudinalControl: + if self.frame % 3 == 0: + # Press distance button until we are at the correct bar length. Only change while enabled to avoid skipping startup popup + if self.frame % 6 == 0 and self.CP.openpilotLongitudinalControl: + desired_distance = 4 - hud_control.leadDistanceBars + if CS.out.cruiseState.enabled and CS.pcm_follow_distance != desired_distance: + self.distance_button = not self.distance_button + else: + self.distance_button = 0 + + # internal PCM gas command can get stuck unwinding from negative accel so we apply a generous rate limit + pcm_accel_cmd = min(actuators.accel, self.accel + ACCEL_WINDUP_LIMIT) if CC.longActive else 0.0 + + # calculate amount of acceleration PCM should apply to reach target, given pitch + accel_due_to_pitch = math.sin(CC.orientationNED[1]) * ACCELERATION_DUE_TO_GRAVITY if len(CC.orientationNED) == 3 else 0.0 + net_acceleration_request = pcm_accel_cmd + accel_due_to_pitch + + # For cars where we allow a higher max acceleration of 2.0 m/s^2, compensate for PCM request overshoot and imprecise braking + if self.CP.flags & ToyotaFlags.RAISED_ACCEL_LIMIT and CC.longActive and not CS.out.cruiseState.standstill: + # let PCM handle stopping for now + pcm_accel_compensation = 0.0 + if not stopping: + pcm_accel_compensation = 2.0 * (CS.pcm_accel_net - net_acceleration_request) + + # prevent compensation windup + pcm_accel_compensation = clip(pcm_accel_compensation, pcm_accel_cmd - self.params.ACCEL_MAX, + pcm_accel_cmd - self.params.ACCEL_MIN) + + self.pcm_accel_compensation = rate_limit(pcm_accel_compensation, self.pcm_accel_compensation, -0.03, 0.03) + pcm_accel_cmd = pcm_accel_cmd - self.pcm_accel_compensation + + else: + self.pcm_accel_compensation = 0.0 + self.permit_braking = True + + # Along with rate limiting positive jerk above, this greatly improves gas response time + # Consider the net acceleration request that the PCM should be applying (pitch included) + if net_acceleration_request < 0.1 or stopping or not CC.longActive: + self.permit_braking = True + elif net_acceleration_request > 0.2: + self.permit_braking = False + + pcm_accel_cmd = clip(pcm_accel_cmd, self.params.ACCEL_MIN, self.params.ACCEL_MAX) + + can_sends.append(toyotacan.create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.permit_braking, self.standstill_req, lead, + CS.acc_type, fcw_alert, self.distance_button)) + self.accel = pcm_accel_cmd + + else: + # we can spam can to cancel the system even if we are using lat only control + if pcm_cancel_cmd: + if self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: + can_sends.append(toyotacan.create_acc_cancel_command(self.packer)) + else: + can_sends.append(toyotacan.create_accel_command(self.packer, 0, pcm_cancel_cmd, True, False, lead, CS.acc_type, False, self.distance_button)) + + # *** hud ui *** + if self.CP.carFingerprint != CAR.TOYOTA_PRIUS_V: + # ui mesg is at 1Hz but we send asap if: + # - there is something to display + # - there is something to stop displaying + send_ui = False + if ((fcw_alert or steer_alert) and not self.alert_active) or \ + (not (fcw_alert or steer_alert) and self.alert_active): + send_ui = True + self.alert_active = not self.alert_active + elif pcm_cancel_cmd: + # forcing the pcm to disengage causes a bad fault sound so play a good sound instead + send_ui = True + + if self.frame % 20 == 0 or send_ui: + can_sends.append(toyotacan.create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, + hud_control.rightLaneVisible, hud_control.leftLaneDepart, + hud_control.rightLaneDepart, CC.enabled, CS.lkas_hud)) + + if (self.frame % 100 == 0 or send_ui) and (self.CP.enableDsu or self.CP.flags & ToyotaFlags.DISABLE_RADAR.value): + can_sends.append(toyotacan.create_fcw_command(self.packer, fcw_alert)) + + # *** static msgs *** + for addr, cars, bus, fr_step, vl in STATIC_DSU_MSGS: + if self.frame % fr_step == 0 and self.CP.enableDsu and self.CP.carFingerprint in cars: + can_sends.append(CanData(addr, vl, bus)) + + # keep radar disabled + if self.frame % 20 == 0 and self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: + can_sends.append(make_tester_present_msg(0x750, 0, 0xF)) + + new_actuators = actuators.as_builder() + new_actuators.steer = apply_steer / self.params.STEER_MAX + new_actuators.steerOutputCan = apply_steer + new_actuators.steeringAngleDeg = self.last_angle + new_actuators.accel = self.accel + + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/toyota/carstate.py b/opendbc_repo/opendbc/car/toyota/carstate.py new file mode 100644 index 000000000000000..e319d2c394b599e --- /dev/null +++ b/opendbc_repo/opendbc/car/toyota/carstate.py @@ -0,0 +1,281 @@ +import copy + +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from opendbc.car import DT_CTRL, create_button_events, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.common.filter_simple import FirstOrderFilter +from opendbc.car.common.numpy_fast import mean +from opendbc.car.interfaces import CarStateBase +from opendbc.car.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, \ + TSS2_CAR, RADAR_ACC_CAR, EPS_SCALE, UNSUPPORTED_DSU_CAR, SECOC_CAR + +ButtonType = structs.CarState.ButtonEvent.Type +SteerControlType = structs.CarParams.SteerControlType + +# These steering fault definitions seem to be common across LKA (torque) and LTA (angle): +# - high steer rate fault: goes to 21 or 25 for 1 frame, then 9 for 2 seconds +# - lka/lta msg drop out: goes to 9 then 11 for a combined total of 2 seconds, then 3. +# if using the other control command, goes directly to 3 after 1.5 seconds +# - initializing: LTA can report 0 as long as STEER_TORQUE_SENSOR->STEER_ANGLE_INITIALIZING is 1, +# and is a catch-all for LKA +TEMP_STEER_FAULTS = (0, 9, 11, 21, 25) +# - lka/lta msg drop out: 3 (recoverable) +# - prolonged high driver torque: 17 (permanent) +PERM_STEER_FAULTS = (3, 17) + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.eps_torque_scale = EPS_SCALE[CP.carFingerprint] / 100. + self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. + self.cluster_min_speed = CV.KPH_TO_MS / 2. + + if CP.flags & ToyotaFlags.SECOC.value: + self.shifter_values = can_define.dv["GEAR_PACKET_HYBRID"]["GEAR"] + else: + self.shifter_values = can_define.dv["GEAR_PACKET"]["GEAR"] + + # On cars with cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] + # the signal is zeroed to where the steering angle is at start. + # Need to apply an offset as soon as the steering angle measurements are both received + self.accurate_steer_angle_seen = False + self.angle_offset = FirstOrderFilter(None, 60.0, DT_CTRL, initialized=False) + + self.distance_button = 0 + + self.pcm_follow_distance = 0 + + self.acc_type = 1 + self.lkas_hud = {} + self.pcm_accel_net = 0.0 + self.secoc_synchronization = None + + def update(self, cp, cp_cam, *_) -> structs.CarState: + ret = structs.CarState() + cp_acc = cp_cam if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) else cp + + # Describes the acceleration request from the PCM if on flat ground, may be higher or lower if pitched + # CLUTCH->ACCEL_NET is only accurate for gas, PCM_CRUISE->ACCEL_NET is only accurate for brake + # These signals only have meaning when ACC is active + if "CLUTCH" in cp.vl: + self.pcm_accel_net = max(cp.vl["CLUTCH"]["ACCEL_NET"], 0.0) + + # Sometimes ACC_BRAKING can be 1 while showing we're applying gas already + if cp.vl["PCM_CRUISE"]["ACC_BRAKING"]: + self.pcm_accel_net += min(cp.vl["PCM_CRUISE"]["ACCEL_NET"], 0.0) + + # add creeping force at low speeds only for braking, CLUTCH->ACCEL_NET already shows this + neutral_accel = max(cp.vl["PCM_CRUISE"]["NEUTRAL_FORCE"] / self.CP.mass, 0.0) + if self.pcm_accel_net + neutral_accel < 0.0: + self.pcm_accel_net += neutral_accel + + ret.doorOpen = any([cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FR"], + cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RR"]]) + ret.seatbeltUnlatched = cp.vl["BODY_CONTROL_STATE"]["SEATBELT_DRIVER_UNLATCHED"] != 0 + ret.parkingBrake = cp.vl["BODY_CONTROL_STATE"]["PARKING_BRAKE"] == 1 + + ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 + ret.brakeHoldActive = cp.vl["ESP_CONTROL"]["BRAKE_HOLD_ACTIVE"] == 1 + + if self.CP.flags & ToyotaFlags.SECOC.value: + self.secoc_synchronization = copy.copy(cp.vl["SECOC_SYNCHRONIZATION"]) + ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL_USER"] + ret.gasPressed = cp.vl["GAS_PEDAL"]["GAS_PEDAL_USER"] > 0 + can_gear = int(cp.vl["GEAR_PACKET_HYBRID"]["GEAR"]) + else: + ret.gasPressed = cp.vl["PCM_CRUISE"]["GAS_RELEASED"] == 0 # TODO: these also have GAS_PEDAL, come back and unify + can_gear = int(cp.vl["GEAR_PACKET"]["GEAR"]) + if not self.CP.enableDsu and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: + ret.stockAeb = bool(cp_acc.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_acc.vl["PRE_COLLISION"]["FORCE"] < -1e-5) + if self.CP.carFingerprint != CAR.TOYOTA_MIRAI: + ret.engineRpm = cp.vl["ENGINE_RPM"]["RPM"] + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], + ) + ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]) + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.vEgoCluster = ret.vEgo * 1.015 # minimum of all the cars + + 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"] + torque_sensor_angle_deg = cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] + + # On some cars, the angle measurement is non-zero while initializing + if abs(torque_sensor_angle_deg) > 1e-3 and not bool(cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE_INITIALIZING"]): + self.accurate_steer_angle_seen = True + + if self.accurate_steer_angle_seen: + # Offset seems to be invalid for large steering angles and high angle rates + if abs(ret.steeringAngleDeg) < 90 and abs(ret.steeringRateDeg) < 100 and cp.can_valid: + self.angle_offset.update(torque_sensor_angle_deg - ret.steeringAngleDeg) + + if self.angle_offset.initialized: + ret.steeringAngleOffsetDeg = self.angle_offset.x + ret.steeringAngleDeg = torque_sensor_angle_deg - self.angle_offset.x + + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + ret.leftBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 1 + ret.rightBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 2 + + 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 + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + + # Check EPS LKA/LTA fault status + ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] in TEMP_STEER_FAULTS + ret.steerFaultPermanent = cp.vl["EPS_STATUS"]["LKA_STATE"] in PERM_STEER_FAULTS + + if self.CP.steerControlType == SteerControlType.angle: + ret.steerFaultTemporary = ret.steerFaultTemporary or cp.vl["EPS_STATUS"]["LTA_STATE"] in TEMP_STEER_FAULTS + ret.steerFaultPermanent = ret.steerFaultPermanent or cp.vl["EPS_STATUS"]["LTA_STATE"] in PERM_STEER_FAULTS + + # Lane Tracing Assist control is unavailable (EPS_STATUS->LTA_STATE=0) until + # the more accurate angle sensor signal is initialized + ret.vehicleSensorsInvalid = not self.accurate_steer_angle_seen + + if self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: + # TODO: find the bit likely in DSU_CRUISE that describes an ACC fault. one may also exist in CLUTCH + ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 + ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS + cluster_set_speed = cp.vl["PCM_CRUISE_ALT"]["UI_SET_SPEED"] + else: + ret.accFaulted = cp.vl["PCM_CRUISE_2"]["ACC_FAULTED"] != 0 + ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 + ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS + cluster_set_speed = cp.vl["PCM_CRUISE_SM"]["UI_SET_SPEED"] + + # UI_SET_SPEED is always non-zero when main is on, hide until first enable + if ret.cruiseState.speed != 0: + is_metric = cp.vl["BODY_CONTROL_STATE_2"]["UNITS"] in (1, 2) + conversion_factor = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS + ret.cruiseState.speedCluster = cluster_set_speed * conversion_factor + + if self.CP.carFingerprint in TSS2_CAR and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: + self.acc_type = cp_acc.vl["ACC_CONTROL"]["ACC_TYPE"] + ret.stockFcw = bool(cp_acc.vl["PCS_HUD"]["FCW"]) + + # some TSS2 cars have low speed lockout permanently set, so ignore on those cars + # these cars are identified by an ACC_TYPE value of 2. + # TODO: it is possible to avoid the lockout and gain stop and go if you + # send your own ACC_CONTROL msg on startup with ACC_TYPE set to 1 + if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR) or \ + (self.CP.carFingerprint in TSS2_CAR and self.acc_type == 1): + ret.accFaulted = ret.accFaulted or cp.vl["PCM_CRUISE_2"]["LOW_SPEED_LOCKOUT"] == 2 + + self.pcm_acc_status = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] + if self.CP.carFingerprint not in (NO_STOP_TIMER_CAR - TSS2_CAR): + # ignore standstill state in certain vehicles, since pcm allows to restart with just an acceleration request + ret.cruiseState.standstill = self.pcm_acc_status == 7 + ret.cruiseState.enabled = bool(cp.vl["PCM_CRUISE"]["CRUISE_ACTIVE"]) + ret.cruiseState.nonAdaptive = self.pcm_acc_status in (1, 2, 3, 4, 5, 6) + + ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"]) + ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 + + if self.CP.enableBsm: + ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1) + ret.rightBlindspot = (cp.vl["BSM"]["R_ADJACENT"] == 1) or (cp.vl["BSM"]["R_APPROACHING"] == 1) + + if self.CP.carFingerprint != CAR.TOYOTA_PRIUS_V: + self.lkas_hud = copy.copy(cp_cam.vl["LKAS_HUD"]) + + if self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR: + self.pcm_follow_distance = cp.vl["PCM_CRUISE_2"]["PCM_FOLLOW_DISTANCE"] + + if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): + # distance button is wired to the ACC module (camera or radar) + prev_distance_button = self.distance_button + self.distance_button = cp_acc.vl["ACC_CONTROL"]["DISTANCE"] + + ret.buttonEvents = create_button_events(self.distance_button, prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + ("LIGHT_STALK", 1), + ("BLINKERS_STATE", 0.15), + ("BODY_CONTROL_STATE", 3), + ("BODY_CONTROL_STATE_2", 2), + ("ESP_CONTROL", 3), + ("EPS_STATUS", 25), + ("BRAKE_MODULE", 40), + ("WHEEL_SPEEDS", 80), + ("STEER_ANGLE_SENSOR", 80), + ("PCM_CRUISE", 33), + ("PCM_CRUISE_SM", 1), + ("STEER_TORQUE_SENSOR", 50), + ] + + if CP.flags & ToyotaFlags.SECOC.value: + messages += [ + ("GEAR_PACKET_HYBRID", 60), + ("SECOC_SYNCHRONIZATION", 10), + ("GAS_PEDAL", 42), + ] + else: + if CP.carFingerprint not in [CAR.TOYOTA_MIRAI]: + messages.append(("ENGINE_RPM", 42)) + + messages += [ + ("GEAR_PACKET", 1), + ] + + if CP.carFingerprint in (TSS2_CAR - SECOC_CAR - {CAR.LEXUS_NX_TSS2, CAR.TOYOTA_ALPHARD_TSS2, CAR.LEXUS_IS_TSS2}): + messages.append(("CLUTCH", 15)) + + if CP.carFingerprint in UNSUPPORTED_DSU_CAR: + messages.append(("DSU_CRUISE", 5)) + messages.append(("PCM_CRUISE_ALT", 1)) + else: + messages.append(("PCM_CRUISE_2", 33)) + + if CP.enableBsm: + messages.append(("BSM", 1)) + + if CP.carFingerprint in RADAR_ACC_CAR and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: + messages += [ + ("PCS_HUD", 1), + ("ACC_CONTROL", 33), + ] + + if CP.carFingerprint not in (TSS2_CAR - RADAR_ACC_CAR) and not CP.enableDsu and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: + messages += [ + ("PRE_COLLISION", 33), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_cam_can_parser(CP): + messages = [] + + if CP.carFingerprint != CAR.TOYOTA_PRIUS_V: + messages += [ + ("LKAS_HUD", 1), + ] + + if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): + messages += [ + ("ACC_CONTROL", 33), + ("PCS_HUD", 1), + ] + + # TODO: Figure out new layout of the PRE_COLLISION message + if not CP.flags & ToyotaFlags.SECOC.value: + messages += [ + ("PRE_COLLISION", 33), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/opendbc_repo/opendbc/car/toyota/fingerprints.py b/opendbc_repo/opendbc/car/toyota/fingerprints.py new file mode 100644 index 000000000000000..dbe91fd6a49f937 --- /dev/null +++ b/opendbc_repo/opendbc/car/toyota/fingerprints.py @@ -0,0 +1,1760 @@ +from opendbc.car.structs import CarParams +from opendbc.car.toyota.values import CAR + +Ecu = CarParams.Ecu + +FW_VERSIONS = { + CAR.TOYOTA_AVALON: { + (Ecu.abs, 0x7b0, None): [ + b'F152607060\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510701300\x00\x00\x00\x00', + b'881510705100\x00\x00\x00\x00', + b'881510705200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B41051\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0701100\x00\x00\x00\x00', + b'8646F0703000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_AVALON_2019: { + (Ecu.abs, 0x7b0, None): [ + b'F152607110\x00\x00\x00\x00\x00\x00', + b'F152607140\x00\x00\x00\x00\x00\x00', + b'F152607171\x00\x00\x00\x00\x00\x00', + b'F152607180\x00\x00\x00\x00\x00\x00', + b'F152641040\x00\x00\x00\x00\x00\x00', + b'F152641050\x00\x00\x00\x00\x00\x00', + b'F152641060\x00\x00\x00\x00\x00\x00', + b'F152641061\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510703200\x00\x00\x00\x00', + b'881510704200\x00\x00\x00\x00', + b'881514107100\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B07010\x00\x00\x00\x00\x00\x00', + b'8965B41070\x00\x00\x00\x00\x00\x00', + b'8965B41080\x00\x00\x00\x00\x00\x00', + b'8965B41090\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896630725100\x00\x00\x00\x00', + b'\x01896630725200\x00\x00\x00\x00', + b'\x01896630725300\x00\x00\x00\x00', + b'\x01896630725400\x00\x00\x00\x00', + b'\x01896630735100\x00\x00\x00\x00', + b'\x01896630738000\x00\x00\x00\x00', + b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x02896630728000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x02896630734000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x02896630737000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0702100\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_AVALON_TSS2: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F152607240\x00\x00\x00\x00\x00\x00', + b'\x01F152607250\x00\x00\x00\x00\x00\x00', + b'\x01F152607280\x00\x00\x00\x00\x00\x00', + b'F152641080\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B41110\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x01896630742000\x00\x00\x00\x00', + b'\x01896630743000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_CAMRY: { + (Ecu.engine, 0x700, None): [ + b'\x018966306L3100\x00\x00\x00\x00', + b'\x018966306L4200\x00\x00\x00\x00', + b'\x018966306L5200\x00\x00\x00\x00', + b'\x018966306L9000\x00\x00\x00\x00', + b'\x018966306P8000\x00\x00\x00\x00', + b'\x018966306Q3100\x00\x00\x00\x00', + b'\x018966306Q4000\x00\x00\x00\x00', + b'\x018966306Q4100\x00\x00\x00\x00', + b'\x018966306Q4200\x00\x00\x00\x00', + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x018966333N1100\x00\x00\x00\x00', + b'\x018966333N4300\x00\x00\x00\x00', + b'\x018966333P3100\x00\x00\x00\x00', + b'\x018966333P3200\x00\x00\x00\x00', + b'\x018966333P4200\x00\x00\x00\x00', + b'\x018966333P4300\x00\x00\x00\x00', + b'\x018966333P4400\x00\x00\x00\x00', + b'\x018966333P4500\x00\x00\x00\x00', + b'\x018966333P4700\x00\x00\x00\x00', + b'\x018966333P4900\x00\x00\x00\x00', + b'\x018966333Q6000\x00\x00\x00\x00', + b'\x018966333Q6200\x00\x00\x00\x00', + b'\x018966333Q6300\x00\x00\x00\x00', + b'\x018966333Q6500\x00\x00\x00\x00', + b'\x018966333Q9200\x00\x00\x00\x00', + b'\x018966333W6000\x00\x00\x00\x00', + b'\x018966333X0000\x00\x00\x00\x00', + b'\x018966333X4000\x00\x00\x00\x00', + b'\x01896633T16000\x00\x00\x00\x00', + b'\x01896633TA2000\x00\x00\x00\x00', + b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306B2500\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8200\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8400\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R5000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R6000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S0000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02333P1100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'8821F0601200 ', + b'8821F0601300 ', + b'8821F0601400 ', + b'8821F0601500 ', + b'8821F0602000 ', + b'8821F0603300 ', + b'8821F0603400 ', + b'8821F0604000 ', + b'8821F0604100 ', + b'8821F0604200 ', + b'8821F0605200 ', + b'8821F0606200 ', + b'8821F0607200 ', + b'8821F0608000 ', + b'8821F0608200 ', + b'8821F0608300 ', + b'8821F0609000 ', + b'8821F0609100 ', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152606210\x00\x00\x00\x00\x00\x00', + b'F152606230\x00\x00\x00\x00\x00\x00', + b'F152606260\x00\x00\x00\x00\x00\x00', + b'F152606270\x00\x00\x00\x00\x00\x00', + b'F152606290\x00\x00\x00\x00\x00\x00', + b'F152606410\x00\x00\x00\x00\x00\x00', + b'F152633214\x00\x00\x00\x00\x00\x00', + b'F152633540\x00\x00\x00\x00\x00\x00', + b'F152633660\x00\x00\x00\x00\x00\x00', + b'F152633712\x00\x00\x00\x00\x00\x00', + b'F152633713\x00\x00\x00\x00\x00\x00', + b'F152633A10\x00\x00\x00\x00\x00\x00', + b'F152633A20\x00\x00\x00\x00\x00\x00', + b'F152633B51\x00\x00\x00\x00\x00\x00', + b'F152633B60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33540\x00\x00\x00\x00\x00\x00', + b'8965B33542\x00\x00\x00\x00\x00\x00', + b'8965B33550\x00\x00\x00\x00\x00\x00', + b'8965B33551\x00\x00\x00\x00\x00\x00', + b'8965B33580\x00\x00\x00\x00\x00\x00', + b'8965B33581\x00\x00\x00\x00\x00\x00', + b'8965B33611\x00\x00\x00\x00\x00\x00', + b'8965B33621\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F0601200 ', + b'8821F0601300 ', + b'8821F0601400 ', + b'8821F0601500 ', + b'8821F0602000 ', + b'8821F0603300 ', + b'8821F0603400 ', + b'8821F0604000 ', + b'8821F0604100 ', + b'8821F0604200 ', + b'8821F0605200 ', + b'8821F0606200 ', + b'8821F0607200 ', + b'8821F0608000 ', + b'8821F0608200 ', + b'8821F0608300 ', + b'8821F0609000 ', + b'8821F0609100 ', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0601200 ', + b'8646F0601300 ', + b'8646F0601400 ', + b'8646F0603400 ', + b'8646F0603500 ', + b'8646F0604000 ', + b'8646F0604100 ', + b'8646F0605000 ', + b'8646F0606000 ', + b'8646F0606100 ', + b'8646F0607000 ', + b'8646F0607100 ', + ], + }, + CAR.TOYOTA_CAMRY_TSS2: { + (Ecu.eps, 0x7a1, None): [ + b'8965B33630\x00\x00\x00\x00\x00\x00', + b'8965B33640\x00\x00\x00\x00\x00\x00', + b'8965B33650\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152606370\x00\x00\x00\x00\x00\x00', + b'\x01F152606390\x00\x00\x00\x00\x00\x00', + b'\x01F152606400\x00\x00\x00\x00\x00\x00', + b'\x01F152606431\x00\x00\x00\x00\x00\x00', + b'\x01F152633E11\x00\x00\x00\x00\x00\x00', + b'F152633310\x00\x00\x00\x00\x00\x00', + b'F152633D00\x00\x00\x00\x00\x00\x00', + b'F152633D60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x018966306Q5000\x00\x00\x00\x00', + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x018966306Q7000\x00\x00\x00\x00', + b'\x018966306Q9000\x00\x00\x00\x00', + b'\x018966306R3000\x00\x00\x00\x00', + b'\x018966306R8000\x00\x00\x00\x00', + b'\x018966306T0000\x00\x00\x00\x00', + b'\x018966306T3100\x00\x00\x00\x00', + b'\x018966306T3200\x00\x00\x00\x00', + b'\x018966306T4000\x00\x00\x00\x00', + b'\x018966306T4100\x00\x00\x00\x00', + b'\x018966306V1000\x00\x00\x00\x00', + b'\x018966333Z1000\x00\x00\x00\x00', + b'\x01896633T20000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0602100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F0602200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F0602300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F3305300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F3305400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305500\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_CHR: { + (Ecu.engine, 0x700, None): [ + b'\x01896631017100\x00\x00\x00\x00', + b'\x01896631017200\x00\x00\x00\x00', + b'\x01896631021100\x00\x00\x00\x00', + b'\x0189663F413100\x00\x00\x00\x00', + b'\x0189663F414100\x00\x00\x00\x00', + b'\x0189663F438000\x00\x00\x00\x00', + b'\x02896631013200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F405000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F405100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F418000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'8821F0W01000 ', + b'8821F0W01100 ', + b'8821FF401600 ', + b'8821FF402300 ', + b'8821FF402400 ', + b'8821FF404000 ', + b'8821FF404100 ', + b'8821FF405000 ', + b'8821FF405100 ', + b'8821FF406000 ', + b'8821FF407100 ', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152610012\x00\x00\x00\x00\x00\x00', + b'F152610013\x00\x00\x00\x00\x00\x00', + b'F152610014\x00\x00\x00\x00\x00\x00', + b'F152610020\x00\x00\x00\x00\x00\x00', + b'F152610040\x00\x00\x00\x00\x00\x00', + b'F152610153\x00\x00\x00\x00\x00\x00', + b'F152610190\x00\x00\x00\x00\x00\x00', + b'F152610200\x00\x00\x00\x00\x00\x00', + b'F152610210\x00\x00\x00\x00\x00\x00', + b'F152610220\x00\x00\x00\x00\x00\x00', + b'F152610230\x00\x00\x00\x00\x00\x00', + b'F1526F4034\x00\x00\x00\x00\x00\x00', + b'F1526F4044\x00\x00\x00\x00\x00\x00', + b'F1526F4073\x00\x00\x00\x00\x00\x00', + b'F1526F4121\x00\x00\x00\x00\x00\x00', + b'F1526F4122\x00\x00\x00\x00\x00\x00', + b'F1526F4190\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', + b'\x033F435000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F0W01000 ', + b'8821F0W01100 ', + b'8821FF401600 ', + b'8821FF402300 ', + b'8821FF402400 ', + b'8821FF404000 ', + b'8821FF404100 ', + b'8821FF405000 ', + b'8821FF405100 ', + b'8821FF406000 ', + b'8821FF407100 ', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646FF401700 ', + b'8646FF401800 ', + b'8646FF402100 ', + b'8646FF404000 ', + b'8646FF406000 ', + b'8646FF407000 ', + b'8646FF407100 ', + ], + }, + CAR.TOYOTA_CHR_TSS2: { + (Ecu.abs, 0x7b0, None): [ + b'F152610041\x00\x00\x00\x00\x00\x00', + b'F152610260\x00\x00\x00\x00\x00\x00', + b'F1526F4270\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B10091\x00\x00\x00\x00\x00\x00', + b'8965B10092\x00\x00\x00\x00\x00\x00', + b'8965B10110\x00\x00\x00\x00\x00\x00', + b'8965B10111\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x0189663F438000\x00\x00\x00\x00', + b'\x0189663F459000\x00\x00\x00\x00', + b'\x02896631025000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F453000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0331014000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821FF410200\x00\x00\x00\x00', + b'\x018821FF410300\x00\x00\x00\x00', + b'\x018821FF410400\x00\x00\x00\x00', + b'\x018821FF410500\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00', + b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00', + b'\x028646FF413000\x00\x00\x00\x008646GF411000\x00\x00\x00\x00', + b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_COROLLA: { + (Ecu.engine, 0x7e0, None): [ + b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0330ZC1200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510201100\x00\x00\x00\x00', + b'881510201200\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152602190\x00\x00\x00\x00\x00\x00', + b'F152602191\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B02181\x00\x00\x00\x00\x00\x00', + b'8965B02191\x00\x00\x00\x00\x00\x00', + b'8965B48150\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0201101\x00\x00\x00\x00', + b'8646F0201200\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_COROLLA_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630A22000\x00\x00\x00\x00', + b'\x01896630A42000\x00\x00\x00\x00', + b'\x01896630ZG2000\x00\x00\x00\x00', + b'\x01896630ZG5000\x00\x00\x00\x00', + b'\x01896630ZG5100\x00\x00\x00\x00', + b'\x01896630ZG5200\x00\x00\x00\x00', + b'\x01896630ZG5300\x00\x00\x00\x00', + b'\x01896630ZJ1000\x00\x00\x00\x00', + b'\x01896630ZP1000\x00\x00\x00\x00', + b'\x01896630ZP2000\x00\x00\x00\x00', + b'\x01896630ZQ5000\x00\x00\x00\x00', + b'\x01896630ZU8000\x00\x00\x00\x00', + b'\x01896630ZU9000\x00\x00\x00\x00', + b'\x01896630ZX4000\x00\x00\x00\x00', + b'\x01896630ZX7100\x00\x00\x00\x00', + b'\x018966312L8000\x00\x00\x00\x00', + b'\x018966312M0000\x00\x00\x00\x00', + b'\x018966312M9000\x00\x00\x00\x00', + b'\x018966312P9000\x00\x00\x00\x00', + b'\x018966312P9100\x00\x00\x00\x00', + b'\x018966312P9200\x00\x00\x00\x00', + b'\x018966312P9300\x00\x00\x00\x00', + b'\x018966312Q2300\x00\x00\x00\x00', + b'\x018966312Q8000\x00\x00\x00\x00', + b'\x018966312R0000\x00\x00\x00\x00', + b'\x018966312R0100\x00\x00\x00\x00', + b'\x018966312R0200\x00\x00\x00\x00', + b'\x018966312R1000\x00\x00\x00\x00', + b'\x018966312R1100\x00\x00\x00\x00', + b'\x018966312R3100\x00\x00\x00\x00', + b'\x018966312S5000\x00\x00\x00\x00', + b'\x018966312S7000\x00\x00\x00\x00', + b'\x018966312W3000\x00\x00\x00\x00', + b'\x018966312W9000\x00\x00\x00\x00', + b'\x01896637621000\x00\x00\x00\x00', + b'\x01896637623000\x00\x00\x00\x00', + b'\x01896637624000\x00\x00\x00\x00', + b'\x01896637626000\x00\x00\x00\x00', + b'\x01896637639000\x00\x00\x00\x00', + b'\x01896637643000\x00\x00\x00\x00', + b'\x01896637644000\x00\x00\x00\x00', + b'\x01896637648000\x00\x00\x00\x00', + b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZK8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZT8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZT9000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZZ0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312K6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312L0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q3100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', + b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x038966312T3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230A10000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230A11000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZN5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x03312K7000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312M3000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x018965B12350\x00\x00\x00\x00\x00\x00', + b'\x018965B12470\x00\x00\x00\x00\x00\x00', + b'\x018965B12490\x00\x00\x00\x00\x00\x00', + b'\x018965B12500\x00\x00\x00\x00\x00\x00', + b'\x018965B12510\x00\x00\x00\x00\x00\x00', + b'\x018965B12520\x00\x00\x00\x00\x00\x00', + b'\x018965B12530\x00\x00\x00\x00\x00\x00', + b'\x018965B1254000\x00\x00\x00\x00', + b'\x018965B1255000\x00\x00\x00\x00', + b'\x018965B1256000\x00\x00\x00\x00', + b'\x018965B1270000\x00\x00\x00\x00', + b'8965B12361\x00\x00\x00\x00\x00\x00', + b'8965B12451\x00\x00\x00\x00\x00\x00', + b'8965B16011\x00\x00\x00\x00\x00\x00', + b'8965B16101\x00\x00\x00\x00\x00\x00', + b'8965B16170\x00\x00\x00\x00\x00\x00', + b'8965B16260\x00\x00\x00\x00\x00\x00', + b'8965B76012\x00\x00\x00\x00\x00\x00', + b'8965B76050\x00\x00\x00\x00\x00\x00', + b'8965B76091\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152602280\x00\x00\x00\x00\x00\x00', + b'\x01F152602281\x00\x00\x00\x00\x00\x00', + b'\x01F152602470\x00\x00\x00\x00\x00\x00', + b'\x01F152602560\x00\x00\x00\x00\x00\x00', + b'\x01F152602590\x00\x00\x00\x00\x00\x00', + b'\x01F152602650\x00\x00\x00\x00\x00\x00', + b'\x01F15260A010\x00\x00\x00\x00\x00\x00', + b'\x01F15260A050\x00\x00\x00\x00\x00\x00', + b'\x01F15260A070\x00\x00\x00\x00\x00\x00', + b'\x01F15260A33000\x00\x00\x00\x00', + b'\x01F152612641\x00\x00\x00\x00\x00\x00', + b'\x01F152612651\x00\x00\x00\x00\x00\x00', + b'\x01F152612862\x00\x00\x00\x00\x00\x00', + b'\x01F152612B10\x00\x00\x00\x00\x00\x00', + b'\x01F152612B51\x00\x00\x00\x00\x00\x00', + b'\x01F152612B60\x00\x00\x00\x00\x00\x00', + b'\x01F152612B61\x00\x00\x00\x00\x00\x00', + b'\x01F152612B62\x00\x00\x00\x00\x00\x00', + b'\x01F152612B70\x00\x00\x00\x00\x00\x00', + b'\x01F152612B71\x00\x00\x00\x00\x00\x00', + b'\x01F152612B81\x00\x00\x00\x00\x00\x00', + b'\x01F152612B90\x00\x00\x00\x00\x00\x00', + b'\x01F152612B91\x00\x00\x00\x00\x00\x00', + b'\x01F152612C00\x00\x00\x00\x00\x00\x00', + b'\x01F152676250\x00\x00\x00\x00\x00\x00', + b'F152612590\x00\x00\x00\x00\x00\x00', + b'F152612691\x00\x00\x00\x00\x00\x00', + b'F152612692\x00\x00\x00\x00\x00\x00', + b'F152612700\x00\x00\x00\x00\x00\x00', + b'F152612710\x00\x00\x00\x00\x00\x00', + b'F152612790\x00\x00\x00\x00\x00\x00', + b'F152612800\x00\x00\x00\x00\x00\x00', + b'F152612820\x00\x00\x00\x00\x00\x00', + b'F152612840\x00\x00\x00\x00\x00\x00', + b'F152612842\x00\x00\x00\x00\x00\x00', + b'F152612890\x00\x00\x00\x00\x00\x00', + b'F152612A00\x00\x00\x00\x00\x00\x00', + b'F152612A10\x00\x00\x00\x00\x00\x00', + b'F152612D00\x00\x00\x00\x00\x00\x00', + b'F152616011\x00\x00\x00\x00\x00\x00', + b'F152616030\x00\x00\x00\x00\x00\x00', + b'F152616060\x00\x00\x00\x00\x00\x00', + b'F152642540\x00\x00\x00\x00\x00\x00', + b'F152676293\x00\x00\x00\x00\x00\x00', + b'F152676303\x00\x00\x00\x00\x00\x00', + b'F152676304\x00\x00\x00\x00\x00\x00', + b'F152676371\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F12010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1201400\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1206000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1601500\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F7603300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F7605100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_HIGHLANDER: { + (Ecu.engine, 0x700, None): [ + b'\x01896630E09000\x00\x00\x00\x00', + b'\x01896630E43000\x00\x00\x00\x00', + b'\x01896630E43100\x00\x00\x00\x00', + b'\x01896630E43200\x00\x00\x00\x00', + b'\x01896630E44200\x00\x00\x00\x00', + b'\x01896630E44400\x00\x00\x00\x00', + b'\x01896630E45000\x00\x00\x00\x00', + b'\x01896630E45100\x00\x00\x00\x00', + b'\x01896630E45200\x00\x00\x00\x00', + b'\x01896630E46000\x00\x00\x00\x00', + b'\x01896630E46200\x00\x00\x00\x00', + b'\x01896630E74000\x00\x00\x00\x00', + b'\x01896630E75000\x00\x00\x00\x00', + b'\x01896630E76000\x00\x00\x00\x00', + b'\x01896630E77000\x00\x00\x00\x00', + b'\x01896630E83000\x00\x00\x00\x00', + b'\x01896630E84000\x00\x00\x00\x00', + b'\x01896630E85000\x00\x00\x00\x00', + b'\x01896630E86000\x00\x00\x00\x00', + b'\x01896630E88000\x00\x00\x00\x00', + b'\x01896630EA0000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230E40100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230E51000\x00\x00\x00\x00\x00\x00\x00\x0050E17000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230EA2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230EA2100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48140\x00\x00\x00\x00\x00\x00', + b'8965B48150\x00\x00\x00\x00\x00\x00', + b'8965B48160\x00\x00\x00\x00\x00\x00', + b'8965B48210\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F15260E011\x00\x00\x00\x00\x00\x00', + b'F152648541\x00\x00\x00\x00\x00\x00', + b'F152648542\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510E01100\x00\x00\x00\x00', + b'881510E01200\x00\x00\x00\x00', + b'881510E02100\x00\x00\x00\x00', + b'881510E02200\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0E01200\x00\x00\x00\x00', + b'8646F0E01300\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_HIGHLANDER_TSS2: { + (Ecu.eps, 0x7a1, None): [ + b'8965B48241\x00\x00\x00\x00\x00\x00', + b'8965B48310\x00\x00\x00\x00\x00\x00', + b'8965B48320\x00\x00\x00\x00\x00\x00', + b'8965B48400\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260E051\x00\x00\x00\x00\x00\x00', + b'\x01F15260E05300\x00\x00\x00\x00', + b'\x01F15260E061\x00\x00\x00\x00\x00\x00', + b'\x01F15260E110\x00\x00\x00\x00\x00\x00', + b'\x01F15260E170\x00\x00\x00\x00\x00\x00', + b'\x01F15264872300\x00\x00\x00\x00', + b'\x01F15264872400\x00\x00\x00\x00', + b'\x01F15264872500\x00\x00\x00\x00', + b'\x01F15264872600\x00\x00\x00\x00', + b'\x01F15264872700\x00\x00\x00\x00', + b'\x01F15264873500\x00\x00\x00\x00', + b'\x01F152648C6300\x00\x00\x00\x00', + b'\x01F152648J4000\x00\x00\x00\x00', + b'\x01F152648J5000\x00\x00\x00\x00', + b'\x01F152648J6000\x00\x00\x00\x00', + b'\x01F152648J7000\x00\x00\x00\x00', + b'\x01F152648L5000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896630E62100\x00\x00\x00\x00', + b'\x01896630E62200\x00\x00\x00\x00', + b'\x01896630E64100\x00\x00\x00\x00', + b'\x01896630E64200\x00\x00\x00\x00', + b'\x01896630E64400\x00\x00\x00\x00', + b'\x01896630E67000\x00\x00\x00\x00', + b'\x01896630EA1000\x00\x00\x00\x00', + b'\x01896630EB1000\x00\x00\x00\x00', + b'\x01896630EB1100\x00\x00\x00\x00', + b'\x01896630EB1200\x00\x00\x00\x00', + b'\x01896630EB1300\x00\x00\x00\x00', + b'\x01896630EB2000\x00\x00\x00\x00', + b'\x01896630EB2100\x00\x00\x00\x00', + b'\x01896630EB2200\x00\x00\x00\x00', + b'\x01896630EC4000\x00\x00\x00\x00', + b'\x01896630ED9000\x00\x00\x00\x00', + b'\x01896630ED9100\x00\x00\x00\x00', + b'\x01896630EE1000\x00\x00\x00\x00', + b'\x01896630EE1100\x00\x00\x00\x00', + b'\x01896630EE4000\x00\x00\x00\x00', + b'\x01896630EE4100\x00\x00\x00\x00', + b'\x01896630EE5000\x00\x00\x00\x00', + b'\x01896630EE6000\x00\x00\x00\x00', + b'\x01896630EE7000\x00\x00\x00\x00', + b'\x01896630EF8000\x00\x00\x00\x00', + b'\x01896630EG3000\x00\x00\x00\x00', + b'\x01896630EG3100\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', + b'\x02896630EB3200\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_IS: { + (Ecu.engine, 0x700, None): [ + b'\x018966353M7000\x00\x00\x00\x00', + b'\x018966353M7100\x00\x00\x00\x00', + b'\x018966353Q2000\x00\x00\x00\x00', + b'\x018966353Q2100\x00\x00\x00\x00', + b'\x018966353Q2300\x00\x00\x00\x00', + b'\x018966353Q4000\x00\x00\x00\x00', + b'\x018966353R1100\x00\x00\x00\x00', + b'\x018966353R7100\x00\x00\x00\x00', + b'\x018966353R8000\x00\x00\x00\x00', + b'\x018966353R8100\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0232480000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152653300\x00\x00\x00\x00\x00\x00', + b'F152653301\x00\x00\x00\x00\x00\x00', + b'F152653310\x00\x00\x00\x00\x00\x00', + b'F152653330\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881515306200\x00\x00\x00\x00', + b'881515306400\x00\x00\x00\x00', + b'881515306500\x00\x00\x00\x00', + b'881515307400\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B53270\x00\x00\x00\x00\x00\x00', + b'8965B53271\x00\x00\x00\x00\x00\x00', + b'8965B53280\x00\x00\x00\x00\x00\x00', + b'8965B53281\x00\x00\x00\x00\x00\x00', + b'8965B53311\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F5301101\x00\x00\x00\x00', + b'8646F5301200\x00\x00\x00\x00', + b'8646F5301300\x00\x00\x00\x00', + b'8646F5301400\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_IS_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966353S1000\x00\x00\x00\x00', + b'\x018966353S2000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02353U0000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15265337200\x00\x00\x00\x00', + b'\x01F15265342000\x00\x00\x00\x00', + b'\x01F15265343000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B53450\x00\x00\x00\x00\x00\x00', + b'8965B53800\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F5303300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F5303300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F5303400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_PRIUS: { + (Ecu.engine, 0x700, None): [ + b'\x02896634761000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634761100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634761200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634762000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634762100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634763000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634763100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634770000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634770100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634782000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347B0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701002\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703001\x00\x00\x00\x00', + b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x03896634768100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', + b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', + b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', + b'\x038966347B6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B47021\x00\x00\x00\x00\x00\x00', + b'8965B47022\x00\x00\x00\x00\x00\x00', + b'8965B47023\x00\x00\x00\x00\x00\x00', + b'8965B47050\x00\x00\x00\x00\x00\x00', + b'8965B47060\x00\x00\x00\x00\x00\x00', + b'8965B47070\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152647290\x00\x00\x00\x00\x00\x00', + b'F152647300\x00\x00\x00\x00\x00\x00', + b'F152647310\x00\x00\x00\x00\x00\x00', + b'F152647414\x00\x00\x00\x00\x00\x00', + b'F152647415\x00\x00\x00\x00\x00\x00', + b'F152647416\x00\x00\x00\x00\x00\x00', + b'F152647417\x00\x00\x00\x00\x00\x00', + b'F152647470\x00\x00\x00\x00\x00\x00', + b'F152647490\x00\x00\x00\x00\x00\x00', + b'F152647682\x00\x00\x00\x00\x00\x00', + b'F152647683\x00\x00\x00\x00\x00\x00', + b'F152647684\x00\x00\x00\x00\x00\x00', + b'F152647862\x00\x00\x00\x00\x00\x00', + b'F152647863\x00\x00\x00\x00\x00\x00', + b'F152647864\x00\x00\x00\x00\x00\x00', + b'F152647865\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514702300\x00\x00\x00\x00', + b'881514702400\x00\x00\x00\x00', + b'881514703100\x00\x00\x00\x00', + b'881514704100\x00\x00\x00\x00', + b'881514706000\x00\x00\x00\x00', + b'881514706100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4701300\x00\x00\x00\x00', + b'8646F4702001\x00\x00\x00\x00', + b'8646F4702100\x00\x00\x00\x00', + b'8646F4702200\x00\x00\x00\x00', + b'8646F4705000\x00\x00\x00\x00', + b'8646F4705200\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_PRIUS_V: { + (Ecu.abs, 0x7b0, None): [ + b'F152647280\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0234781000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514705100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4703300\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4: { + (Ecu.engine, 0x7e0, None): [ + b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1100\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1200\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1300\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2000\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2100\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2200\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q4000\x00\x00\x00\x00\x00\x00\x00\x0054215000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B42063\x00\x00\x00\x00\x00\x00', + b'8965B42073\x00\x00\x00\x00\x00\x00', + b'8965B42082\x00\x00\x00\x00\x00\x00', + b'8965B42083\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F15260R102\x00\x00\x00\x00\x00\x00', + b'F15260R103\x00\x00\x00\x00\x00\x00', + b'F152642492\x00\x00\x00\x00\x00\x00', + b'F152642493\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514201200\x00\x00\x00\x00', + b'881514201300\x00\x00\x00\x00', + b'881514201400\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4201100\x00\x00\x00\x00', + b'8646F4201200\x00\x00\x00\x00', + b'8646F4202001\x00\x00\x00\x00', + b'8646F4202100\x00\x00\x00\x00', + b'8646F4204000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4H: { + (Ecu.engine, 0x7e0, None): [ + b'\x02342N9000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342N9100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342P0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B42102\x00\x00\x00\x00\x00\x00', + b'8965B42103\x00\x00\x00\x00\x00\x00', + b'8965B42112\x00\x00\x00\x00\x00\x00', + b'8965B42162\x00\x00\x00\x00\x00\x00', + b'8965B42163\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152642090\x00\x00\x00\x00\x00\x00', + b'F152642110\x00\x00\x00\x00\x00\x00', + b'F152642120\x00\x00\x00\x00\x00\x00', + b'F152642400\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514202200\x00\x00\x00\x00', + b'881514202300\x00\x00\x00\x00', + b'881514202400\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4201100\x00\x00\x00\x00', + b'8646F4201200\x00\x00\x00\x00', + b'8646F4202001\x00\x00\x00\x00', + b'8646F4202100\x00\x00\x00\x00', + b'8646F4204000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4_PRIME: { + (Ecu.engine, 0x700, None): [ + b'\x018966342S7000\x00\x00\x00\x00', + b'\x018966342Z1000\x00\x00\x00\x00', + b'\x018966342Z1100\x00\x00\x00\x00', + b'\x01896634AJ7000\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15264228300\x00\x00\x00\x00', + b'\x01F15264228500\x00\x00\x00\x00', + b'\x01F15264284100\x00\x00\x00\x00', + b'\x01F152642F3000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x018965B4209000\x00\x00\x00\x00', + b'\x018965B4233100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4205200\x00\x00\x00\x008646G4202000\x00\x00\x00\x00', + b'\x028646F4205300\x00\x00\x00\x008646G4202100\x00\x00\x00\x00', + b'\x028646F4210100\x00\x00\x00\x008646G3305000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630R58000\x00\x00\x00\x00', + b'\x01896630R58100\x00\x00\x00\x00', + b'\x018966342E2000\x00\x00\x00\x00', + b'\x018966342M5000\x00\x00\x00\x00', + b'\x018966342M8000\x00\x00\x00\x00', + b'\x018966342S9000\x00\x00\x00\x00', + b'\x018966342T1000\x00\x00\x00\x00', + b'\x018966342T6000\x00\x00\x00\x00', + b'\x018966342T9000\x00\x00\x00\x00', + b'\x018966342U4000\x00\x00\x00\x00', + b'\x018966342U4100\x00\x00\x00\x00', + b'\x018966342U5100\x00\x00\x00\x00', + b'\x018966342V0000\x00\x00\x00\x00', + b'\x018966342V3000\x00\x00\x00\x00', + b'\x018966342V3100\x00\x00\x00\x00', + b'\x018966342V3200\x00\x00\x00\x00', + b'\x018966342W5000\x00\x00\x00\x00', + b'\x018966342W7000\x00\x00\x00\x00', + b'\x018966342W8000\x00\x00\x00\x00', + b'\x018966342X5000\x00\x00\x00\x00', + b'\x018966342X6000\x00\x00\x00\x00', + b'\x01896634A05000\x00\x00\x00\x00', + b'\x01896634A15000\x00\x00\x00\x00', + b'\x01896634A19000\x00\x00\x00\x00', + b'\x01896634A19100\x00\x00\x00\x00', + b'\x01896634A20000\x00\x00\x00\x00', + b'\x01896634A20100\x00\x00\x00\x00', + b'\x01896634A22000\x00\x00\x00\x00', + b'\x01896634A22100\x00\x00\x00\x00', + b'\x01896634A25000\x00\x00\x00\x00', + b'\x01896634A30000\x00\x00\x00\x00', + b'\x01896634A44000\x00\x00\x00\x00', + b'\x01896634A45000\x00\x00\x00\x00', + b'\x01896634A46000\x00\x00\x00\x00', + b'\x028966342M7000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342T0000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342V1000\x00\x00\x00\x00897CF1202001\x00\x00\x00\x00', + b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A13000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02896634A13001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A13101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A13201\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF0R01000\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A23000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A23101\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', + b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R210\x00\x00\x00\x00\x00\x00', + b'\x01F15260R220\x00\x00\x00\x00\x00\x00', + b'\x01F15260R290\x00\x00\x00\x00\x00\x00', + b'\x01F15260R292\x00\x00\x00\x00\x00\x00', + b'\x01F15260R300\x00\x00\x00\x00\x00\x00', + b'\x01F15260R302\x00\x00\x00\x00\x00\x00', + b'\x01F152642551\x00\x00\x00\x00\x00\x00', + b'\x01F152642561\x00\x00\x00\x00\x00\x00', + b'\x01F152642601\x00\x00\x00\x00\x00\x00', + b'\x01F152642700\x00\x00\x00\x00\x00\x00', + b'\x01F152642701\x00\x00\x00\x00\x00\x00', + b'\x01F152642710\x00\x00\x00\x00\x00\x00', + b'\x01F152642711\x00\x00\x00\x00\x00\x00', + b'\x01F152642750\x00\x00\x00\x00\x00\x00', + b'\x01F152642751\x00\x00\x00\x00\x00\x00', + b'F152642290\x00\x00\x00\x00\x00\x00', + b'F152642291\x00\x00\x00\x00\x00\x00', + b'F152642322\x00\x00\x00\x00\x00\x00', + b'F152642330\x00\x00\x00\x00\x00\x00', + b'F152642331\x00\x00\x00\x00\x00\x00', + b'F152642520\x00\x00\x00\x00\x00\x00', + b'F152642521\x00\x00\x00\x00\x00\x00', + b'F152642531\x00\x00\x00\x00\x00\x00', + b'F152642532\x00\x00\x00\x00\x00\x00', + b'F152642540\x00\x00\x00\x00\x00\x00', + b'F152642541\x00\x00\x00\x00\x00\x00', + b'F152642542\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', + b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', + b'\x028965B0R01400\x00\x00\x00\x008965B0R02400\x00\x00\x00\x00', + b'8965B42170\x00\x00\x00\x00\x00\x00', + b'8965B42171\x00\x00\x00\x00\x00\x00', + b'8965B42180\x00\x00\x00\x00\x00\x00', + b'8965B42181\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4203200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4_TSS2_2022: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R350\x00\x00\x00\x00\x00\x00', + b'\x01F15260R361\x00\x00\x00\x00\x00\x00', + b'\x01F15264283100\x00\x00\x00\x00', + b'\x01F15264283200\x00\x00\x00\x00', + b'\x01F15264286100\x00\x00\x00\x00', + b'\x01F15264286200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', + b'8965B42172\x00\x00\x00\x00\x00\x00', + b'8965B42182\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896634A02001\x00\x00\x00\x00', + b'\x01896634A03000\x00\x00\x00\x00', + b'\x01896634A08000\x00\x00\x00\x00', + b'\x01896634A61000\x00\x00\x00\x00', + b'\x01896634A62000\x00\x00\x00\x00', + b'\x01896634A62100\x00\x00\x00\x00', + b'\x01896634A63000\x00\x00\x00\x00', + b'\x01896634A88000\x00\x00\x00\x00', + b'\x01896634A89000\x00\x00\x00\x00', + b'\x01896634A89100\x00\x00\x00\x00', + b'\x01896634AA0000\x00\x00\x00\x00', + b'\x01896634AA0100\x00\x00\x00\x00', + b'\x01896634AA1000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F0R01100\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0R02100\x00\x00\x00\x008646G0R01100\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4_TSS2_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R440\x00\x00\x00\x00\x00\x00', + b'\x01F15260R450\x00\x00\x00\x00\x00\x00', + b'\x01F15260R50000\x00\x00\x00\x00', + b'\x01F15260R51000\x00\x00\x00\x00', + b'\x01F15264283200\x00\x00\x00\x00', + b'\x01F15264283300\x00\x00\x00\x00', + b'\x01F152642F1000\x00\x00\x00\x00', + b'\x01F152642F8000\x00\x00\x00\x00', + b'\x01F152642F8100\x00\x00\x00\x00', + b'\x01F152642F9000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R11000\x00\x00\x00\x008965B0R12000\x00\x00\x00\x00', + b'8965B42371\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896634A61000\x00\x00\x00\x00', + b'\x01896634A88100\x00\x00\x00\x00', + b'\x01896634A89100\x00\x00\x00\x00', + b'\x01896634AE1001\x00\x00\x00\x00', + b'\x01896634AF0000\x00\x00\x00\x00', + b'\x01896634AJ2000\x00\x00\x00\x00', + b'\x01896634AJ3000\x00\x00\x00\x00', + b'\x01896634AL5000\x00\x00\x00\x00', + b'\x01896634AL6000\x00\x00\x00\x00', + b'\x01896634AL8000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F0R03100\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0R05100\x00\x00\x00\x008646G0R02100\x00\x00\x00\x00', + b'\x028646F0R05200\x00\x00\x00\x008646G0R02200\x00\x00\x00\x00', + b'\x028646F0R11000\x00\x00\x00\x008646G0R04000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_SIENNA: { + (Ecu.engine, 0x700, None): [ + b'\x01896630832100\x00\x00\x00\x00', + b'\x01896630832200\x00\x00\x00\x00', + b'\x01896630838000\x00\x00\x00\x00', + b'\x01896630838100\x00\x00\x00\x00', + b'\x01896630842000\x00\x00\x00\x00', + b'\x01896630843000\x00\x00\x00\x00', + b'\x01896630851000\x00\x00\x00\x00', + b'\x01896630851100\x00\x00\x00\x00', + b'\x01896630851200\x00\x00\x00\x00', + b'\x01896630852000\x00\x00\x00\x00', + b'\x01896630852100\x00\x00\x00\x00', + b'\x01896630859000\x00\x00\x00\x00', + b'\x01896630860000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B45070\x00\x00\x00\x00\x00\x00', + b'8965B45080\x00\x00\x00\x00\x00\x00', + b'8965B45082\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152608130\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510801100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702200\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0801100\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_SIENNA_4TH_GEN: { + (Ecu.engine, 0x700, None): [ + b'\x01896630841000\x00\x00\x00\x00', + b'\x01896630857101\x00\x00\x00\x00', + b'\x01896630864000\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260815100\x00\x00\x00\x00', + b'\x01F15260815300\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x018965B4509100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301500\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0802200\x00\x00\x00\x008646G4202100\x00\x00\x00\x00', + b'\x028646F0802300\x00\x00\x00\x008646G4202100\x00\x00\x00\x00', + b'\x028646F0802400\x00\x00\x00\x008646G4202100\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'\x01896633T63000\x00\x00\x00\x00', + b'\x028966333S8000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966333S8000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333W1000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', + b'\x02896633T10000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152606281\x00\x00\x00\x00\x00\x00', + b'\x01F152606340\x00\x00\x00\x00\x00\x00', + b'\x01F152606461\x00\x00\x00\x00\x00\x00', + b'\x01F15260646200\x00\x00\x00\x00', + b'F152633423\x00\x00\x00\x00\x00\x00', + b'F152633680\x00\x00\x00\x00\x00\x00', + b'F152633681\x00\x00\x00\x00\x00\x00', + b'F152633F50\x00\x00\x00\x00\x00\x00', + b'F152633F51\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33252\x00\x00\x00\x00\x00\x00', + b'8965B33590\x00\x00\x00\x00\x00\x00', + b'8965B33690\x00\x00\x00\x00\x00\x00', + b'8965B33702\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', + b'\x028646F3309400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_ES: { + (Ecu.engine, 0x7e0, None): [ + b'\x02333M4100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02333R0000\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152606202\x00\x00\x00\x00\x00\x00', + b'F152633171\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881513309400\x00\x00\x00\x00', + b'881513309500\x00\x00\x00\x00', + b'881513310400\x00\x00\x00\x00', + b'881513310500\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33502\x00\x00\x00\x00\x00\x00', + b'8965B33512\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4701100\x00\x00\x00\x00', + b'8821F4701200\x00\x00\x00\x00', + b'8821F4701300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F3302001\x00\x00\x00\x00', + b'8646F3302100\x00\x00\x00\x00', + b'8646F3302200\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_GS_F: { + (Ecu.engine, 0x7e0, None): [ + b'\x0233075200\x00\x00\x00\x00\x00\x00\x00\x00530B9000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152630700\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881513016200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B30551\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F3002100\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_NX: { + (Ecu.engine, 0x700, None): [ + b'\x01896637850000\x00\x00\x00\x00', + b'\x01896637851000\x00\x00\x00\x00', + b'\x01896637852000\x00\x00\x00\x00', + b'\x01896637854000\x00\x00\x00\x00', + b'\x01896637873000\x00\x00\x00\x00', + b'\x01896637878000\x00\x00\x00\x00', + b'\x01896637878100\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237842000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237880000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152678130\x00\x00\x00\x00\x00\x00', + b'F152678140\x00\x00\x00\x00\x00\x00', + b'F152678160\x00\x00\x00\x00\x00\x00', + b'F152678170\x00\x00\x00\x00\x00\x00', + b'F152678171\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881517803100\x00\x00\x00\x00', + b'881517803300\x00\x00\x00\x00', + b'881517804100\x00\x00\x00\x00', + b'881517804300\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B78060\x00\x00\x00\x00\x00\x00', + b'8965B78080\x00\x00\x00\x00\x00\x00', + b'8965B78100\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F7801100\x00\x00\x00\x00', + b'8646F7801300\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_NX_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966378B2000\x00\x00\x00\x00', + b'\x018966378B2100\x00\x00\x00\x00', + b'\x018966378B3000\x00\x00\x00\x00', + b'\x018966378B3100\x00\x00\x00\x00', + b'\x018966378B4100\x00\x00\x00\x00', + b'\x018966378G2000\x00\x00\x00\x00', + b'\x018966378G3000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0237881000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02378A0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02378F4000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152678221\x00\x00\x00\x00\x00\x00', + b'F152678200\x00\x00\x00\x00\x00\x00', + b'F152678210\x00\x00\x00\x00\x00\x00', + b'F152678211\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B78110\x00\x00\x00\x00\x00\x00', + b'8965B78120\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F78030A0\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F7803100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_LC_TSS2: { + (Ecu.engine, 0x7e0, None): [ + b'\x0131130000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152611390\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B11091\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F1104200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F1105200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RC: { + (Ecu.engine, 0x700, None): [ + b'\x01896632461100\x00\x00\x00\x00', + b'\x01896632478100\x00\x00\x00\x00', + b'\x01896632478200\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152624150\x00\x00\x00\x00\x00\x00', + b'F152624221\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881512404100\x00\x00\x00\x00', + b'881512407000\x00\x00\x00\x00', + b'881512409100\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B24081\x00\x00\x00\x00\x00\x00', + b'8965B24240\x00\x00\x00\x00\x00\x00', + b'8965B24320\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F2401100\x00\x00\x00\x00', + b'8646F2401200\x00\x00\x00\x00', + b'8646F2402200\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RX: { + (Ecu.engine, 0x700, None): [ + b'\x01896630E36100\x00\x00\x00\x00', + b'\x01896630E36200\x00\x00\x00\x00', + b'\x01896630E36300\x00\x00\x00\x00', + b'\x01896630E37100\x00\x00\x00\x00', + b'\x01896630E37200\x00\x00\x00\x00', + b'\x01896630E37300\x00\x00\x00\x00', + b'\x01896630E41000\x00\x00\x00\x00', + b'\x01896630E41100\x00\x00\x00\x00', + b'\x01896630E41200\x00\x00\x00\x00', + b'\x01896630E41500\x00\x00\x00\x00', + b'\x01896630EA3100\x00\x00\x00\x00', + b'\x01896630EA3300\x00\x00\x00\x00', + b'\x01896630EA3400\x00\x00\x00\x00', + b'\x01896630EA4100\x00\x00\x00\x00', + b'\x01896630EA4200\x00\x00\x00\x00', + b'\x01896630EA4300\x00\x00\x00\x00', + b'\x01896630EA4400\x00\x00\x00\x00', + b'\x01896630EA6300\x00\x00\x00\x00', + b'\x018966348R1300\x00\x00\x00\x00', + b'\x018966348R8500\x00\x00\x00\x00', + b'\x018966348R9300\x00\x00\x00\x00', + b'\x018966348W1300\x00\x00\x00\x00', + b'\x018966348W2300\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02348J7000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348N0000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Q4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Q4100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1200\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152648361\x00\x00\x00\x00\x00\x00', + b'F152648472\x00\x00\x00\x00\x00\x00', + b'F152648473\x00\x00\x00\x00\x00\x00', + b'F152648474\x00\x00\x00\x00\x00\x00', + b'F152648492\x00\x00\x00\x00\x00\x00', + b'F152648493\x00\x00\x00\x00\x00\x00', + b'F152648494\x00\x00\x00\x00\x00\x00', + b'F152648501\x00\x00\x00\x00\x00\x00', + b'F152648502\x00\x00\x00\x00\x00\x00', + b'F152648504\x00\x00\x00\x00\x00\x00', + b'F152648630\x00\x00\x00\x00\x00\x00', + b'F152648740\x00\x00\x00\x00\x00\x00', + b'F152648A30\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514810300\x00\x00\x00\x00', + b'881514810500\x00\x00\x00\x00', + b'881514810700\x00\x00\x00\x00', + b'881514811300\x00\x00\x00\x00', + b'881514811500\x00\x00\x00\x00', + b'881514811700\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B0E011\x00\x00\x00\x00\x00\x00', + b'8965B0E012\x00\x00\x00\x00\x00\x00', + b'8965B48102\x00\x00\x00\x00\x00\x00', + b'8965B48111\x00\x00\x00\x00\x00\x00', + b'8965B48112\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4701000\x00\x00\x00\x00', + b'8821F4701100\x00\x00\x00\x00', + b'8821F4701200\x00\x00\x00\x00', + b'8821F4701300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4801100\x00\x00\x00\x00', + b'8646F4801200\x00\x00\x00\x00', + b'8646F4802001\x00\x00\x00\x00', + b'8646F4802100\x00\x00\x00\x00', + b'8646F4802200\x00\x00\x00\x00', + b'8646F4809000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RX_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630EA9000\x00\x00\x00\x00', + b'\x01896630EB0000\x00\x00\x00\x00', + b'\x01896630EC9000\x00\x00\x00\x00', + b'\x01896630EC9100\x00\x00\x00\x00', + b'\x01896630ED0000\x00\x00\x00\x00', + b'\x01896630ED0100\x00\x00\x00\x00', + b'\x01896630ED5000\x00\x00\x00\x00', + b'\x01896630ED6000\x00\x00\x00\x00', + b'\x018966348R9200\x00\x00\x00\x00', + b'\x018966348T8000\x00\x00\x00\x00', + b'\x018966348W5100\x00\x00\x00\x00', + b'\x018966348W9000\x00\x00\x00\x00', + b'\x018966348X0000\x00\x00\x00\x00', + b'\x01896634D11000\x00\x00\x00\x00', + b'\x01896634D12000\x00\x00\x00\x00', + b'\x01896634D12100\x00\x00\x00\x00', + b'\x01896634D43000\x00\x00\x00\x00', + b'\x01896634D44000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02348U2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X5000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Y3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0234D14000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260E031\x00\x00\x00\x00\x00\x00', + b'\x01F15260E041\x00\x00\x00\x00\x00\x00', + b'\x01F152648781\x00\x00\x00\x00\x00\x00', + b'\x01F152648801\x00\x00\x00\x00\x00\x00', + b'F152648493\x00\x00\x00\x00\x00\x00', + b'F152648811\x00\x00\x00\x00\x00\x00', + b'F152648831\x00\x00\x00\x00\x00\x00', + b'F152648891\x00\x00\x00\x00\x00\x00', + b'F152648C80\x00\x00\x00\x00\x00\x00', + b'F152648D00\x00\x00\x00\x00\x00\x00', + b'F152648D60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48261\x00\x00\x00\x00\x00\x00', + b'8965B48271\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4810400\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_PRIUS_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', + b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', + b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', + b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152647500\x00\x00\x00\x00\x00\x00', + b'F152647510\x00\x00\x00\x00\x00\x00', + b'F152647520\x00\x00\x00\x00\x00\x00', + b'F152647521\x00\x00\x00\x00\x00\x00', + b'F152647531\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B47070\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4707000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4710000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F4712000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_MIRAI: { + (Ecu.abs, 0x7d1, None): [ + b'\x01898A36203000\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15266203200\x00\x00\x00\x00', + b'\x01F15266203500\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B6204100\x00\x00\x00\x008965B6203100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_ALPHARD_TSS2: { + (Ecu.engine, 0x7e0, None): [ + b'\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B58040\x00\x00\x00\x00\x00\x00', + b'8965B58052\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152658320\x00\x00\x00\x00\x00\x00', + b'F152658341\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F58010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646FV201000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, +} diff --git a/opendbc_repo/opendbc/car/toyota/interface.py b/opendbc_repo/opendbc/car/toyota/interface.py new file mode 100644 index 000000000000000..3691f9f78cf6b84 --- /dev/null +++ b/opendbc_repo/opendbc/car/toyota/interface.py @@ -0,0 +1,159 @@ +from panda import Panda +from panda import uds +from opendbc.car import structs, get_safety_config +from opendbc.car.toyota.values import Ecu, CAR, DBC, ToyotaFlags, CarControllerParams, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, \ + MIN_ACC_SPEED, EPS_SCALE, UNSUPPORTED_DSU_CAR, NO_STOP_TIMER_CAR, ANGLE_CONTROL_CAR +from opendbc.car.disable_ecu import disable_ecu +from opendbc.car.interfaces import CarInterfaceBase + +SteerControlType = structs.CarParams.SteerControlType + + +class CarInterface(CarInterfaceBase): + @staticmethod + def get_pid_accel_limits(CP, current_speed, cruise_speed): + return CarControllerParams(CP).ACCEL_MIN, CarControllerParams(CP).ACCEL_MAX + + @staticmethod + def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "toyota" + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.toyota)] + ret.safetyConfigs[0].safetyParam = EPS_SCALE[candidate] + + # BRAKE_MODULE is on a different address for these cars + if DBC[candidate]["pt"] == "toyota_new_mc_pt_generated": + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_ALT_BRAKE + + if ret.flags & ToyotaFlags.SECOC.value: + ret.secOcRequired = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_SECOC + + if candidate in ANGLE_CONTROL_CAR: + 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.18 + ret.steerLimitTimer = 0.8 + else: + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay + ret.steerLimitTimer = 0.4 + + stop_and_go = candidate in TSS2_CAR + + # In TSS2 cars, the camera does long control + 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) + + if candidate == CAR.LEXUS_ES_TSS2 and Ecu.hybrid not in found_ecus: + ret.flags |= ToyotaFlags.RAISED_ACCEL_LIMIT.value + + if candidate == CAR.TOYOTA_PRIUS: + stop_and_go = True + # Only give steer angle deadzone to for bad angle sensor prius + for fw in car_fw: + if fw.ecu == "eps" and not fw.fwVersion == b'8965B47060\x00\x00\x00\x00\x00\x00': + ret.steerActuatorDelay = 0.25 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg=0.2) + + elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RX_TSS2): + stop_and_go = True + ret.wheelSpeedFactor = 1.035 + + elif candidate in (CAR.TOYOTA_AVALON, CAR.TOYOTA_AVALON_2019, CAR.TOYOTA_AVALON_TSS2): + # starting from 2019, all Avalon variants have stop and go + # https://engage.toyota.com/static/images/toyota_safety_sense/TSS_Applicability_Chart.pdf + stop_and_go = candidate != CAR.TOYOTA_AVALON + + elif candidate in (CAR.TOYOTA_RAV4_TSS2, CAR.TOYOTA_RAV4_TSS2_2022, CAR.TOYOTA_RAV4_TSS2_2023, CAR.TOYOTA_RAV4_PRIME, CAR.TOYOTA_SIENNA_4TH_GEN): + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kiBP = [0.0] + ret.lateralTuning.pid.kpBP = [0.0] + ret.lateralTuning.pid.kpV = [0.6] + ret.lateralTuning.pid.kiV = [0.1] + ret.lateralTuning.pid.kf = 0.00007818594 + + # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. + # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 + for fw in car_fw: + if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']): + ret.lateralTuning.pid.kpV = [0.15] + ret.lateralTuning.pid.kiV = [0.05] + ret.lateralTuning.pid.kf = 0.00004 + break + + elif candidate in (CAR.TOYOTA_CHR, CAR.TOYOTA_CAMRY, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_NX): + # TODO: Some of these platforms are not advertised to have full range ACC, are they similar to SNG_WITHOUT_DSU cars? + stop_and_go = True + + # TODO: these models can do stop and go, but unclear if it requires sDSU or unplugging DSU. + # For now, don't list stop and go functionality in the docs + if ret.flags & ToyotaFlags.SNG_WITHOUT_DSU: + stop_and_go = stop_and_go or (ret.enableDsu and not docs) + + ret.centerToFront = ret.wheelbase * 0.44 + + # TODO: Some TSS-P platforms have BSM, but are flipped based on region or driving direction. + # Detect flipped signals and enable for C-HR and others + ret.enableBsm = 0x3F6 in fingerprint[0] and candidate in TSS2_CAR + + # No radar dbc for cars without DSU which are not TSS 2.0 + # TODO: make an adas dbc file for dsu-less models + ret.radarUnavailable = DBC[candidate]['radar'] is None or candidate in (NO_DSU_CAR - TSS2_CAR) + + # since we don't yet parse radar on TSS2/TSS-P radar-based ACC cars, gate longitudinal behind experimental toggle + if candidate in (RADAR_ACC_CAR | NO_DSU_CAR): + ret.experimentalLongitudinalAvailable = candidate in RADAR_ACC_CAR + + # Disabling radar is only supported on TSS2 radar-ACC cars + if experimental_long and candidate in RADAR_ACC_CAR: + ret.flags |= ToyotaFlags.DISABLE_RADAR.value + + # openpilot longitudinal enabled by default: + # - cars w/ DSU disconnected + # - TSS2 cars with camera sending ACC_CONTROL where we can block it + # openpilot longitudinal behind experimental long toggle: + # - TSS2 radar ACC cars (disables radar) + + if ret.flags & ToyotaFlags.SECOC.value: + ret.openpilotLongitudinalControl = False + else: + ret.openpilotLongitudinalControl = 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 + + if not ret.openpilotLongitudinalControl: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL + + # 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 else MIN_ACC_SPEED + + tune = ret.longitudinalTuning + if candidate in TSS2_CAR: + tune.kpV = [0.0] + tune.kiV = [0.5] + ret.vEgoStopping = 0.25 + ret.vEgoStarting = 0.25 + ret.stoppingDecelRate = 0.3 # reach stopping target smoothly + + # Since we compensate for imprecise acceleration in carcontroller, we can be less aggressive with tuning + # This also prevents unnecessary request windup due to internal car jerk limits + if ret.flags & ToyotaFlags.RAISED_ACCEL_LIMIT: + tune.kiV = [0.25] + else: + tune.kiBP = [0., 5., 35.] + tune.kiV = [3.6, 2.4, 1.5] + + return ret + + @staticmethod + def init(CP, can_recv, can_send): + # disable radar if alpha longitudinal toggled on radar-ACC car + if CP.flags & ToyotaFlags.DISABLE_RADAR.value: + communication_control = bytes([uds.SERVICE_TYPE.COMMUNICATION_CONTROL, uds.CONTROL_TYPE.ENABLE_RX_DISABLE_TX, uds.MESSAGE_TYPE.NORMAL]) + disable_ecu(can_recv, can_send, bus=0, addr=0x750, sub_addr=0xf, com_cont_req=communication_control) diff --git a/opendbc_repo/opendbc/car/toyota/radar_interface.py b/opendbc_repo/opendbc/car/toyota/radar_interface.py new file mode 100755 index 000000000000000..bfb2df04942156c --- /dev/null +++ b/opendbc_repo/opendbc/car/toyota/radar_interface.py @@ -0,0 +1,93 @@ +#!/usr/bin/env python3 +from opendbc.can.parser import CANParser +from opendbc.car.structs import RadarData +from opendbc.car.toyota.values import DBC, TSS2_CAR +from opendbc.car.interfaces import RadarInterfaceBase + + +def _create_radar_can_parser(car_fingerprint): + if car_fingerprint in TSS2_CAR: + RADAR_A_MSGS = list(range(0x180, 0x190)) + RADAR_B_MSGS = list(range(0x190, 0x1a0)) + else: + RADAR_A_MSGS = list(range(0x210, 0x220)) + RADAR_B_MSGS = list(range(0x220, 0x230)) + + msg_a_n = len(RADAR_A_MSGS) + msg_b_n = len(RADAR_B_MSGS) + messages = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20] * (msg_a_n + msg_b_n), strict=True)) + + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.track_id = 0 + + if CP.carFingerprint in TSS2_CAR: + self.RADAR_A_MSGS = list(range(0x180, 0x190)) + self.RADAR_B_MSGS = list(range(0x190, 0x1a0)) + else: + self.RADAR_A_MSGS = list(range(0x210, 0x220)) + self.RADAR_B_MSGS = list(range(0x220, 0x230)) + + self.valid_cnt = {key: 0 for key in self.RADAR_A_MSGS} + + self.rcp = None if CP.radarUnavailable else _create_radar_can_parser(CP.carFingerprint) + self.trigger_msg = self.RADAR_B_MSGS[-1] + self.updated_messages = set() + + def update(self, can_strings): + if self.rcp is None: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + rr = self._update(self.updated_messages) + self.updated_messages.clear() + + return rr + + def _update(self, updated_messages): + ret = RadarData() + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + ret.errors = errors + + for ii in sorted(updated_messages): + if ii in self.RADAR_A_MSGS: + cpt = self.rcp.vl[ii] + + if cpt['LONG_DIST'] >= 255 or cpt['NEW_TRACK']: + self.valid_cnt[ii] = 0 # reset counter + if cpt['VALID'] and cpt['LONG_DIST'] < 255: + self.valid_cnt[ii] += 1 + else: + self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) + + score = self.rcp.vl[ii+16]['SCORE'] + # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] + + # radar point only valid if it's a valid measurement and score is above 50 + if cpt['VALID'] or (score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = RadarData.RadarPoint() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = bool(cpt['VALID']) + else: + if ii in self.pts: + del self.pts[ii] + + ret.points = list(self.pts.values()) + return ret diff --git a/body/board/obj/.placeholder b/opendbc_repo/opendbc/car/toyota/tests/__init__.py similarity index 100% rename from body/board/obj/.placeholder rename to opendbc_repo/opendbc/car/toyota/tests/__init__.py diff --git a/opendbc_repo/opendbc/car/toyota/tests/print_platform_codes.py b/opendbc_repo/opendbc/car/toyota/tests/print_platform_codes.py new file mode 100755 index 000000000000000..333e7dca26af256 --- /dev/null +++ b/opendbc_repo/opendbc/car/toyota/tests/print_platform_codes.py @@ -0,0 +1,31 @@ +#!/usr/bin/env python3 +from collections import defaultdict +from opendbc.car.toyota.values import PLATFORM_CODE_ECUS, get_platform_codes +from opendbc.car.toyota.fingerprints import FW_VERSIONS + +if __name__ == "__main__": + parts_for_ecu: dict = defaultdict(set) + cars_for_code: dict = defaultdict(lambda: defaultdict(set)) + for car_model, ecus in FW_VERSIONS.items(): + print() + print(car_model) + for ecu in sorted(ecus): + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + platform_codes = get_platform_codes(ecus[ecu]) + parts_for_ecu[ecu] |= {code.split(b'-')[0] for code in platform_codes if code.count(b'-') > 1} + for code in platform_codes: + cars_for_code[ecu][b'-'.join(code.split(b'-')[:2])] |= {car_model} + print(f' (Ecu.{ecu[0]}, {hex(ecu[1])}, {ecu[2]}):') + print(f' Codes: {platform_codes}') + + print('\nECU parts:') + for ecu, parts in parts_for_ecu.items(): + print(f' (Ecu.{ecu[0]}, {hex(ecu[1])}, {ecu[2]}): {parts}') + + print('\nCar models vs. platform codes (no major versions):') + for ecu, codes in cars_for_code.items(): + print(f' (Ecu.{ecu[0]}, {hex(ecu[1])}, {ecu[2]}):') + for code, cars in codes.items(): + print(f' {code!r}: {sorted(cars)}') diff --git a/selfdrive/car/toyota/tests/test_toyota.py b/opendbc_repo/opendbc/car/toyota/tests/test_toyota.py similarity index 90% rename from selfdrive/car/toyota/tests/test_toyota.py rename to opendbc_repo/opendbc/car/toyota/tests/test_toyota.py index 0217a0fbc1957c3..bcf80e4be0414e5 100644 --- a/selfdrive/car/toyota/tests/test_toyota.py +++ b/opendbc_repo/opendbc/car/toyota/tests/test_toyota.py @@ -1,18 +1,18 @@ from hypothesis import given, settings, strategies as st -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.toyota.fingerprints import FW_VERSIONS -from openpilot.selfdrive.car.toyota.values import CAR, DBC, TSS2_CAR, ANGLE_CONTROL_CAR, RADAR_ACC_CAR, \ +from opendbc.car.structs import CarParams +from opendbc.car.fw_versions import build_fw_dict +from opendbc.car.toyota.fingerprints import FW_VERSIONS +from opendbc.car.toyota.values import CAR, DBC, TSS2_CAR, ANGLE_CONTROL_CAR, RADAR_ACC_CAR, SECOC_CAR, \ FW_QUERY_CONFIG, PLATFORM_CODE_ECUS, FUZZY_EXCLUDED_PLATFORMS, \ get_platform_codes -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} +Ecu = CarParams.Ecu def check_fw_version(fw_version: bytes) -> bool: - return b'?' not in fw_version + # TODO: just use the FW patterns, need to support all chunks + return b'?' not in fw_version and b'!' not in fw_version class TestToyotaInterfaces: @@ -28,7 +28,7 @@ def test_tss2_dbc(self): # We make some assumptions about TSS2 platforms, # like looking up certain signals only in this DBC for car_model, dbc in DBC.items(): - if car_model in TSS2_CAR: + if car_model in TSS2_CAR and car_model not in SECOC_CAR: assert dbc["pt"] == "toyota_nodsu_pt_generated" def test_essential_ecus(self, subtests): @@ -152,10 +152,10 @@ def test_fuzzy_excluded_platforms(self): for ecu, fw_versions in fw_by_addr.items(): ecu_name, addr, sub_addr = ecu for fw in fw_versions: - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) + car_fw.append(CarParams.CarFw(ecu=ecu_name, fwVersion=fw, address=addr, + subAddress=0 if sub_addr is None else sub_addr)) - CP = car.CarParams.new_message(carFw=car_fw) + CP = CarParams(carFw=car_fw) matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) if len(matches) == 1: assert list(matches)[0] == platform diff --git a/opendbc_repo/opendbc/car/toyota/toyotacan.py b/opendbc_repo/opendbc/car/toyota/toyotacan.py new file mode 100644 index 000000000000000..c4f27510d683eca --- /dev/null +++ b/opendbc_repo/opendbc/car/toyota/toyotacan.py @@ -0,0 +1,148 @@ +from opendbc.car.structs import CarParams + +SteerControlType = CarParams.SteerControlType + + +def create_steer_command(packer, steer, steer_req): + """Creates a CAN message for the Toyota Steer Command.""" + + values = { + "STEER_REQUEST": steer_req, + "STEER_TORQUE_CMD": steer, + "SET_ME_1": 1, + } + return packer.make_can_msg("STEERING_LKA", 0, values) + + +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, # 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, + "TORQUE_WIND_DOWN": torque_wind_down, + "ANGLE": 0, + "STEER_ANGLE_CMD": steer_angle, + "STEER_REQUEST": steer_req, + "STEER_REQUEST_2": steer_req, + "CLEAR_HOLD_STEERING_ALERT": 0, + } + return packer.make_can_msg("STEERING_LTA", 0, values) + + +def create_lta_steer_command_2(packer, frame): + values = { + "COUNTER": frame + 128, + } + return packer.make_can_msg("STEERING_LTA_2", 0, values) + + +def create_accel_command(packer, accel, pcm_cancel, permit_braking, standstill_req, lead, acc_type, fcw_alert, distance): + # TODO: find the exact canceling bit that does not create a chime + values = { + "ACCEL_CMD": accel, + "ACC_TYPE": acc_type, + "DISTANCE": distance, + "MINI_CAR": lead, + "PERMIT_BRAKING": permit_braking, + "RELEASE_STANDSTILL": not standstill_req, + "CANCEL_REQ": pcm_cancel, + "ALLOW_LONG_PRESS": 1, + "ACC_CUT_IN": fcw_alert, # only shown when ACC enabled + } + return packer.make_can_msg("ACC_CONTROL", 0, values) + + +def create_pcs_commands(packer, accel, active, mass): + values1 = { + "COUNTER": 0, + "FORCE": round(min(accel, 0) * mass * 2), + "STATE": 3 if active else 0, + "BRAKE_STATUS": 0, + "PRECOLLISION_ACTIVE": 1 if active else 0, + } + msg1 = packer.make_can_msg("PRE_COLLISION", 0, values1) + + values2 = { + "DSS1GDRV": min(accel, 0), # accel + "PCSALM": 1 if active else 0, # goes high same time as PRECOLLISION_ACTIVE + "IBTRGR": 1 if active else 0, # unknown + "PBATRGR": 1 if active else 0, # noisy actuation bit? + "PREFILL": 1 if active else 0, # goes on and off before DSS1GDRV + "AVSTRGR": 1 if active else 0, + } + msg2 = packer.make_can_msg("PRE_COLLISION_2", 0, values2) + + return [msg1, msg2] + + +def create_acc_cancel_command(packer): + values = { + "GAS_RELEASED": 0, + "CRUISE_ACTIVE": 0, + "ACC_BRAKING": 0, + "ACCEL_NET": 0, + "CRUISE_STATE": 0, + "CANCEL_REQ": 1, + } + return packer.make_can_msg("PCM_CRUISE", 0, values) + + +def create_fcw_command(packer, fcw): + values = { + "PCS_INDICATOR": 1, # PCS turned off + "FCW": fcw, + "SET_ME_X20": 0x20, + "SET_ME_X10": 0x10, + "PCS_OFF": 1, + "PCS_SENSITIVITY": 0, + } + return packer.make_can_msg("PCS_HUD", 0, values) + + +def create_ui_command(packer, steer, chime, left_line, right_line, left_lane_depart, right_lane_depart, enabled, stock_lkas_hud): + values = { + "TWO_BEEPS": chime, + "LDA_ALERT": steer, + "RIGHT_LINE": 3 if right_lane_depart else 1 if right_line else 2, + "LEFT_LINE": 3 if left_lane_depart else 1 if left_line else 2, + "BARRIERS": 1 if enabled else 0, + + # static signals + "SET_ME_X02": 2, + "SET_ME_X01": 1, + "LKAS_STATUS": 1, + "REPEATED_BEEPS": 0, + "LANE_SWAY_FLD": 7, + "LANE_SWAY_BUZZER": 0, + "LANE_SWAY_WARNING": 0, + "LDA_FRONT_CAMERA_BLOCKED": 0, + "TAKE_CONTROL": 0, + "LANE_SWAY_SENSITIVITY": 2, + "LANE_SWAY_TOGGLE": 1, + "LDA_ON_MESSAGE": 0, + "LDA_MESSAGES": 0, + "LDA_SA_TOGGLE": 1, + "LDA_SENSITIVITY": 2, + "LDA_UNAVAILABLE": 0, + "LDA_MALFUNCTION": 0, + "LDA_UNAVAILABLE_QUIET": 0, + "ADJUSTING_CAMERA": 0, + "LDW_EXIST": 1, + } + + # lane sway functionality + # not all cars have LKAS_HUD — update with camera values if available + if len(stock_lkas_hud): + values.update({s: stock_lkas_hud[s] for s in [ + "LANE_SWAY_FLD", + "LANE_SWAY_BUZZER", + "LANE_SWAY_WARNING", + "LANE_SWAY_SENSITIVITY", + "LANE_SWAY_TOGGLE", + ]}) + + return packer.make_can_msg("LKAS_HUD", 0, values) diff --git a/opendbc_repo/opendbc/car/toyota/values.py b/opendbc_repo/opendbc/car/toyota/values.py new file mode 100644 index 000000000000000..d61849f35423adb --- /dev/null +++ b/opendbc_repo/opendbc/car/toyota/values.py @@ -0,0 +1,596 @@ +import re +from collections import defaultdict +from dataclasses import dataclass, field +from enum import Enum, IntFlag + +from opendbc.car import CarSpecs, PlatformConfig, Platforms, AngleRateLimit, dbc_dict +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.structs import CarParams +from opendbc.car.docs_definitions import CarFootnote, CarDocs, Column, CarParts, CarHarness +from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = CarParams.Ecu +MIN_ACC_SPEED = 19. * CV.MPH_TO_MS +PEDAL_TRANSITION = 10. * CV.MPH_TO_MS + + +class CarControllerParams: + STEER_STEP = 1 + STEER_MAX = 1500 + STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor + + # Lane Tracing Assist (LTA) control limits + # 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: + # 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]) + + def __init__(self, CP): + if CP.flags & ToyotaFlags.RAISED_ACCEL_LIMIT: + self.ACCEL_MAX = 2.0 + else: + self.ACCEL_MAX = 1.5 # m/s2, lower than allowed 2.0 m/s^2 for tuning reasons + self.ACCEL_MIN = -3.5 # m/s2 + + if CP.lateralTuning.which() == 'torque': + self.STEER_DELTA_UP = 15 # 1.0s time to peak torque + self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) + else: + self.STEER_DELTA_UP = 10 # 1.5s time to peak torque + self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) + + +class ToyotaFlags(IntFlag): + # Detected flags + HYBRID = 1 + DISABLE_RADAR = 4 + + # Static flags + TSS2 = 8 + NO_DSU = 16 + UNSUPPORTED_DSU = 32 + RADAR_ACC = 64 + # these cars use the Lane Tracing Assist (LTA) message for lateral control + ANGLE_CONTROL = 128 + NO_STOP_TIMER = 256 + # these cars are speculated to allow stop and go when the DSU is unplugged + SNG_WITHOUT_DSU = 512 + # these cars can utilize 2.0 m/s^2 + RAISED_ACCEL_LIMIT = 1024 + SECOC = 2048 + +class Footnote(Enum): + CAMRY = CarFootnote( + "openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.", + Column.FSR_LONGITUDINAL) + + +@dataclass +class ToyotaCarDocs(CarDocs): + package: str = "All" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.toyota_a])) + + +@dataclass +class ToyotaTSS2PlatformConfig(PlatformConfig): + dbc_dict: dict = field(default_factory=lambda: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas')) + + def init(self): + self.flags |= ToyotaFlags.TSS2 | ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.NO_DSU + + if self.flags & ToyotaFlags.RADAR_ACC: + self.dbc_dict = dbc_dict('toyota_nodsu_pt_generated', None) + + +class CAR(Platforms): + # Toyota + TOYOTA_ALPHARD_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota Alphard 2019-20"), + ToyotaCarDocs("Toyota Alphard Hybrid 2021"), + ], + CarSpecs(mass=4305. * CV.LB_TO_KG, wheelbase=3.0, steerRatio=14.2, tireStiffnessFactor=0.444), + ) + TOYOTA_AVALON = PlatformConfig( + [ + ToyotaCarDocs("Toyota Avalon 2016", "Toyota Safety Sense P"), + ToyotaCarDocs("Toyota Avalon 2017-18"), + ], + CarSpecs(mass=3505. * CV.LB_TO_KG, wheelbase=2.82, steerRatio=14.8, tireStiffnessFactor=0.7983), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + ) + TOYOTA_AVALON_2019 = PlatformConfig( + [ + ToyotaCarDocs("Toyota Avalon 2019-21"), + ToyotaCarDocs("Toyota Avalon Hybrid 2019-21"), + ], + TOYOTA_AVALON.specs, + dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + ) + TOYOTA_AVALON_TSS2 = ToyotaTSS2PlatformConfig( # TSS 2.5 + [ + ToyotaCarDocs("Toyota Avalon 2022"), + ToyotaCarDocs("Toyota Avalon Hybrid 2022"), + ], + TOYOTA_AVALON.specs, + ) + TOYOTA_CAMRY = PlatformConfig( + [ + ToyotaCarDocs("Toyota Camry 2018-20", video_link="https://www.youtube.com/watch?v=fkcjviZY9CM", footnotes=[Footnote.CAMRY]), + ToyotaCarDocs("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk"), + ], + CarSpecs(mass=3400. * CV.LB_TO_KG, wheelbase=2.82448, steerRatio=13.7, tireStiffnessFactor=0.7933), + dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_DSU, + ) + TOYOTA_CAMRY_TSS2 = ToyotaTSS2PlatformConfig( # TSS 2.5 + [ + ToyotaCarDocs("Toyota Camry 2021-24", footnotes=[Footnote.CAMRY]), + ToyotaCarDocs("Toyota Camry Hybrid 2021-24"), + ], + TOYOTA_CAMRY.specs, + ) + TOYOTA_CHR = PlatformConfig( + [ + ToyotaCarDocs("Toyota C-HR 2017-20"), + ToyotaCarDocs("Toyota C-HR Hybrid 2017-20"), + ], + CarSpecs(mass=3300. * CV.LB_TO_KG, wheelbase=2.63906, steerRatio=13.6, tireStiffnessFactor=0.7933), + dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_DSU, + ) + TOYOTA_CHR_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota C-HR 2021"), + ToyotaCarDocs("Toyota C-HR Hybrid 2021-22"), + ], + TOYOTA_CHR.specs, + flags=ToyotaFlags.RADAR_ACC, + ) + TOYOTA_COROLLA = PlatformConfig( + [ToyotaCarDocs("Toyota Corolla 2017-19")], + CarSpecs(mass=2860. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=18.27, tireStiffnessFactor=0.444), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + ) + # LSS2 Lexus UX Hybrid is same as a TSS2 Corolla Hybrid + TOYOTA_COROLLA_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), + ToyotaCarDocs("Toyota Corolla Cross (Non-US only) 2020-23", min_enable_speed=7.5), + ToyotaCarDocs("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), + # Hybrid platforms + ToyotaCarDocs("Toyota Corolla Hybrid 2020-22"), + ToyotaCarDocs("Toyota Corolla Hybrid (South America only) 2020-23", min_enable_speed=7.5), + ToyotaCarDocs("Toyota Corolla Cross Hybrid (Non-US only) 2020-22", min_enable_speed=7.5), + ToyotaCarDocs("Lexus UX Hybrid 2019-23"), + ], + CarSpecs(mass=3060. * CV.LB_TO_KG, wheelbase=2.67, steerRatio=13.9, tireStiffnessFactor=0.444), + ) + TOYOTA_HIGHLANDER = PlatformConfig( + [ + ToyotaCarDocs("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"), + ToyotaCarDocs("Toyota Highlander Hybrid 2017-19"), + ], + CarSpecs(mass=4516. * CV.LB_TO_KG, wheelbase=2.8194, steerRatio=16.0, tireStiffnessFactor=0.8), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, + ) + TOYOTA_HIGHLANDER_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota Highlander 2020-23"), + ToyotaCarDocs("Toyota Highlander Hybrid 2020-23"), + ], + TOYOTA_HIGHLANDER.specs, + ) + TOYOTA_PRIUS = PlatformConfig( + [ + ToyotaCarDocs("Toyota Prius 2016", "Toyota Safety Sense P", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ToyotaCarDocs("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ToyotaCarDocs("Toyota Prius Prime 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ], + CarSpecs(mass=3045. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.74, tireStiffnessFactor=0.6371), + dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + ) + TOYOTA_PRIUS_V = PlatformConfig( + [ToyotaCarDocs("Toyota Prius v 2017", "Toyota Safety Sense P", min_enable_speed=MIN_ACC_SPEED)], + CarSpecs(mass=3340. * CV.LB_TO_KG, wheelbase=2.78, steerRatio=17.4, tireStiffnessFactor=0.5533), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, + ) + TOYOTA_PRIUS_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota Prius 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), + ToyotaCarDocs("Toyota Prius Prime 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), + ], + CarSpecs(mass=3115. * CV.LB_TO_KG, wheelbase=2.70002, steerRatio=13.4, tireStiffnessFactor=0.6371), + ) + TOYOTA_RAV4 = PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 2016", "Toyota Safety Sense P"), + ToyotaCarDocs("Toyota RAV4 2017-18") + ], + CarSpecs(mass=3650. * CV.LB_TO_KG, wheelbase=2.65, steerRatio=16.88, tireStiffnessFactor=0.5533), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + ) + TOYOTA_RAV4H = PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 Hybrid 2016", "Toyota Safety Sense P", video_link="https://youtu.be/LhT5VzJVfNI?t=26"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2017-18", video_link="https://youtu.be/LhT5VzJVfNI?t=26") + ], + TOYOTA_RAV4.specs, + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + # Note that the ICE RAV4 does not respect positive acceleration commands under 19 mph + flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, + ) + TOYOTA_RAV4_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 2019-21", video_link="https://www.youtube.com/watch?v=wJxjDd42gGA"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2019-21"), + ], + CarSpecs(mass=3585. * CV.LB_TO_KG, wheelbase=2.68986, steerRatio=14.3, tireStiffnessFactor=0.7933), + ) + TOYOTA_RAV4_TSS2_2022 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 2022"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2022", video_link="https://youtu.be/U0nH9cnrFB0"), + ], + TOYOTA_RAV4_TSS2.specs, + flags=ToyotaFlags.RADAR_ACC, + ) + TOYOTA_RAV4_TSS2_2023 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 2023-24"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2023-24"), + ], + TOYOTA_RAV4_TSS2.specs, + flags=ToyotaFlags.RADAR_ACC | ToyotaFlags.ANGLE_CONTROL, + ) + TOYOTA_RAV4_PRIME = PlatformConfig( + # TODO: Enable this docs entry when it can be suppressed from openpilot CARS.md + # [ToyotaCarDocs("Toyota RAV4 Prime 2021-23", min_enable_speed=MIN_ACC_SPEED)], + [], + CarSpecs(mass=4372. * CV.LB_TO_KG, wheelbase=2.68, steerRatio=16.88, tireStiffnessFactor=0.5533), + dbc_dict('toyota_rav4_prime_generated', 'toyota_tss2_adas'), + flags=ToyotaFlags.TSS2 | ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.NO_DSU | ToyotaFlags.SECOC, + ) + TOYOTA_MIRAI = ToyotaTSS2PlatformConfig( # TSS 2.5 + [ToyotaCarDocs("Toyota Mirai 2021")], + CarSpecs(mass=4300. * CV.LB_TO_KG, wheelbase=2.91, steerRatio=14.8, tireStiffnessFactor=0.8), + ) + TOYOTA_SIENNA = PlatformConfig( + [ToyotaCarDocs("Toyota Sienna 2018-20", video_link="https://www.youtube.com/watch?v=q1UPOo4Sh68", min_enable_speed=MIN_ACC_SPEED)], + CarSpecs(mass=4590. * CV.LB_TO_KG, wheelbase=3.03, steerRatio=15.5, tireStiffnessFactor=0.444), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_STOP_TIMER, + ) + TOYOTA_SIENNA_4TH_GEN = PlatformConfig( + # TODO: Enable this docs entry when it can be suppressed from openpilot CARS.md + # [ToyotaCarDocs("Toyota Sienna 2021-23", min_enable_speed=MIN_ACC_SPEED)], + [], + CarSpecs(mass=4625. * CV.LB_TO_KG, wheelbase=3.06, steerRatio=17.8, tireStiffnessFactor=0.444), + dbc_dict('toyota_rav4_prime_generated', 'toyota_tss2_adas'), + flags=ToyotaFlags.TSS2 | ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.NO_DSU | ToyotaFlags.SECOC, + ) + + # Lexus + LEXUS_CTH = PlatformConfig( + [ToyotaCarDocs("Lexus CT Hybrid 2017-18", "Lexus Safety System+")], + CarSpecs(mass=3108. * CV.LB_TO_KG, wheelbase=2.6, steerRatio=18.6, tireStiffnessFactor=0.517), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + ) + LEXUS_ES = PlatformConfig( + [ + ToyotaCarDocs("Lexus ES 2017-18"), + ToyotaCarDocs("Lexus ES Hybrid 2017-18"), + ], + CarSpecs(mass=3677. * CV.LB_TO_KG, wheelbase=2.8702, steerRatio=16.0, tireStiffnessFactor=0.444), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + ) + LEXUS_ES_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Lexus ES 2019-24"), + ToyotaCarDocs("Lexus ES Hybrid 2019-24", video_link="https://youtu.be/BZ29osRVJeg?t=12"), + ], + LEXUS_ES.specs, + ) + LEXUS_IS = PlatformConfig( + [ToyotaCarDocs("Lexus IS 2017-19")], + CarSpecs(mass=3736.8 * CV.LB_TO_KG, wheelbase=2.79908, steerRatio=13.3, tireStiffnessFactor=0.444), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.UNSUPPORTED_DSU, + ) + LEXUS_IS_TSS2 = ToyotaTSS2PlatformConfig( + [ToyotaCarDocs("Lexus IS 2022-23")], + LEXUS_IS.specs, + ) + LEXUS_NX = PlatformConfig( + [ + ToyotaCarDocs("Lexus NX 2018-19"), + ToyotaCarDocs("Lexus NX Hybrid 2018-19"), + ], + CarSpecs(mass=4070. * CV.LB_TO_KG, wheelbase=2.66, steerRatio=14.7, tireStiffnessFactor=0.444), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + ) + LEXUS_NX_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Lexus NX 2020-21"), + ToyotaCarDocs("Lexus NX Hybrid 2020-21"), + ], + LEXUS_NX.specs, + ) + LEXUS_LC_TSS2 = ToyotaTSS2PlatformConfig( + [ToyotaCarDocs("Lexus LC 2024")], + CarSpecs(mass=4500. * CV.LB_TO_KG, wheelbase=2.87, steerRatio=13.0, tireStiffnessFactor=0.444), + ) + LEXUS_RC = PlatformConfig( + [ToyotaCarDocs("Lexus RC 2018-20")], + LEXUS_IS.specs, + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.UNSUPPORTED_DSU, + ) + LEXUS_RX = PlatformConfig( + [ + ToyotaCarDocs("Lexus RX 2016", "Lexus Safety System+"), + ToyotaCarDocs("Lexus RX 2017-19"), + # Hybrid platforms + ToyotaCarDocs("Lexus RX Hybrid 2016", "Lexus Safety System+"), + ToyotaCarDocs("Lexus RX Hybrid 2017-19"), + ], + CarSpecs(mass=4481. * CV.LB_TO_KG, wheelbase=2.79, steerRatio=16., tireStiffnessFactor=0.5533), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + ) + LEXUS_RX_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Lexus RX 2020-22"), + ToyotaCarDocs("Lexus RX Hybrid 2020-22"), + ], + LEXUS_RX.specs, + ) + LEXUS_GS_F = PlatformConfig( + [ToyotaCarDocs("Lexus GS F 2016")], + CarSpecs(mass=4034. * CV.LB_TO_KG, wheelbase=2.84988, steerRatio=13.3, tireStiffnessFactor=0.444), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.UNSUPPORTED_DSU, + ) + + +# (addr, cars, bus, 1/freq*100, vl) +STATIC_DSU_MSGS = [ + (0x128, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON), \ + 1, 3, b'\xf4\x01\x90\x83\x00\x37'), + (0x128, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 3, b'\x03\x00\x20\x00\x00\x52'), + (0x141, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 2, b'\x00\x00\x00\x46'), + (0x160, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), + (0x161, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_PRIUS_V), + 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), + (0X161, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), + (0x283, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), + (0x2E6, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), + (0x2E7, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), + (0x33E, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), + (0x344, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), + (0x365, (CAR.TOYOTA_PRIUS, CAR.LEXUS_NX, CAR.TOYOTA_HIGHLANDER), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), + (0x365, (CAR.TOYOTA_RAV4, CAR.TOYOTA_RAV4H, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_RX, + CAR.TOYOTA_PRIUS_V), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), + (0x366, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_HIGHLANDER), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), + (0x366, (CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), + 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), + (0x470, (CAR.TOYOTA_PRIUS, CAR.LEXUS_RX), 1, 100, b'\x00\x00\x02\x7a'), + (0x470, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_RAV4H, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 100, b'\x00\x00\x01\x79'), + (0x4CB, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), +] + + +def get_platform_codes(fw_versions: list[bytes]) -> dict[bytes, set[bytes]]: + # Returns sub versions in a dict so comparisons can be made within part-platform-major_version combos + codes = defaultdict(set) # Optional[part]-platform-major_version: set of sub_version + for fw in fw_versions: + # FW versions returned from UDS queries can return multiple fields/chunks of data (different ECU calibrations, different data?) + # and are prefixed with a byte that describes how many chunks of data there are. + # But FW returned from KWP requires querying of each sub-data id and does not have a length prefix. + + length_code = 1 + length_code_match = FW_LEN_CODE.search(fw) + if length_code_match is not None: + length_code = length_code_match.group()[0] + fw = fw[1:] + + # fw length should be multiple of 16 bytes (per chunk, even if no length code), skip parsing if unexpected length + if length_code * FW_CHUNK_LEN != len(fw): + continue + + chunks = [fw[FW_CHUNK_LEN * i:FW_CHUNK_LEN * i + FW_CHUNK_LEN].strip(b'\x00 ') for i in range(length_code)] + + # only first is considered for now since second is commonly shared (TODO: understand that) + first_chunk = chunks[0] + if len(first_chunk) == 8: + # TODO: no part number, but some short chunks have it in subsequent chunks + fw_match = SHORT_FW_PATTERN.search(first_chunk) + if fw_match is not None: + platform, major_version, sub_version = fw_match.groups() + codes[b'-'.join((platform, major_version))].add(sub_version) + + elif len(first_chunk) == 10: + fw_match = MEDIUM_FW_PATTERN.search(first_chunk) + if fw_match is not None: + part, platform, major_version, sub_version = fw_match.groups() + codes[b'-'.join((part, platform, major_version))].add(sub_version) + + elif len(first_chunk) == 12: + fw_match = LONG_FW_PATTERN.search(first_chunk) + if fw_match is not None: + part, platform, major_version, sub_version = fw_match.groups() + codes[b'-'.join((part, platform, major_version))].add(sub_version) + + return dict(codes) + + +def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: + candidates = set() + + 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} + for ecu, expected_versions in fws.items(): + addr = ecu[1:] + # Only check ECUs expected to have platform codes + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + # Expected platform codes & versions + expected_platform_codes = get_platform_codes(expected_versions) + + # Found platform codes & versions + found_platform_codes = get_platform_codes(live_fw_versions.get(addr, set())) + + # Check part number + platform code + major version matches for any found versions + # Platform codes and major versions change for different physical parts, generation, API, etc. + # Sub-versions are incremented for minor recalls, do not need to be checked. + if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): + break + + valid_found_ecus.add(addr) + + # If all live ECUs pass all checks for candidate, add it as a match + if valid_expected_ecus.issubset(valid_found_ecus): + candidates.add(candidate) + + return {str(c) for c in (candidates - FUZZY_EXCLUDED_PLATFORMS)} + + +# Regex patterns for parsing more general platform-specific identifiers from FW versions. +# - Part number: Toyota part number (usually last character needs to be ignored to find a match). +# Each ECU address has just one part number. +# - Platform: usually multiple codes per an openpilot platform, however this is the least variable and +# is usually shared across ECUs and model years signifying this describes something about the specific platform. +# This describes more generational changes (TSS-P vs TSS2), or manufacture region. +# - Major version: second least variable part of the FW version. Seen splitting cars by model year/API such as +# RAV4 2022/2023 and Avalon. Used to differentiate cars where API has changed slightly, but is not a generational change. +# It is important to note that these aren't always consecutive, for example: +# Avalon 2016-18's fwdCamera has these major versions: 01, 03 while 2019 has: 02 +# - Sub version: exclusive to major version, but shared with other cars. Should only be used for further filtering. +# Seen bumped in TSB FW updates, and describes other minor differences. +SHORT_FW_PATTERN = re.compile(b'[A-Z0-9](?P[A-Z0-9]{2})(?P[A-Z0-9]{2})(?P[A-Z0-9]{3})') +MEDIUM_FW_PATTERN = re.compile(b'(?P[A-Z0-9]{5})(?P[A-Z0-9]{2})(?P[A-Z0-9]{1})(?P[A-Z0-9]{2})') +LONG_FW_PATTERN = re.compile(b'(?P[A-Z0-9]{5})(?P[A-Z0-9]{2})(?P[A-Z0-9]{2})(?P[A-Z0-9]{3})') +FW_LEN_CODE = re.compile(b'^[\x01-\x03]') # highest seen is 3 chunks, 16 bytes each +FW_CHUNK_LEN = 16 + +# List of ECUs that are most unique across openpilot platforms +# - 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. +# 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.fwdRadar, Ecu.eps) + +# These platforms have at least one platform code for all ECUs shared with another platform. +FUZZY_EXCLUDED_PLATFORMS: set[CAR] = set() + +# Some ECUs that use KWP2000 have their FW versions on non-standard data identifiers. +# Toyota diagnostic software first gets the supported data ids, then queries them one by one. +# For example, sends: 0x1a8800, receives: 0x1a8800010203, queries: 0x1a8801, 0x1a8802, 0x1a8803 +TOYOTA_VERSION_REQUEST_KWP = b'\x1a\x88\x01' +TOYOTA_VERSION_RESPONSE_KWP = b'\x5a\x88\x01' + +FW_QUERY_CONFIG = FwQueryConfig( + # TODO: look at data to whitelist new ECUs effectively + requests=[ + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST_KWP], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE_KWP], + whitelist_ecus=[Ecu.fwdCamera, Ecu.fwdRadar, Ecu.dsu, Ecu.abs, Ecu.eps, Ecu.srs, Ecu.transmission, Ecu.hvac], + bus=0, + ), + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, StdQueries.OBD_VERSION_REQUEST], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, StdQueries.OBD_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.hybrid, Ecu.srs, Ecu.transmission, Ecu.hvac], + bus=0, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.EXTENDED_DIAGNOSTIC_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.EXTENDED_DIAGNOSTIC_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.abs, Ecu.eps, + Ecu.hybrid, Ecu.srs, Ecu.transmission, Ecu.hvac], + bus=0, + ), + ], + non_essential_ecus={ + # FIXME: On some models, abs can sometimes be missing + Ecu.abs: [CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_IS, CAR.TOYOTA_ALPHARD_TSS2], + # On some models, the engine can show on two different addresses + Ecu.engine: [CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_CAMRY, CAR.TOYOTA_COROLLA_TSS2, CAR.TOYOTA_CHR, CAR.TOYOTA_CHR_TSS2, CAR.LEXUS_IS, + CAR.LEXUS_IS_TSS2, 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: + # Responds to UDS: + # - Combination Meter (0x7c0) + # - HV Battery (0x713, 0x747) + # - Motor Generator (0x716, 0x724) + # - 2nd ABS "Brake/EPB" (0x730) + # - Electronic Parking Brake ((0x750, 0x2c)) + # - Telematics ((0x750, 0xc7)) + # Responds to KWP (0x1a8801): + # - Steering Angle Sensor (0x7b3) + # - EPS/EMPS (0x7a0, 0x7a1) + # - 2nd SRS Airbag (0x784) + # - Central Gateway ((0x750, 0x5f)) + # - Telematics ((0x750, 0xc7)) + # Responds to KWP (0x1a8881): + # - Body Control Module ((0x750, 0x40)) + # - Telematics ((0x750, 0xc7)) + + # Hybrid control computer can be on 0x7e2 (KWP) or 0x7d2 (UDS) depending on platform + (Ecu.hybrid, 0x7e2, None), # Hybrid Control Assembly & Computer + (Ecu.hybrid, 0x7d2, None), # Hybrid Control Assembly & Computer + (Ecu.srs, 0x780, None), # SRS Airbag + # Transmission is combined with engine on some platforms, such as TSS-P RAV4 + (Ecu.transmission, 0x701, None), + # A few platforms have a tester present response on this address, add to log + (Ecu.transmission, 0x7e1, None), + (Ecu.hvac, 0x7c4, None), + ], + match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, +) + + +STEER_THRESHOLD = 100 + +# These cars have non-standard EPS torque scale factors. All others are 73 +EPS_SCALE = defaultdict(lambda: 73, + {CAR.TOYOTA_PRIUS: 66, CAR.TOYOTA_COROLLA: 88, CAR.LEXUS_IS: 77, CAR.LEXUS_RC: 77, CAR.LEXUS_CTH: 100, CAR.TOYOTA_PRIUS_V: 100}) + +# Toyota/Lexus Safety Sense 2.0 and 2.5 +TSS2_CAR = CAR.with_flags(ToyotaFlags.TSS2) + +NO_DSU_CAR = CAR.with_flags(ToyotaFlags.NO_DSU) + +# the DSU uses the AEB message for longitudinal on these cars +UNSUPPORTED_DSU_CAR = CAR.with_flags(ToyotaFlags.UNSUPPORTED_DSU) + +# these cars have a radar which sends ACC messages instead of the camera +RADAR_ACC_CAR = CAR.with_flags(ToyotaFlags.RADAR_ACC) + +ANGLE_CONTROL_CAR = CAR.with_flags(ToyotaFlags.ANGLE_CONTROL) + +SECOC_CAR = CAR.with_flags(ToyotaFlags.SECOC) + +# no resume button press required +NO_STOP_TIMER_CAR = CAR.with_flags(ToyotaFlags.NO_STOP_TIMER) + +DBC = CAR.create_dbc_map() diff --git a/opendbc_repo/opendbc/car/values.py b/opendbc_repo/opendbc/car/values.py new file mode 100644 index 000000000000000..31406441f330f04 --- /dev/null +++ b/opendbc_repo/opendbc/car/values.py @@ -0,0 +1,19 @@ +from typing import get_args +from opendbc.car.body.values import CAR as BODY +from opendbc.car.chrysler.values import CAR as CHRYSLER +from opendbc.car.ford.values import CAR as FORD +from opendbc.car.gm.values import CAR as GM +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.hyundai.values import CAR as HYUNDAI +from opendbc.car.mazda.values import CAR as MAZDA +from opendbc.car.mock.values import CAR as MOCK +from opendbc.car.nissan.values import CAR as NISSAN +from opendbc.car.subaru.values import CAR as SUBARU +from opendbc.car.tesla.values import CAR as TESLA +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.volkswagen.values import CAR as VOLKSWAGEN + +Platform = BODY | CHRYSLER | FORD | GM | HONDA | HYUNDAI | MAZDA | MOCK | NISSAN | SUBARU | TESLA | TOYOTA | VOLKSWAGEN +BRANDS = get_args(Platform) + +PLATFORMS: dict[str, Platform] = {str(platform): platform for brand in BRANDS for platform in brand} diff --git a/opendbc_repo/opendbc/car/vin.py b/opendbc_repo/opendbc/car/vin.py new file mode 100644 index 000000000000000..5f816524a16ee46 --- /dev/null +++ b/opendbc_repo/opendbc/car/vin.py @@ -0,0 +1,58 @@ +import re + +from panda import uds +from opendbc.car import carlog +from opendbc.car.isotp_parallel_query import IsoTpParallelQuery +from opendbc.car.fw_query_definitions import STANDARD_VIN_ADDRS, StdQueries + +VIN_UNKNOWN = "0" * 17 +VIN_RE = "[A-HJ-NPR-Z0-9]{17}" + + +def is_valid_vin(vin: str): + return re.fullmatch(VIN_RE, vin) is not None + + +def get_vin(can_recv, can_send, buses, timeout=0.1, retry=2, debug=False): + for i in range(retry): + for bus in buses: + for request, response, valid_buses, vin_addrs, functional_addrs, rx_offset in ( + (StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE, (0, 1), STANDARD_VIN_ADDRS, uds.FUNCTIONAL_ADDRS, 0x8), + (StdQueries.OBD_VIN_REQUEST, StdQueries.OBD_VIN_RESPONSE, (0, 1), STANDARD_VIN_ADDRS, uds.FUNCTIONAL_ADDRS, 0x8), + (StdQueries.GM_VIN_REQUEST, StdQueries.GM_VIN_RESPONSE, (0,), [0x24b], None, 0x400), # Bolt fwdCamera + (StdQueries.KWP_VIN_REQUEST, StdQueries.KWP_VIN_RESPONSE, (0,), [0x797], None, 0x3), # Nissan Leaf VCM + (StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE, (0,), [0x74f], None, 0x6a), # Volkswagen fwdCamera + ): + if bus not in valid_buses: + continue + + # When querying functional addresses, ideally we respond to everything that sends a first frame to avoid leaving the + # ECU in a temporary bad state. Note that we may not cover all ECUs and response offsets. TODO: query physical addrs + tx_addrs = vin_addrs + if functional_addrs is not None: + tx_addrs = [a for a in range(0x700, 0x800) if a != 0x7DF] + list(range(0x18DA00F1, 0x18DB00F1, 0x100)) + + try: + query = IsoTpParallelQuery(can_send, can_recv, bus, tx_addrs, [request, ], [response, ], response_offset=rx_offset, + functional_addrs=functional_addrs, debug=debug) + results = query.get_data(timeout) + + for addr in vin_addrs: + vin = results.get((addr, None)) + if vin is not None: + # Ford and Nissan pads with null bytes + if len(vin) in (19, 24): + vin = re.sub(b'\x00*$', b'', vin) + + # Honda Bosch response starts with a length, trim to correct length + if vin.startswith(b'\x11'): + vin = vin[1:18] + + carlog.error(f"got vin with {request=}") + return uds.get_rx_addr_for_tx_addr(addr, rx_offset=rx_offset), bus, vin.decode() + except Exception: + carlog.exception("VIN query exception") + + carlog.error(f"vin query retry ({i+1}) ...") + + return -1, -1, VIN_UNKNOWN diff --git a/opendbc_repo/opendbc/car/volkswagen/__init__.py b/opendbc_repo/opendbc/car/volkswagen/__init__.py new file mode 100644 index 000000000000000..e69de29bb2d1d64 diff --git a/opendbc_repo/opendbc/car/volkswagen/carcontroller.py b/opendbc_repo/opendbc/car/volkswagen/carcontroller.py new file mode 100644 index 000000000000000..f96e1923b065f0c --- /dev/null +++ b/opendbc_repo/opendbc/car/volkswagen/carcontroller.py @@ -0,0 +1,118 @@ +from opendbc.can.packer import CANPacker +from opendbc.car import DT_CTRL, apply_driver_steer_torque_limits, structs +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.common.numpy_fast import clip +from opendbc.car.interfaces import CarControllerBase +from opendbc.car.volkswagen import mqbcan, pqcan +from opendbc.car.volkswagen.values import CANBUS, CarControllerParams, VolkswagenFlags + +VisualAlert = structs.CarControl.HUDControl.VisualAlert +LongCtrlState = structs.CarControl.Actuators.LongControlState + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP): + super().__init__(dbc_name, CP) + self.CCP = CarControllerParams(CP) + self.CCS = pqcan if CP.flags & VolkswagenFlags.PQ else mqbcan + self.packer_pt = CANPacker(dbc_name) + self.ext_bus = CANBUS.pt if CP.networkLocation == structs.CarParams.NetworkLocation.fwdCamera else CANBUS.cam + + self.apply_steer_last = 0 + self.gra_acc_counter_last = None + self.eps_timer_soft_disable_alert = False + self.hca_frame_timer_running = 0 + self.hca_frame_same_torque = 0 + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + can_sends = [] + + # **** Steering Controls ************************************************ # + + if self.frame % self.CCP.STEER_STEP == 0: + # Logic to avoid HCA state 4 "refused": + # * Don't steer unless HCA is in state 3 "ready" or 5 "active" + # * Don't steer at standstill + # * Don't send > 3.00 Newton-meters torque + # * Don't send the same torque for > 6 seconds + # * Don't send uninterrupted steering for > 360 seconds + # MQB racks reset the uninterrupted steering timer after a single frame + # of HCA disabled; this is done whenever output happens to be zero. + + if CC.latActive: + new_steer = int(round(actuators.steer * self.CCP.STEER_MAX)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP) + self.hca_frame_timer_running += self.CCP.STEER_STEP + if self.apply_steer_last == apply_steer: + self.hca_frame_same_torque += self.CCP.STEER_STEP + if self.hca_frame_same_torque > self.CCP.STEER_TIME_STUCK_TORQUE / DT_CTRL: + apply_steer -= (1, -1)[apply_steer < 0] + self.hca_frame_same_torque = 0 + else: + self.hca_frame_same_torque = 0 + hca_enabled = abs(apply_steer) > 0 + else: + hca_enabled = False + apply_steer = 0 + + if not hca_enabled: + self.hca_frame_timer_running = 0 + + self.eps_timer_soft_disable_alert = self.hca_frame_timer_running > self.CCP.STEER_TIME_ALERT / DT_CTRL + self.apply_steer_last = apply_steer + can_sends.append(self.CCS.create_steering_control(self.packer_pt, CANBUS.pt, apply_steer, hca_enabled)) + + if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + # Pacify VW Emergency Assist driver inactivity detection by changing its view of driver steering input torque + # to the greatest of actual driver input or 2x openpilot's output (1x openpilot output is not enough to + # consistently reset inactivity detection on straight level roads). See commaai/openpilot#23274 for background. + ea_simulated_torque = clip(apply_steer * 2, -self.CCP.STEER_MAX, self.CCP.STEER_MAX) + if abs(CS.out.steeringTorque) > abs(ea_simulated_torque): + ea_simulated_torque = CS.out.steeringTorque + can_sends.append(self.CCS.create_eps_update(self.packer_pt, CANBUS.cam, CS.eps_stock_values, ea_simulated_torque)) + + # **** Acceleration Controls ******************************************** # + + if self.frame % self.CCP.ACC_CONTROL_STEP == 0 and self.CP.openpilotLongitudinalControl: + acc_control = self.CCS.acc_control_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) + accel = clip(actuators.accel, self.CCP.ACCEL_MIN, self.CCP.ACCEL_MAX) if CC.longActive else 0 + stopping = actuators.longControlState == LongCtrlState.stopping + starting = actuators.longControlState == LongCtrlState.pid and (CS.esp_hold_confirmation or CS.out.vEgo < self.CP.vEgoStopping) + can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, CS.acc_type, CC.longActive, accel, + acc_control, stopping, starting, CS.esp_hold_confirmation)) + + # **** HUD Controls ***************************************************** # + + if self.frame % self.CCP.LDW_STEP == 0: + hud_alert = 0 + if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw): + hud_alert = self.CCP.LDW_MESSAGES["laneAssistTakeOver"] + can_sends.append(self.CCS.create_lka_hud_control(self.packer_pt, CANBUS.pt, CS.ldw_stock_values, CC.latActive, + CS.out.steeringPressed, hud_alert, hud_control)) + + if self.frame % self.CCP.ACC_HUD_STEP == 0 and self.CP.openpilotLongitudinalControl: + lead_distance = 0 + if hud_control.leadVisible and self.frame * DT_CTRL > 1.0: # Don't display lead until we know the scaling factor + lead_distance = 512 if CS.upscale_lead_car_signal else 8 + acc_hud_status = self.CCS.acc_hud_status_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) + # FIXME: follow the recent displayed-speed updates, also use mph_kmh toggle to fix display rounding problem? + set_speed = hud_control.setSpeed * CV.MS_TO_KPH + can_sends.append(self.CCS.create_acc_hud_control(self.packer_pt, CANBUS.pt, acc_hud_status, set_speed, + lead_distance, hud_control.leadDistanceBars)) + + # **** Stock ACC Button Controls **************************************** # + + gra_send_ready = self.CP.pcmCruise and CS.gra_stock_values["COUNTER"] != self.gra_acc_counter_last + if gra_send_ready and (CC.cruiseControl.cancel or CC.cruiseControl.resume): + can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, self.ext_bus, CS.gra_stock_values, + cancel=CC.cruiseControl.cancel, resume=CC.cruiseControl.resume)) + + new_actuators = actuators.as_builder() + new_actuators.steer = self.apply_steer_last / self.CCP.STEER_MAX + new_actuators.steerOutputCan = self.apply_steer_last + + self.gra_acc_counter_last = CS.gra_stock_values["COUNTER"] + self.frame += 1 + return new_actuators, can_sends diff --git a/opendbc_repo/opendbc/car/volkswagen/carstate.py b/opendbc_repo/opendbc/car/volkswagen/carstate.py new file mode 100644 index 000000000000000..b8b783e0dfd0b0c --- /dev/null +++ b/opendbc_repo/opendbc/car/volkswagen/carstate.py @@ -0,0 +1,402 @@ +import numpy as np +from opendbc.can.parser import CANParser +from opendbc.car import structs +from opendbc.car.interfaces import CarStateBase +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car.volkswagen.values import DBC, CANBUS, NetworkLocation, TransmissionType, GearShifter, \ + CarControllerParams, VolkswagenFlags + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + self.frame = 0 + self.eps_init_complete = False + self.CCP = CarControllerParams(CP) + self.button_states = {button.event_type: False for button in self.CCP.BUTTONS} + self.esp_hold_confirmation = False + self.upscale_lead_car_signal = False + self.eps_stock_values = False + + def create_button_events(self, pt_cp, buttons): + button_events = [] + + for button in buttons: + state = pt_cp.vl[button.can_addr][button.can_msg] in button.values + if self.button_states[button.event_type] != state: + event = structs.CarState.ButtonEvent() + event.type = button.event_type + event.pressed = state + button_events.append(event) + self.button_states[button.event_type] = state + + return button_events + + def update(self, pt_cp, cam_cp, *_) -> structs.CarState: + + ext_cp = pt_cp if self.CP.networkLocation == NetworkLocation.fwdCamera else cam_cp + + if self.CP.flags & VolkswagenFlags.PQ: + return self.update_pq(pt_cp, cam_cp, ext_cp) + + ret = structs.CarState() + # Update vehicle speed and acceleration from ABS wheel speeds. + ret.wheelSpeeds = self.get_wheel_speeds( + pt_cp.vl["ESP_19"]["ESP_VL_Radgeschw_02"], + pt_cp.vl["ESP_19"]["ESP_VR_Radgeschw_02"], + pt_cp.vl["ESP_19"]["ESP_HL_Radgeschw_02"], + pt_cp.vl["ESP_19"]["ESP_HR_Radgeschw_02"], + ) + + ret.vEgoRaw = float(np.mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr])) + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.vEgoRaw == 0 + + # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. + ret.steeringAngleDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradwinkel"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradwinkel"])] + ret.steeringRateDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradw_Geschw"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradw_Geschw"])] + ret.steeringTorque = pt_cp.vl["LH_EPS_03"]["EPS_Lenkmoment"] * (1, -1)[int(pt_cp.vl["LH_EPS_03"]["EPS_VZ_Lenkmoment"])] + ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE + ret.yawRate = pt_cp.vl["ESP_02"]["ESP_Gierrate"] * (1, -1)[int(pt_cp.vl["ESP_02"]["ESP_VZ_Gierrate"])] * CV.DEG_TO_RAD + hca_status = self.CCP.hca_status_values.get(pt_cp.vl["LH_EPS_03"]["EPS_HCA_Status"]) + ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) + + # VW Emergency Assist status tracking and mitigation + self.eps_stock_values = pt_cp.vl["LH_EPS_03"] + if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + ret.carFaultedNonCritical = bool(cam_cp.vl["HCA_01"]["EA_Ruckfreigabe"]) or cam_cp.vl["HCA_01"]["EA_ACC_Sollstatus"] > 0 + + # Update gas, brakes, and gearshift. + ret.gas = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] / 100.0 + ret.gasPressed = ret.gas > 0 + ret.brake = pt_cp.vl["ESP_05"]["ESP_Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects + brake_pedal_pressed = bool(pt_cp.vl["Motor_14"]["MO_Fahrer_bremst"]) + brake_pressure_detected = bool(pt_cp.vl["ESP_05"]["ESP_Fahrer_bremst"]) + ret.brakePressed = brake_pedal_pressed or brake_pressure_detected + ret.parkingBrake = bool(pt_cp.vl["Kombi_01"]["KBI_Handbremse"]) # FIXME: need to include an EPB check as well + + # Update gear and/or clutch position data. + if self.CP.transmissionType == TransmissionType.automatic: + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_11"]["GE_Fahrstufe"], None)) + elif self.CP.transmissionType == TransmissionType.direct: + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Motor_EV_01"]["MO_Waehlpos"], None)) + elif self.CP.transmissionType == TransmissionType.manual: + ret.clutchPressed = not pt_cp.vl["Motor_14"]["MO_Kuppl_schalter"] + if bool(pt_cp.vl["Gateway_72"]["BCM1_Rueckfahrlicht_Schalter"]): + ret.gearShifter = GearShifter.reverse + else: + ret.gearShifter = GearShifter.drive + + # Update door and trunk/hatch lid open status. + ret.doorOpen = any([pt_cp.vl["Gateway_72"]["ZV_FT_offen"], + pt_cp.vl["Gateway_72"]["ZV_BT_offen"], + pt_cp.vl["Gateway_72"]["ZV_HFS_offen"], + pt_cp.vl["Gateway_72"]["ZV_HBFS_offen"], + pt_cp.vl["Gateway_72"]["ZV_HD_offen"]]) + + # Update seatbelt fastened status. + ret.seatbeltUnlatched = pt_cp.vl["Airbag_02"]["AB_Gurtschloss_FA"] != 3 + + # Consume blind-spot monitoring info/warning LED states, if available. + # Infostufe: BSM LED on, Warnung: BSM LED flashing + if self.CP.enableBsm: + ret.leftBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_li"]) + ret.rightBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_re"]) + + # Consume factory LDW data relevant for factory SWA (Lane Change Assist) + # and capture it for forwarding to the blind spot radar controller + self.ldw_stock_values = cam_cp.vl["LDW_02"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} + + # Stock FCW is considered active if the release bit for brake-jerk warning + # is set. Stock AEB considered active if the partial braking or target + # braking release bits are set. + # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance + # Systems, chapter on Front Assist with Braking: Golf Family for all MQB + ret.stockFcw = bool(ext_cp.vl["ACC_10"]["AWV2_Freigabe"]) + ret.stockAeb = bool(ext_cp.vl["ACC_10"]["ANB_Teilbremsung_Freigabe"]) or bool(ext_cp.vl["ACC_10"]["ANB_Zielbremsung_Freigabe"]) + + # Update ACC radar status. + self.acc_type = ext_cp.vl["ACC_06"]["ACC_Typ"] + + # ACC okay but disabled (1), ACC ready (2), a radar visibility or other fault/disruption (6 or 7) + # currently regulating speed (3), driver accel override (4), brake only (5) + ret.cruiseState.available = pt_cp.vl["TSK_06"]["TSK_Status"] in (2, 3, 4, 5) + ret.cruiseState.enabled = pt_cp.vl["TSK_06"]["TSK_Status"] in (3, 4, 5) + + if self.CP.pcmCruise: + # Cruise Control mode; check for distance UI setting from the radar. + # ECM does not manage this, so do not need to check for openpilot longitudinal + ret.cruiseState.nonAdaptive = ext_cp.vl["ACC_02"]["ACC_Gesetzte_Zeitluecke"] == 0 + else: + # Speed limiter mode; ECM faults if we command ACC while not pcmCruise + ret.cruiseState.nonAdaptive = bool(pt_cp.vl["TSK_06"]["TSK_Limiter_ausgewaehlt"]) + + ret.accFaulted = pt_cp.vl["TSK_06"]["TSK_Status"] in (6, 7) + + self.esp_hold_confirmation = bool(pt_cp.vl["ESP_21"]["ESP_Haltebestaetigung"]) + ret.cruiseState.standstill = self.CP.pcmCruise and self.esp_hold_confirmation + + # Update ACC setpoint. When the setpoint is zero or there's an error, the + # radar sends a set-speed of ~90.69 m/s / 203mph. + if self.CP.pcmCruise: + ret.cruiseState.speed = ext_cp.vl["ACC_02"]["ACC_Wunschgeschw_02"] * CV.KPH_TO_MS + if ret.cruiseState.speed > 90: + ret.cruiseState.speed = 0 + + # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough + ret.leftBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Left"]) + ret.rightBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Right"]) + ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) + self.gra_stock_values = pt_cp.vl["GRA_ACC_01"] + + # Additional safety checks performed in CarInterface. + ret.espDisabled = pt_cp.vl["ESP_21"]["ESP_Tastung_passiv"] != 0 + + # Digital instrument clusters expect the ACC HUD lead car distance to be scaled differently + self.upscale_lead_car_signal = bool(pt_cp.vl["Kombi_03"]["KBI_Variante"]) + + self.frame += 1 + return ret + + def update_pq(self, pt_cp, cam_cp, ext_cp) -> structs.CarState: + ret = structs.CarState() + # Update vehicle speed and acceleration from ABS wheel speeds. + ret.wheelSpeeds = self.get_wheel_speeds( + pt_cp.vl["Bremse_3"]["Radgeschw__VL_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__VR_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__HL_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__HR_4_1"], + ) + + # vEgo obtained from Bremse_1 vehicle speed rather than Bremse_3 wheel speeds because Bremse_3 isn't present on NSF + ret.vEgoRaw = pt_cp.vl["Bremse_1"]["Geschwindigkeit_neu__Bremse_1_"] * CV.KPH_TO_MS + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.vEgoRaw == 0 + + # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. + ret.steeringAngleDeg = pt_cp.vl["Lenkhilfe_3"]["LH3_BLW"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_BLWSign"])] + ret.steeringRateDeg = pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit"] * (1, -1)[int(pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit_S"])] + ret.steeringTorque = pt_cp.vl["Lenkhilfe_3"]["LH3_LM"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_LMSign"])] + ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE + ret.yawRate = pt_cp.vl["Bremse_5"]["Giergeschwindigkeit"] * (1, -1)[int(pt_cp.vl["Bremse_5"]["Vorzeichen_der_Giergeschwindigk"])] * CV.DEG_TO_RAD + hca_status = self.CCP.hca_status_values.get(pt_cp.vl["Lenkhilfe_2"]["LH2_Sta_HCA"]) + ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) + + # Update gas, brakes, and gearshift. + ret.gas = pt_cp.vl["Motor_3"]["Fahrpedal_Rohsignal"] / 100.0 + ret.gasPressed = ret.gas > 0 + ret.brake = pt_cp.vl["Bremse_5"]["Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects + ret.brakePressed = bool(pt_cp.vl["Motor_2"]["Bremslichtschalter"]) + ret.parkingBrake = bool(pt_cp.vl["Kombi_1"]["Bremsinfo"]) + + # Update gear and/or clutch position data. + if self.CP.transmissionType == TransmissionType.automatic: + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"], None)) + elif self.CP.transmissionType == TransmissionType.manual: + ret.clutchPressed = not pt_cp.vl["Motor_1"]["Kupplungsschalter"] + reverse_light = bool(pt_cp.vl["Gate_Komf_1"]["GK1_Rueckfahr"]) + if reverse_light: + ret.gearShifter = GearShifter.reverse + else: + ret.gearShifter = GearShifter.drive + + # Update door and trunk/hatch lid open status. + ret.doorOpen = any([pt_cp.vl["Gate_Komf_1"]["GK1_Fa_Tuerkont"], + pt_cp.vl["Gate_Komf_1"]["BSK_BT_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HL_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HR_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HD_Hauptraste"]]) + + # Update seatbelt fastened status. + ret.seatbeltUnlatched = not bool(pt_cp.vl["Airbag_1"]["Gurtschalter_Fahrer"]) + + # Consume blind-spot monitoring info/warning LED states, if available. + # Infostufe: BSM LED on, Warnung: BSM LED flashing + if self.CP.enableBsm: + ret.leftBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_li"]) + ret.rightBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_re"]) + + # Consume factory LDW data relevant for factory SWA (Lane Change Assist) + # and capture it for forwarding to the blind spot radar controller + self.ldw_stock_values = cam_cp.vl["LDW_Status"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} + + # Stock FCW is considered active if the release bit for brake-jerk warning + # is set. Stock AEB considered active if the partial braking or target + # braking release bits are set. + # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance + # Systems, chapters on Front Assist with Braking and City Emergency + # Braking for the 2016 Passat NMS + # TODO: deferred until we can collect data on pre-MY2016 behavior, AWV message may be shorter with fewer signals + ret.stockFcw = False + ret.stockAeb = False + + # Update ACC radar status. + self.acc_type = ext_cp.vl["ACC_System"]["ACS_Typ_ACC"] + ret.cruiseState.available = bool(pt_cp.vl["Motor_5"]["GRA_Hauptschalter"]) + ret.cruiseState.enabled = pt_cp.vl["Motor_2"]["GRA_Status"] in (1, 2) + if self.CP.pcmCruise: + ret.accFaulted = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_StaACC"] in (6, 7) + else: + ret.accFaulted = pt_cp.vl["Motor_2"]["GRA_Status"] == 3 + + # Update ACC setpoint. When the setpoint reads as 255, the driver has not + # yet established an ACC setpoint, so treat it as zero. + ret.cruiseState.speed = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_V_Wunsch"] * CV.KPH_TO_MS + if ret.cruiseState.speed > 70: # 255 kph in m/s == no current setpoint + ret.cruiseState.speed = 0 + + # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(300, pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_li"], + pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_re"]) + ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) + self.gra_stock_values = pt_cp.vl["GRA_Neu"] + + # Additional safety checks performed in CarInterface. + ret.espDisabled = bool(pt_cp.vl["Bremse_1"]["ESP_Passiv_getastet"]) + + self.frame += 1 + return ret + + def update_hca_state(self, hca_status): + # Treat INITIALIZING and FAULT as temporary for worst likely EPS recovery time, for cars without factory Lane Assist + # DISABLED means the EPS hasn't been configured to support Lane Assist + self.eps_init_complete = self.eps_init_complete or (hca_status in ("DISABLED", "READY", "ACTIVE") or self.frame > 600) + perm_fault = hca_status == "DISABLED" or (self.eps_init_complete and hca_status in ("INITIALIZING", "FAULT")) + temp_fault = hca_status in ("REJECTED", "PREEMPTED") or not self.eps_init_complete + return temp_fault, perm_fault + + @staticmethod + def get_can_parser(CP): + if CP.flags & VolkswagenFlags.PQ: + return CarState.get_can_parser_pq(CP) + + messages = [ + # sig_address, frequency + ("LWI_01", 100), # From J500 Steering Assist with integrated sensors + ("LH_EPS_03", 100), # From J500 Steering Assist with integrated sensors + ("ESP_19", 100), # From J104 ABS/ESP controller + ("ESP_05", 50), # From J104 ABS/ESP controller + ("ESP_21", 50), # From J104 ABS/ESP controller + ("Motor_20", 50), # From J623 Engine control module + ("TSK_06", 50), # From J623 Engine control module + ("ESP_02", 50), # From J104 ABS/ESP controller + ("GRA_ACC_01", 33), # From J533 CAN gateway (via LIN from steering wheel controls) + ("Gateway_72", 10), # From J533 CAN gateway (aggregated data) + ("Motor_14", 10), # From J623 Engine control module + ("Airbag_02", 5), # From J234 Airbag control module + ("Kombi_01", 2), # From J285 Instrument cluster + ("Blinkmodi_02", 1), # From J519 BCM (sent at 1Hz when no lights active, 50Hz when active) + ("Kombi_03", 0), # From J285 instrument cluster (not present on older cars, 1Hz when present) + ] + + if CP.transmissionType == TransmissionType.automatic: + messages.append(("Getriebe_11", 20)) # From J743 Auto transmission control module + elif CP.transmissionType == TransmissionType.direct: + messages.append(("Motor_EV_01", 10)) # From J??? unknown EV control module + + if CP.networkLocation == NetworkLocation.fwdCamera: + # Radars are here on CANBUS.pt + messages += MqbExtraSignals.fwd_radar_messages + if CP.enableBsm: + messages += MqbExtraSignals.bsm_radar_messages + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) + + @staticmethod + def get_cam_can_parser(CP): + if CP.flags & VolkswagenFlags.PQ: + return CarState.get_cam_can_parser_pq(CP) + + messages = [] + + if CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + messages += [ + ("HCA_01", 1), # From R242 Driver assistance camera, 50Hz if steering/1Hz if not + ] + + if CP.networkLocation == NetworkLocation.fwdCamera: + messages += [ + # sig_address, frequency + ("LDW_02", 10) # From R242 Driver assistance camera + ] + else: + # Radars are here on CANBUS.cam + messages += MqbExtraSignals.fwd_radar_messages + if CP.enableBsm: + messages += MqbExtraSignals.bsm_radar_messages + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) + + @staticmethod + def get_can_parser_pq(CP): + messages = [ + # sig_address, frequency + ("Bremse_1", 100), # From J104 ABS/ESP controller + ("Bremse_3", 100), # From J104 ABS/ESP controller + ("Lenkhilfe_3", 100), # From J500 Steering Assist with integrated sensors + ("Lenkwinkel_1", 100), # From J500 Steering Assist with integrated sensors + ("Motor_3", 100), # From J623 Engine control module + ("Airbag_1", 50), # From J234 Airbag control module + ("Bremse_5", 50), # From J104 ABS/ESP controller + ("GRA_Neu", 50), # From J??? steering wheel control buttons + ("Kombi_1", 50), # From J285 Instrument cluster + ("Motor_2", 50), # From J623 Engine control module + ("Motor_5", 50), # From J623 Engine control module + ("Lenkhilfe_2", 20), # From J500 Steering Assist with integrated sensors + ("Gate_Komf_1", 10), # From J533 CAN gateway + ] + + if CP.transmissionType == TransmissionType.automatic: + messages += [("Getriebe_1", 100)] # From J743 Auto transmission control module + elif CP.transmissionType == TransmissionType.manual: + messages += [("Motor_1", 100)] # From J623 Engine control module + + if CP.networkLocation == NetworkLocation.fwdCamera: + # Extended CAN devices other than the camera are here on CANBUS.pt + messages += PqExtraSignals.fwd_radar_messages + if CP.enableBsm: + messages += PqExtraSignals.bsm_radar_messages + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) + + @staticmethod + def get_cam_can_parser_pq(CP): + + messages = [] + + if CP.networkLocation == NetworkLocation.fwdCamera: + messages += [ + # sig_address, frequency + ("LDW_Status", 10) # From R242 Driver assistance camera + ] + + if CP.networkLocation == NetworkLocation.gateway: + # Radars are here on CANBUS.cam + messages += PqExtraSignals.fwd_radar_messages + if CP.enableBsm: + messages += PqExtraSignals.bsm_radar_messages + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) + + +class MqbExtraSignals: + # Additional signal and message lists for optional or bus-portable controllers + fwd_radar_messages = [ + ("ACC_06", 50), # From J428 ACC radar control module + ("ACC_10", 50), # From J428 ACC radar control module + ("ACC_02", 17), # From J428 ACC radar control module + ] + bsm_radar_messages = [ + ("SWA_01", 20), # From J1086 Lane Change Assist + ] + + +class PqExtraSignals: + # Additional signal and message lists for optional or bus-portable controllers + fwd_radar_messages = [ + ("ACC_System", 50), # From J428 ACC radar control module + ("ACC_GRA_Anzeige", 25), # From J428 ACC radar control module + ] + bsm_radar_messages = [ + ("SWA_1", 20), # From J1086 Lane Change Assist + ] diff --git a/opendbc_repo/opendbc/car/volkswagen/fingerprints.py b/opendbc_repo/opendbc/car/volkswagen/fingerprints.py new file mode 100644 index 000000000000000..123e19baa2deeff --- /dev/null +++ b/opendbc_repo/opendbc/car/volkswagen/fingerprints.py @@ -0,0 +1,1223 @@ +from opendbc.car.structs import CarParams +from opendbc.car.volkswagen.values import CAR + +Ecu = CarParams.Ecu + +# TODO: Sharan Mk2 EPS and DQ250 auto trans both require KWP2000 support for fingerprinting + + +FW_VERSIONS = { + CAR.VOLKSWAGEN_ARTEON_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x873G0906259AH\xf1\x890001', + b'\xf1\x873G0906259F \xf1\x890004', + b'\xf1\x873G0906259G \xf1\x890004', + b'\xf1\x873G0906259G \xf1\x890005', + b'\xf1\x873G0906259M \xf1\x890003', + b'\xf1\x873G0906259N \xf1\x890004', + b'\xf1\x873G0906259P \xf1\x890001', + b'\xf1\x875NA907115H \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158L \xf1\x893611', + b'\xf1\x870DL300014C \xf1\x893704', + b'\xf1\x870GC300011L \xf1\x891401', + b'\xf1\x870GC300014M \xf1\x892802', + b'\xf1\x870GC300019G \xf1\x892804', + b'\xf1\x870GC300040P \xf1\x891401', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121157161111572900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', + b'\xf1\x873Q0959655CK\xf1\x890711\xf1\x82\x0e1712141712141105121122052900', + b'\xf1\x873Q0959655DA\xf1\x890720\xf1\x82\x0e1712141712141105121122052900', + b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\x0e1812141812171105141123052J00', + b'\xf1\x875QF959655AP\xf1\x890755\xf1\x82\x1311110011111311111100110200--1611125F49', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571B41815A1', + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571B00817A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020800', + b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002MB4092M7N', + b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002NB4202N7N', + b'\xf1\x875WA907145Q \xf1\x891063\xf1\x82\x002KB4092KOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572T \xf1\x890383', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.VOLKSWAGEN_ATLAS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703H906026AA\xf1\x899970', + b'\xf1\x8703H906026AG\xf1\x899971', + b'\xf1\x8703H906026AG\xf1\x899973', + b'\xf1\x8703H906026AJ\xf1\x890638', + b'\xf1\x8703H906026AJ\xf1\x891017', + b'\xf1\x8703H906026AT\xf1\x891922', + b'\xf1\x8703H906026BC\xf1\x892664', + b'\xf1\x8703H906026F \xf1\x896696', + b'\xf1\x8703H906026F \xf1\x899970', + b'\xf1\x8703H906026J \xf1\x896026', + b'\xf1\x8703H906026J \xf1\x899970', + b'\xf1\x8703H906026J \xf1\x899971', + b'\xf1\x8703H906026S \xf1\x896693', + b'\xf1\x8703H906026S \xf1\x899970', + b'\xf1\x873CN906259 \xf1\x890005', + b'\xf1\x873CN906259F \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158A \xf1\x893387', + b'\xf1\x8709G927158DR\xf1\x893536', + b'\xf1\x8709G927158DR\xf1\x893742', + b'\xf1\x8709G927158EN\xf1\x893691', + b'\xf1\x8709G927158F \xf1\x893489', + b'\xf1\x8709G927158FT\xf1\x893835', + b'\xf1\x8709G927158GL\xf1\x893939', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\x0e1914151912001103111122031200', + b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\x0e2214152212001105141122052900', + b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e1114151112001105111122052900', + b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e2214152212001105141122052900', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105111122052J00', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B60924A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6G920A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6M921A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6N920A1', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6080105', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, + CAR.VOLKSWAGEN_CADDY_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027T \xf1\x892363', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872K5959655E \xf1\x890018\xf1\x82\x05000P037605', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0155', + ], + }, + CAR.VOLKSWAGEN_CRAFTER_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906056BP\xf1\x894729', + b'\xf1\x8704L906056EK\xf1\x896391', + b'\xf1\x8705L906023BC\xf1\x892688', + b'\xf1\x8705L906023MH\xf1\x892588', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AL\xf1\x890505\xf1\x82\x0e1411001413001203151311031100', + b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900', + b'\xf1\x875QF959655AS\xf1\x890755\xf1\x82\x1315140015150011111100050200--1311120749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872N0909143D\x00\xf1\x897010\xf1\x82\x05183AZ306A2', + b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2', + b'\xf1\x872N0909143H \xf1\x897045\xf1\x82\x05263AZ309A2', + b'\xf1\x872N0909144K \xf1\x897045\xf1\x82\x05233AZ810A2', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572J \xf1\x890156', + b'\xf1\x872Q0907572M \xf1\x890233', + ], + }, + CAR.VOLKSWAGEN_GOLF_MK7: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906016A \xf1\x897697', + b'\xf1\x8704E906016AD\xf1\x895758', + b'\xf1\x8704E906016CE\xf1\x899096', + b'\xf1\x8704E906016CH\xf1\x899226', + b'\xf1\x8704E906016N \xf1\x899105', + b'\xf1\x8704E906023AG\xf1\x891726', + b'\xf1\x8704E906023BN\xf1\x894518', + b'\xf1\x8704E906024K \xf1\x896811', + b'\xf1\x8704E906024K \xf1\x899970', + b'\xf1\x8704E906027GR\xf1\x892394', + b'\xf1\x8704E906027HD\xf1\x892603', + b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704E906027MA\xf1\x894958', + b'\xf1\x8704L906021DT\xf1\x895520', + b'\xf1\x8704L906021DT\xf1\x898127', + b'\xf1\x8704L906021N \xf1\x895518', + b'\xf1\x8704L906021N \xf1\x898138', + b'\xf1\x8704L906026BN\xf1\x891197', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906026NF\xf1\x899528', + b'\xf1\x8704L906056CL\xf1\x893823', + b'\xf1\x8704L906056CR\xf1\x895813', + b'\xf1\x8704L906056HE\xf1\x893758', + b'\xf1\x8704L906056HN\xf1\x896590', + b'\xf1\x8704L906056HT\xf1\x896591', + b'\xf1\x8704L997022N \xf1\x899459', + b'\xf1\x870EA906016A \xf1\x898343', + b'\xf1\x870EA906016E \xf1\x894219', + b'\xf1\x870EA906016F \xf1\x894238', + b'\xf1\x870EA906016F \xf1\x895002', + b'\xf1\x870EA906016Q \xf1\x895993', + b'\xf1\x870EA906016S \xf1\x897207', + b'\xf1\x875G0906259 \xf1\x890007', + b'\xf1\x875G0906259D \xf1\x890002', + b'\xf1\x875G0906259J \xf1\x890002', + b'\xf1\x875G0906259L \xf1\x890002', + b'\xf1\x875G0906259N \xf1\x890003', + b'\xf1\x875G0906259Q \xf1\x890002', + b'\xf1\x875G0906259Q \xf1\x892313', + b'\xf1\x875G0906259T \xf1\x890003', + b'\xf1\x878V0906259H \xf1\x890002', + b'\xf1\x878V0906259J \xf1\x890003', + b'\xf1\x878V0906259J \xf1\x890103', + b'\xf1\x878V0906259K \xf1\x890001', + b'\xf1\x878V0906259K \xf1\x890003', + b'\xf1\x878V0906259P \xf1\x890001', + b'\xf1\x878V0906259Q \xf1\x890002', + b'\xf1\x878V0906259R \xf1\x890002', + b'\xf1\x878V0906264F \xf1\x890003', + b'\xf1\x878V0906264L \xf1\x890002', + b'\xf1\x878V0906264M \xf1\x890001', + b'\xf1\x878V09C0BB01 \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927749AP\xf1\x892943', + b'\xf1\x8709S927158A \xf1\x893585', + b'\xf1\x870CW300040H \xf1\x890606', + b'\xf1\x870CW300041D \xf1\x891004', + b'\xf1\x870CW300041H \xf1\x891010', + b'\xf1\x870CW300042F \xf1\x891604', + b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870CW300043E \xf1\x891603', + b'\xf1\x870CW300044S \xf1\x894530', + b'\xf1\x870CW300044T \xf1\x895245', + b'\xf1\x870CW300045 \xf1\x894531', + b'\xf1\x870CW300047D \xf1\x895261', + b'\xf1\x870CW300047E \xf1\x895261', + b'\xf1\x870CW300048J \xf1\x890611', + b'\xf1\x870CW300049H \xf1\x890905', + b'\xf1\x870CW300050G \xf1\x891905', + b'\xf1\x870D9300012 \xf1\x894904', + b'\xf1\x870D9300012 \xf1\x894913', + b'\xf1\x870D9300012 \xf1\x894937', + b'\xf1\x870D9300012 \xf1\x895045', + b'\xf1\x870D9300012 \xf1\x895046', + b'\xf1\x870D9300014M \xf1\x895004', + b'\xf1\x870D9300014Q \xf1\x895006', + b'\xf1\x870D9300018 \xf1\x895201', + b'\xf1\x870D9300020J \xf1\x894902', + b'\xf1\x870D9300020Q \xf1\x895201', + b'\xf1\x870D9300020S \xf1\x895201', + b'\xf1\x870D9300040A \xf1\x893613', + b'\xf1\x870D9300040S \xf1\x894311', + b'\xf1\x870D9300041H \xf1\x895220', + b'\xf1\x870D9300041N \xf1\x894512', + b'\xf1\x870D9300041P \xf1\x894507', + b'\xf1\x870DD300045K \xf1\x891120', + b'\xf1\x870DD300046F \xf1\x891601', + b'\xf1\x870GC300012A \xf1\x891401', + b'\xf1\x870GC300012A \xf1\x891403', + b'\xf1\x870GC300012A \xf1\x891422', + b'\xf1\x870GC300012M \xf1\x892301', + b'\xf1\x870GC300014B \xf1\x892401', + b'\xf1\x870GC300014B \xf1\x892403', + b'\xf1\x870GC300014B \xf1\x892405', + b'\xf1\x870GC300020G \xf1\x892401', + b'\xf1\x870GC300020G \xf1\x892403', + b'\xf1\x870GC300020G \xf1\x892404', + b'\xf1\x870GC300020N \xf1\x892804', + b'\xf1\x870GC300043T \xf1\x899999', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120043114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120053114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114417121411149113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113', + b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x13141500111233003142114A2131219333313100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333423100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100', + b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x13141600111233003142115A2232229333463100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2251229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100', + b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', + b'\xf1\x875Q0959655D \xf1\x890388\xf1\x82\x111413001113120006110417121A101A9113', + b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13271112111312--071104171825102591131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271112111312--071104171825102591131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271212111312--071104171838103891131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13272512111312--07110417182C102C91131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13341512112212--071104172328102891131211', + b'\xf1\x875Q0959655M \xf1\x890361\xf1\x82\x111413001112120041114115121611169112', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200061104171717101791132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200621143171717111791132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200061104171724102491132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200621143171724112491132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200631143171724122491132111', + b'\xf1\x875Q0959655T \xf1\x890825\xf1\x82\x13271200111312--071104171837103791132111', + b'\xf1\x875Q0959655T \xf1\x890830\xf1\x82\x13271100111312--071104171826102691131211', + b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111413001113120006110417121D101D9112', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561A01612A0', + b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566A0J612A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A00514A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01613A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A0J712A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571A0J714A1', + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A01A18A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A02A16A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A0JA16A1', + b'\xf1\x873QM909144 \xf1\x895072\xf1\x82\x0571A01714A1', + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820519A9040203', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00441A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00608A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00641A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00442A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00642A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A07B05A1', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00502A0', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00602A0', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0522A00402A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511A00403A0', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00404A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00504A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A07A02A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00407A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00507A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A07B04A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A20B03A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A2000400', + b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1', + b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00442A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00642A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A16A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A18A1', + b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A01A18A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907567G \xf1\x890390\xf1\x82\x0101', + b'\xf1\x875Q0907567J \xf1\x890396\xf1\x82\x0101', + b'\xf1\x875Q0907567L \xf1\x890098\xf1\x82\x0101', + b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\x0101', + b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', + b'\xf1\x875Q0907572C \xf1\x890210\xf1\x82\x0101', + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572E \xf1\x89X310\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572G \xf1\x890571', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890653', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, + CAR.VOLKSWAGEN_JETTA_MK6: { + (Ecu.srs, 0x715, None): [ + b'\xf1\x875C0959655M \xf1\x890726\xf1\x82\t00NB1108--------24', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0151', + ], + }, + CAR.VOLKSWAGEN_JETTA_MK7: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906024AK\xf1\x899937', + b'\xf1\x8704E906024AS\xf1\x899912', + b'\xf1\x8704E906024B \xf1\x895594', + b'\xf1\x8704E906024BC\xf1\x899971', + b'\xf1\x8704E906024BG\xf1\x891057', + b'\xf1\x8704E906024C \xf1\x899970', + b'\xf1\x8704E906024C \xf1\x899971', + b'\xf1\x8704E906024L \xf1\x895595', + b'\xf1\x8704E906024L \xf1\x899970', + b'\xf1\x8704E906027MS\xf1\x896223', + b'\xf1\x8705E906013BN\xf1\x893711', + b'\xf1\x8705E906013DB\xf1\x893361', + b'\xf1\x875G0906259T \xf1\x890003', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158BQ\xf1\x893545', + b'\xf1\x8709H927158 \xf1\x890515', + 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', + b'\xf1\x875QV907144F \xf1\x891122\xf1\x82\x0001A00701]V', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907567B \xf1\x890534', + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x875Q0907572N \xf1\x890681', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.VOLKSWAGEN_PASSAT_MK8: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703N906026E \xf1\x892114', + b'\xf1\x8704E906023AH\xf1\x893379', + b'\xf1\x8704E906023BM\xf1\x894522', + b'\xf1\x8704L906026DP\xf1\x891538', + b'\xf1\x8704L906026ET\xf1\x891990', + b'\xf1\x8704L906026FP\xf1\x892012', + b'\xf1\x8704L906026GA\xf1\x892013', + b'\xf1\x8704L906026GK\xf1\x899971', + b'\xf1\x8704L906026KD\xf1\x894798', + b'\xf1\x8705L906022A \xf1\x890827', + b'\xf1\x873G0906259 \xf1\x890004', + b'\xf1\x873G0906259B \xf1\x890002', + b'\xf1\x873G0906264 \xf1\x890004', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041E \xf1\x891006', + b'\xf1\x870CW300042H \xf1\x891601', + b'\xf1\x870CW300042H \xf1\x891607', + b'\xf1\x870CW300043H \xf1\x891601', + b'\xf1\x870CW300048R \xf1\x890610', + b'\xf1\x870D9300013A \xf1\x894905', + b'\xf1\x870D9300014L \xf1\x895002', + b'\xf1\x870D9300018C \xf1\x895297', + b'\xf1\x870D9300041A \xf1\x894801', + b'\xf1\x870D9300042H \xf1\x894901', + b'\xf1\x870DD300045T \xf1\x891601', + b'\xf1\x870DD300046H \xf1\x891601', + b'\xf1\x870DL300011H \xf1\x895201', + b'\xf1\x870GC300042H \xf1\x891404', + b'\xf1\x870GC300043 \xf1\x892301', + b'\xf1\x870GC300046P \xf1\x892805', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111', + b'\xf1\x873Q0959655AF\xf1\x890195\xf1\x82\r56140056130012026612120211', + b'\xf1\x873Q0959655AN\xf1\x890305\xf1\x82\r58160058140013036914110311', + b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', + b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012416612124111', + b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111', + b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', + b'\xf1\x873Q0959655BG\xf1\x890712\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001344701311442900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001354701311542900', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011111200631145171716121691132111', + b'\xf1\x875QF959655S \xf1\x890639\xf1\x82\x13131100131300111111000120----2211114A48', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1', + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514B0060703', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526B0060905', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521B00606A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516B00501A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00603A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00703A1', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563B0000600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x873Q0907572A \xf1\x890126', + b'\xf1\x873Q0907572A \xf1\x890130', + b'\xf1\x873Q0907572B \xf1\x890192', + b'\xf1\x873Q0907572B \xf1\x890194', + b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x873Q0907572C \xf1\x890196', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, + CAR.VOLKSWAGEN_PASSAT_NMS: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8706K906016C \xf1\x899609', + b'\xf1\x8706K906016E \xf1\x899830', + b'\xf1\x8706K906016G \xf1\x891124', + b'\xf1\x8706K906071BJ\xf1\x894891', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158AB\xf1\x893318', + b'\xf1\x8709G927158BD\xf1\x893121', + b'\xf1\x8709G927158DK\xf1\x893594', + b'\xf1\x8709G927158FQ\xf1\x893745', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x87561959655 \xf1\x890210\xf1\x82\x1212121111113000102011--121012--101312', + b'\xf1\x87561959655C \xf1\x890508\xf1\x82\x1215141111121100314919--153015--304831', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x87561907567A \xf1\x890132', + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0152', + ], + }, + CAR.VOLKSWAGEN_POLO_MK6: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025H \xf1\x895177', + b'\xf1\x8705C906032J \xf1\x891702', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300042D \xf1\x891612', + b'\xf1\x870CW300050D \xf1\x891908', + b'\xf1\x870CW300051G \xf1\x891909', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AG\xf1\x890248\xf1\x82\x1218130411110411--04040404231811152H14', + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1248130411110416--04040404784811152H14', + b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1384830511110516041405820599841215391471', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144M \xf1\x896041', + b'\xf1\x872Q2909144AB\xf1\x896050', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + ], + }, + CAR.VOLKSWAGEN_SHARAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906016HE\xf1\x894635', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x877N0959655D \xf1\x890016\xf1\x82\x0801100705----10--', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0153', + ], + }, + CAR.VOLKSWAGEN_TAOS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906025CK\xf1\x892228', + b'\xf1\x8704E906027NJ\xf1\x891445', + b'\xf1\x8704E906027NP\xf1\x891286', + b'\xf1\x8705E906013BD\xf1\x892496', + b'\xf1\x8705E906013E \xf1\x891624', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158EM\xf1\x893812', + b'\xf1\x8709S927158BL\xf1\x893791', + b'\xf1\x8709S927158CR\xf1\x893924', + b'\xf1\x8709S927158DN\xf1\x893946', + b'\xf1\x8709S927158FF\xf1\x893876', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1311111111333500314646021450149333613100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1312111111333500314646021550159333613100', + b'\xf1\x875Q0959655CE\xf1\x890421\xf1\x82\x1311110011333300314240021350139333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x001O06081OOM', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060405A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060605A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.VOLKSWAGEN_TCROSS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025AK\xf1\x897053', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300050E \xf1\x891903', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1212130411110411--04041104141311152H14', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144M \xf1\x896041', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.VOLKSWAGEN_TIGUAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703N906026D \xf1\x893680', + b'\xf1\x8704E906024AP\xf1\x891461', + b'\xf1\x8704E906027NB\xf1\x899504', + b'\xf1\x8704L906026EJ\xf1\x893661', + b'\xf1\x8704L906026EJ\xf1\x893916', + b'\xf1\x8704L906027G \xf1\x899893', + b'\xf1\x8705E906018BS\xf1\x890914', + b'\xf1\x875N0906259 \xf1\x890002', + b'\xf1\x875NA906259H \xf1\x890002', + b'\xf1\x875NA907115E \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890005', + b'\xf1\x875NA907115J \xf1\x890002', + b'\xf1\x875NA907115K \xf1\x890004', + b'\xf1\x8783A907115 \xf1\x890007', + b'\xf1\x8783A907115B \xf1\x890005', + b'\xf1\x8783A907115F \xf1\x890002', + b'\xf1\x8783A907115G \xf1\x890001', + b'\xf1\x8783A907115K \xf1\x890001', + b'\xf1\x8783A907115K \xf1\x890002', + b'\xf1\x8783A907115Q \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158DS\xf1\x893699', + b'\xf1\x8709G927158DT\xf1\x893698', + b'\xf1\x8709G927158FM\xf1\x893757', + b'\xf1\x8709G927158GC\xf1\x893821', + b'\xf1\x8709G927158GD\xf1\x893820', + b'\xf1\x8709G927158GM\xf1\x893936', + b'\xf1\x8709G927158GN\xf1\x893938', + b'\xf1\x8709G927158HB\xf1\x894069', + b'\xf1\x8709G927158HC\xf1\x894070', + b'\xf1\x870D9300043 \xf1\x895202', + b'\xf1\x870DD300046K \xf1\x892302', + b'\xf1\x870DL300011N \xf1\x892001', + b'\xf1\x870DL300011N \xf1\x892012', + b'\xf1\x870DL300011N \xf1\x892014', + b'\xf1\x870DL300012M \xf1\x892107', + b'\xf1\x870DL300012P \xf1\x892103', + b'\xf1\x870DL300013A \xf1\x893005', + b'\xf1\x870DL300013G \xf1\x892119', + b'\xf1\x870DL300013G \xf1\x892120', + b'\xf1\x870DL300014C \xf1\x893703', + b'\xf1\x870GC300013P \xf1\x892401', + b'\xf1\x870GC300046Q \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1316143231313500314617011730179333423100', + b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1316143231313500314617011730179333423100', + b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x1331310031333334313132573732379333313100', + b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1311140031333300314232583632369333423100', + b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1312110031333300314232583732379333423100', + b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1331310031333334313132013730379333423100', + b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1316143231313500314641011750179333423100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1312110031333300314240013750379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1312110031333300314240583752379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140013750379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140573752379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333336313140013950399333423100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100', + b'\xf1\x875Q0959655CD\xf1\x890421\xf1\x82\x13123112313333003145406F6154619333613100', + b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x1331310031333300314240024050409333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820529A6060603', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6050705', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6070705', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A60604A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6000600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6017A00', + b'\xf1\x875QF909144 \xf1\x895572\xf1\x82\x0571A60833A1', + b'\xf1\x875QF909144A \xf1\x895581\xf1\x82\x0571A60834A1', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A60634A1', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A62A32A1', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002RA60A2ROM', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002SA6092SOM', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60604A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60804A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60604A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60804A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572J \xf1\x890156', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572Q \xf1\x890342', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.VOLKSWAGEN_TOURAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906025BE\xf1\x890720', + b'\xf1\x8704E906027HQ\xf1\x893746', + b'\xf1\x8704L906026HM\xf1\x893017', + b'\xf1\x8705E906018CQ\xf1\x890808', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020A \xf1\x891936', + b'\xf1\x870CW300041E \xf1\x891005', + b'\xf1\x870CW300041Q \xf1\x891606', + b'\xf1\x870CW300051M \xf1\x891926', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x1336350021353335314132014730479333313100', + b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x13363500213533353141324C4732479333313100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1336350021353336314740025250529333613100', + b'\xf1\x875QD959655AJ\xf1\x890421\xf1\x82\x1336350021313300314240023330339333663100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A8090400', + b'\xf1\x875QD909144F \xf1\x891082\xf1\x82\x0521A00642A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.VOLKSWAGEN_TRANSPORTER_T61: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906056AG\xf1\x899970', + b'\xf1\x8704L906056AL\xf1\x899970', + b'\xf1\x8704L906057AP\xf1\x891186', + b'\xf1\x8704L906057N \xf1\x890413', + b'\xf1\x8705L906023E \xf1\x891352', + b'\xf1\x8705L906023MR\xf1\x892582', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870BT300012E \xf1\x893105', + b'\xf1\x870BT300012G \xf1\x893102', + b'\xf1\x870BT300046R \xf1\x893102', + b'\xf1\x870DV300012B \xf1\x893701', + b'\xf1\x870DV300012B \xf1\x893702', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704161611152S1411', + b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704171711152S1411', + b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', + b'\xf1\x872Q0959655AQ\xf1\x890511\xf1\x82\x1316170411110411--0404170426261215391421', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x0532380518A2', + b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x05323A5519A2', + b'\xf1\x877LA909144G \xf1\x897160\xf1\x82\x05333A5519A2', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + ], + }, + CAR.VOLKSWAGEN_TROC_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018AT\xf1\x899640', + b'\xf1\x8705E906018CK\xf1\x890863', + b'\xf1\x8705E906018P \xf1\x896020', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041S \xf1\x891615', + b'\xf1\x870CW300050J \xf1\x891911', + b'\xf1\x870CW300051M \xf1\x891925', + b'\xf1\x870CW300051M \xf1\x891928', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1111001111001105111111052900', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1311110012333300314240681152119333463100', + b'\xf1\x875Q0959655CF\xf1\x890421\xf1\x82\x1311110012333300314240021150119333613100', + b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1152119333613100', + b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1154119333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521060403A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521060405A1', + b'\xf1\x875WA907144M \xf1\x891051\xf1\x82\x001T06081T7N', + b'\xf1\x875WA907144Q \xf1\x891063\xf1\x82\x001O06081OOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.AUDI_A3_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906023AN\xf1\x893695', + b'\xf1\x8704E906023AR\xf1\x893440', + b'\xf1\x8704E906023BL\xf1\x895190', + b'\xf1\x8704E906027CJ\xf1\x897798', + b'\xf1\x8704L997022N \xf1\x899459', + b'\xf1\x875G0906259A \xf1\x890004', + b'\xf1\x875G0906259D \xf1\x890002', + b'\xf1\x875G0906259L \xf1\x890002', + b'\xf1\x875G0906259Q \xf1\x890002', + b'\xf1\x875G0906259Q \xf1\x890007', + 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', + b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002VG60A2VOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SEAT_ATECA_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027KA\xf1\x893749', + b'\xf1\x8704L906021EL\xf1\x897542', + b'\xf1\x8704L906026BP\xf1\x891198', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906056CR\xf1\x892181', + b'\xf1\x8704L906056CR\xf1\x892797', + b'\xf1\x8705E906018AS\xf1\x899596', + b'\xf1\x8781A906259B \xf1\x890003', + b'\xf1\x878V0906264H \xf1\x890005', + b'\xf1\x878V0907115E \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041D \xf1\x891004', + b'\xf1\x870CW300041G \xf1\x891003', + b'\xf1\x870CW300050J \xf1\x891908', + b'\xf1\x870D9300014S \xf1\x895202', + b'\xf1\x870D9300042M \xf1\x895016', + b'\xf1\x870GC300014P \xf1\x892801', + b'\xf1\x870GC300043A \xf1\x892304', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11110011110011021511110200', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1212001211001305121211052900', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900', + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1312001313001305171311052900', + b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e1312001313001305171311052900', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1113121149', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571N60511A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521N01842A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521N01342A1', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511N01805A0', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N05808A1', + b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x0013N619137N', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.SKODA_FABIA_MK4: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018CF\xf1\x891905', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300051M \xf1\x891936', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1111120749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144S \xf1\x896042', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + ], + }, + CAR.SKODA_KAMIQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025AK\xf1\x897053', + b'\xf1\x8705C906032M \xf1\x891333', + b'\xf1\x8705C906032M \xf1\x892365', + b'\xf1\x8705E906013CK\xf1\x892540', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020 \xf1\x891906', + b'\xf1\x870CW300020 \xf1\x891907', + b'\xf1\x870CW300020T \xf1\x892204', + b'\xf1\x870CW300050 \xf1\x891709', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14', + b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x12111104111104112104040404111111112H14', + b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x122221042111042121040404042E2711152H14', + b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1311150411110411210404040417151215391413', + b'\xf1\x872Q0959655BJ\xf1\x890412\xf1\x82\x132223042111042121040404042B251215391423', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144AB\xf1\x896050', + b'\xf1\x872Q1909144M \xf1\x896041', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_KAROQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906013CL\xf1\x892541', + b'\xf1\x8705E906013H \xf1\x892407', + b'\xf1\x8705E906018P \xf1\x895472', + b'\xf1\x8705E906018P \xf1\x896020', + b'\xf1\x8705L906022BS\xf1\x890913', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020T \xf1\x892202', + b'\xf1\x870CW300041S \xf1\x891615', + b'\xf1\x870GC300014L \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001101131112012100', + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1213001211001101131122012100', + b'\xf1\x873Q0959655DE\xf1\x890731\xf1\x82\x0e1213001211001101131121012J00', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1312110012120011111100010200--2521210749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563T6090500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100700', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_KODIAQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027DD\xf1\x893123', + b'\xf1\x8704E906027LD\xf1\x893433', + b'\xf1\x8704E906027NB\xf1\x896517', + b'\xf1\x8704E906027NB\xf1\x899504', + b'\xf1\x8704L906026DE\xf1\x895418', + b'\xf1\x8704L906026EJ\xf1\x893661', + b'\xf1\x8704L906026HT\xf1\x893617', + b'\xf1\x8705E906018DJ\xf1\x890915', + b'\xf1\x8705E906018DJ\xf1\x891903', + b'\xf1\x8705L906022GM\xf1\x893411', + b'\xf1\x875NA906259E \xf1\x890003', + b'\xf1\x875NA907115D \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890005', + b'\xf1\x8783A907115E \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870D9300014S \xf1\x895201', + b'\xf1\x870D9300043 \xf1\x895202', + b'\xf1\x870DL300011N \xf1\x892014', + b'\xf1\x870DL300012G \xf1\x892006', + b'\xf1\x870DL300012M \xf1\x892107', + b'\xf1\x870DL300012N \xf1\x892110', + b'\xf1\x870DL300013G \xf1\x892119', + b'\xf1\x870GC300014N \xf1\x892801', + b'\xf1\x870GC300018S \xf1\x892803', + b'\xf1\x870GC300019H \xf1\x892806', + b'\xf1\x870GC300046Q \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r11110011110011031111310311', + b'\xf1\x873Q0959655AP\xf1\x890306\xf1\x82\r11110011110011421111314211', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', + b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1213001211001244212111442100', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', + b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', + b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121240749', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121246149', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6060405', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', + b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x0025T6BA25OM', + b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002LT61A2LOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572Q \xf1\x890342', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_OCTAVIA_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025L \xf1\x896198', + b'\xf1\x8704E906016ER\xf1\x895823', + b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704E906027MH\xf1\x894786', + b'\xf1\x8704L906021DT\xf1\x898127', + b'\xf1\x8704L906021ER\xf1\x898361', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906026BS\xf1\x891541', + b'\xf1\x8704L906026BT\xf1\x897612', + b'\xf1\x875G0906259C \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041L \xf1\x891601', + b'\xf1\x870CW300041N \xf1\x891605', + b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870CW300043P \xf1\x891605', + b'\xf1\x870D9300012H \xf1\x894518', + b'\xf1\x870D9300014T \xf1\x895221', + b'\xf1\x870D9300041C \xf1\x894936', + b'\xf1\x870D9300041H \xf1\x895220', + b'\xf1\x870D9300041J \xf1\x894902', + b'\xf1\x870D9300041P \xf1\x894507', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655AK\xf1\x890306\xf1\x82\r31210031210021033733310331', + b'\xf1\x873Q0959655AP\xf1\x890305\xf1\x82\r11110011110011213331312131', + b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01513A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521T00403A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00603A1', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521T00601A1', + b'\xf1\x875QD909144E \xf1\x891081\xf1\x82\x0521T00503A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907567P \xf1\x890100\xf1\x82\x0101', + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.SKODA_SUPERB_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027BS\xf1\x892887', + b'\xf1\x8704E906027BT\xf1\x899042', + b'\xf1\x8704L906026ET\xf1\x891343', + b'\xf1\x8704L906026ET\xf1\x891990', + b'\xf1\x8704L906026FP\xf1\x891196', + b'\xf1\x8704L906026KA\xf1\x896014', + b'\xf1\x8704L906026KB\xf1\x894071', + b'\xf1\x8704L906026KD\xf1\x894798', + b'\xf1\x8704L906026MT\xf1\x893076', + b'\xf1\x8705L906022BK\xf1\x899971', + b'\xf1\x873G0906259 \xf1\x890004', + b'\xf1\x873G0906259B \xf1\x890002', + b'\xf1\x873G0906259L \xf1\x890003', + b'\xf1\x873G0906264A \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300042H \xf1\x891601', + b'\xf1\x870CW300043B \xf1\x891603', + b'\xf1\x870CW300049Q \xf1\x890906', + b'\xf1\x870D9300011T \xf1\x894801', + b'\xf1\x870D9300012 \xf1\x894940', + b'\xf1\x870D9300013A \xf1\x894905', + b'\xf1\x870D9300014K \xf1\x895006', + b'\xf1\x870D9300041H \xf1\x894905', + b'\xf1\x870D9300042M \xf1\x895013', + b'\xf1\x870D9300043F \xf1\x895202', + b'\xf1\x870GC300013K \xf1\x892403', + b'\xf1\x870GC300014M \xf1\x892801', + b'\xf1\x870GC300019G \xf1\x892803', + b'\xf1\x870GC300043 \xf1\x892301', + b'\xf1\x870GC300046D \xf1\x892402', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', + b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121118112231292221111', + b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', + b'\xf1\x875Q0959655AS\xf1\x890317\xf1\x82\x1331310031313100313131823133319331313100', + b'\xf1\x875Q0959655AT\xf1\x890317\xf1\x82\x1331310031313100313131013131319331313100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', + b'\xf1\x875Q0959655BK\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1333310031313100313152015351539331423100', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151013141319331423100', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151823143319331423100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152025350539331463100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152855372539331463100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ050303', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ060505', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ070505', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060700', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070700', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x873Q0907572B \xf1\x890192', + b'\xf1\x873Q0907572B \xf1\x890194', + b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x875Q0907572R \xf1\x890771', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, +} diff --git a/opendbc_repo/opendbc/car/volkswagen/interface.py b/opendbc_repo/opendbc/car/volkswagen/interface.py new file mode 100644 index 000000000000000..d11662722d6e607 --- /dev/null +++ b/opendbc_repo/opendbc/car/volkswagen/interface.py @@ -0,0 +1,86 @@ +from panda import Panda +from opendbc.car import get_safety_config, structs +from opendbc.car.interfaces import CarInterfaceBase +from opendbc.car.volkswagen.values import CAR, NetworkLocation, TransmissionType, VolkswagenFlags + + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret: structs.CarParams, candidate: CAR, fingerprint, car_fw, experimental_long, docs) -> structs.CarParams: + ret.carName = "volkswagen" + ret.radarUnavailable = True + + if ret.flags & VolkswagenFlags.PQ: + # Set global PQ35/PQ46/NMS parameters + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.volkswagenPq)] + ret.enableBsm = 0x3BA in fingerprint[0] # SWA_1 + + if 0x440 in fingerprint[0] or docs: # Getriebe_1 + ret.transmissionType = TransmissionType.automatic + else: + ret.transmissionType = TransmissionType.manual + + if any(msg in fingerprint[1] for msg in (0x1A0, 0xC2)): # Bremse_1, Lenkwinkel_1 + ret.networkLocation = NetworkLocation.gateway + else: + ret.networkLocation = NetworkLocation.fwdCamera + + # The PQ port is in dashcam-only mode due to a fixed six-minute maximum timer on HCA steering. An unsupported + # EPS flash update to work around this timer, and enable steering down to zero, is available from: + # https://github.com/pd0wm/pq-flasher + # It is documented in a four-part blog series: + # https://blog.willemmelching.nl/carhacking/2022/01/02/vw-part1/ + # Panda ALLOW_DEBUG firmware required. + ret.dashcamOnly = True + + else: + # Set global MQB parameters + ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.volkswagen)] + ret.enableBsm = 0x30F in fingerprint[0] # SWA_01 + + if 0xAD in fingerprint[0] or docs: # Getriebe_11 + ret.transmissionType = TransmissionType.automatic + elif 0x187 in fingerprint[0]: # Motor_EV_01 + ret.transmissionType = TransmissionType.direct + else: + ret.transmissionType = TransmissionType.manual + + if any(msg in fingerprint[1] for msg in (0x40, 0x86, 0xB2, 0xFD)): # Airbag_01, LWI_01, ESP_19, ESP_21 + ret.networkLocation = NetworkLocation.gateway + else: + ret.networkLocation = NetworkLocation.fwdCamera + + if 0x126 in fingerprint[2]: # HCA_01 + ret.flags |= VolkswagenFlags.STOCK_HCA_PRESENT.value + + # Global lateral tuning defaults, can be overridden per-vehicle + + ret.steerLimitTimer = 0.4 + if ret.flags & VolkswagenFlags.PQ: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + else: + ret.steerActuatorDelay = 0.1 + ret.lateralTuning.pid.kpBP = [0.] + ret.lateralTuning.pid.kiBP = [0.] + ret.lateralTuning.pid.kf = 0.00006 + ret.lateralTuning.pid.kpV = [0.6] + ret.lateralTuning.pid.kiV = [0.2] + + # Global longitudinal tuning defaults, can be overridden per-vehicle + + ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or docs + if experimental_long: + # Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required. + ret.openpilotLongitudinalControl = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL + if ret.transmissionType == TransmissionType.manual: + ret.minEnableSpeed = 4.5 + + ret.pcmCruise = not ret.openpilotLongitudinalControl + ret.stopAccel = -0.55 + ret.vEgoStarting = 0.1 + ret.vEgoStopping = 0.5 + ret.autoResumeSng = ret.minEnableSpeed == -1 + + return ret diff --git a/selfdrive/car/volkswagen/mqbcan.py b/opendbc_repo/opendbc/car/volkswagen/mqbcan.py similarity index 100% rename from selfdrive/car/volkswagen/mqbcan.py rename to opendbc_repo/opendbc/car/volkswagen/mqbcan.py diff --git a/selfdrive/car/volkswagen/pqcan.py b/opendbc_repo/opendbc/car/volkswagen/pqcan.py similarity index 100% rename from selfdrive/car/volkswagen/pqcan.py rename to opendbc_repo/opendbc/car/volkswagen/pqcan.py diff --git a/opendbc_repo/opendbc/car/volkswagen/radar_interface.py b/opendbc_repo/opendbc/car/volkswagen/radar_interface.py new file mode 100644 index 000000000000000..6e552bf618fda6f --- /dev/null +++ b/opendbc_repo/opendbc/car/volkswagen/radar_interface.py @@ -0,0 +1,4 @@ +from opendbc.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/opendbc_repo/opendbc/car/volkswagen/tests/__init__.py b/opendbc_repo/opendbc/car/volkswagen/tests/__init__.py new file mode 100644 index 000000000000000..e69de29bb2d1d64 diff --git a/selfdrive/car/volkswagen/tests/test_volkswagen.py b/opendbc_repo/opendbc/car/volkswagen/tests/test_volkswagen.py similarity index 92% rename from selfdrive/car/volkswagen/tests/test_volkswagen.py rename to opendbc_repo/opendbc/car/volkswagen/tests/test_volkswagen.py index 00025781057324f..cc046e572059b16 100644 --- a/selfdrive/car/volkswagen/tests/test_volkswagen.py +++ b/opendbc_repo/opendbc/car/volkswagen/tests/test_volkswagen.py @@ -1,11 +1,11 @@ import random import re -from cereal import car -from openpilot.selfdrive.car.volkswagen.values import CAR, FW_QUERY_CONFIG, WMI -from openpilot.selfdrive.car.volkswagen.fingerprints import FW_VERSIONS +from opendbc.car.structs import CarParams +from opendbc.car.volkswagen.values import CAR, FW_QUERY_CONFIG, WMI +from opendbc.car.volkswagen.fingerprints import FW_VERSIONS -Ecu = car.CarParams.Ecu +Ecu = CarParams.Ecu CHASSIS_CODE_PATTERN = re.compile('[A-Z0-9]{2}') # TODO: determine the unknown groups diff --git a/opendbc_repo/opendbc/car/volkswagen/values.py b/opendbc_repo/opendbc/car/volkswagen/values.py new file mode 100644 index 000000000000000..c095b7767f1e7e6 --- /dev/null +++ b/opendbc_repo/opendbc/car/volkswagen/values.py @@ -0,0 +1,522 @@ +from collections import defaultdict, namedtuple +from dataclasses import dataclass, field +from enum import Enum, IntFlag, StrEnum + +from panda import uds +from opendbc.can.can_define import CANDefine +from opendbc.car import dbc_dict, CarSpecs, DbcDict, PlatformConfig, Platforms +from opendbc.car.common.conversions import Conversions as CV +from opendbc.car import structs +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ + Device +from opendbc.car.fw_query_definitions import EcuAddrSubAddr, FwQueryConfig, Request, p16 + +Ecu = structs.CarParams.Ecu +NetworkLocation = structs.CarParams.NetworkLocation +TransmissionType = structs.CarParams.TransmissionType +GearShifter = structs.CarState.GearShifter +Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) + + +class CarControllerParams: + STEER_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz + ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz + + # Documented lateral limits: 3.00 Nm max, rate of change 5.00 Nm/sec. + # MQB vs PQ maximums are shared, but rate-of-change limited differently + # based on safety requirements driven by lateral accel testing. + + STEER_MAX = 300 # Max heading control assist torque 3.00 Nm + STEER_DRIVER_MULTIPLIER = 3 # weight driver torque heavily + STEER_DRIVER_FACTOR = 1 # from dbc + + STEER_TIME_MAX = 360 # Max time that EPS allows uninterrupted HCA steering control + STEER_TIME_ALERT = STEER_TIME_MAX - 10 # If mitigation fails, time to soft disengage before EPS timer expires + STEER_TIME_STUCK_TORQUE = 1.9 # EPS limits same torque to 6 seconds, reset timer 3x within that period + + DEFAULT_MIN_STEER_SPEED = 0.4 # m/s, newer EPS racks fault below this speed, don't show a low speed alert + + ACCEL_MAX = 2.0 # 2.0 m/s max acceleration + ACCEL_MIN = -3.5 # 3.5 m/s max deceleration + + def __init__(self, CP): + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + if CP.flags & VolkswagenFlags.PQ: + self.LDW_STEP = 5 # LDW_1 message frequency 20Hz + self.ACC_HUD_STEP = 4 # ACC_GRA_Anzeige frequency 25Hz + self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm + self.STEER_DELTA_UP = 6 # Max HCA reached in 1.00s (STEER_MAX / (50Hz * 1.00)) + self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) + + if CP.transmissionType == TransmissionType.automatic: + self.shifter_values = can_define.dv["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"] + self.hca_status_values = can_define.dv["Lenkhilfe_2"]["LH2_Sta_HCA"] + + self.BUTTONS = [ + Button(structs.CarState.ButtonEvent.Type.setCruise, "GRA_Neu", "GRA_Neu_Setzen", [1]), + Button(structs.CarState.ButtonEvent.Type.resumeCruise, "GRA_Neu", "GRA_Recall", [1]), + Button(structs.CarState.ButtonEvent.Type.accelCruise, "GRA_Neu", "GRA_Up_kurz", [1]), + Button(structs.CarState.ButtonEvent.Type.decelCruise, "GRA_Neu", "GRA_Down_kurz", [1]), + Button(structs.CarState.ButtonEvent.Type.cancel, "GRA_Neu", "GRA_Abbrechen", [1]), + Button(structs.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_Neu", "GRA_Zeitluecke", [1]), + ] + + self.LDW_MESSAGES = { + "none": 0, # Nothing to display + "laneAssistUnavail": 1, # "Lane Assist currently not available." + "laneAssistUnavailSysError": 2, # "Lane Assist system error" + "laneAssistUnavailNoSensorView": 3, # "Lane Assist not available. No sensor view." + "laneAssistTakeOver": 4, # "Lane Assist: Please Take Over Steering" + "laneAssistDeactivTrailer": 5, # "Lane Assist: no function with trailer" + } + + else: + self.LDW_STEP = 10 # LDW_02 message frequency 10Hz + self.ACC_HUD_STEP = 6 # ACC_02 message frequency 16Hz + self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm + self.STEER_DELTA_UP = 4 # Max HCA reached in 1.50s (STEER_MAX / (50Hz * 1.50)) + self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) + + if CP.transmissionType == TransmissionType.automatic: + self.shifter_values = can_define.dv["Getriebe_11"]["GE_Fahrstufe"] + elif CP.transmissionType == TransmissionType.direct: + self.shifter_values = can_define.dv["Motor_EV_01"]["MO_Waehlpos"] + self.hca_status_values = can_define.dv["LH_EPS_03"]["EPS_HCA_Status"] + + self.BUTTONS = [ + Button(structs.CarState.ButtonEvent.Type.setCruise, "GRA_ACC_01", "GRA_Tip_Setzen", [1]), + Button(structs.CarState.ButtonEvent.Type.resumeCruise, "GRA_ACC_01", "GRA_Tip_Wiederaufnahme", [1]), + Button(structs.CarState.ButtonEvent.Type.accelCruise, "GRA_ACC_01", "GRA_Tip_Hoch", [1]), + Button(structs.CarState.ButtonEvent.Type.decelCruise, "GRA_ACC_01", "GRA_Tip_Runter", [1]), + Button(structs.CarState.ButtonEvent.Type.cancel, "GRA_ACC_01", "GRA_Abbrechen", [1]), + Button(structs.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_ACC_01", "GRA_Verstellung_Zeitluecke", [1]), + ] + + self.LDW_MESSAGES = { + "none": 0, # Nothing to display + "laneAssistUnavailChime": 1, # "Lane Assist currently not available." with chime + "laneAssistUnavailNoSensorChime": 3, # "Lane Assist not available. No sensor view." with chime + "laneAssistTakeOverUrgent": 4, # "Lane Assist: Please Take Over Steering" with urgent beep + "emergencyAssistUrgent": 6, # "Emergency Assist: Please Take Over Steering" with urgent beep + "laneAssistTakeOverChime": 7, # "Lane Assist: Please Take Over Steering" with chime + "laneAssistTakeOver": 8, # "Lane Assist: Please Take Over Steering" silent + "emergencyAssistChangingLanes": 9, # "Emergency Assist: Changing lanes..." with urgent beep + "laneAssistDeactivated": 10, # "Lane Assist deactivated." silent with persistent icon afterward + } + + +class CANBUS: + pt = 0 + cam = 2 + + +class WMI(StrEnum): + VOLKSWAGEN_USA_SUV = "1V2" + VOLKSWAGEN_USA_CAR = "1VW" + VOLKSWAGEN_MEXICO_SUV = "3VV" + VOLKSWAGEN_MEXICO_CAR = "3VW" + VOLKSWAGEN_ARGENTINA = "8AW" + VOLKSWAGEN_BRASIL = "9BW" + SAIC_VOLKSWAGEN = "LSV" + SKODA = "TMB" + SEAT = "VSS" + AUDI_EUROPE_MPV = "WA1" + AUDI_GERMANY_CAR = "WAU" + MAN = "WMA" + AUDI_SPORT = "WUA" + VOLKSWAGEN_COMMERCIAL = "WV1" + VOLKSWAGEN_COMMERCIAL_BUS_VAN = "WV2" + VOLKSWAGEN_EUROPE_SUV = "WVG" + VOLKSWAGEN_EUROPE_CAR = "WVW" + VOLKSWAGEN_GROUP_RUS = "XW8" + + +class VolkswagenFlags(IntFlag): + # Detected flags + STOCK_HCA_PRESENT = 1 + + # Static flags + PQ = 2 + + +@dataclass +class VolkswagenMQBPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_mqb_2010', None)) + # Volkswagen uses the VIN WMI and chassis code to match in the absence of the comma power + # on camera-integrated cars, as we lose too many ECUs to reliably identify the vehicle + chassis_codes: set[str] = field(default_factory=set) + wmis: set[WMI] = field(default_factory=set) + + +@dataclass +class VolkswagenPQPlatformConfig(VolkswagenMQBPlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_golf_mk4', None)) + + def init(self): + self.flags |= VolkswagenFlags.PQ + + +@dataclass(frozen=True, kw_only=True) +class VolkswagenCarSpecs(CarSpecs): + centerToFrontRatio: float = 0.45 + steerRatio: float = 15.6 + minSteerSpeed: float = CarControllerParams.DEFAULT_MIN_STEER_SPEED + + +class Footnote(Enum): + KAMIQ = CarFootnote( + "Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.", + Column.MODEL) + PASSAT = CarFootnote( + "Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.", + Column.MODEL) + SKODA_HEATED_WINDSHIELD = CarFootnote( + "Some Škoda vehicles are equipped with heated windshields, which are known " + + "to block GPS signal needed for some comma 3X functionality.", + Column.MODEL) + VW_EXP_LONG = CarFootnote( + "Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness " + + "are limited to using stock ACC.", + Column.LONGITUDINAL) + VW_MQB_A0 = CarFootnote( + "Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot " + + "in software, but doesn't yet have a harness available from the comma store.", + Column.HARDWARE) + + +@dataclass +class VWCarDocs(CarDocs): + package: str = "Adaptive Cruise Control (ACC) & Lane Assist" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.vw_j533])) + + def init_make(self, CP: structs.CarParams): + self.footnotes.append(Footnote.VW_EXP_LONG) + if "SKODA" in CP.carFingerprint: + self.footnotes.append(Footnote.SKODA_HEATED_WINDSHIELD) + + if CP.carFingerprint in (CAR.VOLKSWAGEN_CRAFTER_MK2, CAR.VOLKSWAGEN_TRANSPORTER_T61): + self.car_parts = CarParts([Device.threex_angled_mount, CarHarness.vw_j533]) + + if abs(CP.minSteerSpeed - CarControllerParams.DEFAULT_MIN_STEER_SPEED) < 1e-3: + self.min_steer_speed = 0 + + +# Check the 7th and 8th characters of the VIN before adding a new CAR. If the +# chassis code is already listed below, don't add a new CAR, just add to the +# FW_VERSIONS for that existing CAR. + +class CAR(Platforms): + config: VolkswagenMQBPlatformConfig | VolkswagenPQPlatformConfig + + VOLKSWAGEN_ARTEON_MK1 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Arteon 2018-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon R 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon eHybrid 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon Shooting Brake 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen CC 2018-22", video_link="https://youtu.be/FAomFKPFlDA"), + ], + VolkswagenCarSpecs(mass=1733, wheelbase=2.84), + chassis_codes={"AN", "3H"}, + wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_ATLAS_MK1 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Atlas 2018-23"), + VWCarDocs("Volkswagen Atlas Cross Sport 2020-22"), + VWCarDocs("Volkswagen Teramont 2018-22"), + VWCarDocs("Volkswagen Teramont Cross Sport 2021-22"), + VWCarDocs("Volkswagen Teramont X 2021-22"), + ], + VolkswagenCarSpecs(mass=2011, wheelbase=2.98), + chassis_codes={"CA"}, + wmis={WMI.VOLKSWAGEN_USA_SUV, WMI.VOLKSWAGEN_EUROPE_SUV}, + ) + VOLKSWAGEN_CADDY_MK3 = VolkswagenPQPlatformConfig( + [ + VWCarDocs("Volkswagen Caddy 2019"), + VWCarDocs("Volkswagen Caddy Maxi 2019"), + ], + VolkswagenCarSpecs(mass=1613, wheelbase=2.6, minSteerSpeed=21 * CV.KPH_TO_MS), + chassis_codes={"2K"}, + wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, + ) + VOLKSWAGEN_CRAFTER_MK2 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Crafter 2017-24", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("Volkswagen e-Crafter 2018-24", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("Volkswagen Grand California 2019-24", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("MAN TGE 2017-24", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("MAN eTGE 2020-24", video_link="https://youtu.be/4100gLeabmo"), + ], + VolkswagenCarSpecs(mass=2100, wheelbase=3.64, minSteerSpeed=50 * CV.KPH_TO_MS), + chassis_codes={"SY", "SZ", "UY", "UZ"}, + wmis={WMI.VOLKSWAGEN_COMMERCIAL, WMI.MAN}, + ) + VOLKSWAGEN_GOLF_MK7 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen e-Golf 2014-20"), + VWCarDocs("Volkswagen Golf 2015-20", auto_resume=False), + VWCarDocs("Volkswagen Golf Alltrack 2015-19", auto_resume=False), + VWCarDocs("Volkswagen Golf GTD 2015-20"), + VWCarDocs("Volkswagen Golf GTE 2015-20"), + VWCarDocs("Volkswagen Golf GTI 2015-21", auto_resume=False), + VWCarDocs("Volkswagen Golf R 2015-19"), + VWCarDocs("Volkswagen Golf SportsVan 2015-20"), + ], + VolkswagenCarSpecs(mass=1397, wheelbase=2.62), + chassis_codes={"5G", "AU", "BA", "BE"}, + wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_JETTA_MK6 = VolkswagenPQPlatformConfig( + [VWCarDocs("Volkswagen Jetta 2015-18")], + VolkswagenCarSpecs(mass=1518, wheelbase=2.65, minSteerSpeed=50 * CV.KPH_TO_MS, minEnableSpeed=20 * CV.KPH_TO_MS), + chassis_codes={"5K", "AJ"}, + wmis={WMI.VOLKSWAGEN_MEXICO_CAR}, + ) + VOLKSWAGEN_JETTA_MK7 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Jetta 2018-23"), + VWCarDocs("Volkswagen Jetta GLI 2021-23"), + ], + VolkswagenCarSpecs(mass=1328, wheelbase=2.71), + chassis_codes={"BU"}, + wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_PASSAT_MK8 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Passat 2015-22", footnotes=[Footnote.PASSAT]), + VWCarDocs("Volkswagen Passat Alltrack 2015-22"), + VWCarDocs("Volkswagen Passat GTE 2015-22"), + ], + VolkswagenCarSpecs(mass=1551, wheelbase=2.79), + chassis_codes={"3C", "3G"}, + wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_PASSAT_NMS = VolkswagenPQPlatformConfig( + [VWCarDocs("Volkswagen Passat NMS 2017-22")], + VolkswagenCarSpecs(mass=1503, wheelbase=2.80, minSteerSpeed=50 * CV.KPH_TO_MS, minEnableSpeed=20 * CV.KPH_TO_MS), + chassis_codes={"A3"}, + wmis={WMI.VOLKSWAGEN_USA_CAR}, + ) + VOLKSWAGEN_POLO_MK6 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Polo 2018-23", footnotes=[Footnote.VW_MQB_A0]), + VWCarDocs("Volkswagen Polo GTI 2018-23", footnotes=[Footnote.VW_MQB_A0]), + ], + VolkswagenCarSpecs(mass=1230, wheelbase=2.55), + chassis_codes={"AW"}, + wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_SHARAN_MK2 = VolkswagenPQPlatformConfig( + [ + VWCarDocs("Volkswagen Sharan 2018-22"), + VWCarDocs("SEAT Alhambra 2018-20"), + ], + VolkswagenCarSpecs(mass=1639, wheelbase=2.92, minSteerSpeed=50 * CV.KPH_TO_MS), + chassis_codes={"7N"}, + wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_TAOS_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Volkswagen Taos 2022-23")], + VolkswagenCarSpecs(mass=1498, wheelbase=2.69), + chassis_codes={"B2"}, + wmis={WMI.VOLKSWAGEN_MEXICO_SUV, WMI.VOLKSWAGEN_ARGENTINA}, + ) + VOLKSWAGEN_TCROSS_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_MQB_A0])], + VolkswagenCarSpecs(mass=1150, wheelbase=2.60), + chassis_codes={"C1"}, + wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, + ) + VOLKSWAGEN_TIGUAN_MK2 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Tiguan 2018-24"), + VWCarDocs("Volkswagen Tiguan eHybrid 2021-23"), + ], + VolkswagenCarSpecs(mass=1715, wheelbase=2.74), + chassis_codes={"5N", "AD", "AX", "BW"}, + wmis={WMI.VOLKSWAGEN_EUROPE_SUV, WMI.VOLKSWAGEN_MEXICO_SUV}, + ) + VOLKSWAGEN_TOURAN_MK2 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Volkswagen Touran 2016-23")], + VolkswagenCarSpecs(mass=1516, wheelbase=2.79), + chassis_codes={"1T"}, + wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, + ) + VOLKSWAGEN_TRANSPORTER_T61 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Caravelle 2020"), + VWCarDocs("Volkswagen California 2021-23"), + ], + VolkswagenCarSpecs(mass=1926, wheelbase=3.00, minSteerSpeed=14.0), + chassis_codes={"7H", "7L"}, + wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, + ) + VOLKSWAGEN_TROC_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Volkswagen T-Roc 2018-23")], + VolkswagenCarSpecs(mass=1413, wheelbase=2.63), + chassis_codes={"A1"}, + wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, + ) + AUDI_A3_MK3 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Audi A3 2014-19"), + VWCarDocs("Audi A3 Sportback e-tron 2017-18"), + VWCarDocs("Audi RS3 2018"), + VWCarDocs("Audi S3 2015-17"), + ], + VolkswagenCarSpecs(mass=1335, wheelbase=2.61), + chassis_codes={"8V", "FF"}, + wmis={WMI.AUDI_GERMANY_CAR, WMI.AUDI_SPORT}, + ) + AUDI_Q2_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Audi Q2 2018")], + VolkswagenCarSpecs(mass=1205, wheelbase=2.61), + chassis_codes={"GA"}, + wmis={WMI.AUDI_GERMANY_CAR}, + ) + AUDI_Q3_MK2 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Audi Q3 2019-23")], + VolkswagenCarSpecs(mass=1623, wheelbase=2.68), + chassis_codes={"8U", "F3", "FS"}, + wmis={WMI.AUDI_EUROPE_MPV, WMI.AUDI_GERMANY_CAR}, + ) + SEAT_ATECA_MK1 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("CUPRA Ateca 2018-23"), + VWCarDocs("SEAT Ateca 2016-23"), + VWCarDocs("SEAT Leon 2014-20"), + ], + VolkswagenCarSpecs(mass=1300, wheelbase=2.64), + chassis_codes={"5F"}, + wmis={WMI.SEAT}, + ) + SKODA_FABIA_MK4 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Škoda Fabia 2022-23", footnotes=[Footnote.VW_MQB_A0])], + VolkswagenCarSpecs(mass=1266, wheelbase=2.56), + chassis_codes={"PJ"}, + wmis={WMI.SKODA}, + ) + SKODA_KAMIQ_MK1 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Škoda Kamiq 2021-23", footnotes=[Footnote.VW_MQB_A0, Footnote.KAMIQ]), + VWCarDocs("Škoda Scala 2020-23", footnotes=[Footnote.VW_MQB_A0]), + ], + VolkswagenCarSpecs(mass=1230, wheelbase=2.66), + chassis_codes={"NW"}, + wmis={WMI.SKODA}, + ) + SKODA_KAROQ_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Škoda Karoq 2019-23")], + VolkswagenCarSpecs(mass=1278, wheelbase=2.66), + chassis_codes={"NU"}, + wmis={WMI.SKODA}, + ) + SKODA_KODIAQ_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Škoda Kodiaq 2017-23")], + VolkswagenCarSpecs(mass=1569, wheelbase=2.79), + chassis_codes={"NS"}, + wmis={WMI.SKODA, WMI.VOLKSWAGEN_GROUP_RUS}, + ) + SKODA_OCTAVIA_MK3 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Škoda Octavia 2015-19"), + VWCarDocs("Škoda Octavia RS 2016"), + VWCarDocs("Škoda Octavia Scout 2017-19"), + ], + VolkswagenCarSpecs(mass=1388, wheelbase=2.68), + chassis_codes={"NE"}, + wmis={WMI.SKODA}, + ) + SKODA_SUPERB_MK3 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Škoda Superb 2015-22")], + VolkswagenCarSpecs(mass=1505, wheelbase=2.84), + chassis_codes={"3V", "NP"}, + wmis={WMI.SKODA}, + ) + + +def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: + candidates = set() + + # Compile all FW versions for each ECU + all_ecu_versions: dict[EcuAddrSubAddr, set[str]] = defaultdict(set) + for ecus in offline_fw_versions.values(): + for ecu, versions in ecus.items(): + all_ecu_versions[ecu] |= set(versions) + + # Check the WMI and chassis code to determine the platform + wmi = vin[:3] + chassis_code = vin[6:8] + + for platform in CAR: + valid_ecus = set() + for ecu in offline_fw_versions[platform]: + addr = ecu[1:] + if ecu[0] not in CHECK_FUZZY_ECUS: + continue + + # Sanity check that live FW is in the superset of all FW, Volkswagen ECU part numbers are commonly shared + found_versions = live_fw_versions.get(addr, []) + expected_versions = all_ecu_versions[ecu] + if not any(found_version in expected_versions for found_version in found_versions): + break + + valid_ecus.add(ecu[0]) + + if valid_ecus != CHECK_FUZZY_ECUS: + continue + + if wmi in platform.config.wmis and chassis_code in platform.config.chassis_codes: + candidates.add(platform) + + return {str(c) for c in candidates} + + +# These ECUs are required to match to gain a VIN match +# TODO: do we want to check camera when we add its FW? +CHECK_FUZZY_ECUS = {Ecu.fwdRadar} + +# All supported cars should return FW from the engine, srs, eps, and fwdRadar. Cars +# with a manual trans won't return transmission firmware, but all other cars will. +# +# The 0xF187 SW part number query should return in the form of N[NX][NX] NNN NNN [X[X]], +# where N=number, X=letter, and the trailing two letters are optional. Performance +# tuners sometimes tamper with that field (e.g. 8V0 9C0 BB0 1 from COBB/EQT). Tampered +# ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have +# them repaired by the tuner before including them in openpilot. + +VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) +VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + +VOLKSWAGEN_RX_OFFSET = 0x6a + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[request for bus, obd_multiplexing in [(1, True), (1, False), (0, False)] for request in [ + Request( + [VOLKSWAGEN_VERSION_REQUEST_MULTI], + [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar, Ecu.fwdCamera], + rx_offset=VOLKSWAGEN_RX_OFFSET, + bus=bus, + obd_multiplexing=obd_multiplexing, + ), + Request( + [VOLKSWAGEN_VERSION_REQUEST_MULTI], + [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], + bus=bus, + obd_multiplexing=obd_multiplexing, + ), + ]], + non_essential_ecus={Ecu.eps: list(CAR)}, + extra_ecus=[(Ecu.fwdCamera, 0x74f, None)], + match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, +) + +DBC = CAR.create_dbc_map() diff --git a/opendbc_repo/opendbc/dbc/ESR.dbc b/opendbc_repo/opendbc/dbc/ESR.dbc new file mode 100644 index 000000000000000..e3837a68b2ff5a2 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/ESR.dbc @@ -0,0 +1,1080 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: Gateway ESR +VAL_TABLE_ ForwardReverse 1 "Reverse" 0 "Forward" ; +VAL_TABLE_ LeftRight 1 "Right Clockwise" 0 "Left CounterClockwise" ; +VAL_TABLE_ ValidInvalid 1 "Valid" 0 "Invalid" ; +VAL_TABLE_ TrueFalse 1 "True" 0 "False" ; + + +BO_ 1343 Target64: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1342 Target63: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1341 Target62: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1340 Target61: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1339 Target60: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1338 Target59: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1337 Target58: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1336 Target57: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1335 Target56: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1334 Target55: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1333 Target54: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1332 Target53: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1331 Target52: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1330 Target51: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1329 Target50: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1328 Target49: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1327 Target48: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1326 Target47: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1325 Target46: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1324 Target45: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1323 Target44: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1322 Target43: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1321 Target42: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1320 Target41: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1319 Target40: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1318 Target39: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1317 Target38: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1316 Target37: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1315 Target36: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1314 Target35: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1313 Target34: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1312 Target33: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1311 Target32: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1310 Target31: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1309 Target30: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1308 Target29: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1307 Target28: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1306 Target27: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1305 Target26: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1304 Target25: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1303 Target24: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1302 Target23: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1301 Target22: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1300 Target21: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1299 Target20: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1298 Target19: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1297 Target18: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1296 Target17: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1295 Target16: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1294 Target15: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1293 Target14: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1292 Target13: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1291 Target12: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1290 Target11: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1289 Target10: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1288 Target9: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1287 Target8: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1285 Target6: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1286 Target7: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1284 Target5: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1283 Target4: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1282 Target3: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1281 Target2: 8 Vector__XXX + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1524 VehicleData3: 8 Gateway + SG_ CAN_RX_YAW_RATE_BIAS_SHIFT : 15|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_WHEELBASE : 55|8@0+ (2,200) [200|710] "cm" Vector__XXX + SG_ CAN_RX_STEERING_GEAR_RATIO : 63|8@0+ (0.125,0) [0|31.875] "" Vector__XXX + SG_ CAN_RX_OVERSTEER_UNDERSTEER : 7|8@0- (1,0) [-128|127] "%" Vector__XXX + SG_ CAN_RX_FUNNEL_OFFSET_RIGHT : 31|8@0- (0.1,0) [-12.8|12.7] "m" Vector__XXX + SG_ CAN_RX_FUNNEL_OFFSET_LEFT : 23|8@0- (0.1,0) [-12.8|12.7] "m" Vector__XXX + SG_ CAN_RX_DISTANCE_REAR_AXLE : 47|8@0+ (2,200) [200|710] "cm" Vector__XXX + SG_ CAN_RX_CW_BLOCKAGE_TRESHOLD : 39|8@0+ (0.0078125,0) [0|1.9921875] "" Vector__XXX + SG_ CAN_RX_BEAMWIDTH_VERT : 14|7@0+ (0.0625,0) [0|7.9375] "deg" Vector__XXX + +BO_ 1523 FactoryAlignment: 8 Gateway + +BO_ 1522 Vehicle_Data2: 8 Gateway + SG_ CAN_RX_WHEEL_SLIP : 41|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_RX_SERV_ALIGN_UPDATES_NEED : 55|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_RX_SERV_ALIGN_TYPE : 47|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_RADAR_HEIGHT : 38|7@0+ (1,0) [0|127] "cm" Vector__XXX + SG_ CAN_RX_RADAR_FOV_MR : 30|7@0+ (1,0) [0|127] "deg" Vector__XXX + SG_ CAN_RX_RADAR_FOV_LR : 19|5@0+ (1,0) [0|31] "deg" Vector__XXX + SG_ CAN_RX_LONG_ACCEL_VALIDITY : 7|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_LONG_ACCEL : 12|9@0- (0.03125,0) [-8|7.96875] "m/s^2" Vector__XXX + SG_ CAN_RX_LAT_ACCEL_VALIDITY : 6|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_LAT_ACCEL : 5|9@0- (0.03125,0) [-8|7.96875] "m/s^2" Vector__XXX + SG_ CAN_RX_AUTO_ALIGN_DISABLE : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_AUTO_ALIGN_CONVERGED : 42|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_ANGLE_MOUNTING_OFFSET : 63|8@0- (0.0625,0) [-8|7.9375] "deg" Vector__XXX + SG_ CAN_RX_AALIGN_AVG_CTR_TOTAL : 45|3@0+ (250,250) [250|2000] "" Vector__XXX + +BO_ 1512 CIPV_Targets_Etc: 8 ESR + +BO_ 1511 ESR_History_Fault: 8 ESR + +BO_ 1510 ESR_Active_Fault: 8 ESR + +BO_ 1508 AD_Data: 8 ESR + +BO_ 1489 SensorValidation2: 8 ESR + SG_ CAN_TX_VALID_MR_SN : 7|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_VALID_MR_RANGE_RATE : 31|16@0- (0.0078125,0) [-256|255.9921875] "m/s" Vector__XXX + SG_ CAN_TX_VALID_MR_RANGE : 15|16@0+ (0.0078125,0) [0|511.9921875] "m" Vector__XXX + SG_ CAN_TX_VALID_MR_POWER : 63|8@0- (1,0) [-128|127] "db" Vector__XXX + SG_ CAN_TX_VALID_MR_ANGLE : 40|16@1- (0.0625,0) [-2048|2047.9375] "deg" Vector__XXX + +BO_ 1488 SensorValidation: 8 ESR + SG_ CAN_TX_VALID_LR_SN : 7|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_VALID_LR_RANGE_RATE : 31|16@0- (0.0078125,0) [-256|255.9921875] "m/s" Vector__XXX + SG_ CAN_TX_VALID_LR_RANGE : 15|16@0+ (0.0078125,0) [0|511.9921875] "m" Vector__XXX + SG_ CAN_TX_VALID_LR_POWER : 63|8@0- (1,0) [-128|127] "db" Vector__XXX + SG_ CAN_TX_VALID_LR_ANGLE : 47|16@0- (0.0625,0) [-2048|2047.9375] "deg" Vector__XXX + +BO_ 1344 Track_Sensor: 1 ESR + SG_ CAN_TX_TRACK_ROLLING_COUNT_2 : 4|1@0+ (1,0) [0|1] "" Vector__XXX + +BO_ 1280 Target1: 8 ESR + SG_ CAN_TX_TRACK_WIDTH : 37|4@0+ (0.5,0) [0|7.5] "" Vector__XXX + SG_ CAN_TX_TRACK_STATUS : 15|3@0+ (1,0) [0|7] "" Vector__XXX + SG_ CAN_TX_TRACK_ROLLING_COUNT : 38|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_RATE : 53|14@0- (0.01,0) [-81.92|81.91] "m/s" Vector__XXX + SG_ CAN_TX_TRACK_RANGE_ACCEL : 33|10@0- (0.05,0) [-25.6|25.55] "m/s^2" Vector__XXX + SG_ CAN_TX_TRACK_RANGE : 18|11@0+ (0.1,0) [0|204.7] "m" Vector__XXX + SG_ CAN_TX_TRACK_ONCOMING : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_MED_RANGE_MODE : 55|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_TRACK_LAT_RATE : 7|6@0- (0.25,0) [-8|7.75] "" Vector__XXX + SG_ CAN_TX_TRACK_GROUPING_CHANGED : 1|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_BRIDGE_OBJECT : 39|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_TRACK_ANGLE : 12|10@0- (0.1,0) [-51.2|51.1] "" Vector__XXX + +BO_ 1265 SensorInput: 8 Gateway + SG_ CAN_RX_USE_ANGLE_MISALIGNMENT : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CAN_RX_SCAN_INDEX_ACK : 7|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_RX_LATERAL_MOUNTING_OFFSET : 47|8@0- (0.01563,0) [-2.00064|1.98501] "m" Vector__XXX + SG_ CAN_RX_WIPER_STATUS : 57|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_VOLVO_SHORT_TRACK_ROC : 31|4@0- (500,0) [-4000|3500] "m" Vector__XXX + SG_ CAN_RX_VEHICLE_SPEED_VALIDITY : 61|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_TURN_SIGNAL_STATUS : 63|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_RX_RAW_DATA_ENABLE : 56|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_RADAR_CMD_RADIATE : 55|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_MR_ONLY_TRANSMIT : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CAN_RX_MMR_UPSIDE_DOWN : 60|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_MAXIMUM_TRACKS : 53|6@0+ (1,0) [0|63] "" Vector__XXX + SG_ CAN_RX_LR_ONLY_TRANSMIT : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CAN_RX_HIGH_YAW_ANGLE : 21|6@0- (1,0) [-32|31] "deg" Vector__XXX + SG_ CAN_RX_GROUPING_MODE : 59|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_RX_CLEAR_FAULTS : 22|1@0- (1,0) [0|0] "" Vector__XXX + SG_ CAN_RX_BLOCKAGE_DISABLE : 54|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_ANGLE_MISALIGNMENT : 39|8@0- (0.0625,0) [-8|7.9375] "deg" Vector__XXX + +BO_ 1264 Vehicle_Data: 8 Gateway + SG_ CAN_RX_YAW_RATE_VALIDITY : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CAN_RX_YAW_RATE : 11|12@0- (0.0625,0) [-128|127.9375] "deg/s" Vector__XXX + SG_ CAN_RX_VEHICLE_SPEED_DIRECTION : 12|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_VEHICLE_SPEED : 7|11@0+ (0.0625,0) [0|127.9375] "m/s" Vector__XXX + SG_ CAN_RX_RADIUS_CURVATURE : 29|14@0- (1,0) [-8192|8191] "m" Vector__XXX + SG_ CAN_RX_STEERING_VALIDITY : 47|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_STEERING_ANGLE_SIGN : 46|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_STEERING_ANGLE_RATE_SIGN : 30|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_RX_STEERING_ANGLE_RATE : 50|11@0+ (1,0) [0|2047] "deg/s" Vector__XXX + SG_ CAN_RX_STEERING_ANGLE : 45|11@0+ (1,0) [0|2047] "deg" Vector__XXX + +BO_ 1251 ESR_Output_InPath: 8 ESR + SG_ CAN_TX_PATH_ID_ACC_MOVE : 15|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_TRUCK_TARGET_DET : 7|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_SIDELOBE_BLOCKATE : 5|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_ROLLING_COUNT_3 : 1|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_PATH_ID_FCW_STAT : 47|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_PATH_ID_FCW_MOVE : 39|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_PATH_ID_CMBB_STAT : 31|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_PATH_ID_CMBB_MOVE : 23|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_PATH_ID_ACC_STAT : 63|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_PARTIAL_BLOCKAGE : 4|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_LR_ONLY_GRATING_LOBE_DET : 6|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_LMR_LR_MODE : 3|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_AUTO_ALIGN_ANGLE : 55|8@0- (0.0625,0) [-8|7.9375] "" Vector__XXX + +BO_ 1250 ESR_SW: 8 ESR + SG_ CAN_TX_SW_VERSION_PLD : 63|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_TX_SW_VERSION_HOST : 15|24@0+ (1,0) [0|16777215] "" Vector__XXX + SG_ CAN_TX_SERIAL_NUM : 39|24@0+ (1,0) [0|16777215] "" Vector__XXX + SG_ CAN_TX_INTERFACE_VERSION : 7|4@0+ (1,0) [0|15] "" Vector__XXX + SG_ CAN_TX_HW_VERSION : 3|4@0+ (1,0) [0|15] "" Vector__XXX + +BO_ 1249 ESR_Status2: 8 ESR + SG_ CAN_TX_YAW_RATE_BIAS : 47|8@0- (0.125,0) [-16|15.875] "" Vector__XXX + SG_ CAN_TX_XCVR_OPERATIONAL : 12|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_VEH_SPD_COMP_FACTOR : 39|6@0- (0.00195,1) [0.9376|1.06045] "" Vector__XXX + SG_ CAN_TX_TEMPERATURE : 31|8@0- (1,0) [-128|127] "degC" Vector__XXX + SG_ CAN_TX_SW_VERSION_DSP : 55|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_TX_STEERING_ANGLE_ACK : 10|11@0+ (1,0) [0|2047] "deg" Vector__XXX + SG_ CAN_TX_ROLLING_COUNT_2 : 1|2@0+ (1,0) [0|3] "" Vector__XXX + SG_ CAN_TX_RAW_DATA_MODE : 11|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_RANGE_PERF_ERROR : 14|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_OVERHEAT_ERROR : 15|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_MAXIMUM_TRACKS_ACK : 7|6@0+ (1,1) [1|64] "" Vector__XXX + SG_ CAN_TX_INTERNAL_ERROR : 13|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_TX_GROUPING_MODE : 33|2@0+ (1,0) [0|3] "" Vector__XXX + +BO_ 1248 ESR_Status: 8 ESR + SG_ CAN_TX_COMM_ERROR : 14|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CAN_TX_RADIUS_CURVATURE_CALC : 13|14@0- (1,0) [-8192|8191] "" Vector__XXX + SG_ CAN_TX_YAW_RATE_CALC : 47|12@0- (0.0625,0) [-128|127.9375] "deg/s" Vector__XXX + SG_ CAN_TX_VEHICLE_SPEED_CALC : 50|11@0+ (0.0625,0) [0|127.9375] "m/s" Vector__XXX + SG_ CAN_TX_DSP_TIMESTAMP : 5|7@0+ (2,0) [0|254] "ms" Vector__XXX + SG_ CAN_TX_SCAN_INDEX : 31|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_TX_ROLLING_COUNT_1 : 6|2@1+ (1,0) [0|3] "" Vector__XXX + + + +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "BusType" "CAN"; +VAL_ 1264 CAN_RX_YAW_RATE_VALIDITY 1 "Valid" 0 "Invalid" ; +VAL_ 1264 CAN_RX_VEHICLE_SPEED_DIRECTION 1 "Reverse" 0 "Forward" ; +VAL_ 1264 CAN_RX_STEERING_VALIDITY 1 "True" 0 "False" ; +VAL_ 1264 CAN_RX_STEERING_ANGLE_SIGN 1 "Right Clockwise" 0 "Left CounterClockwise" ; +VAL_ 1264 CAN_RX_STEERING_ANGLE_RATE_SIGN 1 "Right Clockwise" 0 "Left CounterClockwise" ; + diff --git a/opendbc/FORD_CADS.dbc b/opendbc_repo/opendbc/dbc/FORD_CADS.dbc similarity index 99% rename from opendbc/FORD_CADS.dbc rename to opendbc_repo/opendbc/dbc/FORD_CADS.dbc index aab4b8d282f8439..569739c9c59a78a 100644 --- a/opendbc/FORD_CADS.dbc +++ b/opendbc_repo/opendbc/dbc/FORD_CADS.dbc @@ -3464,7 +3464,7 @@ VAL_ 33 Active_Flt_Latched_byte0_bit3 1 "Fault Present" 0 "No Fault"; VAL_ 33 KeepAliveChecksumFault 1 "Fault Present" 0 "No Fault"; VAL_ 33 ProgramCalibrationFlashChecksum 1 "Fault Present" 0 "No Fault"; VAL_ 33 ApplicationFlashChecksumFault 1 "Fault Present" 0 "No Fault"; -VAL_ 371 CAN_AUTO_ALIGN_HANGLE_QF 3 "Accurate" 2 "Innacurate" 1 "Temporarily undefined" 0 "Undefined"; +VAL_ 371 CAN_AUTO_ALIGN_HANGLE_QF 3 "Accurate" 2 "Inaccurate" 1 "Temporarily undefined" 0 "Undefined"; VAL_ 371 CAN_ALIGNMENT_STATUS 15 "Undefined_2" 14 "Undefined_1" 13 "Low Amplitude (Flat-plate only)" 12 "No Peak (Flat-plate only)" 11 "Fail Ver and Hor OutOfRange" 10 "Fail Vertical Align OutOfRange" 9 "Fail Horizontal Align OutOfRange" 8 "Fail Time Out" 7 "Fail Only Right Target Found" 6 "Fail Only Left Target Found" 5 "Fail Variance Too Large" 4 "Fail Deviation Too Large" 3 "Fail No Target" 2 "Success" 1 "Busy" 0 "Off"; VAL_ 371 CAN_ALIGNMENT_STATE 6 "Static alignment flat-plate" 5 "Static alignment 2-target" 4 "Static alignment 1-target" 3 "Service alignment" 2 "Short track alignment" 1 "Auto alignment" 0 "Off"; VAL_ 291 CAN_DET_CONFID_AZIMUTH_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; diff --git a/opendbc_repo/opendbc/dbc/FORD_CADS_64.dbc b/opendbc_repo/opendbc/dbc/FORD_CADS_64.dbc new file mode 100644 index 000000000000000..2ae927a6f2ecd95 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/FORD_CADS_64.dbc @@ -0,0 +1,7289 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: +BU_: MRR +BO_ 1073741824 VECTOR__INDEPENDENT_SIG_MSG: 0 Vector__XXX + SG_ New_Signal_943 : 0|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ CAN_SENSOR_VANGLE_OFFSET : 0|8@0+ (0.0625,-8) [-8|7.9375] "deg" Vector__XXX + SG_ CAN_SENSOR_FOV_VER : 0|8@0+ (1,0) [0|255] "deg" Vector__XXX + SG_ CAN_AUTO_ALIGN_VANGLE_QF : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_AUTO_ALIGN_VANGLE_REF : 0|10@0+ (0.03125,-10) [-10|21.9688] "deg" Vector__XXX + SG_ CAN_AUTO_ALIGN_VANGLE : 0|10@0+ (0.03125,-10) [-10|21.9688] "deg" Vector__XXX + SG_ CAN_MMIC_Temp4 : 0|8@0+ (1,-50) [-50|205] "C" Vector__XXX + SG_ CAN_MMIC_Temp3 : 0|8@0+ (1,-50) [-50|205] "C" Vector__XXX + SG_ CAN_MMIC_Temp2 : 0|8@0+ (1,-50) [-50|205] "C" Vector__XXX + SG_ CAN_Processor_Temp2 : 0|8@0+ (1,-50) [-50|205] "C" Vector__XXX + SG_ CAN_CHECKSUM : 0|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_COUNTER : 0|4@0+ (1,0) [0|15] "" Vector__XXX + SG_ CAN_VEHICLE_MODE : 0|4@0+ (1,0) [0|15] "" Vector__XXX + SG_ CAN_USC_CAL_VER_MAJOR : 0|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_USC_CAL_VER_MINOR : 0|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_SMC_CAL_VER_MAJOR : 0|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_HW_VERSION : 0|32@0+ (1,0) [0|4.29497e+09] "" Vector__XXX + SG_ CAN_FAC_TGT_MTG_SPACE_VER : 0|8@0+ (1,-128) [-128|127] "cm" Vector__XXX + SG_ CAN_ANGLE_MISALIGNMENT_VER : 0|10@0+ (0.03125,-10) [-10|21.9688] "deg" Vector__XXX + SG_ CAN_ANGLE_MOUNTING_VOFFSET : 0|8@0+ (0.0625,-8) [-8|7.9375] "deg" Vector__XXX + SG_ CAN_LATCH_FAULTS : 0|64@0+ (1,0) [0|100] "" Vector__XXX + SG_ CAN_ACTIVE_FAULTS : 0|64@0+ (1,0) [0|1.84467e+19] "" Vector__XXX + SG_ CAN_HISTORY_FAULTS : 0|64@0+ (1,0) [0|1.84467e+19] "" Vector__XXX + SG_ CAN_SERV_ALIGN_ENABLE : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_LONG_MOUNTING_OFFSET : 0|8@0+ (0.015625,-2) [-2|1.98438] "" Vector__XXX + SG_ CAN_BEAMWIDTH_VERT : 0|7@0+ (0.125,0) [0|15.875] "deg" Vector__XXX + SG_ CAN_VEHICLE_SPEED_CALC_QF : 0|2@0+ (1,0) [0|3] "" Vector__XXX + +BO_ 34 Active_Fault_Latched_2: 8 MRR + SG_ IPMA_PCAN_DataRangeCheck : 4|1@1+ (1,0) [0|1] "" External_Tool + SG_ IPMA_PCAN_MissingMsg : 3|1@1+ (1,0) [0|1] "" External_Tool + SG_ VINSignalCompareFailure : 2|1@1+ (1,0) [0|1] "" External_Tool + SG_ ModuleNotConfiguredError : 1|1@1+ (1,0) [0|1] "" External_Tool + SG_ CarCfgNotConfiguredError : 0|1@1+ (1,0) [0|1] "" External_Tool + +BO_ 33 Active_Fault_Latched_1: 8 MRR + SG_ Active_Flt_Latched_byte7_bit7 : 63|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte7_bit6 : 62|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte7_bit5 : 61|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte7_bit4 : 60|1@1+ (1,0) [0|1] "" External_Tool + SG_ ARMtoDSPChksumFault : 59|1@1+ (1,0) [0|1] "" External_Tool + SG_ DSPtoArmChksumFault : 58|1@1+ (1,0) [0|1] "" External_Tool + SG_ HostToArmChksumFault : 57|1@1+ (1,0) [0|1] "" External_Tool + SG_ ARMtoHostChksumFault : 56|1@1+ (1,0) [0|1] "" External_Tool + SG_ LoopBWOutOfRange : 55|1@1+ (1,0) [0|1] "" External_Tool + SG_ DSPOverrunFault : 54|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte6_bit5 : 53|1@1+ (1,0) [0|1] "" External_Tool + SG_ TuningSensitivityFault : 52|1@1+ (1,0) [0|1] "" External_Tool + SG_ SaturatedTuningFreqFault : 51|1@1+ (1,0) [0|1] "" External_Tool + SG_ LocalOscPowerFault : 50|1@1+ (1,0) [0|1] "" External_Tool + SG_ TransmitterPowerFault : 49|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte6_bit0 : 48|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte5_bit7 : 47|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte5_bit6 : 46|1@1+ (1,0) [0|1] "" External_Tool + SG_ XCVRDeviceSPIFault : 45|1@1+ (1,0) [0|1] "" External_Tool + SG_ FreqSynthesizerSPIFault : 44|1@1+ (1,0) [0|1] "" External_Tool + SG_ AnalogConverterDevicSPIFault : 43|1@1+ (1,0) [0|1] "" External_Tool + SG_ SidelobeBlockage : 42|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte5_bit1 : 41|1@1+ (1,0) [0|1] "" External_Tool + SG_ MNRBlocked : 40|1@1+ (1,0) [0|1] "" External_Tool + SG_ ECUTempHighFault : 39|1@1+ (1,0) [0|1] "" External_Tool + SG_ TransmitterTempHighFault : 38|1@1+ (1,0) [0|1] "" External_Tool + SG_ AlignmentRoutineFailedFault : 37|1@1+ (1,0) [0|1] "" External_Tool + SG_ UnreasonableRadarData : 36|1@1+ (1,0) [0|1] "" External_Tool + SG_ MicroprocessorTempHighFault : 35|1@1+ (1,0) [0|1] "" External_Tool + SG_ VerticalAlignmentOutOfRange : 34|1@1+ (1,0) [0|1] "" External_Tool + SG_ HorizontalAlignmentOutOfRange : 33|1@1+ (1,0) [0|1] "" External_Tool + SG_ FactoryAlignmentMode : 32|1@1+ (1,0) [0|1] "" External_Tool + SG_ BatteryLowFault : 31|1@1+ (1,0) [0|1] "" External_Tool + SG_ BatteryHighFault : 30|1@1+ (1,0) [0|1] "" External_Tool + SG_ v_1p25SupplyOutOfRange : 29|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte3_bit4 : 28|1@1+ (1,0) [0|1] "" External_Tool + SG_ ThermistorOutOfRange : 27|1@1+ (1,0) [0|1] "" External_Tool + SG_ v_3p3DACSupplyOutOfRange : 26|1@1+ (1,0) [0|1] "" External_Tool + SG_ v_3p3RAWSupplyOutOfRange : 25|1@1+ (1,0) [0|1] "" External_Tool + SG_ v_5_SupplyOutOfRange : 24|1@1+ (1,0) [0|1] "" External_Tool + SG_ TransmitterIDFault : 23|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit6 : 22|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit5 : 21|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit4 : 20|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit3 : 19|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit2 : 18|1@1+ (1,0) [0|1] "" External_Tool + SG_ PCANMissingMsgFault : 17|1@1+ (1,0) [0|1] "" External_Tool + SG_ PCANBusOff : 16|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte1_bit7 : 15|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte1_bit6 : 14|1@1+ (1,0) [0|1] "" External_Tool + SG_ InstructionSetCheckFault : 13|1@1+ (1,0) [0|1] "" External_Tool + SG_ StackOverflowFault : 12|1@1+ (1,0) [0|1] "" External_Tool + SG_ WatchdogFault : 11|1@1+ (1,0) [0|1] "" External_Tool + SG_ PLLLockFault : 10|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte1_bit1 : 9|1@1+ (1,0) [0|1] "" External_Tool + SG_ RAMMemoryTestFault : 8|1@1+ (1,0) [0|1] "" External_Tool + SG_ USCValidationFault : 7|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte0_bit6 : 6|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte0_bit5 : 5|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte0_bit4 : 4|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte0_bit3 : 3|1@1+ (1,0) [0|1] "" External_Tool + SG_ KeepAliveChecksumFault : 2|1@1+ (1,0) [0|1] "" External_Tool + SG_ ProgramCalibrationFlashChecksum : 1|1@1+ (1,0) [0|1] "" External_Tool + SG_ ApplicationFlashChecksumFault : 0|1@1+ (1,0) [0|1] "" External_Tool + +BO_ 500 XCP_MRR_DAQ_RESP: 8 MRR + SG_ MRR_xcp_daq_resp_byte7 : 63|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte6 : 55|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte5 : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte4 : 39|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte3 : 31|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte2 : 23|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte1 : 15|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte0 : 7|8@0+ (1,0) [0|255] "" External_Tool + +BO_ 499 XCP_MRR_DTO_RESP: 8 MRR + SG_ MRR_xcp_dto_resp_byte7 : 63|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte6 : 55|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte5 : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte4 : 39|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte3 : 31|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte2 : 23|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte1 : 15|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte0 : 7|8@0+ (1,0) [0|255] "" External_Tool + +BO_ 497 XCP_MRR_CTO_RESP: 8 MRR + SG_ MRR_xcp_cto_resp_byte7 : 63|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte6 : 55|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte5 : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte4 : 39|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte3 : 31|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte2 : 23|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte1 : 15|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte0 : 7|8@0+ (1,0) [0|255] "" External_Tool + +BO_ 1900 Ford_Diag_Resp_Phys: 8 MRR + SG_ TesterPhysicalResCCM : 7|64@0+ (1,0) [0|1.84467e+19] "" IFV_Host + +BO_ 261 MRR_Status_SerialNumber: 8 MRR + SG_ CAN_SEQUENCE_NUMBER : 55|16@0+ (1,0) [0|65535] "" External_Tool + SG_ CAN_SERIAL_NUMBER : 7|40@0+ (1,0) [0|1.09951e+12] "" External_Tool + +BO_ 264 MRR_Status_SwVersion: 8 MRR + SG_ CAN_PBL_Field_Revision : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_PBL_Promote_Revision : 39|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_SW_Field_Revision : 23|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_SW_Promote_Revision : 15|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_SW_Release_Revision : 7|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_PBL_Release_Revision : 31|8@0+ (1,0) [0|255] "" External_Tool + +BO_ 373 MRR_Header_SensorPosition: 8 MRR + SG_ CAN_SENSOR_POLARITY : 55|1@0+ (1,0) [0|1] "" External_Tool + SG_ CAN_SENSOR_LAT_OFFSET : 39|16@0+ (0.01,0) [0|655.35] "cm" External_Tool + SG_ CAN_SENSOR_LONG_OFFSET : 23|16@0+ (0.01,0) [0|655.35] "cm" External_Tool + SG_ CAN_SENSOR_HANGLE_OFFSET : 7|8@0+ (0.0625,-8) [-8|7.9375] "deg" External_Tool + +BO_ 372 MRR_Header_SensorCoverage: 8 MRR + SG_ CAN_SENSOR_FOV_HOR : 39|8@0+ (1,0) [0|255] "deg" IFV_VFP + SG_ CAN_DOPPLER_COVERAGE : 23|8@0+ (1,-128) [-128|127] "m/s" IFV_VFP + SG_ CAN_RANGE_COVERAGE : 7|8@0+ (1,0) [0|255] "m" IFV_VFP + +BO_ 371 MRR_Header_AlignmentState: 8 MRR + SG_ CAN_AUTO_ALIGN_HANGLE_QF : 13|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_ALIGNMENT_STATUS : 51|4@0+ (1,0) [0|11] "" IFV_VFP + SG_ CAN_ALIGNMENT_STATE : 55|3@0+ (1,0) [0|7] "" IFV_VFP + SG_ CAN_AUTO_ALIGN_HANGLE_REF : 11|10@0+ (0.000341218,-0.174533) [-0.174533|0.174533] "rad" IFV_VFP + SG_ CAN_AUTO_ALIGN_HANGLE : 7|10@0+ (0.000341218,-0.174533) [-0.174533|0.174533] "rad" IFV_VFP + +BO_ 369 MRR_Header_Timestamps: 8 MRR + SG_ CAN_DET_TIME_SINCE_MEAS : 39|11@0+ (0.1,0) [0|204.7] "ms" IFV_Host + SG_ CAN_SENSOR_TIME_STAMP : 7|32@0+ (0.1,0) [0|4.29497e+08] "ms" IFV_VFP + +BO_ 368 MRR_Header_InformationDetections: 8 MRR + SG_ CAN_ALIGN_UPDATES_DONE : 55|16@0+ (1,0) [0|65535] "" IFV_VFP + SG_ CAN_SCAN_INDEX : 31|16@0+ (1,0) [0|65535] "" IFV_VFP + SG_ CAN_NUMBER_OF_DET : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_LOOK_ID : 23|2@0+ (1,0) [0|3] "" External_Tool + SG_ CAN_LOOK_INDEX : 7|16@0+ (1,0) [0|65535] "" External_Tool + +BO_ 265 MRR_Status_Temp_Volt: 8 MRR + SG_ CAN_BATT_VOLTS : 63|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_1_25_V : 55|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_5_V : 47|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_3_3_V_RAW : 31|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_3_3_V_DAC : 15|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_MMIC_Temp1 : 39|8@0+ (1,-50) [-50|205] "C" External_Tool + SG_ CAN_Processor_Thermistor : 23|8@0+ (1,-50) [-50|205] "C" External_Tool + SG_ CAN_Processor_Temp1 : 7|8@0+ (1,-50) [-50|205] "C" External_Tool + +BO_ 291 MRR_Detection_004: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_04_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_04_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_04_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_04_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_04_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_04_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_04_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_04_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_04_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_04_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_04_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_04_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_04_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_04_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_04_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_04_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_04_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_04_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_04_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_04_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_04_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_04_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_04_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_04_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_04_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_04_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_04_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_04_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_04_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_04_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_04_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_04_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_04_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_04_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_04_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_04_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_04_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_04_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_04_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_04_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_04_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_04_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_04_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_04_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_04_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_04_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_04_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_04_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_04_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_04_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_04_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_04_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_04_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_04_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_04_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_04_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_04_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_04_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_04_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_04_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 351 MRR_Detection_064: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_64 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_64 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_64 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_64 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_64 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_64 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_64 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_64 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_64 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_64 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 350 MRR_Detection_063: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_63 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_63 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_63 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_63 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_63 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_63 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_63 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_63 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_63 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_63 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 349 MRR_Detection_062: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_62 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_62 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_62 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_62 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_62 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_62 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_62 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_62 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_62 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_62 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 348 MRR_Detection_061: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_61 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_61 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_61 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_61 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_61 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_61 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_61 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_61 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_61 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_61 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 347 MRR_Detection_060: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_60 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_60 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_60 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_60 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_60 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_60 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_60 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_60 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_60 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_60 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 346 MRR_Detection_059: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_59 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_59 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_59 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_59 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_59 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_59 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_59 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_59 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_59 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_59 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 345 MRR_Detection_058: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_58 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_58 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_58 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_58 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_58 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_58 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_58 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_58 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_58 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_58 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 344 MRR_Detection_057: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_57 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_57 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_57 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_57 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_57 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_57 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_57 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_57 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_57 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_57 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 343 MRR_Detection_056: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_56 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_56 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_56 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_56 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_56 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_56 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_56 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_56 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_56 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_56 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 342 MRR_Detection_055: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_55 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_55 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_55 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_55 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_55 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_55 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_55 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_55 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_55 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_55 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 335 MRR_Detection_048: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_48 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_48 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_48 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_48 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_48 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_48 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_48 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_48 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_48 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_48 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 334 MRR_Detection_047: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_47 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_47 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_47 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_47 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_47 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_47 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_47 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_47 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_47 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_47 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 333 MRR_Detection_046: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_46 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_46 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_46 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_46 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_46 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_46 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_46 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_46 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_46 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_46 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 332 MRR_Detection_045: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_45 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_45 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_45 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_45 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_45 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_45 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_45 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_45 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_45 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_45 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 331 MRR_Detection_044: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_44 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_44 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_44 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_44 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_44 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_44 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_44 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_44 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_44 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_44 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 330 MRR_Detection_043: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_43 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_43 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_43 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_43 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_43 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_43 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_43 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_43 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_43 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_43 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 329 MRR_Detection_042: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_42 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_42 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_42 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_42 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_42 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_42 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_42 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_42 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_42 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_42 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 328 MRR_Detection_041: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_41 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_41 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_41 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_41 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_41 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_41 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_41 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_41 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_41 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_41 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 327 MRR_Detection_040: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_40 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_40 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_40 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_40 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_40 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_40 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_40 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_40 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_40 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_40 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 325 MRR_Detection_038: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_38 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_38 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_38 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_38 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_38 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_38 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_38 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_38 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_38 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_38 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 324 MRR_Detection_037: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_37 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_37 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_37 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_37 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_37 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_37 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_37 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_37 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_37 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_37 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 323 MRR_Detection_036: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_36 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_36 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_36 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_36 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_36 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_36 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_36 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_36 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_36 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_36 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 322 MRR_Detection_035: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_35 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_35 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_35 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_35 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_35 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_35 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_35 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_35 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_35 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_35 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 321 MRR_Detection_034: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_34 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_34 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_34 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_34 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_34 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_34 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_34 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_34 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_34 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_34 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 320 MRR_Detection_033: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_33 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_33 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_33 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_33 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_33 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_33 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_33 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_33 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_33 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_33 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 319 MRR_Detection_032: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_32 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_32 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_32 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_32 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_32 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_32 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_32 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_32 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_32 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_32 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 318 MRR_Detection_031: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_31 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_31 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_31 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_31 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_31 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_31 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_31 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_31 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_31 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_31 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 317 MRR_Detection_030: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_30 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_30 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_30 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_30 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_30 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_30 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_30 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_30 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_30 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_30 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 316 MRR_Detection_029: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_29 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_29 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_29 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_29 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_29 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_29 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_29 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_29 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_29 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_29 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 314 MRR_Detection_027: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_27 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_27 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_27 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_27 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_27 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_27 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_27 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_27 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_27 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_27 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 313 MRR_Detection_026: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_26 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_26 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_26 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_26 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_26 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_26 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_26 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_26 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_26 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_26 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 312 MRR_Detection_025: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_25 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_25 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_25 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_25 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_25 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_25 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_25 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_25 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_25 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_25 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 311 MRR_Detection_024: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_24 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_24 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_24 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_24 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_24 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_24 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_24 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_24 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_24 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_24 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 310 MRR_Detection_023: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_23 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_23 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_23 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_23 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_23 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_23 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_23 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_23 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_23 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_23 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 309 MRR_Detection_022: 24 MRR + SG_ CAN_DET_CONFID_AZIMUTH_22_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_22_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_22_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_22_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_22_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_22_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_22_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_22_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_22_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_22_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_22_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_22_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_22_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_22_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_22_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_22_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_22_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_22_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_22_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_22_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_22_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_22_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_22_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_22_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_22_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_22_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_22_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_22_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_22_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_22_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 308 MRR_Detection_021: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_21_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_21_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_21_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_21_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_21_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_21_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_21_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_21_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_21_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_21_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_21_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_21_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_21_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_21_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_21_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_21_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_21_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_21_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_21_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_21_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_21_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_21_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_21_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_21_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_21_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_21_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_21_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_21_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_21_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_21_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_21_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_21_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_21_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_21_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_21_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_21_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_21_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_21_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_21_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_21_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_21_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_21_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_21_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_21_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_21_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_21_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_21_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_21_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_21_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_21_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_21_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_21_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_21_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_21_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_21_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_21_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_21_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_21_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_21_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_21_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 307 MRR_Detection_020: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_20_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_20_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_20_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_20_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_20_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_20_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_20_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_20_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_20_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_20_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_20_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_20_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_20_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_20_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_20_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_20_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_20_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_20_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_20_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_20_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_20_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_20_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_20_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_20_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_20_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_20_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_20_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_20_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_20_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_20_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_20_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_20_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_20_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_20_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_20_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_20_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_20_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_20_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_20_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_20_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_20_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_20_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_20_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_20_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_20_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_20_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_20_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_20_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_20_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_20_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_20_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_20_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_20_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_20_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_20_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_20_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_20_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_20_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_20_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_20_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 306 MRR_Detection_019: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_19_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_19_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_19_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_19_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_19_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_19_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_19_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_19_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_19_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_19_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_19_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_19_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_19_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_19_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_19_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_19_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_19_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_19_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_19_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_19_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_19_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_19_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_19_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_19_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_19_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_19_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_19_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_19_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_19_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_19_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_19_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_19_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_19_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_19_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_19_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_19_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_19_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_19_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_19_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_19_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_19_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_19_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_19_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_19_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_19_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_19_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_19_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_19_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_19_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_19_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_19_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_19_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_19_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_19_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_19_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_19_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_19_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_19_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_19_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_19_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 305 MRR_Detection_018: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_18_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_18_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_18_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_18_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_18_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_18_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_18_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_18_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_18_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_18_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_18_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_18_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_18_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_18_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_18_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_18_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_18_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_18_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_18_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_18_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_18_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_18_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_18_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_18_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_18_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_18_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_18_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_18_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_18_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_18_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_18_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_18_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_18_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_18_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_18_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_18_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_18_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_18_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_18_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_18_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_18_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_18_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_18_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_18_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_18_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_18_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_18_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_18_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_18_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_18_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_18_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_18_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_18_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_18_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_18_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_18_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_18_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_18_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_18_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_18_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 341 MRR_Detection_054: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_54 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_54 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_54 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_54 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_54 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_54 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_54 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_54 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_54 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_54 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 340 MRR_Detection_053: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_53 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_53 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_53 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_53 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_53 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_53 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_53 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_53 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_53 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_53 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 339 MRR_Detection_052: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_52 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_52 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_52 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_52 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_52 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_52 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_52 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_52 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_52 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_52 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 338 MRR_Detection_051: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_51 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_51 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_51 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_51 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_51 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_51 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_51 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_51 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_51 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_51 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 337 MRR_Detection_050: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_50 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_50 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_50 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_50 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_50 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_50 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_50 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_50 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_50 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_50 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 336 MRR_Detection_049: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_49 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_49 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_49 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_49 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_49 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_49 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_49 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_49 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_49 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_49 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 326 MRR_Detection_039: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_39 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_39 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_39 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_39 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_39 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_39 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_39 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_39 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_39 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_39 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 315 MRR_Detection_028: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_28 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_28 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_28 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_28 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_28 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_28 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_28 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_28 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_28 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_28 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 304 MRR_Detection_017: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_17_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_17_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_17_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_17_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_17_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_17_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_17_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_17_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_17_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_17_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_17_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_17_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_17_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_17_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_17_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_17_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_17_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_17_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_17_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_17_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_17_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_17_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_17_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_17_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_17_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_17_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_17_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_17_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_17_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_17_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_17_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_17_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_17_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_17_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_17_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_17_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_17_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_17_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_17_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_17_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_17_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_17_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_17_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_17_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_17_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_17_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_17_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_17_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_17_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_17_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_17_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_17_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_17_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_17_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_17_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_17_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_17_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_17_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_17_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_17_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 303 MRR_Detection_016: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_16_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_16_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_16_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_16_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_16_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_16_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_16_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_16_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_16_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_16_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_16_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_16_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_16_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_16_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_16_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_16_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_16_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_16_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_16_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_16_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_16_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_16_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_16_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_16_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_16_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_16_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_16_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_16_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_16_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_16_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_16_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_16_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_16_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_16_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_16_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_16_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_16_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_16_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_16_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_16_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_16_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_16_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_16_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_16_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_16_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_16_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_16_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_16_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_16_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_16_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_16_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_16_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_16_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_16_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_16_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_16_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_16_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_16_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_16_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_16_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 302 MRR_Detection_015: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_15_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_15_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_15_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_15_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_15_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_15_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_15_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_15_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_15_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_15_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_15_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_15_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_15_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_15_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_15_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_15_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_15_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_15_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_15_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_15_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_15_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_15_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_15_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_15_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_15_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_15_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_15_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_15_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_15_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_15_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_15_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_15_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_15_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_15_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_15_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_15_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_15_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_15_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_15_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_15_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_15_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_15_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_15_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_15_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_15_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_15_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_15_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_15_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_15_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_15_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_15_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_15_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_15_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_15_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_15_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_15_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_15_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_15_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_15_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_15_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 301 MRR_Detection_014: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_14_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_14_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_14_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_14_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_14_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_14_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_14_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_14_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_14_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_14_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_14_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_14_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_14_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_14_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_14_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_14_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_14_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_14_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_14_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_14_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_14_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_14_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_14_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_14_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_14_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_14_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_14_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_14_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_14_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_14_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_14_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_14_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_14_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_14_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_14_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_14_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_14_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_14_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_14_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_14_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_14_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_14_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_14_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_14_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_14_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_14_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_14_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_14_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_14_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_14_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_14_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_14_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_14_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_14_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_14_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_14_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_14_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_14_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_14_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_14_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 300 MRR_Detection_013: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_13_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_13_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_13_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_13_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_13_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_13_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_13_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_13_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_13_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_13_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_13_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_13_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_13_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_13_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_13_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_13_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_13_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_13_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_13_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_13_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_13_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_13_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_13_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_13_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_13_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_13_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_13_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_13_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_13_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_13_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_13_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_13_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_13_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_13_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_13_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_13_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_13_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_13_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_13_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_13_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_13_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_13_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_13_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_13_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_13_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_13_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_13_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_13_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_13_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_13_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_13_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_13_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_13_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_13_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_13_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_13_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_13_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_13_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_13_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_13_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 299 MRR_Detection_012: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_12_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_12_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_12_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_12_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_12_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_12_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_12_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_12_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_12_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_12_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_12_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_12_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_12_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_12_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_12_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_12_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_12_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_12_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_12_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_12_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_12_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_12_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_12_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_12_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_12_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_12_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_12_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_12_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_12_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_12_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_12_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_12_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_12_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_12_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_12_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_12_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_12_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_12_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_12_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_12_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_12_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_12_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_12_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_12_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_12_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_12_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_12_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_12_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_12_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_12_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_12_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_12_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_12_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_12_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_12_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_12_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_12_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_12_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_12_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_12_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 298 MRR_Detection_011: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_11_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_11_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_11_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_11_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_11_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_11_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_11_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_11_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_11_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_11_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_11_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_11_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_11_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_11_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_11_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_11_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_11_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_11_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_11_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_11_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_11_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_11_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_11_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_11_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_11_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_11_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_11_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_11_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_11_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_11_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_11_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_11_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_11_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_11_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_11_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_11_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_11_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_11_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_11_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_11_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_11_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_11_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_11_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_11_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_11_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_11_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_11_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_11_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_11_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_11_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_11_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_11_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_11_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_11_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_11_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_11_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_11_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_11_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_11_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_11_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 297 MRR_Detection_010: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_10_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_10_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_10_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_10_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_10_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_10_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_10_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_10_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_10_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_10_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_10_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_10_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_10_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_10_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_10_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_10_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_10_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_10_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_10_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_10_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_10_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_10_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_10_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_10_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_10_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_10_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_10_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_10_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_10_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_10_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_10_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_10_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_10_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_10_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_10_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_10_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_10_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_10_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_10_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_10_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_10_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_10_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_10_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_10_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_10_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_10_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_10_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_10_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_10_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_10_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_10_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_10_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_10_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_10_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_10_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_10_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_10_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_10_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_10_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_10_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 296 MRR_Detection_009: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_09_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_09_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_09_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_09_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_09_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_09_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_09_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_09_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_09_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_09_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_09_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_09_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_09_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_09_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_09_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_09_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_09_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_09_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_09_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_09_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_09_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_09_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_09_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_09_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_09_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_09_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_09_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_09_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_09_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_09_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_09_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_09_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_09_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_09_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_09_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_09_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_09_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_09_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_09_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_09_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_09_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_09_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_09_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_09_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_09_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_09_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_09_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_09_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_09_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_09_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_09_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_09_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_09_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_09_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_09_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_09_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_09_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_09_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_09_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_09_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 295 MRR_Detection_008: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_08_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_08_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_08_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_08_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_08_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_08_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_08_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_08_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_08_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_08_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_08_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_08_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_08_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_08_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_08_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_08_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_08_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_08_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_08_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_08_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_08_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_08_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_08_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_08_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_08_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_08_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_08_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_08_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_08_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_08_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_08_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_08_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_08_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_08_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_08_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_08_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_08_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_08_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_08_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_08_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_08_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_08_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_08_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_08_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_08_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_08_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_08_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_08_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_08_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_08_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_08_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_08_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_08_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_08_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_08_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_08_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_08_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_08_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_08_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_08_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 294 MRR_Detection_007: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_07_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_07_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_07_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_07_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_07_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_07_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_07_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_07_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_07_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_07_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_07_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_07_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_07_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_07_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_07_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_07_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_07_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_07_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_07_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_07_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_07_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_07_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_07_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_07_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_07_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_07_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_07_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_07_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_07_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_07_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_07_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_07_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_07_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_07_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_07_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_07_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_07_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_07_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_07_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_07_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_07_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_07_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_07_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_07_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_07_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_07_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_07_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_07_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_07_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_07_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_07_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_07_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_07_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_07_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_07_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_07_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_07_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_07_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_07_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_07_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 293 MRR_Detection_006: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_06_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_06_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_06_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_06_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_06_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_06_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_06_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_06_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_06_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_06_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_06_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_06_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_06_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_06_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_06_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_06_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_06_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_06_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_06_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_06_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_06_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_06_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_06_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_06_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_06_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_06_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_06_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_06_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_06_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_06_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_06_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_06_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_06_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_06_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_06_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_06_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_06_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_06_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_06_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_06_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_06_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_06_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_06_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_06_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_06_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_06_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_06_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_06_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_06_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_06_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_06_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_06_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_06_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_06_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_06_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_06_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_06_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_06_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_06_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_06_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 292 MRR_Detection_005: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_05_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_05_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_05_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_05_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_05_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_05_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_05_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_05_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_05_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_05_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_05_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_05_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_05_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_05_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_05_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_05_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_05_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_05_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_05_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_05_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_05_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_05_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_05_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_05_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_05_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_05_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_05_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_05_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_05_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_05_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_05_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_05_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_05_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_05_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_05_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_05_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_05_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_05_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_05_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_05_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_05_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_05_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_05_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_05_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_05_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_05_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_05_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_05_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_05_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_05_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_05_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_05_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_05_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_05_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_05_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_05_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_05_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_05_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_05_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_05_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 290 MRR_Detection_003: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_03_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_03_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_03_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_03_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_03_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_03_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_03_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_03_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_03_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_03_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_03_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_03_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_03_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_03_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_03_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_03_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_03_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_03_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_03_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_03_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_03_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_03_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_03_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_03_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_03_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_03_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_03_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_03_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_03_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_03_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_03_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_03_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_03_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_03_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_03_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_03_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_03_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_03_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_03_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_03_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_03_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_03_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_03_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_03_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_03_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_03_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_03_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_03_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_03_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_03_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_03_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_03_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_03_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_03_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_03_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_03_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_03_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_03_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_03_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_03_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 289 MRR_Detection_002: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_02_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_02_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_02_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_02_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_02_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_02_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_02_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_02_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_02_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_02_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_02_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_02_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_02_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_02_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_02_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_02_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_02_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_02_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_02_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_02_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_02_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_02_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_02_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_02_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_02_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_02_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_02_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_02_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_02_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_02_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_02_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_02_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_02_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_02_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_02_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_02_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_02_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_02_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_02_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_02_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_02_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_02_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_02_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_02_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_02_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_02_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_02_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_02_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_02_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_02_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_02_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_02_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_02_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_02_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_02_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_02_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_02_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_02_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_02_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_02_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 256 MRR_Status_CANVersion: 8 MRR + SG_ CAN_USC_SECTION_COMPATIBILITY : 23|16@0+ (1,0) [0|65535] "" External_Tool + SG_ CAN_PCAN_MINOR_MRR : 7|8@0+ (1,0) [0|255] "" IFV_VFP + SG_ CAN_PCAN_MAJOR_MRR : 15|8@0+ (1,0) [0|255] "" IFV_VFP + +BO_ 257 MRR_Status_Radar: 8 MRR + SG_ CAN_INTERFERENCE_TYPE : 11|2@0+ (1,0) [0|3] "" IFV_Host + SG_ CAN_RECOMMEND_UNCONVERGE : 9|1@0+ (1,0) [0|1] "" IFV_Host + SG_ CAN_BLOCKAGE_SIDELOBE_FILTER_VAL : 15|4@0+ (1,0) [0|15] "" IFV_Host + SG_ CAN_RADAR_ALIGN_INCOMPLETE : 8|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_BLOCKAGE_SIDELOBE : 4|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_BLOCKAGE_MNR : 5|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_EXT_COND_NOK : 1|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_ALIGN_OUT_RANGE : 2|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_ALIGN_NOT_START : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_OVERHEAT_ERROR : 3|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_NOT_OP : 6|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_XCVR_OPERATIONAL : 7|1@0+ (1,0) [0|1] "" IFV_VFP + +BO_ 288 MRR_Detection_001: 64 MRR + SG_ CAN_DET_CONFID_AZIMUTH_01_01 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_01_01 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_01_01 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_01_01 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_01_01 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_01_01 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_01_01 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_01_01 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_01_01 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_01_01 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_01_02 : 105|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_01_02 : 128|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_01_02 : 120|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_01_02 : 121|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_01_02 : 72|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_01_02 : 119|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_01_02 : 103|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_01_02 : 87|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_01_02 : 79|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_01_02 : 89|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_01_03 : 177|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_01_03 : 200|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_01_03 : 192|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_01_03 : 193|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_01_03 : 144|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_01_03 : 191|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_01_03 : 175|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_01_03 : 159|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_01_03 : 151|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_01_03 : 161|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_01_04 : 249|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_01_04 : 272|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_01_04 : 264|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_01_04 : 265|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_01_04 : 216|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_01_04 : 263|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_01_04 : 247|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_01_04 : 231|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_01_04 : 223|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_01_04 : 233|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_01_05 : 321|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_01_05 : 344|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_01_05 : 336|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_01_05 : 337|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_01_05 : 288|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_01_05 : 335|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_01_05 : 319|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_01_05 : 303|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_01_05 : 295|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_01_05 : 305|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_CONFID_AZIMUTH_01_06 : 393|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_01_06 : 416|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_01_06 : 408|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_01_06 : 409|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_01_06 : 360|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_01_06 : 407|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_01_06 : 391|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_01_06 : 375|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_01_06 : 367|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_01_06 : 377|2@0+ (1,0) [0|3] "" IFV_VFP + +BA_DEF_ SG_ "CrossOver_InfoCAN" ENUM "No","Yes"; +BA_DEF_ SG_ "CrossOver_LIN" ENUM "No","Yes","No","Yes"; +BA_DEF_ SG_ "UsedOnPgmDBC" ENUM "No","Yes","No","Yes","No","Yes"; +BA_DEF_ SG_ "ContentDependant" ENUM "No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ SG_ "GenSigTimeoutTime_RCM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_GWM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_OCS" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_ABS_ESC" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_CCM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_IPMA" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_TSTR" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_SCCM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_PSCM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime__delete" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_Generic_BCM" INT 0 100000; +BA_DEF_ BO_ "NmMessage" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "DiagResponse" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "DiagRequest" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "TpTxIndex" INT 0 255; +BA_DEF_ BO_ "DiagState" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "TpApplType" STRING ; +BA_DEF_ BO_ "NmAsrMessage" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "Mulitplexer" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "ConfiguredTransmitter" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "EventRateOfChange" INT 10 10000; +BA_DEF_ BO_ "GenMsgHandlingTypeDoc" STRING ; +BA_DEF_ BO_ "GenMsgHandlingTypeCode" STRING ; +BA_DEF_ BO_ "GenMsgMarked" STRING ; +BA_DEF_ SG_ "GenSigMarked" STRING ; +BA_DEF_ SG_ "GenSigVtIndex" STRING ; +BA_DEF_ SG_ "GenSigVtName" STRING ; +BA_DEF_ SG_ "GenSigVtEn" STRING ; +BA_DEF_ SG_ "GenSigSNA" STRING ; +BA_DEF_ SG_ "GenSigCmt" STRING ; +BA_DEF_ BO_ "GenMsgCmt" STRING ; +BA_DEF_ SG_ "GenSigSendType" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType"; +BA_DEF_ SG_ "GenSigInactiveValue" INT 0 100000; +BA_DEF_ SG_ "GenSigMissingSourceValue" INT 0 1e+09; +BA_DEF_ SG_ "WakeupSignal" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes"; +BA_DEF_ SG_ "GenSigStartValue" INT 0 1e+09; +BA_DEF_ BO_ "GenMsgILSupport" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes"; +BA_DEF_ BO_ "NetworkInitializationCommand" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "GenMsgSendType" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType"; +BA_DEF_ BO_ "GenMsgCycleTime" INT 0 100000; +BA_DEF_ BO_ "GenMsgCycleTimeFast" INT 0 100000; +BA_DEF_ BO_ "GenMsgDelayTime" INT 0 1000; +BA_DEF_ BO_ "GenMsgNrOfRepetition" INT 0 100; +BA_DEF_ BO_ "GenMsgStartDelayTime" INT 0 10000; +BA_DEF_ BO_ "NetworkInitialization" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes"; +BA_DEF_ BO_ "MessageGateway" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes","No","Yes"; +BA_DEF_ BU_ "ILUsed" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BU_ "NetworkInitializationUsed" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BU_ "PowerType" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes","No","Yes","No","Yes","No","Yes","Switched","Latched","Sleep","vector_leerstring","vector_leerstring"; +BA_DEF_ BU_ "NodeStartUpTime" INT 0 10000; +BA_DEF_ BU_ "NodeWakeUpTime" INT 0 10000; +BA_DEF_ BO_ "GenMsgBackgroundColor" STRING ; +BA_DEF_ BO_ "GenMsgForegroundColor" STRING ; +BA_ "GenMsgCycleTime" BO_ 34 1000; +BA_ "GenMsgSendType" BO_ 34 0; +BA_ "GenSigVtEn" SG_ 34 IPMA_PCAN_DataRangeCheck "IPMA_PCAN_DataRangeCheck"; +BA_ "GenSigVtName" SG_ 34 IPMA_PCAN_DataRangeCheck "IPMA_PCAN_DataRangeCheck"; +BA_ "GenSigVtEn" SG_ 34 IPMA_PCAN_MissingMsg "IPMA_PCAN_MissingMsg"; +BA_ "GenSigVtName" SG_ 34 IPMA_PCAN_MissingMsg "IPMA_PCAN_MissingMsg"; +BA_ "GenSigVtEn" SG_ 34 VINSignalCompareFailure "VINSignalCompareFailure"; +BA_ "GenSigVtName" SG_ 34 VINSignalCompareFailure "VINSignalCompareFailure"; +BA_ "GenSigVtEn" SG_ 34 ModuleNotConfiguredError "ModuleNotConfiguredError"; +BA_ "GenSigVtName" SG_ 34 ModuleNotConfiguredError "ModuleNotConfiguredError"; +BA_ "GenSigVtEn" SG_ 34 CarCfgNotConfiguredError "CarCfgNotConfiguredError"; +BA_ "GenSigVtName" SG_ 34 CarCfgNotConfiguredError "CarCfgNotConfiguredError"; +BA_ "GenMsgCycleTime" BO_ 33 1000; +BA_ "GenMsgSendType" BO_ 33 0; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte7_bit7 "Active_Flt_Latched_byte7_bit7"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte7_bit7 "Active_Flt_Latched_byte7_bit7"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte7_bit6 "Active_Flt_Latched_byte7_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte7_bit6 "Active_Flt_Latched_byte7_bit6"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte7_bit5 "Active_Flt_Latched_byte7_bit5"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte7_bit5 "Active_Flt_Latched_byte7_bit5"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte7_bit4 "Active_Flt_Latched_byte7_bit4"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte7_bit4 "Active_Flt_Latched_byte7_bit4"; +BA_ "GenSigVtEn" SG_ 33 ARMtoDSPChksumFault "ARMtoDSPChksumFault"; +BA_ "GenSigVtName" SG_ 33 ARMtoDSPChksumFault "ARMtoDSPChksumFault"; +BA_ "GenSigVtEn" SG_ 33 DSPtoArmChksumFault "DSPtoArmChksumFault"; +BA_ "GenSigVtName" SG_ 33 DSPtoArmChksumFault "DSPtoArmChksumFault"; +BA_ "GenSigVtEn" SG_ 33 HostToArmChksumFault "HostToArmChksumFault"; +BA_ "GenSigVtName" SG_ 33 HostToArmChksumFault "HostToArmChksumFault"; +BA_ "GenSigVtEn" SG_ 33 ARMtoHostChksumFault "ARMtoHostChksumFault"; +BA_ "GenSigVtName" SG_ 33 ARMtoHostChksumFault "ARMtoHostChksumFault"; +BA_ "GenSigVtEn" SG_ 33 LoopBWOutOfRange "LoopBWOutOfRange"; +BA_ "GenSigVtName" SG_ 33 LoopBWOutOfRange "LoopBWOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 DSPOverrunFault "DSPOverrunFault"; +BA_ "GenSigVtName" SG_ 33 DSPOverrunFault "DSPOverrunFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte6_bit5 "Active_Flt_Latched_byte6_bit5"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte6_bit5 "Active_Flt_Latched_byte6_bit5"; +BA_ "GenSigVtEn" SG_ 33 TuningSensitivityFault "TuningSensitivityFault"; +BA_ "GenSigVtName" SG_ 33 TuningSensitivityFault "TuningSensitivityFault"; +BA_ "GenSigVtEn" SG_ 33 SaturatedTuningFreqFault "SaturatedTuningFreqFault"; +BA_ "GenSigVtName" SG_ 33 SaturatedTuningFreqFault "SaturatedTuningFreqFault"; +BA_ "GenSigVtEn" SG_ 33 LocalOscPowerFault "LocalOscPowerFault"; +BA_ "GenSigVtName" SG_ 33 LocalOscPowerFault "LocalOscPowerFault"; +BA_ "GenSigVtEn" SG_ 33 TransmitterPowerFault "TransmitterPowerFault"; +BA_ "GenSigVtName" SG_ 33 TransmitterPowerFault "TransmitterPowerFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte6_bit0 "Active_Flt_Latched_byte6_bit0"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte6_bit0 "Active_Flt_Latched_byte6_bit0"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte5_bit7 "Active_Flt_Latched_byte5_bit7"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte5_bit7 "Active_Flt_Latched_byte5_bit7"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte5_bit6 "Active_Flt_Latched_byte5_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte5_bit6 "Active_Flt_Latched_byte5_bit6"; +BA_ "GenSigVtEn" SG_ 33 XCVRDeviceSPIFault "XCVRDeviceSPIFault"; +BA_ "GenSigVtName" SG_ 33 XCVRDeviceSPIFault "XCVRDeviceSPIFault"; +BA_ "GenSigVtEn" SG_ 33 FreqSynthesizerSPIFault "FreqSynthesizerSPIFault"; +BA_ "GenSigVtName" SG_ 33 FreqSynthesizerSPIFault "FreqSynthesizerSPIFault"; +BA_ "GenSigVtEn" SG_ 33 AnalogConverterDevicSPIFault "AnalogConverterDevicSPIFault"; +BA_ "GenSigVtName" SG_ 33 AnalogConverterDevicSPIFault "AnalogConverterDevicSPIFault"; +BA_ "GenSigVtEn" SG_ 33 SidelobeBlockage "SidelobeBlockage"; +BA_ "GenSigVtName" SG_ 33 SidelobeBlockage "SidelobeBlockage"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte5_bit1 "Active_Flt_Latched_byte5_bit1"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte5_bit1 "Active_Flt_Latched_byte5_bit1"; +BA_ "GenSigVtEn" SG_ 33 MNRBlocked "MNRBlocked"; +BA_ "GenSigVtName" SG_ 33 MNRBlocked "MNRBlocked"; +BA_ "GenSigVtEn" SG_ 33 ECUTempHighFault "ECUTempHighFault"; +BA_ "GenSigVtName" SG_ 33 ECUTempHighFault "ECUTempHighFault"; +BA_ "GenSigVtEn" SG_ 33 TransmitterTempHighFault "TransmitterTempHighFault"; +BA_ "GenSigVtName" SG_ 33 TransmitterTempHighFault "TransmitterTempHighFault"; +BA_ "GenSigVtEn" SG_ 33 AlignmentRoutineFailedFault "AlignmentRoutineFailedFault"; +BA_ "GenSigVtName" SG_ 33 AlignmentRoutineFailedFault "AlignmentRoutineFailedFault"; +BA_ "GenSigVtEn" SG_ 33 UnreasonableRadarData "UnreasonableRadarData"; +BA_ "GenSigVtName" SG_ 33 UnreasonableRadarData "UnreasonableRadarData"; +BA_ "GenSigVtEn" SG_ 33 MicroprocessorTempHighFault "MicroprocessorTempHighFault"; +BA_ "GenSigVtName" SG_ 33 MicroprocessorTempHighFault "MicroprocessorTempHighFault"; +BA_ "GenSigVtEn" SG_ 33 VerticalAlignmentOutOfRange "VerticalAlignmentOutOfRange"; +BA_ "GenSigVtName" SG_ 33 VerticalAlignmentOutOfRange "VerticalAlignmentOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 HorizontalAlignmentOutOfRange "HorizontalAlignmentOutOfRange"; +BA_ "GenSigVtName" SG_ 33 HorizontalAlignmentOutOfRange "HorizontalAlignmentOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 FactoryAlignmentMode "FactoryAlignmentMode"; +BA_ "GenSigVtName" SG_ 33 FactoryAlignmentMode "FactoryAlignmentMode"; +BA_ "GenSigVtEn" SG_ 33 BatteryLowFault "BatteryLowFault"; +BA_ "GenSigVtName" SG_ 33 BatteryLowFault "BatteryLowFault"; +BA_ "GenSigVtEn" SG_ 33 BatteryHighFault "BatteryHighFault"; +BA_ "GenSigVtName" SG_ 33 BatteryHighFault "BatteryHighFault"; +BA_ "GenSigVtEn" SG_ 33 v_1p25SupplyOutOfRange "v_1p25SupplyOutOfRange"; +BA_ "GenSigVtName" SG_ 33 v_1p25SupplyOutOfRange "v_1p25SupplyOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte3_bit4 "Active_Flt_Latched_byte3_bit4"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte3_bit4 "Active_Flt_Latched_byte3_bit4"; +BA_ "GenSigVtEn" SG_ 33 ThermistorOutOfRange "ThermistorOutOfRange"; +BA_ "GenSigVtName" SG_ 33 ThermistorOutOfRange "ThermistorOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 v_3p3DACSupplyOutOfRange "v_3p3DACSupplyOutOfRange"; +BA_ "GenSigVtName" SG_ 33 v_3p3DACSupplyOutOfRange "v_3p3DACSupplyOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 v_3p3RAWSupplyOutOfRange "v_3p3RAWSupplyOutOfRange"; +BA_ "GenSigVtName" SG_ 33 v_3p3RAWSupplyOutOfRange "v_3p3RAWSupplyOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 v_5_SupplyOutOfRange "v_5_SupplyOutOfRange"; +BA_ "GenSigVtName" SG_ 33 v_5_SupplyOutOfRange "v_5_SupplyOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 TransmitterIDFault "TransmitterIDFault"; +BA_ "GenSigVtName" SG_ 33 TransmitterIDFault "TransmitterIDFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit6 "Active_Flt_Latched_byte2_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit6 "Active_Flt_Latched_byte2_bit6"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit5 "Active_Flt_Latched_byte2_bit5"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit5 "Active_Flt_Latched_byte2_bit5"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit4 "Active_Flt_Latched_byte2_bit4"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit4 "Active_Flt_Latched_byte2_bit4"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit3 "Active_Flt_Latched_byte2_bit3"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit3 "Active_Flt_Latched_byte2_bit3"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit2 "Active_Flt_Latched_byte2_bit2"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit2 "Active_Flt_Latched_byte2_bit2"; +BA_ "GenSigVtEn" SG_ 33 PCANMissingMsgFault "PCANMissingMsgFault"; +BA_ "GenSigVtName" SG_ 33 PCANMissingMsgFault "PCANMissingMsgFault"; +BA_ "GenSigVtEn" SG_ 33 PCANBusOff "PCANBusOff"; +BA_ "GenSigVtName" SG_ 33 PCANBusOff "PCANBusOff"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte1_bit7 "Active_Flt_Latched_byte1_bit7"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte1_bit7 "Active_Flt_Latched_byte1_bit7"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte1_bit6 "Active_Flt_Latched_byte1_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte1_bit6 "Active_Flt_Latched_byte1_bit6"; +BA_ "GenSigVtEn" SG_ 33 InstructionSetCheckFault "InstructionSetCheckFault"; +BA_ "GenSigVtName" SG_ 33 InstructionSetCheckFault "InstructionSetCheckFault"; +BA_ "GenSigVtEn" SG_ 33 StackOverflowFault "StackOverflowFault"; +BA_ "GenSigVtName" SG_ 33 StackOverflowFault "StackOverflowFault"; +BA_ "GenSigVtEn" SG_ 33 WatchdogFault "WatchdogFault"; +BA_ "GenSigVtName" SG_ 33 WatchdogFault "WatchdogFault"; +BA_ "GenSigVtEn" SG_ 33 PLLLockFault "PLLLockFault"; +BA_ "GenSigVtName" SG_ 33 PLLLockFault "PLLLockFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte1_bit1 "Active_Flt_Latched_byte1_bit1"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte1_bit1 "Active_Flt_Latched_byte1_bit1"; +BA_ "GenSigVtEn" SG_ 33 RAMMemoryTestFault "RAMMemoryTestFault"; +BA_ "GenSigVtName" SG_ 33 RAMMemoryTestFault "RAMMemoryTestFault"; +BA_ "GenSigVtName" SG_ 33 USCValidationFault "USCValidationFault"; +BA_ "GenSigVtEn" SG_ 33 USCValidationFault "USCValidationFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte0_bit6 "Active_Flt_Latched_byte0_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte0_bit6 "Active_Flt_Latched_byte0_bit6"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte0_bit5 "Active_Flt_Latched_byte0_bit5"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte0_bit5 "Active_Flt_Latched_byte0_bit5"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte0_bit4 "Active_Flt_Latched_byte0_bit4"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte0_bit4 "Active_Flt_Latched_byte0_bit4"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte0_bit3 "Active_Flt_Latched_byte0_bit3"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte0_bit3 "Active_Flt_Latched_byte0_bit3"; +BA_ "GenSigVtEn" SG_ 33 KeepAliveChecksumFault "KeepAliveChecksumFault"; +BA_ "GenSigVtName" SG_ 33 KeepAliveChecksumFault "KeepAliveChecksumFault"; +BA_ "GenSigVtEn" SG_ 33 ProgramCalibrationFlashChecksum "ProgramCalibrationFlashChecksum"; +BA_ "GenSigVtName" SG_ 33 ProgramCalibrationFlashChecksum "ProgramCalibrationFlashChecksum"; +BA_ "GenSigVtEn" SG_ 33 ApplicationFlashChecksumFault "ApplicationFlashChecksumFault"; +BA_ "GenSigVtName" SG_ 33 ApplicationFlashChecksumFault "ApplicationFlashChecksumFault"; +BA_ "GenMsgNrOfRepetition" BO_ 500 0; +BA_ "GenMsgSendType" BO_ 500 1; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte7 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte7 "MRR_xcp_daq_resp_byte7"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte6 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte6 "MRR_xcp_daq_resp_byte6"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte5 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte5 "MRR_xcp_daq_resp_byte5"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte4 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte4 "MRR_xcp_daq_resp_byte4"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte3 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte3 "MRR_xcp_daq_resp_byte3"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte2 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte2 "MRR_xcp_daq_resp_byte2"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte1 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte1 "MRR_xcp_daq_resp_byte1"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte0 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte0 "MRR_xcp_daq_resp_byte0"; +BA_ "GenMsgNrOfRepetition" BO_ 499 0; +BA_ "GenMsgSendType" BO_ 499 1; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte7 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte7 "MRR_xcp_dto_resp_byte7"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte6 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte6 "MRR_xcp_dto_resp_byte6"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte5 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte5 "MRR_xcp_dto_resp_byte5"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte4 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte4 "MRR_xcp_dto_resp_byte4"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte3 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte3 "MRR_xcp_dto_resp_byte3"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte2 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte2 "MRR_xcp_dto_resp_byte2"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte1 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte1 "MRR_xcp_dto_resp_byte1"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte0 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte0 "MRR_xcp_dto_resp_byte0"; +BA_ "GenMsgNrOfRepetition" BO_ 497 0; +BA_ "GenMsgSendType" BO_ 497 1; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte7 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte7 "MRR_xcp_cto_resp_byte7"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte6 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte6 "MRR_xcp_cto_resp_byte6"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte5 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte5 "MRR_xcp_cto_resp_byte5"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte4 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte4 "MRR_xcp_cto_resp_byte4"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte3 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte3 "MRR_xcp_cto_resp_byte3"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte2 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte2 "MRR_xcp_cto_resp_byte2"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte1 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte1 "MRR_xcp_cto_resp_byte1"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte0 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte0 "MRR_xcp_cto_resp_byte0"; +BA_ "GenMsgSendType" BO_ 1900 1; +BA_ "GenMsgNrOfRepetition" BO_ 1900 0; +BA_ "DiagResponse" BO_ 1900 1; +BA_ "GenSigCmt" SG_ 1900 TesterPhysicalResCCM "TesterPhysicalResCCM"; +BA_ "GenSigSendType" SG_ 1900 TesterPhysicalResCCM 0; +BA_ "GenMsgSendType" BO_ 261 0; +BA_ "GenMsgCycleTime" BO_ 261 1000; +BA_ "GenMsgNrOfRepetition" BO_ 261 0; +BA_ "GenSigCmt" SG_ 261 CAN_SEQUENCE_NUMBER "CAN_SEQUENCE_NUMBER"; +BA_ "GenSigCmt" SG_ 261 CAN_SERIAL_NUMBER "CAN_SERIAL_NUMBER"; +BA_ "GenSigSendType" SG_ 261 CAN_SERIAL_NUMBER 0; +BA_ "GenMsgSendType" BO_ 264 1; +BA_ "GenMsgNrOfRepetition" BO_ 264 0; +BA_ "GenSigSendType" SG_ 264 CAN_PBL_Field_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_PBL_Promote_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_SW_Field_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_SW_Promote_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_SW_Release_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_PBL_Release_Revision 0; +BA_ "GenMsgSendType" BO_ 373 1; +BA_ "NetworkInitialization" BO_ 373 0; +BA_ "GenMsgNrOfRepetition" BO_ 373 0; +BA_ "GenSigSendType" SG_ 373 CAN_SENSOR_POLARITY 0; +BA_ "GenSigCmt" SG_ 373 CAN_SENSOR_POLARITY "CAN_SENSOR_POLARITY"; +BA_ "GenSigSendType" SG_ 373 CAN_SENSOR_LAT_OFFSET 0; +BA_ "GenSigCmt" SG_ 373 CAN_SENSOR_LAT_OFFSET "CAN_SENSOR_LAT_OFFSET"; +BA_ "GenSigSendType" SG_ 373 CAN_SENSOR_LONG_OFFSET 0; +BA_ "GenSigCmt" SG_ 373 CAN_SENSOR_LONG_OFFSET "CAN_SENSOR_LONG_OFFSET"; +BA_ "GenSigSendType" SG_ 373 CAN_SENSOR_HANGLE_OFFSET 0; +BA_ "GenSigCmt" SG_ 373 CAN_SENSOR_HANGLE_OFFSET "CAN_SENSOR_HANGLE_OFFSET"; +BA_ "GenSigStartValue" SG_ 373 CAN_SENSOR_HANGLE_OFFSET 0; +BA_ "GenMsgSendType" BO_ 372 1; +BA_ "NetworkInitialization" BO_ 372 0; +BA_ "GenMsgNrOfRepetition" BO_ 372 0; +BA_ "GenSigSendType" SG_ 372 CAN_SENSOR_FOV_HOR 0; +BA_ "GenSigCmt" SG_ 372 CAN_SENSOR_FOV_HOR "CAN_SENSOR_FOV_HOR"; +BA_ "GenSigStartValue" SG_ 372 CAN_SENSOR_FOV_HOR 0; +BA_ "GenSigSendType" SG_ 372 CAN_DOPPLER_COVERAGE 0; +BA_ "GenSigCmt" SG_ 372 CAN_DOPPLER_COVERAGE "CAN_DOPPLER_COVERAGE"; +BA_ "GenSigStartValue" SG_ 372 CAN_DOPPLER_COVERAGE 0; +BA_ "GenSigSendType" SG_ 372 CAN_RANGE_COVERAGE 0; +BA_ "GenSigCmt" SG_ 372 CAN_RANGE_COVERAGE "CAN_RANGE_COVERAGE"; +BA_ "GenMsgSendType" BO_ 371 1; +BA_ "NetworkInitialization" BO_ 371 0; +BA_ "GenMsgNrOfRepetition" BO_ 371 0; +BA_ "GenSigVtEn" SG_ 371 CAN_AUTO_ALIGN_HANGLE_QF "CAN_AUTO_ALIGN_HANGLE_QF"; +BA_ "GenSigVtName" SG_ 371 CAN_AUTO_ALIGN_HANGLE_QF "CAN_AUTO_ALIGN_HANGLE_QF"; +BA_ "GenSigSendType" SG_ 371 CAN_AUTO_ALIGN_HANGLE_QF 0; +BA_ "GenSigCmt" SG_ 371 CAN_AUTO_ALIGN_HANGLE_QF "CAN_AUTO_ALIGN_HANGLE_QF"; +BA_ "GenSigVtEn" SG_ 371 CAN_ALIGNMENT_STATUS "CAN_ALIGNMENT_STATUS"; +BA_ "GenSigVtName" SG_ 371 CAN_ALIGNMENT_STATUS "CAN_ALIGNMENT_STATUS"; +BA_ "GenSigSendType" SG_ 371 CAN_ALIGNMENT_STATUS 0; +BA_ "GenSigCmt" SG_ 371 CAN_ALIGNMENT_STATUS "CAN_ALIGNMENT_STATUS"; +BA_ "GenSigVtEn" SG_ 371 CAN_ALIGNMENT_STATE "CAN_ALIGNMENT_STATE"; +BA_ "GenSigVtName" SG_ 371 CAN_ALIGNMENT_STATE "CAN_ALIGNMENT_STATE"; +BA_ "GenSigSendType" SG_ 371 CAN_ALIGNMENT_STATE 0; +BA_ "GenSigCmt" SG_ 371 CAN_ALIGNMENT_STATE "CAN_ALIGNMENT_STATE"; +BA_ "GenSigSendType" SG_ 371 CAN_AUTO_ALIGN_HANGLE_REF 0; +BA_ "GenSigStartValue" SG_ 371 CAN_AUTO_ALIGN_HANGLE_REF 0; +BA_ "GenSigCmt" SG_ 371 CAN_AUTO_ALIGN_HANGLE_REF "CAN_AUTO_ALIGN_HANGLE_REF"; +BA_ "GenSigStartValue" SG_ 371 CAN_AUTO_ALIGN_HANGLE 0; +BA_ "GenSigSendType" SG_ 371 CAN_AUTO_ALIGN_HANGLE 0; +BA_ "GenSigCmt" SG_ 371 CAN_AUTO_ALIGN_HANGLE "CAN_AUTO_ALIGN_HANGLE"; +BA_ "GenMsgSendType" BO_ 369 1; +BA_ "NetworkInitialization" BO_ 369 0; +BA_ "GenMsgNrOfRepetition" BO_ 369 0; +BA_ "GenSigCmt" SG_ 369 CAN_DET_TIME_SINCE_MEAS "CAN_DET_TIME_SINCE_MEAS"; +BA_ "GenSigSendType" SG_ 369 CAN_DET_TIME_SINCE_MEAS 0; +BA_ "GenSigSendType" SG_ 369 CAN_SENSOR_TIME_STAMP 0; +BA_ "GenSigCmt" SG_ 369 CAN_SENSOR_TIME_STAMP "CAN_SENSOR_TIME_STAMP"; +BA_ "GenMsgSendType" BO_ 368 1; +BA_ "NetworkInitialization" BO_ 368 0; +BA_ "GenMsgNrOfRepetition" BO_ 368 0; +BA_ "GenSigSendType" SG_ 368 CAN_ALIGN_UPDATES_DONE 0; +BA_ "GenSigCmt" SG_ 368 CAN_ALIGN_UPDATES_DONE "CAN_ALIGN_UPDATES_DONE"; +BA_ "GenSigSendType" SG_ 368 CAN_SCAN_INDEX 0; +BA_ "GenSigCmt" SG_ 368 CAN_SCAN_INDEX "CAN_SCAN_INDEX"; +BA_ "GenSigSendType" SG_ 368 CAN_NUMBER_OF_DET 0; +BA_ "GenSigCmt" SG_ 368 CAN_NUMBER_OF_DET "CAN_NUMBER_OF_DET"; +BA_ "GenSigSendType" SG_ 368 CAN_LOOK_ID 0; +BA_ "GenSigCmt" SG_ 368 CAN_LOOK_ID "CAN_LOOK_ID"; +BA_ "GenSigSendType" SG_ 368 CAN_LOOK_INDEX 0; +BA_ "GenSigCmt" SG_ 368 CAN_LOOK_INDEX "CAN_LOOK_INDEX"; +BA_ "GenMsgSendType" BO_ 265 1; +BA_ "NetworkInitialization" BO_ 265 0; +BA_ "GenMsgNrOfRepetition" BO_ 265 0; +BA_ "GenSigCmt" SG_ 265 CAN_BATT_VOLTS "CAN_BATT_VOLTS"; +BA_ "GenSigCmt" SG_ 265 CAN_1_25_V "CAN_1_25_V"; +BA_ "GenSigCmt" SG_ 265 CAN_5_V "CAN_5_V"; +BA_ "GenSigCmt" SG_ 265 CAN_3_3_V_RAW "CAN_3_3_V_RAW"; +BA_ "GenSigCmt" SG_ 265 CAN_3_3_V_DAC "CAN_3_3_V_DAC"; +BA_ "GenSigSendType" SG_ 265 CAN_MMIC_Temp1 0; +BA_ "GenSigCmt" SG_ 265 CAN_MMIC_Temp1 "CAN_MMIC_Temp1"; +BA_ "GenSigStartValue" SG_ 265 CAN_MMIC_Temp1 0; +BA_ "GenSigSendType" SG_ 265 CAN_Processor_Thermistor 0; +BA_ "GenSigCmt" SG_ 265 CAN_Processor_Thermistor "CAN_Processor_Thermistor"; +BA_ "GenSigStartValue" SG_ 265 CAN_Processor_Thermistor 0; +BA_ "GenSigSendType" SG_ 265 CAN_Processor_Temp1 0; +BA_ "GenSigCmt" SG_ 265 CAN_Processor_Temp1 "CAN_Processor_Temp1"; +BA_ "GenSigStartValue" SG_ 265 CAN_Processor_Temp1 0; +BA_ "GenMsgSendType" BO_ 291 1; +BA_ "GenMsgILSupport" BO_ 291 1; +BA_ "GenMsgNrOfRepetition" BO_ 291 0; +BA_ "GenMsgCycleTime" BO_ 291 0; +BA_ "NetworkInitialization" BO_ 291 0; +BA_ "GenMsgDelayTime" BO_ 291 0; +BA_ "GenSigVtEn" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_01 "CAN_DET_CONFID_AZIMUTH_04_01"; +BA_ "GenSigVtName" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_01 "CAN_DET_CONFID_AZIMUTH_04_01"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_01 "CAN_DET_CONFID_AZIMUTH_04_01"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_01 "CAN_DET_SUPER_RES_TARGET_04_01"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_ND_TARGET_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_ND_TARGET_04_01 "CAN_DET_ND_TARGET_04_01"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_01 "CAN_DET_HOST_VEH_CLUTTER_04_01"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_VALID_LEVEL_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_VALID_LEVEL_04_01 "CAN_DET_VALID_LEVEL_04_01"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_AZIMUTH_04_01 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AZIMUTH_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AZIMUTH_04_01 "CAN_DET_AZIMUTH_04_01"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_04_01 "CAN_DET_RANGE_04_01"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_RANGE_RATE_04_01 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_RATE_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_RATE_04_01 "CAN_DET_RANGE_RATE_04_01"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AMPLITUDE_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AMPLITUDE_04_01 "CAN_DET_AMPLITUDE_04_01"; +BA_ "GenSigSendType" SG_ 291 CAN_SCAN_INDEX_2LSB_04_01 0; +BA_ "GenSigCmt" SG_ 291 CAN_SCAN_INDEX_2LSB_04_01 "CAN_SCAN_INDEX_2LSB_04_01"; +BA_ "GenSigVtEn" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_02 "CAN_DET_CONFID_AZIMUTH_04_02"; +BA_ "GenSigVtName" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_02 "CAN_DET_CONFID_AZIMUTH_04_02"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_02 "CAN_DET_CONFID_AZIMUTH_04_02"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_02 "CAN_DET_SUPER_RES_TARGET_04_02"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_ND_TARGET_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_ND_TARGET_04_02 "CAN_DET_ND_TARGET_04_02"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_02 "CAN_DET_HOST_VEH_CLUTTER_04_02"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_VALID_LEVEL_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_VALID_LEVEL_04_02 "CAN_DET_VALID_LEVEL_04_02"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_AZIMUTH_04_02 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AZIMUTH_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AZIMUTH_04_02 "CAN_DET_AZIMUTH_04_02"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_04_02 "CAN_DET_RANGE_04_02"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_RANGE_RATE_04_02 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_RATE_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_RATE_04_02 "CAN_DET_RANGE_RATE_04_02"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AMPLITUDE_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AMPLITUDE_04_02 "CAN_DET_AMPLITUDE_04_02"; +BA_ "GenSigSendType" SG_ 291 CAN_SCAN_INDEX_2LSB_04_02 0; +BA_ "GenSigCmt" SG_ 291 CAN_SCAN_INDEX_2LSB_04_02 "CAN_SCAN_INDEX_2LSB_04_02"; +BA_ "GenSigVtEn" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_03 "CAN_DET_CONFID_AZIMUTH_04_03"; +BA_ "GenSigVtName" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_03 "CAN_DET_CONFID_AZIMUTH_04_03"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_03 "CAN_DET_CONFID_AZIMUTH_04_03"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_03 "CAN_DET_SUPER_RES_TARGET_04_03"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_ND_TARGET_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_ND_TARGET_04_03 "CAN_DET_ND_TARGET_04_03"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_03 "CAN_DET_HOST_VEH_CLUTTER_04_03"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_VALID_LEVEL_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_VALID_LEVEL_04_03 "CAN_DET_VALID_LEVEL_04_03"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_AZIMUTH_04_03 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AZIMUTH_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AZIMUTH_04_03 "CAN_DET_AZIMUTH_04_03"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_04_03 "CAN_DET_RANGE_04_03"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_RANGE_RATE_04_03 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_RATE_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_RATE_04_03 "CAN_DET_RANGE_RATE_04_03"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AMPLITUDE_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AMPLITUDE_04_03 "CAN_DET_AMPLITUDE_04_03"; +BA_ "GenSigSendType" SG_ 291 CAN_SCAN_INDEX_2LSB_04_03 0; +BA_ "GenSigCmt" SG_ 291 CAN_SCAN_INDEX_2LSB_04_03 "CAN_SCAN_INDEX_2LSB_04_03"; +BA_ "GenSigVtEn" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_04 "CAN_DET_CONFID_AZIMUTH_04_04"; +BA_ "GenSigVtName" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_04 "CAN_DET_CONFID_AZIMUTH_04_04"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_04 "CAN_DET_CONFID_AZIMUTH_04_04"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_04 "CAN_DET_SUPER_RES_TARGET_04_04"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_ND_TARGET_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_ND_TARGET_04_04 "CAN_DET_ND_TARGET_04_04"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_04 "CAN_DET_HOST_VEH_CLUTTER_04_04"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_VALID_LEVEL_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_VALID_LEVEL_04_04 "CAN_DET_VALID_LEVEL_04_04"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_AZIMUTH_04_04 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AZIMUTH_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AZIMUTH_04_04 "CAN_DET_AZIMUTH_04_04"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_04_04 "CAN_DET_RANGE_04_04"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_RANGE_RATE_04_04 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_RATE_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_RATE_04_04 "CAN_DET_RANGE_RATE_04_04"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AMPLITUDE_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AMPLITUDE_04_04 "CAN_DET_AMPLITUDE_04_04"; +BA_ "GenSigSendType" SG_ 291 CAN_SCAN_INDEX_2LSB_04_04 0; +BA_ "GenSigCmt" SG_ 291 CAN_SCAN_INDEX_2LSB_04_04 "CAN_SCAN_INDEX_2LSB_04_04"; +BA_ "GenSigVtEn" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_05 "CAN_DET_CONFID_AZIMUTH_04_05"; +BA_ "GenSigVtName" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_05 "CAN_DET_CONFID_AZIMUTH_04_05"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_05 "CAN_DET_CONFID_AZIMUTH_04_05"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_05 "CAN_DET_SUPER_RES_TARGET_04_05"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_ND_TARGET_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_ND_TARGET_04_05 "CAN_DET_ND_TARGET_04_05"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_05 "CAN_DET_HOST_VEH_CLUTTER_04_05"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_VALID_LEVEL_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_VALID_LEVEL_04_05 "CAN_DET_VALID_LEVEL_04_05"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_AZIMUTH_04_05 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AZIMUTH_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AZIMUTH_04_05 "CAN_DET_AZIMUTH_04_05"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_04_05 "CAN_DET_RANGE_04_05"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_RANGE_RATE_04_05 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_RATE_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_RATE_04_05 "CAN_DET_RANGE_RATE_04_05"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AMPLITUDE_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AMPLITUDE_04_05 "CAN_DET_AMPLITUDE_04_05"; +BA_ "GenSigSendType" SG_ 291 CAN_SCAN_INDEX_2LSB_04_05 0; +BA_ "GenSigCmt" SG_ 291 CAN_SCAN_INDEX_2LSB_04_05 "CAN_SCAN_INDEX_2LSB_04_05"; +BA_ "GenSigVtEn" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_06 "CAN_DET_CONFID_AZIMUTH_04_06"; +BA_ "GenSigVtName" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_06 "CAN_DET_CONFID_AZIMUTH_04_06"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_CONFID_AZIMUTH_04_06 "CAN_DET_CONFID_AZIMUTH_04_06"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_SUPER_RES_TARGET_04_06 "CAN_DET_SUPER_RES_TARGET_04_06"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_ND_TARGET_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_ND_TARGET_04_06 "CAN_DET_ND_TARGET_04_06"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_HOST_VEH_CLUTTER_04_06 "CAN_DET_HOST_VEH_CLUTTER_04_06"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_VALID_LEVEL_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_VALID_LEVEL_04_06 "CAN_DET_VALID_LEVEL_04_06"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_AZIMUTH_04_06 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AZIMUTH_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AZIMUTH_04_06 "CAN_DET_AZIMUTH_04_06"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_04_06 "CAN_DET_RANGE_04_06"; +BA_ "GenSigStartValue" SG_ 291 CAN_DET_RANGE_RATE_04_06 0; +BA_ "GenSigSendType" SG_ 291 CAN_DET_RANGE_RATE_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_RANGE_RATE_04_06 "CAN_DET_RANGE_RATE_04_06"; +BA_ "GenSigSendType" SG_ 291 CAN_DET_AMPLITUDE_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_DET_AMPLITUDE_04_06 "CAN_DET_AMPLITUDE_04_06"; +BA_ "GenSigSendType" SG_ 291 CAN_SCAN_INDEX_2LSB_04_06 0; +BA_ "GenSigCmt" SG_ 291 CAN_SCAN_INDEX_2LSB_04_06 "CAN_SCAN_INDEX_2LSB_04_06"; +BA_ "GenMsgSendType" BO_ 351 1; +BA_ "GenMsgILSupport" BO_ 351 1; +BA_ "GenMsgNrOfRepetition" BO_ 351 0; +BA_ "GenMsgCycleTime" BO_ 351 0; +BA_ "NetworkInitialization" BO_ 351 0; +BA_ "GenMsgDelayTime" BO_ 351 0; +BA_ "GenSigVtEn" SG_ 351 CAN_DET_CONFID_AZIMUTH_64 "CAN_DET_CONFID_AZIMUTH_64"; +BA_ "GenSigVtName" SG_ 351 CAN_DET_CONFID_AZIMUTH_64 "CAN_DET_CONFID_AZIMUTH_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_CONFID_AZIMUTH_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_CONFID_AZIMUTH_64 "CAN_DET_CONFID_AZIMUTH_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_SUPER_RES_TARGET_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_SUPER_RES_TARGET_64 "CAN_DET_SUPER_RES_TARGET_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_ND_TARGET_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_ND_TARGET_64 "CAN_DET_ND_TARGET_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_HOST_VEH_CLUTTER_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_HOST_VEH_CLUTTER_64 "CAN_DET_HOST_VEH_CLUTTER_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_VALID_LEVEL_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_VALID_LEVEL_64 "CAN_DET_VALID_LEVEL_64"; +BA_ "GenSigStartValue" SG_ 351 CAN_DET_AZIMUTH_64 0; +BA_ "GenSigSendType" SG_ 351 CAN_DET_AZIMUTH_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_AZIMUTH_64 "CAN_DET_AZIMUTH_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_RANGE_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_RANGE_64 "CAN_DET_RANGE_64"; +BA_ "GenSigStartValue" SG_ 351 CAN_DET_RANGE_RATE_64 0; +BA_ "GenSigSendType" SG_ 351 CAN_DET_RANGE_RATE_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_RANGE_RATE_64 "CAN_DET_RANGE_RATE_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_AMPLITUDE_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_AMPLITUDE_64 "CAN_DET_AMPLITUDE_64"; +BA_ "GenSigSendType" SG_ 351 CAN_SCAN_INDEX_2LSB_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_SCAN_INDEX_2LSB_64 "CAN_SCAN_INDEX_2LSB_64"; +BA_ "GenMsgSendType" BO_ 350 1; +BA_ "GenMsgILSupport" BO_ 350 1; +BA_ "GenMsgNrOfRepetition" BO_ 350 0; +BA_ "GenMsgCycleTime" BO_ 350 0; +BA_ "NetworkInitialization" BO_ 350 0; +BA_ "GenMsgDelayTime" BO_ 350 0; +BA_ "GenSigVtEn" SG_ 350 CAN_DET_CONFID_AZIMUTH_63 "CAN_DET_CONFID_AZIMUTH_63"; +BA_ "GenSigVtName" SG_ 350 CAN_DET_CONFID_AZIMUTH_63 "CAN_DET_CONFID_AZIMUTH_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_CONFID_AZIMUTH_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_CONFID_AZIMUTH_63 "CAN_DET_CONFID_AZIMUTH_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_SUPER_RES_TARGET_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_SUPER_RES_TARGET_63 "CAN_DET_SUPER_RES_TARGET_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_ND_TARGET_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_ND_TARGET_63 "CAN_DET_ND_TARGET_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_HOST_VEH_CLUTTER_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_HOST_VEH_CLUTTER_63 "CAN_DET_HOST_VEH_CLUTTER_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_VALID_LEVEL_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_VALID_LEVEL_63 "CAN_DET_VALID_LEVEL_63"; +BA_ "GenSigStartValue" SG_ 350 CAN_DET_AZIMUTH_63 0; +BA_ "GenSigSendType" SG_ 350 CAN_DET_AZIMUTH_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_AZIMUTH_63 "CAN_DET_AZIMUTH_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_RANGE_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_RANGE_63 "CAN_DET_RANGE_63"; +BA_ "GenSigStartValue" SG_ 350 CAN_DET_RANGE_RATE_63 0; +BA_ "GenSigSendType" SG_ 350 CAN_DET_RANGE_RATE_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_RANGE_RATE_63 "CAN_DET_RANGE_RATE_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_AMPLITUDE_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_AMPLITUDE_63 "CAN_DET_AMPLITUDE_63"; +BA_ "GenSigSendType" SG_ 350 CAN_SCAN_INDEX_2LSB_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_SCAN_INDEX_2LSB_63 "CAN_SCAN_INDEX_2LSB_63"; +BA_ "GenMsgSendType" BO_ 349 1; +BA_ "GenMsgILSupport" BO_ 349 1; +BA_ "GenMsgNrOfRepetition" BO_ 349 0; +BA_ "GenMsgCycleTime" BO_ 349 0; +BA_ "NetworkInitialization" BO_ 349 0; +BA_ "GenMsgDelayTime" BO_ 349 0; +BA_ "GenSigVtEn" SG_ 349 CAN_DET_CONFID_AZIMUTH_62 "CAN_DET_CONFID_AZIMUTH_62"; +BA_ "GenSigVtName" SG_ 349 CAN_DET_CONFID_AZIMUTH_62 "CAN_DET_CONFID_AZIMUTH_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_CONFID_AZIMUTH_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_CONFID_AZIMUTH_62 "CAN_DET_CONFID_AZIMUTH_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_SUPER_RES_TARGET_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_SUPER_RES_TARGET_62 "CAN_DET_SUPER_RES_TARGET_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_ND_TARGET_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_ND_TARGET_62 "CAN_DET_ND_TARGET_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_HOST_VEH_CLUTTER_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_HOST_VEH_CLUTTER_62 "CAN_DET_HOST_VEH_CLUTTER_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_VALID_LEVEL_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_VALID_LEVEL_62 "CAN_DET_VALID_LEVEL_62"; +BA_ "GenSigStartValue" SG_ 349 CAN_DET_AZIMUTH_62 0; +BA_ "GenSigSendType" SG_ 349 CAN_DET_AZIMUTH_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_AZIMUTH_62 "CAN_DET_AZIMUTH_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_RANGE_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_RANGE_62 "CAN_DET_RANGE_62"; +BA_ "GenSigStartValue" SG_ 349 CAN_DET_RANGE_RATE_62 0; +BA_ "GenSigSendType" SG_ 349 CAN_DET_RANGE_RATE_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_RANGE_RATE_62 "CAN_DET_RANGE_RATE_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_AMPLITUDE_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_AMPLITUDE_62 "CAN_DET_AMPLITUDE_62"; +BA_ "GenSigSendType" SG_ 349 CAN_SCAN_INDEX_2LSB_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_SCAN_INDEX_2LSB_62 "CAN_SCAN_INDEX_2LSB_62"; +BA_ "GenMsgSendType" BO_ 348 1; +BA_ "GenMsgILSupport" BO_ 348 1; +BA_ "GenMsgNrOfRepetition" BO_ 348 0; +BA_ "GenMsgCycleTime" BO_ 348 0; +BA_ "NetworkInitialization" BO_ 348 0; +BA_ "GenMsgDelayTime" BO_ 348 0; +BA_ "GenSigVtEn" SG_ 348 CAN_DET_CONFID_AZIMUTH_61 "CAN_DET_CONFID_AZIMUTH_61"; +BA_ "GenSigVtName" SG_ 348 CAN_DET_CONFID_AZIMUTH_61 "CAN_DET_CONFID_AZIMUTH_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_CONFID_AZIMUTH_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_CONFID_AZIMUTH_61 "CAN_DET_CONFID_AZIMUTH_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_SUPER_RES_TARGET_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_SUPER_RES_TARGET_61 "CAN_DET_SUPER_RES_TARGET_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_ND_TARGET_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_ND_TARGET_61 "CAN_DET_ND_TARGET_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_HOST_VEH_CLUTTER_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_HOST_VEH_CLUTTER_61 "CAN_DET_HOST_VEH_CLUTTER_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_VALID_LEVEL_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_VALID_LEVEL_61 "CAN_DET_VALID_LEVEL_61"; +BA_ "GenSigStartValue" SG_ 348 CAN_DET_AZIMUTH_61 0; +BA_ "GenSigSendType" SG_ 348 CAN_DET_AZIMUTH_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_AZIMUTH_61 "CAN_DET_AZIMUTH_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_RANGE_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_RANGE_61 "CAN_DET_RANGE_61"; +BA_ "GenSigStartValue" SG_ 348 CAN_DET_RANGE_RATE_61 0; +BA_ "GenSigSendType" SG_ 348 CAN_DET_RANGE_RATE_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_RANGE_RATE_61 "CAN_DET_RANGE_RATE_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_AMPLITUDE_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_AMPLITUDE_61 "CAN_DET_AMPLITUDE_61"; +BA_ "GenSigSendType" SG_ 348 CAN_SCAN_INDEX_2LSB_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_SCAN_INDEX_2LSB_61 "CAN_SCAN_INDEX_2LSB_61"; +BA_ "GenMsgSendType" BO_ 347 1; +BA_ "GenMsgILSupport" BO_ 347 1; +BA_ "GenMsgNrOfRepetition" BO_ 347 0; +BA_ "GenMsgCycleTime" BO_ 347 0; +BA_ "NetworkInitialization" BO_ 347 0; +BA_ "GenMsgDelayTime" BO_ 347 0; +BA_ "GenSigVtEn" SG_ 347 CAN_DET_CONFID_AZIMUTH_60 "CAN_DET_CONFID_AZIMUTH_60"; +BA_ "GenSigVtName" SG_ 347 CAN_DET_CONFID_AZIMUTH_60 "CAN_DET_CONFID_AZIMUTH_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_CONFID_AZIMUTH_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_CONFID_AZIMUTH_60 "CAN_DET_CONFID_AZIMUTH_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_SUPER_RES_TARGET_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_SUPER_RES_TARGET_60 "CAN_DET_SUPER_RES_TARGET_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_ND_TARGET_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_ND_TARGET_60 "CAN_DET_ND_TARGET_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_HOST_VEH_CLUTTER_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_HOST_VEH_CLUTTER_60 "CAN_DET_HOST_VEH_CLUTTER_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_VALID_LEVEL_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_VALID_LEVEL_60 "CAN_DET_VALID_LEVEL_60"; +BA_ "GenSigStartValue" SG_ 347 CAN_DET_AZIMUTH_60 0; +BA_ "GenSigSendType" SG_ 347 CAN_DET_AZIMUTH_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_AZIMUTH_60 "CAN_DET_AZIMUTH_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_RANGE_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_RANGE_60 "CAN_DET_RANGE_60"; +BA_ "GenSigStartValue" SG_ 347 CAN_DET_RANGE_RATE_60 0; +BA_ "GenSigSendType" SG_ 347 CAN_DET_RANGE_RATE_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_RANGE_RATE_60 "CAN_DET_RANGE_RATE_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_AMPLITUDE_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_AMPLITUDE_60 "CAN_DET_AMPLITUDE_60"; +BA_ "GenSigSendType" SG_ 347 CAN_SCAN_INDEX_2LSB_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_SCAN_INDEX_2LSB_60 "CAN_SCAN_INDEX_2LSB_60"; +BA_ "GenMsgSendType" BO_ 346 1; +BA_ "GenMsgILSupport" BO_ 346 1; +BA_ "GenMsgNrOfRepetition" BO_ 346 0; +BA_ "GenMsgCycleTime" BO_ 346 0; +BA_ "NetworkInitialization" BO_ 346 0; +BA_ "GenMsgDelayTime" BO_ 346 0; +BA_ "GenSigVtEn" SG_ 346 CAN_DET_CONFID_AZIMUTH_59 "CAN_DET_CONFID_AZIMUTH_59"; +BA_ "GenSigVtName" SG_ 346 CAN_DET_CONFID_AZIMUTH_59 "CAN_DET_CONFID_AZIMUTH_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_CONFID_AZIMUTH_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_CONFID_AZIMUTH_59 "CAN_DET_CONFID_AZIMUTH_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_SUPER_RES_TARGET_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_SUPER_RES_TARGET_59 "CAN_DET_SUPER_RES_TARGET_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_ND_TARGET_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_ND_TARGET_59 "CAN_DET_ND_TARGET_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_HOST_VEH_CLUTTER_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_HOST_VEH_CLUTTER_59 "CAN_DET_HOST_VEH_CLUTTER_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_VALID_LEVEL_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_VALID_LEVEL_59 "CAN_DET_VALID_LEVEL_59"; +BA_ "GenSigStartValue" SG_ 346 CAN_DET_AZIMUTH_59 0; +BA_ "GenSigSendType" SG_ 346 CAN_DET_AZIMUTH_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_AZIMUTH_59 "CAN_DET_AZIMUTH_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_RANGE_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_RANGE_59 "CAN_DET_RANGE_59"; +BA_ "GenSigStartValue" SG_ 346 CAN_DET_RANGE_RATE_59 0; +BA_ "GenSigSendType" SG_ 346 CAN_DET_RANGE_RATE_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_RANGE_RATE_59 "CAN_DET_RANGE_RATE_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_AMPLITUDE_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_AMPLITUDE_59 "CAN_DET_AMPLITUDE_59"; +BA_ "GenSigSendType" SG_ 346 CAN_SCAN_INDEX_2LSB_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_SCAN_INDEX_2LSB_59 "CAN_SCAN_INDEX_2LSB_59"; +BA_ "GenMsgSendType" BO_ 345 1; +BA_ "GenMsgILSupport" BO_ 345 1; +BA_ "GenMsgNrOfRepetition" BO_ 345 0; +BA_ "GenMsgCycleTime" BO_ 345 0; +BA_ "NetworkInitialization" BO_ 345 0; +BA_ "GenMsgDelayTime" BO_ 345 0; +BA_ "GenSigVtEn" SG_ 345 CAN_DET_CONFID_AZIMUTH_58 "CAN_DET_CONFID_AZIMUTH_58"; +BA_ "GenSigVtName" SG_ 345 CAN_DET_CONFID_AZIMUTH_58 "CAN_DET_CONFID_AZIMUTH_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_CONFID_AZIMUTH_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_CONFID_AZIMUTH_58 "CAN_DET_CONFID_AZIMUTH_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_SUPER_RES_TARGET_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_SUPER_RES_TARGET_58 "CAN_DET_SUPER_RES_TARGET_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_ND_TARGET_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_ND_TARGET_58 "CAN_DET_ND_TARGET_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_HOST_VEH_CLUTTER_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_HOST_VEH_CLUTTER_58 "CAN_DET_HOST_VEH_CLUTTER_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_VALID_LEVEL_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_VALID_LEVEL_58 "CAN_DET_VALID_LEVEL_58"; +BA_ "GenSigStartValue" SG_ 345 CAN_DET_AZIMUTH_58 0; +BA_ "GenSigSendType" SG_ 345 CAN_DET_AZIMUTH_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_AZIMUTH_58 "CAN_DET_AZIMUTH_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_RANGE_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_RANGE_58 "CAN_DET_RANGE_58"; +BA_ "GenSigStartValue" SG_ 345 CAN_DET_RANGE_RATE_58 0; +BA_ "GenSigSendType" SG_ 345 CAN_DET_RANGE_RATE_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_RANGE_RATE_58 "CAN_DET_RANGE_RATE_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_AMPLITUDE_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_AMPLITUDE_58 "CAN_DET_AMPLITUDE_58"; +BA_ "GenSigSendType" SG_ 345 CAN_SCAN_INDEX_2LSB_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_SCAN_INDEX_2LSB_58 "CAN_SCAN_INDEX_2LSB_58"; +BA_ "GenMsgSendType" BO_ 344 1; +BA_ "GenMsgILSupport" BO_ 344 1; +BA_ "GenMsgNrOfRepetition" BO_ 344 0; +BA_ "GenMsgCycleTime" BO_ 344 0; +BA_ "NetworkInitialization" BO_ 344 0; +BA_ "GenMsgDelayTime" BO_ 344 0; +BA_ "GenSigVtEn" SG_ 344 CAN_DET_CONFID_AZIMUTH_57 "CAN_DET_CONFID_AZIMUTH_57"; +BA_ "GenSigVtName" SG_ 344 CAN_DET_CONFID_AZIMUTH_57 "CAN_DET_CONFID_AZIMUTH_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_CONFID_AZIMUTH_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_CONFID_AZIMUTH_57 "CAN_DET_CONFID_AZIMUTH_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_SUPER_RES_TARGET_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_SUPER_RES_TARGET_57 "CAN_DET_SUPER_RES_TARGET_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_ND_TARGET_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_ND_TARGET_57 "CAN_DET_ND_TARGET_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_HOST_VEH_CLUTTER_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_HOST_VEH_CLUTTER_57 "CAN_DET_HOST_VEH_CLUTTER_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_VALID_LEVEL_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_VALID_LEVEL_57 "CAN_DET_VALID_LEVEL_57"; +BA_ "GenSigStartValue" SG_ 344 CAN_DET_AZIMUTH_57 0; +BA_ "GenSigSendType" SG_ 344 CAN_DET_AZIMUTH_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_AZIMUTH_57 "CAN_DET_AZIMUTH_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_RANGE_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_RANGE_57 "CAN_DET_RANGE_57"; +BA_ "GenSigStartValue" SG_ 344 CAN_DET_RANGE_RATE_57 0; +BA_ "GenSigSendType" SG_ 344 CAN_DET_RANGE_RATE_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_RANGE_RATE_57 "CAN_DET_RANGE_RATE_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_AMPLITUDE_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_AMPLITUDE_57 "CAN_DET_AMPLITUDE_57"; +BA_ "GenSigSendType" SG_ 344 CAN_SCAN_INDEX_2LSB_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_SCAN_INDEX_2LSB_57 "CAN_SCAN_INDEX_2LSB_57"; +BA_ "GenMsgSendType" BO_ 343 1; +BA_ "GenMsgILSupport" BO_ 343 1; +BA_ "GenMsgNrOfRepetition" BO_ 343 0; +BA_ "GenMsgCycleTime" BO_ 343 0; +BA_ "NetworkInitialization" BO_ 343 0; +BA_ "GenMsgDelayTime" BO_ 343 0; +BA_ "GenSigVtEn" SG_ 343 CAN_DET_CONFID_AZIMUTH_56 "CAN_DET_CONFID_AZIMUTH_56"; +BA_ "GenSigVtName" SG_ 343 CAN_DET_CONFID_AZIMUTH_56 "CAN_DET_CONFID_AZIMUTH_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_CONFID_AZIMUTH_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_CONFID_AZIMUTH_56 "CAN_DET_CONFID_AZIMUTH_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_SUPER_RES_TARGET_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_SUPER_RES_TARGET_56 "CAN_DET_SUPER_RES_TARGET_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_ND_TARGET_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_ND_TARGET_56 "CAN_DET_ND_TARGET_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_HOST_VEH_CLUTTER_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_HOST_VEH_CLUTTER_56 "CAN_DET_HOST_VEH_CLUTTER_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_VALID_LEVEL_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_VALID_LEVEL_56 "CAN_DET_VALID_LEVEL_56"; +BA_ "GenSigStartValue" SG_ 343 CAN_DET_AZIMUTH_56 0; +BA_ "GenSigSendType" SG_ 343 CAN_DET_AZIMUTH_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_AZIMUTH_56 "CAN_DET_AZIMUTH_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_RANGE_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_RANGE_56 "CAN_DET_RANGE_56"; +BA_ "GenSigStartValue" SG_ 343 CAN_DET_RANGE_RATE_56 0; +BA_ "GenSigSendType" SG_ 343 CAN_DET_RANGE_RATE_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_RANGE_RATE_56 "CAN_DET_RANGE_RATE_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_AMPLITUDE_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_AMPLITUDE_56 "CAN_DET_AMPLITUDE_56"; +BA_ "GenSigSendType" SG_ 343 CAN_SCAN_INDEX_2LSB_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_SCAN_INDEX_2LSB_56 "CAN_SCAN_INDEX_2LSB_56"; +BA_ "GenMsgSendType" BO_ 342 1; +BA_ "GenMsgILSupport" BO_ 342 1; +BA_ "GenMsgNrOfRepetition" BO_ 342 0; +BA_ "GenMsgCycleTime" BO_ 342 0; +BA_ "NetworkInitialization" BO_ 342 0; +BA_ "GenMsgDelayTime" BO_ 342 0; +BA_ "GenSigVtEn" SG_ 342 CAN_DET_CONFID_AZIMUTH_55 "CAN_DET_CONFID_AZIMUTH_55"; +BA_ "GenSigVtName" SG_ 342 CAN_DET_CONFID_AZIMUTH_55 "CAN_DET_CONFID_AZIMUTH_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_CONFID_AZIMUTH_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_CONFID_AZIMUTH_55 "CAN_DET_CONFID_AZIMUTH_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_SUPER_RES_TARGET_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_SUPER_RES_TARGET_55 "CAN_DET_SUPER_RES_TARGET_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_ND_TARGET_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_ND_TARGET_55 "CAN_DET_ND_TARGET_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_HOST_VEH_CLUTTER_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_HOST_VEH_CLUTTER_55 "CAN_DET_HOST_VEH_CLUTTER_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_VALID_LEVEL_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_VALID_LEVEL_55 "CAN_DET_VALID_LEVEL_55"; +BA_ "GenSigStartValue" SG_ 342 CAN_DET_AZIMUTH_55 0; +BA_ "GenSigSendType" SG_ 342 CAN_DET_AZIMUTH_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_AZIMUTH_55 "CAN_DET_AZIMUTH_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_RANGE_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_RANGE_55 "CAN_DET_RANGE_55"; +BA_ "GenSigStartValue" SG_ 342 CAN_DET_RANGE_RATE_55 0; +BA_ "GenSigSendType" SG_ 342 CAN_DET_RANGE_RATE_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_RANGE_RATE_55 "CAN_DET_RANGE_RATE_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_AMPLITUDE_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_AMPLITUDE_55 "CAN_DET_AMPLITUDE_55"; +BA_ "GenSigSendType" SG_ 342 CAN_SCAN_INDEX_2LSB_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_SCAN_INDEX_2LSB_55 "CAN_SCAN_INDEX_2LSB_55"; +BA_ "GenMsgSendType" BO_ 335 1; +BA_ "GenMsgILSupport" BO_ 335 1; +BA_ "GenMsgNrOfRepetition" BO_ 335 0; +BA_ "GenMsgCycleTime" BO_ 335 0; +BA_ "NetworkInitialization" BO_ 335 0; +BA_ "GenMsgDelayTime" BO_ 335 0; +BA_ "GenSigVtEn" SG_ 335 CAN_DET_CONFID_AZIMUTH_48 "CAN_DET_CONFID_AZIMUTH_48"; +BA_ "GenSigVtName" SG_ 335 CAN_DET_CONFID_AZIMUTH_48 "CAN_DET_CONFID_AZIMUTH_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_CONFID_AZIMUTH_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_CONFID_AZIMUTH_48 "CAN_DET_CONFID_AZIMUTH_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_SUPER_RES_TARGET_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_SUPER_RES_TARGET_48 "CAN_DET_SUPER_RES_TARGET_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_ND_TARGET_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_ND_TARGET_48 "CAN_DET_ND_TARGET_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_HOST_VEH_CLUTTER_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_HOST_VEH_CLUTTER_48 "CAN_DET_HOST_VEH_CLUTTER_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_VALID_LEVEL_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_VALID_LEVEL_48 "CAN_DET_VALID_LEVEL_48"; +BA_ "GenSigStartValue" SG_ 335 CAN_DET_AZIMUTH_48 0; +BA_ "GenSigSendType" SG_ 335 CAN_DET_AZIMUTH_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_AZIMUTH_48 "CAN_DET_AZIMUTH_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_RANGE_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_RANGE_48 "CAN_DET_RANGE_48"; +BA_ "GenSigStartValue" SG_ 335 CAN_DET_RANGE_RATE_48 0; +BA_ "GenSigSendType" SG_ 335 CAN_DET_RANGE_RATE_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_RANGE_RATE_48 "CAN_DET_RANGE_RATE_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_AMPLITUDE_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_AMPLITUDE_48 "CAN_DET_AMPLITUDE_48"; +BA_ "GenSigSendType" SG_ 335 CAN_SCAN_INDEX_2LSB_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_SCAN_INDEX_2LSB_48 "CAN_SCAN_INDEX_2LSB_48"; +BA_ "GenMsgSendType" BO_ 334 1; +BA_ "GenMsgILSupport" BO_ 334 1; +BA_ "GenMsgNrOfRepetition" BO_ 334 0; +BA_ "GenMsgCycleTime" BO_ 334 0; +BA_ "NetworkInitialization" BO_ 334 0; +BA_ "GenMsgDelayTime" BO_ 334 0; +BA_ "GenSigVtEn" SG_ 334 CAN_DET_CONFID_AZIMUTH_47 "CAN_DET_CONFID_AZIMUTH_47"; +BA_ "GenSigVtName" SG_ 334 CAN_DET_CONFID_AZIMUTH_47 "CAN_DET_CONFID_AZIMUTH_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_CONFID_AZIMUTH_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_CONFID_AZIMUTH_47 "CAN_DET_CONFID_AZIMUTH_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_SUPER_RES_TARGET_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_SUPER_RES_TARGET_47 "CAN_DET_SUPER_RES_TARGET_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_ND_TARGET_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_ND_TARGET_47 "CAN_DET_ND_TARGET_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_HOST_VEH_CLUTTER_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_HOST_VEH_CLUTTER_47 "CAN_DET_HOST_VEH_CLUTTER_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_VALID_LEVEL_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_VALID_LEVEL_47 "CAN_DET_VALID_LEVEL_47"; +BA_ "GenSigStartValue" SG_ 334 CAN_DET_AZIMUTH_47 0; +BA_ "GenSigSendType" SG_ 334 CAN_DET_AZIMUTH_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_AZIMUTH_47 "CAN_DET_AZIMUTH_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_RANGE_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_RANGE_47 "CAN_DET_RANGE_47"; +BA_ "GenSigStartValue" SG_ 334 CAN_DET_RANGE_RATE_47 0; +BA_ "GenSigSendType" SG_ 334 CAN_DET_RANGE_RATE_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_RANGE_RATE_47 "CAN_DET_RANGE_RATE_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_AMPLITUDE_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_AMPLITUDE_47 "CAN_DET_AMPLITUDE_47"; +BA_ "GenSigSendType" SG_ 334 CAN_SCAN_INDEX_2LSB_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_SCAN_INDEX_2LSB_47 "CAN_SCAN_INDEX_2LSB_47"; +BA_ "GenMsgSendType" BO_ 333 1; +BA_ "GenMsgILSupport" BO_ 333 1; +BA_ "GenMsgNrOfRepetition" BO_ 333 0; +BA_ "GenMsgCycleTime" BO_ 333 0; +BA_ "NetworkInitialization" BO_ 333 0; +BA_ "GenMsgDelayTime" BO_ 333 0; +BA_ "GenSigVtEn" SG_ 333 CAN_DET_CONFID_AZIMUTH_46 "CAN_DET_CONFID_AZIMUTH_46"; +BA_ "GenSigVtName" SG_ 333 CAN_DET_CONFID_AZIMUTH_46 "CAN_DET_CONFID_AZIMUTH_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_CONFID_AZIMUTH_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_CONFID_AZIMUTH_46 "CAN_DET_CONFID_AZIMUTH_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_SUPER_RES_TARGET_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_SUPER_RES_TARGET_46 "CAN_DET_SUPER_RES_TARGET_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_ND_TARGET_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_ND_TARGET_46 "CAN_DET_ND_TARGET_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_HOST_VEH_CLUTTER_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_HOST_VEH_CLUTTER_46 "CAN_DET_HOST_VEH_CLUTTER_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_VALID_LEVEL_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_VALID_LEVEL_46 "CAN_DET_VALID_LEVEL_46"; +BA_ "GenSigStartValue" SG_ 333 CAN_DET_AZIMUTH_46 0; +BA_ "GenSigSendType" SG_ 333 CAN_DET_AZIMUTH_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_AZIMUTH_46 "CAN_DET_AZIMUTH_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_RANGE_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_RANGE_46 "CAN_DET_RANGE_46"; +BA_ "GenSigStartValue" SG_ 333 CAN_DET_RANGE_RATE_46 0; +BA_ "GenSigSendType" SG_ 333 CAN_DET_RANGE_RATE_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_RANGE_RATE_46 "CAN_DET_RANGE_RATE_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_AMPLITUDE_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_AMPLITUDE_46 "CAN_DET_AMPLITUDE_46"; +BA_ "GenSigSendType" SG_ 333 CAN_SCAN_INDEX_2LSB_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_SCAN_INDEX_2LSB_46 "CAN_SCAN_INDEX_2LSB_46"; +BA_ "GenMsgSendType" BO_ 332 1; +BA_ "GenMsgILSupport" BO_ 332 1; +BA_ "GenMsgNrOfRepetition" BO_ 332 0; +BA_ "GenMsgCycleTime" BO_ 332 0; +BA_ "NetworkInitialization" BO_ 332 0; +BA_ "GenMsgDelayTime" BO_ 332 0; +BA_ "GenSigVtEn" SG_ 332 CAN_DET_CONFID_AZIMUTH_45 "CAN_DET_CONFID_AZIMUTH_45"; +BA_ "GenSigVtName" SG_ 332 CAN_DET_CONFID_AZIMUTH_45 "CAN_DET_CONFID_AZIMUTH_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_CONFID_AZIMUTH_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_CONFID_AZIMUTH_45 "CAN_DET_CONFID_AZIMUTH_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_SUPER_RES_TARGET_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_SUPER_RES_TARGET_45 "CAN_DET_SUPER_RES_TARGET_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_ND_TARGET_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_ND_TARGET_45 "CAN_DET_ND_TARGET_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_HOST_VEH_CLUTTER_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_HOST_VEH_CLUTTER_45 "CAN_DET_HOST_VEH_CLUTTER_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_VALID_LEVEL_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_VALID_LEVEL_45 "CAN_DET_VALID_LEVEL_45"; +BA_ "GenSigStartValue" SG_ 332 CAN_DET_AZIMUTH_45 0; +BA_ "GenSigSendType" SG_ 332 CAN_DET_AZIMUTH_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_AZIMUTH_45 "CAN_DET_AZIMUTH_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_RANGE_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_RANGE_45 "CAN_DET_RANGE_45"; +BA_ "GenSigStartValue" SG_ 332 CAN_DET_RANGE_RATE_45 0; +BA_ "GenSigSendType" SG_ 332 CAN_DET_RANGE_RATE_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_RANGE_RATE_45 "CAN_DET_RANGE_RATE_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_AMPLITUDE_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_AMPLITUDE_45 "CAN_DET_AMPLITUDE_45"; +BA_ "GenSigSendType" SG_ 332 CAN_SCAN_INDEX_2LSB_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_SCAN_INDEX_2LSB_45 "CAN_SCAN_INDEX_2LSB_45"; +BA_ "GenMsgSendType" BO_ 331 1; +BA_ "GenMsgILSupport" BO_ 331 1; +BA_ "GenMsgNrOfRepetition" BO_ 331 0; +BA_ "GenMsgCycleTime" BO_ 331 0; +BA_ "NetworkInitialization" BO_ 331 0; +BA_ "GenMsgDelayTime" BO_ 331 0; +BA_ "GenSigVtEn" SG_ 331 CAN_DET_CONFID_AZIMUTH_44 "CAN_DET_CONFID_AZIMUTH_44"; +BA_ "GenSigVtName" SG_ 331 CAN_DET_CONFID_AZIMUTH_44 "CAN_DET_CONFID_AZIMUTH_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_CONFID_AZIMUTH_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_CONFID_AZIMUTH_44 "CAN_DET_CONFID_AZIMUTH_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_SUPER_RES_TARGET_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_SUPER_RES_TARGET_44 "CAN_DET_SUPER_RES_TARGET_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_ND_TARGET_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_ND_TARGET_44 "CAN_DET_ND_TARGET_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_HOST_VEH_CLUTTER_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_HOST_VEH_CLUTTER_44 "CAN_DET_HOST_VEH_CLUTTER_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_VALID_LEVEL_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_VALID_LEVEL_44 "CAN_DET_VALID_LEVEL_44"; +BA_ "GenSigStartValue" SG_ 331 CAN_DET_AZIMUTH_44 0; +BA_ "GenSigSendType" SG_ 331 CAN_DET_AZIMUTH_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_AZIMUTH_44 "CAN_DET_AZIMUTH_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_RANGE_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_RANGE_44 "CAN_DET_RANGE_44"; +BA_ "GenSigStartValue" SG_ 331 CAN_DET_RANGE_RATE_44 0; +BA_ "GenSigSendType" SG_ 331 CAN_DET_RANGE_RATE_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_RANGE_RATE_44 "CAN_DET_RANGE_RATE_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_AMPLITUDE_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_AMPLITUDE_44 "CAN_DET_AMPLITUDE_44"; +BA_ "GenSigSendType" SG_ 331 CAN_SCAN_INDEX_2LSB_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_SCAN_INDEX_2LSB_44 "CAN_SCAN_INDEX_2LSB_44"; +BA_ "GenMsgSendType" BO_ 330 1; +BA_ "GenMsgILSupport" BO_ 330 1; +BA_ "GenMsgNrOfRepetition" BO_ 330 0; +BA_ "GenMsgCycleTime" BO_ 330 0; +BA_ "NetworkInitialization" BO_ 330 0; +BA_ "GenMsgDelayTime" BO_ 330 0; +BA_ "GenSigVtEn" SG_ 330 CAN_DET_CONFID_AZIMUTH_43 "CAN_DET_CONFID_AZIMUTH_43"; +BA_ "GenSigVtName" SG_ 330 CAN_DET_CONFID_AZIMUTH_43 "CAN_DET_CONFID_AZIMUTH_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_CONFID_AZIMUTH_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_CONFID_AZIMUTH_43 "CAN_DET_CONFID_AZIMUTH_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_SUPER_RES_TARGET_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_SUPER_RES_TARGET_43 "CAN_DET_SUPER_RES_TARGET_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_ND_TARGET_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_ND_TARGET_43 "CAN_DET_ND_TARGET_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_HOST_VEH_CLUTTER_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_HOST_VEH_CLUTTER_43 "CAN_DET_HOST_VEH_CLUTTER_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_VALID_LEVEL_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_VALID_LEVEL_43 "CAN_DET_VALID_LEVEL_43"; +BA_ "GenSigStartValue" SG_ 330 CAN_DET_AZIMUTH_43 0; +BA_ "GenSigSendType" SG_ 330 CAN_DET_AZIMUTH_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_AZIMUTH_43 "CAN_DET_AZIMUTH_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_RANGE_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_RANGE_43 "CAN_DET_RANGE_43"; +BA_ "GenSigStartValue" SG_ 330 CAN_DET_RANGE_RATE_43 0; +BA_ "GenSigSendType" SG_ 330 CAN_DET_RANGE_RATE_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_RANGE_RATE_43 "CAN_DET_RANGE_RATE_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_AMPLITUDE_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_AMPLITUDE_43 "CAN_DET_AMPLITUDE_43"; +BA_ "GenSigSendType" SG_ 330 CAN_SCAN_INDEX_2LSB_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_SCAN_INDEX_2LSB_43 "CAN_SCAN_INDEX_2LSB_43"; +BA_ "GenMsgSendType" BO_ 329 1; +BA_ "GenMsgILSupport" BO_ 329 1; +BA_ "GenMsgNrOfRepetition" BO_ 329 0; +BA_ "GenMsgCycleTime" BO_ 329 0; +BA_ "NetworkInitialization" BO_ 329 0; +BA_ "GenMsgDelayTime" BO_ 329 0; +BA_ "GenSigVtEn" SG_ 329 CAN_DET_CONFID_AZIMUTH_42 "CAN_DET_CONFID_AZIMUTH_42"; +BA_ "GenSigVtName" SG_ 329 CAN_DET_CONFID_AZIMUTH_42 "CAN_DET_CONFID_AZIMUTH_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_CONFID_AZIMUTH_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_CONFID_AZIMUTH_42 "CAN_DET_CONFID_AZIMUTH_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_SUPER_RES_TARGET_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_SUPER_RES_TARGET_42 "CAN_DET_SUPER_RES_TARGET_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_ND_TARGET_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_ND_TARGET_42 "CAN_DET_ND_TARGET_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_HOST_VEH_CLUTTER_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_HOST_VEH_CLUTTER_42 "CAN_DET_HOST_VEH_CLUTTER_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_VALID_LEVEL_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_VALID_LEVEL_42 "CAN_DET_VALID_LEVEL_42"; +BA_ "GenSigStartValue" SG_ 329 CAN_DET_AZIMUTH_42 0; +BA_ "GenSigSendType" SG_ 329 CAN_DET_AZIMUTH_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_AZIMUTH_42 "CAN_DET_AZIMUTH_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_RANGE_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_RANGE_42 "CAN_DET_RANGE_42"; +BA_ "GenSigStartValue" SG_ 329 CAN_DET_RANGE_RATE_42 0; +BA_ "GenSigSendType" SG_ 329 CAN_DET_RANGE_RATE_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_RANGE_RATE_42 "CAN_DET_RANGE_RATE_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_AMPLITUDE_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_AMPLITUDE_42 "CAN_DET_AMPLITUDE_42"; +BA_ "GenSigSendType" SG_ 329 CAN_SCAN_INDEX_2LSB_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_SCAN_INDEX_2LSB_42 "CAN_SCAN_INDEX_2LSB_42"; +BA_ "GenMsgSendType" BO_ 328 1; +BA_ "GenMsgILSupport" BO_ 328 1; +BA_ "GenMsgNrOfRepetition" BO_ 328 0; +BA_ "GenMsgCycleTime" BO_ 328 0; +BA_ "NetworkInitialization" BO_ 328 0; +BA_ "GenMsgDelayTime" BO_ 328 0; +BA_ "GenSigVtEn" SG_ 328 CAN_DET_CONFID_AZIMUTH_41 "CAN_DET_CONFID_AZIMUTH_41"; +BA_ "GenSigVtName" SG_ 328 CAN_DET_CONFID_AZIMUTH_41 "CAN_DET_CONFID_AZIMUTH_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_CONFID_AZIMUTH_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_CONFID_AZIMUTH_41 "CAN_DET_CONFID_AZIMUTH_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_SUPER_RES_TARGET_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_SUPER_RES_TARGET_41 "CAN_DET_SUPER_RES_TARGET_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_ND_TARGET_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_ND_TARGET_41 "CAN_DET_ND_TARGET_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_HOST_VEH_CLUTTER_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_HOST_VEH_CLUTTER_41 "CAN_DET_HOST_VEH_CLUTTER_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_VALID_LEVEL_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_VALID_LEVEL_41 "CAN_DET_VALID_LEVEL_41"; +BA_ "GenSigStartValue" SG_ 328 CAN_DET_AZIMUTH_41 0; +BA_ "GenSigSendType" SG_ 328 CAN_DET_AZIMUTH_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_AZIMUTH_41 "CAN_DET_AZIMUTH_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_RANGE_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_RANGE_41 "CAN_DET_RANGE_41"; +BA_ "GenSigStartValue" SG_ 328 CAN_DET_RANGE_RATE_41 0; +BA_ "GenSigSendType" SG_ 328 CAN_DET_RANGE_RATE_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_RANGE_RATE_41 "CAN_DET_RANGE_RATE_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_AMPLITUDE_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_AMPLITUDE_41 "CAN_DET_AMPLITUDE_41"; +BA_ "GenSigSendType" SG_ 328 CAN_SCAN_INDEX_2LSB_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_SCAN_INDEX_2LSB_41 "CAN_SCAN_INDEX_2LSB_41"; +BA_ "GenMsgSendType" BO_ 327 1; +BA_ "GenMsgILSupport" BO_ 327 1; +BA_ "GenMsgNrOfRepetition" BO_ 327 0; +BA_ "GenMsgCycleTime" BO_ 327 0; +BA_ "NetworkInitialization" BO_ 327 0; +BA_ "GenMsgDelayTime" BO_ 327 0; +BA_ "GenSigVtEn" SG_ 327 CAN_DET_CONFID_AZIMUTH_40 "CAN_DET_CONFID_AZIMUTH_40"; +BA_ "GenSigVtName" SG_ 327 CAN_DET_CONFID_AZIMUTH_40 "CAN_DET_CONFID_AZIMUTH_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_CONFID_AZIMUTH_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_CONFID_AZIMUTH_40 "CAN_DET_CONFID_AZIMUTH_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_SUPER_RES_TARGET_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_SUPER_RES_TARGET_40 "CAN_DET_SUPER_RES_TARGET_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_ND_TARGET_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_ND_TARGET_40 "CAN_DET_ND_TARGET_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_HOST_VEH_CLUTTER_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_HOST_VEH_CLUTTER_40 "CAN_DET_HOST_VEH_CLUTTER_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_VALID_LEVEL_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_VALID_LEVEL_40 "CAN_DET_VALID_LEVEL_40"; +BA_ "GenSigStartValue" SG_ 327 CAN_DET_AZIMUTH_40 0; +BA_ "GenSigSendType" SG_ 327 CAN_DET_AZIMUTH_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_AZIMUTH_40 "CAN_DET_AZIMUTH_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_RANGE_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_RANGE_40 "CAN_DET_RANGE_40"; +BA_ "GenSigStartValue" SG_ 327 CAN_DET_RANGE_RATE_40 0; +BA_ "GenSigSendType" SG_ 327 CAN_DET_RANGE_RATE_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_RANGE_RATE_40 "CAN_DET_RANGE_RATE_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_AMPLITUDE_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_AMPLITUDE_40 "CAN_DET_AMPLITUDE_40"; +BA_ "GenSigSendType" SG_ 327 CAN_SCAN_INDEX_2LSB_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_SCAN_INDEX_2LSB_40 "CAN_SCAN_INDEX_2LSB_40"; +BA_ "GenMsgSendType" BO_ 325 1; +BA_ "GenMsgILSupport" BO_ 325 1; +BA_ "GenMsgNrOfRepetition" BO_ 325 0; +BA_ "GenMsgCycleTime" BO_ 325 0; +BA_ "NetworkInitialization" BO_ 325 0; +BA_ "GenMsgDelayTime" BO_ 325 0; +BA_ "GenSigVtEn" SG_ 325 CAN_DET_CONFID_AZIMUTH_38 "CAN_DET_CONFID_AZIMUTH_38"; +BA_ "GenSigVtName" SG_ 325 CAN_DET_CONFID_AZIMUTH_38 "CAN_DET_CONFID_AZIMUTH_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_CONFID_AZIMUTH_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_CONFID_AZIMUTH_38 "CAN_DET_CONFID_AZIMUTH_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_SUPER_RES_TARGET_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_SUPER_RES_TARGET_38 "CAN_DET_SUPER_RES_TARGET_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_ND_TARGET_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_ND_TARGET_38 "CAN_DET_ND_TARGET_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_HOST_VEH_CLUTTER_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_HOST_VEH_CLUTTER_38 "CAN_DET_HOST_VEH_CLUTTER_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_VALID_LEVEL_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_VALID_LEVEL_38 "CAN_DET_VALID_LEVEL_38"; +BA_ "GenSigStartValue" SG_ 325 CAN_DET_AZIMUTH_38 0; +BA_ "GenSigSendType" SG_ 325 CAN_DET_AZIMUTH_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_AZIMUTH_38 "CAN_DET_AZIMUTH_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_RANGE_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_RANGE_38 "CAN_DET_RANGE_38"; +BA_ "GenSigStartValue" SG_ 325 CAN_DET_RANGE_RATE_38 0; +BA_ "GenSigSendType" SG_ 325 CAN_DET_RANGE_RATE_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_RANGE_RATE_38 "CAN_DET_RANGE_RATE_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_AMPLITUDE_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_AMPLITUDE_38 "CAN_DET_AMPLITUDE_38"; +BA_ "GenSigSendType" SG_ 325 CAN_SCAN_INDEX_2LSB_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_SCAN_INDEX_2LSB_38 "CAN_SCAN_INDEX_2LSB_38"; +BA_ "GenMsgSendType" BO_ 324 1; +BA_ "GenMsgILSupport" BO_ 324 1; +BA_ "GenMsgNrOfRepetition" BO_ 324 0; +BA_ "GenMsgCycleTime" BO_ 324 0; +BA_ "NetworkInitialization" BO_ 324 0; +BA_ "GenMsgDelayTime" BO_ 324 0; +BA_ "GenSigVtEn" SG_ 324 CAN_DET_CONFID_AZIMUTH_37 "CAN_DET_CONFID_AZIMUTH_37"; +BA_ "GenSigVtName" SG_ 324 CAN_DET_CONFID_AZIMUTH_37 "CAN_DET_CONFID_AZIMUTH_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_CONFID_AZIMUTH_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_CONFID_AZIMUTH_37 "CAN_DET_CONFID_AZIMUTH_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_SUPER_RES_TARGET_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_SUPER_RES_TARGET_37 "CAN_DET_SUPER_RES_TARGET_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_ND_TARGET_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_ND_TARGET_37 "CAN_DET_ND_TARGET_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_HOST_VEH_CLUTTER_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_HOST_VEH_CLUTTER_37 "CAN_DET_HOST_VEH_CLUTTER_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_VALID_LEVEL_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_VALID_LEVEL_37 "CAN_DET_VALID_LEVEL_37"; +BA_ "GenSigStartValue" SG_ 324 CAN_DET_AZIMUTH_37 0; +BA_ "GenSigSendType" SG_ 324 CAN_DET_AZIMUTH_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_AZIMUTH_37 "CAN_DET_AZIMUTH_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_RANGE_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_RANGE_37 "CAN_DET_RANGE_37"; +BA_ "GenSigStartValue" SG_ 324 CAN_DET_RANGE_RATE_37 0; +BA_ "GenSigSendType" SG_ 324 CAN_DET_RANGE_RATE_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_RANGE_RATE_37 "CAN_DET_RANGE_RATE_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_AMPLITUDE_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_AMPLITUDE_37 "CAN_DET_AMPLITUDE_37"; +BA_ "GenSigSendType" SG_ 324 CAN_SCAN_INDEX_2LSB_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_SCAN_INDEX_2LSB_37 "CAN_SCAN_INDEX_2LSB_37"; +BA_ "GenMsgSendType" BO_ 323 1; +BA_ "GenMsgILSupport" BO_ 323 1; +BA_ "GenMsgNrOfRepetition" BO_ 323 0; +BA_ "GenMsgCycleTime" BO_ 323 0; +BA_ "NetworkInitialization" BO_ 323 0; +BA_ "GenMsgDelayTime" BO_ 323 0; +BA_ "GenSigVtEn" SG_ 323 CAN_DET_CONFID_AZIMUTH_36 "CAN_DET_CONFID_AZIMUTH_36"; +BA_ "GenSigVtName" SG_ 323 CAN_DET_CONFID_AZIMUTH_36 "CAN_DET_CONFID_AZIMUTH_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_CONFID_AZIMUTH_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_CONFID_AZIMUTH_36 "CAN_DET_CONFID_AZIMUTH_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_SUPER_RES_TARGET_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_SUPER_RES_TARGET_36 "CAN_DET_SUPER_RES_TARGET_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_ND_TARGET_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_ND_TARGET_36 "CAN_DET_ND_TARGET_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_HOST_VEH_CLUTTER_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_HOST_VEH_CLUTTER_36 "CAN_DET_HOST_VEH_CLUTTER_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_VALID_LEVEL_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_VALID_LEVEL_36 "CAN_DET_VALID_LEVEL_36"; +BA_ "GenSigStartValue" SG_ 323 CAN_DET_AZIMUTH_36 0; +BA_ "GenSigSendType" SG_ 323 CAN_DET_AZIMUTH_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_AZIMUTH_36 "CAN_DET_AZIMUTH_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_RANGE_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_RANGE_36 "CAN_DET_RANGE_36"; +BA_ "GenSigStartValue" SG_ 323 CAN_DET_RANGE_RATE_36 0; +BA_ "GenSigSendType" SG_ 323 CAN_DET_RANGE_RATE_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_RANGE_RATE_36 "CAN_DET_RANGE_RATE_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_AMPLITUDE_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_AMPLITUDE_36 "CAN_DET_AMPLITUDE_36"; +BA_ "GenSigSendType" SG_ 323 CAN_SCAN_INDEX_2LSB_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_SCAN_INDEX_2LSB_36 "CAN_SCAN_INDEX_2LSB_36"; +BA_ "GenMsgSendType" BO_ 322 1; +BA_ "GenMsgILSupport" BO_ 322 1; +BA_ "GenMsgNrOfRepetition" BO_ 322 0; +BA_ "GenMsgCycleTime" BO_ 322 0; +BA_ "NetworkInitialization" BO_ 322 0; +BA_ "GenMsgDelayTime" BO_ 322 0; +BA_ "GenSigVtEn" SG_ 322 CAN_DET_CONFID_AZIMUTH_35 "CAN_DET_CONFID_AZIMUTH_35"; +BA_ "GenSigVtName" SG_ 322 CAN_DET_CONFID_AZIMUTH_35 "CAN_DET_CONFID_AZIMUTH_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_CONFID_AZIMUTH_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_CONFID_AZIMUTH_35 "CAN_DET_CONFID_AZIMUTH_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_SUPER_RES_TARGET_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_SUPER_RES_TARGET_35 "CAN_DET_SUPER_RES_TARGET_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_ND_TARGET_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_ND_TARGET_35 "CAN_DET_ND_TARGET_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_HOST_VEH_CLUTTER_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_HOST_VEH_CLUTTER_35 "CAN_DET_HOST_VEH_CLUTTER_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_VALID_LEVEL_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_VALID_LEVEL_35 "CAN_DET_VALID_LEVEL_35"; +BA_ "GenSigStartValue" SG_ 322 CAN_DET_AZIMUTH_35 0; +BA_ "GenSigSendType" SG_ 322 CAN_DET_AZIMUTH_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_AZIMUTH_35 "CAN_DET_AZIMUTH_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_RANGE_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_RANGE_35 "CAN_DET_RANGE_35"; +BA_ "GenSigStartValue" SG_ 322 CAN_DET_RANGE_RATE_35 0; +BA_ "GenSigSendType" SG_ 322 CAN_DET_RANGE_RATE_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_RANGE_RATE_35 "CAN_DET_RANGE_RATE_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_AMPLITUDE_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_AMPLITUDE_35 "CAN_DET_AMPLITUDE_35"; +BA_ "GenSigSendType" SG_ 322 CAN_SCAN_INDEX_2LSB_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_SCAN_INDEX_2LSB_35 "CAN_SCAN_INDEX_2LSB_35"; +BA_ "GenMsgSendType" BO_ 321 1; +BA_ "GenMsgILSupport" BO_ 321 1; +BA_ "GenMsgNrOfRepetition" BO_ 321 0; +BA_ "GenMsgCycleTime" BO_ 321 0; +BA_ "NetworkInitialization" BO_ 321 0; +BA_ "GenMsgDelayTime" BO_ 321 0; +BA_ "GenSigVtEn" SG_ 321 CAN_DET_CONFID_AZIMUTH_34 "CAN_DET_CONFID_AZIMUTH_34"; +BA_ "GenSigVtName" SG_ 321 CAN_DET_CONFID_AZIMUTH_34 "CAN_DET_CONFID_AZIMUTH_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_CONFID_AZIMUTH_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_CONFID_AZIMUTH_34 "CAN_DET_CONFID_AZIMUTH_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_SUPER_RES_TARGET_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_SUPER_RES_TARGET_34 "CAN_DET_SUPER_RES_TARGET_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_ND_TARGET_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_ND_TARGET_34 "CAN_DET_ND_TARGET_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_HOST_VEH_CLUTTER_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_HOST_VEH_CLUTTER_34 "CAN_DET_HOST_VEH_CLUTTER_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_VALID_LEVEL_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_VALID_LEVEL_34 "CAN_DET_VALID_LEVEL_34"; +BA_ "GenSigStartValue" SG_ 321 CAN_DET_AZIMUTH_34 0; +BA_ "GenSigSendType" SG_ 321 CAN_DET_AZIMUTH_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_AZIMUTH_34 "CAN_DET_AZIMUTH_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_RANGE_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_RANGE_34 "CAN_DET_RANGE_34"; +BA_ "GenSigStartValue" SG_ 321 CAN_DET_RANGE_RATE_34 0; +BA_ "GenSigSendType" SG_ 321 CAN_DET_RANGE_RATE_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_RANGE_RATE_34 "CAN_DET_RANGE_RATE_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_AMPLITUDE_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_AMPLITUDE_34 "CAN_DET_AMPLITUDE_34"; +BA_ "GenSigSendType" SG_ 321 CAN_SCAN_INDEX_2LSB_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_SCAN_INDEX_2LSB_34 "CAN_SCAN_INDEX_2LSB_34"; +BA_ "GenMsgSendType" BO_ 320 1; +BA_ "GenMsgILSupport" BO_ 320 1; +BA_ "GenMsgNrOfRepetition" BO_ 320 0; +BA_ "GenMsgCycleTime" BO_ 320 0; +BA_ "NetworkInitialization" BO_ 320 0; +BA_ "GenMsgDelayTime" BO_ 320 0; +BA_ "GenSigVtEn" SG_ 320 CAN_DET_CONFID_AZIMUTH_33 "CAN_DET_CONFID_AZIMUTH_33"; +BA_ "GenSigVtName" SG_ 320 CAN_DET_CONFID_AZIMUTH_33 "CAN_DET_CONFID_AZIMUTH_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_CONFID_AZIMUTH_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_CONFID_AZIMUTH_33 "CAN_DET_CONFID_AZIMUTH_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_SUPER_RES_TARGET_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_SUPER_RES_TARGET_33 "CAN_DET_SUPER_RES_TARGET_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_ND_TARGET_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_ND_TARGET_33 "CAN_DET_ND_TARGET_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_HOST_VEH_CLUTTER_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_HOST_VEH_CLUTTER_33 "CAN_DET_HOST_VEH_CLUTTER_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_VALID_LEVEL_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_VALID_LEVEL_33 "CAN_DET_VALID_LEVEL_33"; +BA_ "GenSigStartValue" SG_ 320 CAN_DET_AZIMUTH_33 0; +BA_ "GenSigSendType" SG_ 320 CAN_DET_AZIMUTH_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_AZIMUTH_33 "CAN_DET_AZIMUTH_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_RANGE_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_RANGE_33 "CAN_DET_RANGE_33"; +BA_ "GenSigStartValue" SG_ 320 CAN_DET_RANGE_RATE_33 0; +BA_ "GenSigSendType" SG_ 320 CAN_DET_RANGE_RATE_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_RANGE_RATE_33 "CAN_DET_RANGE_RATE_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_AMPLITUDE_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_AMPLITUDE_33 "CAN_DET_AMPLITUDE_33"; +BA_ "GenSigSendType" SG_ 320 CAN_SCAN_INDEX_2LSB_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_SCAN_INDEX_2LSB_33 "CAN_SCAN_INDEX_2LSB_33"; +BA_ "GenMsgSendType" BO_ 319 1; +BA_ "GenMsgILSupport" BO_ 319 1; +BA_ "GenMsgNrOfRepetition" BO_ 319 0; +BA_ "GenMsgCycleTime" BO_ 319 0; +BA_ "NetworkInitialization" BO_ 319 0; +BA_ "GenMsgDelayTime" BO_ 319 0; +BA_ "GenSigVtEn" SG_ 319 CAN_DET_CONFID_AZIMUTH_32 "CAN_DET_CONFID_AZIMUTH_32"; +BA_ "GenSigVtName" SG_ 319 CAN_DET_CONFID_AZIMUTH_32 "CAN_DET_CONFID_AZIMUTH_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_CONFID_AZIMUTH_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_CONFID_AZIMUTH_32 "CAN_DET_CONFID_AZIMUTH_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_SUPER_RES_TARGET_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_SUPER_RES_TARGET_32 "CAN_DET_SUPER_RES_TARGET_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_ND_TARGET_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_ND_TARGET_32 "CAN_DET_ND_TARGET_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_HOST_VEH_CLUTTER_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_HOST_VEH_CLUTTER_32 "CAN_DET_HOST_VEH_CLUTTER_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_VALID_LEVEL_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_VALID_LEVEL_32 "CAN_DET_VALID_LEVEL_32"; +BA_ "GenSigStartValue" SG_ 319 CAN_DET_AZIMUTH_32 0; +BA_ "GenSigSendType" SG_ 319 CAN_DET_AZIMUTH_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_AZIMUTH_32 "CAN_DET_AZIMUTH_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_RANGE_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_RANGE_32 "CAN_DET_RANGE_32"; +BA_ "GenSigStartValue" SG_ 319 CAN_DET_RANGE_RATE_32 0; +BA_ "GenSigSendType" SG_ 319 CAN_DET_RANGE_RATE_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_RANGE_RATE_32 "CAN_DET_RANGE_RATE_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_AMPLITUDE_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_AMPLITUDE_32 "CAN_DET_AMPLITUDE_32"; +BA_ "GenSigSendType" SG_ 319 CAN_SCAN_INDEX_2LSB_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_SCAN_INDEX_2LSB_32 "CAN_SCAN_INDEX_2LSB_32"; +BA_ "GenMsgSendType" BO_ 318 1; +BA_ "GenMsgILSupport" BO_ 318 1; +BA_ "GenMsgNrOfRepetition" BO_ 318 0; +BA_ "GenMsgCycleTime" BO_ 318 0; +BA_ "NetworkInitialization" BO_ 318 0; +BA_ "GenMsgDelayTime" BO_ 318 0; +BA_ "GenSigVtEn" SG_ 318 CAN_DET_CONFID_AZIMUTH_31 "CAN_DET_CONFID_AZIMUTH_31"; +BA_ "GenSigVtName" SG_ 318 CAN_DET_CONFID_AZIMUTH_31 "CAN_DET_CONFID_AZIMUTH_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_CONFID_AZIMUTH_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_CONFID_AZIMUTH_31 "CAN_DET_CONFID_AZIMUTH_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_SUPER_RES_TARGET_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_SUPER_RES_TARGET_31 "CAN_DET_SUPER_RES_TARGET_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_ND_TARGET_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_ND_TARGET_31 "CAN_DET_ND_TARGET_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_HOST_VEH_CLUTTER_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_HOST_VEH_CLUTTER_31 "CAN_DET_HOST_VEH_CLUTTER_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_VALID_LEVEL_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_VALID_LEVEL_31 "CAN_DET_VALID_LEVEL_31"; +BA_ "GenSigStartValue" SG_ 318 CAN_DET_AZIMUTH_31 0; +BA_ "GenSigSendType" SG_ 318 CAN_DET_AZIMUTH_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_AZIMUTH_31 "CAN_DET_AZIMUTH_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_RANGE_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_RANGE_31 "CAN_DET_RANGE_31"; +BA_ "GenSigStartValue" SG_ 318 CAN_DET_RANGE_RATE_31 0; +BA_ "GenSigSendType" SG_ 318 CAN_DET_RANGE_RATE_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_RANGE_RATE_31 "CAN_DET_RANGE_RATE_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_AMPLITUDE_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_AMPLITUDE_31 "CAN_DET_AMPLITUDE_31"; +BA_ "GenSigSendType" SG_ 318 CAN_SCAN_INDEX_2LSB_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_SCAN_INDEX_2LSB_31 "CAN_SCAN_INDEX_2LSB_31"; +BA_ "GenMsgSendType" BO_ 317 1; +BA_ "GenMsgILSupport" BO_ 317 1; +BA_ "GenMsgNrOfRepetition" BO_ 317 0; +BA_ "GenMsgCycleTime" BO_ 317 0; +BA_ "NetworkInitialization" BO_ 317 0; +BA_ "GenMsgDelayTime" BO_ 317 0; +BA_ "GenSigVtEn" SG_ 317 CAN_DET_CONFID_AZIMUTH_30 "CAN_DET_CONFID_AZIMUTH_30"; +BA_ "GenSigVtName" SG_ 317 CAN_DET_CONFID_AZIMUTH_30 "CAN_DET_CONFID_AZIMUTH_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_CONFID_AZIMUTH_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_CONFID_AZIMUTH_30 "CAN_DET_CONFID_AZIMUTH_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_SUPER_RES_TARGET_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_SUPER_RES_TARGET_30 "CAN_DET_SUPER_RES_TARGET_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_ND_TARGET_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_ND_TARGET_30 "CAN_DET_ND_TARGET_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_HOST_VEH_CLUTTER_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_HOST_VEH_CLUTTER_30 "CAN_DET_HOST_VEH_CLUTTER_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_VALID_LEVEL_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_VALID_LEVEL_30 "CAN_DET_VALID_LEVEL_30"; +BA_ "GenSigStartValue" SG_ 317 CAN_DET_AZIMUTH_30 0; +BA_ "GenSigSendType" SG_ 317 CAN_DET_AZIMUTH_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_AZIMUTH_30 "CAN_DET_AZIMUTH_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_RANGE_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_RANGE_30 "CAN_DET_RANGE_30"; +BA_ "GenSigStartValue" SG_ 317 CAN_DET_RANGE_RATE_30 0; +BA_ "GenSigSendType" SG_ 317 CAN_DET_RANGE_RATE_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_RANGE_RATE_30 "CAN_DET_RANGE_RATE_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_AMPLITUDE_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_AMPLITUDE_30 "CAN_DET_AMPLITUDE_30"; +BA_ "GenSigSendType" SG_ 317 CAN_SCAN_INDEX_2LSB_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_SCAN_INDEX_2LSB_30 "CAN_SCAN_INDEX_2LSB_30"; +BA_ "GenMsgSendType" BO_ 316 1; +BA_ "GenMsgILSupport" BO_ 316 1; +BA_ "GenMsgNrOfRepetition" BO_ 316 0; +BA_ "GenMsgCycleTime" BO_ 316 0; +BA_ "NetworkInitialization" BO_ 316 0; +BA_ "GenMsgDelayTime" BO_ 316 0; +BA_ "GenSigVtEn" SG_ 316 CAN_DET_CONFID_AZIMUTH_29 "CAN_DET_CONFID_AZIMUTH_29"; +BA_ "GenSigVtName" SG_ 316 CAN_DET_CONFID_AZIMUTH_29 "CAN_DET_CONFID_AZIMUTH_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_CONFID_AZIMUTH_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_CONFID_AZIMUTH_29 "CAN_DET_CONFID_AZIMUTH_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_SUPER_RES_TARGET_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_SUPER_RES_TARGET_29 "CAN_DET_SUPER_RES_TARGET_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_ND_TARGET_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_ND_TARGET_29 "CAN_DET_ND_TARGET_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_HOST_VEH_CLUTTER_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_HOST_VEH_CLUTTER_29 "CAN_DET_HOST_VEH_CLUTTER_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_VALID_LEVEL_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_VALID_LEVEL_29 "CAN_DET_VALID_LEVEL_29"; +BA_ "GenSigStartValue" SG_ 316 CAN_DET_AZIMUTH_29 0; +BA_ "GenSigSendType" SG_ 316 CAN_DET_AZIMUTH_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_AZIMUTH_29 "CAN_DET_AZIMUTH_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_RANGE_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_RANGE_29 "CAN_DET_RANGE_29"; +BA_ "GenSigStartValue" SG_ 316 CAN_DET_RANGE_RATE_29 0; +BA_ "GenSigSendType" SG_ 316 CAN_DET_RANGE_RATE_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_RANGE_RATE_29 "CAN_DET_RANGE_RATE_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_AMPLITUDE_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_AMPLITUDE_29 "CAN_DET_AMPLITUDE_29"; +BA_ "GenSigSendType" SG_ 316 CAN_SCAN_INDEX_2LSB_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_SCAN_INDEX_2LSB_29 "CAN_SCAN_INDEX_2LSB_29"; +BA_ "GenMsgSendType" BO_ 314 1; +BA_ "GenMsgILSupport" BO_ 314 1; +BA_ "GenMsgNrOfRepetition" BO_ 314 0; +BA_ "GenMsgCycleTime" BO_ 314 0; +BA_ "NetworkInitialization" BO_ 314 0; +BA_ "GenMsgDelayTime" BO_ 314 0; +BA_ "GenSigVtEn" SG_ 314 CAN_DET_CONFID_AZIMUTH_27 "CAN_DET_CONFID_AZIMUTH_27"; +BA_ "GenSigVtName" SG_ 314 CAN_DET_CONFID_AZIMUTH_27 "CAN_DET_CONFID_AZIMUTH_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_CONFID_AZIMUTH_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_CONFID_AZIMUTH_27 "CAN_DET_CONFID_AZIMUTH_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_SUPER_RES_TARGET_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_SUPER_RES_TARGET_27 "CAN_DET_SUPER_RES_TARGET_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_ND_TARGET_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_ND_TARGET_27 "CAN_DET_ND_TARGET_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_HOST_VEH_CLUTTER_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_HOST_VEH_CLUTTER_27 "CAN_DET_HOST_VEH_CLUTTER_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_VALID_LEVEL_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_VALID_LEVEL_27 "CAN_DET_VALID_LEVEL_27"; +BA_ "GenSigStartValue" SG_ 314 CAN_DET_AZIMUTH_27 0; +BA_ "GenSigSendType" SG_ 314 CAN_DET_AZIMUTH_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_AZIMUTH_27 "CAN_DET_AZIMUTH_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_RANGE_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_RANGE_27 "CAN_DET_RANGE_27"; +BA_ "GenSigStartValue" SG_ 314 CAN_DET_RANGE_RATE_27 0; +BA_ "GenSigSendType" SG_ 314 CAN_DET_RANGE_RATE_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_RANGE_RATE_27 "CAN_DET_RANGE_RATE_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_AMPLITUDE_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_AMPLITUDE_27 "CAN_DET_AMPLITUDE_27"; +BA_ "GenSigSendType" SG_ 314 CAN_SCAN_INDEX_2LSB_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_SCAN_INDEX_2LSB_27 "CAN_SCAN_INDEX_2LSB_27"; +BA_ "GenMsgSendType" BO_ 313 1; +BA_ "GenMsgILSupport" BO_ 313 1; +BA_ "GenMsgNrOfRepetition" BO_ 313 0; +BA_ "GenMsgCycleTime" BO_ 313 0; +BA_ "NetworkInitialization" BO_ 313 0; +BA_ "GenMsgDelayTime" BO_ 313 0; +BA_ "GenSigVtEn" SG_ 313 CAN_DET_CONFID_AZIMUTH_26 "CAN_DET_CONFID_AZIMUTH_26"; +BA_ "GenSigVtName" SG_ 313 CAN_DET_CONFID_AZIMUTH_26 "CAN_DET_CONFID_AZIMUTH_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_CONFID_AZIMUTH_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_CONFID_AZIMUTH_26 "CAN_DET_CONFID_AZIMUTH_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_SUPER_RES_TARGET_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_SUPER_RES_TARGET_26 "CAN_DET_SUPER_RES_TARGET_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_ND_TARGET_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_ND_TARGET_26 "CAN_DET_ND_TARGET_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_HOST_VEH_CLUTTER_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_HOST_VEH_CLUTTER_26 "CAN_DET_HOST_VEH_CLUTTER_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_VALID_LEVEL_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_VALID_LEVEL_26 "CAN_DET_VALID_LEVEL_26"; +BA_ "GenSigStartValue" SG_ 313 CAN_DET_AZIMUTH_26 0; +BA_ "GenSigSendType" SG_ 313 CAN_DET_AZIMUTH_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_AZIMUTH_26 "CAN_DET_AZIMUTH_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_RANGE_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_RANGE_26 "CAN_DET_RANGE_26"; +BA_ "GenSigStartValue" SG_ 313 CAN_DET_RANGE_RATE_26 0; +BA_ "GenSigSendType" SG_ 313 CAN_DET_RANGE_RATE_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_RANGE_RATE_26 "CAN_DET_RANGE_RATE_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_AMPLITUDE_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_AMPLITUDE_26 "CAN_DET_AMPLITUDE_26"; +BA_ "GenSigSendType" SG_ 313 CAN_SCAN_INDEX_2LSB_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_SCAN_INDEX_2LSB_26 "CAN_SCAN_INDEX_2LSB_26"; +BA_ "GenMsgSendType" BO_ 312 1; +BA_ "GenMsgILSupport" BO_ 312 1; +BA_ "GenMsgNrOfRepetition" BO_ 312 0; +BA_ "GenMsgCycleTime" BO_ 312 0; +BA_ "NetworkInitialization" BO_ 312 0; +BA_ "GenMsgDelayTime" BO_ 312 0; +BA_ "GenSigVtEn" SG_ 312 CAN_DET_CONFID_AZIMUTH_25 "CAN_DET_CONFID_AZIMUTH_25"; +BA_ "GenSigVtName" SG_ 312 CAN_DET_CONFID_AZIMUTH_25 "CAN_DET_CONFID_AZIMUTH_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_CONFID_AZIMUTH_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_CONFID_AZIMUTH_25 "CAN_DET_CONFID_AZIMUTH_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_SUPER_RES_TARGET_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_SUPER_RES_TARGET_25 "CAN_DET_SUPER_RES_TARGET_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_ND_TARGET_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_ND_TARGET_25 "CAN_DET_ND_TARGET_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_HOST_VEH_CLUTTER_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_HOST_VEH_CLUTTER_25 "CAN_DET_HOST_VEH_CLUTTER_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_VALID_LEVEL_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_VALID_LEVEL_25 "CAN_DET_VALID_LEVEL_25"; +BA_ "GenSigStartValue" SG_ 312 CAN_DET_AZIMUTH_25 0; +BA_ "GenSigSendType" SG_ 312 CAN_DET_AZIMUTH_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_AZIMUTH_25 "CAN_DET_AZIMUTH_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_RANGE_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_RANGE_25 "CAN_DET_RANGE_25"; +BA_ "GenSigStartValue" SG_ 312 CAN_DET_RANGE_RATE_25 0; +BA_ "GenSigSendType" SG_ 312 CAN_DET_RANGE_RATE_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_RANGE_RATE_25 "CAN_DET_RANGE_RATE_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_AMPLITUDE_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_AMPLITUDE_25 "CAN_DET_AMPLITUDE_25"; +BA_ "GenSigSendType" SG_ 312 CAN_SCAN_INDEX_2LSB_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_SCAN_INDEX_2LSB_25 "CAN_SCAN_INDEX_2LSB_25"; +BA_ "GenMsgSendType" BO_ 311 1; +BA_ "GenMsgILSupport" BO_ 311 1; +BA_ "GenMsgNrOfRepetition" BO_ 311 0; +BA_ "GenMsgCycleTime" BO_ 311 0; +BA_ "NetworkInitialization" BO_ 311 0; +BA_ "GenMsgDelayTime" BO_ 311 0; +BA_ "GenSigVtEn" SG_ 311 CAN_DET_CONFID_AZIMUTH_24 "CAN_DET_CONFID_AZIMUTH_24"; +BA_ "GenSigVtName" SG_ 311 CAN_DET_CONFID_AZIMUTH_24 "CAN_DET_CONFID_AZIMUTH_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_CONFID_AZIMUTH_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_CONFID_AZIMUTH_24 "CAN_DET_CONFID_AZIMUTH_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_SUPER_RES_TARGET_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_SUPER_RES_TARGET_24 "CAN_DET_SUPER_RES_TARGET_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_ND_TARGET_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_ND_TARGET_24 "CAN_DET_ND_TARGET_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_HOST_VEH_CLUTTER_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_HOST_VEH_CLUTTER_24 "CAN_DET_HOST_VEH_CLUTTER_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_VALID_LEVEL_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_VALID_LEVEL_24 "CAN_DET_VALID_LEVEL_24"; +BA_ "GenSigStartValue" SG_ 311 CAN_DET_AZIMUTH_24 0; +BA_ "GenSigSendType" SG_ 311 CAN_DET_AZIMUTH_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_AZIMUTH_24 "CAN_DET_AZIMUTH_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_RANGE_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_RANGE_24 "CAN_DET_RANGE_24"; +BA_ "GenSigStartValue" SG_ 311 CAN_DET_RANGE_RATE_24 0; +BA_ "GenSigSendType" SG_ 311 CAN_DET_RANGE_RATE_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_RANGE_RATE_24 "CAN_DET_RANGE_RATE_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_AMPLITUDE_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_AMPLITUDE_24 "CAN_DET_AMPLITUDE_24"; +BA_ "GenSigSendType" SG_ 311 CAN_SCAN_INDEX_2LSB_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_SCAN_INDEX_2LSB_24 "CAN_SCAN_INDEX_2LSB_24"; +BA_ "GenMsgSendType" BO_ 310 1; +BA_ "GenMsgILSupport" BO_ 310 1; +BA_ "GenMsgNrOfRepetition" BO_ 310 0; +BA_ "GenMsgCycleTime" BO_ 310 0; +BA_ "NetworkInitialization" BO_ 310 0; +BA_ "GenMsgDelayTime" BO_ 310 0; +BA_ "GenSigVtEn" SG_ 310 CAN_DET_CONFID_AZIMUTH_23 "CAN_DET_CONFID_AZIMUTH_23"; +BA_ "GenSigVtName" SG_ 310 CAN_DET_CONFID_AZIMUTH_23 "CAN_DET_CONFID_AZIMUTH_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_CONFID_AZIMUTH_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_CONFID_AZIMUTH_23 "CAN_DET_CONFID_AZIMUTH_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_SUPER_RES_TARGET_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_SUPER_RES_TARGET_23 "CAN_DET_SUPER_RES_TARGET_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_ND_TARGET_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_ND_TARGET_23 "CAN_DET_ND_TARGET_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_HOST_VEH_CLUTTER_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_HOST_VEH_CLUTTER_23 "CAN_DET_HOST_VEH_CLUTTER_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_VALID_LEVEL_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_VALID_LEVEL_23 "CAN_DET_VALID_LEVEL_23"; +BA_ "GenSigStartValue" SG_ 310 CAN_DET_AZIMUTH_23 0; +BA_ "GenSigSendType" SG_ 310 CAN_DET_AZIMUTH_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_AZIMUTH_23 "CAN_DET_AZIMUTH_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_RANGE_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_RANGE_23 "CAN_DET_RANGE_23"; +BA_ "GenSigStartValue" SG_ 310 CAN_DET_RANGE_RATE_23 0; +BA_ "GenSigSendType" SG_ 310 CAN_DET_RANGE_RATE_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_RANGE_RATE_23 "CAN_DET_RANGE_RATE_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_AMPLITUDE_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_AMPLITUDE_23 "CAN_DET_AMPLITUDE_23"; +BA_ "GenSigSendType" SG_ 310 CAN_SCAN_INDEX_2LSB_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_SCAN_INDEX_2LSB_23 "CAN_SCAN_INDEX_2LSB_23"; +BA_ "GenMsgSendType" BO_ 309 1; +BA_ "GenMsgILSupport" BO_ 309 1; +BA_ "GenMsgNrOfRepetition" BO_ 309 0; +BA_ "GenMsgCycleTime" BO_ 309 0; +BA_ "NetworkInitialization" BO_ 309 0; +BA_ "GenMsgDelayTime" BO_ 309 0; +BA_ "GenSigVtEn" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_01 "CAN_DET_CONFID_AZIMUTH_22_01"; +BA_ "GenSigVtName" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_01 "CAN_DET_CONFID_AZIMUTH_22_01"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_01 "CAN_DET_CONFID_AZIMUTH_22_01"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_SUPER_RES_TARGET_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_SUPER_RES_TARGET_22_01 "CAN_DET_SUPER_RES_TARGET_22_01"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_ND_TARGET_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_ND_TARGET_22_01 "CAN_DET_ND_TARGET_22_01"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_HOST_VEH_CLUTTER_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_HOST_VEH_CLUTTER_22_01 "CAN_DET_HOST_VEH_CLUTTER_22_01"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_VALID_LEVEL_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_VALID_LEVEL_22_01 "CAN_DET_VALID_LEVEL_22_01"; +BA_ "GenSigStartValue" SG_ 309 CAN_DET_AZIMUTH_22_01 0; +BA_ "GenSigSendType" SG_ 309 CAN_DET_AZIMUTH_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_AZIMUTH_22_01 "CAN_DET_AZIMUTH_22_01"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_RANGE_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_RANGE_22_01 "CAN_DET_RANGE_22_01"; +BA_ "GenSigStartValue" SG_ 309 CAN_DET_RANGE_RATE_22_01 0; +BA_ "GenSigSendType" SG_ 309 CAN_DET_RANGE_RATE_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_RANGE_RATE_22_01 "CAN_DET_RANGE_RATE_22_01"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_AMPLITUDE_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_AMPLITUDE_22_01 "CAN_DET_AMPLITUDE_22_01"; +BA_ "GenSigSendType" SG_ 309 CAN_SCAN_INDEX_2LSB_22_01 0; +BA_ "GenSigCmt" SG_ 309 CAN_SCAN_INDEX_2LSB_22_01 "CAN_SCAN_INDEX_2LSB_22_01"; +BA_ "GenSigVtEn" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_02 "CAN_DET_CONFID_AZIMUTH_22_02"; +BA_ "GenSigVtName" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_02 "CAN_DET_CONFID_AZIMUTH_22_02"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_02 "CAN_DET_CONFID_AZIMUTH_22_02"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_SUPER_RES_TARGET_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_SUPER_RES_TARGET_22_02 "CAN_DET_SUPER_RES_TARGET_22_02"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_ND_TARGET_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_ND_TARGET_22_02 "CAN_DET_ND_TARGET_22_02"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_HOST_VEH_CLUTTER_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_HOST_VEH_CLUTTER_22_02 "CAN_DET_HOST_VEH_CLUTTER_22_02"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_VALID_LEVEL_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_VALID_LEVEL_22_02 "CAN_DET_VALID_LEVEL_22_02"; +BA_ "GenSigStartValue" SG_ 309 CAN_DET_AZIMUTH_22_02 0; +BA_ "GenSigSendType" SG_ 309 CAN_DET_AZIMUTH_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_AZIMUTH_22_02 "CAN_DET_AZIMUTH_22_02"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_RANGE_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_RANGE_22_02 "CAN_DET_RANGE_22_02"; +BA_ "GenSigStartValue" SG_ 309 CAN_DET_RANGE_RATE_22_02 0; +BA_ "GenSigSendType" SG_ 309 CAN_DET_RANGE_RATE_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_RANGE_RATE_22_02 "CAN_DET_RANGE_RATE_22_02"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_AMPLITUDE_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_AMPLITUDE_22_02 "CAN_DET_AMPLITUDE_22_02"; +BA_ "GenSigSendType" SG_ 309 CAN_SCAN_INDEX_2LSB_22_02 0; +BA_ "GenSigCmt" SG_ 309 CAN_SCAN_INDEX_2LSB_22_02 "CAN_SCAN_INDEX_2LSB_22_02"; +BA_ "GenSigVtEn" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_03 "CAN_DET_CONFID_AZIMUTH_22_03"; +BA_ "GenSigVtName" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_03 "CAN_DET_CONFID_AZIMUTH_22_03"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_CONFID_AZIMUTH_22_03 "CAN_DET_CONFID_AZIMUTH_22_03"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_SUPER_RES_TARGET_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_SUPER_RES_TARGET_22_03 "CAN_DET_SUPER_RES_TARGET_22_03"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_ND_TARGET_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_ND_TARGET_22_03 "CAN_DET_ND_TARGET_22_03"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_HOST_VEH_CLUTTER_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_HOST_VEH_CLUTTER_22_03 "CAN_DET_HOST_VEH_CLUTTER_22_03"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_VALID_LEVEL_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_VALID_LEVEL_22_03 "CAN_DET_VALID_LEVEL_22_03"; +BA_ "GenSigStartValue" SG_ 309 CAN_DET_AZIMUTH_22_03 0; +BA_ "GenSigSendType" SG_ 309 CAN_DET_AZIMUTH_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_AZIMUTH_22_03 "CAN_DET_AZIMUTH_22_03"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_RANGE_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_RANGE_22_03 "CAN_DET_RANGE_22_03"; +BA_ "GenSigStartValue" SG_ 309 CAN_DET_RANGE_RATE_22_03 0; +BA_ "GenSigSendType" SG_ 309 CAN_DET_RANGE_RATE_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_RANGE_RATE_22_03 "CAN_DET_RANGE_RATE_22_03"; +BA_ "GenSigSendType" SG_ 309 CAN_DET_AMPLITUDE_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_DET_AMPLITUDE_22_03 "CAN_DET_AMPLITUDE_22_03"; +BA_ "GenSigSendType" SG_ 309 CAN_SCAN_INDEX_2LSB_22_03 0; +BA_ "GenSigCmt" SG_ 309 CAN_SCAN_INDEX_2LSB_22_03 "CAN_SCAN_INDEX_2LSB_22_03"; +BA_ "GenMsgSendType" BO_ 308 1; +BA_ "GenMsgILSupport" BO_ 308 1; +BA_ "GenMsgNrOfRepetition" BO_ 308 0; +BA_ "GenMsgCycleTime" BO_ 308 0; +BA_ "NetworkInitialization" BO_ 308 0; +BA_ "GenMsgDelayTime" BO_ 308 0; +BA_ "GenSigVtEn" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_01 "CAN_DET_CONFID_AZIMUTH_21_01"; +BA_ "GenSigVtName" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_01 "CAN_DET_CONFID_AZIMUTH_21_01"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_01 "CAN_DET_CONFID_AZIMUTH_21_01"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_01 "CAN_DET_SUPER_RES_TARGET_21_01"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_ND_TARGET_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_ND_TARGET_21_01 "CAN_DET_ND_TARGET_21_01"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_01 "CAN_DET_HOST_VEH_CLUTTER_21_01"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_VALID_LEVEL_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_VALID_LEVEL_21_01 "CAN_DET_VALID_LEVEL_21_01"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_AZIMUTH_21_01 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AZIMUTH_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AZIMUTH_21_01 "CAN_DET_AZIMUTH_21_01"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_21_01 "CAN_DET_RANGE_21_01"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_RANGE_RATE_21_01 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_RATE_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_RATE_21_01 "CAN_DET_RANGE_RATE_21_01"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AMPLITUDE_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AMPLITUDE_21_01 "CAN_DET_AMPLITUDE_21_01"; +BA_ "GenSigSendType" SG_ 308 CAN_SCAN_INDEX_2LSB_21_01 0; +BA_ "GenSigCmt" SG_ 308 CAN_SCAN_INDEX_2LSB_21_01 "CAN_SCAN_INDEX_2LSB_21_01"; +BA_ "GenSigVtEn" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_02 "CAN_DET_CONFID_AZIMUTH_21_02"; +BA_ "GenSigVtName" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_02 "CAN_DET_CONFID_AZIMUTH_21_02"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_02 "CAN_DET_CONFID_AZIMUTH_21_02"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_02 "CAN_DET_SUPER_RES_TARGET_21_02"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_ND_TARGET_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_ND_TARGET_21_02 "CAN_DET_ND_TARGET_21_02"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_02 "CAN_DET_HOST_VEH_CLUTTER_21_02"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_VALID_LEVEL_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_VALID_LEVEL_21_02 "CAN_DET_VALID_LEVEL_21_02"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_AZIMUTH_21_02 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AZIMUTH_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AZIMUTH_21_02 "CAN_DET_AZIMUTH_21_02"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_21_02 "CAN_DET_RANGE_21_02"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_RANGE_RATE_21_02 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_RATE_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_RATE_21_02 "CAN_DET_RANGE_RATE_21_02"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AMPLITUDE_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AMPLITUDE_21_02 "CAN_DET_AMPLITUDE_21_02"; +BA_ "GenSigSendType" SG_ 308 CAN_SCAN_INDEX_2LSB_21_02 0; +BA_ "GenSigCmt" SG_ 308 CAN_SCAN_INDEX_2LSB_21_02 "CAN_SCAN_INDEX_2LSB_21_02"; +BA_ "GenSigVtEn" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_03 "CAN_DET_CONFID_AZIMUTH_21_03"; +BA_ "GenSigVtName" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_03 "CAN_DET_CONFID_AZIMUTH_21_03"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_03 "CAN_DET_CONFID_AZIMUTH_21_03"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_03 "CAN_DET_SUPER_RES_TARGET_21_03"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_ND_TARGET_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_ND_TARGET_21_03 "CAN_DET_ND_TARGET_21_03"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_03 "CAN_DET_HOST_VEH_CLUTTER_21_03"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_VALID_LEVEL_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_VALID_LEVEL_21_03 "CAN_DET_VALID_LEVEL_21_03"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_AZIMUTH_21_03 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AZIMUTH_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AZIMUTH_21_03 "CAN_DET_AZIMUTH_21_03"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_21_03 "CAN_DET_RANGE_21_03"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_RANGE_RATE_21_03 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_RATE_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_RATE_21_03 "CAN_DET_RANGE_RATE_21_03"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AMPLITUDE_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AMPLITUDE_21_03 "CAN_DET_AMPLITUDE_21_03"; +BA_ "GenSigSendType" SG_ 308 CAN_SCAN_INDEX_2LSB_21_03 0; +BA_ "GenSigCmt" SG_ 308 CAN_SCAN_INDEX_2LSB_21_03 "CAN_SCAN_INDEX_2LSB_21_03"; +BA_ "GenSigVtEn" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_04 "CAN_DET_CONFID_AZIMUTH_21_04"; +BA_ "GenSigVtName" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_04 "CAN_DET_CONFID_AZIMUTH_21_04"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_04 "CAN_DET_CONFID_AZIMUTH_21_04"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_04 "CAN_DET_SUPER_RES_TARGET_21_04"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_ND_TARGET_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_ND_TARGET_21_04 "CAN_DET_ND_TARGET_21_04"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_04 "CAN_DET_HOST_VEH_CLUTTER_21_04"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_VALID_LEVEL_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_VALID_LEVEL_21_04 "CAN_DET_VALID_LEVEL_21_04"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_AZIMUTH_21_04 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AZIMUTH_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AZIMUTH_21_04 "CAN_DET_AZIMUTH_21_04"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_21_04 "CAN_DET_RANGE_21_04"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_RANGE_RATE_21_04 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_RATE_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_RATE_21_04 "CAN_DET_RANGE_RATE_21_04"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AMPLITUDE_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AMPLITUDE_21_04 "CAN_DET_AMPLITUDE_21_04"; +BA_ "GenSigSendType" SG_ 308 CAN_SCAN_INDEX_2LSB_21_04 0; +BA_ "GenSigCmt" SG_ 308 CAN_SCAN_INDEX_2LSB_21_04 "CAN_SCAN_INDEX_2LSB_21_04"; +BA_ "GenSigVtEn" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_05 "CAN_DET_CONFID_AZIMUTH_21_05"; +BA_ "GenSigVtName" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_05 "CAN_DET_CONFID_AZIMUTH_21_05"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_05 "CAN_DET_CONFID_AZIMUTH_21_05"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_05 "CAN_DET_SUPER_RES_TARGET_21_05"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_ND_TARGET_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_ND_TARGET_21_05 "CAN_DET_ND_TARGET_21_05"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_05 "CAN_DET_HOST_VEH_CLUTTER_21_05"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_VALID_LEVEL_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_VALID_LEVEL_21_05 "CAN_DET_VALID_LEVEL_21_05"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_AZIMUTH_21_05 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AZIMUTH_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AZIMUTH_21_05 "CAN_DET_AZIMUTH_21_05"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_21_05 "CAN_DET_RANGE_21_05"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_RANGE_RATE_21_05 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_RATE_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_RATE_21_05 "CAN_DET_RANGE_RATE_21_05"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AMPLITUDE_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AMPLITUDE_21_05 "CAN_DET_AMPLITUDE_21_05"; +BA_ "GenSigSendType" SG_ 308 CAN_SCAN_INDEX_2LSB_21_05 0; +BA_ "GenSigCmt" SG_ 308 CAN_SCAN_INDEX_2LSB_21_05 "CAN_SCAN_INDEX_2LSB_21_05"; +BA_ "GenSigVtEn" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_06 "CAN_DET_CONFID_AZIMUTH_21_06"; +BA_ "GenSigVtName" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_06 "CAN_DET_CONFID_AZIMUTH_21_06"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_CONFID_AZIMUTH_21_06 "CAN_DET_CONFID_AZIMUTH_21_06"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_SUPER_RES_TARGET_21_06 "CAN_DET_SUPER_RES_TARGET_21_06"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_ND_TARGET_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_ND_TARGET_21_06 "CAN_DET_ND_TARGET_21_06"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_HOST_VEH_CLUTTER_21_06 "CAN_DET_HOST_VEH_CLUTTER_21_06"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_VALID_LEVEL_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_VALID_LEVEL_21_06 "CAN_DET_VALID_LEVEL_21_06"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_AZIMUTH_21_06 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AZIMUTH_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AZIMUTH_21_06 "CAN_DET_AZIMUTH_21_06"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_21_06 "CAN_DET_RANGE_21_06"; +BA_ "GenSigStartValue" SG_ 308 CAN_DET_RANGE_RATE_21_06 0; +BA_ "GenSigSendType" SG_ 308 CAN_DET_RANGE_RATE_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_RANGE_RATE_21_06 "CAN_DET_RANGE_RATE_21_06"; +BA_ "GenSigSendType" SG_ 308 CAN_DET_AMPLITUDE_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_DET_AMPLITUDE_21_06 "CAN_DET_AMPLITUDE_21_06"; +BA_ "GenSigSendType" SG_ 308 CAN_SCAN_INDEX_2LSB_21_06 0; +BA_ "GenSigCmt" SG_ 308 CAN_SCAN_INDEX_2LSB_21_06 "CAN_SCAN_INDEX_2LSB_21_06"; +BA_ "GenMsgSendType" BO_ 307 1; +BA_ "GenMsgILSupport" BO_ 307 1; +BA_ "GenMsgNrOfRepetition" BO_ 307 0; +BA_ "GenMsgCycleTime" BO_ 307 0; +BA_ "NetworkInitialization" BO_ 307 0; +BA_ "GenMsgDelayTime" BO_ 307 0; +BA_ "GenSigVtEn" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_01 "CAN_DET_CONFID_AZIMUTH_20_01"; +BA_ "GenSigVtName" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_01 "CAN_DET_CONFID_AZIMUTH_20_01"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_01 "CAN_DET_CONFID_AZIMUTH_20_01"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_01 "CAN_DET_SUPER_RES_TARGET_20_01"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_ND_TARGET_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_ND_TARGET_20_01 "CAN_DET_ND_TARGET_20_01"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_01 "CAN_DET_HOST_VEH_CLUTTER_20_01"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_VALID_LEVEL_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_VALID_LEVEL_20_01 "CAN_DET_VALID_LEVEL_20_01"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_AZIMUTH_20_01 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AZIMUTH_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AZIMUTH_20_01 "CAN_DET_AZIMUTH_20_01"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_20_01 "CAN_DET_RANGE_20_01"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_RANGE_RATE_20_01 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_RATE_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_RATE_20_01 "CAN_DET_RANGE_RATE_20_01"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AMPLITUDE_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AMPLITUDE_20_01 "CAN_DET_AMPLITUDE_20_01"; +BA_ "GenSigSendType" SG_ 307 CAN_SCAN_INDEX_2LSB_20_01 0; +BA_ "GenSigCmt" SG_ 307 CAN_SCAN_INDEX_2LSB_20_01 "CAN_SCAN_INDEX_2LSB_20_01"; +BA_ "GenSigVtEn" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_02 "CAN_DET_CONFID_AZIMUTH_20_02"; +BA_ "GenSigVtName" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_02 "CAN_DET_CONFID_AZIMUTH_20_02"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_02 "CAN_DET_CONFID_AZIMUTH_20_02"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_02 "CAN_DET_SUPER_RES_TARGET_20_02"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_ND_TARGET_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_ND_TARGET_20_02 "CAN_DET_ND_TARGET_20_02"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_02 "CAN_DET_HOST_VEH_CLUTTER_20_02"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_VALID_LEVEL_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_VALID_LEVEL_20_02 "CAN_DET_VALID_LEVEL_20_02"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_AZIMUTH_20_02 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AZIMUTH_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AZIMUTH_20_02 "CAN_DET_AZIMUTH_20_02"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_20_02 "CAN_DET_RANGE_20_02"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_RANGE_RATE_20_02 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_RATE_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_RATE_20_02 "CAN_DET_RANGE_RATE_20_02"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AMPLITUDE_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AMPLITUDE_20_02 "CAN_DET_AMPLITUDE_20_02"; +BA_ "GenSigSendType" SG_ 307 CAN_SCAN_INDEX_2LSB_20_02 0; +BA_ "GenSigCmt" SG_ 307 CAN_SCAN_INDEX_2LSB_20_02 "CAN_SCAN_INDEX_2LSB_20_02"; +BA_ "GenSigVtEn" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_03 "CAN_DET_CONFID_AZIMUTH_20_03"; +BA_ "GenSigVtName" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_03 "CAN_DET_CONFID_AZIMUTH_20_03"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_03 "CAN_DET_CONFID_AZIMUTH_20_03"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_03 "CAN_DET_SUPER_RES_TARGET_20_03"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_ND_TARGET_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_ND_TARGET_20_03 "CAN_DET_ND_TARGET_20_03"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_03 "CAN_DET_HOST_VEH_CLUTTER_20_03"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_VALID_LEVEL_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_VALID_LEVEL_20_03 "CAN_DET_VALID_LEVEL_20_03"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_AZIMUTH_20_03 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AZIMUTH_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AZIMUTH_20_03 "CAN_DET_AZIMUTH_20_03"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_20_03 "CAN_DET_RANGE_20_03"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_RANGE_RATE_20_03 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_RATE_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_RATE_20_03 "CAN_DET_RANGE_RATE_20_03"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AMPLITUDE_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AMPLITUDE_20_03 "CAN_DET_AMPLITUDE_20_03"; +BA_ "GenSigSendType" SG_ 307 CAN_SCAN_INDEX_2LSB_20_03 0; +BA_ "GenSigCmt" SG_ 307 CAN_SCAN_INDEX_2LSB_20_03 "CAN_SCAN_INDEX_2LSB_20_03"; +BA_ "GenSigVtEn" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_04 "CAN_DET_CONFID_AZIMUTH_20_04"; +BA_ "GenSigVtName" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_04 "CAN_DET_CONFID_AZIMUTH_20_04"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_04 "CAN_DET_CONFID_AZIMUTH_20_04"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_04 "CAN_DET_SUPER_RES_TARGET_20_04"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_ND_TARGET_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_ND_TARGET_20_04 "CAN_DET_ND_TARGET_20_04"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_04 "CAN_DET_HOST_VEH_CLUTTER_20_04"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_VALID_LEVEL_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_VALID_LEVEL_20_04 "CAN_DET_VALID_LEVEL_20_04"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_AZIMUTH_20_04 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AZIMUTH_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AZIMUTH_20_04 "CAN_DET_AZIMUTH_20_04"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_20_04 "CAN_DET_RANGE_20_04"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_RANGE_RATE_20_04 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_RATE_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_RATE_20_04 "CAN_DET_RANGE_RATE_20_04"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AMPLITUDE_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AMPLITUDE_20_04 "CAN_DET_AMPLITUDE_20_04"; +BA_ "GenSigSendType" SG_ 307 CAN_SCAN_INDEX_2LSB_20_04 0; +BA_ "GenSigCmt" SG_ 307 CAN_SCAN_INDEX_2LSB_20_04 "CAN_SCAN_INDEX_2LSB_20_04"; +BA_ "GenSigVtEn" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_05 "CAN_DET_CONFID_AZIMUTH_20_05"; +BA_ "GenSigVtName" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_05 "CAN_DET_CONFID_AZIMUTH_20_05"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_05 "CAN_DET_CONFID_AZIMUTH_20_05"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_05 "CAN_DET_SUPER_RES_TARGET_20_05"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_ND_TARGET_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_ND_TARGET_20_05 "CAN_DET_ND_TARGET_20_05"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_05 "CAN_DET_HOST_VEH_CLUTTER_20_05"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_VALID_LEVEL_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_VALID_LEVEL_20_05 "CAN_DET_VALID_LEVEL_20_05"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_AZIMUTH_20_05 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AZIMUTH_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AZIMUTH_20_05 "CAN_DET_AZIMUTH_20_05"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_20_05 "CAN_DET_RANGE_20_05"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_RANGE_RATE_20_05 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_RATE_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_RATE_20_05 "CAN_DET_RANGE_RATE_20_05"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AMPLITUDE_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AMPLITUDE_20_05 "CAN_DET_AMPLITUDE_20_05"; +BA_ "GenSigSendType" SG_ 307 CAN_SCAN_INDEX_2LSB_20_05 0; +BA_ "GenSigCmt" SG_ 307 CAN_SCAN_INDEX_2LSB_20_05 "CAN_SCAN_INDEX_2LSB_20_05"; +BA_ "GenSigVtEn" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_06 "CAN_DET_CONFID_AZIMUTH_20_06"; +BA_ "GenSigVtName" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_06 "CAN_DET_CONFID_AZIMUTH_20_06"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_CONFID_AZIMUTH_20_06 "CAN_DET_CONFID_AZIMUTH_20_06"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_SUPER_RES_TARGET_20_06 "CAN_DET_SUPER_RES_TARGET_20_06"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_ND_TARGET_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_ND_TARGET_20_06 "CAN_DET_ND_TARGET_20_06"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_HOST_VEH_CLUTTER_20_06 "CAN_DET_HOST_VEH_CLUTTER_20_06"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_VALID_LEVEL_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_VALID_LEVEL_20_06 "CAN_DET_VALID_LEVEL_20_06"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_AZIMUTH_20_06 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AZIMUTH_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AZIMUTH_20_06 "CAN_DET_AZIMUTH_20_06"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_20_06 "CAN_DET_RANGE_20_06"; +BA_ "GenSigStartValue" SG_ 307 CAN_DET_RANGE_RATE_20_06 0; +BA_ "GenSigSendType" SG_ 307 CAN_DET_RANGE_RATE_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_RANGE_RATE_20_06 "CAN_DET_RANGE_RATE_20_06"; +BA_ "GenSigSendType" SG_ 307 CAN_DET_AMPLITUDE_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_DET_AMPLITUDE_20_06 "CAN_DET_AMPLITUDE_20_06"; +BA_ "GenSigSendType" SG_ 307 CAN_SCAN_INDEX_2LSB_20_06 0; +BA_ "GenSigCmt" SG_ 307 CAN_SCAN_INDEX_2LSB_20_06 "CAN_SCAN_INDEX_2LSB_20_06"; +BA_ "GenMsgSendType" BO_ 306 1; +BA_ "GenMsgILSupport" BO_ 306 1; +BA_ "GenMsgNrOfRepetition" BO_ 306 0; +BA_ "GenMsgCycleTime" BO_ 306 0; +BA_ "NetworkInitialization" BO_ 306 0; +BA_ "GenMsgDelayTime" BO_ 306 0; +BA_ "GenSigVtEn" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_01 "CAN_DET_CONFID_AZIMUTH_19_01"; +BA_ "GenSigVtName" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_01 "CAN_DET_CONFID_AZIMUTH_19_01"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_01 "CAN_DET_CONFID_AZIMUTH_19_01"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_01 "CAN_DET_SUPER_RES_TARGET_19_01"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_ND_TARGET_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_ND_TARGET_19_01 "CAN_DET_ND_TARGET_19_01"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_01 "CAN_DET_HOST_VEH_CLUTTER_19_01"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_VALID_LEVEL_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_VALID_LEVEL_19_01 "CAN_DET_VALID_LEVEL_19_01"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_AZIMUTH_19_01 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AZIMUTH_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AZIMUTH_19_01 "CAN_DET_AZIMUTH_19_01"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_19_01 "CAN_DET_RANGE_19_01"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_RANGE_RATE_19_01 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_RATE_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_RATE_19_01 "CAN_DET_RANGE_RATE_19_01"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AMPLITUDE_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AMPLITUDE_19_01 "CAN_DET_AMPLITUDE_19_01"; +BA_ "GenSigSendType" SG_ 306 CAN_SCAN_INDEX_2LSB_19_01 0; +BA_ "GenSigCmt" SG_ 306 CAN_SCAN_INDEX_2LSB_19_01 "CAN_SCAN_INDEX_2LSB_19_01"; +BA_ "GenSigVtEn" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_02 "CAN_DET_CONFID_AZIMUTH_19_02"; +BA_ "GenSigVtName" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_02 "CAN_DET_CONFID_AZIMUTH_19_02"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_02 "CAN_DET_CONFID_AZIMUTH_19_02"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_02 "CAN_DET_SUPER_RES_TARGET_19_02"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_ND_TARGET_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_ND_TARGET_19_02 "CAN_DET_ND_TARGET_19_02"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_02 "CAN_DET_HOST_VEH_CLUTTER_19_02"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_VALID_LEVEL_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_VALID_LEVEL_19_02 "CAN_DET_VALID_LEVEL_19_02"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_AZIMUTH_19_02 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AZIMUTH_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AZIMUTH_19_02 "CAN_DET_AZIMUTH_19_02"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_19_02 "CAN_DET_RANGE_19_02"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_RANGE_RATE_19_02 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_RATE_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_RATE_19_02 "CAN_DET_RANGE_RATE_19_02"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AMPLITUDE_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AMPLITUDE_19_02 "CAN_DET_AMPLITUDE_19_02"; +BA_ "GenSigSendType" SG_ 306 CAN_SCAN_INDEX_2LSB_19_02 0; +BA_ "GenSigCmt" SG_ 306 CAN_SCAN_INDEX_2LSB_19_02 "CAN_SCAN_INDEX_2LSB_19_02"; +BA_ "GenSigVtEn" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_03 "CAN_DET_CONFID_AZIMUTH_19_03"; +BA_ "GenSigVtName" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_03 "CAN_DET_CONFID_AZIMUTH_19_03"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_03 "CAN_DET_CONFID_AZIMUTH_19_03"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_03 "CAN_DET_SUPER_RES_TARGET_19_03"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_ND_TARGET_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_ND_TARGET_19_03 "CAN_DET_ND_TARGET_19_03"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_03 "CAN_DET_HOST_VEH_CLUTTER_19_03"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_VALID_LEVEL_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_VALID_LEVEL_19_03 "CAN_DET_VALID_LEVEL_19_03"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_AZIMUTH_19_03 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AZIMUTH_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AZIMUTH_19_03 "CAN_DET_AZIMUTH_19_03"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_19_03 "CAN_DET_RANGE_19_03"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_RANGE_RATE_19_03 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_RATE_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_RATE_19_03 "CAN_DET_RANGE_RATE_19_03"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AMPLITUDE_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AMPLITUDE_19_03 "CAN_DET_AMPLITUDE_19_03"; +BA_ "GenSigSendType" SG_ 306 CAN_SCAN_INDEX_2LSB_19_03 0; +BA_ "GenSigCmt" SG_ 306 CAN_SCAN_INDEX_2LSB_19_03 "CAN_SCAN_INDEX_2LSB_19_03"; +BA_ "GenSigVtEn" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_04 "CAN_DET_CONFID_AZIMUTH_19_04"; +BA_ "GenSigVtName" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_04 "CAN_DET_CONFID_AZIMUTH_19_04"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_04 "CAN_DET_CONFID_AZIMUTH_19_04"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_04 "CAN_DET_SUPER_RES_TARGET_19_04"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_ND_TARGET_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_ND_TARGET_19_04 "CAN_DET_ND_TARGET_19_04"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_04 "CAN_DET_HOST_VEH_CLUTTER_19_04"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_VALID_LEVEL_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_VALID_LEVEL_19_04 "CAN_DET_VALID_LEVEL_19_04"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_AZIMUTH_19_04 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AZIMUTH_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AZIMUTH_19_04 "CAN_DET_AZIMUTH_19_04"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_19_04 "CAN_DET_RANGE_19_04"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_RANGE_RATE_19_04 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_RATE_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_RATE_19_04 "CAN_DET_RANGE_RATE_19_04"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AMPLITUDE_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AMPLITUDE_19_04 "CAN_DET_AMPLITUDE_19_04"; +BA_ "GenSigSendType" SG_ 306 CAN_SCAN_INDEX_2LSB_19_04 0; +BA_ "GenSigCmt" SG_ 306 CAN_SCAN_INDEX_2LSB_19_04 "CAN_SCAN_INDEX_2LSB_19_04"; +BA_ "GenSigVtEn" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_05 "CAN_DET_CONFID_AZIMUTH_19_05"; +BA_ "GenSigVtName" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_05 "CAN_DET_CONFID_AZIMUTH_19_05"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_05 "CAN_DET_CONFID_AZIMUTH_19_05"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_05 "CAN_DET_SUPER_RES_TARGET_19_05"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_ND_TARGET_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_ND_TARGET_19_05 "CAN_DET_ND_TARGET_19_05"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_05 "CAN_DET_HOST_VEH_CLUTTER_19_05"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_VALID_LEVEL_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_VALID_LEVEL_19_05 "CAN_DET_VALID_LEVEL_19_05"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_AZIMUTH_19_05 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AZIMUTH_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AZIMUTH_19_05 "CAN_DET_AZIMUTH_19_05"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_19_05 "CAN_DET_RANGE_19_05"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_RANGE_RATE_19_05 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_RATE_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_RATE_19_05 "CAN_DET_RANGE_RATE_19_05"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AMPLITUDE_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AMPLITUDE_19_05 "CAN_DET_AMPLITUDE_19_05"; +BA_ "GenSigSendType" SG_ 306 CAN_SCAN_INDEX_2LSB_19_05 0; +BA_ "GenSigCmt" SG_ 306 CAN_SCAN_INDEX_2LSB_19_05 "CAN_SCAN_INDEX_2LSB_19_05"; +BA_ "GenSigVtEn" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_06 "CAN_DET_CONFID_AZIMUTH_19_06"; +BA_ "GenSigVtName" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_06 "CAN_DET_CONFID_AZIMUTH_19_06"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_CONFID_AZIMUTH_19_06 "CAN_DET_CONFID_AZIMUTH_19_06"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_SUPER_RES_TARGET_19_06 "CAN_DET_SUPER_RES_TARGET_19_06"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_ND_TARGET_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_ND_TARGET_19_06 "CAN_DET_ND_TARGET_19_06"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_HOST_VEH_CLUTTER_19_06 "CAN_DET_HOST_VEH_CLUTTER_19_06"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_VALID_LEVEL_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_VALID_LEVEL_19_06 "CAN_DET_VALID_LEVEL_19_06"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_AZIMUTH_19_06 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AZIMUTH_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AZIMUTH_19_06 "CAN_DET_AZIMUTH_19_06"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_19_06 "CAN_DET_RANGE_19_06"; +BA_ "GenSigStartValue" SG_ 306 CAN_DET_RANGE_RATE_19_06 0; +BA_ "GenSigSendType" SG_ 306 CAN_DET_RANGE_RATE_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_RANGE_RATE_19_06 "CAN_DET_RANGE_RATE_19_06"; +BA_ "GenSigSendType" SG_ 306 CAN_DET_AMPLITUDE_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_DET_AMPLITUDE_19_06 "CAN_DET_AMPLITUDE_19_06"; +BA_ "GenSigSendType" SG_ 306 CAN_SCAN_INDEX_2LSB_19_06 0; +BA_ "GenSigCmt" SG_ 306 CAN_SCAN_INDEX_2LSB_19_06 "CAN_SCAN_INDEX_2LSB_19_06"; +BA_ "GenMsgSendType" BO_ 305 1; +BA_ "GenMsgILSupport" BO_ 305 1; +BA_ "GenMsgNrOfRepetition" BO_ 305 0; +BA_ "GenMsgCycleTime" BO_ 305 0; +BA_ "NetworkInitialization" BO_ 305 0; +BA_ "GenMsgDelayTime" BO_ 305 0; +BA_ "GenSigVtEn" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_01 "CAN_DET_CONFID_AZIMUTH_18_01"; +BA_ "GenSigVtName" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_01 "CAN_DET_CONFID_AZIMUTH_18_01"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_01 "CAN_DET_CONFID_AZIMUTH_18_01"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_01 "CAN_DET_SUPER_RES_TARGET_18_01"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_ND_TARGET_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_ND_TARGET_18_01 "CAN_DET_ND_TARGET_18_01"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_01 "CAN_DET_HOST_VEH_CLUTTER_18_01"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_VALID_LEVEL_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_VALID_LEVEL_18_01 "CAN_DET_VALID_LEVEL_18_01"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_AZIMUTH_18_01 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AZIMUTH_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AZIMUTH_18_01 "CAN_DET_AZIMUTH_18_01"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_18_01 "CAN_DET_RANGE_18_01"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_RANGE_RATE_18_01 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_RATE_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_RATE_18_01 "CAN_DET_RANGE_RATE_18_01"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AMPLITUDE_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AMPLITUDE_18_01 "CAN_DET_AMPLITUDE_18_01"; +BA_ "GenSigSendType" SG_ 305 CAN_SCAN_INDEX_2LSB_18_01 0; +BA_ "GenSigCmt" SG_ 305 CAN_SCAN_INDEX_2LSB_18_01 "CAN_SCAN_INDEX_2LSB_18_01"; +BA_ "GenSigVtEn" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_02 "CAN_DET_CONFID_AZIMUTH_18_02"; +BA_ "GenSigVtName" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_02 "CAN_DET_CONFID_AZIMUTH_18_02"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_02 "CAN_DET_CONFID_AZIMUTH_18_02"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_02 "CAN_DET_SUPER_RES_TARGET_18_02"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_ND_TARGET_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_ND_TARGET_18_02 "CAN_DET_ND_TARGET_18_02"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_02 "CAN_DET_HOST_VEH_CLUTTER_18_02"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_VALID_LEVEL_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_VALID_LEVEL_18_02 "CAN_DET_VALID_LEVEL_18_02"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_AZIMUTH_18_02 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AZIMUTH_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AZIMUTH_18_02 "CAN_DET_AZIMUTH_18_02"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_18_02 "CAN_DET_RANGE_18_02"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_RANGE_RATE_18_02 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_RATE_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_RATE_18_02 "CAN_DET_RANGE_RATE_18_02"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AMPLITUDE_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AMPLITUDE_18_02 "CAN_DET_AMPLITUDE_18_02"; +BA_ "GenSigSendType" SG_ 305 CAN_SCAN_INDEX_2LSB_18_02 0; +BA_ "GenSigCmt" SG_ 305 CAN_SCAN_INDEX_2LSB_18_02 "CAN_SCAN_INDEX_2LSB_18_02"; +BA_ "GenSigVtEn" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_03 "CAN_DET_CONFID_AZIMUTH_18_03"; +BA_ "GenSigVtName" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_03 "CAN_DET_CONFID_AZIMUTH_18_03"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_03 "CAN_DET_CONFID_AZIMUTH_18_03"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_03 "CAN_DET_SUPER_RES_TARGET_18_03"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_ND_TARGET_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_ND_TARGET_18_03 "CAN_DET_ND_TARGET_18_03"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_03 "CAN_DET_HOST_VEH_CLUTTER_18_03"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_VALID_LEVEL_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_VALID_LEVEL_18_03 "CAN_DET_VALID_LEVEL_18_03"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_AZIMUTH_18_03 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AZIMUTH_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AZIMUTH_18_03 "CAN_DET_AZIMUTH_18_03"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_18_03 "CAN_DET_RANGE_18_03"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_RANGE_RATE_18_03 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_RATE_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_RATE_18_03 "CAN_DET_RANGE_RATE_18_03"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AMPLITUDE_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AMPLITUDE_18_03 "CAN_DET_AMPLITUDE_18_03"; +BA_ "GenSigSendType" SG_ 305 CAN_SCAN_INDEX_2LSB_18_03 0; +BA_ "GenSigCmt" SG_ 305 CAN_SCAN_INDEX_2LSB_18_03 "CAN_SCAN_INDEX_2LSB_18_03"; +BA_ "GenSigVtEn" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_04 "CAN_DET_CONFID_AZIMUTH_18_04"; +BA_ "GenSigVtName" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_04 "CAN_DET_CONFID_AZIMUTH_18_04"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_04 "CAN_DET_CONFID_AZIMUTH_18_04"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_04 "CAN_DET_SUPER_RES_TARGET_18_04"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_ND_TARGET_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_ND_TARGET_18_04 "CAN_DET_ND_TARGET_18_04"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_04 "CAN_DET_HOST_VEH_CLUTTER_18_04"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_VALID_LEVEL_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_VALID_LEVEL_18_04 "CAN_DET_VALID_LEVEL_18_04"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_AZIMUTH_18_04 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AZIMUTH_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AZIMUTH_18_04 "CAN_DET_AZIMUTH_18_04"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_18_04 "CAN_DET_RANGE_18_04"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_RANGE_RATE_18_04 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_RATE_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_RATE_18_04 "CAN_DET_RANGE_RATE_18_04"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AMPLITUDE_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AMPLITUDE_18_04 "CAN_DET_AMPLITUDE_18_04"; +BA_ "GenSigSendType" SG_ 305 CAN_SCAN_INDEX_2LSB_18_04 0; +BA_ "GenSigCmt" SG_ 305 CAN_SCAN_INDEX_2LSB_18_04 "CAN_SCAN_INDEX_2LSB_18_04"; +BA_ "GenSigVtEn" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_05 "CAN_DET_CONFID_AZIMUTH_18_05"; +BA_ "GenSigVtName" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_05 "CAN_DET_CONFID_AZIMUTH_18_05"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_05 "CAN_DET_CONFID_AZIMUTH_18_05"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_05 "CAN_DET_SUPER_RES_TARGET_18_05"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_ND_TARGET_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_ND_TARGET_18_05 "CAN_DET_ND_TARGET_18_05"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_05 "CAN_DET_HOST_VEH_CLUTTER_18_05"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_VALID_LEVEL_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_VALID_LEVEL_18_05 "CAN_DET_VALID_LEVEL_18_05"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_AZIMUTH_18_05 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AZIMUTH_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AZIMUTH_18_05 "CAN_DET_AZIMUTH_18_05"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_18_05 "CAN_DET_RANGE_18_05"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_RANGE_RATE_18_05 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_RATE_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_RATE_18_05 "CAN_DET_RANGE_RATE_18_05"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AMPLITUDE_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AMPLITUDE_18_05 "CAN_DET_AMPLITUDE_18_05"; +BA_ "GenSigSendType" SG_ 305 CAN_SCAN_INDEX_2LSB_18_05 0; +BA_ "GenSigCmt" SG_ 305 CAN_SCAN_INDEX_2LSB_18_05 "CAN_SCAN_INDEX_2LSB_18_05"; +BA_ "GenSigVtEn" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_06 "CAN_DET_CONFID_AZIMUTH_18_06"; +BA_ "GenSigVtName" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_06 "CAN_DET_CONFID_AZIMUTH_18_06"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_CONFID_AZIMUTH_18_06 "CAN_DET_CONFID_AZIMUTH_18_06"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_SUPER_RES_TARGET_18_06 "CAN_DET_SUPER_RES_TARGET_18_06"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_ND_TARGET_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_ND_TARGET_18_06 "CAN_DET_ND_TARGET_18_06"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_HOST_VEH_CLUTTER_18_06 "CAN_DET_HOST_VEH_CLUTTER_18_06"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_VALID_LEVEL_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_VALID_LEVEL_18_06 "CAN_DET_VALID_LEVEL_18_06"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_AZIMUTH_18_06 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AZIMUTH_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AZIMUTH_18_06 "CAN_DET_AZIMUTH_18_06"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_18_06 "CAN_DET_RANGE_18_06"; +BA_ "GenSigStartValue" SG_ 305 CAN_DET_RANGE_RATE_18_06 0; +BA_ "GenSigSendType" SG_ 305 CAN_DET_RANGE_RATE_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_RANGE_RATE_18_06 "CAN_DET_RANGE_RATE_18_06"; +BA_ "GenSigSendType" SG_ 305 CAN_DET_AMPLITUDE_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_DET_AMPLITUDE_18_06 "CAN_DET_AMPLITUDE_18_06"; +BA_ "GenSigSendType" SG_ 305 CAN_SCAN_INDEX_2LSB_18_06 0; +BA_ "GenSigCmt" SG_ 305 CAN_SCAN_INDEX_2LSB_18_06 "CAN_SCAN_INDEX_2LSB_18_06"; +BA_ "GenMsgSendType" BO_ 341 1; +BA_ "GenMsgILSupport" BO_ 341 1; +BA_ "GenMsgNrOfRepetition" BO_ 341 0; +BA_ "GenMsgCycleTime" BO_ 341 0; +BA_ "NetworkInitialization" BO_ 341 0; +BA_ "GenMsgDelayTime" BO_ 341 0; +BA_ "GenSigVtEn" SG_ 341 CAN_DET_CONFID_AZIMUTH_54 "CAN_DET_CONFID_AZIMUTH_54"; +BA_ "GenSigVtName" SG_ 341 CAN_DET_CONFID_AZIMUTH_54 "CAN_DET_CONFID_AZIMUTH_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_CONFID_AZIMUTH_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_CONFID_AZIMUTH_54 "CAN_DET_CONFID_AZIMUTH_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_SUPER_RES_TARGET_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_SUPER_RES_TARGET_54 "CAN_DET_SUPER_RES_TARGET_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_ND_TARGET_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_ND_TARGET_54 "CAN_DET_ND_TARGET_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_HOST_VEH_CLUTTER_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_HOST_VEH_CLUTTER_54 "CAN_DET_HOST_VEH_CLUTTER_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_VALID_LEVEL_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_VALID_LEVEL_54 "CAN_DET_VALID_LEVEL_54"; +BA_ "GenSigStartValue" SG_ 341 CAN_DET_AZIMUTH_54 0; +BA_ "GenSigSendType" SG_ 341 CAN_DET_AZIMUTH_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_AZIMUTH_54 "CAN_DET_AZIMUTH_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_RANGE_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_RANGE_54 "CAN_DET_RANGE_54"; +BA_ "GenSigStartValue" SG_ 341 CAN_DET_RANGE_RATE_54 0; +BA_ "GenSigSendType" SG_ 341 CAN_DET_RANGE_RATE_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_RANGE_RATE_54 "CAN_DET_RANGE_RATE_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_AMPLITUDE_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_AMPLITUDE_54 "CAN_DET_AMPLITUDE_54"; +BA_ "GenSigSendType" SG_ 341 CAN_SCAN_INDEX_2LSB_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_SCAN_INDEX_2LSB_54 "CAN_SCAN_INDEX_2LSB_54"; +BA_ "GenMsgSendType" BO_ 340 1; +BA_ "GenMsgILSupport" BO_ 340 1; +BA_ "GenMsgNrOfRepetition" BO_ 340 0; +BA_ "GenMsgCycleTime" BO_ 340 0; +BA_ "NetworkInitialization" BO_ 340 0; +BA_ "GenMsgDelayTime" BO_ 340 0; +BA_ "GenSigVtEn" SG_ 340 CAN_DET_CONFID_AZIMUTH_53 "CAN_DET_CONFID_AZIMUTH_53"; +BA_ "GenSigVtName" SG_ 340 CAN_DET_CONFID_AZIMUTH_53 "CAN_DET_CONFID_AZIMUTH_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_CONFID_AZIMUTH_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_CONFID_AZIMUTH_53 "CAN_DET_CONFID_AZIMUTH_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_SUPER_RES_TARGET_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_SUPER_RES_TARGET_53 "CAN_DET_SUPER_RES_TARGET_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_ND_TARGET_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_ND_TARGET_53 "CAN_DET_ND_TARGET_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_HOST_VEH_CLUTTER_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_HOST_VEH_CLUTTER_53 "CAN_DET_HOST_VEH_CLUTTER_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_VALID_LEVEL_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_VALID_LEVEL_53 "CAN_DET_VALID_LEVEL_53"; +BA_ "GenSigStartValue" SG_ 340 CAN_DET_AZIMUTH_53 0; +BA_ "GenSigSendType" SG_ 340 CAN_DET_AZIMUTH_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_AZIMUTH_53 "CAN_DET_AZIMUTH_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_RANGE_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_RANGE_53 "CAN_DET_RANGE_53"; +BA_ "GenSigStartValue" SG_ 340 CAN_DET_RANGE_RATE_53 0; +BA_ "GenSigSendType" SG_ 340 CAN_DET_RANGE_RATE_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_RANGE_RATE_53 "CAN_DET_RANGE_RATE_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_AMPLITUDE_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_AMPLITUDE_53 "CAN_DET_AMPLITUDE_53"; +BA_ "GenSigSendType" SG_ 340 CAN_SCAN_INDEX_2LSB_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_SCAN_INDEX_2LSB_53 "CAN_SCAN_INDEX_2LSB_53"; +BA_ "GenMsgSendType" BO_ 339 1; +BA_ "GenMsgILSupport" BO_ 339 1; +BA_ "GenMsgNrOfRepetition" BO_ 339 0; +BA_ "GenMsgCycleTime" BO_ 339 0; +BA_ "NetworkInitialization" BO_ 339 0; +BA_ "GenMsgDelayTime" BO_ 339 0; +BA_ "GenSigVtEn" SG_ 339 CAN_DET_CONFID_AZIMUTH_52 "CAN_DET_CONFID_AZIMUTH_52"; +BA_ "GenSigVtName" SG_ 339 CAN_DET_CONFID_AZIMUTH_52 "CAN_DET_CONFID_AZIMUTH_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_CONFID_AZIMUTH_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_CONFID_AZIMUTH_52 "CAN_DET_CONFID_AZIMUTH_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_SUPER_RES_TARGET_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_SUPER_RES_TARGET_52 "CAN_DET_SUPER_RES_TARGET_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_ND_TARGET_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_ND_TARGET_52 "CAN_DET_ND_TARGET_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_HOST_VEH_CLUTTER_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_HOST_VEH_CLUTTER_52 "CAN_DET_HOST_VEH_CLUTTER_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_VALID_LEVEL_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_VALID_LEVEL_52 "CAN_DET_VALID_LEVEL_52"; +BA_ "GenSigStartValue" SG_ 339 CAN_DET_AZIMUTH_52 0; +BA_ "GenSigSendType" SG_ 339 CAN_DET_AZIMUTH_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_AZIMUTH_52 "CAN_DET_AZIMUTH_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_RANGE_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_RANGE_52 "CAN_DET_RANGE_52"; +BA_ "GenSigStartValue" SG_ 339 CAN_DET_RANGE_RATE_52 0; +BA_ "GenSigSendType" SG_ 339 CAN_DET_RANGE_RATE_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_RANGE_RATE_52 "CAN_DET_RANGE_RATE_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_AMPLITUDE_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_AMPLITUDE_52 "CAN_DET_AMPLITUDE_52"; +BA_ "GenSigSendType" SG_ 339 CAN_SCAN_INDEX_2LSB_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_SCAN_INDEX_2LSB_52 "CAN_SCAN_INDEX_2LSB_52"; +BA_ "GenMsgSendType" BO_ 338 1; +BA_ "GenMsgILSupport" BO_ 338 1; +BA_ "GenMsgNrOfRepetition" BO_ 338 0; +BA_ "GenMsgCycleTime" BO_ 338 0; +BA_ "NetworkInitialization" BO_ 338 0; +BA_ "GenMsgDelayTime" BO_ 338 0; +BA_ "GenSigVtEn" SG_ 338 CAN_DET_CONFID_AZIMUTH_51 "CAN_DET_CONFID_AZIMUTH_51"; +BA_ "GenSigVtName" SG_ 338 CAN_DET_CONFID_AZIMUTH_51 "CAN_DET_CONFID_AZIMUTH_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_CONFID_AZIMUTH_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_CONFID_AZIMUTH_51 "CAN_DET_CONFID_AZIMUTH_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_SUPER_RES_TARGET_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_SUPER_RES_TARGET_51 "CAN_DET_SUPER_RES_TARGET_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_ND_TARGET_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_ND_TARGET_51 "CAN_DET_ND_TARGET_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_HOST_VEH_CLUTTER_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_HOST_VEH_CLUTTER_51 "CAN_DET_HOST_VEH_CLUTTER_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_VALID_LEVEL_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_VALID_LEVEL_51 "CAN_DET_VALID_LEVEL_51"; +BA_ "GenSigStartValue" SG_ 338 CAN_DET_AZIMUTH_51 0; +BA_ "GenSigSendType" SG_ 338 CAN_DET_AZIMUTH_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_AZIMUTH_51 "CAN_DET_AZIMUTH_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_RANGE_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_RANGE_51 "CAN_DET_RANGE_51"; +BA_ "GenSigStartValue" SG_ 338 CAN_DET_RANGE_RATE_51 0; +BA_ "GenSigSendType" SG_ 338 CAN_DET_RANGE_RATE_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_RANGE_RATE_51 "CAN_DET_RANGE_RATE_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_AMPLITUDE_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_AMPLITUDE_51 "CAN_DET_AMPLITUDE_51"; +BA_ "GenSigSendType" SG_ 338 CAN_SCAN_INDEX_2LSB_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_SCAN_INDEX_2LSB_51 "CAN_SCAN_INDEX_2LSB_51"; +BA_ "GenMsgSendType" BO_ 337 1; +BA_ "GenMsgILSupport" BO_ 337 1; +BA_ "GenMsgNrOfRepetition" BO_ 337 0; +BA_ "GenMsgCycleTime" BO_ 337 0; +BA_ "NetworkInitialization" BO_ 337 0; +BA_ "GenMsgDelayTime" BO_ 337 0; +BA_ "GenSigVtEn" SG_ 337 CAN_DET_CONFID_AZIMUTH_50 "CAN_DET_CONFID_AZIMUTH_50"; +BA_ "GenSigVtName" SG_ 337 CAN_DET_CONFID_AZIMUTH_50 "CAN_DET_CONFID_AZIMUTH_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_CONFID_AZIMUTH_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_CONFID_AZIMUTH_50 "CAN_DET_CONFID_AZIMUTH_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_SUPER_RES_TARGET_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_SUPER_RES_TARGET_50 "CAN_DET_SUPER_RES_TARGET_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_ND_TARGET_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_ND_TARGET_50 "CAN_DET_ND_TARGET_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_HOST_VEH_CLUTTER_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_HOST_VEH_CLUTTER_50 "CAN_DET_HOST_VEH_CLUTTER_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_VALID_LEVEL_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_VALID_LEVEL_50 "CAN_DET_VALID_LEVEL_50"; +BA_ "GenSigStartValue" SG_ 337 CAN_DET_AZIMUTH_50 0; +BA_ "GenSigSendType" SG_ 337 CAN_DET_AZIMUTH_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_AZIMUTH_50 "CAN_DET_AZIMUTH_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_RANGE_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_RANGE_50 "CAN_DET_RANGE_50"; +BA_ "GenSigStartValue" SG_ 337 CAN_DET_RANGE_RATE_50 0; +BA_ "GenSigSendType" SG_ 337 CAN_DET_RANGE_RATE_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_RANGE_RATE_50 "CAN_DET_RANGE_RATE_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_AMPLITUDE_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_AMPLITUDE_50 "CAN_DET_AMPLITUDE_50"; +BA_ "GenSigSendType" SG_ 337 CAN_SCAN_INDEX_2LSB_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_SCAN_INDEX_2LSB_50 "CAN_SCAN_INDEX_2LSB_50"; +BA_ "GenMsgSendType" BO_ 336 1; +BA_ "GenMsgILSupport" BO_ 336 1; +BA_ "GenMsgNrOfRepetition" BO_ 336 0; +BA_ "GenMsgCycleTime" BO_ 336 0; +BA_ "NetworkInitialization" BO_ 336 0; +BA_ "GenMsgDelayTime" BO_ 336 0; +BA_ "GenSigVtEn" SG_ 336 CAN_DET_CONFID_AZIMUTH_49 "CAN_DET_CONFID_AZIMUTH_49"; +BA_ "GenSigVtName" SG_ 336 CAN_DET_CONFID_AZIMUTH_49 "CAN_DET_CONFID_AZIMUTH_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_CONFID_AZIMUTH_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_CONFID_AZIMUTH_49 "CAN_DET_CONFID_AZIMUTH_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_SUPER_RES_TARGET_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_SUPER_RES_TARGET_49 "CAN_DET_SUPER_RES_TARGET_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_ND_TARGET_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_ND_TARGET_49 "CAN_DET_ND_TARGET_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_HOST_VEH_CLUTTER_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_HOST_VEH_CLUTTER_49 "CAN_DET_HOST_VEH_CLUTTER_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_VALID_LEVEL_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_VALID_LEVEL_49 "CAN_DET_VALID_LEVEL_49"; +BA_ "GenSigStartValue" SG_ 336 CAN_DET_AZIMUTH_49 0; +BA_ "GenSigSendType" SG_ 336 CAN_DET_AZIMUTH_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_AZIMUTH_49 "CAN_DET_AZIMUTH_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_RANGE_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_RANGE_49 "CAN_DET_RANGE_49"; +BA_ "GenSigStartValue" SG_ 336 CAN_DET_RANGE_RATE_49 0; +BA_ "GenSigSendType" SG_ 336 CAN_DET_RANGE_RATE_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_RANGE_RATE_49 "CAN_DET_RANGE_RATE_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_AMPLITUDE_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_AMPLITUDE_49 "CAN_DET_AMPLITUDE_49"; +BA_ "GenSigSendType" SG_ 336 CAN_SCAN_INDEX_2LSB_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_SCAN_INDEX_2LSB_49 "CAN_SCAN_INDEX_2LSB_49"; +BA_ "GenMsgSendType" BO_ 326 1; +BA_ "GenMsgILSupport" BO_ 326 1; +BA_ "GenMsgNrOfRepetition" BO_ 326 0; +BA_ "GenMsgCycleTime" BO_ 326 0; +BA_ "NetworkInitialization" BO_ 326 0; +BA_ "GenMsgDelayTime" BO_ 326 0; +BA_ "GenSigVtEn" SG_ 326 CAN_DET_CONFID_AZIMUTH_39 "CAN_DET_CONFID_AZIMUTH_39"; +BA_ "GenSigVtName" SG_ 326 CAN_DET_CONFID_AZIMUTH_39 "CAN_DET_CONFID_AZIMUTH_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_CONFID_AZIMUTH_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_CONFID_AZIMUTH_39 "CAN_DET_CONFID_AZIMUTH_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_SUPER_RES_TARGET_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_SUPER_RES_TARGET_39 "CAN_DET_SUPER_RES_TARGET_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_ND_TARGET_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_ND_TARGET_39 "CAN_DET_ND_TARGET_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_HOST_VEH_CLUTTER_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_HOST_VEH_CLUTTER_39 "CAN_DET_HOST_VEH_CLUTTER_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_VALID_LEVEL_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_VALID_LEVEL_39 "CAN_DET_VALID_LEVEL_39"; +BA_ "GenSigStartValue" SG_ 326 CAN_DET_AZIMUTH_39 0; +BA_ "GenSigSendType" SG_ 326 CAN_DET_AZIMUTH_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_AZIMUTH_39 "CAN_DET_AZIMUTH_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_RANGE_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_RANGE_39 "CAN_DET_RANGE_39"; +BA_ "GenSigStartValue" SG_ 326 CAN_DET_RANGE_RATE_39 0; +BA_ "GenSigSendType" SG_ 326 CAN_DET_RANGE_RATE_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_RANGE_RATE_39 "CAN_DET_RANGE_RATE_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_AMPLITUDE_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_AMPLITUDE_39 "CAN_DET_AMPLITUDE_39"; +BA_ "GenSigSendType" SG_ 326 CAN_SCAN_INDEX_2LSB_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_SCAN_INDEX_2LSB_39 "CAN_SCAN_INDEX_2LSB_39"; +BA_ "GenMsgSendType" BO_ 315 1; +BA_ "GenMsgILSupport" BO_ 315 1; +BA_ "GenMsgNrOfRepetition" BO_ 315 0; +BA_ "GenMsgCycleTime" BO_ 315 0; +BA_ "NetworkInitialization" BO_ 315 0; +BA_ "GenMsgDelayTime" BO_ 315 0; +BA_ "GenSigVtEn" SG_ 315 CAN_DET_CONFID_AZIMUTH_28 "CAN_DET_CONFID_AZIMUTH_28"; +BA_ "GenSigVtName" SG_ 315 CAN_DET_CONFID_AZIMUTH_28 "CAN_DET_CONFID_AZIMUTH_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_CONFID_AZIMUTH_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_CONFID_AZIMUTH_28 "CAN_DET_CONFID_AZIMUTH_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_SUPER_RES_TARGET_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_SUPER_RES_TARGET_28 "CAN_DET_SUPER_RES_TARGET_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_ND_TARGET_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_ND_TARGET_28 "CAN_DET_ND_TARGET_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_HOST_VEH_CLUTTER_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_HOST_VEH_CLUTTER_28 "CAN_DET_HOST_VEH_CLUTTER_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_VALID_LEVEL_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_VALID_LEVEL_28 "CAN_DET_VALID_LEVEL_28"; +BA_ "GenSigStartValue" SG_ 315 CAN_DET_AZIMUTH_28 0; +BA_ "GenSigSendType" SG_ 315 CAN_DET_AZIMUTH_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_AZIMUTH_28 "CAN_DET_AZIMUTH_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_RANGE_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_RANGE_28 "CAN_DET_RANGE_28"; +BA_ "GenSigStartValue" SG_ 315 CAN_DET_RANGE_RATE_28 0; +BA_ "GenSigSendType" SG_ 315 CAN_DET_RANGE_RATE_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_RANGE_RATE_28 "CAN_DET_RANGE_RATE_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_AMPLITUDE_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_AMPLITUDE_28 "CAN_DET_AMPLITUDE_28"; +BA_ "GenSigSendType" SG_ 315 CAN_SCAN_INDEX_2LSB_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_SCAN_INDEX_2LSB_28 "CAN_SCAN_INDEX_2LSB_28"; +BA_ "GenMsgSendType" BO_ 304 1; +BA_ "GenMsgILSupport" BO_ 304 1; +BA_ "GenMsgNrOfRepetition" BO_ 304 0; +BA_ "GenMsgCycleTime" BO_ 304 0; +BA_ "NetworkInitialization" BO_ 304 0; +BA_ "GenMsgDelayTime" BO_ 304 0; +BA_ "GenSigVtEn" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_01 "CAN_DET_CONFID_AZIMUTH_17_01"; +BA_ "GenSigVtName" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_01 "CAN_DET_CONFID_AZIMUTH_17_01"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_01 "CAN_DET_CONFID_AZIMUTH_17_01"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_01 "CAN_DET_SUPER_RES_TARGET_17_01"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_ND_TARGET_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_ND_TARGET_17_01 "CAN_DET_ND_TARGET_17_01"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_01 "CAN_DET_HOST_VEH_CLUTTER_17_01"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_VALID_LEVEL_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_VALID_LEVEL_17_01 "CAN_DET_VALID_LEVEL_17_01"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_AZIMUTH_17_01 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AZIMUTH_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AZIMUTH_17_01 "CAN_DET_AZIMUTH_17_01"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_17_01 "CAN_DET_RANGE_17_01"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_RANGE_RATE_17_01 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_RATE_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_RATE_17_01 "CAN_DET_RANGE_RATE_17_01"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AMPLITUDE_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AMPLITUDE_17_01 "CAN_DET_AMPLITUDE_17_01"; +BA_ "GenSigSendType" SG_ 304 CAN_SCAN_INDEX_2LSB_17_01 0; +BA_ "GenSigCmt" SG_ 304 CAN_SCAN_INDEX_2LSB_17_01 "CAN_SCAN_INDEX_2LSB_17_01"; +BA_ "GenSigVtEn" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_02 "CAN_DET_CONFID_AZIMUTH_17_02"; +BA_ "GenSigVtName" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_02 "CAN_DET_CONFID_AZIMUTH_17_02"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_02 "CAN_DET_CONFID_AZIMUTH_17_02"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_02 "CAN_DET_SUPER_RES_TARGET_17_02"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_ND_TARGET_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_ND_TARGET_17_02 "CAN_DET_ND_TARGET_17_02"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_02 "CAN_DET_HOST_VEH_CLUTTER_17_02"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_VALID_LEVEL_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_VALID_LEVEL_17_02 "CAN_DET_VALID_LEVEL_17_02"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_AZIMUTH_17_02 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AZIMUTH_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AZIMUTH_17_02 "CAN_DET_AZIMUTH_17_02"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_17_02 "CAN_DET_RANGE_17_02"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_RANGE_RATE_17_02 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_RATE_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_RATE_17_02 "CAN_DET_RANGE_RATE_17_02"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AMPLITUDE_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AMPLITUDE_17_02 "CAN_DET_AMPLITUDE_17_02"; +BA_ "GenSigSendType" SG_ 304 CAN_SCAN_INDEX_2LSB_17_02 0; +BA_ "GenSigCmt" SG_ 304 CAN_SCAN_INDEX_2LSB_17_02 "CAN_SCAN_INDEX_2LSB_17_02"; +BA_ "GenSigVtEn" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_03 "CAN_DET_CONFID_AZIMUTH_17_03"; +BA_ "GenSigVtName" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_03 "CAN_DET_CONFID_AZIMUTH_17_03"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_03 "CAN_DET_CONFID_AZIMUTH_17_03"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_03 "CAN_DET_SUPER_RES_TARGET_17_03"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_ND_TARGET_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_ND_TARGET_17_03 "CAN_DET_ND_TARGET_17_03"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_03 "CAN_DET_HOST_VEH_CLUTTER_17_03"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_VALID_LEVEL_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_VALID_LEVEL_17_03 "CAN_DET_VALID_LEVEL_17_03"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_AZIMUTH_17_03 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AZIMUTH_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AZIMUTH_17_03 "CAN_DET_AZIMUTH_17_03"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_17_03 "CAN_DET_RANGE_17_03"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_RANGE_RATE_17_03 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_RATE_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_RATE_17_03 "CAN_DET_RANGE_RATE_17_03"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AMPLITUDE_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AMPLITUDE_17_03 "CAN_DET_AMPLITUDE_17_03"; +BA_ "GenSigSendType" SG_ 304 CAN_SCAN_INDEX_2LSB_17_03 0; +BA_ "GenSigCmt" SG_ 304 CAN_SCAN_INDEX_2LSB_17_03 "CAN_SCAN_INDEX_2LSB_17_03"; +BA_ "GenSigVtEn" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_04 "CAN_DET_CONFID_AZIMUTH_17_04"; +BA_ "GenSigVtName" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_04 "CAN_DET_CONFID_AZIMUTH_17_04"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_04 "CAN_DET_CONFID_AZIMUTH_17_04"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_04 "CAN_DET_SUPER_RES_TARGET_17_04"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_ND_TARGET_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_ND_TARGET_17_04 "CAN_DET_ND_TARGET_17_04"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_04 "CAN_DET_HOST_VEH_CLUTTER_17_04"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_VALID_LEVEL_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_VALID_LEVEL_17_04 "CAN_DET_VALID_LEVEL_17_04"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_AZIMUTH_17_04 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AZIMUTH_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AZIMUTH_17_04 "CAN_DET_AZIMUTH_17_04"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_17_04 "CAN_DET_RANGE_17_04"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_RANGE_RATE_17_04 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_RATE_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_RATE_17_04 "CAN_DET_RANGE_RATE_17_04"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AMPLITUDE_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AMPLITUDE_17_04 "CAN_DET_AMPLITUDE_17_04"; +BA_ "GenSigSendType" SG_ 304 CAN_SCAN_INDEX_2LSB_17_04 0; +BA_ "GenSigCmt" SG_ 304 CAN_SCAN_INDEX_2LSB_17_04 "CAN_SCAN_INDEX_2LSB_17_04"; +BA_ "GenSigVtEn" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_05 "CAN_DET_CONFID_AZIMUTH_17_05"; +BA_ "GenSigVtName" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_05 "CAN_DET_CONFID_AZIMUTH_17_05"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_05 "CAN_DET_CONFID_AZIMUTH_17_05"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_05 "CAN_DET_SUPER_RES_TARGET_17_05"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_ND_TARGET_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_ND_TARGET_17_05 "CAN_DET_ND_TARGET_17_05"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_05 "CAN_DET_HOST_VEH_CLUTTER_17_05"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_VALID_LEVEL_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_VALID_LEVEL_17_05 "CAN_DET_VALID_LEVEL_17_05"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_AZIMUTH_17_05 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AZIMUTH_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AZIMUTH_17_05 "CAN_DET_AZIMUTH_17_05"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_17_05 "CAN_DET_RANGE_17_05"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_RANGE_RATE_17_05 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_RATE_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_RATE_17_05 "CAN_DET_RANGE_RATE_17_05"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AMPLITUDE_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AMPLITUDE_17_05 "CAN_DET_AMPLITUDE_17_05"; +BA_ "GenSigSendType" SG_ 304 CAN_SCAN_INDEX_2LSB_17_05 0; +BA_ "GenSigCmt" SG_ 304 CAN_SCAN_INDEX_2LSB_17_05 "CAN_SCAN_INDEX_2LSB_17_05"; +BA_ "GenSigVtEn" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_06 "CAN_DET_CONFID_AZIMUTH_17_06"; +BA_ "GenSigVtName" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_06 "CAN_DET_CONFID_AZIMUTH_17_06"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_CONFID_AZIMUTH_17_06 "CAN_DET_CONFID_AZIMUTH_17_06"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_SUPER_RES_TARGET_17_06 "CAN_DET_SUPER_RES_TARGET_17_06"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_ND_TARGET_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_ND_TARGET_17_06 "CAN_DET_ND_TARGET_17_06"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_HOST_VEH_CLUTTER_17_06 "CAN_DET_HOST_VEH_CLUTTER_17_06"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_VALID_LEVEL_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_VALID_LEVEL_17_06 "CAN_DET_VALID_LEVEL_17_06"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_AZIMUTH_17_06 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AZIMUTH_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AZIMUTH_17_06 "CAN_DET_AZIMUTH_17_06"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_17_06 "CAN_DET_RANGE_17_06"; +BA_ "GenSigStartValue" SG_ 304 CAN_DET_RANGE_RATE_17_06 0; +BA_ "GenSigSendType" SG_ 304 CAN_DET_RANGE_RATE_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_RANGE_RATE_17_06 "CAN_DET_RANGE_RATE_17_06"; +BA_ "GenSigSendType" SG_ 304 CAN_DET_AMPLITUDE_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_DET_AMPLITUDE_17_06 "CAN_DET_AMPLITUDE_17_06"; +BA_ "GenSigSendType" SG_ 304 CAN_SCAN_INDEX_2LSB_17_06 0; +BA_ "GenSigCmt" SG_ 304 CAN_SCAN_INDEX_2LSB_17_06 "CAN_SCAN_INDEX_2LSB_17_06"; +BA_ "GenMsgSendType" BO_ 303 1; +BA_ "GenMsgILSupport" BO_ 303 1; +BA_ "GenMsgNrOfRepetition" BO_ 303 0; +BA_ "GenMsgCycleTime" BO_ 303 0; +BA_ "NetworkInitialization" BO_ 303 0; +BA_ "GenMsgDelayTime" BO_ 303 0; +BA_ "GenSigVtEn" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_01 "CAN_DET_CONFID_AZIMUTH_16_01"; +BA_ "GenSigVtName" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_01 "CAN_DET_CONFID_AZIMUTH_16_01"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_01 "CAN_DET_CONFID_AZIMUTH_16_01"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_01 "CAN_DET_SUPER_RES_TARGET_16_01"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_ND_TARGET_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_ND_TARGET_16_01 "CAN_DET_ND_TARGET_16_01"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_01 "CAN_DET_HOST_VEH_CLUTTER_16_01"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_VALID_LEVEL_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_VALID_LEVEL_16_01 "CAN_DET_VALID_LEVEL_16_01"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_AZIMUTH_16_01 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AZIMUTH_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AZIMUTH_16_01 "CAN_DET_AZIMUTH_16_01"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_16_01 "CAN_DET_RANGE_16_01"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_RANGE_RATE_16_01 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_RATE_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_RATE_16_01 "CAN_DET_RANGE_RATE_16_01"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AMPLITUDE_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AMPLITUDE_16_01 "CAN_DET_AMPLITUDE_16_01"; +BA_ "GenSigSendType" SG_ 303 CAN_SCAN_INDEX_2LSB_16_01 0; +BA_ "GenSigCmt" SG_ 303 CAN_SCAN_INDEX_2LSB_16_01 "CAN_SCAN_INDEX_2LSB_16_01"; +BA_ "GenSigVtEn" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_02 "CAN_DET_CONFID_AZIMUTH_16_02"; +BA_ "GenSigVtName" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_02 "CAN_DET_CONFID_AZIMUTH_16_02"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_02 "CAN_DET_CONFID_AZIMUTH_16_02"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_02 "CAN_DET_SUPER_RES_TARGET_16_02"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_ND_TARGET_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_ND_TARGET_16_02 "CAN_DET_ND_TARGET_16_02"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_02 "CAN_DET_HOST_VEH_CLUTTER_16_02"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_VALID_LEVEL_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_VALID_LEVEL_16_02 "CAN_DET_VALID_LEVEL_16_02"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_AZIMUTH_16_02 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AZIMUTH_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AZIMUTH_16_02 "CAN_DET_AZIMUTH_16_02"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_16_02 "CAN_DET_RANGE_16_02"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_RANGE_RATE_16_02 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_RATE_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_RATE_16_02 "CAN_DET_RANGE_RATE_16_02"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AMPLITUDE_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AMPLITUDE_16_02 "CAN_DET_AMPLITUDE_16_02"; +BA_ "GenSigSendType" SG_ 303 CAN_SCAN_INDEX_2LSB_16_02 0; +BA_ "GenSigCmt" SG_ 303 CAN_SCAN_INDEX_2LSB_16_02 "CAN_SCAN_INDEX_2LSB_16_02"; +BA_ "GenSigVtEn" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_03 "CAN_DET_CONFID_AZIMUTH_16_03"; +BA_ "GenSigVtName" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_03 "CAN_DET_CONFID_AZIMUTH_16_03"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_03 "CAN_DET_CONFID_AZIMUTH_16_03"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_03 "CAN_DET_SUPER_RES_TARGET_16_03"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_ND_TARGET_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_ND_TARGET_16_03 "CAN_DET_ND_TARGET_16_03"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_03 "CAN_DET_HOST_VEH_CLUTTER_16_03"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_VALID_LEVEL_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_VALID_LEVEL_16_03 "CAN_DET_VALID_LEVEL_16_03"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_AZIMUTH_16_03 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AZIMUTH_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AZIMUTH_16_03 "CAN_DET_AZIMUTH_16_03"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_16_03 "CAN_DET_RANGE_16_03"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_RANGE_RATE_16_03 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_RATE_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_RATE_16_03 "CAN_DET_RANGE_RATE_16_03"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AMPLITUDE_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AMPLITUDE_16_03 "CAN_DET_AMPLITUDE_16_03"; +BA_ "GenSigSendType" SG_ 303 CAN_SCAN_INDEX_2LSB_16_03 0; +BA_ "GenSigCmt" SG_ 303 CAN_SCAN_INDEX_2LSB_16_03 "CAN_SCAN_INDEX_2LSB_16_03"; +BA_ "GenSigVtEn" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_04 "CAN_DET_CONFID_AZIMUTH_16_04"; +BA_ "GenSigVtName" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_04 "CAN_DET_CONFID_AZIMUTH_16_04"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_04 "CAN_DET_CONFID_AZIMUTH_16_04"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_04 "CAN_DET_SUPER_RES_TARGET_16_04"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_ND_TARGET_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_ND_TARGET_16_04 "CAN_DET_ND_TARGET_16_04"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_04 "CAN_DET_HOST_VEH_CLUTTER_16_04"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_VALID_LEVEL_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_VALID_LEVEL_16_04 "CAN_DET_VALID_LEVEL_16_04"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_AZIMUTH_16_04 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AZIMUTH_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AZIMUTH_16_04 "CAN_DET_AZIMUTH_16_04"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_16_04 "CAN_DET_RANGE_16_04"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_RANGE_RATE_16_04 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_RATE_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_RATE_16_04 "CAN_DET_RANGE_RATE_16_04"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AMPLITUDE_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AMPLITUDE_16_04 "CAN_DET_AMPLITUDE_16_04"; +BA_ "GenSigSendType" SG_ 303 CAN_SCAN_INDEX_2LSB_16_04 0; +BA_ "GenSigCmt" SG_ 303 CAN_SCAN_INDEX_2LSB_16_04 "CAN_SCAN_INDEX_2LSB_16_04"; +BA_ "GenSigVtEn" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_05 "CAN_DET_CONFID_AZIMUTH_16_05"; +BA_ "GenSigVtName" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_05 "CAN_DET_CONFID_AZIMUTH_16_05"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_05 "CAN_DET_CONFID_AZIMUTH_16_05"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_05 "CAN_DET_SUPER_RES_TARGET_16_05"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_ND_TARGET_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_ND_TARGET_16_05 "CAN_DET_ND_TARGET_16_05"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_05 "CAN_DET_HOST_VEH_CLUTTER_16_05"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_VALID_LEVEL_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_VALID_LEVEL_16_05 "CAN_DET_VALID_LEVEL_16_05"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_AZIMUTH_16_05 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AZIMUTH_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AZIMUTH_16_05 "CAN_DET_AZIMUTH_16_05"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_16_05 "CAN_DET_RANGE_16_05"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_RANGE_RATE_16_05 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_RATE_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_RATE_16_05 "CAN_DET_RANGE_RATE_16_05"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AMPLITUDE_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AMPLITUDE_16_05 "CAN_DET_AMPLITUDE_16_05"; +BA_ "GenSigSendType" SG_ 303 CAN_SCAN_INDEX_2LSB_16_05 0; +BA_ "GenSigCmt" SG_ 303 CAN_SCAN_INDEX_2LSB_16_05 "CAN_SCAN_INDEX_2LSB_16_05"; +BA_ "GenSigVtEn" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_06 "CAN_DET_CONFID_AZIMUTH_16_06"; +BA_ "GenSigVtName" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_06 "CAN_DET_CONFID_AZIMUTH_16_06"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_CONFID_AZIMUTH_16_06 "CAN_DET_CONFID_AZIMUTH_16_06"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_SUPER_RES_TARGET_16_06 "CAN_DET_SUPER_RES_TARGET_16_06"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_ND_TARGET_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_ND_TARGET_16_06 "CAN_DET_ND_TARGET_16_06"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_HOST_VEH_CLUTTER_16_06 "CAN_DET_HOST_VEH_CLUTTER_16_06"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_VALID_LEVEL_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_VALID_LEVEL_16_06 "CAN_DET_VALID_LEVEL_16_06"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_AZIMUTH_16_06 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AZIMUTH_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AZIMUTH_16_06 "CAN_DET_AZIMUTH_16_06"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_16_06 "CAN_DET_RANGE_16_06"; +BA_ "GenSigStartValue" SG_ 303 CAN_DET_RANGE_RATE_16_06 0; +BA_ "GenSigSendType" SG_ 303 CAN_DET_RANGE_RATE_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_RANGE_RATE_16_06 "CAN_DET_RANGE_RATE_16_06"; +BA_ "GenSigSendType" SG_ 303 CAN_DET_AMPLITUDE_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_DET_AMPLITUDE_16_06 "CAN_DET_AMPLITUDE_16_06"; +BA_ "GenSigSendType" SG_ 303 CAN_SCAN_INDEX_2LSB_16_06 0; +BA_ "GenSigCmt" SG_ 303 CAN_SCAN_INDEX_2LSB_16_06 "CAN_SCAN_INDEX_2LSB_16_06"; +BA_ "GenMsgSendType" BO_ 302 1; +BA_ "GenMsgILSupport" BO_ 302 1; +BA_ "GenMsgNrOfRepetition" BO_ 302 0; +BA_ "GenMsgCycleTime" BO_ 302 0; +BA_ "NetworkInitialization" BO_ 302 0; +BA_ "GenMsgDelayTime" BO_ 302 0; +BA_ "GenSigVtEn" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_01 "CAN_DET_CONFID_AZIMUTH_15_01"; +BA_ "GenSigVtName" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_01 "CAN_DET_CONFID_AZIMUTH_15_01"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_01 "CAN_DET_CONFID_AZIMUTH_15_01"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_01 "CAN_DET_SUPER_RES_TARGET_15_01"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_ND_TARGET_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_ND_TARGET_15_01 "CAN_DET_ND_TARGET_15_01"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_01 "CAN_DET_HOST_VEH_CLUTTER_15_01"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_VALID_LEVEL_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_VALID_LEVEL_15_01 "CAN_DET_VALID_LEVEL_15_01"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_AZIMUTH_15_01 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AZIMUTH_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AZIMUTH_15_01 "CAN_DET_AZIMUTH_15_01"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_15_01 "CAN_DET_RANGE_15_01"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_RANGE_RATE_15_01 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_RATE_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_RATE_15_01 "CAN_DET_RANGE_RATE_15_01"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AMPLITUDE_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AMPLITUDE_15_01 "CAN_DET_AMPLITUDE_15_01"; +BA_ "GenSigSendType" SG_ 302 CAN_SCAN_INDEX_2LSB_15_01 0; +BA_ "GenSigCmt" SG_ 302 CAN_SCAN_INDEX_2LSB_15_01 "CAN_SCAN_INDEX_2LSB_15_01"; +BA_ "GenSigVtEn" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_02 "CAN_DET_CONFID_AZIMUTH_15_02"; +BA_ "GenSigVtName" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_02 "CAN_DET_CONFID_AZIMUTH_15_02"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_02 "CAN_DET_CONFID_AZIMUTH_15_02"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_02 "CAN_DET_SUPER_RES_TARGET_15_02"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_ND_TARGET_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_ND_TARGET_15_02 "CAN_DET_ND_TARGET_15_02"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_02 "CAN_DET_HOST_VEH_CLUTTER_15_02"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_VALID_LEVEL_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_VALID_LEVEL_15_02 "CAN_DET_VALID_LEVEL_15_02"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_AZIMUTH_15_02 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AZIMUTH_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AZIMUTH_15_02 "CAN_DET_AZIMUTH_15_02"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_15_02 "CAN_DET_RANGE_15_02"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_RANGE_RATE_15_02 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_RATE_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_RATE_15_02 "CAN_DET_RANGE_RATE_15_02"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AMPLITUDE_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AMPLITUDE_15_02 "CAN_DET_AMPLITUDE_15_02"; +BA_ "GenSigSendType" SG_ 302 CAN_SCAN_INDEX_2LSB_15_02 0; +BA_ "GenSigCmt" SG_ 302 CAN_SCAN_INDEX_2LSB_15_02 "CAN_SCAN_INDEX_2LSB_15_02"; +BA_ "GenSigVtEn" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_03 "CAN_DET_CONFID_AZIMUTH_15_03"; +BA_ "GenSigVtName" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_03 "CAN_DET_CONFID_AZIMUTH_15_03"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_03 "CAN_DET_CONFID_AZIMUTH_15_03"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_03 "CAN_DET_SUPER_RES_TARGET_15_03"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_ND_TARGET_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_ND_TARGET_15_03 "CAN_DET_ND_TARGET_15_03"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_03 "CAN_DET_HOST_VEH_CLUTTER_15_03"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_VALID_LEVEL_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_VALID_LEVEL_15_03 "CAN_DET_VALID_LEVEL_15_03"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_AZIMUTH_15_03 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AZIMUTH_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AZIMUTH_15_03 "CAN_DET_AZIMUTH_15_03"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_15_03 "CAN_DET_RANGE_15_03"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_RANGE_RATE_15_03 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_RATE_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_RATE_15_03 "CAN_DET_RANGE_RATE_15_03"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AMPLITUDE_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AMPLITUDE_15_03 "CAN_DET_AMPLITUDE_15_03"; +BA_ "GenSigSendType" SG_ 302 CAN_SCAN_INDEX_2LSB_15_03 0; +BA_ "GenSigCmt" SG_ 302 CAN_SCAN_INDEX_2LSB_15_03 "CAN_SCAN_INDEX_2LSB_15_03"; +BA_ "GenSigVtEn" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_04 "CAN_DET_CONFID_AZIMUTH_15_04"; +BA_ "GenSigVtName" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_04 "CAN_DET_CONFID_AZIMUTH_15_04"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_04 "CAN_DET_CONFID_AZIMUTH_15_04"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_04 "CAN_DET_SUPER_RES_TARGET_15_04"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_ND_TARGET_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_ND_TARGET_15_04 "CAN_DET_ND_TARGET_15_04"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_04 "CAN_DET_HOST_VEH_CLUTTER_15_04"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_VALID_LEVEL_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_VALID_LEVEL_15_04 "CAN_DET_VALID_LEVEL_15_04"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_AZIMUTH_15_04 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AZIMUTH_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AZIMUTH_15_04 "CAN_DET_AZIMUTH_15_04"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_15_04 "CAN_DET_RANGE_15_04"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_RANGE_RATE_15_04 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_RATE_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_RATE_15_04 "CAN_DET_RANGE_RATE_15_04"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AMPLITUDE_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AMPLITUDE_15_04 "CAN_DET_AMPLITUDE_15_04"; +BA_ "GenSigSendType" SG_ 302 CAN_SCAN_INDEX_2LSB_15_04 0; +BA_ "GenSigCmt" SG_ 302 CAN_SCAN_INDEX_2LSB_15_04 "CAN_SCAN_INDEX_2LSB_15_04"; +BA_ "GenSigVtEn" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_05 "CAN_DET_CONFID_AZIMUTH_15_05"; +BA_ "GenSigVtName" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_05 "CAN_DET_CONFID_AZIMUTH_15_05"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_05 "CAN_DET_CONFID_AZIMUTH_15_05"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_05 "CAN_DET_SUPER_RES_TARGET_15_05"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_ND_TARGET_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_ND_TARGET_15_05 "CAN_DET_ND_TARGET_15_05"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_05 "CAN_DET_HOST_VEH_CLUTTER_15_05"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_VALID_LEVEL_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_VALID_LEVEL_15_05 "CAN_DET_VALID_LEVEL_15_05"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_AZIMUTH_15_05 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AZIMUTH_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AZIMUTH_15_05 "CAN_DET_AZIMUTH_15_05"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_15_05 "CAN_DET_RANGE_15_05"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_RANGE_RATE_15_05 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_RATE_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_RATE_15_05 "CAN_DET_RANGE_RATE_15_05"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AMPLITUDE_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AMPLITUDE_15_05 "CAN_DET_AMPLITUDE_15_05"; +BA_ "GenSigSendType" SG_ 302 CAN_SCAN_INDEX_2LSB_15_05 0; +BA_ "GenSigCmt" SG_ 302 CAN_SCAN_INDEX_2LSB_15_05 "CAN_SCAN_INDEX_2LSB_15_05"; +BA_ "GenSigVtEn" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_06 "CAN_DET_CONFID_AZIMUTH_15_06"; +BA_ "GenSigVtName" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_06 "CAN_DET_CONFID_AZIMUTH_15_06"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_CONFID_AZIMUTH_15_06 "CAN_DET_CONFID_AZIMUTH_15_06"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_SUPER_RES_TARGET_15_06 "CAN_DET_SUPER_RES_TARGET_15_06"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_ND_TARGET_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_ND_TARGET_15_06 "CAN_DET_ND_TARGET_15_06"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_HOST_VEH_CLUTTER_15_06 "CAN_DET_HOST_VEH_CLUTTER_15_06"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_VALID_LEVEL_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_VALID_LEVEL_15_06 "CAN_DET_VALID_LEVEL_15_06"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_AZIMUTH_15_06 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AZIMUTH_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AZIMUTH_15_06 "CAN_DET_AZIMUTH_15_06"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_15_06 "CAN_DET_RANGE_15_06"; +BA_ "GenSigStartValue" SG_ 302 CAN_DET_RANGE_RATE_15_06 0; +BA_ "GenSigSendType" SG_ 302 CAN_DET_RANGE_RATE_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_RANGE_RATE_15_06 "CAN_DET_RANGE_RATE_15_06"; +BA_ "GenSigSendType" SG_ 302 CAN_DET_AMPLITUDE_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_DET_AMPLITUDE_15_06 "CAN_DET_AMPLITUDE_15_06"; +BA_ "GenSigSendType" SG_ 302 CAN_SCAN_INDEX_2LSB_15_06 0; +BA_ "GenSigCmt" SG_ 302 CAN_SCAN_INDEX_2LSB_15_06 "CAN_SCAN_INDEX_2LSB_15_06"; +BA_ "GenMsgSendType" BO_ 301 1; +BA_ "GenMsgILSupport" BO_ 301 1; +BA_ "GenMsgNrOfRepetition" BO_ 301 0; +BA_ "GenMsgCycleTime" BO_ 301 0; +BA_ "NetworkInitialization" BO_ 301 0; +BA_ "GenMsgDelayTime" BO_ 301 0; +BA_ "GenSigVtEn" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_01 "CAN_DET_CONFID_AZIMUTH_14_01"; +BA_ "GenSigVtName" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_01 "CAN_DET_CONFID_AZIMUTH_14_01"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_01 "CAN_DET_CONFID_AZIMUTH_14_01"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_01 "CAN_DET_SUPER_RES_TARGET_14_01"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_ND_TARGET_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_ND_TARGET_14_01 "CAN_DET_ND_TARGET_14_01"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_01 "CAN_DET_HOST_VEH_CLUTTER_14_01"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_VALID_LEVEL_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_VALID_LEVEL_14_01 "CAN_DET_VALID_LEVEL_14_01"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_AZIMUTH_14_01 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AZIMUTH_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AZIMUTH_14_01 "CAN_DET_AZIMUTH_14_01"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_14_01 "CAN_DET_RANGE_14_01"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_RANGE_RATE_14_01 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_RATE_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_RATE_14_01 "CAN_DET_RANGE_RATE_14_01"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AMPLITUDE_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AMPLITUDE_14_01 "CAN_DET_AMPLITUDE_14_01"; +BA_ "GenSigSendType" SG_ 301 CAN_SCAN_INDEX_2LSB_14_01 0; +BA_ "GenSigCmt" SG_ 301 CAN_SCAN_INDEX_2LSB_14_01 "CAN_SCAN_INDEX_2LSB_14_01"; +BA_ "GenSigVtEn" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_02 "CAN_DET_CONFID_AZIMUTH_14_02"; +BA_ "GenSigVtName" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_02 "CAN_DET_CONFID_AZIMUTH_14_02"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_02 "CAN_DET_CONFID_AZIMUTH_14_02"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_02 "CAN_DET_SUPER_RES_TARGET_14_02"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_ND_TARGET_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_ND_TARGET_14_02 "CAN_DET_ND_TARGET_14_02"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_02 "CAN_DET_HOST_VEH_CLUTTER_14_02"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_VALID_LEVEL_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_VALID_LEVEL_14_02 "CAN_DET_VALID_LEVEL_14_02"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_AZIMUTH_14_02 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AZIMUTH_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AZIMUTH_14_02 "CAN_DET_AZIMUTH_14_02"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_14_02 "CAN_DET_RANGE_14_02"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_RANGE_RATE_14_02 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_RATE_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_RATE_14_02 "CAN_DET_RANGE_RATE_14_02"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AMPLITUDE_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AMPLITUDE_14_02 "CAN_DET_AMPLITUDE_14_02"; +BA_ "GenSigSendType" SG_ 301 CAN_SCAN_INDEX_2LSB_14_02 0; +BA_ "GenSigCmt" SG_ 301 CAN_SCAN_INDEX_2LSB_14_02 "CAN_SCAN_INDEX_2LSB_14_02"; +BA_ "GenSigVtEn" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_03 "CAN_DET_CONFID_AZIMUTH_14_03"; +BA_ "GenSigVtName" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_03 "CAN_DET_CONFID_AZIMUTH_14_03"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_03 "CAN_DET_CONFID_AZIMUTH_14_03"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_03 "CAN_DET_SUPER_RES_TARGET_14_03"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_ND_TARGET_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_ND_TARGET_14_03 "CAN_DET_ND_TARGET_14_03"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_03 "CAN_DET_HOST_VEH_CLUTTER_14_03"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_VALID_LEVEL_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_VALID_LEVEL_14_03 "CAN_DET_VALID_LEVEL_14_03"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_AZIMUTH_14_03 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AZIMUTH_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AZIMUTH_14_03 "CAN_DET_AZIMUTH_14_03"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_14_03 "CAN_DET_RANGE_14_03"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_RANGE_RATE_14_03 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_RATE_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_RATE_14_03 "CAN_DET_RANGE_RATE_14_03"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AMPLITUDE_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AMPLITUDE_14_03 "CAN_DET_AMPLITUDE_14_03"; +BA_ "GenSigSendType" SG_ 301 CAN_SCAN_INDEX_2LSB_14_03 0; +BA_ "GenSigCmt" SG_ 301 CAN_SCAN_INDEX_2LSB_14_03 "CAN_SCAN_INDEX_2LSB_14_03"; +BA_ "GenSigVtEn" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_04 "CAN_DET_CONFID_AZIMUTH_14_04"; +BA_ "GenSigVtName" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_04 "CAN_DET_CONFID_AZIMUTH_14_04"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_04 "CAN_DET_CONFID_AZIMUTH_14_04"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_04 "CAN_DET_SUPER_RES_TARGET_14_04"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_ND_TARGET_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_ND_TARGET_14_04 "CAN_DET_ND_TARGET_14_04"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_04 "CAN_DET_HOST_VEH_CLUTTER_14_04"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_VALID_LEVEL_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_VALID_LEVEL_14_04 "CAN_DET_VALID_LEVEL_14_04"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_AZIMUTH_14_04 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AZIMUTH_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AZIMUTH_14_04 "CAN_DET_AZIMUTH_14_04"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_14_04 "CAN_DET_RANGE_14_04"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_RANGE_RATE_14_04 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_RATE_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_RATE_14_04 "CAN_DET_RANGE_RATE_14_04"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AMPLITUDE_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AMPLITUDE_14_04 "CAN_DET_AMPLITUDE_14_04"; +BA_ "GenSigSendType" SG_ 301 CAN_SCAN_INDEX_2LSB_14_04 0; +BA_ "GenSigCmt" SG_ 301 CAN_SCAN_INDEX_2LSB_14_04 "CAN_SCAN_INDEX_2LSB_14_04"; +BA_ "GenSigVtEn" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_05 "CAN_DET_CONFID_AZIMUTH_14_05"; +BA_ "GenSigVtName" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_05 "CAN_DET_CONFID_AZIMUTH_14_05"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_05 "CAN_DET_CONFID_AZIMUTH_14_05"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_05 "CAN_DET_SUPER_RES_TARGET_14_05"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_ND_TARGET_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_ND_TARGET_14_05 "CAN_DET_ND_TARGET_14_05"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_05 "CAN_DET_HOST_VEH_CLUTTER_14_05"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_VALID_LEVEL_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_VALID_LEVEL_14_05 "CAN_DET_VALID_LEVEL_14_05"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_AZIMUTH_14_05 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AZIMUTH_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AZIMUTH_14_05 "CAN_DET_AZIMUTH_14_05"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_14_05 "CAN_DET_RANGE_14_05"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_RANGE_RATE_14_05 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_RATE_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_RATE_14_05 "CAN_DET_RANGE_RATE_14_05"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AMPLITUDE_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AMPLITUDE_14_05 "CAN_DET_AMPLITUDE_14_05"; +BA_ "GenSigSendType" SG_ 301 CAN_SCAN_INDEX_2LSB_14_05 0; +BA_ "GenSigCmt" SG_ 301 CAN_SCAN_INDEX_2LSB_14_05 "CAN_SCAN_INDEX_2LSB_14_05"; +BA_ "GenSigVtEn" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_06 "CAN_DET_CONFID_AZIMUTH_14_06"; +BA_ "GenSigVtName" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_06 "CAN_DET_CONFID_AZIMUTH_14_06"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_CONFID_AZIMUTH_14_06 "CAN_DET_CONFID_AZIMUTH_14_06"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_SUPER_RES_TARGET_14_06 "CAN_DET_SUPER_RES_TARGET_14_06"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_ND_TARGET_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_ND_TARGET_14_06 "CAN_DET_ND_TARGET_14_06"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_HOST_VEH_CLUTTER_14_06 "CAN_DET_HOST_VEH_CLUTTER_14_06"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_VALID_LEVEL_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_VALID_LEVEL_14_06 "CAN_DET_VALID_LEVEL_14_06"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_AZIMUTH_14_06 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AZIMUTH_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AZIMUTH_14_06 "CAN_DET_AZIMUTH_14_06"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_14_06 "CAN_DET_RANGE_14_06"; +BA_ "GenSigStartValue" SG_ 301 CAN_DET_RANGE_RATE_14_06 0; +BA_ "GenSigSendType" SG_ 301 CAN_DET_RANGE_RATE_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_RANGE_RATE_14_06 "CAN_DET_RANGE_RATE_14_06"; +BA_ "GenSigSendType" SG_ 301 CAN_DET_AMPLITUDE_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_DET_AMPLITUDE_14_06 "CAN_DET_AMPLITUDE_14_06"; +BA_ "GenSigSendType" SG_ 301 CAN_SCAN_INDEX_2LSB_14_06 0; +BA_ "GenSigCmt" SG_ 301 CAN_SCAN_INDEX_2LSB_14_06 "CAN_SCAN_INDEX_2LSB_14_06"; +BA_ "GenMsgSendType" BO_ 300 1; +BA_ "GenMsgILSupport" BO_ 300 1; +BA_ "GenMsgNrOfRepetition" BO_ 300 0; +BA_ "GenMsgCycleTime" BO_ 300 0; +BA_ "NetworkInitialization" BO_ 300 0; +BA_ "GenMsgDelayTime" BO_ 300 0; +BA_ "GenSigVtEn" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_01 "CAN_DET_CONFID_AZIMUTH_13_01"; +BA_ "GenSigVtName" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_01 "CAN_DET_CONFID_AZIMUTH_13_01"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_01 "CAN_DET_CONFID_AZIMUTH_13_01"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_01 "CAN_DET_SUPER_RES_TARGET_13_01"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_ND_TARGET_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_ND_TARGET_13_01 "CAN_DET_ND_TARGET_13_01"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_01 "CAN_DET_HOST_VEH_CLUTTER_13_01"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_VALID_LEVEL_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_VALID_LEVEL_13_01 "CAN_DET_VALID_LEVEL_13_01"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_AZIMUTH_13_01 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AZIMUTH_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AZIMUTH_13_01 "CAN_DET_AZIMUTH_13_01"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_13_01 "CAN_DET_RANGE_13_01"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_RANGE_RATE_13_01 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_RATE_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_RATE_13_01 "CAN_DET_RANGE_RATE_13_01"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AMPLITUDE_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AMPLITUDE_13_01 "CAN_DET_AMPLITUDE_13_01"; +BA_ "GenSigSendType" SG_ 300 CAN_SCAN_INDEX_2LSB_13_01 0; +BA_ "GenSigCmt" SG_ 300 CAN_SCAN_INDEX_2LSB_13_01 "CAN_SCAN_INDEX_2LSB_13_01"; +BA_ "GenSigVtEn" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_02 "CAN_DET_CONFID_AZIMUTH_13_02"; +BA_ "GenSigVtName" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_02 "CAN_DET_CONFID_AZIMUTH_13_02"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_02 "CAN_DET_CONFID_AZIMUTH_13_02"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_02 "CAN_DET_SUPER_RES_TARGET_13_02"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_ND_TARGET_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_ND_TARGET_13_02 "CAN_DET_ND_TARGET_13_02"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_02 "CAN_DET_HOST_VEH_CLUTTER_13_02"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_VALID_LEVEL_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_VALID_LEVEL_13_02 "CAN_DET_VALID_LEVEL_13_02"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_AZIMUTH_13_02 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AZIMUTH_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AZIMUTH_13_02 "CAN_DET_AZIMUTH_13_02"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_13_02 "CAN_DET_RANGE_13_02"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_RANGE_RATE_13_02 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_RATE_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_RATE_13_02 "CAN_DET_RANGE_RATE_13_02"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AMPLITUDE_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AMPLITUDE_13_02 "CAN_DET_AMPLITUDE_13_02"; +BA_ "GenSigSendType" SG_ 300 CAN_SCAN_INDEX_2LSB_13_02 0; +BA_ "GenSigCmt" SG_ 300 CAN_SCAN_INDEX_2LSB_13_02 "CAN_SCAN_INDEX_2LSB_13_02"; +BA_ "GenSigVtEn" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_03 "CAN_DET_CONFID_AZIMUTH_13_03"; +BA_ "GenSigVtName" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_03 "CAN_DET_CONFID_AZIMUTH_13_03"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_03 "CAN_DET_CONFID_AZIMUTH_13_03"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_03 "CAN_DET_SUPER_RES_TARGET_13_03"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_ND_TARGET_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_ND_TARGET_13_03 "CAN_DET_ND_TARGET_13_03"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_03 "CAN_DET_HOST_VEH_CLUTTER_13_03"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_VALID_LEVEL_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_VALID_LEVEL_13_03 "CAN_DET_VALID_LEVEL_13_03"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_AZIMUTH_13_03 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AZIMUTH_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AZIMUTH_13_03 "CAN_DET_AZIMUTH_13_03"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_13_03 "CAN_DET_RANGE_13_03"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_RANGE_RATE_13_03 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_RATE_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_RATE_13_03 "CAN_DET_RANGE_RATE_13_03"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AMPLITUDE_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AMPLITUDE_13_03 "CAN_DET_AMPLITUDE_13_03"; +BA_ "GenSigSendType" SG_ 300 CAN_SCAN_INDEX_2LSB_13_03 0; +BA_ "GenSigCmt" SG_ 300 CAN_SCAN_INDEX_2LSB_13_03 "CAN_SCAN_INDEX_2LSB_13_03"; +BA_ "GenSigVtEn" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_04 "CAN_DET_CONFID_AZIMUTH_13_04"; +BA_ "GenSigVtName" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_04 "CAN_DET_CONFID_AZIMUTH_13_04"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_04 "CAN_DET_CONFID_AZIMUTH_13_04"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_04 "CAN_DET_SUPER_RES_TARGET_13_04"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_ND_TARGET_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_ND_TARGET_13_04 "CAN_DET_ND_TARGET_13_04"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_04 "CAN_DET_HOST_VEH_CLUTTER_13_04"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_VALID_LEVEL_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_VALID_LEVEL_13_04 "CAN_DET_VALID_LEVEL_13_04"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_AZIMUTH_13_04 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AZIMUTH_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AZIMUTH_13_04 "CAN_DET_AZIMUTH_13_04"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_13_04 "CAN_DET_RANGE_13_04"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_RANGE_RATE_13_04 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_RATE_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_RATE_13_04 "CAN_DET_RANGE_RATE_13_04"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AMPLITUDE_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AMPLITUDE_13_04 "CAN_DET_AMPLITUDE_13_04"; +BA_ "GenSigSendType" SG_ 300 CAN_SCAN_INDEX_2LSB_13_04 0; +BA_ "GenSigCmt" SG_ 300 CAN_SCAN_INDEX_2LSB_13_04 "CAN_SCAN_INDEX_2LSB_13_04"; +BA_ "GenSigVtEn" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_05 "CAN_DET_CONFID_AZIMUTH_13_05"; +BA_ "GenSigVtName" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_05 "CAN_DET_CONFID_AZIMUTH_13_05"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_05 "CAN_DET_CONFID_AZIMUTH_13_05"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_05 "CAN_DET_SUPER_RES_TARGET_13_05"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_ND_TARGET_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_ND_TARGET_13_05 "CAN_DET_ND_TARGET_13_05"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_05 "CAN_DET_HOST_VEH_CLUTTER_13_05"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_VALID_LEVEL_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_VALID_LEVEL_13_05 "CAN_DET_VALID_LEVEL_13_05"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_AZIMUTH_13_05 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AZIMUTH_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AZIMUTH_13_05 "CAN_DET_AZIMUTH_13_05"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_13_05 "CAN_DET_RANGE_13_05"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_RANGE_RATE_13_05 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_RATE_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_RATE_13_05 "CAN_DET_RANGE_RATE_13_05"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AMPLITUDE_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AMPLITUDE_13_05 "CAN_DET_AMPLITUDE_13_05"; +BA_ "GenSigSendType" SG_ 300 CAN_SCAN_INDEX_2LSB_13_05 0; +BA_ "GenSigCmt" SG_ 300 CAN_SCAN_INDEX_2LSB_13_05 "CAN_SCAN_INDEX_2LSB_13_05"; +BA_ "GenSigVtEn" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_06 "CAN_DET_CONFID_AZIMUTH_13_06"; +BA_ "GenSigVtName" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_06 "CAN_DET_CONFID_AZIMUTH_13_06"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_CONFID_AZIMUTH_13_06 "CAN_DET_CONFID_AZIMUTH_13_06"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_SUPER_RES_TARGET_13_06 "CAN_DET_SUPER_RES_TARGET_13_06"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_ND_TARGET_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_ND_TARGET_13_06 "CAN_DET_ND_TARGET_13_06"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_HOST_VEH_CLUTTER_13_06 "CAN_DET_HOST_VEH_CLUTTER_13_06"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_VALID_LEVEL_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_VALID_LEVEL_13_06 "CAN_DET_VALID_LEVEL_13_06"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_AZIMUTH_13_06 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AZIMUTH_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AZIMUTH_13_06 "CAN_DET_AZIMUTH_13_06"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_13_06 "CAN_DET_RANGE_13_06"; +BA_ "GenSigStartValue" SG_ 300 CAN_DET_RANGE_RATE_13_06 0; +BA_ "GenSigSendType" SG_ 300 CAN_DET_RANGE_RATE_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_RANGE_RATE_13_06 "CAN_DET_RANGE_RATE_13_06"; +BA_ "GenSigSendType" SG_ 300 CAN_DET_AMPLITUDE_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_DET_AMPLITUDE_13_06 "CAN_DET_AMPLITUDE_13_06"; +BA_ "GenSigSendType" SG_ 300 CAN_SCAN_INDEX_2LSB_13_06 0; +BA_ "GenSigCmt" SG_ 300 CAN_SCAN_INDEX_2LSB_13_06 "CAN_SCAN_INDEX_2LSB_13_06"; +BA_ "GenMsgSendType" BO_ 299 1; +BA_ "GenMsgILSupport" BO_ 299 1; +BA_ "GenMsgNrOfRepetition" BO_ 299 0; +BA_ "GenMsgCycleTime" BO_ 299 0; +BA_ "NetworkInitialization" BO_ 299 0; +BA_ "GenMsgDelayTime" BO_ 299 0; +BA_ "GenSigVtEn" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_01 "CAN_DET_CONFID_AZIMUTH_12_01"; +BA_ "GenSigVtName" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_01 "CAN_DET_CONFID_AZIMUTH_12_01"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_01 "CAN_DET_CONFID_AZIMUTH_12_01"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_01 "CAN_DET_SUPER_RES_TARGET_12_01"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_ND_TARGET_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_ND_TARGET_12_01 "CAN_DET_ND_TARGET_12_01"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_01 "CAN_DET_HOST_VEH_CLUTTER_12_01"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_VALID_LEVEL_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_VALID_LEVEL_12_01 "CAN_DET_VALID_LEVEL_12_01"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_AZIMUTH_12_01 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AZIMUTH_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AZIMUTH_12_01 "CAN_DET_AZIMUTH_12_01"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_12_01 "CAN_DET_RANGE_12_01"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_RANGE_RATE_12_01 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_RATE_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_RATE_12_01 "CAN_DET_RANGE_RATE_12_01"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AMPLITUDE_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AMPLITUDE_12_01 "CAN_DET_AMPLITUDE_12_01"; +BA_ "GenSigSendType" SG_ 299 CAN_SCAN_INDEX_2LSB_12_01 0; +BA_ "GenSigCmt" SG_ 299 CAN_SCAN_INDEX_2LSB_12_01 "CAN_SCAN_INDEX_2LSB_12_01"; +BA_ "GenSigVtEn" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_02 "CAN_DET_CONFID_AZIMUTH_12_02"; +BA_ "GenSigVtName" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_02 "CAN_DET_CONFID_AZIMUTH_12_02"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_02 "CAN_DET_CONFID_AZIMUTH_12_02"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_02 "CAN_DET_SUPER_RES_TARGET_12_02"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_ND_TARGET_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_ND_TARGET_12_02 "CAN_DET_ND_TARGET_12_02"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_02 "CAN_DET_HOST_VEH_CLUTTER_12_02"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_VALID_LEVEL_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_VALID_LEVEL_12_02 "CAN_DET_VALID_LEVEL_12_02"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_AZIMUTH_12_02 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AZIMUTH_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AZIMUTH_12_02 "CAN_DET_AZIMUTH_12_02"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_12_02 "CAN_DET_RANGE_12_02"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_RANGE_RATE_12_02 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_RATE_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_RATE_12_02 "CAN_DET_RANGE_RATE_12_02"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AMPLITUDE_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AMPLITUDE_12_02 "CAN_DET_AMPLITUDE_12_02"; +BA_ "GenSigSendType" SG_ 299 CAN_SCAN_INDEX_2LSB_12_02 0; +BA_ "GenSigCmt" SG_ 299 CAN_SCAN_INDEX_2LSB_12_02 "CAN_SCAN_INDEX_2LSB_12_02"; +BA_ "GenSigVtEn" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_03 "CAN_DET_CONFID_AZIMUTH_12_03"; +BA_ "GenSigVtName" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_03 "CAN_DET_CONFID_AZIMUTH_12_03"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_03 "CAN_DET_CONFID_AZIMUTH_12_03"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_03 "CAN_DET_SUPER_RES_TARGET_12_03"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_ND_TARGET_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_ND_TARGET_12_03 "CAN_DET_ND_TARGET_12_03"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_03 "CAN_DET_HOST_VEH_CLUTTER_12_03"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_VALID_LEVEL_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_VALID_LEVEL_12_03 "CAN_DET_VALID_LEVEL_12_03"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_AZIMUTH_12_03 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AZIMUTH_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AZIMUTH_12_03 "CAN_DET_AZIMUTH_12_03"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_12_03 "CAN_DET_RANGE_12_03"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_RANGE_RATE_12_03 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_RATE_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_RATE_12_03 "CAN_DET_RANGE_RATE_12_03"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AMPLITUDE_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AMPLITUDE_12_03 "CAN_DET_AMPLITUDE_12_03"; +BA_ "GenSigSendType" SG_ 299 CAN_SCAN_INDEX_2LSB_12_03 0; +BA_ "GenSigCmt" SG_ 299 CAN_SCAN_INDEX_2LSB_12_03 "CAN_SCAN_INDEX_2LSB_12_03"; +BA_ "GenSigVtEn" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_04 "CAN_DET_CONFID_AZIMUTH_12_04"; +BA_ "GenSigVtName" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_04 "CAN_DET_CONFID_AZIMUTH_12_04"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_04 "CAN_DET_CONFID_AZIMUTH_12_04"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_04 "CAN_DET_SUPER_RES_TARGET_12_04"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_ND_TARGET_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_ND_TARGET_12_04 "CAN_DET_ND_TARGET_12_04"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_04 "CAN_DET_HOST_VEH_CLUTTER_12_04"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_VALID_LEVEL_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_VALID_LEVEL_12_04 "CAN_DET_VALID_LEVEL_12_04"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_AZIMUTH_12_04 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AZIMUTH_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AZIMUTH_12_04 "CAN_DET_AZIMUTH_12_04"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_12_04 "CAN_DET_RANGE_12_04"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_RANGE_RATE_12_04 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_RATE_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_RATE_12_04 "CAN_DET_RANGE_RATE_12_04"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AMPLITUDE_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AMPLITUDE_12_04 "CAN_DET_AMPLITUDE_12_04"; +BA_ "GenSigSendType" SG_ 299 CAN_SCAN_INDEX_2LSB_12_04 0; +BA_ "GenSigCmt" SG_ 299 CAN_SCAN_INDEX_2LSB_12_04 "CAN_SCAN_INDEX_2LSB_12_04"; +BA_ "GenSigVtEn" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_05 "CAN_DET_CONFID_AZIMUTH_12_05"; +BA_ "GenSigVtName" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_05 "CAN_DET_CONFID_AZIMUTH_12_05"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_05 "CAN_DET_CONFID_AZIMUTH_12_05"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_05 "CAN_DET_SUPER_RES_TARGET_12_05"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_ND_TARGET_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_ND_TARGET_12_05 "CAN_DET_ND_TARGET_12_05"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_05 "CAN_DET_HOST_VEH_CLUTTER_12_05"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_VALID_LEVEL_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_VALID_LEVEL_12_05 "CAN_DET_VALID_LEVEL_12_05"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_AZIMUTH_12_05 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AZIMUTH_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AZIMUTH_12_05 "CAN_DET_AZIMUTH_12_05"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_12_05 "CAN_DET_RANGE_12_05"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_RANGE_RATE_12_05 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_RATE_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_RATE_12_05 "CAN_DET_RANGE_RATE_12_05"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AMPLITUDE_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AMPLITUDE_12_05 "CAN_DET_AMPLITUDE_12_05"; +BA_ "GenSigSendType" SG_ 299 CAN_SCAN_INDEX_2LSB_12_05 0; +BA_ "GenSigCmt" SG_ 299 CAN_SCAN_INDEX_2LSB_12_05 "CAN_SCAN_INDEX_2LSB_12_05"; +BA_ "GenSigVtEn" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_06 "CAN_DET_CONFID_AZIMUTH_12_06"; +BA_ "GenSigVtName" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_06 "CAN_DET_CONFID_AZIMUTH_12_06"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_CONFID_AZIMUTH_12_06 "CAN_DET_CONFID_AZIMUTH_12_06"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_SUPER_RES_TARGET_12_06 "CAN_DET_SUPER_RES_TARGET_12_06"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_ND_TARGET_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_ND_TARGET_12_06 "CAN_DET_ND_TARGET_12_06"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_HOST_VEH_CLUTTER_12_06 "CAN_DET_HOST_VEH_CLUTTER_12_06"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_VALID_LEVEL_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_VALID_LEVEL_12_06 "CAN_DET_VALID_LEVEL_12_06"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_AZIMUTH_12_06 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AZIMUTH_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AZIMUTH_12_06 "CAN_DET_AZIMUTH_12_06"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_12_06 "CAN_DET_RANGE_12_06"; +BA_ "GenSigStartValue" SG_ 299 CAN_DET_RANGE_RATE_12_06 0; +BA_ "GenSigSendType" SG_ 299 CAN_DET_RANGE_RATE_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_RANGE_RATE_12_06 "CAN_DET_RANGE_RATE_12_06"; +BA_ "GenSigSendType" SG_ 299 CAN_DET_AMPLITUDE_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_DET_AMPLITUDE_12_06 "CAN_DET_AMPLITUDE_12_06"; +BA_ "GenSigSendType" SG_ 299 CAN_SCAN_INDEX_2LSB_12_06 0; +BA_ "GenSigCmt" SG_ 299 CAN_SCAN_INDEX_2LSB_12_06 "CAN_SCAN_INDEX_2LSB_12_06"; +BA_ "GenMsgSendType" BO_ 298 1; +BA_ "GenMsgILSupport" BO_ 298 1; +BA_ "GenMsgNrOfRepetition" BO_ 298 0; +BA_ "GenMsgCycleTime" BO_ 298 0; +BA_ "NetworkInitialization" BO_ 298 0; +BA_ "GenMsgDelayTime" BO_ 298 0; +BA_ "GenSigVtEn" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_01 "CAN_DET_CONFID_AZIMUTH_11_01"; +BA_ "GenSigVtName" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_01 "CAN_DET_CONFID_AZIMUTH_11_01"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_01 "CAN_DET_CONFID_AZIMUTH_11_01"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_01 "CAN_DET_SUPER_RES_TARGET_11_01"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_ND_TARGET_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_ND_TARGET_11_01 "CAN_DET_ND_TARGET_11_01"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_01 "CAN_DET_HOST_VEH_CLUTTER_11_01"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_VALID_LEVEL_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_VALID_LEVEL_11_01 "CAN_DET_VALID_LEVEL_11_01"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_AZIMUTH_11_01 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AZIMUTH_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AZIMUTH_11_01 "CAN_DET_AZIMUTH_11_01"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_11_01 "CAN_DET_RANGE_11_01"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_RANGE_RATE_11_01 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_RATE_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_RATE_11_01 "CAN_DET_RANGE_RATE_11_01"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AMPLITUDE_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AMPLITUDE_11_01 "CAN_DET_AMPLITUDE_11_01"; +BA_ "GenSigSendType" SG_ 298 CAN_SCAN_INDEX_2LSB_11_01 0; +BA_ "GenSigCmt" SG_ 298 CAN_SCAN_INDEX_2LSB_11_01 "CAN_SCAN_INDEX_2LSB_11_01"; +BA_ "GenSigVtEn" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_02 "CAN_DET_CONFID_AZIMUTH_11_02"; +BA_ "GenSigVtName" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_02 "CAN_DET_CONFID_AZIMUTH_11_02"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_02 "CAN_DET_CONFID_AZIMUTH_11_02"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_02 "CAN_DET_SUPER_RES_TARGET_11_02"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_ND_TARGET_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_ND_TARGET_11_02 "CAN_DET_ND_TARGET_11_02"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_02 "CAN_DET_HOST_VEH_CLUTTER_11_02"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_VALID_LEVEL_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_VALID_LEVEL_11_02 "CAN_DET_VALID_LEVEL_11_02"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_AZIMUTH_11_02 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AZIMUTH_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AZIMUTH_11_02 "CAN_DET_AZIMUTH_11_02"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_11_02 "CAN_DET_RANGE_11_02"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_RANGE_RATE_11_02 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_RATE_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_RATE_11_02 "CAN_DET_RANGE_RATE_11_02"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AMPLITUDE_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AMPLITUDE_11_02 "CAN_DET_AMPLITUDE_11_02"; +BA_ "GenSigSendType" SG_ 298 CAN_SCAN_INDEX_2LSB_11_02 0; +BA_ "GenSigCmt" SG_ 298 CAN_SCAN_INDEX_2LSB_11_02 "CAN_SCAN_INDEX_2LSB_11_02"; +BA_ "GenSigVtEn" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_03 "CAN_DET_CONFID_AZIMUTH_11_03"; +BA_ "GenSigVtName" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_03 "CAN_DET_CONFID_AZIMUTH_11_03"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_03 "CAN_DET_CONFID_AZIMUTH_11_03"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_03 "CAN_DET_SUPER_RES_TARGET_11_03"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_ND_TARGET_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_ND_TARGET_11_03 "CAN_DET_ND_TARGET_11_03"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_03 "CAN_DET_HOST_VEH_CLUTTER_11_03"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_VALID_LEVEL_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_VALID_LEVEL_11_03 "CAN_DET_VALID_LEVEL_11_03"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_AZIMUTH_11_03 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AZIMUTH_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AZIMUTH_11_03 "CAN_DET_AZIMUTH_11_03"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_11_03 "CAN_DET_RANGE_11_03"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_RANGE_RATE_11_03 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_RATE_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_RATE_11_03 "CAN_DET_RANGE_RATE_11_03"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AMPLITUDE_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AMPLITUDE_11_03 "CAN_DET_AMPLITUDE_11_03"; +BA_ "GenSigSendType" SG_ 298 CAN_SCAN_INDEX_2LSB_11_03 0; +BA_ "GenSigCmt" SG_ 298 CAN_SCAN_INDEX_2LSB_11_03 "CAN_SCAN_INDEX_2LSB_11_03"; +BA_ "GenSigVtEn" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_04 "CAN_DET_CONFID_AZIMUTH_11_04"; +BA_ "GenSigVtName" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_04 "CAN_DET_CONFID_AZIMUTH_11_04"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_04 "CAN_DET_CONFID_AZIMUTH_11_04"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_04 "CAN_DET_SUPER_RES_TARGET_11_04"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_ND_TARGET_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_ND_TARGET_11_04 "CAN_DET_ND_TARGET_11_04"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_04 "CAN_DET_HOST_VEH_CLUTTER_11_04"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_VALID_LEVEL_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_VALID_LEVEL_11_04 "CAN_DET_VALID_LEVEL_11_04"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_AZIMUTH_11_04 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AZIMUTH_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AZIMUTH_11_04 "CAN_DET_AZIMUTH_11_04"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_11_04 "CAN_DET_RANGE_11_04"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_RANGE_RATE_11_04 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_RATE_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_RATE_11_04 "CAN_DET_RANGE_RATE_11_04"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AMPLITUDE_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AMPLITUDE_11_04 "CAN_DET_AMPLITUDE_11_04"; +BA_ "GenSigSendType" SG_ 298 CAN_SCAN_INDEX_2LSB_11_04 0; +BA_ "GenSigCmt" SG_ 298 CAN_SCAN_INDEX_2LSB_11_04 "CAN_SCAN_INDEX_2LSB_11_04"; +BA_ "GenSigVtEn" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_05 "CAN_DET_CONFID_AZIMUTH_11_05"; +BA_ "GenSigVtName" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_05 "CAN_DET_CONFID_AZIMUTH_11_05"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_05 "CAN_DET_CONFID_AZIMUTH_11_05"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_05 "CAN_DET_SUPER_RES_TARGET_11_05"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_ND_TARGET_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_ND_TARGET_11_05 "CAN_DET_ND_TARGET_11_05"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_05 "CAN_DET_HOST_VEH_CLUTTER_11_05"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_VALID_LEVEL_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_VALID_LEVEL_11_05 "CAN_DET_VALID_LEVEL_11_05"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_AZIMUTH_11_05 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AZIMUTH_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AZIMUTH_11_05 "CAN_DET_AZIMUTH_11_05"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_11_05 "CAN_DET_RANGE_11_05"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_RANGE_RATE_11_05 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_RATE_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_RATE_11_05 "CAN_DET_RANGE_RATE_11_05"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AMPLITUDE_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AMPLITUDE_11_05 "CAN_DET_AMPLITUDE_11_05"; +BA_ "GenSigSendType" SG_ 298 CAN_SCAN_INDEX_2LSB_11_05 0; +BA_ "GenSigCmt" SG_ 298 CAN_SCAN_INDEX_2LSB_11_05 "CAN_SCAN_INDEX_2LSB_11_05"; +BA_ "GenSigVtEn" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_06 "CAN_DET_CONFID_AZIMUTH_11_06"; +BA_ "GenSigVtName" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_06 "CAN_DET_CONFID_AZIMUTH_11_06"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_CONFID_AZIMUTH_11_06 "CAN_DET_CONFID_AZIMUTH_11_06"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_SUPER_RES_TARGET_11_06 "CAN_DET_SUPER_RES_TARGET_11_06"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_ND_TARGET_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_ND_TARGET_11_06 "CAN_DET_ND_TARGET_11_06"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_HOST_VEH_CLUTTER_11_06 "CAN_DET_HOST_VEH_CLUTTER_11_06"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_VALID_LEVEL_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_VALID_LEVEL_11_06 "CAN_DET_VALID_LEVEL_11_06"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_AZIMUTH_11_06 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AZIMUTH_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AZIMUTH_11_06 "CAN_DET_AZIMUTH_11_06"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_11_06 "CAN_DET_RANGE_11_06"; +BA_ "GenSigStartValue" SG_ 298 CAN_DET_RANGE_RATE_11_06 0; +BA_ "GenSigSendType" SG_ 298 CAN_DET_RANGE_RATE_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_RANGE_RATE_11_06 "CAN_DET_RANGE_RATE_11_06"; +BA_ "GenSigSendType" SG_ 298 CAN_DET_AMPLITUDE_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_DET_AMPLITUDE_11_06 "CAN_DET_AMPLITUDE_11_06"; +BA_ "GenSigSendType" SG_ 298 CAN_SCAN_INDEX_2LSB_11_06 0; +BA_ "GenSigCmt" SG_ 298 CAN_SCAN_INDEX_2LSB_11_06 "CAN_SCAN_INDEX_2LSB_11_06"; +BA_ "GenMsgSendType" BO_ 297 1; +BA_ "GenMsgILSupport" BO_ 297 1; +BA_ "GenMsgNrOfRepetition" BO_ 297 0; +BA_ "GenMsgCycleTime" BO_ 297 0; +BA_ "NetworkInitialization" BO_ 297 0; +BA_ "GenMsgDelayTime" BO_ 297 0; +BA_ "GenSigVtEn" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_01 "CAN_DET_CONFID_AZIMUTH_10_01"; +BA_ "GenSigVtName" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_01 "CAN_DET_CONFID_AZIMUTH_10_01"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_01 "CAN_DET_CONFID_AZIMUTH_10_01"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_01 "CAN_DET_SUPER_RES_TARGET_10_01"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_ND_TARGET_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_ND_TARGET_10_01 "CAN_DET_ND_TARGET_10_01"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_01 "CAN_DET_HOST_VEH_CLUTTER_10_01"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_VALID_LEVEL_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_VALID_LEVEL_10_01 "CAN_DET_VALID_LEVEL_10_01"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_AZIMUTH_10_01 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AZIMUTH_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AZIMUTH_10_01 "CAN_DET_AZIMUTH_10_01"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_10_01 "CAN_DET_RANGE_10_01"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_RANGE_RATE_10_01 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_RATE_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_RATE_10_01 "CAN_DET_RANGE_RATE_10_01"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AMPLITUDE_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AMPLITUDE_10_01 "CAN_DET_AMPLITUDE_10_01"; +BA_ "GenSigSendType" SG_ 297 CAN_SCAN_INDEX_2LSB_10_01 0; +BA_ "GenSigCmt" SG_ 297 CAN_SCAN_INDEX_2LSB_10_01 "CAN_SCAN_INDEX_2LSB_10_01"; +BA_ "GenSigVtEn" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_02 "CAN_DET_CONFID_AZIMUTH_10_02"; +BA_ "GenSigVtName" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_02 "CAN_DET_CONFID_AZIMUTH_10_02"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_02 "CAN_DET_CONFID_AZIMUTH_10_02"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_02 "CAN_DET_SUPER_RES_TARGET_10_02"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_ND_TARGET_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_ND_TARGET_10_02 "CAN_DET_ND_TARGET_10_02"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_02 "CAN_DET_HOST_VEH_CLUTTER_10_02"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_VALID_LEVEL_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_VALID_LEVEL_10_02 "CAN_DET_VALID_LEVEL_10_02"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_AZIMUTH_10_02 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AZIMUTH_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AZIMUTH_10_02 "CAN_DET_AZIMUTH_10_02"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_10_02 "CAN_DET_RANGE_10_02"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_RANGE_RATE_10_02 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_RATE_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_RATE_10_02 "CAN_DET_RANGE_RATE_10_02"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AMPLITUDE_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AMPLITUDE_10_02 "CAN_DET_AMPLITUDE_10_02"; +BA_ "GenSigSendType" SG_ 297 CAN_SCAN_INDEX_2LSB_10_02 0; +BA_ "GenSigCmt" SG_ 297 CAN_SCAN_INDEX_2LSB_10_02 "CAN_SCAN_INDEX_2LSB_10_02"; +BA_ "GenSigVtEn" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_03 "CAN_DET_CONFID_AZIMUTH_10_03"; +BA_ "GenSigVtName" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_03 "CAN_DET_CONFID_AZIMUTH_10_03"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_03 "CAN_DET_CONFID_AZIMUTH_10_03"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_03 "CAN_DET_SUPER_RES_TARGET_10_03"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_ND_TARGET_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_ND_TARGET_10_03 "CAN_DET_ND_TARGET_10_03"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_03 "CAN_DET_HOST_VEH_CLUTTER_10_03"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_VALID_LEVEL_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_VALID_LEVEL_10_03 "CAN_DET_VALID_LEVEL_10_03"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_AZIMUTH_10_03 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AZIMUTH_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AZIMUTH_10_03 "CAN_DET_AZIMUTH_10_03"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_10_03 "CAN_DET_RANGE_10_03"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_RANGE_RATE_10_03 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_RATE_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_RATE_10_03 "CAN_DET_RANGE_RATE_10_03"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AMPLITUDE_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AMPLITUDE_10_03 "CAN_DET_AMPLITUDE_10_03"; +BA_ "GenSigSendType" SG_ 297 CAN_SCAN_INDEX_2LSB_10_03 0; +BA_ "GenSigCmt" SG_ 297 CAN_SCAN_INDEX_2LSB_10_03 "CAN_SCAN_INDEX_2LSB_10_03"; +BA_ "GenSigVtEn" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_04 "CAN_DET_CONFID_AZIMUTH_10_04"; +BA_ "GenSigVtName" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_04 "CAN_DET_CONFID_AZIMUTH_10_04"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_04 "CAN_DET_CONFID_AZIMUTH_10_04"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_04 "CAN_DET_SUPER_RES_TARGET_10_04"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_ND_TARGET_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_ND_TARGET_10_04 "CAN_DET_ND_TARGET_10_04"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_04 "CAN_DET_HOST_VEH_CLUTTER_10_04"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_VALID_LEVEL_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_VALID_LEVEL_10_04 "CAN_DET_VALID_LEVEL_10_04"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_AZIMUTH_10_04 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AZIMUTH_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AZIMUTH_10_04 "CAN_DET_AZIMUTH_10_04"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_10_04 "CAN_DET_RANGE_10_04"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_RANGE_RATE_10_04 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_RATE_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_RATE_10_04 "CAN_DET_RANGE_RATE_10_04"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AMPLITUDE_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AMPLITUDE_10_04 "CAN_DET_AMPLITUDE_10_04"; +BA_ "GenSigSendType" SG_ 297 CAN_SCAN_INDEX_2LSB_10_04 0; +BA_ "GenSigCmt" SG_ 297 CAN_SCAN_INDEX_2LSB_10_04 "CAN_SCAN_INDEX_2LSB_10_04"; +BA_ "GenSigVtEn" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_05 "CAN_DET_CONFID_AZIMUTH_10_05"; +BA_ "GenSigVtName" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_05 "CAN_DET_CONFID_AZIMUTH_10_05"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_05 "CAN_DET_CONFID_AZIMUTH_10_05"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_05 "CAN_DET_SUPER_RES_TARGET_10_05"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_ND_TARGET_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_ND_TARGET_10_05 "CAN_DET_ND_TARGET_10_05"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_05 "CAN_DET_HOST_VEH_CLUTTER_10_05"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_VALID_LEVEL_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_VALID_LEVEL_10_05 "CAN_DET_VALID_LEVEL_10_05"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_AZIMUTH_10_05 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AZIMUTH_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AZIMUTH_10_05 "CAN_DET_AZIMUTH_10_05"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_10_05 "CAN_DET_RANGE_10_05"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_RANGE_RATE_10_05 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_RATE_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_RATE_10_05 "CAN_DET_RANGE_RATE_10_05"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AMPLITUDE_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AMPLITUDE_10_05 "CAN_DET_AMPLITUDE_10_05"; +BA_ "GenSigSendType" SG_ 297 CAN_SCAN_INDEX_2LSB_10_05 0; +BA_ "GenSigCmt" SG_ 297 CAN_SCAN_INDEX_2LSB_10_05 "CAN_SCAN_INDEX_2LSB_10_05"; +BA_ "GenSigVtEn" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_06 "CAN_DET_CONFID_AZIMUTH_10_06"; +BA_ "GenSigVtName" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_06 "CAN_DET_CONFID_AZIMUTH_10_06"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_CONFID_AZIMUTH_10_06 "CAN_DET_CONFID_AZIMUTH_10_06"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_SUPER_RES_TARGET_10_06 "CAN_DET_SUPER_RES_TARGET_10_06"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_ND_TARGET_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_ND_TARGET_10_06 "CAN_DET_ND_TARGET_10_06"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_HOST_VEH_CLUTTER_10_06 "CAN_DET_HOST_VEH_CLUTTER_10_06"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_VALID_LEVEL_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_VALID_LEVEL_10_06 "CAN_DET_VALID_LEVEL_10_06"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_AZIMUTH_10_06 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AZIMUTH_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AZIMUTH_10_06 "CAN_DET_AZIMUTH_10_06"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_10_06 "CAN_DET_RANGE_10_06"; +BA_ "GenSigStartValue" SG_ 297 CAN_DET_RANGE_RATE_10_06 0; +BA_ "GenSigSendType" SG_ 297 CAN_DET_RANGE_RATE_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_RANGE_RATE_10_06 "CAN_DET_RANGE_RATE_10_06"; +BA_ "GenSigSendType" SG_ 297 CAN_DET_AMPLITUDE_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_DET_AMPLITUDE_10_06 "CAN_DET_AMPLITUDE_10_06"; +BA_ "GenSigSendType" SG_ 297 CAN_SCAN_INDEX_2LSB_10_06 0; +BA_ "GenSigCmt" SG_ 297 CAN_SCAN_INDEX_2LSB_10_06 "CAN_SCAN_INDEX_2LSB_10_06"; +BA_ "GenMsgSendType" BO_ 296 1; +BA_ "GenMsgILSupport" BO_ 296 1; +BA_ "GenMsgNrOfRepetition" BO_ 296 0; +BA_ "GenMsgCycleTime" BO_ 296 0; +BA_ "NetworkInitialization" BO_ 296 0; +BA_ "GenMsgDelayTime" BO_ 296 0; +BA_ "GenSigVtEn" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_01 "CAN_DET_CONFID_AZIMUTH_09_01"; +BA_ "GenSigVtName" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_01 "CAN_DET_CONFID_AZIMUTH_09_01"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_01 "CAN_DET_CONFID_AZIMUTH_09_01"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_01 "CAN_DET_SUPER_RES_TARGET_09_01"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_ND_TARGET_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_ND_TARGET_09_01 "CAN_DET_ND_TARGET_09_01"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_01 "CAN_DET_HOST_VEH_CLUTTER_09_01"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_VALID_LEVEL_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_VALID_LEVEL_09_01 "CAN_DET_VALID_LEVEL_09_01"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_AZIMUTH_09_01 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AZIMUTH_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AZIMUTH_09_01 "CAN_DET_AZIMUTH_09_01"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_09_01 "CAN_DET_RANGE_09_01"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_RANGE_RATE_09_01 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_RATE_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_RATE_09_01 "CAN_DET_RANGE_RATE_09_01"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AMPLITUDE_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AMPLITUDE_09_01 "CAN_DET_AMPLITUDE_09_01"; +BA_ "GenSigSendType" SG_ 296 CAN_SCAN_INDEX_2LSB_09_01 0; +BA_ "GenSigCmt" SG_ 296 CAN_SCAN_INDEX_2LSB_09_01 "CAN_SCAN_INDEX_2LSB_09_01"; +BA_ "GenSigVtEn" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_02 "CAN_DET_CONFID_AZIMUTH_09_02"; +BA_ "GenSigVtName" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_02 "CAN_DET_CONFID_AZIMUTH_09_02"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_02 "CAN_DET_CONFID_AZIMUTH_09_02"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_02 "CAN_DET_SUPER_RES_TARGET_09_02"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_ND_TARGET_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_ND_TARGET_09_02 "CAN_DET_ND_TARGET_09_02"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_02 "CAN_DET_HOST_VEH_CLUTTER_09_02"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_VALID_LEVEL_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_VALID_LEVEL_09_02 "CAN_DET_VALID_LEVEL_09_02"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_AZIMUTH_09_02 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AZIMUTH_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AZIMUTH_09_02 "CAN_DET_AZIMUTH_09_02"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_09_02 "CAN_DET_RANGE_09_02"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_RANGE_RATE_09_02 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_RATE_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_RATE_09_02 "CAN_DET_RANGE_RATE_09_02"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AMPLITUDE_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AMPLITUDE_09_02 "CAN_DET_AMPLITUDE_09_02"; +BA_ "GenSigSendType" SG_ 296 CAN_SCAN_INDEX_2LSB_09_02 0; +BA_ "GenSigCmt" SG_ 296 CAN_SCAN_INDEX_2LSB_09_02 "CAN_SCAN_INDEX_2LSB_09_02"; +BA_ "GenSigVtEn" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_03 "CAN_DET_CONFID_AZIMUTH_09_03"; +BA_ "GenSigVtName" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_03 "CAN_DET_CONFID_AZIMUTH_09_03"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_03 "CAN_DET_CONFID_AZIMUTH_09_03"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_03 "CAN_DET_SUPER_RES_TARGET_09_03"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_ND_TARGET_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_ND_TARGET_09_03 "CAN_DET_ND_TARGET_09_03"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_03 "CAN_DET_HOST_VEH_CLUTTER_09_03"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_VALID_LEVEL_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_VALID_LEVEL_09_03 "CAN_DET_VALID_LEVEL_09_03"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_AZIMUTH_09_03 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AZIMUTH_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AZIMUTH_09_03 "CAN_DET_AZIMUTH_09_03"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_09_03 "CAN_DET_RANGE_09_03"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_RANGE_RATE_09_03 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_RATE_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_RATE_09_03 "CAN_DET_RANGE_RATE_09_03"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AMPLITUDE_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AMPLITUDE_09_03 "CAN_DET_AMPLITUDE_09_03"; +BA_ "GenSigSendType" SG_ 296 CAN_SCAN_INDEX_2LSB_09_03 0; +BA_ "GenSigCmt" SG_ 296 CAN_SCAN_INDEX_2LSB_09_03 "CAN_SCAN_INDEX_2LSB_09_03"; +BA_ "GenSigVtEn" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_04 "CAN_DET_CONFID_AZIMUTH_09_04"; +BA_ "GenSigVtName" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_04 "CAN_DET_CONFID_AZIMUTH_09_04"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_04 "CAN_DET_CONFID_AZIMUTH_09_04"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_04 "CAN_DET_SUPER_RES_TARGET_09_04"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_ND_TARGET_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_ND_TARGET_09_04 "CAN_DET_ND_TARGET_09_04"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_04 "CAN_DET_HOST_VEH_CLUTTER_09_04"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_VALID_LEVEL_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_VALID_LEVEL_09_04 "CAN_DET_VALID_LEVEL_09_04"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_AZIMUTH_09_04 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AZIMUTH_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AZIMUTH_09_04 "CAN_DET_AZIMUTH_09_04"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_09_04 "CAN_DET_RANGE_09_04"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_RANGE_RATE_09_04 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_RATE_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_RATE_09_04 "CAN_DET_RANGE_RATE_09_04"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AMPLITUDE_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AMPLITUDE_09_04 "CAN_DET_AMPLITUDE_09_04"; +BA_ "GenSigSendType" SG_ 296 CAN_SCAN_INDEX_2LSB_09_04 0; +BA_ "GenSigCmt" SG_ 296 CAN_SCAN_INDEX_2LSB_09_04 "CAN_SCAN_INDEX_2LSB_09_04"; +BA_ "GenSigVtEn" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_05 "CAN_DET_CONFID_AZIMUTH_09_05"; +BA_ "GenSigVtName" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_05 "CAN_DET_CONFID_AZIMUTH_09_05"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_05 "CAN_DET_CONFID_AZIMUTH_09_05"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_05 "CAN_DET_SUPER_RES_TARGET_09_05"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_ND_TARGET_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_ND_TARGET_09_05 "CAN_DET_ND_TARGET_09_05"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_05 "CAN_DET_HOST_VEH_CLUTTER_09_05"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_VALID_LEVEL_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_VALID_LEVEL_09_05 "CAN_DET_VALID_LEVEL_09_05"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_AZIMUTH_09_05 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AZIMUTH_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AZIMUTH_09_05 "CAN_DET_AZIMUTH_09_05"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_09_05 "CAN_DET_RANGE_09_05"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_RANGE_RATE_09_05 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_RATE_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_RATE_09_05 "CAN_DET_RANGE_RATE_09_05"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AMPLITUDE_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AMPLITUDE_09_05 "CAN_DET_AMPLITUDE_09_05"; +BA_ "GenSigSendType" SG_ 296 CAN_SCAN_INDEX_2LSB_09_05 0; +BA_ "GenSigCmt" SG_ 296 CAN_SCAN_INDEX_2LSB_09_05 "CAN_SCAN_INDEX_2LSB_09_05"; +BA_ "GenSigVtEn" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_06 "CAN_DET_CONFID_AZIMUTH_09_06"; +BA_ "GenSigVtName" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_06 "CAN_DET_CONFID_AZIMUTH_09_06"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_CONFID_AZIMUTH_09_06 "CAN_DET_CONFID_AZIMUTH_09_06"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_SUPER_RES_TARGET_09_06 "CAN_DET_SUPER_RES_TARGET_09_06"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_ND_TARGET_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_ND_TARGET_09_06 "CAN_DET_ND_TARGET_09_06"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_HOST_VEH_CLUTTER_09_06 "CAN_DET_HOST_VEH_CLUTTER_09_06"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_VALID_LEVEL_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_VALID_LEVEL_09_06 "CAN_DET_VALID_LEVEL_09_06"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_AZIMUTH_09_06 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AZIMUTH_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AZIMUTH_09_06 "CAN_DET_AZIMUTH_09_06"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_09_06 "CAN_DET_RANGE_09_06"; +BA_ "GenSigStartValue" SG_ 296 CAN_DET_RANGE_RATE_09_06 0; +BA_ "GenSigSendType" SG_ 296 CAN_DET_RANGE_RATE_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_RANGE_RATE_09_06 "CAN_DET_RANGE_RATE_09_06"; +BA_ "GenSigSendType" SG_ 296 CAN_DET_AMPLITUDE_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_DET_AMPLITUDE_09_06 "CAN_DET_AMPLITUDE_09_06"; +BA_ "GenSigSendType" SG_ 296 CAN_SCAN_INDEX_2LSB_09_06 0; +BA_ "GenSigCmt" SG_ 296 CAN_SCAN_INDEX_2LSB_09_06 "CAN_SCAN_INDEX_2LSB_09_06"; +BA_ "GenMsgSendType" BO_ 295 1; +BA_ "GenMsgILSupport" BO_ 295 1; +BA_ "GenMsgNrOfRepetition" BO_ 295 0; +BA_ "GenMsgCycleTime" BO_ 295 0; +BA_ "NetworkInitialization" BO_ 295 0; +BA_ "GenMsgDelayTime" BO_ 295 0; +BA_ "GenSigVtEn" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_01 "CAN_DET_CONFID_AZIMUTH_08_01"; +BA_ "GenSigVtName" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_01 "CAN_DET_CONFID_AZIMUTH_08_01"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_01 "CAN_DET_CONFID_AZIMUTH_08_01"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_01 "CAN_DET_SUPER_RES_TARGET_08_01"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_ND_TARGET_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_ND_TARGET_08_01 "CAN_DET_ND_TARGET_08_01"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_01 "CAN_DET_HOST_VEH_CLUTTER_08_01"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_VALID_LEVEL_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_VALID_LEVEL_08_01 "CAN_DET_VALID_LEVEL_08_01"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_AZIMUTH_08_01 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AZIMUTH_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AZIMUTH_08_01 "CAN_DET_AZIMUTH_08_01"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_08_01 "CAN_DET_RANGE_08_01"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_RANGE_RATE_08_01 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_RATE_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_RATE_08_01 "CAN_DET_RANGE_RATE_08_01"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AMPLITUDE_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AMPLITUDE_08_01 "CAN_DET_AMPLITUDE_08_01"; +BA_ "GenSigSendType" SG_ 295 CAN_SCAN_INDEX_2LSB_08_01 0; +BA_ "GenSigCmt" SG_ 295 CAN_SCAN_INDEX_2LSB_08_01 "CAN_SCAN_INDEX_2LSB_08_01"; +BA_ "GenSigVtEn" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_02 "CAN_DET_CONFID_AZIMUTH_08_02"; +BA_ "GenSigVtName" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_02 "CAN_DET_CONFID_AZIMUTH_08_02"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_02 "CAN_DET_CONFID_AZIMUTH_08_02"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_02 "CAN_DET_SUPER_RES_TARGET_08_02"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_ND_TARGET_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_ND_TARGET_08_02 "CAN_DET_ND_TARGET_08_02"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_02 "CAN_DET_HOST_VEH_CLUTTER_08_02"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_VALID_LEVEL_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_VALID_LEVEL_08_02 "CAN_DET_VALID_LEVEL_08_02"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_AZIMUTH_08_02 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AZIMUTH_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AZIMUTH_08_02 "CAN_DET_AZIMUTH_08_02"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_08_02 "CAN_DET_RANGE_08_02"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_RANGE_RATE_08_02 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_RATE_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_RATE_08_02 "CAN_DET_RANGE_RATE_08_02"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AMPLITUDE_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AMPLITUDE_08_02 "CAN_DET_AMPLITUDE_08_02"; +BA_ "GenSigSendType" SG_ 295 CAN_SCAN_INDEX_2LSB_08_02 0; +BA_ "GenSigCmt" SG_ 295 CAN_SCAN_INDEX_2LSB_08_02 "CAN_SCAN_INDEX_2LSB_08_02"; +BA_ "GenSigVtEn" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_03 "CAN_DET_CONFID_AZIMUTH_08_03"; +BA_ "GenSigVtName" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_03 "CAN_DET_CONFID_AZIMUTH_08_03"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_03 "CAN_DET_CONFID_AZIMUTH_08_03"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_03 "CAN_DET_SUPER_RES_TARGET_08_03"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_ND_TARGET_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_ND_TARGET_08_03 "CAN_DET_ND_TARGET_08_03"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_03 "CAN_DET_HOST_VEH_CLUTTER_08_03"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_VALID_LEVEL_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_VALID_LEVEL_08_03 "CAN_DET_VALID_LEVEL_08_03"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_AZIMUTH_08_03 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AZIMUTH_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AZIMUTH_08_03 "CAN_DET_AZIMUTH_08_03"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_08_03 "CAN_DET_RANGE_08_03"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_RANGE_RATE_08_03 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_RATE_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_RATE_08_03 "CAN_DET_RANGE_RATE_08_03"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AMPLITUDE_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AMPLITUDE_08_03 "CAN_DET_AMPLITUDE_08_03"; +BA_ "GenSigSendType" SG_ 295 CAN_SCAN_INDEX_2LSB_08_03 0; +BA_ "GenSigCmt" SG_ 295 CAN_SCAN_INDEX_2LSB_08_03 "CAN_SCAN_INDEX_2LSB_08_03"; +BA_ "GenSigVtEn" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_04 "CAN_DET_CONFID_AZIMUTH_08_04"; +BA_ "GenSigVtName" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_04 "CAN_DET_CONFID_AZIMUTH_08_04"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_04 "CAN_DET_CONFID_AZIMUTH_08_04"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_04 "CAN_DET_SUPER_RES_TARGET_08_04"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_ND_TARGET_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_ND_TARGET_08_04 "CAN_DET_ND_TARGET_08_04"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_04 "CAN_DET_HOST_VEH_CLUTTER_08_04"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_VALID_LEVEL_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_VALID_LEVEL_08_04 "CAN_DET_VALID_LEVEL_08_04"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_AZIMUTH_08_04 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AZIMUTH_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AZIMUTH_08_04 "CAN_DET_AZIMUTH_08_04"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_08_04 "CAN_DET_RANGE_08_04"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_RANGE_RATE_08_04 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_RATE_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_RATE_08_04 "CAN_DET_RANGE_RATE_08_04"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AMPLITUDE_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AMPLITUDE_08_04 "CAN_DET_AMPLITUDE_08_04"; +BA_ "GenSigSendType" SG_ 295 CAN_SCAN_INDEX_2LSB_08_04 0; +BA_ "GenSigCmt" SG_ 295 CAN_SCAN_INDEX_2LSB_08_04 "CAN_SCAN_INDEX_2LSB_08_04"; +BA_ "GenSigVtEn" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_05 "CAN_DET_CONFID_AZIMUTH_08_05"; +BA_ "GenSigVtName" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_05 "CAN_DET_CONFID_AZIMUTH_08_05"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_05 "CAN_DET_CONFID_AZIMUTH_08_05"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_05 "CAN_DET_SUPER_RES_TARGET_08_05"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_ND_TARGET_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_ND_TARGET_08_05 "CAN_DET_ND_TARGET_08_05"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_05 "CAN_DET_HOST_VEH_CLUTTER_08_05"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_VALID_LEVEL_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_VALID_LEVEL_08_05 "CAN_DET_VALID_LEVEL_08_05"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_AZIMUTH_08_05 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AZIMUTH_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AZIMUTH_08_05 "CAN_DET_AZIMUTH_08_05"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_08_05 "CAN_DET_RANGE_08_05"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_RANGE_RATE_08_05 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_RATE_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_RATE_08_05 "CAN_DET_RANGE_RATE_08_05"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AMPLITUDE_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AMPLITUDE_08_05 "CAN_DET_AMPLITUDE_08_05"; +BA_ "GenSigSendType" SG_ 295 CAN_SCAN_INDEX_2LSB_08_05 0; +BA_ "GenSigCmt" SG_ 295 CAN_SCAN_INDEX_2LSB_08_05 "CAN_SCAN_INDEX_2LSB_08_05"; +BA_ "GenSigVtEn" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_06 "CAN_DET_CONFID_AZIMUTH_08_06"; +BA_ "GenSigVtName" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_06 "CAN_DET_CONFID_AZIMUTH_08_06"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_CONFID_AZIMUTH_08_06 "CAN_DET_CONFID_AZIMUTH_08_06"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_SUPER_RES_TARGET_08_06 "CAN_DET_SUPER_RES_TARGET_08_06"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_ND_TARGET_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_ND_TARGET_08_06 "CAN_DET_ND_TARGET_08_06"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_HOST_VEH_CLUTTER_08_06 "CAN_DET_HOST_VEH_CLUTTER_08_06"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_VALID_LEVEL_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_VALID_LEVEL_08_06 "CAN_DET_VALID_LEVEL_08_06"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_AZIMUTH_08_06 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AZIMUTH_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AZIMUTH_08_06 "CAN_DET_AZIMUTH_08_06"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_08_06 "CAN_DET_RANGE_08_06"; +BA_ "GenSigStartValue" SG_ 295 CAN_DET_RANGE_RATE_08_06 0; +BA_ "GenSigSendType" SG_ 295 CAN_DET_RANGE_RATE_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_RANGE_RATE_08_06 "CAN_DET_RANGE_RATE_08_06"; +BA_ "GenSigSendType" SG_ 295 CAN_DET_AMPLITUDE_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_DET_AMPLITUDE_08_06 "CAN_DET_AMPLITUDE_08_06"; +BA_ "GenSigSendType" SG_ 295 CAN_SCAN_INDEX_2LSB_08_06 0; +BA_ "GenSigCmt" SG_ 295 CAN_SCAN_INDEX_2LSB_08_06 "CAN_SCAN_INDEX_2LSB_08_06"; +BA_ "GenMsgSendType" BO_ 294 1; +BA_ "GenMsgILSupport" BO_ 294 1; +BA_ "GenMsgNrOfRepetition" BO_ 294 0; +BA_ "GenMsgCycleTime" BO_ 294 0; +BA_ "NetworkInitialization" BO_ 294 0; +BA_ "GenMsgDelayTime" BO_ 294 0; +BA_ "GenSigVtEn" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_01 "CAN_DET_CONFID_AZIMUTH_07_01"; +BA_ "GenSigVtName" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_01 "CAN_DET_CONFID_AZIMUTH_07_01"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_01 "CAN_DET_CONFID_AZIMUTH_07_01"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_01 "CAN_DET_SUPER_RES_TARGET_07_01"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_ND_TARGET_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_ND_TARGET_07_01 "CAN_DET_ND_TARGET_07_01"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_01 "CAN_DET_HOST_VEH_CLUTTER_07_01"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_VALID_LEVEL_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_VALID_LEVEL_07_01 "CAN_DET_VALID_LEVEL_07_01"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_AZIMUTH_07_01 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AZIMUTH_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AZIMUTH_07_01 "CAN_DET_AZIMUTH_07_01"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_07_01 "CAN_DET_RANGE_07_01"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_RANGE_RATE_07_01 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_RATE_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_RATE_07_01 "CAN_DET_RANGE_RATE_07_01"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AMPLITUDE_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AMPLITUDE_07_01 "CAN_DET_AMPLITUDE_07_01"; +BA_ "GenSigSendType" SG_ 294 CAN_SCAN_INDEX_2LSB_07_01 0; +BA_ "GenSigCmt" SG_ 294 CAN_SCAN_INDEX_2LSB_07_01 "CAN_SCAN_INDEX_2LSB_07_01"; +BA_ "GenSigVtEn" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_02 "CAN_DET_CONFID_AZIMUTH_07_02"; +BA_ "GenSigVtName" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_02 "CAN_DET_CONFID_AZIMUTH_07_02"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_02 "CAN_DET_CONFID_AZIMUTH_07_02"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_02 "CAN_DET_SUPER_RES_TARGET_07_02"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_ND_TARGET_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_ND_TARGET_07_02 "CAN_DET_ND_TARGET_07_02"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_02 "CAN_DET_HOST_VEH_CLUTTER_07_02"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_VALID_LEVEL_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_VALID_LEVEL_07_02 "CAN_DET_VALID_LEVEL_07_02"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_AZIMUTH_07_02 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AZIMUTH_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AZIMUTH_07_02 "CAN_DET_AZIMUTH_07_02"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_07_02 "CAN_DET_RANGE_07_02"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_RANGE_RATE_07_02 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_RATE_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_RATE_07_02 "CAN_DET_RANGE_RATE_07_02"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AMPLITUDE_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AMPLITUDE_07_02 "CAN_DET_AMPLITUDE_07_02"; +BA_ "GenSigSendType" SG_ 294 CAN_SCAN_INDEX_2LSB_07_02 0; +BA_ "GenSigCmt" SG_ 294 CAN_SCAN_INDEX_2LSB_07_02 "CAN_SCAN_INDEX_2LSB_07_02"; +BA_ "GenSigVtEn" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_03 "CAN_DET_CONFID_AZIMUTH_07_03"; +BA_ "GenSigVtName" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_03 "CAN_DET_CONFID_AZIMUTH_07_03"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_03 "CAN_DET_CONFID_AZIMUTH_07_03"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_03 "CAN_DET_SUPER_RES_TARGET_07_03"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_ND_TARGET_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_ND_TARGET_07_03 "CAN_DET_ND_TARGET_07_03"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_03 "CAN_DET_HOST_VEH_CLUTTER_07_03"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_VALID_LEVEL_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_VALID_LEVEL_07_03 "CAN_DET_VALID_LEVEL_07_03"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_AZIMUTH_07_03 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AZIMUTH_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AZIMUTH_07_03 "CAN_DET_AZIMUTH_07_03"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_07_03 "CAN_DET_RANGE_07_03"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_RANGE_RATE_07_03 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_RATE_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_RATE_07_03 "CAN_DET_RANGE_RATE_07_03"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AMPLITUDE_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AMPLITUDE_07_03 "CAN_DET_AMPLITUDE_07_03"; +BA_ "GenSigSendType" SG_ 294 CAN_SCAN_INDEX_2LSB_07_03 0; +BA_ "GenSigCmt" SG_ 294 CAN_SCAN_INDEX_2LSB_07_03 "CAN_SCAN_INDEX_2LSB_07_03"; +BA_ "GenSigVtEn" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_04 "CAN_DET_CONFID_AZIMUTH_07_04"; +BA_ "GenSigVtName" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_04 "CAN_DET_CONFID_AZIMUTH_07_04"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_04 "CAN_DET_CONFID_AZIMUTH_07_04"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_04 "CAN_DET_SUPER_RES_TARGET_07_04"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_ND_TARGET_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_ND_TARGET_07_04 "CAN_DET_ND_TARGET_07_04"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_04 "CAN_DET_HOST_VEH_CLUTTER_07_04"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_VALID_LEVEL_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_VALID_LEVEL_07_04 "CAN_DET_VALID_LEVEL_07_04"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_AZIMUTH_07_04 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AZIMUTH_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AZIMUTH_07_04 "CAN_DET_AZIMUTH_07_04"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_07_04 "CAN_DET_RANGE_07_04"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_RANGE_RATE_07_04 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_RATE_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_RATE_07_04 "CAN_DET_RANGE_RATE_07_04"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AMPLITUDE_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AMPLITUDE_07_04 "CAN_DET_AMPLITUDE_07_04"; +BA_ "GenSigSendType" SG_ 294 CAN_SCAN_INDEX_2LSB_07_04 0; +BA_ "GenSigCmt" SG_ 294 CAN_SCAN_INDEX_2LSB_07_04 "CAN_SCAN_INDEX_2LSB_07_04"; +BA_ "GenSigVtEn" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_05 "CAN_DET_CONFID_AZIMUTH_07_05"; +BA_ "GenSigVtName" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_05 "CAN_DET_CONFID_AZIMUTH_07_05"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_05 "CAN_DET_CONFID_AZIMUTH_07_05"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_05 "CAN_DET_SUPER_RES_TARGET_07_05"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_ND_TARGET_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_ND_TARGET_07_05 "CAN_DET_ND_TARGET_07_05"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_05 "CAN_DET_HOST_VEH_CLUTTER_07_05"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_VALID_LEVEL_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_VALID_LEVEL_07_05 "CAN_DET_VALID_LEVEL_07_05"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_AZIMUTH_07_05 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AZIMUTH_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AZIMUTH_07_05 "CAN_DET_AZIMUTH_07_05"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_07_05 "CAN_DET_RANGE_07_05"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_RANGE_RATE_07_05 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_RATE_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_RATE_07_05 "CAN_DET_RANGE_RATE_07_05"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AMPLITUDE_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AMPLITUDE_07_05 "CAN_DET_AMPLITUDE_07_05"; +BA_ "GenSigSendType" SG_ 294 CAN_SCAN_INDEX_2LSB_07_05 0; +BA_ "GenSigCmt" SG_ 294 CAN_SCAN_INDEX_2LSB_07_05 "CAN_SCAN_INDEX_2LSB_07_05"; +BA_ "GenSigVtEn" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_06 "CAN_DET_CONFID_AZIMUTH_07_06"; +BA_ "GenSigVtName" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_06 "CAN_DET_CONFID_AZIMUTH_07_06"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_CONFID_AZIMUTH_07_06 "CAN_DET_CONFID_AZIMUTH_07_06"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_SUPER_RES_TARGET_07_06 "CAN_DET_SUPER_RES_TARGET_07_06"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_ND_TARGET_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_ND_TARGET_07_06 "CAN_DET_ND_TARGET_07_06"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_HOST_VEH_CLUTTER_07_06 "CAN_DET_HOST_VEH_CLUTTER_07_06"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_VALID_LEVEL_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_VALID_LEVEL_07_06 "CAN_DET_VALID_LEVEL_07_06"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_AZIMUTH_07_06 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AZIMUTH_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AZIMUTH_07_06 "CAN_DET_AZIMUTH_07_06"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_07_06 "CAN_DET_RANGE_07_06"; +BA_ "GenSigStartValue" SG_ 294 CAN_DET_RANGE_RATE_07_06 0; +BA_ "GenSigSendType" SG_ 294 CAN_DET_RANGE_RATE_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_RANGE_RATE_07_06 "CAN_DET_RANGE_RATE_07_06"; +BA_ "GenSigSendType" SG_ 294 CAN_DET_AMPLITUDE_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_DET_AMPLITUDE_07_06 "CAN_DET_AMPLITUDE_07_06"; +BA_ "GenSigSendType" SG_ 294 CAN_SCAN_INDEX_2LSB_07_06 0; +BA_ "GenSigCmt" SG_ 294 CAN_SCAN_INDEX_2LSB_07_06 "CAN_SCAN_INDEX_2LSB_07_06"; +BA_ "GenMsgSendType" BO_ 293 1; +BA_ "GenMsgILSupport" BO_ 293 1; +BA_ "GenMsgNrOfRepetition" BO_ 293 0; +BA_ "GenMsgCycleTime" BO_ 293 0; +BA_ "NetworkInitialization" BO_ 293 0; +BA_ "GenMsgDelayTime" BO_ 293 0; +BA_ "GenSigVtEn" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_01 "CAN_DET_CONFID_AZIMUTH_06_01"; +BA_ "GenSigVtName" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_01 "CAN_DET_CONFID_AZIMUTH_06_01"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_01 "CAN_DET_CONFID_AZIMUTH_06_01"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_01 "CAN_DET_SUPER_RES_TARGET_06_01"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_ND_TARGET_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_ND_TARGET_06_01 "CAN_DET_ND_TARGET_06_01"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_01 "CAN_DET_HOST_VEH_CLUTTER_06_01"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_VALID_LEVEL_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_VALID_LEVEL_06_01 "CAN_DET_VALID_LEVEL_06_01"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_AZIMUTH_06_01 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AZIMUTH_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AZIMUTH_06_01 "CAN_DET_AZIMUTH_06_01"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_06_01 "CAN_DET_RANGE_06_01"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_RANGE_RATE_06_01 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_RATE_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_RATE_06_01 "CAN_DET_RANGE_RATE_06_01"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AMPLITUDE_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AMPLITUDE_06_01 "CAN_DET_AMPLITUDE_06_01"; +BA_ "GenSigSendType" SG_ 293 CAN_SCAN_INDEX_2LSB_06_01 0; +BA_ "GenSigCmt" SG_ 293 CAN_SCAN_INDEX_2LSB_06_01 "CAN_SCAN_INDEX_2LSB_06_01"; +BA_ "GenSigVtEn" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_02 "CAN_DET_CONFID_AZIMUTH_06_02"; +BA_ "GenSigVtName" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_02 "CAN_DET_CONFID_AZIMUTH_06_02"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_02 "CAN_DET_CONFID_AZIMUTH_06_02"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_02 "CAN_DET_SUPER_RES_TARGET_06_02"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_ND_TARGET_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_ND_TARGET_06_02 "CAN_DET_ND_TARGET_06_02"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_02 "CAN_DET_HOST_VEH_CLUTTER_06_02"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_VALID_LEVEL_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_VALID_LEVEL_06_02 "CAN_DET_VALID_LEVEL_06_02"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_AZIMUTH_06_02 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AZIMUTH_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AZIMUTH_06_02 "CAN_DET_AZIMUTH_06_02"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_06_02 "CAN_DET_RANGE_06_02"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_RANGE_RATE_06_02 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_RATE_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_RATE_06_02 "CAN_DET_RANGE_RATE_06_02"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AMPLITUDE_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AMPLITUDE_06_02 "CAN_DET_AMPLITUDE_06_02"; +BA_ "GenSigSendType" SG_ 293 CAN_SCAN_INDEX_2LSB_06_02 0; +BA_ "GenSigCmt" SG_ 293 CAN_SCAN_INDEX_2LSB_06_02 "CAN_SCAN_INDEX_2LSB_06_02"; +BA_ "GenSigVtEn" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_03 "CAN_DET_CONFID_AZIMUTH_06_03"; +BA_ "GenSigVtName" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_03 "CAN_DET_CONFID_AZIMUTH_06_03"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_03 "CAN_DET_CONFID_AZIMUTH_06_03"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_03 "CAN_DET_SUPER_RES_TARGET_06_03"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_ND_TARGET_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_ND_TARGET_06_03 "CAN_DET_ND_TARGET_06_03"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_03 "CAN_DET_HOST_VEH_CLUTTER_06_03"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_VALID_LEVEL_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_VALID_LEVEL_06_03 "CAN_DET_VALID_LEVEL_06_03"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_AZIMUTH_06_03 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AZIMUTH_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AZIMUTH_06_03 "CAN_DET_AZIMUTH_06_03"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_06_03 "CAN_DET_RANGE_06_03"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_RANGE_RATE_06_03 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_RATE_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_RATE_06_03 "CAN_DET_RANGE_RATE_06_03"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AMPLITUDE_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AMPLITUDE_06_03 "CAN_DET_AMPLITUDE_06_03"; +BA_ "GenSigSendType" SG_ 293 CAN_SCAN_INDEX_2LSB_06_03 0; +BA_ "GenSigCmt" SG_ 293 CAN_SCAN_INDEX_2LSB_06_03 "CAN_SCAN_INDEX_2LSB_06_03"; +BA_ "GenSigVtEn" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_04 "CAN_DET_CONFID_AZIMUTH_06_04"; +BA_ "GenSigVtName" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_04 "CAN_DET_CONFID_AZIMUTH_06_04"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_04 "CAN_DET_CONFID_AZIMUTH_06_04"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_04 "CAN_DET_SUPER_RES_TARGET_06_04"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_ND_TARGET_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_ND_TARGET_06_04 "CAN_DET_ND_TARGET_06_04"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_04 "CAN_DET_HOST_VEH_CLUTTER_06_04"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_VALID_LEVEL_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_VALID_LEVEL_06_04 "CAN_DET_VALID_LEVEL_06_04"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_AZIMUTH_06_04 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AZIMUTH_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AZIMUTH_06_04 "CAN_DET_AZIMUTH_06_04"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_06_04 "CAN_DET_RANGE_06_04"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_RANGE_RATE_06_04 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_RATE_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_RATE_06_04 "CAN_DET_RANGE_RATE_06_04"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AMPLITUDE_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AMPLITUDE_06_04 "CAN_DET_AMPLITUDE_06_04"; +BA_ "GenSigSendType" SG_ 293 CAN_SCAN_INDEX_2LSB_06_04 0; +BA_ "GenSigCmt" SG_ 293 CAN_SCAN_INDEX_2LSB_06_04 "CAN_SCAN_INDEX_2LSB_06_04"; +BA_ "GenSigVtEn" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_05 "CAN_DET_CONFID_AZIMUTH_06_05"; +BA_ "GenSigVtName" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_05 "CAN_DET_CONFID_AZIMUTH_06_05"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_05 "CAN_DET_CONFID_AZIMUTH_06_05"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_05 "CAN_DET_SUPER_RES_TARGET_06_05"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_ND_TARGET_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_ND_TARGET_06_05 "CAN_DET_ND_TARGET_06_05"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_05 "CAN_DET_HOST_VEH_CLUTTER_06_05"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_VALID_LEVEL_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_VALID_LEVEL_06_05 "CAN_DET_VALID_LEVEL_06_05"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_AZIMUTH_06_05 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AZIMUTH_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AZIMUTH_06_05 "CAN_DET_AZIMUTH_06_05"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_06_05 "CAN_DET_RANGE_06_05"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_RANGE_RATE_06_05 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_RATE_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_RATE_06_05 "CAN_DET_RANGE_RATE_06_05"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AMPLITUDE_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AMPLITUDE_06_05 "CAN_DET_AMPLITUDE_06_05"; +BA_ "GenSigSendType" SG_ 293 CAN_SCAN_INDEX_2LSB_06_05 0; +BA_ "GenSigCmt" SG_ 293 CAN_SCAN_INDEX_2LSB_06_05 "CAN_SCAN_INDEX_2LSB_06_05"; +BA_ "GenSigVtEn" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_06 "CAN_DET_CONFID_AZIMUTH_06_06"; +BA_ "GenSigVtName" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_06 "CAN_DET_CONFID_AZIMUTH_06_06"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_CONFID_AZIMUTH_06_06 "CAN_DET_CONFID_AZIMUTH_06_06"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_SUPER_RES_TARGET_06_06 "CAN_DET_SUPER_RES_TARGET_06_06"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_ND_TARGET_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_ND_TARGET_06_06 "CAN_DET_ND_TARGET_06_06"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_HOST_VEH_CLUTTER_06_06 "CAN_DET_HOST_VEH_CLUTTER_06_06"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_VALID_LEVEL_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_VALID_LEVEL_06_06 "CAN_DET_VALID_LEVEL_06_06"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_AZIMUTH_06_06 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AZIMUTH_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AZIMUTH_06_06 "CAN_DET_AZIMUTH_06_06"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_06_06 "CAN_DET_RANGE_06_06"; +BA_ "GenSigStartValue" SG_ 293 CAN_DET_RANGE_RATE_06_06 0; +BA_ "GenSigSendType" SG_ 293 CAN_DET_RANGE_RATE_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_RANGE_RATE_06_06 "CAN_DET_RANGE_RATE_06_06"; +BA_ "GenSigSendType" SG_ 293 CAN_DET_AMPLITUDE_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_DET_AMPLITUDE_06_06 "CAN_DET_AMPLITUDE_06_06"; +BA_ "GenSigSendType" SG_ 293 CAN_SCAN_INDEX_2LSB_06_06 0; +BA_ "GenSigCmt" SG_ 293 CAN_SCAN_INDEX_2LSB_06_06 "CAN_SCAN_INDEX_2LSB_06_06"; +BA_ "GenMsgSendType" BO_ 292 1; +BA_ "GenMsgILSupport" BO_ 292 1; +BA_ "GenMsgNrOfRepetition" BO_ 292 0; +BA_ "GenMsgCycleTime" BO_ 292 0; +BA_ "NetworkInitialization" BO_ 292 0; +BA_ "GenMsgDelayTime" BO_ 292 0; +BA_ "GenSigVtEn" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_01 "CAN_DET_CONFID_AZIMUTH_05_01"; +BA_ "GenSigVtName" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_01 "CAN_DET_CONFID_AZIMUTH_05_01"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_01 "CAN_DET_CONFID_AZIMUTH_05_01"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_01 "CAN_DET_SUPER_RES_TARGET_05_01"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_ND_TARGET_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_ND_TARGET_05_01 "CAN_DET_ND_TARGET_05_01"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_01 "CAN_DET_HOST_VEH_CLUTTER_05_01"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_VALID_LEVEL_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_VALID_LEVEL_05_01 "CAN_DET_VALID_LEVEL_05_01"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_AZIMUTH_05_01 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AZIMUTH_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AZIMUTH_05_01 "CAN_DET_AZIMUTH_05_01"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_05_01 "CAN_DET_RANGE_05_01"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_RANGE_RATE_05_01 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_RATE_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_RATE_05_01 "CAN_DET_RANGE_RATE_05_01"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AMPLITUDE_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AMPLITUDE_05_01 "CAN_DET_AMPLITUDE_05_01"; +BA_ "GenSigSendType" SG_ 292 CAN_SCAN_INDEX_2LSB_05_01 0; +BA_ "GenSigCmt" SG_ 292 CAN_SCAN_INDEX_2LSB_05_01 "CAN_SCAN_INDEX_2LSB_05_01"; +BA_ "GenSigVtEn" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_02 "CAN_DET_CONFID_AZIMUTH_05_02"; +BA_ "GenSigVtName" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_02 "CAN_DET_CONFID_AZIMUTH_05_02"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_02 "CAN_DET_CONFID_AZIMUTH_05_02"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_02 "CAN_DET_SUPER_RES_TARGET_05_02"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_ND_TARGET_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_ND_TARGET_05_02 "CAN_DET_ND_TARGET_05_02"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_02 "CAN_DET_HOST_VEH_CLUTTER_05_02"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_VALID_LEVEL_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_VALID_LEVEL_05_02 "CAN_DET_VALID_LEVEL_05_02"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_AZIMUTH_05_02 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AZIMUTH_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AZIMUTH_05_02 "CAN_DET_AZIMUTH_05_02"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_05_02 "CAN_DET_RANGE_05_02"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_RANGE_RATE_05_02 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_RATE_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_RATE_05_02 "CAN_DET_RANGE_RATE_05_02"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AMPLITUDE_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AMPLITUDE_05_02 "CAN_DET_AMPLITUDE_05_02"; +BA_ "GenSigSendType" SG_ 292 CAN_SCAN_INDEX_2LSB_05_02 0; +BA_ "GenSigCmt" SG_ 292 CAN_SCAN_INDEX_2LSB_05_02 "CAN_SCAN_INDEX_2LSB_05_02"; +BA_ "GenSigVtEn" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_03 "CAN_DET_CONFID_AZIMUTH_05_03"; +BA_ "GenSigVtName" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_03 "CAN_DET_CONFID_AZIMUTH_05_03"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_03 "CAN_DET_CONFID_AZIMUTH_05_03"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_03 "CAN_DET_SUPER_RES_TARGET_05_03"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_ND_TARGET_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_ND_TARGET_05_03 "CAN_DET_ND_TARGET_05_03"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_03 "CAN_DET_HOST_VEH_CLUTTER_05_03"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_VALID_LEVEL_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_VALID_LEVEL_05_03 "CAN_DET_VALID_LEVEL_05_03"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_AZIMUTH_05_03 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AZIMUTH_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AZIMUTH_05_03 "CAN_DET_AZIMUTH_05_03"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_05_03 "CAN_DET_RANGE_05_03"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_RANGE_RATE_05_03 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_RATE_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_RATE_05_03 "CAN_DET_RANGE_RATE_05_03"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AMPLITUDE_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AMPLITUDE_05_03 "CAN_DET_AMPLITUDE_05_03"; +BA_ "GenSigSendType" SG_ 292 CAN_SCAN_INDEX_2LSB_05_03 0; +BA_ "GenSigCmt" SG_ 292 CAN_SCAN_INDEX_2LSB_05_03 "CAN_SCAN_INDEX_2LSB_05_03"; +BA_ "GenSigVtEn" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_04 "CAN_DET_CONFID_AZIMUTH_05_04"; +BA_ "GenSigVtName" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_04 "CAN_DET_CONFID_AZIMUTH_05_04"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_04 "CAN_DET_CONFID_AZIMUTH_05_04"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_04 "CAN_DET_SUPER_RES_TARGET_05_04"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_ND_TARGET_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_ND_TARGET_05_04 "CAN_DET_ND_TARGET_05_04"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_04 "CAN_DET_HOST_VEH_CLUTTER_05_04"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_VALID_LEVEL_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_VALID_LEVEL_05_04 "CAN_DET_VALID_LEVEL_05_04"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_AZIMUTH_05_04 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AZIMUTH_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AZIMUTH_05_04 "CAN_DET_AZIMUTH_05_04"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_05_04 "CAN_DET_RANGE_05_04"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_RANGE_RATE_05_04 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_RATE_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_RATE_05_04 "CAN_DET_RANGE_RATE_05_04"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AMPLITUDE_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AMPLITUDE_05_04 "CAN_DET_AMPLITUDE_05_04"; +BA_ "GenSigSendType" SG_ 292 CAN_SCAN_INDEX_2LSB_05_04 0; +BA_ "GenSigCmt" SG_ 292 CAN_SCAN_INDEX_2LSB_05_04 "CAN_SCAN_INDEX_2LSB_05_04"; +BA_ "GenSigVtEn" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_05 "CAN_DET_CONFID_AZIMUTH_05_05"; +BA_ "GenSigVtName" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_05 "CAN_DET_CONFID_AZIMUTH_05_05"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_05 "CAN_DET_CONFID_AZIMUTH_05_05"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_05 "CAN_DET_SUPER_RES_TARGET_05_05"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_ND_TARGET_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_ND_TARGET_05_05 "CAN_DET_ND_TARGET_05_05"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_05 "CAN_DET_HOST_VEH_CLUTTER_05_05"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_VALID_LEVEL_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_VALID_LEVEL_05_05 "CAN_DET_VALID_LEVEL_05_05"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_AZIMUTH_05_05 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AZIMUTH_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AZIMUTH_05_05 "CAN_DET_AZIMUTH_05_05"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_05_05 "CAN_DET_RANGE_05_05"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_RANGE_RATE_05_05 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_RATE_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_RATE_05_05 "CAN_DET_RANGE_RATE_05_05"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AMPLITUDE_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AMPLITUDE_05_05 "CAN_DET_AMPLITUDE_05_05"; +BA_ "GenSigSendType" SG_ 292 CAN_SCAN_INDEX_2LSB_05_05 0; +BA_ "GenSigCmt" SG_ 292 CAN_SCAN_INDEX_2LSB_05_05 "CAN_SCAN_INDEX_2LSB_05_05"; +BA_ "GenSigVtEn" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_06 "CAN_DET_CONFID_AZIMUTH_05_06"; +BA_ "GenSigVtName" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_06 "CAN_DET_CONFID_AZIMUTH_05_06"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_CONFID_AZIMUTH_05_06 "CAN_DET_CONFID_AZIMUTH_05_06"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_SUPER_RES_TARGET_05_06 "CAN_DET_SUPER_RES_TARGET_05_06"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_ND_TARGET_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_ND_TARGET_05_06 "CAN_DET_ND_TARGET_05_06"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_HOST_VEH_CLUTTER_05_06 "CAN_DET_HOST_VEH_CLUTTER_05_06"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_VALID_LEVEL_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_VALID_LEVEL_05_06 "CAN_DET_VALID_LEVEL_05_06"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_AZIMUTH_05_06 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AZIMUTH_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AZIMUTH_05_06 "CAN_DET_AZIMUTH_05_06"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_05_06 "CAN_DET_RANGE_05_06"; +BA_ "GenSigStartValue" SG_ 292 CAN_DET_RANGE_RATE_05_06 0; +BA_ "GenSigSendType" SG_ 292 CAN_DET_RANGE_RATE_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_RANGE_RATE_05_06 "CAN_DET_RANGE_RATE_05_06"; +BA_ "GenSigSendType" SG_ 292 CAN_DET_AMPLITUDE_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_DET_AMPLITUDE_05_06 "CAN_DET_AMPLITUDE_05_06"; +BA_ "GenSigSendType" SG_ 292 CAN_SCAN_INDEX_2LSB_05_06 0; +BA_ "GenSigCmt" SG_ 292 CAN_SCAN_INDEX_2LSB_05_06 "CAN_SCAN_INDEX_2LSB_05_06"; +BA_ "GenMsgSendType" BO_ 290 1; +BA_ "GenMsgILSupport" BO_ 290 1; +BA_ "GenMsgNrOfRepetition" BO_ 290 0; +BA_ "GenMsgCycleTime" BO_ 290 0; +BA_ "NetworkInitialization" BO_ 290 0; +BA_ "GenMsgDelayTime" BO_ 290 0; +BA_ "GenSigVtEn" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_01 "CAN_DET_CONFID_AZIMUTH_03_01"; +BA_ "GenSigVtName" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_01 "CAN_DET_CONFID_AZIMUTH_03_01"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_01 "CAN_DET_CONFID_AZIMUTH_03_01"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_01 "CAN_DET_SUPER_RES_TARGET_03_01"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_ND_TARGET_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_ND_TARGET_03_01 "CAN_DET_ND_TARGET_03_01"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_01 "CAN_DET_HOST_VEH_CLUTTER_03_01"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_VALID_LEVEL_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_VALID_LEVEL_03_01 "CAN_DET_VALID_LEVEL_03_01"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_AZIMUTH_03_01 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AZIMUTH_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AZIMUTH_03_01 "CAN_DET_AZIMUTH_03_01"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_03_01 "CAN_DET_RANGE_03_01"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_RANGE_RATE_03_01 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_RATE_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_RATE_03_01 "CAN_DET_RANGE_RATE_03_01"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AMPLITUDE_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AMPLITUDE_03_01 "CAN_DET_AMPLITUDE_03_01"; +BA_ "GenSigSendType" SG_ 290 CAN_SCAN_INDEX_2LSB_03_01 0; +BA_ "GenSigCmt" SG_ 290 CAN_SCAN_INDEX_2LSB_03_01 "CAN_SCAN_INDEX_2LSB_03_01"; +BA_ "GenSigVtEn" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_02 "CAN_DET_CONFID_AZIMUTH_03_02"; +BA_ "GenSigVtName" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_02 "CAN_DET_CONFID_AZIMUTH_03_02"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_02 "CAN_DET_CONFID_AZIMUTH_03_02"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_02 "CAN_DET_SUPER_RES_TARGET_03_02"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_ND_TARGET_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_ND_TARGET_03_02 "CAN_DET_ND_TARGET_03_02"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_02 "CAN_DET_HOST_VEH_CLUTTER_03_02"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_VALID_LEVEL_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_VALID_LEVEL_03_02 "CAN_DET_VALID_LEVEL_03_02"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_AZIMUTH_03_02 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AZIMUTH_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AZIMUTH_03_02 "CAN_DET_AZIMUTH_03_02"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_03_02 "CAN_DET_RANGE_03_02"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_RANGE_RATE_03_02 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_RATE_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_RATE_03_02 "CAN_DET_RANGE_RATE_03_02"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AMPLITUDE_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AMPLITUDE_03_02 "CAN_DET_AMPLITUDE_03_02"; +BA_ "GenSigSendType" SG_ 290 CAN_SCAN_INDEX_2LSB_03_02 0; +BA_ "GenSigCmt" SG_ 290 CAN_SCAN_INDEX_2LSB_03_02 "CAN_SCAN_INDEX_2LSB_03_02"; +BA_ "GenSigVtEn" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_03 "CAN_DET_CONFID_AZIMUTH_03_03"; +BA_ "GenSigVtName" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_03 "CAN_DET_CONFID_AZIMUTH_03_03"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_03 "CAN_DET_CONFID_AZIMUTH_03_03"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_03 "CAN_DET_SUPER_RES_TARGET_03_03"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_ND_TARGET_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_ND_TARGET_03_03 "CAN_DET_ND_TARGET_03_03"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_03 "CAN_DET_HOST_VEH_CLUTTER_03_03"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_VALID_LEVEL_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_VALID_LEVEL_03_03 "CAN_DET_VALID_LEVEL_03_03"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_AZIMUTH_03_03 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AZIMUTH_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AZIMUTH_03_03 "CAN_DET_AZIMUTH_03_03"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_03_03 "CAN_DET_RANGE_03_03"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_RANGE_RATE_03_03 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_RATE_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_RATE_03_03 "CAN_DET_RANGE_RATE_03_03"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AMPLITUDE_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AMPLITUDE_03_03 "CAN_DET_AMPLITUDE_03_03"; +BA_ "GenSigSendType" SG_ 290 CAN_SCAN_INDEX_2LSB_03_03 0; +BA_ "GenSigCmt" SG_ 290 CAN_SCAN_INDEX_2LSB_03_03 "CAN_SCAN_INDEX_2LSB_03_03"; +BA_ "GenSigVtEn" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_04 "CAN_DET_CONFID_AZIMUTH_03_04"; +BA_ "GenSigVtName" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_04 "CAN_DET_CONFID_AZIMUTH_03_04"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_04 "CAN_DET_CONFID_AZIMUTH_03_04"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_04 "CAN_DET_SUPER_RES_TARGET_03_04"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_ND_TARGET_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_ND_TARGET_03_04 "CAN_DET_ND_TARGET_03_04"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_04 "CAN_DET_HOST_VEH_CLUTTER_03_04"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_VALID_LEVEL_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_VALID_LEVEL_03_04 "CAN_DET_VALID_LEVEL_03_04"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_AZIMUTH_03_04 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AZIMUTH_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AZIMUTH_03_04 "CAN_DET_AZIMUTH_03_04"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_03_04 "CAN_DET_RANGE_03_04"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_RANGE_RATE_03_04 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_RATE_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_RATE_03_04 "CAN_DET_RANGE_RATE_03_04"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AMPLITUDE_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AMPLITUDE_03_04 "CAN_DET_AMPLITUDE_03_04"; +BA_ "GenSigSendType" SG_ 290 CAN_SCAN_INDEX_2LSB_03_04 0; +BA_ "GenSigCmt" SG_ 290 CAN_SCAN_INDEX_2LSB_03_04 "CAN_SCAN_INDEX_2LSB_03_04"; +BA_ "GenSigVtEn" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_05 "CAN_DET_CONFID_AZIMUTH_03_05"; +BA_ "GenSigVtName" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_05 "CAN_DET_CONFID_AZIMUTH_03_05"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_05 "CAN_DET_CONFID_AZIMUTH_03_05"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_05 "CAN_DET_SUPER_RES_TARGET_03_05"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_ND_TARGET_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_ND_TARGET_03_05 "CAN_DET_ND_TARGET_03_05"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_05 "CAN_DET_HOST_VEH_CLUTTER_03_05"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_VALID_LEVEL_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_VALID_LEVEL_03_05 "CAN_DET_VALID_LEVEL_03_05"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_AZIMUTH_03_05 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AZIMUTH_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AZIMUTH_03_05 "CAN_DET_AZIMUTH_03_05"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_03_05 "CAN_DET_RANGE_03_05"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_RANGE_RATE_03_05 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_RATE_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_RATE_03_05 "CAN_DET_RANGE_RATE_03_05"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AMPLITUDE_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AMPLITUDE_03_05 "CAN_DET_AMPLITUDE_03_05"; +BA_ "GenSigSendType" SG_ 290 CAN_SCAN_INDEX_2LSB_03_05 0; +BA_ "GenSigCmt" SG_ 290 CAN_SCAN_INDEX_2LSB_03_05 "CAN_SCAN_INDEX_2LSB_03_05"; +BA_ "GenSigVtEn" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_06 "CAN_DET_CONFID_AZIMUTH_03_06"; +BA_ "GenSigVtName" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_06 "CAN_DET_CONFID_AZIMUTH_03_06"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_CONFID_AZIMUTH_03_06 "CAN_DET_CONFID_AZIMUTH_03_06"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_SUPER_RES_TARGET_03_06 "CAN_DET_SUPER_RES_TARGET_03_06"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_ND_TARGET_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_ND_TARGET_03_06 "CAN_DET_ND_TARGET_03_06"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_HOST_VEH_CLUTTER_03_06 "CAN_DET_HOST_VEH_CLUTTER_03_06"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_VALID_LEVEL_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_VALID_LEVEL_03_06 "CAN_DET_VALID_LEVEL_03_06"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_AZIMUTH_03_06 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AZIMUTH_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AZIMUTH_03_06 "CAN_DET_AZIMUTH_03_06"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_03_06 "CAN_DET_RANGE_03_06"; +BA_ "GenSigStartValue" SG_ 290 CAN_DET_RANGE_RATE_03_06 0; +BA_ "GenSigSendType" SG_ 290 CAN_DET_RANGE_RATE_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_RANGE_RATE_03_06 "CAN_DET_RANGE_RATE_03_06"; +BA_ "GenSigSendType" SG_ 290 CAN_DET_AMPLITUDE_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_DET_AMPLITUDE_03_06 "CAN_DET_AMPLITUDE_03_06"; +BA_ "GenSigSendType" SG_ 290 CAN_SCAN_INDEX_2LSB_03_06 0; +BA_ "GenSigCmt" SG_ 290 CAN_SCAN_INDEX_2LSB_03_06 "CAN_SCAN_INDEX_2LSB_03_06"; +BA_ "GenMsgSendType" BO_ 289 1; +BA_ "GenMsgILSupport" BO_ 289 1; +BA_ "GenMsgNrOfRepetition" BO_ 289 0; +BA_ "GenMsgCycleTime" BO_ 289 0; +BA_ "NetworkInitialization" BO_ 289 0; +BA_ "GenMsgDelayTime" BO_ 289 0; +BA_ "GenSigVtEn" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_01 "CAN_DET_CONFID_AZIMUTH_02_01"; +BA_ "GenSigVtName" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_01 "CAN_DET_CONFID_AZIMUTH_02_01"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_01 "CAN_DET_CONFID_AZIMUTH_02_01"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_01 "CAN_DET_SUPER_RES_TARGET_02_01"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_ND_TARGET_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_ND_TARGET_02_01 "CAN_DET_ND_TARGET_02_01"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_01 "CAN_DET_HOST_VEH_CLUTTER_02_01"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_VALID_LEVEL_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_VALID_LEVEL_02_01 "CAN_DET_VALID_LEVEL_02_01"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_AZIMUTH_02_01 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AZIMUTH_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AZIMUTH_02_01 "CAN_DET_AZIMUTH_02_01"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_02_01 "CAN_DET_RANGE_02_01"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_RANGE_RATE_02_01 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_RATE_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_RATE_02_01 "CAN_DET_RANGE_RATE_02_01"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AMPLITUDE_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AMPLITUDE_02_01 "CAN_DET_AMPLITUDE_02_01"; +BA_ "GenSigSendType" SG_ 289 CAN_SCAN_INDEX_2LSB_02_01 0; +BA_ "GenSigCmt" SG_ 289 CAN_SCAN_INDEX_2LSB_02_01 "CAN_SCAN_INDEX_2LSB_02_01"; +BA_ "GenSigVtEn" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_02 "CAN_DET_CONFID_AZIMUTH_02_02"; +BA_ "GenSigVtName" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_02 "CAN_DET_CONFID_AZIMUTH_02_02"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_02 "CAN_DET_CONFID_AZIMUTH_02_02"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_02 "CAN_DET_SUPER_RES_TARGET_02_02"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_ND_TARGET_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_ND_TARGET_02_02 "CAN_DET_ND_TARGET_02_02"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_02 "CAN_DET_HOST_VEH_CLUTTER_02_02"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_VALID_LEVEL_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_VALID_LEVEL_02_02 "CAN_DET_VALID_LEVEL_02_02"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_AZIMUTH_02_02 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AZIMUTH_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AZIMUTH_02_02 "CAN_DET_AZIMUTH_02_02"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_02_02 "CAN_DET_RANGE_02_02"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_RANGE_RATE_02_02 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_RATE_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_RATE_02_02 "CAN_DET_RANGE_RATE_02_02"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AMPLITUDE_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AMPLITUDE_02_02 "CAN_DET_AMPLITUDE_02_02"; +BA_ "GenSigSendType" SG_ 289 CAN_SCAN_INDEX_2LSB_02_02 0; +BA_ "GenSigCmt" SG_ 289 CAN_SCAN_INDEX_2LSB_02_02 "CAN_SCAN_INDEX_2LSB_02_02"; +BA_ "GenSigVtEn" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_03 "CAN_DET_CONFID_AZIMUTH_02_03"; +BA_ "GenSigVtName" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_03 "CAN_DET_CONFID_AZIMUTH_02_03"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_03 "CAN_DET_CONFID_AZIMUTH_02_03"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_03 "CAN_DET_SUPER_RES_TARGET_02_03"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_ND_TARGET_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_ND_TARGET_02_03 "CAN_DET_ND_TARGET_02_03"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_03 "CAN_DET_HOST_VEH_CLUTTER_02_03"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_VALID_LEVEL_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_VALID_LEVEL_02_03 "CAN_DET_VALID_LEVEL_02_03"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_AZIMUTH_02_03 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AZIMUTH_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AZIMUTH_02_03 "CAN_DET_AZIMUTH_02_03"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_02_03 "CAN_DET_RANGE_02_03"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_RANGE_RATE_02_03 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_RATE_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_RATE_02_03 "CAN_DET_RANGE_RATE_02_03"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AMPLITUDE_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AMPLITUDE_02_03 "CAN_DET_AMPLITUDE_02_03"; +BA_ "GenSigSendType" SG_ 289 CAN_SCAN_INDEX_2LSB_02_03 0; +BA_ "GenSigCmt" SG_ 289 CAN_SCAN_INDEX_2LSB_02_03 "CAN_SCAN_INDEX_2LSB_02_03"; +BA_ "GenSigVtEn" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_04 "CAN_DET_CONFID_AZIMUTH_02_04"; +BA_ "GenSigVtName" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_04 "CAN_DET_CONFID_AZIMUTH_02_04"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_04 "CAN_DET_CONFID_AZIMUTH_02_04"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_04 "CAN_DET_SUPER_RES_TARGET_02_04"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_ND_TARGET_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_ND_TARGET_02_04 "CAN_DET_ND_TARGET_02_04"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_04 "CAN_DET_HOST_VEH_CLUTTER_02_04"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_VALID_LEVEL_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_VALID_LEVEL_02_04 "CAN_DET_VALID_LEVEL_02_04"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_AZIMUTH_02_04 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AZIMUTH_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AZIMUTH_02_04 "CAN_DET_AZIMUTH_02_04"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_02_04 "CAN_DET_RANGE_02_04"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_RANGE_RATE_02_04 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_RATE_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_RATE_02_04 "CAN_DET_RANGE_RATE_02_04"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AMPLITUDE_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AMPLITUDE_02_04 "CAN_DET_AMPLITUDE_02_04"; +BA_ "GenSigSendType" SG_ 289 CAN_SCAN_INDEX_2LSB_02_04 0; +BA_ "GenSigCmt" SG_ 289 CAN_SCAN_INDEX_2LSB_02_04 "CAN_SCAN_INDEX_2LSB_02_04"; +BA_ "GenSigVtEn" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_05 "CAN_DET_CONFID_AZIMUTH_02_05"; +BA_ "GenSigVtName" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_05 "CAN_DET_CONFID_AZIMUTH_02_05"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_05 "CAN_DET_CONFID_AZIMUTH_02_05"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_05 "CAN_DET_SUPER_RES_TARGET_02_05"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_ND_TARGET_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_ND_TARGET_02_05 "CAN_DET_ND_TARGET_02_05"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_05 "CAN_DET_HOST_VEH_CLUTTER_02_05"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_VALID_LEVEL_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_VALID_LEVEL_02_05 "CAN_DET_VALID_LEVEL_02_05"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_AZIMUTH_02_05 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AZIMUTH_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AZIMUTH_02_05 "CAN_DET_AZIMUTH_02_05"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_02_05 "CAN_DET_RANGE_02_05"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_RANGE_RATE_02_05 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_RATE_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_RATE_02_05 "CAN_DET_RANGE_RATE_02_05"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AMPLITUDE_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AMPLITUDE_02_05 "CAN_DET_AMPLITUDE_02_05"; +BA_ "GenSigSendType" SG_ 289 CAN_SCAN_INDEX_2LSB_02_05 0; +BA_ "GenSigCmt" SG_ 289 CAN_SCAN_INDEX_2LSB_02_05 "CAN_SCAN_INDEX_2LSB_02_05"; +BA_ "GenSigVtEn" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_06 "CAN_DET_CONFID_AZIMUTH_02_06"; +BA_ "GenSigVtName" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_06 "CAN_DET_CONFID_AZIMUTH_02_06"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_CONFID_AZIMUTH_02_06 "CAN_DET_CONFID_AZIMUTH_02_06"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_SUPER_RES_TARGET_02_06 "CAN_DET_SUPER_RES_TARGET_02_06"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_ND_TARGET_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_ND_TARGET_02_06 "CAN_DET_ND_TARGET_02_06"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_HOST_VEH_CLUTTER_02_06 "CAN_DET_HOST_VEH_CLUTTER_02_06"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_VALID_LEVEL_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_VALID_LEVEL_02_06 "CAN_DET_VALID_LEVEL_02_06"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_AZIMUTH_02_06 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AZIMUTH_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AZIMUTH_02_06 "CAN_DET_AZIMUTH_02_06"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_02_06 "CAN_DET_RANGE_02_06"; +BA_ "GenSigStartValue" SG_ 289 CAN_DET_RANGE_RATE_02_06 0; +BA_ "GenSigSendType" SG_ 289 CAN_DET_RANGE_RATE_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_RANGE_RATE_02_06 "CAN_DET_RANGE_RATE_02_06"; +BA_ "GenSigSendType" SG_ 289 CAN_DET_AMPLITUDE_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_DET_AMPLITUDE_02_06 "CAN_DET_AMPLITUDE_02_06"; +BA_ "GenSigSendType" SG_ 289 CAN_SCAN_INDEX_2LSB_02_06 0; +BA_ "GenSigCmt" SG_ 289 CAN_SCAN_INDEX_2LSB_02_06 "CAN_SCAN_INDEX_2LSB_02_06"; +BA_ "GenMsgSendType" BO_ 256 1; +BA_ "GenMsgILSupport" BO_ 256 1; +BA_ "GenMsgNrOfRepetition" BO_ 256 0; +BA_ "NetworkInitialization" BO_ 256 0; +BA_ "GenSigCmt" SG_ 256 CAN_PCAN_MINOR_MRR "CAN_PCAN_MINOR_MRR"; +BA_ "GenSigSendType" SG_ 256 CAN_PCAN_MINOR_MRR 0; +BA_ "GenSigCmt" SG_ 256 CAN_PCAN_MAJOR_MRR "CAN_PCAN_MAJOR_MRR"; +BA_ "GenSigSendType" SG_ 256 CAN_PCAN_MAJOR_MRR 0; +BA_ "GenMsgCycleTime" BO_ 257 30; +BA_ "GenMsgSendType" BO_ 257 0; +BA_ "GenMsgILSupport" BO_ 257 1; +BA_ "GenMsgNrOfRepetition" BO_ 257 0; +BA_ "NetworkInitialization" BO_ 257 0; +BA_ "GenSigCmt" SG_ 257 CAN_INTERFERENCE_TYPE "CAN_INTERFERENCE_TYPE"; +BA_ "GenSigVtEn" SG_ 257 CAN_INTERFERENCE_TYPE "CAN_INTERFERENCE_TYPE"; +BA_ "GenSigVtName" SG_ 257 CAN_INTERFERENCE_TYPE "CAN_INTERFERENCE_TYPE"; +BA_ "GenSigVtName" SG_ 257 CAN_RECOMMEND_UNCONVERGE "CAN_RECOMMEND_UNCONVERGE"; +BA_ "GenSigVtEn" SG_ 257 CAN_RECOMMEND_UNCONVERGE "CAN_RECOMMEND_UNCONVERGE"; +BA_ "GenSigCmt" SG_ 257 CAN_RECOMMEND_UNCONVERGE "CAN_RECOMMEND_UNCONVERGE"; +BA_ "GenSigStartValue" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL 0; +BA_ "GenSigSendType" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL 0; +BA_ "GenSigCmt" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL "CAN_BLOCKAGE_SIDELOBE_FILTER_VAL"; +BA_ "GenSigVtEn" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL "CAN_BLOCKAGE_SIDELOBE_FILTER_VAL"; +BA_ "GenSigVtName" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL "CAN_BLOCKAGE_SIDELOBE_FILTER_VAL"; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_ALIGN_INCOMPLETE "CAN_RADAR_ALIGN_INCOMPLETE"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_ALIGN_INCOMPLETE "CAN_RADAR_ALIGN_INCOMPLETE"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_ALIGN_INCOMPLETE "CAN_RADAR_ALIGN_INCOMPLETE"; +BA_ "GenSigCmt" SG_ 257 CAN_BLOCKAGE_SIDELOBE "CAN_BLOCKAGE_SIDELOBE"; +BA_ "GenSigVtEn" SG_ 257 CAN_BLOCKAGE_SIDELOBE "CAN_BLOCKAGE_SIDELOBE"; +BA_ "GenSigVtName" SG_ 257 CAN_BLOCKAGE_SIDELOBE "CAN_BLOCKAGE_SIDELOBE"; +BA_ "GenSigSendType" SG_ 257 CAN_BLOCKAGE_SIDELOBE 0; +BA_ "GenSigCmt" SG_ 257 CAN_BLOCKAGE_MNR "CAN_BLOCKAGE_MNR"; +BA_ "GenSigVtEn" SG_ 257 CAN_BLOCKAGE_MNR "CAN_BLOCKAGE_MNR"; +BA_ "GenSigVtName" SG_ 257 CAN_BLOCKAGE_MNR "CAN_BLOCKAGE_MNR"; +BA_ "GenSigSendType" SG_ 257 CAN_BLOCKAGE_MNR 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_EXT_COND_NOK "CAN_RADAR_EXT_COND_NOK"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_EXT_COND_NOK "CAN_RADAR_EXT_COND_NOK"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_EXT_COND_NOK "CAN_RADAR_EXT_COND_NOK"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_EXT_COND_NOK 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_ALIGN_OUT_RANGE "CAN_RADAR_ALIGN_OUT_RANGE"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_ALIGN_OUT_RANGE "CAN_RADAR_ALIGN_OUT_RANGE"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_ALIGN_OUT_RANGE "CAN_RADAR_ALIGN_OUT_RANGE"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_ALIGN_OUT_RANGE 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_ALIGN_NOT_START "CAN_RADAR_ALIGN_NOT_START"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_ALIGN_NOT_START "CAN_RADAR_ALIGN_NOT_START"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_ALIGN_NOT_START "CAN_RADAR_ALIGN_NOT_START"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_ALIGN_NOT_START 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_OVERHEAT_ERROR "CAN_RADAR_OVERHEAT_ERROR"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_OVERHEAT_ERROR "CAN_RADAR_OVERHEAT_ERROR"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_OVERHEAT_ERROR "CAN_RADAR_OVERHEAT_ERROR"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_OVERHEAT_ERROR 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_NOT_OP "CAN_RADAR_NOT_OP"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_NOT_OP "CAN_RADAR_NOT_OP"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_NOT_OP "CAN_RADAR_NOT_OP"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_NOT_OP 0; +BA_ "GenSigCmt" SG_ 257 CAN_XCVR_OPERATIONAL "CAN_XCVR_OPERATIONAL"; +BA_ "GenSigVtEn" SG_ 257 CAN_XCVR_OPERATIONAL "CAN_XCVR_OPERATIONAL"; +BA_ "GenSigVtName" SG_ 257 CAN_XCVR_OPERATIONAL "CAN_XCVR_OPERATIONAL"; +BA_ "GenSigSendType" SG_ 257 CAN_XCVR_OPERATIONAL 0; +BA_ "GenMsgSendType" BO_ 288 1; +BA_ "GenMsgILSupport" BO_ 288 1; +BA_ "GenMsgNrOfRepetition" BO_ 288 0; +BA_ "GenMsgCycleTime" BO_ 288 0; +BA_ "NetworkInitialization" BO_ 288 0; +BA_ "GenMsgDelayTime" BO_ 288 0; +BA_ "GenSigVtEn" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_01 "CAN_DET_CONFID_AZIMUTH_01_01"; +BA_ "GenSigVtName" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_01 "CAN_DET_CONFID_AZIMUTH_01_01"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_01 "CAN_DET_CONFID_AZIMUTH_01_01"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_01 "CAN_DET_SUPER_RES_TARGET_01_01"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_ND_TARGET_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_ND_TARGET_01_01 "CAN_DET_ND_TARGET_01_01"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_01 "CAN_DET_HOST_VEH_CLUTTER_01_01"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_VALID_LEVEL_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_VALID_LEVEL_01_01 "CAN_DET_VALID_LEVEL_01_01"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_AZIMUTH_01_01 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AZIMUTH_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AZIMUTH_01_01 "CAN_DET_AZIMUTH_01_01"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_01_01 "CAN_DET_RANGE_01_01"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_RANGE_RATE_01_01 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_RATE_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_RATE_01_01 "CAN_DET_RANGE_RATE_01_01"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AMPLITUDE_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AMPLITUDE_01_01 "CAN_DET_AMPLITUDE_01_01"; +BA_ "GenSigSendType" SG_ 288 CAN_SCAN_INDEX_2LSB_01_01 0; +BA_ "GenSigCmt" SG_ 288 CAN_SCAN_INDEX_2LSB_01_01 "CAN_SCAN_INDEX_2LSB_01_01"; +BA_ "GenSigVtEn" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_02 "CAN_DET_CONFID_AZIMUTH_01_02"; +BA_ "GenSigVtName" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_02 "CAN_DET_CONFID_AZIMUTH_01_02"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_02 "CAN_DET_CONFID_AZIMUTH_01_02"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_02 "CAN_DET_SUPER_RES_TARGET_01_02"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_ND_TARGET_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_ND_TARGET_01_02 "CAN_DET_ND_TARGET_01_02"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_02 "CAN_DET_HOST_VEH_CLUTTER_01_02"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_VALID_LEVEL_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_VALID_LEVEL_01_02 "CAN_DET_VALID_LEVEL_01_02"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_AZIMUTH_01_02 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AZIMUTH_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AZIMUTH_01_02 "CAN_DET_AZIMUTH_01_02"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_01_02 "CAN_DET_RANGE_01_02"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_RANGE_RATE_01_02 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_RATE_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_RATE_01_02 "CAN_DET_RANGE_RATE_01_02"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AMPLITUDE_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AMPLITUDE_01_02 "CAN_DET_AMPLITUDE_01_02"; +BA_ "GenSigSendType" SG_ 288 CAN_SCAN_INDEX_2LSB_01_02 0; +BA_ "GenSigCmt" SG_ 288 CAN_SCAN_INDEX_2LSB_01_02 "CAN_SCAN_INDEX_2LSB_01_02"; +BA_ "GenSigVtEn" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_03 "CAN_DET_CONFID_AZIMUTH_01_03"; +BA_ "GenSigVtName" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_03 "CAN_DET_CONFID_AZIMUTH_01_03"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_03 "CAN_DET_CONFID_AZIMUTH_01_03"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_03 "CAN_DET_SUPER_RES_TARGET_01_03"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_ND_TARGET_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_ND_TARGET_01_03 "CAN_DET_ND_TARGET_01_03"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_03 "CAN_DET_HOST_VEH_CLUTTER_01_03"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_VALID_LEVEL_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_VALID_LEVEL_01_03 "CAN_DET_VALID_LEVEL_01_03"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_AZIMUTH_01_03 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AZIMUTH_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AZIMUTH_01_03 "CAN_DET_AZIMUTH_01_03"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_01_03 "CAN_DET_RANGE_01_03"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_RANGE_RATE_01_03 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_RATE_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_RATE_01_03 "CAN_DET_RANGE_RATE_01_03"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AMPLITUDE_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AMPLITUDE_01_03 "CAN_DET_AMPLITUDE_01_03"; +BA_ "GenSigSendType" SG_ 288 CAN_SCAN_INDEX_2LSB_01_03 0; +BA_ "GenSigCmt" SG_ 288 CAN_SCAN_INDEX_2LSB_01_03 "CAN_SCAN_INDEX_2LSB_01_03"; +BA_ "GenSigVtEn" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_04 "CAN_DET_CONFID_AZIMUTH_01_04"; +BA_ "GenSigVtName" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_04 "CAN_DET_CONFID_AZIMUTH_01_04"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_04 "CAN_DET_CONFID_AZIMUTH_01_04"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_04 "CAN_DET_SUPER_RES_TARGET_01_04"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_ND_TARGET_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_ND_TARGET_01_04 "CAN_DET_ND_TARGET_01_04"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_04 "CAN_DET_HOST_VEH_CLUTTER_01_04"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_VALID_LEVEL_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_VALID_LEVEL_01_04 "CAN_DET_VALID_LEVEL_01_04"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_AZIMUTH_01_04 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AZIMUTH_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AZIMUTH_01_04 "CAN_DET_AZIMUTH_01_04"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_01_04 "CAN_DET_RANGE_01_04"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_RANGE_RATE_01_04 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_RATE_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_RATE_01_04 "CAN_DET_RANGE_RATE_01_04"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AMPLITUDE_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AMPLITUDE_01_04 "CAN_DET_AMPLITUDE_01_04"; +BA_ "GenSigSendType" SG_ 288 CAN_SCAN_INDEX_2LSB_01_04 0; +BA_ "GenSigCmt" SG_ 288 CAN_SCAN_INDEX_2LSB_01_04 "CAN_SCAN_INDEX_2LSB_01_04"; +BA_ "GenSigVtEn" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_05 "CAN_DET_CONFID_AZIMUTH_01_05"; +BA_ "GenSigVtName" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_05 "CAN_DET_CONFID_AZIMUTH_01_05"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_05 "CAN_DET_CONFID_AZIMUTH_01_05"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_05 "CAN_DET_SUPER_RES_TARGET_01_05"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_ND_TARGET_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_ND_TARGET_01_05 "CAN_DET_ND_TARGET_01_05"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_05 "CAN_DET_HOST_VEH_CLUTTER_01_05"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_VALID_LEVEL_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_VALID_LEVEL_01_05 "CAN_DET_VALID_LEVEL_01_05"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_AZIMUTH_01_05 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AZIMUTH_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AZIMUTH_01_05 "CAN_DET_AZIMUTH_01_05"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_01_05 "CAN_DET_RANGE_01_05"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_RANGE_RATE_01_05 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_RATE_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_RATE_01_05 "CAN_DET_RANGE_RATE_01_05"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AMPLITUDE_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AMPLITUDE_01_05 "CAN_DET_AMPLITUDE_01_05"; +BA_ "GenSigSendType" SG_ 288 CAN_SCAN_INDEX_2LSB_01_05 0; +BA_ "GenSigCmt" SG_ 288 CAN_SCAN_INDEX_2LSB_01_05 "CAN_SCAN_INDEX_2LSB_01_05"; +BA_ "GenSigVtEn" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_06 "CAN_DET_CONFID_AZIMUTH_01_06"; +BA_ "GenSigVtName" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_06 "CAN_DET_CONFID_AZIMUTH_01_06"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_CONFID_AZIMUTH_01_06 "CAN_DET_CONFID_AZIMUTH_01_06"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_SUPER_RES_TARGET_01_06 "CAN_DET_SUPER_RES_TARGET_01_06"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_ND_TARGET_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_ND_TARGET_01_06 "CAN_DET_ND_TARGET_01_06"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_HOST_VEH_CLUTTER_01_06 "CAN_DET_HOST_VEH_CLUTTER_01_06"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_VALID_LEVEL_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_VALID_LEVEL_01_06 "CAN_DET_VALID_LEVEL_01_06"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_AZIMUTH_01_06 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AZIMUTH_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AZIMUTH_01_06 "CAN_DET_AZIMUTH_01_06"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_01_06 "CAN_DET_RANGE_01_06"; +BA_ "GenSigStartValue" SG_ 288 CAN_DET_RANGE_RATE_01_06 0; +BA_ "GenSigSendType" SG_ 288 CAN_DET_RANGE_RATE_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_RANGE_RATE_01_06 "CAN_DET_RANGE_RATE_01_06"; +BA_ "GenSigSendType" SG_ 288 CAN_DET_AMPLITUDE_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_DET_AMPLITUDE_01_06 "CAN_DET_AMPLITUDE_01_06"; +BA_ "GenSigSendType" SG_ 288 CAN_SCAN_INDEX_2LSB_01_06 0; +BA_ "GenSigCmt" SG_ 288 CAN_SCAN_INDEX_2LSB_01_06 "CAN_SCAN_INDEX_2LSB_01_06"; +BA_DEF_DEF_ "CrossOver_InfoCAN" "No"; +BA_DEF_DEF_ "CrossOver_LIN" "No"; +BA_DEF_DEF_ "UsedOnPgmDBC" "Yes"; +BA_DEF_DEF_ "ContentDependant" "No"; +BA_DEF_DEF_ "GenSigTimeoutTime_RCM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_GWM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_OCS" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_ABS_ESC" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_CCM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_IPMA" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_TSTR" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_SCCM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_PSCM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime__delete" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_Generic_BCM" 0; +BA_DEF_DEF_ "NmMessage" "No"; +BA_DEF_DEF_ "DiagResponse" "No"; +BA_DEF_DEF_ "DiagRequest" "No"; +BA_DEF_DEF_ "TpTxIndex" 0; +BA_DEF_DEF_ "DiagState" "No"; +BA_DEF_DEF_ "TpApplType" ""; +BA_DEF_DEF_ "NmAsrMessage" "No"; +BA_DEF_DEF_ "Mulitplexer" "No"; +BA_DEF_DEF_ "ConfiguredTransmitter" "No"; +BA_DEF_DEF_ "EventRateOfChange" 10000; +BA_DEF_DEF_ "GenMsgHandlingTypeDoc" ""; +BA_DEF_DEF_ "GenMsgHandlingTypeCode" ""; +BA_DEF_DEF_ "GenMsgMarked" ""; +BA_DEF_DEF_ "GenSigMarked" ""; +BA_DEF_DEF_ "GenSigVtIndex" ""; +BA_DEF_DEF_ "GenSigVtName" ""; +BA_DEF_DEF_ "GenSigVtEn" ""; +BA_DEF_DEF_ "GenSigSNA" ""; +BA_DEF_DEF_ "GenSigCmt" ""; +BA_DEF_DEF_ "GenMsgCmt" ""; +BA_DEF_DEF_ "GenSigSendType" "NoSigSendType"; +BA_DEF_DEF_ "GenSigInactiveValue" 0; +BA_DEF_DEF_ "GenSigMissingSourceValue" 0; +BA_DEF_DEF_ "WakeupSignal" "No"; +BA_DEF_DEF_ "GenSigStartValue" 0; +BA_DEF_DEF_ "GenMsgILSupport" "Yes"; +BA_DEF_DEF_ "NetworkInitializationCommand" "No"; +BA_DEF_DEF_ "GenMsgSendType" "NoMsgSendType"; +BA_DEF_DEF_ "GenMsgCycleTime" 0; +BA_DEF_DEF_ "GenMsgCycleTimeFast" 0; +BA_DEF_DEF_ "GenMsgDelayTime" 0; +BA_DEF_DEF_ "GenMsgNrOfRepetition" 0; +BA_DEF_DEF_ "GenMsgStartDelayTime" 0; +BA_DEF_DEF_ "NetworkInitialization" "No"; +BA_DEF_DEF_ "MessageGateway" "No"; +BA_DEF_DEF_ "ILUsed" "Yes"; +BA_DEF_DEF_ "NetworkInitializationUsed" "No"; +BA_DEF_DEF_ "PowerType" "Switched"; +BA_DEF_DEF_ "NodeStartUpTime" 250; +BA_DEF_DEF_ "NodeWakeUpTime" 10; +BA_DEF_DEF_ "GenMsgBackgroundColor" "#ffffff"; +BA_DEF_DEF_ "GenMsgForegroundColor" "#000000"; +VAL_ 34 IPMA_PCAN_DataRangeCheck 1 "Fault Present" 0 "No Fault"; +VAL_ 34 IPMA_PCAN_MissingMsg 1 "Fault Present" 0 "No Fault "; +VAL_ 34 VINSignalCompareFailure 1 "Fault Present" 0 "No Fault"; +VAL_ 34 ModuleNotConfiguredError 1 "Fault Present" 0 "No Fault"; +VAL_ 34 CarCfgNotConfiguredError 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte7_bit7 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte7_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte7_bit5 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte7_bit4 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ARMtoDSPChksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 DSPtoArmChksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 HostToArmChksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ARMtoHostChksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 LoopBWOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 DSPOverrunFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte6_bit5 1 "Fault Present" 0 "No Fault"; +VAL_ 33 TuningSensitivityFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 SaturatedTuningFreqFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 LocalOscPowerFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 TransmitterPowerFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte6_bit0 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte5_bit7 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte5_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 XCVRDeviceSPIFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 FreqSynthesizerSPIFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 AnalogConverterDevicSPIFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 SidelobeBlockage 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte5_bit1 1 "Fault Present" 0 "No Fault"; +VAL_ 33 MNRBlocked 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ECUTempHighFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 TransmitterTempHighFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 AlignmentRoutineFailedFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 UnreasonableRadarData 1 "Fault Present" 0 "No Fault"; +VAL_ 33 MicroprocessorTempHighFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 VerticalAlignmentOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 HorizontalAlignmentOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 FactoryAlignmentMode 1 "Fault Present" 0 "No Fault"; +VAL_ 33 BatteryLowFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 BatteryHighFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 v_1p25SupplyOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte3_bit4 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ThermistorOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 v_3p3DACSupplyOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 v_3p3RAWSupplyOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 v_5_SupplyOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 TransmitterIDFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit5 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit4 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit3 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit2 1 "Fault Present" 0 "No Fault"; +VAL_ 33 PCANMissingMsgFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 PCANBusOff 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte1_bit7 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte1_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 InstructionSetCheckFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 StackOverflowFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 WatchdogFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 PLLLockFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte1_bit1 1 "Fault Present" 0 "No Fault"; +VAL_ 33 RAMMemoryTestFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 USCValidationFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte0_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte0_bit5 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte0_bit4 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte0_bit3 1 "Fault Present" 0 "No Fault"; +VAL_ 33 KeepAliveChecksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ProgramCalibrationFlashChecksum 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ApplicationFlashChecksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 371 CAN_AUTO_ALIGN_HANGLE_QF 3 "Accurate" 2 "Inaccurate" 1 "Temporarily undefined" 0 "Undefined"; +VAL_ 371 CAN_ALIGNMENT_STATUS 15 "Undefined_2" 14 "Undefined_1" 13 "Low Amplitude (Flat-plate only)" 12 "No Peak (Flat-plate only)" 11 "Fail Ver and Hor OutOfRange" 10 "Fail Vertical Align OutOfRange" 9 "Fail Horizontal Align OutOfRange" 8 "Fail Time Out" 7 "Fail Only Right Target Found" 6 "Fail Only Left Target Found" 5 "Fail Variance Too Large" 4 "Fail Deviation Too Large" 3 "Fail No Target" 2 "Success" 1 "Busy" 0 "Off"; +VAL_ 371 CAN_ALIGNMENT_STATE 6 "Static alignment flat-plate" 5 "Static alignment 2-target" 4 "Static alignment 1-target" 3 "Service alignment" 2 "Short track alignment" 1 "Auto alignment" 0 "Off"; +VAL_ 291 CAN_DET_CONFID_AZIMUTH_04_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 291 CAN_DET_CONFID_AZIMUTH_04_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 291 CAN_DET_CONFID_AZIMUTH_04_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 291 CAN_DET_CONFID_AZIMUTH_04_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 291 CAN_DET_CONFID_AZIMUTH_04_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 291 CAN_DET_CONFID_AZIMUTH_04_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 351 CAN_DET_CONFID_AZIMUTH_64 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 350 CAN_DET_CONFID_AZIMUTH_63 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 349 CAN_DET_CONFID_AZIMUTH_62 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 348 CAN_DET_CONFID_AZIMUTH_61 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 347 CAN_DET_CONFID_AZIMUTH_60 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 346 CAN_DET_CONFID_AZIMUTH_59 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 345 CAN_DET_CONFID_AZIMUTH_58 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 344 CAN_DET_CONFID_AZIMUTH_57 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 343 CAN_DET_CONFID_AZIMUTH_56 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 342 CAN_DET_CONFID_AZIMUTH_55 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 335 CAN_DET_CONFID_AZIMUTH_48 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 334 CAN_DET_CONFID_AZIMUTH_47 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 333 CAN_DET_CONFID_AZIMUTH_46 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 332 CAN_DET_CONFID_AZIMUTH_45 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 331 CAN_DET_CONFID_AZIMUTH_44 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 330 CAN_DET_CONFID_AZIMUTH_43 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 329 CAN_DET_CONFID_AZIMUTH_42 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 328 CAN_DET_CONFID_AZIMUTH_41 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 327 CAN_DET_CONFID_AZIMUTH_40 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 325 CAN_DET_CONFID_AZIMUTH_38 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 324 CAN_DET_CONFID_AZIMUTH_37 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 323 CAN_DET_CONFID_AZIMUTH_36 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 322 CAN_DET_CONFID_AZIMUTH_35 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 321 CAN_DET_CONFID_AZIMUTH_34 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 320 CAN_DET_CONFID_AZIMUTH_33 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 319 CAN_DET_CONFID_AZIMUTH_32 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 318 CAN_DET_CONFID_AZIMUTH_31 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 317 CAN_DET_CONFID_AZIMUTH_30 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 316 CAN_DET_CONFID_AZIMUTH_29 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 314 CAN_DET_CONFID_AZIMUTH_27 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 313 CAN_DET_CONFID_AZIMUTH_26 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 312 CAN_DET_CONFID_AZIMUTH_25 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 311 CAN_DET_CONFID_AZIMUTH_24 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 310 CAN_DET_CONFID_AZIMUTH_23 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 309 CAN_DET_CONFID_AZIMUTH_22_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 309 CAN_DET_CONFID_AZIMUTH_22_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 309 CAN_DET_CONFID_AZIMUTH_22_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 308 CAN_DET_CONFID_AZIMUTH_21_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 308 CAN_DET_CONFID_AZIMUTH_21_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 308 CAN_DET_CONFID_AZIMUTH_21_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 308 CAN_DET_CONFID_AZIMUTH_21_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 308 CAN_DET_CONFID_AZIMUTH_21_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 308 CAN_DET_CONFID_AZIMUTH_21_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 307 CAN_DET_CONFID_AZIMUTH_20_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 307 CAN_DET_CONFID_AZIMUTH_20_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 307 CAN_DET_CONFID_AZIMUTH_20_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 307 CAN_DET_CONFID_AZIMUTH_20_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 307 CAN_DET_CONFID_AZIMUTH_20_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 307 CAN_DET_CONFID_AZIMUTH_20_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 306 CAN_DET_CONFID_AZIMUTH_19_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 306 CAN_DET_CONFID_AZIMUTH_19_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 306 CAN_DET_CONFID_AZIMUTH_19_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 306 CAN_DET_CONFID_AZIMUTH_19_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 306 CAN_DET_CONFID_AZIMUTH_19_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 306 CAN_DET_CONFID_AZIMUTH_19_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 305 CAN_DET_CONFID_AZIMUTH_18_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 305 CAN_DET_CONFID_AZIMUTH_18_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 305 CAN_DET_CONFID_AZIMUTH_18_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 305 CAN_DET_CONFID_AZIMUTH_18_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 305 CAN_DET_CONFID_AZIMUTH_18_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 305 CAN_DET_CONFID_AZIMUTH_18_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 341 CAN_DET_CONFID_AZIMUTH_54 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 340 CAN_DET_CONFID_AZIMUTH_53 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 339 CAN_DET_CONFID_AZIMUTH_52 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 338 CAN_DET_CONFID_AZIMUTH_51 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 337 CAN_DET_CONFID_AZIMUTH_50 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 336 CAN_DET_CONFID_AZIMUTH_49 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 326 CAN_DET_CONFID_AZIMUTH_39 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 315 CAN_DET_CONFID_AZIMUTH_28 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 304 CAN_DET_CONFID_AZIMUTH_17_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 304 CAN_DET_CONFID_AZIMUTH_17_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 304 CAN_DET_CONFID_AZIMUTH_17_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 304 CAN_DET_CONFID_AZIMUTH_17_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 304 CAN_DET_CONFID_AZIMUTH_17_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 304 CAN_DET_CONFID_AZIMUTH_17_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 303 CAN_DET_CONFID_AZIMUTH_16_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 303 CAN_DET_CONFID_AZIMUTH_16_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 303 CAN_DET_CONFID_AZIMUTH_16_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 303 CAN_DET_CONFID_AZIMUTH_16_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 303 CAN_DET_CONFID_AZIMUTH_16_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 303 CAN_DET_CONFID_AZIMUTH_16_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 302 CAN_DET_CONFID_AZIMUTH_15_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 302 CAN_DET_CONFID_AZIMUTH_15_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 302 CAN_DET_CONFID_AZIMUTH_15_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 302 CAN_DET_CONFID_AZIMUTH_15_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 302 CAN_DET_CONFID_AZIMUTH_15_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 302 CAN_DET_CONFID_AZIMUTH_15_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 301 CAN_DET_CONFID_AZIMUTH_14_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 301 CAN_DET_CONFID_AZIMUTH_14_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 301 CAN_DET_CONFID_AZIMUTH_14_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 301 CAN_DET_CONFID_AZIMUTH_14_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 301 CAN_DET_CONFID_AZIMUTH_14_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 301 CAN_DET_CONFID_AZIMUTH_14_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 300 CAN_DET_CONFID_AZIMUTH_13_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 300 CAN_DET_CONFID_AZIMUTH_13_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 300 CAN_DET_CONFID_AZIMUTH_13_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 300 CAN_DET_CONFID_AZIMUTH_13_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 300 CAN_DET_CONFID_AZIMUTH_13_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 300 CAN_DET_CONFID_AZIMUTH_13_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 299 CAN_DET_CONFID_AZIMUTH_12_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 299 CAN_DET_CONFID_AZIMUTH_12_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 299 CAN_DET_CONFID_AZIMUTH_12_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 299 CAN_DET_CONFID_AZIMUTH_12_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 299 CAN_DET_CONFID_AZIMUTH_12_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 299 CAN_DET_CONFID_AZIMUTH_12_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 298 CAN_DET_CONFID_AZIMUTH_11_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 298 CAN_DET_CONFID_AZIMUTH_11_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 298 CAN_DET_CONFID_AZIMUTH_11_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 298 CAN_DET_CONFID_AZIMUTH_11_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 298 CAN_DET_CONFID_AZIMUTH_11_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 298 CAN_DET_CONFID_AZIMUTH_11_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 297 CAN_DET_CONFID_AZIMUTH_10_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 297 CAN_DET_CONFID_AZIMUTH_10_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 297 CAN_DET_CONFID_AZIMUTH_10_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 297 CAN_DET_CONFID_AZIMUTH_10_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 297 CAN_DET_CONFID_AZIMUTH_10_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 297 CAN_DET_CONFID_AZIMUTH_10_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 296 CAN_DET_CONFID_AZIMUTH_09_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 296 CAN_DET_CONFID_AZIMUTH_09_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 296 CAN_DET_CONFID_AZIMUTH_09_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 296 CAN_DET_CONFID_AZIMUTH_09_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 296 CAN_DET_CONFID_AZIMUTH_09_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 296 CAN_DET_CONFID_AZIMUTH_09_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 295 CAN_DET_CONFID_AZIMUTH_08_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 295 CAN_DET_CONFID_AZIMUTH_08_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 295 CAN_DET_CONFID_AZIMUTH_08_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 295 CAN_DET_CONFID_AZIMUTH_08_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 295 CAN_DET_CONFID_AZIMUTH_08_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 295 CAN_DET_CONFID_AZIMUTH_08_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 294 CAN_DET_CONFID_AZIMUTH_07_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 294 CAN_DET_CONFID_AZIMUTH_07_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 294 CAN_DET_CONFID_AZIMUTH_07_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 294 CAN_DET_CONFID_AZIMUTH_07_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 294 CAN_DET_CONFID_AZIMUTH_07_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 294 CAN_DET_CONFID_AZIMUTH_07_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 293 CAN_DET_CONFID_AZIMUTH_06_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 293 CAN_DET_CONFID_AZIMUTH_06_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 293 CAN_DET_CONFID_AZIMUTH_06_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 293 CAN_DET_CONFID_AZIMUTH_06_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 293 CAN_DET_CONFID_AZIMUTH_06_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 293 CAN_DET_CONFID_AZIMUTH_06_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 292 CAN_DET_CONFID_AZIMUTH_05_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 292 CAN_DET_CONFID_AZIMUTH_05_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 292 CAN_DET_CONFID_AZIMUTH_05_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 292 CAN_DET_CONFID_AZIMUTH_05_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 292 CAN_DET_CONFID_AZIMUTH_05_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 292 CAN_DET_CONFID_AZIMUTH_05_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 290 CAN_DET_CONFID_AZIMUTH_03_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 290 CAN_DET_CONFID_AZIMUTH_03_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 290 CAN_DET_CONFID_AZIMUTH_03_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 290 CAN_DET_CONFID_AZIMUTH_03_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 290 CAN_DET_CONFID_AZIMUTH_03_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 290 CAN_DET_CONFID_AZIMUTH_03_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 289 CAN_DET_CONFID_AZIMUTH_02_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 289 CAN_DET_CONFID_AZIMUTH_02_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 289 CAN_DET_CONFID_AZIMUTH_02_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 289 CAN_DET_CONFID_AZIMUTH_02_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 289 CAN_DET_CONFID_AZIMUTH_02_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 289 CAN_DET_CONFID_AZIMUTH_02_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 257 CAN_INTERFERENCE_TYPE 2 "Star PD-Like" 1 "Slow FMCW" 0 "No Interference"; +VAL_ 257 CAN_RECOMMEND_UNCONVERGE 1 "Recommended" 0 "Not Recommended"; +VAL_ 257 CAN_RADAR_ALIGN_INCOMPLETE 1 "Alignment Incomplete" 0 "Alignment Completed"; +VAL_ 257 CAN_BLOCKAGE_SIDELOBE 1 "Radar Blockage" 0 "No Radar Blockage"; +VAL_ 257 CAN_BLOCKAGE_MNR 1 "Radar Blockage" 0 "No Radar Blockage"; +VAL_ 257 CAN_RADAR_EXT_COND_NOK 1 "Too high temp or insufficient pw" 0 "External conditions OK"; +VAL_ 257 CAN_RADAR_ALIGN_OUT_RANGE 1 "Radar out of range" 0 "Radar within range"; +VAL_ 257 CAN_RADAR_ALIGN_NOT_START 1 "Radar align not started" 0 "Radar align started"; +VAL_ 257 CAN_RADAR_OVERHEAT_ERROR 1 "Radar overheat condition" 0 "No Overheat"; +VAL_ 257 CAN_RADAR_NOT_OP 1 "Radar not operational" 0 "Radar operational"; +VAL_ 257 CAN_XCVR_OPERATIONAL 1 "On" 0 "Off "; +VAL_ 288 CAN_DET_CONFID_AZIMUTH_01_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 288 CAN_DET_CONFID_AZIMUTH_01_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 288 CAN_DET_CONFID_AZIMUTH_01_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 288 CAN_DET_CONFID_AZIMUTH_01_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 288 CAN_DET_CONFID_AZIMUTH_01_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 288 CAN_DET_CONFID_AZIMUTH_01_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; diff --git a/opendbc/README.md b/opendbc_repo/opendbc/dbc/README.md similarity index 100% rename from opendbc/README.md rename to opendbc_repo/opendbc/dbc/README.md diff --git a/opendbc_repo/opendbc/dbc/__init__.py b/opendbc_repo/opendbc/dbc/__init__.py new file mode 100644 index 000000000000000..e69de29bb2d1d64 diff --git a/opendbc/acura_ilx_2016_can_generated.dbc b/opendbc_repo/opendbc/dbc/acura_ilx_2016_can_generated.dbc similarity index 94% rename from opendbc/acura_ilx_2016_can_generated.dbc rename to opendbc_repo/opendbc/dbc/acura_ilx_2016_can_generated.dbc index 24c8f678926565e..191ec849335ece9 100644 --- a/opendbc/acura_ilx_2016_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/acura_ilx_2016_can_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc/acura_ilx_2016_nidec.dbc b/opendbc_repo/opendbc/dbc/acura_ilx_2016_nidec.dbc similarity index 100% rename from opendbc/acura_ilx_2016_nidec.dbc rename to opendbc_repo/opendbc/dbc/acura_ilx_2016_nidec.dbc diff --git a/opendbc/acura_rdx_2018_can_generated.dbc b/opendbc_repo/opendbc/dbc/acura_rdx_2018_can_generated.dbc similarity index 94% rename from opendbc/acura_rdx_2018_can_generated.dbc rename to opendbc_repo/opendbc/dbc/acura_rdx_2018_can_generated.dbc index 4c23725176e469b..3c034413cf96aaf 100644 --- a/opendbc/acura_rdx_2018_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/acura_rdx_2018_can_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc/acura_rdx_2020_can_generated.dbc b/opendbc_repo/opendbc/dbc/acura_rdx_2020_can_generated.dbc similarity index 97% rename from opendbc/acura_rdx_2020_can_generated.dbc rename to opendbc_repo/opendbc/dbc/acura_rdx_2020_can_generated.dbc index c6149921dc3c5b2..7a225aa5993e983 100644 --- a/opendbc/acura_rdx_2020_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/acura_rdx_2020_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX BO_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; 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_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc_repo/opendbc/dbc/bmw_e9x_e8x.dbc b/opendbc_repo/opendbc/dbc/bmw_e9x_e8x.dbc new file mode 100644 index 000000000000000..7ec95c0b19f9dc0 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/bmw_e9x_e8x.dbc @@ -0,0 +1,913 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: EON XXX RDC SZL VGSG JBBF RFK FLA RAD1 CAS CID AHM HKL HUD EKP DWA DSC SM_BF GWS VDM DDE1 ACI CCC DSC SM_FA CTM LDM RSE MRSZ VDA EDCK ZBE EGS ACC_Sensor Kombi IHKA ARS ACSM FZD PGS NVC AFS DME FRMFA EMF FKA VSW EPS PDC DKG EHC Diagnosetool_PT_CAN Diagnosetool_K_CAN_System Vector__XXX + + +BO_ 170 AccPedal: 8 DME + SG_ KickDownPressed : 53|1@0+ (1,0) [0|3] "" XXX + SG_ CruisePedalActive : 54|1@0+ (1,0) [0|1] "" XXX + SG_ CruisePedalInactive : 55|1@0+ (1,0) [0|1] "" XXX + SG_ ThrottlelPressed : 50|1@0+ (1,0) [0|1] "" XXX + SG_ AcceleratorPedalPressed : 52|1@0+ (1,0) [0|7] "" XXX + SG_ AcceleratorPedalPercentage : 16|16@1+ (0.04,0) [0|100] "" XXX + SG_ Counter_170 : 8|4@1+ (1,0) [0|15] "" XXX + SG_ EngineSpeed : 32|16@1+ (0.25,0) [0|8000] "rpm" XXX + SG_ Checksum_170 : 0|8@1- (1,0) [0|65535] "" XXX + +BO_ 404 CruiseControl: 4 SZL + SG_ plus1mph_request : 16|1@0+ (1,0) [0|1] "" XXX + SG_ minus1mph_request : 18|1@0+ (1,0) [0|1] "" XXX + SG_ Cancel_request_up_stalk : 23|1@0+ (1,0) [0|1] "" XXX + SG_ Cancel_request_up_or_down_stalk : 20|1@0+ (1,0) [0|1] "" XXX + SG_ Resume_request : 22|1@0+ (1,0) [0|1] "" XXX + SG_ setMe_0xFC : 31|8@0+ (1,0) [0|255] "" XXX + SG_ plus5mph_request : 17|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ minus5mph_request : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ requests_0xF : 15|4@0+ (1,0) [0|15] "" XXX + SG_ Counter_404 : 11|4@0+ (1,0) [0|15] "" XXX + SG_ Checksum_404 : 7|8@0+ (1,0) [0|15] "" XXX + +BO_ 512 CruiseControlStatus: 8 DME + SG_ CruiseControlInactiveFlag : 12|1@0+ (1,0) [0|1] "" XXX + SG_ CruiseCoontrolActiveFlag : 13|1@0+ (1,0) [0|1] "" XXX + SG_ CruiseControlSetpointSpeed : 7|8@0+ (0.25,0) [0|255] "mph" XXX + +BO_ 168 EngineAndBrake: 8 DME + SG_ Checksum_EngineAndBrake : 0|8@1+ (1,0) [0|0] "" XXX + SG_ BrakePressed : 61|1@0+ (1,0) [0|1] "" XXX + SG_ Brake_active2 : 62|1@0+ (1,0) [0|1] "" XXX + SG_ ST_RCPT_ENG_DSC : 52|2@1+ (1,0) [0|0] "" XXX + SG_ ST_RCPT_ENG_ARS : 50|2@1+ (1,0) [0|0] "" XXX + SG_ ST_RCPT_ENG_ACC : 48|2@1+ (1,0) [0|0] "" XXX + SG_ ST_RCPT_ENG_EGS : 54|2@1+ (1,0) [0|0] "" XXX + SG_ ST_DMEA_SWO : 44|2@1+ (1,0) [0|0] "" XXX + SG_ EngineTorque : 12|12@1- (0.03125,0) [-1024|1023] "" XXX + SG_ ALIV_TORQ_1_DME : 8|4@1+ (1,0) [0|15] "" XXX + SG_ EngineTorqueWoInterv : 24|16@1- (0.03125,0) [-1024|1023.96875] "" XXX + +BO_ 470 SteeringButtons: 2 SZL + SG_ Volume_DOWN : 2|1@0+ (1,0) [0|1] "" XXX + SG_ Volume_UP : 3|1@0+ (1,0) [0|1] "" XXX + SG_ VoiceControl : 8|1@0+ (1,0) [0|1] "" XXX + SG_ Telephone : 0|1@0+ (1,0) [0|1] "" XXX + SG_ Next_up : 5|1@0+ (1,0) [0|1] "" XXX + SG_ Previous_down : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 403 DynamicCruiseControlStatus: 8 DSC + SG_ Counter_403 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ CruiseActive : 43|1@0+ (1,0) [0|1] "" XXX + SG_ CruiseSpeedChangeRequest : 48|1@0+ (1,0) [0|1] "" XXX + SG_ CruiseControlSetpointSpeed : 15|8@0+ (1,-2) [0|255] "kph/mph" XXX + +BO_ 201 SteeringWheelAngle_DSC: 8 SZL + SG_ Counter_201 : 20|4@1+ (1,0) [0|15] "" DSC + SG_ SteeringPositionComplementLow : 24|11@1- (1,0) [0|1] "" DSC + SG_ SteeringPosition : 0|16@1- (0.0428316886,0) [-600|600] "deg" DSC + +BO_ 206 WheelSpeeds: 8 DSC + SG_ Wheel_FL : 0|16@1- (0.0625,0) [0|255] "kph" XXX + SG_ Wheel_FR : 16|16@1- (0.0625,0) [0|255] "kph" XXX + SG_ Wheel_RL : 32|16@1- (0.0625,0) [0|255] "kph" XXX + SG_ Wheel_RR : 48|16@1- (0.0625,0) [0|255] "kph" XXX + +BO_ 884 WheelToleranceAdjustment: 8 DSC + +BO_ 678 WiperSwitch: 8 SZL + SG_ AutoWipersOn : 0|1@1+ (1,0) [0|3] "" XXX + +BO_ 304 TerminalStatus: 8 CAS + SG_ AccOn : 23|1@1+ (1,0) [0|255] "" XXX + SG_ IgnitionOff : 22|1@1+ (1,0) [0|3] "" XXX + SG_ Counter_304 : 32|4@1+ (1,0) [0|15] "" XXX + SG_ Checksum_304 : 36|4@1+ (1,0) [0|255] "" XXX + +BO_ 169 Torque2: 8 DME + SG_ TORQ_AVL_SPAR_POS : 52|12@1- (0.5,0) [-1023.5|1023.5] "Nm" XXX + SG_ TORQ_AVL_SPAR_NEG : 40|12@1- (0.5,0) [-1023.5|1023.5] "Nm" XXX + SG_ TORQ_AVL_MAX : 28|12@1- (0.5,0) [-1023.5|1023.5] "Nm" XXX + SG_ TORQ_AVL_MIN : 16|12@1- (0.5,0) [-1023.5|1023.5] "Nm" XXX + SG_ ST_INFS : 14|2@1+ (1,0) [0|0] "" XXX + SG_ ST_SW_LEV_RPM : 12|2@1+ (1,0) [0|0] "" XXX + SG_ ALIV_TORQ_2_DME : 8|4@1+ (1,0) [0|0] "" XXX + SG_ CHKSM_TORQ_2_DME : 0|8@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 184 TorqueTransmisionRequest: 8 LDM + SG_ Checksum_184 : 0|8@1+ (1,0) [0|15] "" XXX + SG_ Counter_184 : 8|4@1+ (1,0) [0|15] "" XXX + +BO_ 196 SteeringWheelAngle: 7 DSC + SG_ SteeringSpeed : 24|16@1- (0.0428316886,0) [0|255] "degree/s" XXX + SG_ SteeringPosition : 0|16@1- (0.0428316886,0) [-600|600] "degree" XXX + +BO_ 180 WheelTorqueDriveTrain1: 8 DME + +BO_ 182 DynamicCruiseControlTorqueDemand: 8 DSC + SG_ TORQ_TAR_DSC : 12|12@1- (0.5,0) [0|1000] "" XXX + SG_ Counter_182 : 8|4@1+ (1,0) [0|14] "" XXX + SG_ Checksum_182 : 0|8@1+ (1,0) [0|15] "" XXX + +BO_ 186 TransmissionData: 8 EGS + SG_ Counter_186 : 48|4@1+ (1,0) [0|14] "" XXX + SG_ Shifting : 4|1@1+ (1,0) [0|15] "" XXX + SG_ OutputShaftSpeed : 24|16@1- (0.125,0) [0|255] "rpm" XXX + SG_ GearRatio : 8|8@1+ (0.05,0) [0|255] "" XXX + SG_ GearTar : 0|4@1+ (1,-4) [0|255] "" XXX + SG_ Checksum_186 : 40|8@1+ (1,0) [0|15] "" XXX + +BO_ 191 RequestedWheelTorqueDriveTrain: 8 LDM + SG_ Checksum_191 : 0|8@1+ (1,0) [0|19] "" XXX + SG_ Counter_191 : 8|4@1- (1,0) [0|255] "" XXX + SG_ TorqueReq : 16|12@1- (0.5,350) [-1024|1023.96875] "" XXX + +BO_ 414 StatusDSC_KCAN: 8 DSC + SG_ BrakePressure : 48|8@1- (1,0) [0|255] "" XXX + SG_ BrakeStates : 40|8@1+ (1,0) [0|255] "" XXX + SG_ Checksum_414 : 56|8@1+ (1,0) [0|15] "" XXX + SG_ Counter_414 : 20|4@1+ (1,0) [0|15] "" XXX + SG_ DTC_on : 12|1@1+ (1,0) [0|3] "" XXX + SG_ DSC_full_off : 8|4@1+ (1,0) [0|15] "" XXX + +BO_ 416 Speed: 8 DSC + SG_ AccX : 28|12@1- (1,0) [0|15] "" XXX + SG_ YawRate : 40|12@1- (1,0) [0|255] "" XXX + SG_ VehicleSpeed : 0|12@1- (0.103,0) [0|255] "kph" XXX + SG_ MovingReverse : 13|1@1+ (1,0) [0|3] "" XXX + SG_ AccY : 16|12@1- (1,0) [0|255] "" XXX + SG_ Counter_416 : 52|4@1+ (1,0) [0|14] "" XXX + SG_ Checksum_416 : 56|8@1+ (1,0) [0|15] "" XXX + SG_ MovingForward : 12|1@1+ (1,0) [0|15] "" XXX + +BO_ 418 TransimissionData2: 8 EGS + SG_ ManualMode : 50|1@0+ (1,0) [0|255] "" XXX + SG_ Counter_418 : 28|4@1+ (1,0) [0|14] "" XXX + SG_ Checksum_418 : 56|8@1+ (1,0) [0|15] "" XXX + +BO_ 690 WheelPressure_KCAN: 8 DSC + +BO_ 691 AccelerationData: 8 DSC + +BO_ 402 GearSelectorSwitch_1: 4 XXX + SG_ Counter_402 : 24|4@1+ (1,0) [0|14] "" XXX + +BO_ 408 GearSelectorSwitch: 8 GWS + SG_ ParkButtonSecond : 26|2@1+ (1,0) [0|3] "" XXX + SG_ SideButton : 28|2@1+ (1,0) [0|3] "" XXX + SG_ SportButtonPressed : 34|2@1+ (1,0) [0|255] "" XXX + SG_ M3_button : 36|2@1+ (1,0) [0|3] "" XXX + SG_ SideButtonXOR11 : 30|2@1+ (1,0) [0|3] "" XXX + SG_ param1XOR11 : 22|2@1+ (1,0) [0|3] "" XXX + SG_ m3ShifterPositionXOR1111 : 8|4@1+ (1,0) [0|15] "" XXX + SG_ always11 : 38|2@1+ (1,0) [0|3] "" XXX + SG_ m3ShifterPosition : 4|4@1+ (1,0) [0|15] "" XXX + SG_ param1 : 20|2@1+ (1,0) [0|3] "" XXX + SG_ param5 : 32|2@1+ (1,0) [0|3] "" XXX + SG_ Counter_408 : 0|4@1+ (1,0) [0|14] "" XXX + SG_ ParkButtonFirst : 24|2@1+ (1,0) [0|3] "" XXX + SG_ ShifterPositionXOR1111 : 16|4@1+ (1,0) [0|15] "" XXX + SG_ ShifterPosition : 12|4@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 422 DistanceRoute: 8 DSC + +BO_ 436 InstrumentClusterStatus_KOMBI: 8 CCC + SG_ HandbrakeActive : 41|1@1+ (1,0) [0|3] "" XXX + +BO_ 464 EngineData: 8 DME + SG_ RPM_IDLG_TAR : 56|8@1+ (5,0) [0|1270] "1/min" XXX + SG_ CTR_SLCK : 48|2@1+ (1,0) [0|0] "" XXX + SG_ IJV_FU : 32|16@1+ (1,-48) [0|0] "C" XXX + SG_ AIP_ENG : 24|8@1+ (2,598) [600|1106] "hPa" XXX + SG_ ST_SW_WAUP : 22|2@1+ (1,0) [0|0] "" XXX + SG_ ST_ENG_RUN : 20|2@1+ (1,0) [0|0] "" XXX + SG_ Counter_464 : 16|4@1+ (1,0) [0|14] "" XXX + SG_ TEMP_EOI : 8|8@1+ (1,-48) [0|0] "C" XXX + SG_ TEMP_ENG : 0|8@1+ (1,-48) [0|0] "C" XXX + +BO_ 945 TransmissionData3: 8 DKG + SG_ Checksum_946 : 0|8@1+ (1,0) [0|19] "" XXX + SG_ Counter_945 : 8|4@1+ (1,0) [0|14] "" XXX + +BO_ 200 SteeringWheelAngle_slow: 6 SZL + SG_ SteeringPosition : 0|16@1- (0.0428316886,0) [-600|600] "degree" XXX + SG_ SteeringSpeed : 24|16@1- (0.0428316886,0) [-65535|65535] "degree/s" XXX + SG_ Counter_200 : 20|4@1+ (1,0) [0|15] "" XXX + +BO_ 466 TransmissionDataDisplay: 8 EGS + SG_ ShiftLeverMode : 32|2@1+ (1,0) [0|3] "" XXX + SG_ GearAct : 12|4@1+ (1,-4) [0|15] "" XXX + SG_ Counter_466 : 28|4@1+ (1,0) [0|14] "" XXX + SG_ ShiftLeverPosition : 0|4@1+ (1,0) [0|8] "" XXX + SG_ xFF : 40|8@1+ (1,0) [0|255] "" XXX + SG_ ShiftLeverPositionXOR : 4|4@1+ (1,0) [0|0] "" Vector__XXX + SG_ SportButtonState : 26|1@1+ (1,0) [0|1] "" XXX + +BO_ 437 HeatFlow_LoadTorqueClimate: 8 IHKA + +BO_ 1152 NetworkManagment1: 8 XXX + +BO_ 1170 NetworkManagment2: 8 XXX + +BO_ 1175 NetworkManagment3: 8 XXX + +BO_ 1176 NetworkManagment4: 8 XXX + +BO_ 1193 NetworkManagment5: 8 XXX + +BO_ 1246 GWS_ShiftLeverHeartbeat: 8 XXX + SG_ IgnOff : 12|1@0+ (1,0) [0|3] "" XXX + +BO_ 438 HeatFlowEngine: 8 DME + +BO_ 784 AmbientTemperature_RelativeTime: 8 Kombi + +BO_ 821 ElectricFuelPumpStatus: 8 EKP + +BO_ 1007 EngineOBD_data: 8 DME + +BO_ 1432 ServicesDKG: 8 XXX + +BO_ 309 CrashDisconnectControl: 8 ACSM + +BO_ 502 TurnSignals: 2 FRMFA + SG_ TurnSignalIdle : 9|1@0+ (1,0) [0|1] "" XXX + SG_ TurnSignalActive : 8|1@0+ (1,0) [0|1] "" XXX + SG_ RightTurn : 5|1@0+ (1,0) [0|1] "" XXX + SG_ LeftTurn : 4|1@1+ (1,0) [0|1] "" XXX + SG_ HoldActivated : 0|1@1+ (1,0) [0|1] "" XXX + +BO_ 514 Dimming: 8 FRMFA + +BO_ 538 LampStatus: 8 FRMFA + +BO_ 550 RainSensorWiperSpeed: 8 FZD + +BO_ 578 ClimateFrontStatus: 8 IHKA + +BO_ 704 LCD_lighting: 8 Kombi + +BO_ 758 LightControl: 8 FRMFA + +BO_ 760 Time_Date: 8 Kombi + +BO_ 762 OccupancySeatBeltContact: 8 ACSM + SG_ NEW_SIGNAL_1 : 8|8@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 0|8@1+ (1,0) [0|15] "" XXX + +BO_ 764 TrunkStatus: 8 CAS + +BO_ 797 TirePressureStatus: 8 DSC + +BO_ 816 Range_Mileage: 8 Kombi + +BO_ 823 StatusFuelControl: 8 DME + +BO_ 897 EngineOilLevel: 8 DME + +BO_ 940 RunOnTimeTerminal30: 8 JBBF + +BO_ 947 PowerManagmentConsumptionControl: 8 DME + +BO_ 948 PowerBatteryVoltage: 8 DME + SG_ BatteryVoltage : 7|24@0+ (0.001,0) [0|65535] "" XXX + +BO_ 958 PowerRunningTime: 8 CAS + +BO_ 1408 ServicesKGM: 8 XXX + +BO_ 1426 ServicesDME: 8 XXX + +BO_ 1449 ServicesDSC: 8 XXX + +BO_ 1504 ServicesKOMBI: 8 XXX + +BO_ 1522 ServicesKBM: 8 XXX + +BO_ 209 Accelerometer1: 8 XXX + SG_ Counter_209 : 52|4@1+ (1,0) [0|255] "" XXX + SG_ Unknown : 16|16@1- (1,0) [0|65535] "" XXX + SG_ YawRate : 0|16@1- (1,0) [0|7] "" XXX + SG_ PitchRate : 32|16@1- (1,0) [0|65535] "" XXX + SG_ CRC8_209 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 172 WheelTorqueDrivetrain2: 8 DME + +BO_ 128 SYNC: 5 XXX + SG_ State2 : 24|4@1+ (1,0) [0|15] "" XXX + SG_ State1 : 16|8@1+ (1,0) [0|255] "" XXX + SG_ Counter_128 : 28|4@1+ (1,0) [0|15] "" XXX + +BO_ 320 Unknown140: 2 XXX + SG_ State : 7|8@0+ (1,0) [0|255] "" XXX + +BO_ 212 Unknown_d4: 8 XXX + SG_ State1 : 40|8@1+ (1,0) [0|255] "" XXX + SG_ Counter_212 : 52|4@1+ (1,0) [0|255] "" XXX + SG_ Checksum_212 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 205 Accelerometer2: 8 XXX + SG_ Counter_205 : 52|4@1+ (1,0) [0|255] "" XXX + SG_ LateralAcceleration : 32|16@1- (1,0) [0|255] "" XXX + SG_ YawRate : 0|16@1- (1,0) [0|255] "" XXX + SG_ CRC8_205 : 16|16@1- (1,0) [0|65535] "" XXX + +BO_ 790 OperationPushButtonDTC: 2 JBBF + SG_ setMe_0x3FFF : 2|14@1+ (1,0) [0|63] "" DSC + SG_ DTC_pressed : 0|1@1+ (1,0) [0|3] "" DSC + +BO_ 1577 Unknown_629: 8 XXX + +BO_ 133 Synchronization_SC_VDA: 8 DSC + +BO_ 173 Delay_request_ACC: 8 LDM + +BO_ 177 Torque_request_steering: 8 DSC + +BO_ 181 Torque_request_EGS: 8 EGS + SG_ Checksum_Torque_request_EGS : 0|8@1+ (1,0) [0|0] "" XXX + SG_ Gearbox_temperature : 56|8@1+ (1,0) [0|0] "C" XXX + +BO_ 183 Torque_request_ACC: 8 LDM + +BO_ 187 Target_torque_request: 8 DSC + +BO_ 188 Status_target_torque_conversion: 8 VGSG + +BO_ 190 Alive_Counter: 8 ARS + +BO_ 192 Alive_Central_Gateway: 8 JBBF + +BO_ 193 Alive_counter_telephone: 8 CCC + +BO_ 213 Request_wheel_torque_brake: 8 DSC + +BO_ 215 Alive_Counter_Security: 8 ACSM + +BO_ 216 CLU1_VDA: 8 VDA + +BO_ 225 Wheel_torque_brake: 8 DSC + +BO_ 226 Status_central_locking_BFT: 8 JBBF + +BO_ 227 CLU2_VDA: 8 VDA + +BO_ 230 Status_central_locking_BFTH: 8 JBBF + +BO_ 234 Status_central_locking_FAT: 8 JBBF + +BO_ 238 Central_locking_status_FATH: 8 JBBF + +BO_ 242 Status_central_locking_HK: 8 JBBF + +BO_ 244 CLU3_VDA: 8 VDA + +BO_ 247 lateral_dynamics_ARS_VDM: 8 ARS + +BO_ 249 Vertical_dynamics_VDM_ARS: 8 VDM + +BO_ 250 Control_window_lifter_FAT: 8 FRMFA + +BO_ 251 Control_window_lifter_BFT: 8 JBBF + +BO_ 252 Control_window_lifter_FATH: 8 JBBF + +BO_ 253 Control_window_lifter_BFTH: 8 JBBF + +BO_ 254 Voltage_level_sensors: 8 VDM + +BO_ 280 Exchange_AFS_DSC: 8 AFS + +BO_ 286 Control_interventions_DSC_AFS: 8 DSC + +BO_ 288 Status_partial_setpoints_AFS_DSC_2: 8 AFS + +BO_ 298 Sensor_data_ROSE: 8 ASCM + +BO_ 300 input_data_ROSE: 8 DSC + +BO_ 336 Request_1_ACC: 8 LDM + +BO_ 339 Request_2_ACC: 8 LDM + +BO_ 345 Object_data_ACC: 8 ACC_Sensor + +BO_ 348 Status_ACC: 8 ACC_Sensor + +BO_ 351 Requirement_angle_FFP: 8 LDM + +BO_ 357 CLU_Status_VDA: 8 VDA + +BO_ 370 Acknowledgment_request_Kombination: 8 CCC + +BO_ 373 Display_motor_data: 8 DME + +BO_ 400 display_ACC: 8 LDM + +BO_ 405 Operation_push_button_MSA: 8 IHKA + +BO_ 419 Raw_data_longitudinal_acceleration: 8 DSC + +BO_ 423 actuation_request_EMF: 8 DSC + +BO_ 426 Effect_ErgoCommander: 8 CCC + +BO_ 428 Status_ARS_module: 8 ARS + +BO_ 440 Operation_ErgoCommander: 8 ZBE + +BO_ 450 Distance_message_PDC: 8 PDC + +BO_ 451 Distance_message_2_PDC: 8 PDC + +BO_ 454 Acoustic_message_PDC: 8 PDC + +BO_ 472 Operation_air_conditioning_air_distribution_FA: 8 CCC + +BO_ 473 Operation_pushbutton_MDrive: 8 SZL + +BO_ 474 Climate_control_remote_control: 8 CAS + +BO_ 476 Operation_stratification_seat_heating: 8 CCC + +BO_ 478 Air_conditioning_controls_rear: 8 CCC + +BO_ 480 Operation_air_conditioning_air_distribution_BF: 8 CCC + +BO_ 482 Operation_air_conditioning_front: 8 CCC + +BO_ 483 Operation_pushbutton_interior_lighting: 8 FZD + +BO_ 487 Operation_seat_heating_seat_climate_FA: 8 IHKA + +BO_ 488 Operation_seat_heating_seat_climate_BF: 8 IHKA + +BO_ 490 Steering_column_adjustment_control: 8 IHKA + +BO_ 491 Operation_active_seat_FA: 8 IHKA + +BO_ 492 Operation_active_seat_BF: 8 IHKA + +BO_ 494 Steering_column_switch_operation: 8 FRMFA + +BO_ 499 Operation_seat_memory_FA: 8 XXX + +BO_ 504 Operation_SHD_MDS: 8 FZD + +BO_ 507 Status_EPS: 8 EPS + +BO_ 508 Status_AFS: 8 AFS + +BO_ 509 Status_request_EMF_KCAN: 8 EMF + +BO_ 510 Crash: 8 ACSM + +BO_ 513 Status_EMF_KCAN: 8 EMF + +BO_ 517 Acoustic_request_Kombi: 8 Kombi + +BO_ 518 Control_Display_Shiftlights: 8 DME + +BO_ 523 Memory_adjustment: 8 SM_FA + +BO_ 524 Steering_column_control: 8 SM_FA + +BO_ 525 Position_steering_column: 8 IHKA + +BO_ 528 Operation_HUD: 8 CCC + +BO_ 529 Status_HUD: 8 HUD + +BO_ 530 Height_levels_air_spring: 8 EHC + +BO_ 540 Operation_NightVision: 8 CCC + +BO_ 542 Status_NightVision: 8 NVC + +BO_ 548 Operation_push_button_NSW: 8 FRMFA + +BO_ 552 Operation_special_function: 8 CCC + +BO_ 554 Status_BFS: 8 JBBF + +BO_ 556 Operation_push_button_NSL: 8 FRMFA + +BO_ 558 Status_BFSH: 8 XXX + +BO_ 562 Status_FAS: 8 JBBF + +BO_ 566 Status_FASH: 8 XXX + +BO_ 570 Status_radio_key: 8 CAS + +BO_ 571 Status_climate_front_extended: 8 IHKA + +BO_ 573 Request_display_climate: 8 IHKA + +BO_ 574 Status_Klima_Fond: 8 FKA + +BO_ 582 Status_air_conditioning_front_control_unit: 8 IHKA + +BO_ 584 Status_rear_view_camera: 8 RFK + +BO_ 585 Control_rear_view_camera: 8 CCC + +BO_ 586 Status_PDC: 8 PDC + +BO_ 587 Status_door_sensors: 8 FRMFA + +BO_ 594 Wiper_status: 8 JBBF + +BO_ 598 Challenge_Passive_Access: 8 CAS + +BO_ 600 Status_Transmission_Passive_Access: 8 PGS + +BO_ 604 Operation_of_climate_additional_programs: 8 CCC + +BO_ 621 Operation_blinds_MK: 8 IHKA + +BO_ 622 Control_FH_SHD_central_comfort: 8 CAS + +BO_ 635 Status_Shiftlights: 8 Kombi + +BO_ 637 Status_convertible_top_manual_convertible: 8 CAS + +BO_ 638 Status_convertible_top_convertible: 8 CTM + +BO_ 639 Status_central_locking_convertible_top: 8 JBBF + +BO_ 642 Control_security_vehicle_2: 8 XXX + +BO_ 644 Control_remote_start_safety_vehicle: 8 CAS + +BO_ 646 Electrochromic_control: 8 FZD + +BO_ 652 Pushbutton_vertical_dynamics: 8 GWS + +BO_ 653 Operation_pushbutton_sport: 8 GWS + +BO_ 656 Control_response_hydrogen_vehicle: 8 XXX + +BO_ 658 Control_high_beam_assistant: 8 FLA + +BO_ 670 Central_locking_control_for_security_vehicle: 8 XXX + +BO_ 671 Remote_control_FondCommander: 8 CAS + +BO_ 672 Central_locking_control: 8 CAS + +BO_ 674 Operation_of_climate_stand_functions: 8 CCC + +BO_ 676 Operation_personalization: 8 Kombi + +BO_ 692 DWA_Alarm: 8 DWA + +BO_ 694 Control_horn_DWA: 8 DWA + +BO_ 696 Operation_onboard_computer: 8 CCC + +BO_ 697 Operation_RSE: 8 CCC + +BO_ 698 Stopwatch: 8 Kombi + +BO_ 701 Request_switching_display: 8 CCC + +BO_ 702 Switch_status_display: 8 VSW + +BO_ 703 Water_valve_control: 8 IHKA + +BO_ 706 Temperatur_Ist_Fond: 8 FKA + +BO_ 711 Display_Kombination_extended: 8 DME + +BO_ 714 Outside_temperature: 8 Kombi + +BO_ 716 Control_monitor_rear: 8 RSE + +BO_ 718 Control_monitor: 8 CCC + +BO_ 719 Status_of_auxiliary_water_pump: 8 JBBF + +BO_ 720 Status_Sensor_AUC: 8 JBBF + +BO_ 721 Status_fitting_window_V: 8 FZD + +BO_ 722 Status_pressure_refrigeration_circuit: 8 JBBF + +BO_ 723 Status_stratification_rear: 8 JBBF + +BO_ 725 Status_heating_rear_window: 8 JBBF + +BO_ 726 Status_valve_air_conditioning_compressor: 8 JBBF + +BO_ 730 Status_tailgate_lift: 8 HKL + +BO_ 734 Switch_control_display: 8 VSW + +BO_ 738 Status_setting_video_night_vision: 8 NVC + +BO_ 739 Status_setting_video_rear_view_camera: 8 RFK + +BO_ 740 Status_trailer: 8 AHM + +BO_ 742 Status_of_air_distribution_FA: 8 IHKA + +BO_ 746 Status_air_distribution_BF: 8 IHKA + +BO_ 750 Status_climate_additional_programs: 8 IHKA + +BO_ 752 Status_air_condition_functions: 8 IHKA + +BO_ 753 Status_driver_detection: 8 MRSZ + +BO_ 755 Display_switching_instruction: 8 DME + +BO_ 756 Air_conditioning_control_SH_ZH_auxiliary_water_pump: 8 IHKA + +BO_ 759 Units: 8 Kombi + +BO_ 768 Status_RSE: 8 RSE + +BO_ 772 Status_Gang: 8 EGS + +BO_ 773 Operation_button_convertible_top: 8 IHKA + +BO_ 774 Vehicle_tilt: 8 FRMFA + +BO_ 775 Operation_button_flap_convertible_top: 8 IHKA + +BO_ 776 Status_MSA: 8 DME + +BO_ 785 Refill_quantity: 8 Kombi + +BO_ 786 Service_Call_Teleservice: 8 Kombi + +BO_ 787 Status_Service_Call_Teleservice: 8 CCC + +BO_ 788 Status_driving_light: 8 FZD + +BO_ 789 Vehicle_mode: 8 JBBF + +BO_ 791 Operation_button_parking_aids: 8 IHKA + +BO_ 792 Status_antennas_Passive_Access: 8 PGS + +BO_ 793 Operation_push_button_RDC: 8 JBBF + +BO_ 794 Operation_button_HDC: 8 IHKA + +BO_ 795 Operation_of_tailgate_interior_button: 8 IHKA + +BO_ 796 Status_tire_pressure: 8 RDC + +BO_ 801 Operation_button_camera_BF: 8 IHKA + +BO_ 802 Damper_current: 8 EDCK + +BO_ 806 Status_damper_program: 8 VDM + +BO_ 808 Relativzeit: 8 Kombi + +BO_ 813 Display_HDC: 8 DSC + +BO_ 814 Status_climate_internal_control_info: 8 IHKA + +BO_ 817 Programming_of_step_cruise_control: 8 CCC + +BO_ 818 Driver_display_speed_range: 8 DME + +BO_ 822 Display_check_control_message_role: 8 Kombi + +BO_ 824 Control_display_check_control_message: 8 Kombi + +BO_ 825 Status_display_climate: 8 CCC + +BO_ 826 Status_Monitor_Front: 8 CID + +BO_ 828 Status_Monitor_Fond_1: 8 CID + +BO_ 830 Status_Monitor_Fond_2: 8 CID + +BO_ 841 Raw_data_level_tank: 8 JBBF + +BO_ 843 Seat_back_lock_status_FA: 8 SM_FA + +BO_ 845 Status_seat_back_lock_BF: 8 SM_BF + +BO_ 847 Status_contact_handbrake: 8 JBBF + SG_ Handbrake_push : 0|2@1+ (1,0) [0|3] "" XXX + +BO_ 858 Appointment_Condition_Based_Service: 8 CCC + +BO_ 860 Status_onboard_computer: 8 Kombi + +BO_ 862 Onboard_computer_data_trip_data: 8 Kombi + +BO_ 864 Data_onboard_computer_start_of_journey: 8 Kombi + +BO_ 866 Data_onboard_computer_average_values: 8 Kombi + +BO_ 868 Data_onboard_computer_arrival: 8 Kombi + +BO_ 869 Status_terminal_request: 8 CAS + +BO_ 870 Display_Kombination_external_display: 8 Kombi + +BO_ 871 Control_display_of_demand_oriented_service: 8 Kombi + +BO_ 877 Setting_the_driving_dynamics_switch: 8 JBBF + +BO_ 886 Status_wear_lamella: 8 VGSG + +BO_ 893 Status_DKG: 8 DKG + +BO_ 894 Temperatur_Bremse: 8 DSC + +BO_ 895 Range_of_diesel_exhaust_gas_additive: 8 DDE1 + +BO_ 896 chassis_number: 8 CAS + +BO_ 898 Electronic_engine_oil_dipstick_M: 8 DME + +BO_ 899 Motor_data_2: 8 DME + +BO_ 904 Vehicle_type: 8 CAS + +BO_ 907 Status_battery: 8 DME + +BO_ 910 Start_speed: 8 DME + +BO_ 914 Status_System_AFS: 8 AFS + +BO_ 916 RDA_request_data_storage: 8 Kombi + +BO_ 917 Coding_power_management: 8 CAS + +BO_ 920 Operation_chassis: 8 CCC + +BO_ 921 Status_MDrive: 6 DME + +BO_ 926 Operation_time_date: 8 CCC + +BO_ 928 Vehicle_state: 8 JBBF + +BO_ 931 Request_Remote_Services: 8 CCC + +BO_ 937 Status_motor_control_CKM: 8 DME + +BO_ 939 Status_Shiftlights_CKM: 8 Kombi + +BO_ 944 Status_gear_reverse: 8 FRMFA + +BO_ 949 Status_water_valve: 8 JBBF + +BO_ 950 Position_window_lifter_FAT: 8 FRMFA + +BO_ 951 Position_window_lifter_FATH: 8 JBBF + +BO_ 952 Position_window_regulator_BFT: 8 FRMFA + +BO_ 953 Position_window_regulator_BFTH: 8 JBBF + +BO_ 954 Position_SHD: 8 FZD + +BO_ 956 Position_window_lifter_security_vehicle: 8 XXX + +BO_ 957 Status_consumer_shutdown: 8 FRMFA + +BO_ 959 Position_window_rear_window: 8 CTM + +BO_ 960 Configuration_FAS: 8 SM_FA + +BO_ 961 Configuration_BFS: 8 SM_BF + +BO_ 964 Status_EDCK_CKM: 8 JBBF + +BO_ 967 Access_radio: 8 RAD1 + +BO_ 968 Operation_push_button_radio: 8 RAD1 + +BO_ 974 Radio_audio_control_interface_display: 8 ACI + +BO_ 975 Acknowledgment_access_radio_audio_control_interface: 8 ACI + +BO_ 979 Status_solar_sensor: 8 FZD + +BO_ 980 Configuration_of_central_locking_CKM: 8 Kombi + +BO_ 981 Status_central_locking_CKM: 8 CAS + +BO_ 982 Configuration_DWA_CKM: 8 Kombi + +BO_ 983 Status_DWA_CKM: 8 FZD + +BO_ 984 Configuration_RLS_CKM: 8 Kombi + +BO_ 985 Status_RLS_CKM: 8 FZD + +BO_ 986 Configuration_of_memory_positions_CKM: 8 Kombi + +BO_ 987 Status_memory_positions_CKM: 8 SM_FA + +BO_ 988 Configuration_light_CKM: 8 Kombi + +BO_ 989 Status_light_CKM: 8 FRMFA + +BO_ 990 Configuration_Climate_CKM: 8 CCC + +BO_ 991 Status_Klima_CKM: 8 IHKA + +BO_ 994 Configuration_of_tailgate_CKM: 8 CCC + +BO_ 995 Status_tailgate_CKM: 8 HKL + +BO_ 996 Configuration_rear_view_camera_CKM: 8 CCC + + + + +CM_ SG_ 170 ThrottlelPressed "Active when accelerator pedal pressed or cruise control: drives"; +CM_ SG_ 170 AcceleratorPedalPressed "Active only when driver actually presses the pedal"; +CM_ SG_ 170 AcceleratorPedalPercentage "ToDo Factor to be adjusted"; +CM_ SG_ 404 plus1mph_request "Appears when +1mph/kph stalk is depressed"; +CM_ SG_ 404 minus1mph_request "Appears when -1mph/kph stalk is depressed"; +CM_ SG_ 404 Cancel_request_up_stalk "Appears when cancel stalk (up) is depressed"; +CM_ SG_ 404 Cancel_request_up_or_down_stalk "Appears when cancel stalk (up or down) is depressed"; +CM_ SG_ 404 Resume_request "It appears when resume stalk button is depressed"; +CM_ SG_ 404 Counter_404 "Message is sent at higher rate when cruise stalk is pressed"; + +CM_ SG_ 168 BrakePressed "Brake when driver presses the brake or hill hold"; +CM_ SG_ 168 EngineTorque "Engine torque without inertia - combustion torque"; +CM_ SG_ 168 EngineTorqueWoInterv "Engine torque without inertia and without shift intervention"; +CM_ SG_ 168 ALIV_TORQ_1_DME "Counter TORQ_1"; + +CM_ SG_ 169 ALIV_TORQ_2_DME "Counter TORQ_2"; + +CM_ SG_ 182 TORQ_TAR_DSC "torque target DSC"; + +CM_ SG_ 403 CruiseControlSetpointSpeed "Speed target - unit depends on locale"; +CM_ SG_ 186 GearTar "Values corresponds to forward gears. TBD Add enums for park, reverse"; +CM_ SG_ 466 GearAct "TransmissionDataDisplay"; +CM_ SG_ 414 DSC_full_off "0x4 enabling, 0xA enabled. TBD"; + +CM_ SG_ 416 YawRate "Lateral Acceleration"; + +CM_ SG_ 408 ParkButtonSecond "Redundant buton. 0x1 = pressed;"; +CM_ SG_ 408 SideButton "0x1 = pressed;"; +CM_ SG_ 408 SportButtonPressed "0x1 = pressed;"; +CM_ SG_ 408 M3_button "M3 POWER (?)"; +CM_ SG_ 408 SideButtonXOR11 "Complement value"; +CM_ SG_ 408 param1 "can not be 0x03. Always 0 in 135i."; +CM_ SG_ 408 param5 "Always 0 in 135i."; +CM_ SG_ 408 ParkButtonFirst "0x1 = pressed"; +CM_ SG_ 408 ShifterPosition "0001 = N|R, 0010 = R, 0011 = N|D, 0100 = D, 0101 = -1, 0110 = +1, 0111 = ManualMode, 1000 = inBetween,"; + +CM_ SG_ 466 ShiftLeverMode "On the dashboard, there are displayed: D1...D7 in Normal. S1...S6 in Sport. M1..M7 in Manual"; + +CM_ SG_ 502 TurnSignalIdle "Turn signal off"; +CM_ SG_ 502 TurnSignalActive "Turn signal on or transitioning"; +CM_ SG_ 502 RightTurn "Indicates right blinker or when steering returning right clears left blinker"; +CM_ SG_ 502 LeftTurn "Indicates left blinker or when steering returning left clears right blinker"; +CM_ SG_ 502 HoldActivated "Spikes down if blinker cleared with timeout or turn. Stays off if blinker cleared with stalk"; + +CM_ SG_ 790 setMe_0x3FFF "All ones"; +CM_ SG_ 790 DTC_pressed "Traction control off. Message transmitted when pressed. Few presses may be required followed by off."; + +VAL_ 408 ShifterPosition 1 "D" 2 "S" 3 "N" 4 "R" 5 "P" ; + +VAL_ 464 ST_SW_WAUP 3 "signal invalid" 2 "EGS forced switching active" 1 "engine warm" 0 "warming up" ; +VAL_ 464 ST_ENG_RUN 3 "signal invalid" 2 "engine running" 1 "engine starting" 0 "engine off" ; +VAL_ 464 CTR_SLCK 3 "signal invalid" 2 "requirement Shiftlock" 1 "no requirement Shiftlock" 0 "not allowed" ; + +VAL_ 466 ShiftLeverMode 0 "Normal" 1 "Sport" 2 "Manual" ; +VAL_ 466 ShiftLeverPosition 0 "Off" 1 "P" 2 "R" 4 "N" 8 "D" ; diff --git a/opendbc_repo/opendbc/dbc/cadillac_ct6_chassis.dbc b/opendbc_repo/opendbc/dbc/cadillac_ct6_chassis.dbc new file mode 100644 index 000000000000000..9de969d762f9a25 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/cadillac_ct6_chassis.dbc @@ -0,0 +1,95 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: K182_PACM K43_PSCM K17_EBCM NEO K124_ASCM + + + +BO_ 823 PACMParkAssitCmd: 7 NEO + SG_ RollingCounter : 35|2@0+ (1,0) [0|0] "" NEO + SG_ SteeringWheelChecksum : 47|16@0+ (1,0) [0|0] "" NEO + SG_ SteeringWheelCmd : 23|16@0+ (1,0) [0|0] "" NEO + +BO_ 560 EBCMRegen: 6 K17_EBCM + SG_ Regen : 1|10@0+ (1,0) [0|0] "" NEO + +BO_ 338 ASCMLKASteeringCmd: 6 NEO + SG_ LKASteeringCmdActive : 7|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 5|14@0- (1,0) [0|0] "" NEO + SG_ RollingCounter : 23|2@0+ (1,0) [0|0] "" NEO + SG_ SetMe1 : 21|1@0+ (1,0) [0|0] "" NEO + SG_ LKASVehicleSpeed : 20|13@0+ (0.22,0) [0|0] "kph" NEO + SG_ LKASMode : 36|2@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 33|10@0+ (1,0) [0|0] "" NEO + +BO_ 340 ASCMBLKASteeringCmd: 6 NEO + SG_ LKASteeringCmdActive : 7|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 5|14@0- (1,0) [0|0] "" NEO + SG_ RollingCounter : 23|2@0+ (1,0) [0|0] "" NEO + SG_ SetMe1 : 21|1@0+ (1,0) [0|0] "" NEO + SG_ LKASVehicleSpeed : 20|13@0+ (0.22,0) [0|0] "kph" NEO + SG_ LKASteeringCmdActive2 : 35|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 33|10@0+ (1,0) [0|0] "" NEO + +BO_ 368 EBCMFrictionBrakeStatus: 8 K17_EBCM + SG_ FrictionBrakePressure : 23|16@0+ (1,0) [0|0] "" NEO + +BO_ 789 EBCMFrictionBrakeCmd: 5 K17_EBCM + SG_ RollingCounter : 37|6@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeMode : 7|4@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeChecksum : 23|16@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeCmd : 3|12@0- (1,0) [0|0] "" NEO + +BO_TX_BU_ 823 : K43_PSCM,NEO; +BO_TX_BU_ 789 : NEO,K17_EBCM; + + +CM_ BU_ K182_PACM "Parking Assist Control Module"; +CM_ BU_ K43_PSCM "Power Steering Control Module"; +CM_ BU_ K17_EBCM "Electronic Brake Control Module"; +CM_ BU_ NEO "Comma NEO"; +CM_ BU_ K124_ASCM "Active Safety Control Module"; +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "UseGMParameterIDs" 0; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; + +VAL_ 338 LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 338 LKASMode 2 "supercruise" 1 "lkas" 0 "Inactive" ; diff --git a/opendbc_repo/opendbc/dbc/cadillac_ct6_object.dbc b/opendbc_repo/opendbc/dbc/cadillac_ct6_object.dbc new file mode 100644 index 000000000000000..3f7cf64cdc131dc --- /dev/null +++ b/opendbc_repo/opendbc/dbc/cadillac_ct6_object.dbc @@ -0,0 +1,3470 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: RRSRR_FO LRSRR_FO CIPM_FO _DOFIMU2_FO _DOFIMU1_FO DMS_FO AMM_FO EOCM2B_IMX6_FO EOCM2B_K2_FO EOCM2B_K1_FO EOCM2A_IMX6_FO EOCM2A_K2_FO EOCM2A_K1_FO NVS_FO Dummy_FO TestTool_FO LRR_FO RFSRR_FO LFSRR_FO RSRR_FO VIS_FO EOCM_F_FO VIS2_FO +VAL_TABLE_ vt_BooleanValues 1 "true" 0 "false" ; +VAL_TABLE_ FrntVsnInPthVehBrkNwSt 10 "Active" 5 "Inactive" ; +VAL_TABLE_ FrntVsnClostPedBrkNwSt 10 "Active" 5 "Inactive" ; +VAL_TABLE_ DrvrMonSysEngSt 7 "Unused and Reserved 1" 6 "Recovering" 5 "Tracking" 4 "Searching" 3 "Video test port only" 2 "Idle" 1 "Invalid state" 0 "Does not exist or DME" ; +VAL_TABLE_ DrvrMonEngUnrecvrFltCod 7 "Unused and Reserved 3" 6 "Unused and Reserved 2" 5 "Unused and Reserved 1" 4 "Vehicle power supply Errors" 3 "Problem with LED illuminators" 2 "Vehicle input signals Errors" 1 "Problem with imager" 0 "Ok" ; +VAL_TABLE_ DrvrMonEngRecvrFltCod 3 "Engine is unable to find a face" 2 "Input Images too dark" 1 "Input images too bright" 0 "Ok" ; +VAL_TABLE_ DrvrMntrSysVTP 1 "Video test port active" 0 "Video test port inactive" ; +VAL_TABLE_ DrvrAttnStatCnfdc 3 "High" 2 "Medium" 1 "Low" 0 "Lowest" ; +VAL_TABLE_ DrvrAttnStat 7 "Invalid" 6 "Driver is exhibiting sleep" 5 "Driver is exhibiting microsleep" 4 "Attention is Center Console" 3 "Attention is Drivers Lap" 2 "Attention is Off Road" 1 "Attention is On Road" 0 "Unknown" ; +VAL_TABLE_ PPSMd 7 "GNSS and RTX and DR and MM" 6 "DR ONLY" 5 "GNSS and RTX and DR" 4 "GNSS and SBAS and DR" 3 "GNSS and DR" 2 "GNSS and RTX" 1 "GNSS and SBAS" 0 "GNSS Standalone" ; +VAL_TABLE_ AdvDrvAstMpPrfShrtAcur 3 "Accuracy Is Unknown" 2 "Lowest Accuracy" 1 "Medium Accuracy" 0 "Highest Accuracy" ; +VAL_TABLE_ AdvDrAstMpStbRtOfWay 3 "Not Applicable" 2 "Unknown" 1 "Sub Path Has Right Of Way Over Path" 0 "Path Has Right Of Way Over Sub Path" ; +VAL_TABLE_ AdvDrAstMpStbPrtCalRut 3 "Not Applicable" 2 "Unknown" 1 "Path From This Point On Is Part Of Calculated Route" 0 "Path From This Point On Is Not Part Of Calculated Route" ; +VAL_TABLE_ AdvDrAstMpStbMsgTyp 7 "Unused and Reserved 2" 6 "Metadata" 5 "Profile Long" 4 "Profile Short" 3 "Stub" 2 "Segment" 1 "Position" 0 "Unused and Reserved 1" ; +VAL_TABLE_ AdvDrAstMpStbFmOfWay 15 "Not Applicable" 14 "Pedestrian Zone" 13 "Entrance To Or Exit To Service" 12 "Entrance To Or Exit Of A Car Park" 11 "Service Road Or Frontage Road" 10 "Slip Road per Ramp" 9 "Slip Road per Ramp On A Freeway Or Controlled Access Road" 8 "Parallel Road" 7 "Unused and Reserved 2" 6 "Unused and Reserved 1" 5 "Traffic Square per Special Traffic Figure" 4 "Roundabout Circle" 3 "Single Carriageway" 2 "Multiple Carriageway Or Multiply Digitized Road" 1 "Freeway Or Controlled Access Road That Is Not A Slip Road Or Ramp" 0 "Unknown" ; +VAL_TABLE_ AdvDrAstMpStbCmplxInsct 3 "Not Applicable" 2 "Unknown" 1 "Stub Is Part Of Complex Intersection" 0 "Stub Is Not Part Of Complex Intersection" ; +VAL_TABLE_ AdvDrAstMpSegTunl 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Tunnel" 0 "Segment Is Not A Part Of Tunnel" ; +VAL_TABLE_ AdvDrAstMpSegPrtCalRut 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Calculated Route" 0 "Segment Is Not Part Of Calculated Route" ; +VAL_TABLE_ AdvDrAstMpSegMsgTyp 7 "Unused and Reserved 2" 6 "Metadata" 5 "Profile Long" 4 "Profile Short" 3 "Stub" 2 "Segment" 1 "Position" 0 "Unused and Reserved 1" ; +VAL_TABLE_ AdvDrAstMpSegFrmOfWay 15 "Not Applicable" 14 "Pedestrian Zone" 13 "Entrance To Or Exit To Service" 12 "Entrance To Or Exit Of A Car Park" 11 "Service Road Or Frontage Road" 10 "Slip Road per Ramp" 9 "Slip Road per Ramp On A Freeway Or Controlled Access Road" 8 "Parallel Road" 7 "Unused and Reserved 2" 6 "Unused and Reserved 1" 5 "Traffic Square per Special Traffic Figure" 4 "Roundabout Circle" 3 "Single Carriageway" 2 "Multiple Carriageway Or Multiply Digitized Road" 1 "Freeway Or Controlled Access Road That Is Not A Slip Road or Ramp" 0 "Unknown" ; +VAL_TABLE_ AdvDrAstMpSegEffSdLmtTp 7 "Not Applicable" 6 "Explicit Snow" 5 "Explicit Rain" 4 "Explicit Time Of Day" 3 "Explicit By Day" 2 "Explicit By Night" 1 "Explicit On Traffic Sign" 0 "Implicit" ; +VAL_TABLE_ AdvDrAstMpSegDivdRd 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Divided Road" 0 "Segment Is Not Part Of Divided Road" ; +VAL_TABLE_ AdvDrAstMpSegCmplxInsct 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Complex Intersection" 0 "Segment Is Not Part Of Complex Intersection" ; +VAL_TABLE_ AdvDrAstMpSegBrdg 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Bridge" 0 "Segment Not Part Of Bridge" ; +VAL_TABLE_ AdvDrAstMpSegBldUpAra 3 "Not Applicable" 2 "Unknown" 1 "Segment Is Part Of Built Up Area" 0 "Segment Is Not Part Of Built Up Area" ; +VAL_TABLE_ AdvDrAstMpMtdtSpdUnt 1 "Miles Per Hour" 0 "Kilometers Per Hour" ; +VAL_TABLE_ AdvDrAstMpMtdtDrvSd 1 "Driving Side Right" 0 "Driving Side Left" ; +VAL_TABLE_ WSMR_WiFiAssnReq 3 "Unexpected Undefined Connection Behavior" 2 "Wi Fi association failed with available credentials" 1 "Failed to receive Wi Fi credentials after 255 attempts" 0 "SSID and Passphrase Request" ; +VAL_TABLE_ StrgColCommsFlt 2 "Disabled Communications DTC" 1 "No Communications Fault" 0 "Communications Fault" ; +VAL_TABLE_ CPMAPINFO4 1 "Hardware Or Software Error" 0 "No Hardware Or Software Error" ; +VAL_TABLE_ AdvDrvAstMpPrfShrt2Acur 3 "Accuracy Is Unknown" 2 "Lowest Accuracy" 1 "Medium Accuracy" 0 "Highest Accuracy" ; +VAL_TABLE_ InterLghtStat 1 "Interior Lights On" 0 "Interior Light Off" ; +VAL_TABLE_ VehLnStatConf 2 "High Confidence" 1 "Low Confidence" 0 "No Confidence" 3 "Very High Confidence" ; +VAL_TABLE_ VehLnStat 3 "Lane Change To Right" 2 "Lane Change To Left" 1 "Staying in Lane" 0 "Unknown" ; +VAL_TABLE_ HrznPrvdRstRq 1 "Reset Not Required" 0 "Reset Required" ; +VAL_TABLE_ ExptNxtTrnstnDirConf 3 "Very High Confidence" 2 "High Confidence" 1 "Low Confidence" 0 "No Confidence" ; +VAL_TABLE_ ExptNxtTrnstnDir 7 "Reserved4" 6 "Reserved3" 5 "Reserved2" 4 "Reserved1" 3 "Traversing Middle Transition" 2 "Traversing Next Transition Right" 1 "Traversing Next Transition Left" 0 "Unknown" ; +VAL_TABLE_ ADASISMsgTypRetrans 7 "GM System Specific" 6 "Meta Data" 5 "Profile Long" 4 "Profile Short" 3 "Stub" 2 "Segment" 1 "Position" 0 "Checksum" ; +VAL_TABLE_ NVSysStat 7 "Needs Headlights" 6 "Temporarily Unavailable" 5 "Not Dark" 4 "Needs Service" 3 "Active" 2 "Inactive" 1 "Initializing" 0 "Unknown" ; +VAL_TABLE_ NVSysPedWrnIndReq 3 "Unused & Reserved" 2 "Pedestrian Alert" 1 "Pedestrian Detected" 0 "None" ; +VAL_TABLE_ NVSysPedDetCstReq 2 "On" 1 "Off" 0 "No Value" ; +VAL_TABLE_ NVSysPedDetCsCrStVal 2 "On" 1 "Off" 0 "No Value" ; +VAL_TABLE_ FwVsnCinCoutPotT9Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT8Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT7Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT6Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT5Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT4Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT3Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT2Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT1Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT12Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT11Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ FwVsnCinCoutPotT10Rev 2 "Right" 1 "Left" 0 "None" ; +VAL_TABLE_ GFHBObjDirTrk8 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk7 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk6 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk5 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk4 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk3 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk2 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBObjDirTrk1 1 "Ahead Traffic" 0 "Incoming Traffic" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk8 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk7 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk6 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk5 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk4 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk3 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk2 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnRelLaneTrk1 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk8 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk7 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk6 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk5 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk4 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk3 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk2 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnMesStatTrk1 3 "Measured this cycle" 2 "Latent track not detected this cycle" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk8 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk7 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk6 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk5 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk4 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk3 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk2 3 "Confident" 2 "Speculative" 1 "Highly Speculative" 0 "Invalid" ; +VAL_TABLE_ GFHBFwVsnCnfdncTrk1 0 "Invalid" 3 "Confident" 2 "Speculative" 1 "Highly Speculative" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev8 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev7 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev6 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev5 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev4 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev3 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev2 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car)" 0 "Unknown" ; +VAL_TABLE_ GFHBFVsnObjTypTrkRev1 12 "Cluster Object" 11 "Child Close to Danger Zone" 10 "Pedestrian Moving Out of Danger Zone" 9 "Pedestrian Moving Into Danger Zone" 8 "Pedestrian Standing Outside Danger Zone" 7 "No Object Present" 6 "Fixed Roadside Object" 5 "Fixed Overhead Object" 4 "Pedestrian" 3 "Motorcycle/ Bicycle" 2 "Large Vehicle (Semi)" 1 "4 Wheel Vehicle (Car" 0 "Unknown" ; +VAL_TABLE_ CRL_Cnfdnc 7 "Reserved4" 6 "Reserved3" 5 "Reserved2" 4 "Reserved1" 3 "Best" 2 "Marking Present" 1 "Weak Marking" 0 "No Lane" ; +VAL_TABLE_ CLL_Cnfdnc 7 "Reserved4" 6 "Reserved3" 5 "Reserved2" 4 "Reserved1" 3 "Best" 2 "Marking Present" 1 "Weak Marking" 0 "No Lane" ; +VAL_TABLE_ VBBrkCtrlSt 4 "Release Control" 3 "Hold Vehicle" 2 "Apply Brake" 1 "Decrease Torque" 0 "No Action" ; +VAL_TABLE_ ObstacleType 6 "NO_OBJECT" 5 "OBJ_GUARDRAIL" 4 "OBJ_TUNNEL " 3 "OBJ_TRAFFIC_SIGN" 2 "OBJ_VEHICLE" 1 "OBJ_BRIDGE " 0 "OBJ_UNKNOWN" ; +VAL_TABLE_ VpathMode 2 "Mid Hi Speed" 1 "Low Speed" 0 "Disabled" ; +VAL_TABLE_ LaneChngStatus 2 "Lane Change Right" 1 "Lane Change Left" 0 "Idle" ; +VAL_TABLE_ TravelDirection 3 "Other (excessive side slip)" 2 "reverse / stopped in rvrs gear" 1 "Forward / stopped in frwd gear" 0 "Unknown" ; +VAL_TABLE_ TrueOrFalse 1 "true" 0 "false" ; +VAL_TABLE_ ModeCommand 5 "Sensing with Reduced Power" 4 "Undefined" 3 "Radio Silent" 2 "Sensing" 1 "Not Sensing" 0 "Undefined" ; +VAL_TABLE_ LaneSnsLLnPosValid 1 "Invalid" 0 "Valid" ; +VAL_TABLE_ LnSnsRLnPosValid 1 "Invalid" 0 "Valid" ; +VAL_TABLE_ Elevation 3 "Low " 2 "mid (reserved)" 1 "high " 0 "Unknown" ; +VAL_TABLE_ ModeCommandFdbk 5 "Sensing with reduced power" 4 "Undefined" 3 "Radio Silent" 2 "Sensing" 1 "Not Sensing" 0 "Undefined" ; +VAL_TABLE_ relativeLane 3 "Left Lane" 2 "Right Lane" 1 "Host Lane" 0 "Unknown" ; +VAL_TABLE_ RoadTypeInfo 5 "Constiction Zone Exit" 4 "Construction Zone Entry" 3 "Highway" 2 "Secondary Road" 1 "City" 0 "Unknown" ; +VAL_TABLE_ ObjectLossInfo 2 "elevation conditions" 1 "tight curve" 0 "not lost" ; +VAL_TABLE_ MeasurementStatus 3 "Measured this cycle" 2 "Latent track not detctd this cyc" 1 "New Object" 0 "No Object" ; +VAL_TABLE_ ObjectType 7 "no object present" 6 "fixed roadside object" 5 "fixed overhead object" 4 "pedestrian" 3 "motocycle / bicycle" 2 "Large vehicle (semi)" 1 "4 Wheel Vehicle (car, small trk)" 0 "Unknown" ; +VAL_TABLE_ Confidence 3 "confident" 2 "speculative" 1 "highly speculative" 0 "invalid" ; +VAL_TABLE_ DynamicProp 4 "Moving in opposite direction" 3 "Moving in same direction as host" 2 "Has moved but currently stopped" 1 "Has never moved" 0 "Unknown" ; +VAL_TABLE_ DrvWndPosSt 6 "Fully Opened" 5 "Open More Than C" 4 "Position C" 3 "Position B" 2 "Position A" 1 "Open Less Than A" 0 "Fully Closed" ; +VAL_TABLE_ VehMovSta 4 "Invalid" 3 "Reverse" 2 "Forward" 1 "Neutral" 0 "Parked" ; +VAL_TABLE_ OtsdAmbtLtLvlStat 2 "Day" 1 "Night" 0 "Unknown" ; +VAL_TABLE_ RtTrnLmpAtv 2 "On with telltale" 1 "On without telltale" 0 "Off" ; +VAL_TABLE_ LftTrnLmpAtv 2 "On with telltale" 1 "On without telltale" 0 "Off" ; +VAL_TABLE_ HdlmpBmSelectStat 2 "High Beams" 1 "Low Beams" 0 "Unknown" ; +VAL_TABLE_ DTCI_DTCFaultType 3 "Type C" 2 "Type B" 1 "Type A" 0 "Not Supported" ; +VAL_TABLE_ TrnsShftLvrPos 13 "Forward Range J" 12 "Forward Range I" 15 "Lever Position Unknown" 11 "Forward Range H" 10 "Forward Range G" 9 "Forward Range F" 8 "Forward Range E" 7 "Forward Range D" 6 "Forward Range C" 5 "Forward Range B" 4 "Forward Range A" 3 "Neutral Range" 2 "Reverse Range" 1 "Park Range" 0 "Between Ranges" ; +VAL_TABLE_ SysPwrMd 3 "Crank Request" 2 "Run" 1 "Accessory" 0 "Off" ; +VAL_TABLE_ ValidityStates 1 "Invalid" 0 "Valid" ; + + +BO_ 1548 ADAS_Profile_Short2_FO: 8 AMM_FO + SG_ AdvDrvAstMpPrfShrt2Val1 : 1|10@0+ (1,0) [0|1023] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Val0 : 33|10@0+ (1,0) [0|1023] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Updt : 39|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2RTrns : 3|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Typ : 38|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2PthIdx : 23|6@0+ (1,0) [0|63] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Ofst : 52|13@0+ (1,0) [0|8191] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2MsgTp : 55|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Dist1 : 17|10@0+ (1,0) [0|1023] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2CycCnt : 7|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2CtlPt : 2|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpPrfShrt2Acur : 5|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 1547 ADAS_Profile_Long2_FO: 8 AMM_FO + SG_ AdvDrAstMpProfLng2Val : 39|32@0+ (1,0) [0|4294967295] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2Updt : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2RTrns : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2PrfTyp : 4|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2PthIdx : 13|6@0+ (1,0) [0|63] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2Ofst : 20|13@0+ (1,0) [0|8191] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2MgTyp : 23|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2CycCt : 15|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLng2CtrlPt : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 1630 USDT_Resp_From_EOCM2B_K2_FO: 8 EOCM2B_K2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1374 UUDT_Resp_From_EOCM2B_K2_FO: 8 EOCM2B_K2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 606 USDT_Req_to_EOCM2B_K2_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2B_K2_FO + +BO_ 328 Vehicle_Info_FO: 5 EOCM2A_K1_FO + SG_ StrWhAngGrd : 27|12@0- (1,0) [-2048|2047] "deg/sec" DMS_FO + SG_ TrnsShftLvrPos : 31|4@0+ (1,0) [0|15] "" DMS_FO + SG_ StrWhAng_148 : 15|16@0- (0.0625,0) [-2048|2047.9375] "deg" DMS_FO + SG_ TrnsShftLvrPosV : 3|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrWhAngV_148 : 4|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrWhAngMsk_148 : 5|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrWhAngGrdV : 6|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrWhAngGrdMsk : 7|1@0+ (1,0) [0|1] "" DMS_FO + +BO_ 1930 DTC_Triggered_78A_FO: 7 LRSRR_FO + SG_ DTCI_CodeSupported_78A : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_78A : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_78A : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_78A : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_78A : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_78A : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_78A : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_78A : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_78A : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_78A : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_78A : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_78A : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_78A : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_78A : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_78A : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_78A : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_78A : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_78A : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_78A : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_78A : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1624 USDT_Resp_From_LRSRR: 8 LRSRR_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1368 UUDT_Resp_From_LRSRR: 8 LRSRR_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 600 USDT_Req_to_LRSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LRSRR_FO + +BO_ 613 PPS_QualMetrics_FO: 8 EOCM2A_K1_FO + SG_ PPSPstnDilPrcs : 47|10@0+ (0.1,0) [0|102.3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSMd : 53|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPS3DAbsPosErrEstmt : 9|10@0+ (0.1,0) [0|102.3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSAbsHdngErrEstmt : 0|7@0+ (0.5,0) [0|63.5] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSAbsVelErrEstmt : 30|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSPosQltyMtrcsChksm : 50|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPS2DAbsPosErrEstmt : 25|10@0+ (0.1,0) [0|102.3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSPosQltyMtcBrstID : 2|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPS2DAbsPosErrEstmtV : 5|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPS3DAbsPosErrEstmtV : 4|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSAbsHdngErrEstmtV : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSAbsVelErrEstmtV : 31|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSMdV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSPstnDilPrcsV : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 612 PPS_Time_FO: 8 EOCM2A_K1_FO + SG_ PPSTmdayV : 2|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSCldrDayV : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSCldrDay : 8|9@0+ (1,0) [0|511] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSTmBrstID : 52|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSTmday : 31|27@0+ (1,0) [0|134217727] "ms" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSTmChksm : 50|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSCldrYrV : 1|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSCldrYr : 15|7@0+ (1,2014) [2014|2141] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 611 PPS_SigAcqTime_FO: 6 EOCM2A_K1_FO + SG_ PPSSigAqTmBrstID : 38|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSSigAcqTmV : 39|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSSigAcqTm : 7|32@0+ (1,0) [0|4294967295] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSSigAqTmChksm : 34|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 610 PPS_PosLong_FO: 6 EOCM2A_K1_FO + SG_ PPSLongBrstID : 39|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLong : 6|31@0- (1,0) [-1073741824|1073741823] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLongV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLongChksm : 34|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 609 PPS_PosLat_FO: 6 EOCM2A_K1_FO + SG_ PPSLatV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLatChksm : 34|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLatBrstID : 36|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSLat : 5|30@0- (1,0) [-536870912|536870911] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 1160 PassPhrase_3_AMM_FO: 8 EOCM2A_K1_FO + SG_ WiFiPssPhrsDgts17to24_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1159 PassPhrase_2_AMM_FO: 8 EOCM2A_K1_FO + SG_ WiFiPssPhrsDgts9to16_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1158 PassPhrase_1_AMM_FO: 8 EOCM2A_K1_FO + SG_ WiFiPssPhrsDgts1to8_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1546 ADAS_Protection_FO: 4 AMM_FO + SG_ AdvDrAstMpPrfLng2Avbl : 11|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPosAvbl : 15|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpHwFlt : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtAvbl : 8|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpProtChksm : 23|16@0+ (1,0) [0|65535] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpProtRTrns : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpProtCycCtMsg : 2|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbAvbl : 9|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpSegAvbl : 10|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfShrtAvbl : 14|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfShrt2Avbl : 13|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrAstMpPrfLngAvbl : 12|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ AdvDrvAstMpInpSigFld : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1545 ADAS_Metadata_FO: 8 AMM_FO + SG_ AdvDrAstMpMtdtVerYrQtr : 60|2@0+ (1,1) [1|4] "Qtr" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtVerYr : 53|6@0+ (1,2000) [2000|2063] "Year" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtSpdUnt : 39|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtPrvdr : 7|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtMsgTyp : 58|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtMnrPrtVr : 23|4@0+ (1,0) [0|15] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtCycCnt : 18|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtRgnCd : 38|15@0+ (1,0) [0|32767] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtHwVer : 16|9@0+ (1,0) [0|511] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtMnrPrtSbVr : 4|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtMjrPrtVr : 55|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtDrvSd : 19|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpMtdtCntryCd : 1|10@0+ (1,0) [0|1023] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1543 ADAS_Profile_Long_FO: 8 AMM_FO + SG_ AdvDrAstMpPrfLngUpdt : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngRTrns : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngCtlPt : 5|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngTyp : 4|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngCycCt : 15|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngPthIdx : 13|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngMsgTp : 23|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngOfst : 20|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPrfLngVal : 39|32@0+ (1,0) [0|4294967295] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1544 ADAS_Profile_Short_FO: 8 AMM_FO + SG_ AdvDrvAstMpPrfShrtVal1 : 1|10@0+ (1,0) [0|1023] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtVal0 : 33|10@0+ (1,0) [0|1023] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtDist1 : 17|10@0+ (1,0) [0|1023] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtCycCnt : 7|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtAcur : 5|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtCtlPt : 2|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtRetr : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtTyp : 38|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtUpdt : 39|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtPthIdx : 23|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtMsgTp : 55|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrvAstMpPrfShrtOfst : 52|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1542 ADAS_Stub_FO: 8 AMM_FO + SG_ AdvDrAstMpStbSubPthIdx : 63|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbUpdt : 55|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbPrtCalRut : 57|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbNmLnDrvDir : 54|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbCycCnt : 51|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbCmplxInsct : 49|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbTrnAngl : 47|8@0+ (1.417,0) [0|361.335] "deg" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbRtOfWay : 38|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbRelProb : 36|5@0+ (3.333,0) [0|103.323] "%" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbRetr : 39|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbNmLnOppDir : 31|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbPathIdx : 29|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbLstStbOfst : 23|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbMsgTyp : 22|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbFmOfWay : 19|4@0+ (1,0) [0|15] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbFuncRdCls : 7|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpStbOfst : 4|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1541 ADAS_Segment_FO: 8 AMM_FO + SG_ AdvDrAstMpSegRelProb : 12|5@0+ (3.333,0) [0|103.323] "%" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegUpdt : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegTunl : 25|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegCycCnt : 39|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegCmplxInsct : 37|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegBldUpAra : 43|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegBrdg : 41|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegRTrns : 1|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegDivdRd : 31|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegPthIdx : 7|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegPrtCalRut : 27|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegNmLnOppDir : 29|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegNmLnDrvDir : 55|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegMsgTyp : 46|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegFunRdCls : 23|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegFrmOfWay : 35|4@0+ (1,0) [0|15] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegEffSpdLmt : 20|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegEffSdLmtTp : 15|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpSegOffset : 52|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 608 PPS_ElevHdSpd_FO: 8 EOCM2A_K1_FO + SG_ PPSVel : 31|8@0+ (1,0) [0|255] "km / h" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSVelV : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSElvHedngSpdBrstID : 5|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSElvHdengSpdChksm : 50|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSHedngV : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSHedng : 2|19@0+ (0.001,0) [0|524.287] "deg" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSElvtnV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + SG_ PPSElvtn : 39|21@0+ (1,-100000) [-100000|1997151] "cm" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,AMM_FO + +BO_ 1168 WiFi_Station_AMM_FO: 5 AMM_FO + SG_ WSMR_WiFiStnMpMACAddr : 15|32@0+ (1,0) [0|4294967295] "" EOCM2B_K1_FO,EOCM2A_K1_FO + SG_ WSMR_WiFiAssnReq : 1|2@0+ (1,0) [0|3] "" EOCM2B_K1_FO,EOCM2A_K1_FO + +BO_ 1161 WiFi_AP_Data_AMM_FO: 2 EOCM2A_K1_FO + SG_ WAPDM_SecurityType : 15|4@0+ (1,0) [0|15] "" EOCM2B_K1_FO,AMM_FO + SG_ WAPDM_WiFiEnStat : 0|1@0+ (1,0) [0|1] "" EOCM2B_K1_FO,AMM_FO + SG_ WAPDM_EncrptnType : 11|4@0+ (1,0) [0|15] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1157 SSID_AMM_3_FO: 8 EOCM2A_K1_FO + SG_ WiFiSSIDDgts17to24_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 326 DMS_Eye_AOI_Info_FO: 6 DMS_FO + SG_ DrvrMontSysInit : 1|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMontSysAvlbl : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMontMdlDatFlshProgrs : 2|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngRecvrFltCodARC : 36|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStatChksm : 34|11@0+ (1,0) [0|2047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStat : 39|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStatPrd : 22|15@0+ (0.025,0) [0|819.175] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngRecvrFltCodV : 23|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngUnrecvrFltCod : 10|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngUnrecvrFltCodV : 11|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStatCnfdc : 13|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonEngRecvrFltCod : 15|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrAttnStatV : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 324 DMS_RawMeasurement_Info2_FO: 8 DMS_FO + SG_ DrvrMonFrmNum : 47|8@0+ (1,0) [0|255] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMntrSysVTP : 29|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonSysEngStV : 2|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonSysEngSt : 28|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonFrmNumV : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrHeadRotAngZV : 4|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrHeadRotAngYV : 5|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrHeadRotAngXV : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrHeadRotAngARC : 52|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonLatV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrMonLat : 50|11@0+ (0.001,0) [0|2.047] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadRotAngZ : 25|10@0- (0.00625,0) [-3.2|3.19375] "rad" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvHeadRotAngY : 23|10@0- (0.00625,0) [-3.2|3.19375] "rad" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvrHeadRotAngX : 1|10@0- (0.00625,0) [-3.2|3.19375] "rad" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 322 DMS_RawMeasurement_Info1_FO: 8 DMS_FO + SG_ DrvrEyeClosrRt : 47|8@0+ (0.005,0) [0|1.275] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrEyeClosrLft : 39|8@0+ (0.005,0) [0|1.275] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadPosZV : 3|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadPosYV : 4|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadPosXV : 5|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrEyeClosrRtV : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrEyeClosrLftV : 7|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvrEyeClosrARC : 52|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ DrvHeadPosZ : 50|11@0- (0.005,0) [-5.12|5.115] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvHeadPosY : 18|11@0- (0.005,0) [-5.12|5.115] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvHeadPosX : 2|11@0- (0.005,0) [-5.12|5.115] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 320 Inertial2_Rates_FO: 8 _DOFIMU2_FO + SG_ MstrTgrSyncInrtl2Rte : 55|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2YawRteV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2YawRte : 36|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2RollRteV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2RollRte : 20|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2RteChksum : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2PitchRteV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2PitchRte : 4|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 308 Inertial1_Rates_FO: 8 _DOFIMU1_FO + SG_ MstrTrgrSyncInrtl1Rte : 55|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1YawRteV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1YawRte : 36|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1RollRteV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1RollRte : 20|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1RteChksum : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1PitchRteV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial1PitchRte : 4|13@0- (0.024,0) [-98.304|98.28] "deg/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 312 Inertial2_Accel2_FO: 8 _DOFIMU2_FO + SG_ MstrTrigSyncInrtl22 : 55|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSns2AccFrm2Chksm : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2YawAccV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2YawAcc : 36|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2RollAccV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2RollAcc : 20|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2PtchAccV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr2PtchAcc : 4|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 306 Inertial1_Accel2_FO: 8 _DOFIMU1_FO + SG_ MstrTrigSyncInrtl12 : 55|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1AccelFrm2Chksm : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1YawAccV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1YawAcc : 36|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1RollAccV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1RollAcc : 20|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1PtchAccV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1PtchAcc : 4|13@0- (0.024,0) [-98.304|98.28] "deg/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 310 Inertial2_Accel1_FO: 8 _DOFIMU2_FO + SG_ MstrTrigSyncInrtl21 : 7|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2VertAccV : 34|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2VertAcc : 33|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2LonAccV : 2|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2LonAcc : 1|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2LatAccV : 18|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ Inertial2LatAcc : 17|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ IntlSnsr2AcelFm1Chksm : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 304 Inertial1_Accel1_FO: 8 _DOFIMU1_FO + SG_ MstrTrigSyncInrtl11 : 7|5@0+ (1,0) [0|31] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1VertAccV : 34|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1VertAcc : 33|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1LonAccV : 2|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1LonAcc : 1|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1LatAccV : 18|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InrtlSnsr1LatAcc : 17|10@0- (0.0625,0) [-32|31.9375] "m/s^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ IntlSnsr1AcelFm1Chksm : 50|11@0+ (1,0) [0|2047] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 356 Map_Pos_Correction_FO: 4 EOCM2A_K1_FO + SG_ LongErrPstn : 7|8@0- (0.5,0) [-64|63.5] "m" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ LatErrPstn : 15|8@0- (0.5,0) [-64|63.5] "m" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ PstnErrChcksm : 18|11@0+ (1,0) [0|2047] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ PstnErrARC : 20|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 354 Map_Retrans_Request_FO: 1 EOCM2A_K1_FO + SG_ HrznPrvdRstRq : 2|1@0+ (1,0) [0|1] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ ADASISRwDtMplxdCycCnt : 7|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ ADASISMsgTypRetrans : 5|3@0+ (1,0) [0|7] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 352 Map_Path_Correction_FO: 6 EOCM2A_K1_FO + SG_ ExptNxtTrnstnDir : 37|3@0+ (1,0) [0|7] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ MstProbLnV : 15|1@0+ (1,0) [0|1] "" AMM_FO + SG_ MstProbLn : 14|5@0+ (1,0) [0|31] "" AMM_FO + SG_ PathCrtnChcksm : 34|11@0+ (1,0) [0|2047] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ PathCrtnARC : 4|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ EgoLnCurvV : 2|1@0+ (1,0) [0|1] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ EgoLnCurv : 23|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m^2" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ VehLnStatV : 1|1@0+ (1,0) [0|1] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ VehLnStatConf : 6|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ VehLnStat : 9|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ ExptNxtTransDirV : 0|1@0+ (1,0) [0|1] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ ExptNxtTrnstnDirConf : 39|2@0+ (1,0) [0|3] "" AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 264 Inertial_Trigger_FO: 1 EOCM2A_K1_FO + SG_ InrtlSnsrMstrTrgrSync : 7|5@0+ (1,0) [0|31] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,_DOFIMU2_FO,_DOFIMU1_FO + +BO_ 1156 SSID_AMM_2_FO: 8 EOCM2A_K1_FO + SG_ WiFiSSIDDgts9to16_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1155 SSID_AMM_1_FO: 8 EOCM2A_K1_FO + SG_ WiFiSSIDDgts1to8_Mp : 7|64@0+ (1,0) [0|0] "" EOCM2B_K1_FO,AMM_FO + +BO_ 1927 DTC_Triggered_787_FO: 7 DMS_FO + SG_ DTCI_CodeSupported_787 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_787 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_787 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_787 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_787 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_787 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_787 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_787 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_787 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_787 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_787 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_787 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_787 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_787 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_787 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_787 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_787 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_787 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_787 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_787 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1926 DTC_Triggered_786_FO: 7 AMM_FO + SG_ DTCI_CodeSupported_786 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_786 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_786 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_786 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_786 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_786 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_786 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_786 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_786 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_786 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_786 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_786 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_786 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_786 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_786 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_786 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_786 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_786 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_786 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_786 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1928 DTC_Triggered_788_FO: 7 _DOFIMU1_FO + SG_ DTCI_CodeSupported_788 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_788 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_788 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_788 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_788 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_788 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_788 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_788 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_788 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_788 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_788 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_788 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_788 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_788 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_788 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_788 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_788 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_788 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_788 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_788 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1929 DTC_Triggered_789_FO: 7 _DOFIMU2_FO + SG_ DTCI_CodeSupported_789 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_789 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_789 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_789 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_789 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_789 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_789 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_789 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_789 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_789 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_789 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_789 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_789 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_789 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_789 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_789 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_789 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_789 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_789 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_789 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1352 UUDT_Resp_From_6DOFIMU2_FO: 8 _DOFIMU2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 588 USDT_Req_to_EOCM2B_K1_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2B_K1_FO + +BO_ 1356 UUDT_Resp_From_EOCM2B_K1_FO: 8 EOCM2B_K1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1612 USDT_Resp_From_EOCM2B_K1_FO: 8 EOCM2B_K1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1616 USDT_Resp_From_EOCM2A_IMX6_FO: 8 EOCM2A_IMX6_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1360 UUDT_Resp_From_EOCM2A_IMX6_FO: 8 EOCM2A_IMX6_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 592 USDT_Req_to_EOCM2A_IMX6_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2A_IMX6_FO + +BO_ 1610 USDT_Resp_From_EOCM2A_K1_FO: 8 EOCM2A_K1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1354 UUDT_Resp_From_EOCM2A_K1_FO: 8 EOCM2A_K1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 586 USDT_Req_to_EOCM2A_K1_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2A_K1_FO + +BO_ 1925 DTC_Triggered_785_FO: 7 NVS_FO + SG_ DTCI_CodeSupported_785 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_785 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_785 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_785 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_785 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_785 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_785 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_785 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_785 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_785 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_785 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_785 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_785 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_785 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_785 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_785 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_785 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_785 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_785 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_785 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1859 VIN_Digits_10_to_17_FO: 8 EOCM_F_FO + SG_ VehIdNmDig10_17 : 7|64@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + +BO_ 1857 VIN_Digits_2_to_9_FO: 8 EOCM_F_FO + SG_ VehIdNmDig2_9 : 7|64@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + +BO_ 771 Outside_Air_Temperature_FO: 2 EOCM_F_FO + SG_ OtsAirTmpCrValV : 0|1@0+ (1,0) [0|1] "" NVS_FO + SG_ OtsAirTmpCrVal : 15|8@0+ (0.5,-40) [-40|87.5] "deg C" NVS_FO + +BO_ 777 Night_Vision_System_Ped_FO: 1 NVS_FO + SG_ NVSysStat : 3|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ NVSysPedWrnIndReq : 7|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ NVSysPedDetCsCrStVal : 5|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ NVSysPedDetCstStAvl : 0|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 607 USDT_Req_to_NVS_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" NVS_FO + +BO_ 1631 USDT_Resp_From_NVS_FO: 8 NVS_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1375 UUDT_Resp_From_NVS_FO: 8 NVS_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1540 ADAS_Position_FO: 8 AMM_FO + SG_ AdvDrAstMpLatOffst : 40|9@0+ (1,-256) [-256|255] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnIndx : 63|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnCnf : 61|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPsnIdxCrLn : 58|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnPthIndx : 46|6@0+ (1,0) [0|63] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnProb : 31|5@0+ (3.333,0) [0|103.323] "%" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnCycCnt : 26|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnAge : 24|9@0+ (5,0) [0|2555] "ms" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnRelHd : 23|8@0+ (1.417,0) [0|361.335] "deg" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnMsgTyp : 7|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + SG_ AdvDrAstMpPstnOfst : 4|13@0+ (1,0) [0|8191] "m" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO + +BO_ 1608 USDT_Resp_From_6DOFIMU2_FO: 8 _DOFIMU2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 871 LGT_ObjectDetect_Info_8_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk8 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk8 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk8 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk8 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev8 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev8 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev8 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk8 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk8 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk8 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 870 LGT_ObjectDetect_Info_7_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk7 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk7 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk7 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk7 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev7 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev7 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev7 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk7 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk7 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk7 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 869 LGT_ObjectDetect_Info_6_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk6 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk6 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk6 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk6 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev6 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev6 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev6 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk6 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk6 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk6 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 868 LGT_ObjectDetect_Info_5_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk5 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk5 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk5 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk5 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev5 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev5 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev5 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk5 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk5 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk5 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 867 LGT_ObjectDetect_Info_4_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk4 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk4 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk4 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk4 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev4 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev4 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev4 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk4 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk4 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk4 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 866 LGT_ObjectDetect_Info_3_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk3 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk3 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk3 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk3 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev3 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev3 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev3 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk3 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk3 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk3 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 865 LGT_ObjectDetect_Info_2_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk2 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk2 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk2 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk2 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev2 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev2 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev2 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk2 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBObjDirTrk2 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk2 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 864 LGT_ObjectDetect_Info_1_FO: 8 VIS2_FO + SG_ GFHBFwVsnWidthTrk1 : 62|7@0+ (0.1,0) [0|12.7] "deg" EOCM_F_FO + SG_ GFHBFwVsnVertPosTrk1 : 53|6@0+ (0.25,-3) [-3|12.75] "deg" EOCM_F_FO + SG_ GFHBFwVsnRelLaneTrk1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnAzmthRtTrk1 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ GFHBFwVsnCnfdncTrk1 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnRngTrkRev1 : 16|12@0+ (0.2,0) [0|819] "m" EOCM_F_FO + SG_ GFHBFwVsnAzmthTrkRev1 : 10|10@0- (0.05,0) [-25.6|25.55] "deg" EOCM_F_FO + SG_ GFHBFVsnObjTypTrkRev1 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ GFHBObjDirTrk1 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ GFHBFwVsnMesStatTrk1 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ GFHBFwVsnObjIDTrk1 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1915 DTC_Triggered_77B_FO: 7 VIS_FO + SG_ DTCI_DTCFaultType_77B : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CodeSupported_77B : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_77B : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_77B : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_77B : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_77B : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_77B : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_77B : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_77B : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_77B : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_77B : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_77B : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_77B : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_77B : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_77B : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_77B : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_77B : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_77B : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_77B : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_77B : 7|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1923 DTC_Triggered_783_FO: 7 RSRR_FO + SG_ DTCI_WrnIndRqdSt_783 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_783 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_783 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_783 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_783 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_783 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCTriggered_783 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCSource_783 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_783 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCFaultType_783 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFailType_783 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CurrentStatus_783 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CodeSupported_783 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_783 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_783 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_783 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_783 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_783 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_783 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_783 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1924 DTC_Triggered_784_FO: 7 RRSRR_FO + SG_ DTCI_HistStat_784 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_784 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_784 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_784 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_784 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_784 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_784 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_784 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_784 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_784 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_784 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_784 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_784 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CodeSupported_784 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CurrentStatus_784 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCFailType_784 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFaultType_784 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_784 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCSource_784 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCTriggered_784 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1922 DTC_Triggered_782_FO: 7 RFSRR_FO + SG_ DTCI_WrnIndRqdSt_782 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_782 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_782 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_782 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_782 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_782 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_782 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_782 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_782 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_782 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_782 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_782 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_782 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCTriggered_782 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCSource_782 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_782 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCFaultType_782 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFailType_782 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CurrentStatus_782 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_CodeSupported_782 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1920 DTC_Triggered_780_FO: 7 LRR_FO + SG_ DTCI_CurrentStatus_780 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_780 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_780 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_780 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_780 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_780 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_780 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_780 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_780 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_780 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_780 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_780 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_780 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_780 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCTriggered_780 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCSource_780 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_780 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCFaultType_780 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFailType_780 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CodeSupported_780 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1921 DTC_Triggered_781_FO: 7 LFSRR_FO + SG_ DTCI_CurrentStatus_781 : 41|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_WrnIndRqdSt_781 : 47|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused7_781 : 1|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused6_781 : 2|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused5_781 : 3|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused4_781 : 4|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused3_781 : 5|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused2_781 : 6|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCIUnused1_781 : 7|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdPwrUpSt_781 : 45|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstNPsdCdClrdSt_781 : 42|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldPwrUpSt_781 : 46|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_TstFldCdClrdStat_781 : 43|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_HistStat_781 : 44|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCTriggered_781 : 0|1@0+ (1,0) [0|1] "" TestTool_FO + SG_ DTCI_DTCSource_781 : 15|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCNumber_781 : 23|16@0+ (1,0) [0|65535] "" TestTool_FO + SG_ DTCI_DTCFaultType_781 : 55|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_DTCFailType_781 : 39|8@0+ (1,0) [0|255] "" TestTool_FO + SG_ DTCI_CodeSupported_781 : 40|1@0+ (1,0) [0|1] "" TestTool_FO + +BO_ 1034 Curvature_Right_Line_FO: 7 VIS2_FO + SG_ CRL_Cnfdnc : 50|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CRL_ViewRng : 33|15@0+ (0.0039064,0) [0|128.0010088] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CRL_CoefdA : 17|16@0- (3.6622E-009,0) [-0.0001200029696|0.0001199993074] "1/m^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CRL_CoefA : 1|16@0- (6.1036E-007,0) [-0.02000027648|0.01999966612] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 1033 Curvature_Left_Line_FO: 7 VIS2_FO + SG_ CLL_Cnfdnc : 50|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CLL_ViewRng : 33|15@0+ (0.0039064,0) [0|128.0010088] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CLL_CoefdA : 17|16@0- (3.6622E-009,0) [-0.0001200029696|0.0001199993074] "1/m^2" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ CLL_CoefA : 1|16@0- (6.1036E-007,0) [-0.02000027648|0.01999966612] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + +BO_ 1365 UUDT_Resp_From_VIS2_FO: 8 VIS2_FO + SG_ DgnInf_OBJ555 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1621 USDT_Resp_From_VIS2_FO: 8 VIS2_FO + SG_ DgnInf_OBJ655 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1094 F_Vision_Obj_Track_12: 8 VIS2_FO + SG_ FwdVsnObjTypTr12Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnAzmthTrk12Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk12Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FVisionWidthTrk12 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FVisionMeasStatTrk12 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnVertPosTrk12 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FVisionRelLaneTrk12 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk12 : 34|11@0- (0.125,0) [-128|127.875] "deg/sec" EOCM_F_FO + SG_ FVisionConfTrk12 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ ObjDirTrk12 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk12 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk12 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1093 F_Vision_Obj_Track_11: 8 VIS2_FO + SG_ FwdVsnObjTypTr11Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnAzmthTrk11Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk11Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FVisionWidthTrk11 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FVisionMeasStatTrk11 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnVertPosTrk11 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FVisionRelLaneTrk11 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk11 : 34|11@0- (0.125,0) [-128|127.875] "deg/sec" EOCM_F_FO + SG_ FVisionConfTrk11 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ ObjDirTrk11 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk11 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk11 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1100 F_Vision_Obj_Track_12_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT12Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk12 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk12 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk12 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk12 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr12 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk12 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo12 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1099 F_Vision_Obj_Track_11_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT11Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk11 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk11 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk11 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk11 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr11 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk11 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo11 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1098 F_Vision_Obj_Track_10_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT10Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk10 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk10 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk10 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk10 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr10 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk10 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo10 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1097 F_Vision_Obj_Track_9_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT9Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk9 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk9 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk9 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk9 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr9 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk9 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo9 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1096 F_Vision_Obj_Track_8_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT8Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk8 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk8 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk8 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk8 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr8 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk8 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo8 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1095 F_Vision_Obj_Track_7_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT7Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk7 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk7 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk7 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk7 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr7 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk7 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo7 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 863 F_Vision_GFHB_Data_FO: 8 VIS2_FO + SG_ RgDtLgtSrcHrtAngl : 49|10@0- (0.04,0) [-20.48|20.44] "deg" EOCM_F_FO + SG_ RgDtLgtSrcHrtAngVcty : 55|6@0- (1,0) [-32|31] "deg/sec" EOCM_F_FO + SG_ LfDtLgtSrcHrtAngl : 33|10@0- (0.04,0) [-20.48|20.44] "deg" EOCM_F_FO + SG_ LfDtLgtSrcHrtAnVcty : 39|6@0- (1,0) [-32|31] "deg/sec" EOCM_F_FO + SG_ AdvWthrStat : 25|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ DtctdLghtSrcDstnc : 22|7@0+ (10,0) [0|1270] "m" EOCM_F_FO + SG_ DtctdLghtSrcVrtclAngl : 1|10@0- (0.04,0) [-20.48|20.44] "deg" EOCM_F_FO + SG_ IntLghtRngAct : 2|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ DtctdLghtSrcDstncV : 3|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ TwnDtctnSts : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ DtctdLghtSrcDrvngDrctn : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 862 LGT_ControlHighBeamGlare_FO: 2 VIS2_FO + SG_ FwdCamSysOpStat : 10|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ EnvIllum : 2|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RdTyp : 5|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ AutoHgBmSts : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1068 F_Vision_Obj_Track_6_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT6Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk6 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk6 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk6 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk6 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr6 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk6 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo6 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1067 F_Vision_Obj_Track_5_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT5Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk5 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk5 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk5 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk5 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr5 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk5 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo5 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1066 F_Vision_Obj_Track_4_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT4Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk4 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk4 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk4 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk4 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr4 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk4 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo4 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1065 F_Vision_Obj_Track_3_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT3Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk3 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk3 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk3 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk3 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr3 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk3 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo3 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1064 F_Vision_Obj_Track_2_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT2Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjAgeTrk2 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk2 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk2 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk2 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr2 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk2 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo2 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1063 F_Vision_Obj_Track_1_B: 8 VIS2_FO + SG_ FwVsnCinCoutPotT1Rev : 5|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnObjSclChgTrk1 : 15|16@0- (0.0002,0) [-6.5536|6.5534] "pix/sec" EOCM_F_FO + SG_ FwdVsnObjAgeTrk1 : 62|7@0+ (1,0) [0|127] "" EOCM_F_FO + SG_ FwdVsnLongVlctyTrk1 : 42|12@0- (0.0625,0) [-128|127.9375] "m/sec" EOCM_F_FO + SG_ FwdVsnLatOfstTrk1 : 36|10@0- (0.125,0) [-64|63.875] "m" EOCM_F_FO + SG_ FwdVsnBrkLtStatTrk1 : 38|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FwdVsnTrnSigStatTr1 : 25|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FrtVsnBrstIDAddInfo1 : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1151 Long_Range_Radar_add_Info_5_FO: 8 LRR_FO + SG_ FrtRdrRdEdgLtLatRdEdgDst : 63|8@0- (0.1,0) [-12.8|12.7] "m/m" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtPrvDst : 5|4@0+ (10,0) [0|150] "" EOCM_F_FO + SG_ FrtRdrRdEdgLtTanHdgAng : 15|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtV : 48|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtGradV : 0|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtGrad : 39|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/(m*sec)" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvtConf : 55|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM_F_FO + SG_ FrtRdrRdEdgLtCrvt : 23|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM_F_FO + SG_ FrtRdrRdEdgLtTanHdgAngV : 1|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAddInfo5BurstID : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1150 Long_Range_Radar_add_Info_4_FO: 8 LRR_FO + SG_ FrtRdrRdEdgRtLatRdEdgDst : 63|8@0- (0.1,0) [-12.8|12.7] "m/m" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtPrvDst : 5|4@0+ (10,0) [0|150] "" EOCM_F_FO + SG_ FrtRdrRdEdgRtTanHdgAngV : 1|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgRtTanHdgAng : 15|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtV : 48|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtGradV : 0|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtGrad : 39|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/(m*sec)" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvtConf : 55|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM_F_FO + SG_ FrtRdrRdEdgRtCrvt : 23|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM_F_FO + SG_ FLRRAddInfo4BurstID : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1088 F_Vision_Obj_Header_2: 8 VIS2_FO + SG_ FrntVsnInPthVehBrkNwSt : 35|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FrntVsnClostPedBrkNwSt : 39|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FrntVsnClostPedObjID : 29|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FrntVsnClostPedAlrtNwFlg : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrntVsnClostPedNotftnFlg : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrntVsnInPthVehAlrtNwFlg : 2|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnVldTgtNum2 : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FrtVsnTmStmp2V : 31|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnTmStmp2 : 10|11@0+ (1,0) [0|2047] "" EOCM_F_FO + SG_ FrtVsnRollCnt2 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FrtVsnBrstChksum2 : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + +BO_ 854 F_Vision_Environment_7: 3 VIS2_FO + SG_ FwdVsnCnstrctAreaDst : 13|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnCnstrctZnDet : 15|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnEgoVehLnPos : 17|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnRdTypDet : 9|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnTunnlDetd : 23|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ FwdVsnTunnlDst : 21|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBrstID5 : 1|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 853 F_Vision_Environment_6: 8 VIS2_FO + SG_ LnMrkg4LnSnsLnHdngTngtV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnHdngTngt : 23|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnDstV : 56|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnDst : 15|8@0- (0.1,0) [-12.8|12.7] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnCrvtV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnCrvtGradV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnCrvtGrad : 47|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/(m*sec)" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnSnsLnCrvt : 31|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnQltyConfLvl : 63|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnMrkrTyp : 4|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBrstID4 : 1|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 852 F_Vision_Environment_5: 8 VIS2_FO + SG_ LnMrkg3LnSnsLnHdngTngtV : 7|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnHdngTngt : 23|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnDstV : 56|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnDst : 15|8@0- (0.1,0) [-12.8|12.7] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnCrvtV : 6|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnCrvtGradV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnCrvtGrad : 47|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/(m*sec)" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnSnsLnCrvt : 31|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnQltyConfLvl : 63|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnMrkrTyp : 4|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBrstID3 : 1|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 602 USDT_Req_to_RRSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RRSRR_FO + +BO_ 1626 USDT_Resp_From_RRSRR: 8 RRSRR_FO + SG_ DgnInf_OBJ65A : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1370 UUDT_Resp_From_RRSRR: 8 RRSRR_FO + SG_ DgnInf_OBJ55A : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1536 RR_SRR_Trace_data: 8 RRSRR_FO + SG_ RRSRRYear : 7|8@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RRSRRSerialNmbr : 39|32@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RRSRRJulianDate : 15|24@0+ (1,0) [0|0] "" EOCM_F_FO + +BO_ 1210 RR_SRR_Object_Track10: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth10 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate10 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange10 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange10 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID10 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation10 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp10 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth10 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1209 RR_SRR_Object_Track9: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth9 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate9 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange9 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange9 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID9 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation9 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp9 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth9 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1208 RR_SRR_Object_Track8: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth8 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate8 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange8 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange8 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID8 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation8 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp8 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth8 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1207 RR_SRR_Object_Track7: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth7 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate7 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange7 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange7 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID7 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation7 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp7 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth7 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1206 RR_SRR_Object_Track6: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth6 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate6 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange6 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange6 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID6 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation6 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp6 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth6 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1205 RR_SRR_Object_Track5: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth5 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate5 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange5 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange5 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID5 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation5 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp5 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth5 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 262 LHT_AutoHighBeamAssistStatus_FO: 5 EOCM_F_FO + SG_ NtVsnSysEnbld : 6|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + SG_ VehMovState : 5|3@0+ (1,0) [0|7] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + SG_ NVSysPedDetCstReq : 2|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO + SG_ StrWhAngV : 8|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO,VIS_FO + SG_ StrWhAngMsk : 9|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ StrWhAng : 23|16@0- (0.0625,0) [-2048|2047.9375] "deg" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO,VIS_FO + SG_ RtTrnLmpAtv : 13|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ MpDataAvlbl : 0|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ LftTrnLmpAtv : 11|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ HdlmpBmSelectStat : 33|2@0+ (1,0) [0|3] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ BldUpArDet : 14|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ FrFogLmpsAct : 15|1@0+ (1,0) [0|1] "" EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,NVS_FO,VIS_FO + +BO_ 309 LHT_CameraObjConfirmation_FO: 1 VIS_FO + SG_ HiBmRecmnd : 1|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ CtLghtDet : 0|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 2034 CCP_Data_Transmission_Object_FO: 8 VIS2_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 2032 CCP_Command_Receive_Object_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" VIS2_FO + +BO_ 1362 F_Vis_Obj_Conf_CPS_1B: 8 EOCM_F_FO + SG_ FObjConfCPSTrkObjectIDB : 7|6@0+ (1,0) [0|63] "" VIS_FO + SG_ CPSVisConfLonPos1 : 20|12@0- (0.125,0) [-256|255.875] "m" VIS_FO + SG_ CPSVisConfLatPos1 : 15|10@0- (0.125,0) [-64|63.875] "m" VIS_FO + SG_ CPSVisConfChecksum : 50|11@0+ (1,0) [0|2047] "" VIS_FO + SG_ FObjConfCPSTrkRangeRate : 45|11@0- (0.125,0) [-128|127.875] "m/s" VIS_FO + SG_ CPSConfTimeStamp : 24|11@0+ (1,0) [0|2047] "ms" VIS_FO + SG_ CPSConfTimeStampV : 21|1@0+ (1,0) [0|1] "" VIS_FO + SG_ FObjConfCPSRollingTrkCnt : 1|2@0+ (1,0) [0|3] "" VIS_FO + +BO_ 1413 TOS_ACC_IDS: 5 EOCM_F_FO + SG_ TOS_ACC_IDSRollCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ TOS_ACC_IDSFuncState : 5|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ TOS_ACC_ID1 : 3|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID2 : 13|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID3 : 23|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID4 : 17|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID5 : 27|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ TOS_ACC_ID6 : 37|6@0+ (1,0) [0|63] "" Dummy_FO + +BO_ 1412 F_ACC_Target: 8 EOCM_F_FO + SG_ FACCTOSRollCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FACCTOSFuncState : 5|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FACCTOSLongPos : 3|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FACCTOSLatPos : 23|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FACCTOSMeasStat : 28|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FACCTOSLongVel : 26|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FACCTOSTrgtDecelFlg : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FACCTOSDynProp : 46|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FACCTOSLatVel : 42|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FACCTOSRelLane : 63|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FACCTOSHiThrtID : 61|6@0+ (1,0) [0|63] "" Dummy_FO + +BO_ 1409 F_CPS_TOS_B: 8 EOCM_F_FO + SG_ CPSTOSObjType : 7|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ CPSTOSHiThrtPriNo : 60|5@0+ (1,0) [0|31] "" Dummy_FO + SG_ CPSTOSRelLongAcc : 53|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ CPSTOSConfAsmt : 21|12@0+ (1,0) [0|4095] "" Dummy_FO + SG_ CPSTOSNumCycTrkd : 4|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ CPSTOSTimeToColl : 1|12@0+ (0.025,0) [0|102.375] "s" Dummy_FO + SG_ CPSTOSClosestInPthVehRng : 47|10@0+ (0.25,0) [0|255.75] "m" Dummy_FO + SG_ CPSTOSClosestInPthObID : 37|6@0+ (1,0) [0|63] "m" Dummy_FO + SG_ CPSTOSMeasStat : 39|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ CPSTOSFuncState : 25|2@0+ (1,0) [0|3] "" Dummy_FO + +BO_ 1408 F_CPS_TOS_A: 8 EOCM_F_FO + SG_ CPSTOSLongPos : 7|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ CPSTOSLatPos : 11|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ CPSTOSLongVel : 16|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ CPSTOSDynProp : 37|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ CPSTOSLatVel : 34|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ CPSTOSARelLane : 63|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ CPSTOSHiThrtID : 61|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ CPSTOSHighestThreatObAsmt : 55|8@0+ (1,0) [0|255] "" Dummy_FO + +BO_ 1344 FLPEstimate: 8 EOCM_F_FO + SG_ FLPRollCount : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ NewLaneIndex : 5|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ VehPathInOK : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LaneSnsInOK : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ MapInOK : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FWDObjFusInOK : 0|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LngthFrstSeg : 15|4@0+ (10,0) [0|150] "m" Dummy_FO + SG_ LngthScndSeg : 11|4@0+ (10,0) [0|150] "m" Dummy_FO + SG_ CurvFrstSeg : 23|13@0- (5E-005,0) [-0.2048|0.20475] "1/m" Dummy_FO + SG_ CurvScndSeg : 26|3@0- (0.001,0) [-0.004|0.003] "1/m" Dummy_FO + SG_ OffstLaneCntr : 39|8@0- (0.05,0) [-6.4|6.35] "m" Dummy_FO + SG_ TngntLaneHead : 47|8@0- (0.002,0) [-0.256|0.254] "m/m" Dummy_FO + SG_ LaneWidth : 55|8@0+ (0.05,0) [0|12.75] "m" Dummy_FO + SG_ FLPDataTimeStampV : 63|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FLPDataTimeStamp : 62|7@0+ (16,0) [0|2032] "ms" Dummy_FO + +BO_ 770 F_Fwd_Collision_Alert: 8 EOCM_F_FO + SG_ Vpath_Accel : 51|11@0- (0.125,0) [-128|127.875] "m/s^2" NVS_FO,Dummy_FO + SG_ FCA_Ra : 7|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FCA_Range : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FCA_AlertLevel : 44|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FCA_Alert_Sup : 31|16@0+ (1,0) [0|65535] "" Dummy_FO + SG_ FCAStatus : 46|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FCA_VehAhead : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCA_CPS_Alert : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCAChime : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCADiagOK : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ NBSMS_Alert : 55|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1601 USDT_Resp_From_VIS: 8 VIS_FO + SG_ DgnInf_OBJ641 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1606 USDT_Resp_From_RFSRR: 8 RFSRR_FO + SG_ DgnInf_OBJ646 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1603 USDT_Resp_From_LFSRR: 8 LFSRR_FO + SG_ DgnInf_OBJ643 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1602 USDT_Resp_From_LRR: 8 LRR_FO + SG_ DgnInf_OBJ642 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1625 USDT_Resp_From_RSRR: 8 RSRR_FO + SG_ DgnInf_OBJ644 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1611 USDT_Resp_From_FEOCM_FO: 8 EOCM_F_FO + SG_ DgnInf_OBJ64B : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 768 F_Smgr_Vehicle_Motion: 8 EOCM_F_FO + SG_ SmgrMotRollAngle : 44|10@0- (0.1,0) [-51.2|51.1] "deg" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotRollAngleV : 0|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotChecksum : 50|11@0+ (1,0) [0|2047] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotPitchAngle : 39|11@0- (0.1,0) [-102.4|102.3] "deg" CIPM_FO,NVS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotPitchAngleV : 1|1@0+ (1,0) [0|1] "" CIPM_FO,NVS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotLongSpeedV : 2|1@0+ (1,0) [0|1] " " CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotLongSpeed : 18|11@0- (0.1,0) [-102.4|102.3] "m/s" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotYawRate : 14|12@0- (0.05,0) [-102.4|102.35] "deg/s" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotYawRateV : 15|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + SG_ SmgrMotRollingCnt : 4|2@0+ (1,0) [0|3] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS_FO + +BO_ 1350 UUDT_Resp_From_RFSRR: 8 RFSRR_FO + SG_ DgnInf_OBJ546 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1369 UUDT_Resp_From_RSRR: 8 RSRR_FO + SG_ DgnInf_OBJ544 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1347 UUDT_Resp_From_LFSRR: 8 LFSRR_FO + SG_ DgnInf_OBJ543 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1346 UUDT_Resp_From_LRR: 8 LRR_FO + SG_ DgnInf_OBJ542 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1345 UUDT_Resp_From_VIS: 8 VIS_FO + SG_ DgnInf_OBJ541 : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 579 USDT_Req_to_LFSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LFSRR_FO + +BO_ 577 USDT_Req_to_VIS: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" VIS_FO + +BO_ 578 USDT_Req_to_LRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LRR_FO + +BO_ 582 USDT_Req_to_RFSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RFSRR_FO + +BO_ 601 USDT_Req_to_RSRR: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RSRR_FO + +BO_ 1355 UUDT_Resp_From_FEOCM_FO: 8 EOCM_F_FO + SG_ DgnInf_OBJ54B : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 587 USDT_Req_to_FEOCM_obj: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2A_K2_FO,EOCM_F_FO + +BO_ 784 Body_Info_FOB: 6 EOCM_F_FO + SG_ StrgColUpDwnPos : 39|8@0+ (1,0) [0|255] "" DMS_FO + SG_ CPMAPINFO4 : 47|1@0+ (1,0) [0|1] "" DMS_FO + SG_ StrgColInOutPos : 31|8@0+ (1,0) [0|255] "" DMS_FO + SG_ StrgColCommsFlt : 19|2@0+ (1,0) [0|3] "" DMS_FO + SG_ DrDoorOpenSwActV : 16|1@0+ (1,0) [0|1] "" DMS_FO + SG_ DrDoorOpenSwAct : 17|1@0+ (1,0) [0|1] "" DMS_FO + SG_ DrvWndPosStat : 22|3@0+ (1,0) [0|7] "" CIPM_FO,DMS_FO,VIS2_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ InterLghtStat : 23|1@0+ (1,0) [0|1] "" CIPM_FO,DMS_FO,VIS2_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvrHndsOnWhlZn3 : 13|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,DMS_FO,VIS2_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ DrvrHndsOnWhlZn2 : 14|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,VIS2_FO + SG_ DrvrHndsOnWhlZn1 : 15|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,VIS2_FO + SG_ WSWshSwAtv : 11|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,VIS_FO,VIS2_FO + SG_ SysPwrMdV : 8|1@0+ (1,0) [0|1] "" NVS_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO,LRSRR_FO,CIPM_FO,_DOFIMU2_FO,_DOFIMU1_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,VIS2_FO + SG_ SysPwrMd : 10|2@0+ (1,0) [0|3] "" NVS_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO,LRSRR_FO,CIPM_FO,_DOFIMU2_FO,_DOFIMU1_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,VIS2_FO + SG_ WSWprAct : 2|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ RtLwBmFld : 4|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ OtsdAmbtLtLvlStatV : 5|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ OtsdAmbtLtLvlStat : 7|2@0+ (1,0) [0|3] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ LowBmAct : 1|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ LftLwBmFld : 3|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ HighBmAct : 0|1@0+ (1,0) [0|1] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,DMS_FO,AMM_FO,NVS_FO,VIS_FO,VIS2_FO + SG_ TrStLgMdAtv : 12|1@0+ (1,0) [0|1] "" CIPM_FO,NVS_FO,RRSRR_FO,LRSRR_FO,_DOFIMU2_FO,_DOFIMU1_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,LRR_FO,RFSRR_FO,LFSRR_FO,RSRR_FO,VIS_FO,VIS2_FO + +BO_ 1539 RF_SRR_Trace_Data: 8 RFSRR_FO + SG_ RFSRRYear : 7|8@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RFSRRSerialNmbr : 39|32@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RFSRRJulianDate : 15|24@0+ (1,0) [0|0] "" EOCM_F_FO + +BO_ 776 F_Vehicle_Path_Data_2: 7 EOCM_F_FO + SG_ Vpath_Data2ModeInfo : 44|2@0+ (1,0) [0|3] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath2_Checksum : 42|11@0+ (1,0) [0|2047] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RFSRR_FO,LFSRR_FO,RSRR_FO,LRR_FO + SG_ Vpath_Data2RollCnt : 46|2@0+ (1,0) [0|3] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2YawRateV : 2|1@0+ (1,0) [0|1] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,NVS_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2LongVelV : 1|1@0+ (1,0) [0|1] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,NVS_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2LatVelV : 47|1@0+ (1,0) [0|1] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2TravlDirctn : 4|2@0+ (1,0) [0|3] "" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2LongVel : 15|12@0- (0.0625,0) [-128|127.9375] "m/s" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,NVS_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2YawRate : 19|12@0- (0.0625,0) [-128|127.9375] "deg/s" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,NVS_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_Data2LatVel : 39|8@0- (0.05,0) [-6.4|6.35] "m/s" CIPM_FO,DMS_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + +BO_ 161 F_Master_Time_Sync: 7 EOCM_F_FO + SG_ FTimeSyncMstrChksm : 35|12@0+ (1,0) [0|4095] "" AMM_FO,CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ FTimeSyncMstrClock : 7|32@0+ (1,0) [0|4294967295] "ms" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ SensorModeCmdLRR : 39|3@0+ (1,0) [0|7] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ SensorModeCmdSRR : 50|3@0+ (1,0) [0|7] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ SensorModeCmdFCamera : 53|3@0+ (1,0) [0|7] "" CIPM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ FTimeSyncMstrClockV : 36|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,LRR_FO,RFSRR_FO,LFSRR_FO + +BO_ 774 F_Vehicle_Path_Estimate: 8 EOCM_F_FO + SG_ Vpath_RollingCount : 7|2@0+ (1,0) [0|3] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_TrnCtrLngOfstV : 1|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,LRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LFSRR_FO + SG_ Vpath_Checksum : 50|11@0+ (1,0) [0|2047] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_TrnCtrLngOfst : 15|8@0- (0.1,0) [-12.8|12.7] "m" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,LRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LFSRR_FO + SG_ Vpath_TrnCtrLatOfst : 21|14@0- (1,0) [-8192|8191] "m" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,LRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LFSRR_FO + SG_ Vpath_Curvature : 39|16@0- (1E-005,0) [-0.32768|0.32767] "1/m" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,RSRR_FO,RFSRR_FO,LRR_FO,LFSRR_FO + SG_ Vpath_CurvatureV : 0|1@0+ (1,0) [0|1] "" CIPM_FO,AMM_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,VIS2_FO,RRSRR_FO,VIS_FO,LRR_FO,RSRR_FO,RFSRR_FO,LFSRR_FO + +BO_ 848 F_Vision_Environment: 8 VIS_FO + SG_ FwdVsnEnvIllum : 37|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTngtOfHdngLnRtV : 1|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTngtOfHdngLnRt : 31|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnChngStatus : 39|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseRollingCount : 7|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseSystemOK : 4|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSnsLLnPosValid : 2|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSenseDistToLLnEdge : 14|7@0+ (0.05,0) [0|6.35] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsRLnPosValid : 0|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsDistToRLnEdge : 22|7@0+ (0.05,0) [0|6.35] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseTimeStampV : 5|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseTimeStamp : 34|11@0+ (1,0) [0|2047] "ms" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LaneSenseSystemOKV : 3|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 849 F_Vision_Environment_2: 8 VIS_FO + SG_ LnSnsLatVRelToRgtMrkg : 23|8@0- (0.02,0) [-2.56|2.54] "m/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM_F_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO + SG_ LnSnsRtLnMrkgTypChgDst : 61|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsCrvtGrdntRtV : 63|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnMrkgWdthRt : 62|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsRtAnchrLn : 57|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLtAnchrLn : 56|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnCrvtrRghtV : 0|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnCrvtrRght : 47|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsCrvtGrdntRt : 31|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/rad/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBurstID : 2|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLatVRelToLftMrkg : 15|8@0- (0.02,0) [-2.56|2.54] "m/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 1184 R_SRR_Object_Header: 8 RSRR_FO + SG_ RSRRNumValidTargets : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ RSrrRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSRRModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTimeStampV : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSrrTimeStamp : 10|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ RSrrBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ RSRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnRllRt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnRllLt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRCANIDAddrsUnsbl : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RSRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1185 R_SRR_Object_Track1: 8 RSRR_FO + SG_ RSrrBurstID1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange1 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate1 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth1 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID1 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation1 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp1 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange1 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth1 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1186 R_SRR_Object_Track2: 8 RSRR_FO + SG_ RSrrBurstID2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange2 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate2 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth2 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID2 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation2 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp2 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange2 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth2 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1187 R_SRR_Object_Track3: 8 RSRR_FO + SG_ RSrrBurstID3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange3 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate3 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth3 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID3 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation3 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp3 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange3 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth3 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1188 R_SRR_Object_Track4: 8 RSRR_FO + SG_ RSrrBurstID4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange4 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate4 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth4 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID4 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation4 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp4 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange4 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth4 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1189 R_SRR_Object_Track5: 8 RSRR_FO + SG_ RSrrBurstID5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange5 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate5 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth5 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID5 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation5 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp5 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange5 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth5 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1190 R_SRR_Object_Track6: 8 RSRR_FO + SG_ RSrrBurstID6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange6 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate6 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth6 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID6 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation6 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp6 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange6 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth6 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1191 R_SRR_Object_Track7: 8 RSRR_FO + SG_ RSrrBurstID7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange7 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate7 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth7 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID7 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation7 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp7 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange7 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth7 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1192 R_SRR_Object_Track8: 8 RSRR_FO + SG_ RSrrBurstID8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange8 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate8 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth8 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID8 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation8 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp8 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange8 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth8 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1193 R_SRR_Object_Track9: 8 RSRR_FO + SG_ RSrrBurstID9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange9 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate9 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth9 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID9 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation9 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp9 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange9 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth9 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1194 R_SRR_Object_Track10: 8 RSRR_FO + SG_ RSrrBurstID10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkRange10 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RSrrTrkRRate10 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RSrrTrkAzimuth10 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RSrrTrkObjID10 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RSrrTrkObjElevation10 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkDynamProp10 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RSrrTrkMeasStatus10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RSrrTrkObsRange10 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RSrrTrkRawAzimuth10 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1410 RVB_TVR_Debug: 6 EOCM_F_FO + SG_ VBBrkRqActv : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ PATOSTTC : 37|12@0+ (0.025,0) [0|102.375] "s" Dummy_FO + SG_ BWTOSObjID : 27|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ BWTOSLonPstn : 23|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ VBSwInd : 10|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ VBBrkCtrlSt : 15|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ BrkPlsRqst : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBOpSt : 12|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ VBAccelOvrrd : 0|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBUnavail : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBFld : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBDisbld : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBEnbl : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VBBrkPrfReq : 5|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1216 LF_SRR_Object_Header: 8 LFSRR_FO + SG_ LFSRRNumValidTargets : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ LFSrrRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSRRModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTimeStampV : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSrrTimeStamp : 10|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ LFSrrBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ LFSRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnRllRt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnRllLt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRCANIDAddrsUnsbl : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ LFSRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1217 LF_SRR_Object_Track1: 8 LFSRR_FO + SG_ LFSrrBurstID1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange1 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate1 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth1 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID1 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation1 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp1 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkObsRange1 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth1 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1218 LF_SRR_Object_Track2: 8 LFSRR_FO + SG_ LFSrrBurstID2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange2 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate2 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth2 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID2 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation2 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp2 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkObsRange2 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth2 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1219 LF_SRR_Object_Track3: 8 LFSRR_FO + SG_ LFSrrBurstID3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange3 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate3 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth3 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID3 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation3 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp3 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkObsRange3 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth3 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1220 LF_SRR_Object_Track4: 8 LFSRR_FO + SG_ LFSrrBurstID4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange4 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate4 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkObsRange4 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrTrkAzimuth4 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID4 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation4 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp4 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth4 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1221 LF_SRR_Object_Track5: 8 LFSRR_FO + SG_ LFSrrTrkObsRange5 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange5 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate5 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth5 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID5 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation5 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp5 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth5 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1222 LF_SRR_Object_Track6: 8 LFSRR_FO + SG_ LFSrrTrkObsRange6 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange6 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate6 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth6 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID6 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation6 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp6 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth6 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1223 LF_SRR_Object_Track7: 8 LFSRR_FO + SG_ LFSrrTrkObsRange7 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange7 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate7 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth7 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID7 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation7 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp7 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth7 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1224 LF_SRR_Object_Track8: 8 LFSRR_FO + SG_ LFSrrTrkObsRange8 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange8 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate8 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth8 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID8 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation8 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp8 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth8 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1225 LF_SRR_Object_Track9: 8 LFSRR_FO + SG_ LFSrrTrkObsRange9 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange9 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate9 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth9 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID9 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation9 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp9 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth9 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1226 LF_SRR_Object_Track10: 8 LFSRR_FO + SG_ LFSrrTrkObsRange10 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ LFSrrBurstID10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRange10 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ LFSrrTrkRRate10 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ LFSrrTrkAzimuth10 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ LFSrrTrkObjID10 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ LFSrrTrkObjElevation10 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkDynamProp10 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ LFSrrTrkMeasStatus10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ LFSrrTrkRawAzimuth10 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + +BO_ 1232 RF_SRR_Object_Header: 8 RFSRR_FO + SG_ RFSRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnRllRt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnRllLt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRCANIDAddrsUnsbl : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RFSRRNumValidTargets : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ RFSrrRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSRRModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTimeStamp : 10|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ RFSrrBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ RFSrrTimeStampV : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1233 RF_SRR_Object_Track1: 8 RFSRR_FO + SG_ RFSrrTrkObsRange1 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth1 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange1 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate1 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth1 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID1 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation1 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp1 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1234 RF_SRR_Object_Track2: 8 RFSRR_FO + SG_ RFSrrTrkObsRange2 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth2 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange2 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate2 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth2 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID2 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation2 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp2 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1235 RF_SRR_Object_Track3: 8 RFSRR_FO + SG_ RFSrrTrkObsRange3 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth3 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange3 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate3 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth3 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID3 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation3 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp3 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1236 RF_SRR_Object_Track4: 8 RFSRR_FO + SG_ RFSrrTrkObsRange4 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth4 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange4 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate4 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth4 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID4 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation4 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp4 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1237 RF_SRR_Object_Track5: 8 RFSRR_FO + SG_ RFSrrTrkObsRange5 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth5 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange5 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate5 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth5 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID5 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation5 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp5 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1238 RF_SRR_Object_Track6: 8 RFSRR_FO + SG_ RFSrrTrkObsRange6 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth6 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange6 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate6 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth6 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID6 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation6 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp6 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1239 RF_SRR_Object_Track7: 8 RFSRR_FO + SG_ RFSrrTrkObsRange7 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth7 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange7 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate7 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth7 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID7 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation7 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp7 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1240 RF_SRR_Object_Track8: 8 RFSRR_FO + SG_ RFSrrTrkObsRange8 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth8 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange8 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate8 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth8 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID8 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation8 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp8 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1241 RF_SRR_Object_Track9: 8 RFSRR_FO + SG_ RFSrrTrkObsRange9 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth9 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange9 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate9 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth9 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID9 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation9 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp9 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1242 RF_SRR_Object_Track10: 8 RFSRR_FO + SG_ RFSrrTrkObsRange10 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RFSrrTrkRawAzimuth10 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RFSrrBurstID10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkRange10 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RFSrrTrkRRate10 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RFSrrTrkAzimuth10 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RFSrrTrkObjID10 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RFSrrTrkObjElevation10 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RFSrrTrkDynamProp10 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RFSrrTrkMeasStatus10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1056 F_Vision_Obj_Header: 6 VIS_FO + SG_ FVsnSnsrBlckd : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ ClstInPathVehObjID : 30|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FrtVsnFld : 6|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnIniDiagSuccCmpt : 5|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnSrvAlgnInPrcs : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FrtVsnUnvlbl : 7|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisionRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVISModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FVisionNumValidTrgts : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FVisionTimeStampV : 31|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisionTimeStamp : 10|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ VISBurstChecksum : 39|16@0+ (1,0) [0|65535] "" EOCM_F_FO + +BO_ 1057 F_Vision_Obj_Track_1: 8 VIS_FO + SG_ FwdVsnRngTrk1Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk1Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr1Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnVertPosTrk1 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FVisBurstIDTrk1 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk1 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk1 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk1 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk1 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ ObjDirTrk1 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1058 F_Vision_Obj_Track_2: 8 VIS_FO + SG_ FwdVsnVertPosTrk2 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk2Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk2Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ ObjDirTrk2 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FwdVsnObjTypTr2Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FVisBurstIDTrk2 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk2 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk2 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk2 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk2 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1059 F_Vision_Obj_Track_3: 8 VIS_FO + SG_ FwdVsnVertPosTrk3 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk3Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk3Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr3Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk3 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk3 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk3 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk3 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk3 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk3 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1060 F_Vision_Obj_Track_4: 8 VIS_FO + SG_ FwdVsnVertPosTrk4 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FVisionMeasStatTrk4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk4 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FwdVsnRngTrk4Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk4Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr4Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FVisBurstIDTrk4 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk4 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ ObjDirTrk4 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisionConfTrk4 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk4 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1061 F_Vision_Obj_Track_5: 8 VIS_FO + SG_ FwdVsnVertPosTrk5 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk5Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk5Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr5Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk5 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk5 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk5 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk5 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk5 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk5 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk5 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk5 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1062 F_Vision_Obj_Track_6: 8 VIS_FO + SG_ FwdVsnVertPosTrk6 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk6Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk6Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr6Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk6 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk6 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk6 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk6 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk6 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk6 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk6 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk6 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1538 LF_SRR_Trace_Data: 8 LFSRR_FO + SG_ LFSRRYear : 7|8@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ LFSRRSerialNmbr : 39|32@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ LFSRRJulianDate : 15|24@0+ (1,0) [0|0] "" EOCM_F_FO + +BO_ 1537 R_SRR_Trace_data: 8 RSRR_FO + SG_ RSRRYear : 7|8@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RSRRSerialNmbr : 39|32@0+ (1,0) [0|0] "" EOCM_F_FO + SG_ RSRRJulianDate : 15|24@0+ (1,0) [0|0] "" EOCM_F_FO + +BO_ 1089 F_Vision_Obj_Track_7: 8 VIS2_FO + SG_ FVisBurstIDTrk7 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk7 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk7 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk7 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk7 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk7 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk7 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FwdVsnRngTrk7Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnObjTypTr7Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnAzmthTrk7Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnVertPosTrk7 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ ObjDirTrk7 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1090 F_Vision_Obj_Track_8: 8 VIS2_FO + SG_ FVisBurstIDTrk8 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk8 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FwdVsnAzmthTrk8Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnVertPosTrk8 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk8Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnObjTypTr8Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk8 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisionConfTrk8 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk8 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk8 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk8 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk8 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1091 F_Vision_Obj_Track_9: 8 VIS2_FO + SG_ FwdVsnVertPosTrk9 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ FwdVsnRngTrk9Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk9Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr9Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ ObjDirTrk9 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk9 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk9 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk9 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk9 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk9 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk9 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk9 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1092 F_Vision_Obj_Track_10: 8 VIS2_FO + SG_ FwdVsnRngTrk10Rev : 16|12@0+ (0.1,0) [0|409.5] "m" EOCM_F_FO + SG_ FwdVsnAzmthTrk10Rev : 10|10@0- (0.1,0) [-51.2|51.1] "deg" EOCM_F_FO + SG_ FwdVsnObjTypTr10Rev : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ FwdVsnVertPosTrk10 : 53|6@0+ (0.25,-2) [-2|13.75] "deg" EOCM_F_FO + SG_ ObjDirTrk10 : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FVisBurstIDTrk10 : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionObjectIDTrk10 : 7|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FVisionConfTrk10 : 36|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionAzRateTrk10 : 34|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FVisionRelLaneTrk10 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionMeasStatTrk10 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FVisionWidthTrk10 : 61|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + +BO_ 1120 F_LRR_Obj_Header: 8 LRR_FO + SG_ FLRRRollingCount : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRModeCmdFdbk : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRNumValidTargets : 20|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ FLRRTimeStampV : 31|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRTimeStamp : 2|11@0+ (1,0) [0|2047] "ms" EOCM_F_FO + SG_ FLRRRoadTypeInfo : 5|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + SG_ FLRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRLonVelPlsblityFlt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRYawRtPlsblityFlt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRTunlDtctd : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ FLRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + +BO_ 1121 F_LRR_Obj_Track_1: 8 LRR_FO + SG_ FLRRTrk1BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk1Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk1RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk1RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk1DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk1Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk1Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk1MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk1ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk1Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1122 F_LRR_Obj_Track_2: 8 LRR_FO + SG_ FLRRTrk2BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk2Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk2RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk2RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk2DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk2Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk2Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk2MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk2ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk2Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1123 F_LRR_Obj_Track_3: 8 LRR_FO + SG_ FLRRTrk3BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk3Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk3RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk3RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk3DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk3Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk3Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk3MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk3ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk3Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1124 F_LRR_Obj_Track_4: 8 LRR_FO + SG_ FLRRTrk4BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk4Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk4RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk4RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk4DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk4Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk4Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk4MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk4ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk4Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1125 F_LRR_Obj_Track_5: 8 LRR_FO + SG_ FLRRTrk5BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk5Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk5RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk5RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk5DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk5Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk5Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk5MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk5ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk5Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1126 F_LRR_Obj_Track_6: 8 LRR_FO + SG_ FLRRTrk6BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk6Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk6RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk6Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk6RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk6DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk6Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk6Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk6MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk6ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1127 F_LRR_Obj_Track_7: 8 LRR_FO + SG_ FLRRTrk7Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk7BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk7Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk7RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk7RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk7DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk7Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk7Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk7MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk7ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1128 F_LRR_Obj_Track_8: 8 LRR_FO + SG_ FLRRTrk8Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk8BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk8Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk8RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk8RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk8DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk8Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk8Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk8MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk8ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1129 F_LRR_Obj_Track_9: 8 LRR_FO + SG_ FLRRTrk9Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk9BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk9Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk9RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk9RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk9DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk9Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk9Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk9MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk9ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1130 F_LRR_Obj_Track_10: 8 LRR_FO + SG_ FLRRTrk10Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk10BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk10Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk10RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk10RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk10DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk10Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk10Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk10MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk10ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1131 F_LRR_Obj_Track_11: 8 LRR_FO + SG_ FLRRTrk11Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk11BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk11Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk11RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk11RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk11DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk11Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk11Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk11MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk11ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1132 F_LRR_Obj_Track_12: 8 LRR_FO + SG_ FLRRTrk12Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk12BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk12Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk12RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk12RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk12DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk12Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk12Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk12MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk12ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1133 F_LRR_Obj_Track_13: 8 LRR_FO + SG_ FLRRTrk13Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk13RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk13RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk13DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk13Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk13Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk13MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1134 F_LRR_Obj_Track_14: 8 LRR_FO + SG_ FLRRTrk14Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk14BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk14Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk14RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk14RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk14DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk14Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk14Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk14MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk14ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1135 F_LRR_Obj_Track_15: 8 LRR_FO + SG_ FLRRTrk15Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk15MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk15Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk15ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + SG_ FLRRTrk15BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk15Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk15RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk15RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk15DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk15Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + +BO_ 1136 F_LRR_Obj_Track_16: 8 LRR_FO + SG_ FLRRTrk16Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk16BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk16Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk16RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk16RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk16DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk16Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk16Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk16MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk16ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1137 F_LRR_Obj_Track_17: 8 LRR_FO + SG_ FLRRTrk17Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk17BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk17Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk17RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk17RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk17DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk17Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk17Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk17MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk17ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1138 F_LRR_Obj_Track_18: 8 LRR_FO + SG_ FLRRTrk18Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk18BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk18Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk18RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk18RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk18DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk18Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk18Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk18MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk18ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1139 F_LRR_Obj_Track_19: 8 LRR_FO + SG_ FLRRTrk19Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk19BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk19Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk19RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk19RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk19DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk19Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk19Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk19MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk19ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1140 F_LRR_Obj_Track_20: 8 LRR_FO + SG_ FLRRTrk20Conf : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk20BurstID : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk20Range : 5|11@0+ (0.125,0) [0|255.875] "m" EOCM_F_FO + SG_ FLRRTrk20RangeRate : 10|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ FLRRTrk20RangeAccel : 31|9@0- (0.125,0) [-32|31.875] "m/s^2" EOCM_F_FO + SG_ FLRRTrk20DynProp : 38|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk20Azimuth : 35|12@0- (0.125,0) [-256|255.875] "deg" EOCM_F_FO + SG_ FLRRTrk20Width : 55|6@0+ (0.25,0) [0|15.75] "m" EOCM_F_FO + SG_ FLRRTrk20MeasStatus : 7|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk20ObjectID : 61|6@0+ (1,0) [0|63] "" EOCM_F_FO + +BO_ 1141 Long_Range_Radar_add_Info_1: 8 LRR_FO + SG_ FLRRAddInfo1BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk1 : 15|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk1 : 9|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk2 : 23|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk2 : 17|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk3 : 31|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk3 : 25|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk4 : 39|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk4 : 33|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk5 : 47|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk5 : 41|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ Cut_In_Out_Pot_Objtrk6 : 55|6@0+ (0.02,0) [0|1.26] "" EOCM_F_FO + SG_ ObjLossInfoObjTrk6 : 49|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1321 F_Fwd_Fus_Obj_TrackB_9: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn9 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB9RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB9Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB9MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB9DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB9RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB9RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB9Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB9ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB9ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB9ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB9ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB9ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB9ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB9NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB9LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB9LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1320 F_Fwd_Fus_Obj_TrackB_8: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn8 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB8RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB8Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB8MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB8DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB8RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB8RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB8Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB8ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB8ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB8ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB8ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB8ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB8ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB8NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB8LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB8LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1319 F_Fwd_Fus_Obj_TrackB_7: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn7 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB7RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB7Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB7MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB7DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB7RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB7RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB7Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB7ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB7ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB7ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB7ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB7ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB7ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB7NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB7LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB7LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1318 F_Fwd_Fus_Obj_TrackB_6: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn6 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB6RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB6Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB6MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB6DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB6RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB6RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB6Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB6ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB6ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB6ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB6ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB6ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB6ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB6NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB6LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB6LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1317 F_Fwd_Fus_Obj_TrackB_5: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn5 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB5RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB5Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB5MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB5DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB5RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB5RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB5Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB5ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB5ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB5ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB5ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB5ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB5ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB5NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB5LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB5LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1316 F_Fwd_Fus_Obj_TrackB_4: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn4 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB4RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB4Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB4MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB4DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB4RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB4RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB4Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB4ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB4ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB4ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB4ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB4ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB4ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB4NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB4LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB4LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1315 F_Fwd_Fus_Obj_TrackB_3: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn3 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB3RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB3Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB3MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB3DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB3RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB3RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB3Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB3ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB3ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB3ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB3ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB3ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB3ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB3NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB3LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB3LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1314 F_Fwd_Fus_Obj_TrackB_2: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn2 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB2RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB2Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB2MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB2DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB2RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB2RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB2Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB2ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB2ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB2ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB2ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB2ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB2ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB2NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB2LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB2LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1327 F_Fwd_Fus_Obj_TrackB_15: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn15 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB15RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB15Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB15MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB15DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB15RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB15RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB15Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB15ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB15ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB15ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB15ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTkB15ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB15ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB15NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB15LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB15LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1326 F_Fwd_Fus_Obj_TrackB_14: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn14 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB14RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB14Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB14MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB14DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB14RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB14RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB14Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB14ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB14ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB14ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB14ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB14ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB14ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB14NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB14LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB14LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1325 F_Fwd_Fus_Obj_TrackB_13: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn13 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB13RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB13Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB13MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB13DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB13RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB13RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB13Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB13ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB13ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB13ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB13ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB13ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB13ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB13NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB13LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB13LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1324 F_Fwd_Fus_Obj_TrackB_12: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn12 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB12RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB12Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB12MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB12DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB12RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB12RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB12Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB12ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB12ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB12ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB12ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB12ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB12ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB12NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB12LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB12LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1323 F_Fwd_Fus_Obj_TrackB_11: 7 EOCM_F_FO + SG_ FwdFusTrkB11DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB11RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB11RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB11Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB11ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB11ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB11ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB11ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB11ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB11ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB11NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB11LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB11LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkBAnlgRlLn11 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB11RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB11Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB11MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + +BO_ 1322 F_Fwd_Fus_Obj_TrackB_10: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn10 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB10RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB10Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB10MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB10DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB10RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB10RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB10Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB10ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB10ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB10ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB10ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB10ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB10ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB10NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB10LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB10LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1313 F_Fwd_Fus_Obj_TrackB_1: 7 EOCM_F_FO + SG_ FwdFusTrkBAnlgRlLn1 : 46|8@0- (0.1,0) [-12.8|12.7] "" Dummy_FO + SG_ FwdFusTrkB1RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB1Width : 5|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FwdFusTrkB1MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkB1DynProp : 11|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB1RelLnAccl : 8|9@0- (0.125,0) [-32|31.875] "m/s^2" Dummy_FO + SG_ FwdFusTrkB1RelLane : 31|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkB1Height : 54|6@0+ (0.25,0) [0|15.75] "m" Dummy_FO + SG_ FFusTrkB1ObjSrcLFSrr : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB1ObjSrcLCSrr : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB1ObjSrcRCSrr : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB1ObjSrcRFSrr : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FFusTrkB1ObjSrcVIs : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB1ObjSrcLrr : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FwdFusTrkB1NmCycTrkd : 39|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB1LatPosDev : 36|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkB1LngPosDev : 33|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1305 F_Fwd_Fus_Obj_TrackA_9: 8 EOCM_F_FO + SG_ FwdFusTrkA9RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA9ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA9MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA9LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA9RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA9Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA9LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA9RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA9MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA9ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1304 F_Fwd_Fus_Obj_TrackA_8: 8 EOCM_F_FO + SG_ FwdFusTrkA8RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA8ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA8MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA8LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA8RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA8Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA8LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA8RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA8MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA8ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1303 F_Fwd_Fus_Obj_TrackA_7: 8 EOCM_F_FO + SG_ FwdFusTrkA7RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA7ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA7MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA7LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA7RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA7Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA7LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA7RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA7MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA7ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1302 F_Fwd_Fus_Obj_TrackA_6: 8 EOCM_F_FO + SG_ FwdFusTrkA6RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA6ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA6MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA6LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA6RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA6Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA6LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA6RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA6MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA6ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1301 F_Fwd_Fus_Obj_TrackA_5: 8 EOCM_F_FO + SG_ FwdFusTrkA5RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA5ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA5MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA5LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA5RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA5Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA5LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA5RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA5MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA5ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1300 F_Fwd_Fus_Obj_TrackA_4: 8 EOCM_F_FO + SG_ FwdFusTrkA4RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA4ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA4MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA4LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA4RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA4Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA4LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA4RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA4MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA4ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1299 F_Fwd_Fus_Obj_TrackA_3: 8 EOCM_F_FO + SG_ FwdFusTrkA3RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA3ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA3MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA3LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA3RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA3Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA3LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA3RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA3MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA3ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1298 F_Fwd_Fus_Obj_TrackA_2: 8 EOCM_F_FO + SG_ FwdFusTrkA2RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA2ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA2MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA2LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA2RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA2Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA2LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA2RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA2MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA2ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1311 F_Fwd_Fus_Obj_TrackA_15: 8 EOCM_F_FO + SG_ FwdFusTrkA15RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA15ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA15MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA15LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA15RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA15Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA15LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA15RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA15MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA15ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1310 F_Fwd_Fus_Obj_TrackA_14: 8 EOCM_F_FO + SG_ FwdFusTrkA14RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA14ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA14MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA14LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA14RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA14Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA14LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA14RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA14MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA14ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1309 F_Fwd_Fus_Obj_TrackA_13: 8 EOCM_F_FO + SG_ FwdFusTrkA13RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA13ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA13MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA13LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA13RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA13Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA13LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA13RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA13MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA13ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1308 F_Fwd_Fus_Obj_TrackA_12: 8 EOCM_F_FO + SG_ FwdFusTrkA12RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA12ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA12MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA12LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA12RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA12Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA12LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA12RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA12MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA12ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1307 F_Fwd_Fus_Obj_TrackA_11: 8 EOCM_F_FO + SG_ FwdFusTrkA11ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA11MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA11LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA11RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA11Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA11LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA11RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA11MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA11ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + SG_ FwdFusTrkA11RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + +BO_ 1306 F_Fwd_Fus_Obj_TrackA_10: 8 EOCM_F_FO + SG_ FwdFusTrkA10RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA10ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA10MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA10LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA10RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA10Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA10LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA10RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA10MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA10ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1297 F_Fwd_Fus_Obj_TrackA_1: 8 EOCM_F_FO + SG_ FwdFusTrkA1RollingCnt : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA1ObjectID : 5|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ FwdFusTrkA1MsgIndex : 15|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ FwdFusTrkA1LongPos : 11|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + SG_ FwdFusTrkA1RelLongVel : 31|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA1Confidence : 36|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA1LatPos : 34|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ FwdFusTrkA1RelLatVel : 55|11@0- (0.125,0) [-128|127.875] "m/s" Dummy_FO + SG_ FwdFusTrkA1MeasStatus : 60|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ FwdFusTrkA1ObjType : 58|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 1296 F_Fwd_Fus_Obj_Header: 7 EOCM_F_FO + SG_ F_FusHeadRollingCount : 7|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ F_FusHeadFuncState : 5|2@0+ (1,0) [0|3] "" Dummy_FO + SG_ F_FusHedNmValTargts : 3|4@0+ (1,0) [0|15] "" Dummy_FO + SG_ F_FusHead_LrrOK : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_LFSRROK : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_VIsOK : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_MapDataOK : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHeadTimStmpV : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHeadTimStmp : 10|11@0+ (1,0) [0|2047] "ms" Dummy_FO + SG_ F_FusHead_LCSRROK : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_RCSRROK : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHead_RFSRROK : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ F_FusHed_ObjClstrCurv : 28|13@0- (5E-005,0) [-0.2048|0.20475] "1/m" Dummy_FO + SG_ F_FusHdObjClstTanHdng : 47|8@0- (0.002,0) [-0.256|0.254] "m/m" Dummy_FO + SG_ RoadTypeInfo : 55|3@0+ (1,0) [0|7] "" Dummy_FO + +BO_ 257 USDT_Req_to_All_FO_ECUs: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LRSRR_FO,_DOFIMU2_FO,_DOFIMU1_FO,DMS_FO,AMM_FO,EOCM2A_K2_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM2A_IMX6_FO,EOCM2A_K1_FO,NVS_FO,CIPM_FO,VIS2_FO,RRSRR_FO,VIS_FO,RFSRR_FO,LRR_FO,LFSRR_FO,RSRR_FO,EOCM_F_FO + +BO_ 584 USDT_Req_to_6DOFIMU2_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" _DOFIMU2_FO + +BO_ 1348 UUDT_Resp_From_6DOFIMU1_FO: 8 _DOFIMU1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1604 USDT_Resp_From_6DOFIMU1_FO: 8 _DOFIMU1_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 580 USDT_Req_to_6DOFIMU1_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" _DOFIMU1_FO + +BO_ 1349 UUDT_Resp_From_DMS_FO: 8 DMS_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1605 USDT_Resp_From_DMS_FO: 8 DMS_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 581 USDT_Req_to_DMS_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" DMS_FO + +BO_ 1372 UUDT_Resp_From_AMM_FO: 8 AMM_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1628 USDT_Resp_From_AMM_FO: 8 AMM_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 604 USDT_Req_to_AMM_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" AMM_FO + +BO_ 1622 USDT_Resp_From_EOCM2B_IMX6_FO: 8 EOCM2B_IMX6_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 1366 UUDT_Resp_From_EOCM2B_IMX6_FO: 8 EOCM2B_IMX6_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" TestTool_FO + +BO_ 598 USDT_Req_to_EOCM2B_IMX6_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" EOCM2B_IMX6_FO + +BO_ 590 USDT_Req_to_Free_4E_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" Vector__XXX + +BO_ 1338 VPDR_Debug: 8 EOCM_F_FO + SG_ FrtRWARateDiagFA : 43|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FrtRWABiasDiagFA : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ HWAFrtVal : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ HWADotValFrt : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAxRangeFA : 39|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAxRateFA : 38|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAxBiasFA : 37|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehAxCompFA : 36|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAxVal : 35|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAxVal : 34|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FrtRWACorrFA : 33|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FrtRWARangeDiagFA : 32|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAyBiasFA : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehAyCompFA : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAyVal : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAyVal : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehAxCorrFA : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAxRangeFA : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAxRateFA : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAxBiasFA : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehWzVal : 23|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehWzVal : 22|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehAyCorrDiagFA : 21|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAyRangeFA : 20|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAyRateFA : 19|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehAyBiasFA : 18|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAyRangeFA : 17|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehAyRateFA : 16|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehWzCorrDiagFA : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehWzRangeFA : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehWzRateFA : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S1VehWzBiasFA : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehWzRangeFA : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehWzRateFA : 10|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ S2VehWzBiasFA : 9|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehWzCompFA : 8|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlVxLFCorrDiagFA : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlVxRFCorrDiagFA : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlVxLRCorrDiagFA : 5|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlVxRRCorrDiagFA : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlLFVal : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlRFVal : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlLRVal : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ WhlRRVal : 0|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1328 Diag_Debug1: 8 EOCM_F_FO + SG_ AlrtWrnIndReqFP : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AlrtWrnIndReqFA : 0|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILRSRRSnsr_FP : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILRSRRSnsr_FA : 23|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILRSRRFrehns_FA : 22|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathEstCrvCSFP : 21|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathEstCrvCSFA : 20|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathWzEstCSFP : 19|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathWzEstCSFA : 18|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathVyEstCSFP : 17|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathVyEstCSFA : 16|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathVxEstCSFP : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VehPathVxEstCSFA : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCCSFP : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCCSFA : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyCSFP : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyCSFA : 10|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThLxVxAxCSFP : 9|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThLxVxAxCSFA : 8|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ CurSetValDiagFP : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ CurSetValDiagFA : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ CrsAltDvrSlTpDiagFP : 5|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ CrsAltDvrSlTpDiagFA : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCAStatDiagFP : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FCAStatDiagFA : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBBrkCtrlStFP : 62|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBBrkCtrlStFA : 61|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBOpStFP : 60|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBOpStFA : 59|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBBrkCtrlAccFP : 58|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBBrkCtrlAccFA : 57|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBAxlTrqRqFP : 56|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ RVBAxlTrqRqFA : 55|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRUPATTCFP : 54|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRUPATTCFA : 53|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtObjIDFP : 52|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtObjIDFA : 51|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtTTCFP : 50|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtTTCFA : 49|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtLxFP : 48|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtLxFA : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtLyFP : 46|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TVRHiThrtLyFA : 45|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFFuncStFP : 44|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFFuncStFA : 43|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFObjIDFP : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFObjIDFA : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLatPstnVelRatFP : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLatPstnVelRatFA : 39|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLonPstnVelFP : 38|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLonPstnVelFA : 37|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLatVelDiagFP : 36|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLatVelDiagFA : 35|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLatPstnDiagFP : 34|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLatPstnDiagFA : 33|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFNrRltvLonPstnFP : 32|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFNrRltvLonPstnFA : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLonPstnVelRatFP : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFLonPstnVelRatFA : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFConfDiagFP : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFConfDiagFA : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLnDiagFP : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ROFRltvLnDiagFA : 25|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1335 Diag_Debug3: 8 EOCM_F_FO + SG_ BrkSysCmdAxDiagFPQ : 63|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ BrkSysCmdAxDiagFAQ : 62|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AxleTorqReqDiagFPQ : 61|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AxleTorqReqDiagFAQ : 60|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AutoBrkTypeDiagFPQ : 59|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AutoBrkTypeDiagFAQ : 58|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCFPQ : 57|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCFAQ : 56|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTmpMemFPQ : 55|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTmpMemFAQ : 54|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLxVxAxFPQ : 53|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLxVxAxFAQ : 52|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtVyFPQ : 51|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtVyFAQ : 50|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyFPQ : 49|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyFAQ : 48|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtConPriFPQ : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtConPriFAQ : 46|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtCJLFPQ : 45|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtCJLFAQ : 44|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPDynPropDiagFPQ : 43|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPDynPropDiagFAQ : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRdTypInfoFPQ : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRdTypInfoFAQ : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRltvLnDiagFPQ : 39|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRltvLnDiagFAQ : 38|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumCycDiagFPQ : 37|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumCycDiagFAQ : 36|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumFusCyclsFPQ : 35|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumFusCyclsFAQ : 34|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNrRltvLonPstnFPQ : 33|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNrRltvLonPstnFAQ : 32|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonVelAccRatFPQ : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonVelAccRatFAQ : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPstnVelRatFPQ : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPstnVelRatFAQ : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPosVelAccFPQ : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPosVelAccFAQ : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatVelDiagFPQ : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatVelDiagFAQ : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatPstnDiagFPQ : 23|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatPstnDiagFAQ : 22|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFConfDiagFPQ : 21|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFConfDiagFAQ : 20|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFOvrlpRtlChk_FAQ : 19|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFOvrlpRtlChk_FAQ : 18|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRROvrlpRtlChk_FAQ : 17|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISOvrlpRtlChk_FAQ : 16|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISAlign_FAQ : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISSnsr_FAQ : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISSnsr_FPQ : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISFrshns_FAQ : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRAlign_FAQ : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRFrshns_FAQ : 10|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRSnsr_FAQ : 9|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRSnsr_FPQ : 8|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRAlign_FAQ : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRFrehns_FAQ : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRSnsr_FAQ : 5|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRSnsr_FPQ : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRSnsr_FPQ : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRSnsr_FAQ : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRFrshns_FAQ : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRAlign_FAQ : 0|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1331 Diag_Debug2: 8 EOCM_F_FO + SG_ TCPHiThrtTmpMemFP : 63|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTmpMemFA : 62|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtConPriFP : 61|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtConPriFA : 60|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtCJLFP : 59|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCFP : 58|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtTTCFA : 57|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtVyFP : 56|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtVyFA : 55|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyFP : 54|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLyFA : 53|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLxVxAxFP : 52|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtLxVxAxFA : 51|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRdTypInfoFP : 50|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRdTypInfoFA : 49|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AutoBrkTypeDiagFA : 48|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ BrkSysCmdAxDiagFP : 47|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ BrkSysCmdAxDiagFA : 46|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AxleTorqReqDiagFP : 45|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AxleTorqReqDiagFA : 44|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPDynPropDiagFP : 43|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPDynPropDiagFA : 42|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ TCPHiThrtCJLFA : 41|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumFusCyclsFP : 40|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ AutoBrkTypeDiagFP : 39|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumFusCyclsFA : 38|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatVelDiagFP : 37|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatVelDiagFA : 36|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatPstnDiagFP : 35|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLatPstnDiagFA : 34|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumCycDiagFP : 33|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNumCycDiagFA : 32|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRltvLnDiagFP : 31|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFRltvLnDiagFA : 30|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFConfDiagFP : 29|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFConfDiagFA : 28|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonVelAccRatFP : 27|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonVelAccRatFA : 26|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPstnVelRatFP : 25|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPstnVelRatFA : 24|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNrRltvLonPstnFP : 23|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFNrRltvLonPstnFA : 22|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPosVelAccFP : 21|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ FOFLonPosVelAccFA : 20|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISOvrlpRtlChk_FA : 19|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRROvrlpRtlChk_FA : 18|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFOvrlpRtlChk_FA : 17|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFOvrlpRtlChk_FA : 16|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISAlign_FA : 15|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISFrshns_FA : 14|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISSnsr_FP : 13|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ VISSnsr_FA : 12|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRAlign_FA : 11|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRFrshns_FA : 10|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRSnsr_FP : 9|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ LRRSnsr_FA : 8|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRAlign_FA : 7|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRFrehns_FA : 6|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRSnsr_FP : 5|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ IRFSRRSnsr_FA : 4|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRAlign_FA : 3|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRFrshns_FA : 2|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRSnsr_FP : 1|1@0+ (1,0) [0|1] "" Dummy_FO + SG_ ILFSRRSnsr_FA : 0|1@0+ (1,0) [0|1] "" Dummy_FO + +BO_ 1787 AL_Test_Tool_Rsp_RFSRR: 8 RFSRR_FO + SG_ RFSRREngRspDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" Dummy_FO + +BO_ 1788 AL_Test_Tool_Rsp_LFSRR: 8 LFSRR_FO + SG_ LFSRREngRspDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" Dummy_FO + +BO_ 1790 AL_Test_Tool_Req_RFSRR: 8 Dummy_FO + SG_ RFSRREngCmdDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RFSRR_FO + +BO_ 1791 AL_Test_Tool_Req_LFSRR: 8 Dummy_FO + SG_ LFSRREngCmdDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" LFSRR_FO + +BO_ 1786 AL_Test_Tool_Rsp_RSRR: 8 RSRR_FO + SG_ RSRREngRspDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" Dummy_FO + +BO_ 1789 AL_Test_Tool_Req_RSRR: 8 Dummy_FO + SG_ RSRREngCmdDta : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" RSRR_FO + +BO_ 1149 F_LRR_Azmth_Rate_Info_4: 8 LRR_FO + SG_ FLRRTrk20AzmthRate : 50|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk19AzmthRate : 45|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk18AzmthRate : 24|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk17AzmthRate : 19|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk16AzmthRate : 14|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRAzRtInf4BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1148 F_LRR_Azmth_Rate_Info_3: 8 LRR_FO + SG_ FLRRTrk15AzmthRate : 50|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk14AzmthRate : 45|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk13AzmthRate : 24|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk12AzmthRate : 19|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk11AzmthRate : 14|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRAzRtInf3BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1147 F_LRR_Azmth_Rate_Info_2: 8 LRR_FO + SG_ FLRRTrk9AzmthRate : 45|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk8AzmthRate : 24|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk7AzmthRate : 19|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk6AzmthRate : 14|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk10AzmthRate : 50|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRAzRtInf2BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1146 F_LRR_Azmth_Rate_Info_1: 8 LRR_FO + SG_ FLRRTrk5AzmthRate : 50|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk4AzmthRate : 45|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk3AzmthRate : 24|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk2AzmthRate : 19|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRTrk1AzmthRate : 14|11@0- (0.125,0) [-128|127.875] "deg/s" EOCM_F_FO + SG_ FLRRAzRtInf1BurstID : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1143 Long_Range_Radar_add_Info_3: 8 LRR_FO + SG_ FLRRAddInfo3BurstID : 57|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13ObstType : 60|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk20ObstTypeConf : 52|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk20ObstType : 55|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk19ObstTypeConf : 44|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk19ObstType : 47|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk18ObstTypeConf : 36|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk18ObstType : 39|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk17ObstTypeConf : 28|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk17ObstType : 31|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk16ObstTypeConf : 20|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk16ObstType : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk15ObstTypeConf : 12|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk15ObstType : 15|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk14ObstTypeConf : 4|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk14ObstType : 7|3@0+ (1,0) [0|7] "" EOCM_F_FO + +BO_ 1142 Long_Range_Radar_add_Info_2: 8 LRR_FO + SG_ FLRRAddInfo2BurstID : 62|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ FLRRTrk13ObstTypeConf : 60|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk12ObstTypeConf : 52|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk12ObstType : 55|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk11ObstTypeConf : 44|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk11ObstType : 47|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk10ObstTypeConf : 36|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk10ObstType : 39|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk9ObstTypeConf : 28|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk9ObstType : 31|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk8ObstTypeConf : 20|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk8ObstType : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk7ObstTypeConf : 12|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk7ObstType : 15|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ FLRRTrk1ObstTypeConf : 4|5@0+ (0.0323,0) [0|1.0013] "" EOCM_F_FO + SG_ FLRRTrk1ObstType : 7|3@0+ (1,0) [0|7] "" EOCM_F_FO + +BO_ 851 F_Vision_Environment_4: 8 VIS_FO + SG_ LnMrkg3LnPrvwDst : 45|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTtlNmLnMrkgDetRt : 4|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsRtLinCrsTm : 25|5@0+ (0.1,0) [0|3.1] "s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsNumPrlLnsDetRt : 33|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsNumPrlLnsDetLt : 36|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsCrvtGrdntLftV : 31|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLtLinCrsTm : 30|5@0+ (0.1,0) [0|3.1] "s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnPrvwDst : 50|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnMrkgTypChgDst : 61|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnMrkgTypChgDst : 40|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnMrkgWdth : 62|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4LnMarkrElvtd : 51|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg4AnchrLnLin : 57|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnMrkgWdth : 41|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3LnMarkrElvtd : 46|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkg3AnchrLnLin : 52|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBurstID2 : 1|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsCrvtGrdntLft : 15|16@0- (5.96E-008,0) [-0.0019529728|0.0019529132] "1/rad/s" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 597 USDT_Req_to_VIS2_FO: 8 TestTool_FO + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" CIPM_FO,VIS2_FO + +BO_ 1204 RR_SRR_Object_Track4: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth4 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate4 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange4 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange4 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID4 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation4 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus4 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp4 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth4 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID4 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1203 RR_SRR_Object_Track3: 8 RRSRR_FO + SG_ RRSrrTrkRawAzimuth3 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate3 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange3 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange3 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID3 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation3 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus3 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp3 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth3 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + SG_ RRSrrBurstID3 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + +BO_ 1202 RR_SRR_Object_Track2: 8 RRSRR_FO + SG_ RRSrrBurstID2 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkRawAzimuth2 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate2 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange2 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange2 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID2 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation2 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus2 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp2 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth2 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + +BO_ 1201 RR_SRR_Object_Track1: 8 RRSRR_FO + SG_ RRSrrBurstID1 : 63|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkRawAzimuth1 : 61|6@0- (1,0) [-32|31] "deg" EOCM_F_FO + SG_ RRSrrTrkRRate1 : 18|11@0- (0.125,0) [-128|127.875] "m/s" EOCM_F_FO + SG_ RRSrrTrkRange1 : 2|11@0+ (0.02,0) [0|40.94] "m" EOCM_F_FO + SG_ RRSrrTrkObsRange1 : 53|6@0- (0.02,0) [-0.64|0.62] "m" EOCM_F_FO + SG_ RRSrrTrkObjID1 : 39|5@0+ (1,0) [0|31] "" EOCM_F_FO + SG_ RRSrrTrkObjElevation1 : 20|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkMeasStatus1 : 55|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSrrTrkDynamProp1 : 23|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSrrTrkAzimuth1 : 34|11@0- (0.125,0) [-128|127.875] "deg" EOCM_F_FO + +BO_ 1200 RR_SRR_Object_Header: 8 RRSRR_FO + SG_ RRSrrTimeStampV : 15|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSrrTimeStamp : 10|11@0+ (1,0) [0|2047] "" EOCM_F_FO + SG_ RRSrrRollingCnt : 1|2@0+ (1,0) [0|3] "" EOCM_F_FO + SG_ RRSRRNumValidTargets : 14|4@0+ (1,0) [0|15] "" EOCM_F_FO + SG_ RRSRRModeCmdFdbk : 4|3@0+ (1,0) [0|7] "" EOCM_F_FO + SG_ RRSRRVltgOutRngLo : 44|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRVltgOutRngHi : 43|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRSvcAlgnInPrcs : 38|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRSnsrBlckd : 45|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRSnstvFltPrsntInt : 24|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRPlntAlgnInProc : 37|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnYawRt : 47|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnYawLt : 46|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnRllRt : 35|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnRllLt : 34|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnPtchUp : 32|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRMsalgnPtchDn : 33|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRInitDiagCmplt : 40|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRHWFltPrsntInt : 25|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRExtIntrfrnc : 36|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRDiagSpare : 30|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRCANSgnlSpvFld : 29|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRCANRxErr : 28|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRCANIDAddrsUnsbl : 27|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRAntTngFltPrsnt : 26|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRAmbTmpOutRngLw : 42|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRAmbTmpOutRngHi : 41|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSRRAlgnFltPrsnt : 39|1@0+ (1,0) [0|1] "" EOCM_F_FO + SG_ RRSrrBurstChecksum : 55|16@0+ (1,0) [0|65535] "" EOCM_F_FO + +BO_ 850 F_Vision_Environment_3: 8 VIS_FO + SG_ LnSnsTtlNmLnMrkgDetLt : 58|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLtLnMrkgWdth : 63|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLtLnMrkgTypChgDst : 62|4@0+ (10,0) [0|150] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTngtOfHdngLnLftV : 23|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsTngtOfHdngLnLft : 31|8@0- (0.002,0) [-0.256|0.254] "m/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnCrvtrLftV : 15|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsLnCrvtrLft : 39|16@0- (9.53E-007,0) [-0.031227904|0.031226951] "1/m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkrTypRght : 50|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkrTypLft : 53|3@0+ (1,0) [0|7] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkrElvtdRght : 54|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnMrkrElvtdLft : 55|1@0+ (1,0) [0|1] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnSnsBurstID1 : 7|2@0+ (1,0) [0|3] "" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnQltyCnfdncLvlRght : 22|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnQltyCnfdncLvlLft : 14|7@0+ (0.7874016,0) [0|100.0000032] "%" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnPrvwDstncRght : 2|3@0+ (10,0) [0|70] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + SG_ LnPrvwDstncLft : 5|3@0+ (10,0) [0|70] "m" EOCM2A_IMX6_FO,EOCM2A_K2_FO,EOCM2A_K1_FO,EOCM2B_IMX6_FO,EOCM2B_K2_FO,EOCM2B_K1_FO,EOCM_F_FO + +BO_ 1414 RVB_TVR_Debug2_FO: 7 EOCM_F_FO + SG_ VBBrkCntlAccel : 45|12@0- (0.01,0) [-20.48|20.47] "m/s^2" Dummy_FO + SG_ VBTOSObjID : 35|6@0+ (1,0) [0|63] "" Dummy_FO + SG_ VBTOSTTC : 31|12@0+ (0.025,0) [0|102.375] "s" Dummy_FO + SG_ VBTOSLatPstn : 11|11@0- (0.125,0) [-128|127.875] "m" Dummy_FO + SG_ VBTOSLonPstn : 7|12@0- (0.125,0) [-256|255.875] "m" Dummy_FO + diff --git a/opendbc_repo/opendbc/dbc/cadillac_ct6_powertrain.dbc b/opendbc_repo/opendbc/dbc/cadillac_ct6_powertrain.dbc new file mode 100644 index 000000000000000..2d0bb1217424a6f --- /dev/null +++ b/opendbc_repo/opendbc/dbc/cadillac_ct6_powertrain.dbc @@ -0,0 +1,248 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: K16_BECM K73_TCIC K9_BCM K43_PSCM K17_EBCM K20_ECM K114B_HPCM NEO K124_ASCM +VAL_TABLE_ TurnSignals 2 "Right Turn" 1 "Left Turn" 0 "None" ; +VAL_TABLE_ ACCLeadCar 1 "Present" 0 "Not Present" ; +VAL_TABLE_ ACCCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ BrakePedalPressed 1 "Pressed" 0 "Depressed" ; +VAL_TABLE_ DistanceButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ LKAButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_TABLE_ PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; +VAL_TABLE_ DoorStatus 1 "Opened" 0 "Closed" ; +VAL_TABLE_ SeatBeltStatus 1 "Latched" 0 "Unlatched" ; +VAL_TABLE_ LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; +VAL_TABLE_ GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; +VAL_TABLE_ GasRegenCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ; +VAL_TABLE_ HandsOffSWDetectionStatus 1 "Hands On" 0 "Hands Off" ; +VAL_TABLE_ HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ; + + +BO_ 717 ASCM_2CD: 5 K124_ASCM + +BO_ 869 ASCM_365: 4 K124_ASCM + +BO_ 1034 ASCM_40A: 7 K124_ASCM + +BO_ 1296 ASCM_510: 4 K124_ASCM + +BO_ 1930 ASCM_78A: 7 K124_ASCM + +BO_ 190 ECMAcceleratorPos: 6 K20_ECM + SG_ BrakePedalPos : 15|8@0+ (1,0) [0|0] "sticky" NEO + SG_ GasPedalAndAcc : 23|8@0+ (1,0) [0|0] "" NEO + +BO_ 201 ECMEngineStatus: 8 K20_ECM + SG_ EngineTPS : 39|8@0+ (0.392156863,0) [0|100.000000065] "%" NEO + SG_ EngineRPM : 15|16@0+ (0.25,0) [0|0] "RPM" NEO + +BO_ 209 EBCMBrakePedalSensors: 7 K17_EBCM + SG_ Counter1 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ Counter2 : 23|2@0+ (1,0) [0|3] "" XXX + SG_ BrakePedalPosition1 : 5|14@0+ (1,0) [0|16383] "" XXX + SG_ BrakePedalPosition2 : 21|14@0- (-1,0) [0|16383] "" XXX + SG_ BrakeNormalized1 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ BrakeNormalized2 : 47|8@0- (-1,0) [0|255] "" XXX + +BO_ 241 EBCMBrakePedalPosition: 6 K17_EBCM + SG_ BrakePedalPosition : 15|8@0+ (1,0) [0|255] "" NEO + +BO_ 298 BCMDoorBeltStatus: 8 K9_BCM + SG_ RearLeftDoor : 8|1@0+ (1,0) [0|0] "" NEO + SG_ FrontLeftDoor : 9|1@0+ (1,0) [0|0] "" NEO + SG_ FrontRightDoor : 10|1@0+ (1,0) [0|0] "" NEO + SG_ RearRightDoor : 23|1@0+ (1,0) [0|0] "" NEO + SG_ LeftSeatBelt : 12|1@0+ (1,0) [0|0] "" NEO + SG_ RightSeatBelt : 53|1@0+ (1,0) [0|0] "" NEO + +BO_ 309 ECMPRDNL: 8 K20_ECM + SG_ PRNDL : 2|3@0+ (1,0) [0|0] "" NEO + +BO_ 320 BCMTurnSignals: 3 K9_BCM + SG_ TurnSignals : 19|2@0+ (1,0) [0|0] "" NEO + +BO_ 336 ASCMLKASStatus: 1 NEO + SG_ Available : 7|1@0+ (1,0) [0|0] "" NEO + +BO_ 338 ASCMLKASteeringCmd: 6 NEO + SG_ LKASteeringCmdActive : 7|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 5|14@0- (1,0) [0|0] "" NEO + SG_ RollingCounter : 23|2@0+ (1,0) [0|0] "" NEO + SG_ SetMe1 : 21|1@0+ (1,0) [0|0] "" NEO + SG_ LKASVehicleSpeed : 20|13@0+ (0.22,0) [0|0] "kph" NEO + SG_ LKASMode : 36|2@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 33|10@0+ (1,0) [0|0] "" NEO + +BO_ 340 ASCMBLKASteeringCmd: 6 NEO + SG_ LKASteeringCmdActive : 7|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 5|14@0- (1,0) [0|0] "" NEO + SG_ RollingCounter : 23|2@0+ (1,0) [0|0] "" NEO + SG_ SetMe1 : 21|1@0+ (1,0) [0|0] "" NEO + SG_ LKASVehicleSpeed : 20|13@0+ (0.22,0) [0|0] "kph" NEO + SG_ LKASMode : 36|2@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 33|10@0+ (1,0) [0|0] "" NEO + +BO_ 381 MSG_17D: 8 K20_ECM + SG_ MSG17D_AccPower : 35|12@0- (1,0) [0|0] "" NEO + +BO_ 356 PSCMStatus: 8 K43_PSCM + SG_ LKATorqueDeliveredStatus : 7|3@0+ (1,0) [0|7] "" NEO + SG_ LKADriverAppldTrq : 2|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO + SG_ LKATBDTorque : 21|14@0- (-0.005,0) [-10.24|10.23] "Nm" NEO + SG_ RollingCounter : 39|2@0+ (1,0) [0|0] "" NEO + SG_ LKATotalTorqueDelivered : 37|14@0- (0.01,0) [-10.24|10.23] "Nm" NEO + +BO_ 417 AcceleratorPedal: 7 XXX + SG_ AcceleratorPedal : 55|8@0+ (1,0) [0|0] "" NEO + +BO_ 451 GasAndAcc: 8 XXX + SG_ GasPedalAndAcc2 : 55|8@0+ (1,0) [0|0] "" NEO + +BO_ 452 AcceleratorPedal2: 8 XXX + SG_ AcceleratorPedal2 : 47|8@0+ (1,0) [0|0] "" NEO + +BO_ 481 ASCMSteeringButton: 7 K124_ASCM + SG_ DistanceButton : 22|1@0+ (1,0) [0|0] "" NEO + SG_ LKAButton : 23|1@0+ (1,0) [0|0] "" NEO + SG_ ACCButtons : 46|3@0+ (1,0) [0|0] "" NEO + +BO_ 485 PSCMSteeringAngle: 8 K43_PSCM + SG_ SteeringWheelAngle : 15|16@0- (0.0625,0) [-2047|2047] "deg" NEO + SG_ SteeringWheelRate : 27|12@0- (1,0) [-2047|2047] "deg/s" NEO + +BO_ 489 EBCMVehicleDynamic: 8 K17_EBCM + SG_ YawRate : 51|12@0- (0.0625,0) [-2047|2047] "grad/s" NEO + SG_ LateralAcceleration : 3|12@0- (0.0161,0) [-2047|2047] "m/s2" NEO + SG_ BrakePedalPressed : 6|1@0+ (1,0) [0|0] "" NEO + +BO_ 711 BECMBatteryVoltageCurrent: 6 K17_EBCM + SG_ HVBatteryVoltage : 31|12@0+ (0.125,0) [0|511.875] "V" NEO + SG_ HVBatteryCurrent : 12|13@0- (0.15,0) [-614.4|614.25] "A" NEO + +BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM + SG_ GasRegenAlwaysOne : 9|1@0+ (1,1) [1|1] "" NEO + SG_ GasRegenAlwaysThree : 15|2@0+ (1,1) [1|1] "" NEO + SG_ GasRegenChecksum : 47|24@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmdActiveInv : 32|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenFullStopActive : 13|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmdActive : 0|1@0+ (1,0) [0|0] "" NEO + SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" NEO + SG_ RollingCounter2 : 36|4@0+ (1,0) [0|0] "" NEO + SG_ GasRegenAlwaysOne2 : 23|1@0+ (1,0) [0|1] "" NEO + SG_ GasRegenCmd : 22|15@0+ (1,0) [0|0] "" NEO + +BO_ 810 TCICOnStarGPSPosition: 8 K73_TCIC + SG_ GPSLongitude : 39|32@0+ (1,-2147483648) [0|0] "milliarcsecond" NEO + SG_ GPSLatitude : 7|32@0+ (1,0) [0|0] "milliarcsecond" NEO + +BO_ 840 EBCMWheelSpdFront: 4 K17_EBCM + SG_ FLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO + SG_ FRWheelSpd : 23|16@0+ (0.0311,0) [0|255] "km/h" NEO + +BO_ 842 EBCMWheelSpdRear: 4 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 + +BO_ 880 ASCMActiveCruiseControlStatus: 6 K124_ASCM + SG_ ACCLeadCar : 44|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCAlwaysOne2 : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCAlwaysOne : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCSpeedSetpoint : 19|12@0+ (0.0625,0) [0|255.9375] "km/h" NEO + SG_ ACCGapLevel : 21|2@0+ (1,0) [0|0] "" NEO + SG_ ACCResumeButton : 1|1@0+ (1,0) [0|0] "" NEO + SG_ ACCCmdActive : 23|1@0+ (1,0) [0|0] "" NEO + +BO_ 1001 ECMVehicleSpeed: 8 K20_ECM + SG_ VehicleSpeed : 7|16@0+ (0.01,0) [0|0] "mph" NEO + +BO_ 1033 ASCMKeepAlive: 7 NEO + SG_ ASCMKeepAliveAllZero : 7|56@0+ (1,0) [0|0] "" NEO + +BO_ 1217 ECMEngineCoolantTemp: 8 K20_ECM + SG_ EngineCoolantTemp : 23|8@0+ (1,-40) [0|0] "C" NEO + +BO_ 1249 VIN_Part2: 8 K20_ECM + SG_ VINPart2 : 7|64@0+ (1,0) [0|0] "" NEO + +BO_ 1300 VIN_Part1: 8 K20_ECM + SG_ VINPart1 : 7|64@0+ (1,0) [0|0] "" NEO + +BO_ 1912 PSCM_778: 8 K43_PSCM + +BO_TX_BU_ 338 : K124_ASCM,NEO; +BO_TX_BU_ 880 : NEO,K124_ASCM; +BO_TX_BU_ 1033 : K124_ASCM,NEO; +BO_TX_BU_ 715 : NEO,K124_ASCM; + + +CM_ BU_ K16_BECM "Battery Energy Control Module"; +CM_ BU_ K73_TCIC "Telematics Communication Control Module"; +CM_ BU_ K9_BCM "Body Control Module"; +CM_ BU_ K43_PSCM "Power Steering Control Module"; +CM_ BU_ K17_EBCM "Electronic Brake Control Module"; +CM_ BU_ K20_ECM "Engine Control Module"; +CM_ BU_ K114B_HPCM "Hybrid Powertrain Control Module"; +CM_ BU_ NEO "Comma NEO"; +CM_ BU_ K124_ASCM "Active Safety Control Module"; +CM_ SG_ 381 MSG17D_AccPower "Need to investigate"; +CM_ SG_ 190 GasPedalAndAcc "ACC baseline is 62"; +CM_ SG_ 451 GasPedalAndAcc2 "ACC baseline is 62"; +CM_ SG_ 715 RollingCounter2 "Values cycle between 0, 7, 10, 13"; +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; +BA_ "UseGMParameterIDs" 0; +VAL_ 481 DistanceButton 1 "Active" 0 "Inactive" ; +VAL_ 481 LKAButton 1 "Active" 0 "Inactive" ; +VAL_ 481 ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_ 309 PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; +VAL_ 338 LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 338 LKASMode 2 "supercruise" 1 "lkas" 0 "Inactive" ; +VAL_ 880 ACCLeadCar 1 "Present" 0 "Not Present" ; +VAL_ 880 ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; +VAL_ 880 ACCResumeButton 1 "Pressed" 0 "Depressed" ; +VAL_ 880 ACCCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 356 LKATorqueDeliveredStatus 7 "Override Fault" 6 "LKAS Fault but Responsive" 5 "TBD but Responsive" 4 "TBD but Responsive" 3 "Fault" 1 "Active" 0 "Inactive" ; +VAL_ 489 BrakePedalPressed 1 "Pressed" 0 "Depressed" ; +VAL_ 715 GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; +VAL_ 715 GasRegenCmdActive 1 "Active" 0 "Inactive" ; diff --git a/opendbc_repo/opendbc/dbc/chrysler_cusw.dbc b/opendbc_repo/opendbc/dbc/chrysler_cusw.dbc new file mode 100644 index 000000000000000..880f6e7255c453d --- /dev/null +++ b/opendbc_repo/opendbc/dbc/chrysler_cusw.dbc @@ -0,0 +1,192 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 492 EPS_STATUS: 8 XXX + SG_ TORQUE_DRIVER : 3|12@0+ (1,-1024) [0|2048] "Nm" XXX + SG_ LKAS_STATE : 16|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_FAULT : 17|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_HIGH_TORQUE : 19|1@0+ (1,0) [0|1] "" XXX + SG_ TORQUE_MOTOR : 27|12@0+ (1,-2048) [0|1] "" XXX + SG_ LAT_TORQUE_REQUEST : 47|12@0+ (1,-2048) [0|4095] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1250 DOORS: 8 XXX + SG_ DOOR_OPEN_FL : 10|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 11|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 13|1@0+ (1,0) [0|1] "" XXX + SG_ TRUNK : 14|1@0+ (1,0) [0|1] "" XXX + +BO_ 1262 GEAR: 8 XXX + SG_ PRNDL : 11|4@0+ (1,0) [0|15] "" XXX + +BO_ 875 SEATBELT_STATUS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 16|1@0+ (1,0) [0|1] "" XXX + +BO_ 1264 STEERING_LEVERS: 7 XXX + SG_ TURN_SIGNALS : 3|4@0+ (1,0) [0|15] "" XXX + SG_ HIGH_BEAM_FLASH : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 480 TRACTION_BUTTON: 8 XXX + SG_ TRACTION_OFF : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 740 WHEEL_SPEEDS_REAR: 8 XXX + SG_ WHEEL_SPEED_RL : 5|13@0+ (0.0087,0) [0|1] "" XXX + SG_ WHEEL_SPEED_RR : 20|13@0+ (0.0087,0) [0|1] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 520 EPS_STATUS_2: 7 XXX + SG_ NEW_SIGNAL_1 : 3|12@0+ (1,-2048) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 19|12@0+ (1,-2048) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 39|12@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 43|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 494 STEERING: 6 XXX + SG_ STEER_ANGLE : 5|14@0+ (0.1,-720) [0|1] "deg" XXX + SG_ STEERING_RATE : 19|12@0+ (1,-2000) [0|1] "" XXX + SG_ COUNTER : 35|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 738 BRAKE_2: 8 XXX + SG_ BRAKE_TORQUE : 7|12@0+ (1,0) [0|15] "" XXX + SG_ BRAKE_LIGHTS : 8|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HUMAN : 9|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 742 WHEEL_SPEEDS_FRONT: 8 XXX + SG_ WHEEL_SPEED_FL : 5|13@0+ (0.0087,0) [0|1] "" XXX + SG_ WHEEL_SPEED_FR : 20|13@0+ (0.0087,0) [0|1] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 502 LKAS_COMMAND: 4 XXX + SG_ STEERING_TORQUE : 7|11@0+ (1,-1024) [0|4087] "" XXX + SG_ LKAS_CONTROL_BIT : 12|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 19|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 31|8@0+ (1,0) [0|1] "" XXX + +BO_ 1498 LKAS_1: 2 XXX + +BO_ 1500 DAS_6: 4 XXX + SG_ LKAS_ICON_COLOR : 1|2@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_0XAC : 15|8@0+ (1,0) [0|255] "" XXX + SG_ LKAS_LANE_LINES : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 1508 LKAS_HEARTBIT: 8 XXX + SG_ LKAS_STATUS_OK : 28|1@0+ (1,0) [0|1] "" XXX + +BO_ 762 CRUISE_BUTTONS: 3 XXX + SG_ ACC_Cancel : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_Distance_Dec : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_Accel : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_Decel : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_Resume : 4|1@0+ (1,0) [0|1] "" XXX + SG_ Cruise_OnOff : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_OnOff : 7|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_Distance_Inc : 8|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 15|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 23|8@0+ (1,0) [0|1] "" XXX + +BO_ 484 BRAKE_1: 8 XXX + SG_ BRAKE_PSI : 7|12@0+ (1,0) [0|1] "" XXX + SG_ VEHICLE_SPEED : 35|12@0+ (0.0174,0) [0|4095] "m/s" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 500 GEARBOX_1: 7 XXX + SG_ DESIRED_GEAR : 35|4@0+ (1,0) [0|1] "" XXX + SG_ ACTUAL_GEAR : 39|4@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 43|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 510 ACCEL_GAS: 5 XXX + SG_ ACC_ACTIVE : 2|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_HUMAN : 15|8@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 27|4@0+ (1,0) [0|1] "" XXX + SG_ GAS_ACC : 28|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|1] "" XXX + +BO_ 490 DASHBOARD: 4 XXX + SG_ ACC_SPEED_CONFIG_KPH : 7|8@0+ (0.1625,0) [0|1] "m/s" XXX + +BO_ 1006 ACC_HUD: 7 XXX + SG_ ACC_STATE : 7|3@0+ (1,0) [0|15] "" XXX + SG_ ACC_SET_SPEED_KMH : 14|8@0+ (1,0) [0|255] "km/h" XXX + SG_ DISTANCE_SETTING : 33|2@0+ (1,0) [0|3] "" XXX + SG_ DISTANCE_TO_LEAD : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 748 ACC_CONTROL: 8 XXX + SG_ ACC_MAIN_ON : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ACTIVE : 7|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_VALUE : 13|10@0+ (1,0) [0|1023] "" XXX + SG_ GAS_VALID : 15|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_VALUE : 28|10@0+ (1,0) [0|1023] "" XXX + SG_ BRAKE_VALID : 30|1@0+ (1,0) [0|1] "" XXX + SG_ UNKNOWN_1 : 33|1@0+ (1,0) [0|1] "" XXX + SG_ UNKNOWN_2 : 46|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 496 CLUSTER_1: 8 XXX + SG_ TACHOMETER : 3|12@0+ (1.024,0) [0|3] "" XXX + SG_ SPEEDOMETER : 19|12@0+ (0.01065,0) [0|1] "m/s" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|1] "" XXX + + +CM_ SG_ 1250 TRUNK "1 = open, 0 = closed"; +CM_ SG_ 1250 DOOR_OPEN_FL "1 = open, 0 = closed"; +CM_ SG_ 1250 DOOR_OPEN_FR "1 = open, 0 = closed"; +CM_ SG_ 1250 DOOR_OPEN_RL "1 = open, 0 = closed"; +CM_ SG_ 1250 DOOR_OPEN_RR "1 = open, 0 = closed"; +CM_ SG_ 1262 PRNDL "1 = park, 2 = reverse, 3 = neutral, 4 = drive, 5 = sport (snicker... sport)"; +CM_ SG_ 875 SEATBELT_DRIVER_UNLATCHED "1 = unlatched, 0 = safety first"; +CM_ SG_ 1264 TURN_SIGNALS "0 = off, 1 = left blinker, 2 = right blinker"; +CM_ SG_ 480 TRACTION_OFF "0 = TCS on, 1 = TCS off (light on dash ON)"; +CM_ SG_ 1500 LKAS_LANE_LINES "0x01 transparent lines, 0x02 left white, 0x03 right white, 0x04 left yellow with car on top, 0x05 left yellow with car on top, 0x06 both white, 0x07 left yellow, 0x08 left yellow right white, 0x09 right yellow, 0x0a right yellow left white, 0x0b left yellow with car on top right white, 0x0c right yellow with car on top left white, (0x00, 0x0d, 0x0e, 0x0f) null"; +CM_ SG_ 1492 LEAD_CAR "lead car present = 4, no car = 2 "; +CM_ SG_ 498 ACC_STATUS_2 "1 no ACC, 3 icpno "; +CM_ SG_ 498 ACC_STATUS_1 "0x00 = acc off, 0x03 = acc on, green, 0x02 acc on, white"; +CM_ SG_ 1006 ACC_STATE "0 = ACC off, 6 = ACC active (white), 8 = ACC engaged (green)"; +CM_ SG_ 502 LKAS_STATE "2 = active (green), 1 = error"; +CM_ SG_ 1006 ACC_SET_SPEED_KMH "min set appears to be 68 km/h, errors below 59 km/h "; +VAL_ 1262 PRNDL 1 "P" 2 "R" 3 "N" 4 "D" 5 "S"; diff --git a/opendbc/chrysler_pacifica_2017_hybrid_generated.dbc b/opendbc_repo/opendbc/dbc/chrysler_pacifica_2017_hybrid_generated.dbc similarity index 100% rename from opendbc/chrysler_pacifica_2017_hybrid_generated.dbc rename to opendbc_repo/opendbc/dbc/chrysler_pacifica_2017_hybrid_generated.dbc diff --git a/opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc b/opendbc_repo/opendbc/dbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc similarity index 100% rename from opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc rename to opendbc_repo/opendbc/dbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc diff --git a/opendbc/chrysler_ram_dt_generated.dbc b/opendbc_repo/opendbc/dbc/chrysler_ram_dt_generated.dbc similarity index 100% rename from opendbc/chrysler_ram_dt_generated.dbc rename to opendbc_repo/opendbc/dbc/chrysler_ram_dt_generated.dbc diff --git a/opendbc/chrysler_ram_hd_generated.dbc b/opendbc_repo/opendbc/dbc/chrysler_ram_hd_generated.dbc similarity index 100% rename from opendbc/chrysler_ram_hd_generated.dbc rename to opendbc_repo/opendbc/dbc/chrysler_ram_hd_generated.dbc diff --git a/opendbc/comma_body.dbc b/opendbc_repo/opendbc/dbc/comma_body.dbc similarity index 100% rename from opendbc/comma_body.dbc rename to opendbc_repo/opendbc/dbc/comma_body.dbc diff --git a/opendbc_repo/opendbc/dbc/fca_giorgio.dbc b/opendbc_repo/opendbc/dbc/fca_giorgio.dbc new file mode 100644 index 000000000000000..f3e22cf4179ca71 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/fca_giorgio.dbc @@ -0,0 +1,243 @@ +BO_ 171 NEW_MSG_AB: 8 XXX + SG_ NEW_SIGNAL_5 : 3|12@0+ (1,0) [0|4095] "" XXX + SG_ NEW_SIGNAL_6 : 21|6@0+ (1,0) [0|63] "" XXX + SG_ NEW_SIGNAL_1 : 23|2@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_2 : 35|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_3 : 51|12@0+ (1,0) [0|4095] "" XXX + SG_ NEW_SIGNAL_4 : 55|4@0+ (1,0) [0|15] "" XXX + +BO_ 222 EPS_1: 6 EPS + SG_ STEERING_ANGLE : 5|14@0+ (0.1,-716.8) [0|16383] "deg" XXX + SG_ STEERING_RATE : 19|12@0+ (0.5,-1000) [0|4095] "deg/s" XXX + SG_ UNKNOWN_1 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ UNKNOWN_2 : 23|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 35|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 228 NEW_MSG_E4: 6 XXX + SG_ NEW_SIGNAL_1 : 13|1@0+ (1,0) [0|1] "" XXX + +BO_ 238 ABS_1: 8 ABS + SG_ WHEEL_SPEED_FL : 7|13@0+ (0.017,0) [0|8191] "m/s" XXX + SG_ WHEEL_SPEED_FR : 10|13@0+ (0.017,0) [0|8191] "m/s" XXX + SG_ WHEEL_SPEED_RL : 29|13@0+ (0.017,0) [0|8191] "m/s" XXX + SG_ WHEEL_SPEED_RR : 32|13@0+ (0.017,0) [0|8191] "m/s" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 241 NEW_MSG_F1: 8 XXX + SG_ MAYBE_VOLTAGE : 18|10@0+ (0.02,0) [0|1023] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 249 NEW_MSG_F9: 4 XXX + SG_ COUNTER : 19|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 250 ABS_3: 8 ABS + SG_ BRAKE_PRESSURE_THRESHOLD : 2|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_PEDAL_SWITCH : 3|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 9|2@0+ (1,0) [0|3] "" XXX + SG_ XCOUNTER : 38|4@0+ (1,0) [0|15] "" XXX + SG_ XCHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 252 ENGINE_1: 8 ENGINE + SG_ ENGINE_RPM : 7|14@0+ (1,0) [0|255] "rev/min" XXX + SG_ ACCEL_PEDAL : 20|8@0+ (0.4,0) [0|255] "percent" XXX + SG_ REVERSE : 26|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 39|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 46|2@1+ (1,0) [0|3] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 254 ABS_2: 8 ABS + SG_ LONG_ACCEL : 7|12@0+ (0.01,-20.48) [0|4095] "m/s2" XXX + SG_ LATERAL_ACCEL : 11|12@0+ (0.01,-20.48) [0|4095] "m/s2" XXX + SG_ YAW_RATE : 31|12@0+ (-0.0014,2.86) [0|4095] "rad/s" XXX + SG_ NEW_SIGNAL_1 : 47|9@0+ (1,0) [0|511] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 257 ABS_6: 8 ABS + SG_ MAYBE_ACC_BRAKE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ VEHICLE_SPEED : 15|11@0+ (0.017,0) [0|2047] "" XXX + SG_ BRAKE_PRESSURE_1 : 20|11@0+ (1,0) [0|2047] "" XXX + SG_ BRAKE_PRESSURE_2 : 43|12@0+ (1,0) [0|4095] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 262 EPS_2: 7 EPS + SG_ UNKNOWN_TORQUE : 7|12@0+ (1,-2000) [0|4095] "" XXX + SG_ UNKNOWN_1 : 8|1@0+ (1,0) [0|1] "" XXX + SG_ UNKNOWN_STATUS : 9|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVER_TORQUE : 23|11@0+ (1,-1024) [0|2047] "" XXX + SG_ UNKNOWN_2 : 27|1@0+ (1,0) [0|1] "" XXX + SG_ LKA_STATUS : 38|2@0+ (1,0) [0|3] "" XXX + SG_ LKA_FAULT : 39|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 43|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 263 ABS_4: 8 ABS + SG_ BRAKE_PRESSURE : 7|8@0+ (1,0) [0|255] "" XXX + +BO_ 265 NEW_MSG_109: 8 XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 270 ABS_7: 7 XXX + SG_ LONG_ACCEL_RAW : 7|12@0+ (0.01,-20.48) [0|4095] "" XXX + SG_ LATERAL_ACCEL_RAW : 11|12@0+ (0.01,-20.48) [0|4095] "" XXX + SG_ YAW_RATE_RAW : 31|12@0+ (-0.0014,2.86) [0|4095] "" XXX + SG_ COUNTER : 43|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 278 ABS_5: 8 ABS + SG_ WHEEL_IMPULSE_FL : 7|8@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_IMPULSE_FR : 15|8@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_IMPULSE_RL : 23|8@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_IMPULSE_RR : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ACTIVE_FL : 32|1@0+ (1,0) [0|1] "" XXX + SG_ ACTIVE_FR : 33|1@0+ (1,0) [0|1] "" XXX + SG_ ACTIVE_RL : 34|1@0+ (1,0) [0|1] "" XXX + SG_ ACTIVE_RR : 35|1@0+ (1,0) [0|1] "" XXX + SG_ FORWARD_1 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ REVERSE_1 : 37|1@0+ (1,0) [0|1] "" XXX + SG_ FORWARD_2 : 38|1@0+ (1,0) [0|1] "" XXX + SG_ REVERSE_2 : 39|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 280 NEW_MSG_118: 6 XXX + SG_ COUNTER : 35|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 282 NEW_MSG_11A: 8 XXX + SG_ NEW_SIGNAL_1 : 7|11@0+ (1,-1000) [0|2047] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 284 NEW_MSG_11C: 8 XXX + SG_ NEW_SIGNAL_1 : 7|12@0+ (1,0) [0|4095] "" XXX + SG_ NEW_SIGNAL_2 : 11|12@0+ (1,0) [0|4095] "" XXX + SG_ NEW_SIGNAL_3 : 28|13@0+ (1,0) [0|8191] "" XXX + SG_ NEW_SIGNAL_4 : 31|2@0+ (1,0) [0|3] "" XXX + SG_ VEHICLE_SPEED : 47|12@0+ (0.017,0) [0|4095] "m/s" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 288 NEW_MSG_120: 6 XXX + SG_ COUNTER : 19|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 290 EPS_3: 4 EPS + SG_ EPS_TORQUE : 7|12@0+ (1,-2048) [0|4095] "" XXX + SG_ COUNTER : 19|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 501 NEW_MSG_1F5: 5 XXX + SG_ NEW_SIGNAL_2 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 27|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_1 : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 502 LKA_COMMAND: 8 CAMERA + SG_ LKA_TORQUE : 7|11@0+ (1,-1024) [0|2047] "" XXX + SG_ HAPTIC_WARN_1 : 8|1@0+ (1,0) [0|1] "" XXX + SG_ LKA_ACTIVE : 11|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 12|1@0+ (1,0) [0|1] "" XXX + SG_ HAPTIC_WARN_2 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 508 NEW_MSG_1FC: 8 XXX + SG_ NEW_SIGNAL_1 : 6|1@0+ (1,0) [0|1] "" XXX + +BO_ 601 NEW_MSG_259: 8 XXX + SG_ NEW_SIGNAL_1 : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 762 NEW_MSG_2FA: 3 XXX + SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX + +BO_ 766 CAM_UNKNOWN_1: 4 CAMERA + +BO_ 900 NEW_MSG_384: 8 XXX + SG_ NEW_SIGNAL_1 : 19|3@0+ (1,0) [0|7] "" XXX + +BO_ 1040 NEW_MSG_410: 8 XXX + SG_ NEW_SIGNAL_3 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 49|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1046 NEW_MSG_416: 8 XXX + SG_ MUX M : 1|2@0+ (1,0) [0|3] "" XXX + SG_ UNKNOWN_M0_1 m0 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M0_2 m0 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M0_3 m0 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M0_4 m0 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M0_5 m0 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M0_6 m0 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M0_7 m0 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M1_1 m1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M1_2 m1 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M1_3 m1 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M1_4 m1 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M1_5 m1 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M1_6 m1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M1_7 m1 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M2_1 m2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M2_2 m2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M2_3 m2 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M2_4 m2 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M2_5 m2 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M2_6 m2 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_M2_7 m2 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1194 CAM_UNKNOWN_2: 8 CAMERA + +BO_ 1198 LKA_HUD_1: 8 CAMERA + SG_ NEW_SIGNAL_1 : 4|5@0+ (1,0) [0|31] "" XXX + SG_ NEW_SIGNAL_3 : 12|5@0+ (1,0) [0|31] "" XXX + SG_ NEW_SIGNAL_2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_5 : 29|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_4 : 38|3@0+ (1,0) [0|7] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1351 LKA_HUD_2: 8 CAMERA + SG_ NEW_SIGNAL_1 : 51|3@0+ (1,0) [0|7] "" XXX + SG_ NEW_SIGNAL_2 : 55|4@0+ (1,0) [0|15] "" XXX + +BO_ 1442 ACC_1: 8 RADAR + SG_ HUD_SPEED : 7|8@0+ (1,0) [0|255] "km/h" XXX + SG_ TARGET_SPEED : 15|8@0+ (0.433,0) [0|255] "m/s" XXX + SG_ NEW_SIGNAL_3 : 17|5@0+ (1,0) [0|31] "" XXX + SG_ NEW_SIGNAL_4 : 18|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_STATUS : 22|2@0+ (1,0) [0|3] "" XXX + SG_ MAYBE_TJA : 23|1@0+ (1,0) [0|1] "" XXX + +BO_ 1458 CAM_UNKNOWN_5: 4 CAMERA + SG_ NEW_SIGNAL_1 : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 1854 BCM_1: 4 BCM + SG_ RIGHT_TURN_STALK : 16|1@0+ (1,0) [0|1] "" XXX + SG_ LEFT_TURN_STALK : 17|1@0+ (1,0) [0|1] "" XXX + +BO_ 1865 NEW_MSG_749: 8 XXX + SG_ NEW_SIGNAL_1 : 23|2@0+ (1,0) [0|3] "" XXX + +BO_ 506855454 CAM_UNKNOWN_6: 1 CAMERA + +CM_ SG_ 254 LONG_ACCEL "scale TBD"; +CM_ SG_ 254 LATERAL_ACCEL "scale TBD"; +CM_ SG_ 254 YAW_RATE "scale estimated"; +CM_ SG_ 257 MAYBE_ACC_BRAKE "may correlate with ACC-actuated braking"; +CM_ SG_ 278 FORWARD_1 "probably per-axle"; +CM_ SG_ 278 REVERSE_1 "probably per-axle"; +CM_ SG_ 278 FORWARD_2 "probably per-axle"; +CM_ SG_ 278 REVERSE_2 "probably per-axle"; +CM_ SG_ 282 NEW_SIGNAL_1 "smoothed yaw rate with low speed cutoff, maybe active forward lighting target angle"; +CM_ SG_ 284 VEHICLE_SPEED "scale estimated"; +CM_ SG_ 502 HAPTIC_WARN_1 "correlates with steering wheel haptic"; +CM_ SG_ 502 HAPTIC_WARN_2 "correlates with steering wheel haptic"; +CM_ BO_ 1198 "Definite LKA activity, probably contains lane-line recognition and lane departure signals, indicator of LKA vs TJA, perhaps indicator of active assist in map-permitted areas"; +VAL_ 262 LKA_STATUS 0 "standby" 1 "lka_active"; diff --git a/opendbc_repo/opendbc/dbc/ford_cgea1_2_bodycan_2011.dbc b/opendbc_repo/opendbc/dbc/ford_cgea1_2_bodycan_2011.dbc new file mode 100644 index 000000000000000..49fcae19c2e4f86 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/ford_cgea1_2_bodycan_2011.dbc @@ -0,0 +1,1070 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 58 BCM_m_FrP01: 8 XXX + SG_ ChildLockCmd : 13|1@0+ (1,0) [0|0] "" XXX + SG_ ChildLockCmd_UB : 12|1@0+ (1,0) [0|0] "" XXX + SG_ CLockCmd : 31|8@0+ (1,0) [0|0] "" XXX + SG_ CLockCmd_UB : 14|1@0+ (1,0) [0|0] "" XXX + SG_ DDShortDrop : 3|2@0+ (1,0) [0|0] "" XXX + SG_ DDShortDrop_UB : 4|1@0+ (1,0) [0|0] "" XXX + SG_ DirectionIndication : 11|2@0+ (1,0) [0|0] "" XXX + SG_ DirectionIndication_UB : 0|1@0+ (1,0) [0|0] "" XXX + SG_ EpsDrvInfo_D_Dsply : 36|4@0+ (1,0) [0|0] "" XXX + SG_ EpsDrvInfo_D_Dsply_UB : 39|1@0+ (1,0) [0|0] "" XXX + SG_ GearRvrseActv_D_Actl : 38|2@0+ (1,0) [0|0] "" XXX + SG_ GearRvrseActv_D_Actl_UB : 15|1@0+ (1,0) [0|0] "" XXX + SG_ VehVActlEng_D_Qf_3A : 9|2@0+ (1,0) [0|0] "" XXX + SG_ Veh_V_ActlEng_UB_3A : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Veh_V_ActlEng_3A : 55|16@0+ (0.01,0) [0|0] "kph" XXX + SG_ Veh_V_DsplyCcSet : 23|8@0+ (1,0) [0|0] "" XXX + SG_ Veh_V_RqCcSet : 32|9@0+ (0.5,0) [0|0] "kph" XXX + SG_ WasherFluidLevelLow : 5|1@0+ (1,0) [0|0] "" XXX + +BO_ 64 BCM_m_FrP02: 8 XXX + SG_ FuelCutoffReq : 7|4@0+ (1,0) [0|0] "" XXX + SG_ FuelCutoffReq_UB : 8|1@0+ (1,0) [0|0] "" XXX + SG_ KVRFRSettings : 54|15@0+ (1,0) [0|0] "" XXX + SG_ KVRFRSettings_UB : 10|1@0+ (1,0) [0|0] "" XXX + SG_ PsngrFrntDetct_D_Actl : 23|2@0+ (1,0) [0|0] "" XXX + SG_ PsngrFrntDetct_D_Actl_UB : 3|1@0+ (1,0) [0|0] "" XXX + SG_ RILReq : 21|2@0+ (1,0) [0|0] "" XXX + SG_ RILReq_UB : 55|1@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBuckleDriver : 31|2@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBuckleDriver_UB : 0|1@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBuckleMid : 29|2@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBuckleMid_UB : 15|1@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBucklePsngr : 27|2@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBucklePsngr_UB : 14|1@0+ (1,0) [0|0] "" XXX + SG_ ThirdRowBuckleDriver : 25|2@0+ (1,0) [0|0] "" XXX + SG_ ThirdRowBuckleDriver_UB : 13|1@0+ (1,0) [0|0] "" XXX + SG_ ThirdRowBucklePsngr : 37|2@0+ (1,0) [0|0] "" XXX + SG_ ThirdRowBucklePsngr_UB : 11|1@0+ (1,0) [0|0] "" XXX + SG_ WheelRotationCnt : 47|8@0+ (1,0) [0|0] "" XXX + SG_ WheelRotationCnt_UB : 9|1@0+ (1,0) [0|0] "" XXX + SG_ WheelRotationCntQF : 35|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRr_D_Actl_UB_40 : 2|1@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRr_D_Actl_40 : 39|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRl_D_Actl_UB_40 : 1|1@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRl_D_Actl_40 : 33|2@0+ (1,0) [0|0] "" XXX + +BO_ 131 MS_Steering_Data: 8 XXX + SG_ SteColumn_Status_UB : 28|1@0+ (1,0) [0|0] "" XXX + SG_ SteColumn_Status : 31|3@0+ (1,0) [0|0] "" XXX + SG_ SteCol_Manual_Override_UB : 26|1@0+ (1,0) [0|0] "" XXX + SG_ SteCol_Manual_Override : 27|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Send_UB : 20|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Send : 6|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Phone_UB : 17|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Phone : 3|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_OK_UB : 16|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_OK : 2|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Volume_Up_UB : 23|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Volume_Down_UB : 22|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Voice_PTT_UB : 21|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Seek_Right_UB : 19|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Seek_Left_UB : 18|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Mode_UB : 11|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Mode : 13|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Media_UB : 9|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Volume_Up : 15|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Volume_Down : 14|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Voice_PTT : 7|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Seek_Right : 5|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Seek_Left : 4|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Media : 1|1@0+ (1,0) [0|0] "" XXX + SG_ VehYaw_W_Actl : 55|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + SG_ SteWhlCtl_End_UB : 8|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_End : 0|1@0+ (1,0) [0|0] "" XXX + SG_ VehYaw_W_Actl_UB : 40|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Mute_UB : 10|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Mute : 12|1@0+ (1,0) [0|0] "" XXX + +BO_ 257 Driver_Seat_Information: 8 XXX + SG_ Reverse_Mirror_Stat : 3|2@0+ (1,0) [0|0] "" XXX + SG_ Memory_Feedback_Rqst : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Easy_Entry_Exit_Stat : 7|2@0+ (1,0) [0|0] "" XXX + +BO_ 260 Driver_Seat_Information_2: 8 XXX + SG_ Memory_Cmd : 15|4@0+ (1,0) [0|0] "" XXX + SG_ Easy_Entry_Rqst : 4|2@0+ (1,0) [0|0] "" XXX + SG_ DrvSeat_Stat : 7|3@0+ (1,0) [0|0] "" XXX + SG_ Cancel_Auto_Movement : 1|1@0+ (1,0) [0|0] "" XXX + +BO_ 269 IdleShutdown_Legacy: 8 XXX + SG_ IDLE_ENGINE_SHUTDOWN : 23|2@0+ (1,0) [0|0] "" XXX + +BO_ 272 Keyfob_Pad_Stat: 8 XXX + SG_ L_Pwr_Sliding_Dr_Rqst : 28|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Decklid_Rqst : 31|1@0+ (1,0) [0|0] "" XXX + SG_ R_Pwr_Sliding_Dr_Rqst : 29|1@0+ (1,0) [0|0] "" XXX + SG_ Keyfob_Pad_Msg_Count : 23|8@0+ (1,0) [0|0] "Counts" XXX + SG_ Keyfob_Pad_Id_Number : 15|8@0+ (1,0) [0|0] "" XXX + SG_ Keyfob_Pad_Button_Pressed : 7|8@0+ (1,0) [0|0] "" XXX + SG_ Power_Liftgate_Rqst : 30|1@0+ (1,0) [0|0] "" XXX + SG_ Keycode_Status : 27|20@0+ (1,0) [0|0] "" XXX + +BO_ 275 Power_Liftgate_Mode_StatM: 8 XXX + SG_ Power_Liftgate_Mode_Stat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ DrTgateChime_D_Rq : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 276 Running_Board_CmdM: 8 XXX + SG_ Running_Board_Cmd : 7|2@0+ (1,0) [0|0] "" XXX + +BO_ 277 Running_Board_StatM: 8 XXX + SG_ Running_Board_Stat : 7|2@0+ (1,0) [0|0] "" XXX + +BO_ 288 ClmtCtrlSeat_SetCmdlegacy1: 8 XXX + SG_ ClmtCtrlSeat_SetCmd_Dvr : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 289 ClmtCtrlSeat_SetStat_DvrM: 8 XXX + SG_ ClmtCtrlSeat_SetStat_Dvr : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 290 ClmtCtrlSeat_SetCmdlegacy2: 8 XXX + SG_ ClmtCtrlSeat_SetCmd_Psgr : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 291 ClmtCtrlSeat_SetStat_PsgrM: 8 XXX + SG_ ClmtCtrlSeat_SetStat_Psgr : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 292 ClmtCtrlSeatSet_Cmd_v2_MS: 8 XXX + SG_ ClmtCtrlSeat_SetCmd_Psgr : 15|8@0+ (1,0) [0|0] "" XXX + SG_ ClmtCtrlSeat_SetCmd_Dvr : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 293 ClmtCtrlSeatSet_Stat_v2: 8 XXX + SG_ ClmtCtrlSeat_SetStat_Psgr : 15|8@0+ (1,0) [0|0] "" XXX + SG_ ClmtCtrlSeat_SetStat_Dvr : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 304 Mirror_Manual_Override_M: 8 XXX + SG_ Mirror_Manual_Override : 7|1@0+ (1,0) [0|0] "Binary" XXX + +BO_ 305 Memory_Sw_StatM: 8 XXX + SG_ Memory_Sw_Message_Count : 15|8@0+ (1,0) [0|0] "Counts" XXX + SG_ Memory_Set_Sw_Stat : 7|1@0+ (1,0) [0|0] "Binary" XXX + SG_ Memory_Set_Cancel : 3|1@0+ (1,0) [0|0] "Binary" XXX + SG_ Memory_3_Sw_Stat : 4|1@0+ (1,0) [0|0] "Binary" XXX + SG_ Memory_2_Sw_Stat : 5|1@0+ (1,0) [0|0] "Binary" XXX + SG_ Memory_1_Sw_Stat : 6|1@0+ (1,0) [0|0] "Binary" XXX + +BO_ 306 Driver_Lock_Sw_StatM: 8 XXX + SG_ Driver_Door_Key_Unlock : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Driver_Door_Key_Lock : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Driver_Lock_Sw_Message_Cnt : 7|8@0+ (1,0) [0|0] "Counts" XXX + SG_ Driver_Lock_Sw_Stat : 15|2@0+ (1,0) [0|0] "" XXX + +BO_ 309 Memory_Cancel_Cmd_M: 8 XXX + SG_ Memory_Cancel_Cmd : 7|1@0+ (1,0) [0|0] "Binary" XXX + +BO_ 310 Driver_Door_Lock_CmdM: 8 XXX + SG_ Driver_Door_Lock_Msg_Cnt : 7|8@0+ (1,0) [0|0] "Counts" XXX + SG_ Driver_Door_Lock_Cmd : 15|4@0+ (1,0) [0|0] "" XXX + +BO_ 311 Pass_Mirror_Sw_StatM: 8 XXX + SG_ Pass_Mirror_Sw_UD_Stat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Pass_Mirror_Sw_LR_Stat : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 313 RPwrSlideDr_Unlock_RqstM: 8 XXX + SG_ RPwrSlideDr_Unlock_Rqst : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 320 LPwrSlideDr_Unlock_RqstM: 8 XXX + SG_ LPwrSlideDr_Unlock_Rqst : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 321 Passive_Entry_Ctrl_Data: 8 XXX + SG_ PE_Control_Data_1 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Control_Cmd : 7|3@0+ (1,0) [0|0] "" XXX + SG_ PK_SearchResults_Prog : 63|4@0+ (1,0) [0|0] "" XXX + SG_ PK_SearchResults_MyKey : 4|4@0+ (1,0) [0|0] "" XXX + SG_ PK_SearchResults_Found : 59|4@0+ (1,0) [0|0] "" XXX + SG_ PK_Search_EvNum : 15|8@0+ (1,0) [0|0] "Counts" XXX + SG_ PE_Control_Data_5 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Control_Data_4 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Control_Data_3 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Control_Data_2 : 31|8@0+ (1,0) [0|0] "" XXX + +BO_ 322 Passive_Entry_Target_Data: 8 XXX + SG_ PE_Target_Data_5 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Target_Cmd : 7|2@0+ (1,0) [0|0] "" XXX + SG_ PE_Target_Status : 5|1@0+ (1,0) [0|0] "" XXX + SG_ PE_Target_Data_1 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Search_Rqst : 4|2@0+ (1,0) [0|0] "" XXX + SG_ PE_Target_Data_4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Target_Data_3 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Target_Data_2 : 23|8@0+ (1,0) [0|0] "" XXX + +BO_ 577 BCM_m_FrP28: 8 XXX + SG_ WheelRotToothCntFrL : 15|8@0+ (1,0) [0|0] "" XXX + SG_ WheelRotToothCntFrL_UB : 42|1@0+ (1,0) [0|0] "" XXX + SG_ WheelRotToothCntFrR : 23|8@0+ (1,0) [0|0] "" XXX + SG_ WheelRotToothCntFrR_UB : 41|1@0+ (1,0) [0|0] "" XXX + SG_ WheelRotToothCntReL : 31|8@0+ (1,0) [0|0] "" XXX + SG_ WheelRotToothCntReL_UB : 40|1@0+ (1,0) [0|0] "" XXX + SG_ WheelRotToothCntReR : 39|8@0+ (1,0) [0|0] "" XXX + SG_ WheelRotToothCntReR_UB : 43|1@0+ (1,0) [0|0] "" XXX + +BO_ 736 FCIM_Button_Press: 8 XXX + SG_ FCIM_Target_ID : 13|4@0+ (1,0) [0|0] "" XXX + SG_ FCIM_Button_Type : 7|8@0+ (1,0) [0|0] "" XXX + SG_ FCIM_Button_State : 15|2@0+ (1,0) [0|0] "" XXX + +BO_ 806 Compressor_Req: 8 XXX + SG_ HvacEvap_Te_Rq : 33|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + SG_ HvacEvap_Te_Actl : 17|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + SG_ HvacAirCond_B_Rq : 7|1@0+ (1,0) [0|0] "" XXX + SG_ HvacEvap_Te_Offst : 1|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + +BO_ 842 MassageSeat_Data1: 8 XXX + SG_ SeatLmbrUpDrv_Pc_Actl : 38|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatLmbrMidDrv_Pc_Actl : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatLmbrLoDrv_Pc_Actl : 22|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatBlUpDrv_Pc_Actl : 14|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatBlLoDrv_Pc_Actl : 6|7@0+ (1,0) [0|0] "%" XXX + +BO_ 843 MassageSeat_Data2: 8 XXX + SG_ SeatLmbrUpPsgr_Pc_Actl : 38|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatLmbrMidPsgr_Pc_Actl : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatLmbrLoPsgr_Pc_Actl : 22|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatBlUpPsgr_Pc_Actl : 14|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatBlLoPsgr_Pc_Actl : 6|7@0+ (1,0) [0|0] "%" XXX + +BO_ 844 MassageSeat_Stat1: 8 XXX + SG_ StmsLmbrDrv_D_Stat : 17|2@0+ (1,0) [0|0] "" XXX + SG_ StmsCshnDrv_D_Stat : 19|2@0+ (1,0) [0|0] "" XXX + SG_ SeatSwtchDrv_B_Stat : 31|1@0+ (1,0) [0|0] "" XXX + SG_ SeatFnDrv_D_Stat : 23|3@0+ (1,0) [0|0] "" XXX + SG_ SeatAirAmb_P_Actl : 7|16@0+ (0.01,0) [0|0] "KiloPascal" XXX + SG_ SeatPDrv_B_Stat : 20|1@0+ (1,0) [0|0] "" XXX + +BO_ 845 MassageSeat_Stat2: 8 XXX + SG_ StmsLmbrPsgr_D_Stat : 15|2@0+ (1,0) [0|0] "" XXX + SG_ StmsCshnPsgr_D_Stat : 13|2@0+ (1,0) [0|0] "" XXX + SG_ SeatSwtchPsgr_B_Stat : 11|1@0+ (1,0) [0|0] "" XXX + SG_ SeatPPsgr_B_Stat : 7|1@0+ (1,0) [0|0] "" XXX + SG_ SeatFnPsgr_D_Stat : 6|3@0+ (1,0) [0|0] "" XXX + SG_ PsgrMemFeedback_Rsp : 3|4@0+ (1,0) [0|0] "" XXX + +BO_ 846 MassageSeat_Req_MS: 8 XXX + SG_ SeatFnPsgr_D_Rq : 15|3@0+ (1,0) [0|0] "" XXX + SG_ SeatFnDrv_D_Rq : 12|3@0+ (1,0) [0|0] "" XXX + SG_ SeatFnDfaltPsgr_B_Rq : 9|1@0+ (1,0) [0|0] "" XXX + SG_ SeatFnDfaltDrv_B_Rq : 8|1@0+ (1,0) [0|0] "" XXX + SG_ SeatFnChngPsgr_D_Rq : 7|2@0+ (1,0) [0|0] "" XXX + SG_ SeatFnChngDrv_D_Rq : 5|2@0+ (1,0) [0|0] "" XXX + SG_ PsgrMemory_Rq : 3|4@0+ (1,0) [0|0] "" XXX + +BO_ 849 MassageSeat_Data3: 8 XXX + SG_ SeatCshnDrvRR_Pc_Actl : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnDrvRL_Pc_Actl : 22|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnDrvFR_Pc_Actl : 14|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnDrvFL_Pc_Actl : 6|7@0+ (1,0) [0|0] "%" XXX + +BO_ 850 MassageSeat_Data4: 8 XXX + SG_ SeatCshnPsgrRR_Pc_Actl : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnPsgrRL_Pc_Actl : 22|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnPsgrFR_Pc_Actl : 14|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnPsgrFL_Pc_Actl : 6|7@0+ (1,0) [0|0] "%" XXX + +BO_ 853 EFP_CC_Status_MS: 8 XXX + SG_ Save_My_Temp : 59|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Left_Temp_Setpt : 31|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RrDefrost_HtdMirrorReq : 60|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Control_Status : 16|1@0+ (1,0) [0|0] "" XXX + SG_ MultipleButtonPressReq : 63|3@0+ (1,0) [0|0] "" XXX + SG_ Rear_System_Mode_Req : 19|3@0+ (1,0) [0|0] "" XXX + SG_ Recirc_Request : 23|2@0+ (1,0) [0|0] "" XXX + SG_ Front_Rt_Temp_Setpt : 39|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ AC_Request : 21|2@0+ (1,0) [0|0] "" XXX + SG_ Windshield_ModeRequest : 15|4@0+ (8.33,0) [0|0] "%" XXX + SG_ Panel_Mode_Request : 7|4@0+ (8.33,0) [0|0] "%" XXX + SG_ Overriding_ModeReq : 10|3@0+ (1,0) [0|0] "" XXX + SG_ Floor_Mode_Request : 3|4@0+ (8.33,0) [0|0] "%" XXX + SG_ Rear_Right_Temp_Setpt : 55|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ Forced_Recirc_Req : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Left_Temp_Setpt : 47|8@0+ (1,0) [0|0] "Mixed" XXX + +BO_ 854 EFP_CC_Seat_Req_Stat_MS: 8 XXX + SG_ Front_Rear_Blower_Req : 31|6@0+ (1,0) [0|0] "Detents" XXX + SG_ Pass_Rr_Cond_Seat_Req : 21|2@0+ (1,0) [0|0] "" XXX + SG_ Pass_Rr_Cond_Seat_Lvl : 8|3@0+ (1,0) [0|0] "" XXX + SG_ Pass_Fr_Cond_Seat_Req : 13|2@0+ (1,0) [0|0] "" XXX + SG_ Pass_Fr_Cond_Seat_Lvl : 11|3@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Rr_Cond_Seat_Req : 15|2@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Rr_Cond_Seat_Lvl : 2|3@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Fr_Cond_Seat_Req : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Fr_Cond_Seat_Lvl : 5|3@0+ (1,0) [0|0] "" XXX + +BO_ 855 RCCM_CC_Status: 8 XXX + SG_ RrBlwrCondStLdShedStat : 25|2@0+ (1,0) [0|0] "" XXX + SG_ FrBlwrCondStLdShedStat : 20|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_Rr_Rt_TempSetpt : 63|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RCCM_Rr_Left_TempSetpt : 55|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RCCM_Fr_Rt_TempSetpt : 47|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RCCM_Fr_Left_TempSetpt : 39|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RCCM_Fr_Rr_Blower_Req : 31|6@0+ (1,0) [0|0] "Detents" XXX + SG_ Panel_Mode_State : 7|4@0+ (8.33,0) [0|0] "%" XXX + SG_ RrDefHtdMirrLdShedStat : 18|2@0+ (1,0) [0|0] "" XXX + SG_ Windshield_Mode_State : 15|4@0+ (8.33,0) [0|0] "%" XXX + SG_ Recirc_Door_State : 11|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_System_Mode_State : 23|3@0+ (1,0) [0|0] "" XXX + SG_ Default_Defrost_State : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Auto_AC_Indicator_Temp : 16|1@0+ (1,0) [0|0] "" XXX + SG_ Floor_Mode_State : 3|4@0+ (8.33,0) [0|0] "%" XXX + SG_ RrDefrost_HtdMirrState : 8|1@0+ (1,0) [0|0] "" XXX + +BO_ 856 RCCM_CC_Seat_Status: 8 XXX + SG_ Active_My_Temp : 2|1@0+ (1,0) [0|0] "" XXX + SG_ CC_HtdStrWhl_Req : 24|1@0+ (1,0) [0|0] "" XXX + SG_ RCCM_PR_Cond_Seat_Lvl : 31|3@0+ (1,0) [0|0] "" XXX + SG_ RCCM_PR_Cond_Seat_Req : 28|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_PF_Cond_Seat_Req : 20|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_PF_Cond_Seat_Lvl : 23|3@0+ (1,0) [0|0] "" XXX + SG_ RCCM_DR_Cond_Seat_Req : 12|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_DR_Cond_Seat_Lvl : 15|3@0+ (1,0) [0|0] "" XXX + SG_ RCCM_DF_Cond_Seat_Req : 4|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_DF_Cond_Seat_Lvl : 7|3@0+ (1,0) [0|0] "" XXX + SG_ PassRrCondStLdShedStat : 26|2@0+ (1,0) [0|0] "" XXX + SG_ PassFrCondStLdShedStat : 18|2@0+ (1,0) [0|0] "" XXX + SG_ DrvRrCondStLdShedStat : 10|2@0+ (1,0) [0|0] "" XXX + SG_ DrvFrCondStLdShedStat : 1|2@0+ (1,0) [0|0] "" XXX + +BO_ 857 RCCM_CC_MBP_Press_Stat: 8 XXX + SG_ Report_Active : 33|2@0+ (1,0) [0|0] "" XXX + SG_ Pass_Temp_Units : 35|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Fan_Bars_Disply : 39|3@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Temp_Units : 36|1@0+ (1,0) [0|0] "" XXX + SG_ MultBtnPushDsplyPass10 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ MultBtnPushDsplyPass1 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ MultBtnPushDsplyDrvr10 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ MultBtnPushDsplyDrvr1 : 15|8@0+ (1,0) [0|0] "" XXX + +BO_ 859 MFD_CC_Status_MS: 8 XXX + SG_ Rear_Mode_Bttn_Status : 38|1@0+ (1,0) [0|0] "" XXX + +BO_ 860 EFP_CC_Info_Status_MS: 8 XXX + SG_ Rear_Panel_Btn_State : 41|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Floor_Btn_State : 40|1@0+ (1,0) [0|0] "" XXX + SG_ HtdStrWhl_SftBtt_Stt : 39|2@0+ (1,0) [0|0] "" XXX + SG_ AC_Sft_Button_State : 23|2@0+ (1,0) [0|0] "" XXX + SG_ DrvRrCondSeatSftBttnSt : 47|3@0+ (1,0) [0|0] "" XXX + SG_ DrvFrCondSeatSftBtnStt : 37|3@0+ (1,0) [0|0] "" XXX + SG_ CC_RecircSBtn_St : 27|2@0+ (1,0) [0|0] "" XXX + SG_ CC_RrDefrSBtn_St : 24|1@0+ (1,0) [0|0] "" XXX + SG_ PasRrCondSeatSftBttnSt : 44|3@0+ (1,0) [0|0] "" XXX + SG_ PasFrCondSeatSftBtnStt : 34|3@0+ (1,0) [0|0] "" XXX + SG_ MyTemp_Soft_Bttn_State : 25|1@0+ (1,0) [0|0] "" XXX + SG_ CC_MaxACSBtn_St : 28|1@0+ (1,0) [0|0] "" XXX + SG_ RearPowerButtonState : 16|1@0+ (1,0) [0|0] "" XXX + SG_ RearCoolBarsDisplayed : 11|3@0+ (1,0) [0|0] "Bars_On" XXX + SG_ Rear_Sft_Control_Stat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ CC_RrNeutralBarDsp_St : 8|1@0+ (1,0) [0|0] "" XXX + SG_ CC_RrHeatBarsDsp_St : 31|3@0+ (1,0) [0|0] "Bars_On" XXX + SG_ Rear_Fan_Bars_Displayed : 19|3@0+ (1,0) [0|0] "" XXX + SG_ CC_RrCtrlBtn_St : 20|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Auto_Button_State : 21|1@0+ (1,0) [0|0] "" XXX + SG_ CC_FrPowerSBtn_St : 14|1@0+ (1,0) [0|0] "" XXX + SG_ CC_FrDefrostSBtn_St : 15|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_Soft_Btn_Stt : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_MODE_State : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_FAN_State : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Dual_Button_State : 12|1@0+ (1,0) [0|0] "" XXX + SG_ CC_BarPnlSBtn_St : 5|1@0+ (1,0) [0|0] "" XXX + SG_ CC_BarPnFlrSBtn_St : 4|1@0+ (1,0) [0|0] "" XXX + SG_ CC_BarFlrWsSBtn_St : 2|1@0+ (1,0) [0|0] "" XXX + SG_ CC_BarDrvFlrSBtn_St : 3|1@0+ (1,0) [0|0] "" XXX + +BO_ 861 HSWheel_CC_Info_Stat: 8 XXX + SG_ HtdStrWhl_SftBtt_State : 57|2@0+ (1,0) [0|0] "" XXX + +BO_ 862 Climate_Control_Data_2: 8 XXX + SG_ HvacRec_Pc_Est : 31|7@0+ (1,0) [0|0] "%" XXX + SG_ HvacEngIdleInc_B_Rq : 24|1@0+ (1,0) [0|0] "" XXX + SG_ HvacAir_Flw_Est : 13|9@0+ (0.5,0) [0|0] "liter/second" XXX + SG_ AmbTempImpr : 7|10@0+ (0.25,-128.0) [0|0] "degreesC" XXX + +BO_ 900 Vehicle_Access_RqstM: 8 XXX + SG_ PE_AssocConfirm_D_Actl : 63|3@0+ (1,0) [0|0] "" XXX + SG_ DrTgateOpen_D_RqRfa : 51|2@0+ (1,0) [0|0] "" XXX + SG_ PE_Decklid_Inhibit_Rqst : 53|2@0+ (1,0) [0|0] "" XXX + SG_ PK_Program : 45|2@0+ (1,0) [0|0] "" XXX + SG_ PE_Packet_Cnt : 31|8@0+ (1,0) [0|0] "Counts" XXX + SG_ PE_Control_Status : 33|2@0+ (1,0) [0|0] "" XXX + SG_ PE_Control_Code : 7|8@0+ (1,0) [0|0] "" XXX + SG_ PE_Perimeter_Lighting_Stat : 15|2@0+ (1,0) [0|0] "" XXX + SG_ PE_RKE_Flash_Rqst : 34|1@0+ (1,0) [0|0] "" XXX + SG_ PE_Lock_EvNum : 23|8@0+ (1,0) [0|0] "Counts" XXX + SG_ PE_Lock_Requestor : 39|5@0+ (1,0) [0|0] "" XXX + SG_ PE_Lock_Sub_Id : 11|4@0+ (1,0) [0|0] "" XXX + SG_ PE_Lock_Status : 13|2@0+ (1,0) [0|0] "" XXX + SG_ PE_DrvCfg_Horn_Rqst : 47|2@0+ (1,0) [0|0] "" XXX + SG_ PEBackupSlot_Stats : 55|2@0+ (1,0) [0|0] "" XXX + SG_ PE_Fob_Number : 43|4@0+ (1,0) [0|0] "Number" XXX + SG_ PE_Keypad_LiftGlass_Rqst : 49|1@0+ (1,0) [0|0] "" XXX + +BO_ 901 Vehicle_Lock_Status: 8 XXX + SG_ CntrStkKeycodeActl : 55|16@0+ (1,0) [0|0] "" XXX + SG_ CntrStk_D_RqAssoc_UB : 40|1@0+ (1,0) [0|0] "" XXX + SG_ CntrStk_D_RqAssoc : 43|3@0+ (1,0) [0|0] "" XXX + SG_ KeyTypeChngMykey_D_Rq : 45|2@0+ (1,0) [0|0] "" XXX + SG_ Veh_Lock_Sub_Id : 21|4@0+ (1,0) [0|0] "" XXX + SG_ Veh_Lock_Status : 17|2@0+ (1,0) [0|0] "" XXX + SG_ Veh_Lock_Requestor : 39|5@0+ (1,0) [0|0] "" XXX + SG_ Veh_Lock_EvNum : 31|8@0+ (1,0) [0|0] "Counts" XXX + SG_ Trim_Switch_Status_Count : 15|8@0+ (1,0) [0|0] "Counts" XXX + SG_ Trim_Switch_Status : 23|2@0+ (1,0) [0|0] "" XXX + SG_ DF_KeyCyl_Switch_Stat_Cnt : 7|8@0+ (1,0) [0|0] "Counts" XXX + SG_ DF_KeyCyl_Switch_Stat : 34|2@0+ (1,0) [0|0] "" XXX + SG_ Perimeter_Alarm_Status : 47|2@0+ (1,0) [0|0] "" XXX + SG_ KeyTypeChngMykey_D_Rq_UB : 32|1@0+ (1,0) [0|0] "" XXX + +BO_ 902 Remote_Start: 8 XXX + SG_ Remote_Start_Req : 7|2@0+ (1,0) [0|0] "" XXX + +BO_ 903 CC_FCIM_Update: 8 XXX + SG_ Rr_Temp_M_H_Heat_Ind : 30|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Fan_7_Indicator : 45|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Fan_6_Indicator : 46|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Fan_5_Indicator : 47|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Fan_4_Indicator : 32|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Fan_3_Indicator : 33|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Fan_2_Indicator : 34|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Fan_Low_Indicator : 35|1@0+ (1,0) [0|0] "" XXX + SG_ AC_Indicator : 36|1@0+ (1,0) [0|0] "" XXX + SG_ Floor_Mode_Indicator : 37|1@0+ (1,0) [0|0] "" XXX + SG_ Panel_Mode_Indicator : 38|1@0+ (1,0) [0|0] "" XXX + SG_ Windshield_Mode_Indicator : 39|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Temp_High_Cool_Ind : 24|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Temp_M_H_Cool_Ind : 25|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Temp_M_L_Cool_Ind : 26|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Temp_Low_Cool_Ind : 27|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Temp_Center_Ind_On : 28|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Temp_High_Heat_Ind : 29|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Temp_M_L_Heat_Ind : 31|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Temp_Low_Heat_Ind : 16|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Control_Indicator : 17|1@0+ (1,0) [0|0] "" XXX + SG_ Auto_Indicator_Rear : 18|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Indicator_Rear : 19|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_U_R_Seat_Cool_Ind : 20|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_M_Seat_Cool_Ind : 21|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_L_L_Seat_Cool_Ind : 22|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_U_R_Seat_Heat_Ind : 23|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_M_Seat_Heat_Ind : 8|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_L_L_Seat_Heat_Ind : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_U_R_Seat_Cool_Ind : 10|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_M_Seat_Cool_Ind : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_L_L_Seat_Cool_Ind : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_U_R_Seat_Heat_Ind : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_M_Seat_Heat_Ind : 14|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_L_L_Seat_Heat_Ind : 15|1@0+ (1,0) [0|0] "" XXX + SG_ Single_Mode_Indicator : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Auto_Indicator : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Recirc_Indicator : 2|1@0+ (1,0) [0|0] "" XXX + SG_ Max_AC_Econ_Indicator : 3|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_DefHtd_Mirr_Indicator : 4|1@0+ (1,0) [0|0] "" XXX + SG_ Defrost_Indicator : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Temp_Dual_Indicator : 6|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Indicator_Front : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 904 CC_NavChassis_Info_Status: 8 XXX + SG_ Rear_Defrost_Soft_Bttn_Stt : 52|1@0+ (1,0) [0|0] "" XXX + SG_ Recirc_Soft_Button_State : 54|2@0+ (1,0) [0|0] "" XXX + SG_ Max_AC_Soft_Button_State : 55|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_Soft_Btn_Stt : 24|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Power_Soft_Btn_State : 25|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Defrost_Soft_Btn_Stt : 26|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Power_Button_State : 33|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_FAN_Indicator : 27|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_MODE_Indicator : 28|1@0+ (1,0) [0|0] "" XXX + SG_ CC_Bar_Rear_Set_Temp_Display : 17|1@0+ (1,0) [0|0] "" XXX + SG_ CC_Bar_Rear_Set_Temp_Units : 19|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_Heat_Bars_Displayed : 42|3@0+ (1,0) [0|0] "Bars_On" XXX + SG_ CC_Bar_Rear_Set_Temp_Dig3 : 21|2@0+ (1,0) [0|0] "" XXX + SG_ CC_Bar_Rear_Set_Temp_Dig2 : 15|8@0+ (1,0) [0|0] "ASCII" XXX + SG_ CC_Bar_Rear_Set_Temp_Dig1 : 7|8@0+ (1,0) [0|0] "ASCII" XXX + SG_ Rear_Neutral_Bar_Displayed : 43|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Fan_Bars_Displayed : 46|3@0+ (1,0) [0|0] "" XXX + SG_ Rear_Control_Button_State : 47|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Auto_Button_State : 32|1@0+ (1,0) [0|0] "" XXX + SG_ AC_Sft_Button_State : 35|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_Cool_Bars_Displayed : 38|3@0+ (1,0) [0|0] "Bars_On" XXX + SG_ Dual_Button_State : 39|1@0+ (1,0) [0|0] "" XXX + SG_ CC_Bar_Sft_Btn_FlrWs_State : 29|1@0+ (1,0) [0|0] "" XXX + SG_ CC_Bar_Sft_Btn_Floor_State : 30|1@0+ (1,0) [0|0] "" XXX + SG_ CC_Bar_Sft_Btn_PnFlr_State : 31|1@0+ (1,0) [0|0] "" XXX + SG_ CC_Bar_Sft_Btn_Pnl_State : 16|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Sft_Control_Status : 23|2@0+ (1,0) [0|0] "" XXX + +BO_ 920 FCIM_CC_Status: 8 XXX + SG_ Manual_Temp_Knob_Pos : 8|9@0+ (1,0) [0|0] "Degrees CW" XXX + SG_ Manual_Blower_Knob_Pos : 24|9@0+ (1,0) [0|0] "Degrees CW" XXX + SG_ Rear_Blower_IncreaseButton : 40|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Blower_DecreaseButton : 55|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Temp_Decrease_Button : 41|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Temp_Increase_Button : 42|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Control_Button : 43|1@0+ (1,0) [0|0] "" XXX + SG_ Auto_Button_Rear : 44|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Button_Rear : 45|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_Heated_Seat_Btn : 47|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_Cooled_Seat_Btn : 46|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_Cooled_Seat_Btn : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_Heated_Seat_Btn : 10|1@0+ (1,0) [0|0] "" XXX + SG_ Blower_Decrease_Button : 25|1@0+ (1,0) [0|0] "" XXX + SG_ Blower_Increase_Button : 26|1@0+ (1,0) [0|0] "" XXX + SG_ Floor_Defrost_Mode_Button : 27|1@0+ (1,0) [0|0] "" XXX + SG_ Floor_Mode_Button : 28|1@0+ (1,0) [0|0] "" XXX + SG_ Panel_Floor_Mode_Button : 29|1@0+ (1,0) [0|0] "" XXX + SG_ Panel_Mode_Button : 30|1@0+ (1,0) [0|0] "" XXX + SG_ Mode_Change_Button : 31|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_Temp_Increase : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_Temp_Decrease : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_Temp_Decrease : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Lft_Side_Temp_Increase : 14|1@0+ (1,0) [0|0] "" XXX + SG_ Auto_Button_Front : 15|1@0+ (1,0) [0|0] "" XXX + SG_ Recirc_Button : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Max_AC_Econ_Button : 1|1@0+ (1,0) [0|0] "" XXX + SG_ AC_Button : 2|1@0+ (1,0) [0|0] "" XXX + SG_ Rr_Def_Htd_Mirr_Button : 3|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Defrost_Button : 4|1@0+ (1,0) [0|0] "" XXX + SG_ Rt_Side_Temp_Dual_Button : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Button_Front : 6|1@0+ (1,0) [0|0] "" XXX + SG_ Climate_Button : 7|1@0+ (1,0) [0|0] "" XXX + SG_ CcdMde_D_Rq : 54|2@0+ (1,0) [0|0] "" XXX + +BO_ 921 Nav_CC_Status: 8 XXX + SG_ Front_System_Button_Status : 7|5@0+ (1,0) [0|0] "" XXX + SG_ Rear_Temp_Button_Status : 23|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_Man_Temp_Bar_Status : 11|4@0+ (1,0) [0|0] "" XXX + SG_ Rear_Fan_Button_Status : 13|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_Man_ATC_Button_Status : 15|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_Blower_Bar_Status : 2|3@0+ (1,0) [0|0] "# of Bars" XXX + +BO_ 922 VoiceRec_CC_Request: 8 XXX + SG_ Recirculate_On : 10|1@0+ (1,0) [0|0] "" XXX + SG_ Recirculate_Off : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Defrost_On : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Defrost_Off : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Max_AC_On : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Max_AC_Off : 15|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Defrost_On : 14|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Defrost_Off : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Blower_Increment : 8|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Blower_Decrement : 23|1@0+ (1,0) [0|0] "" XXX + SG_ Dual_Zone_Off : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Driver_Temp_Increment : 22|1@0+ (1,0) [0|0] "" XXX + SG_ Driver_Temp_Decrement : 21|1@0+ (1,0) [0|0] "" XXX + SG_ Climate_On : 4|1@0+ (1,0) [0|0] "" XXX + SG_ Climate_Off : 3|1@0+ (1,0) [0|0] "" XXX + SG_ Automatic_Mode : 6|1@0+ (1,0) [0|0] "" XXX + SG_ AC_On : 2|1@0+ (1,0) [0|0] "" XXX + SG_ AC_Off : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Voice_Blower_Limit : 7|1@0+ (1,0) [0|0] "" XXX + SG_ Driver_Set_Temp : 31|8@0+ (0.5,0) [0|0] "Degrees" XXX + +BO_ 928 Ignition_Switch_PositionM: 8 XXX + SG_ AirAmb_Te_ActlFilt_UB : 14|1@0+ (1,0) [0|0] "" XXX + SG_ AirAmb_Te_ActlFilt : 49|10@0+ (0.25,-128.0) [0|0] "deg C" XXX + SG_ OdometerMasterValue_UB : 15|1@0+ (1,0) [0|0] "" XXX + SG_ OdometerMasterValue : 31|24@0+ (1,0) [0|0] "km" XXX + SG_ Remote_Start_Status : 13|2@0+ (1,0) [0|0] "" XXX + SG_ Key_In_Ignition_Stat : 3|2@0+ (1,0) [0|0] "" XXX + SG_ Ignition_Switch_Stable : 1|2@0+ (1,0) [0|0] "" XXX + SG_ Ignition_Status : 7|4@0+ (1,0) [0|0] "" XXX + SG_ BOO_Switch_Status : 9|2@0+ (1,0) [0|0] "" XXX + SG_ Remote_Device_Feedback : 23|3@0+ (1,0) [0|0] "" XXX + +BO_ 934 Side_Detect_L_StatusM: 8 XXX + SG_ Cross_Traffic_L_SnState : 23|2@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_L_SysOpState : 3|2@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_L_SnsrState : 1|2@0+ (1,0) [0|0] "" XXX + SG_ Side_Detect_L_Illum : 15|8@0+ (1,0) [0|0] "%" XXX + SG_ Side_Detect_L_Detect : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_L_Op_State : 21|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_L_Alert : 19|2@0+ (1,0) [0|0] "" XXX + SG_ Side_Detect_L_Alert : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 935 Side_Detect_R_StatusM: 8 XXX + SG_ Cross_Traffic_R_Alert : 23|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_R_SnState : 19|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_R_Op_State : 21|2@0+ (1,0) [0|0] "" XXX + SG_ Side_Detect_R_Detect : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Side_Detect_R_Illum : 15|8@0+ (1,0) [0|0] "%" XXX + SG_ SideDetect_R_SnsrState : 1|2@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_R_SysOpState : 3|2@0+ (1,0) [0|0] "" XXX + SG_ Side_Detect_R_Alert : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 944 Body_Information_6_MS: 8 XXX + SG_ DRV_SELECT_STAT : 3|4@0+ (1,0) [0|0] "" XXX + SG_ reserve_2bits : 7|2@0+ (1,0) [0|0] "" XXX + SG_ reserve_2 : 5|1@0+ (1,0) [0|0] "" XXX + SG_ reserve_3 : 4|1@0+ (1,0) [0|0] "" XXX + +BO_ 945 Ajar_Stat: 8 XXX + SG_ Decklid_Ajar_Status : 3|1@0+ (1,0) [0|0] "" XXX + SG_ Hood_Ajar_Status : 0|1@0+ (1,0) [0|0] "" XXX + SG_ LG_Glass_Ajar_Status : 2|1@0+ (1,0) [0|0] "" XXX + SG_ DF_Door_Ajar_Status : 7|1@0+ (1,0) [0|0] "" XXX + SG_ PF_Door_Ajar_Status : 6|1@0+ (1,0) [0|0] "" XXX + SG_ DR_Door_Ajar_Status : 5|1@0+ (1,0) [0|0] "" XXX + SG_ PR_Door_Ajar_Status : 4|1@0+ (1,0) [0|0] "" XXX + SG_ LG_Door_Ajar_Status : 1|1@0+ (1,0) [0|0] "" XXX + +BO_ 946 Body_Information_5_MS: 8 XXX + SG_ CoolantFanStepAct_UB : 8|1@0+ (1,0) [0|0] "" XXX + SG_ AirCondRec_B_Rq_UB : 38|1@0+ (1,0) [0|0] "" XXX + SG_ AirCondRec_B_Rq : 39|1@0+ (1,0) [0|0] "" XXX + SG_ AirCondEvdc_D_Stats_UB : 34|1@0+ (1,0) [0|0] "" XXX + SG_ AirCondEvdc_D_Stats : 37|3@0+ (1,0) [0|0] "" XXX + SG_ AirCondClutch_B_Stats_UB : 19|1@0+ (1,0) [0|0] "" XXX + SG_ AirCondClutch_B_Stats : 20|1@0+ (1,0) [0|0] "" XXX + SG_ CoolantFanStepAct : 47|5@0+ (1,0) [0|0] "Steps" XXX + SG_ AirCondFluidHi_P_Actl_UB : 18|1@0+ (1,0) [0|0] "" XXX + SG_ AirCondFluidHi_P_Actl : 31|8@0+ (0.125,0) [0|0] "bar" XXX + SG_ SECONDARY_HEATER_STAT_UB : 63|1@0+ (1,0) [0|0] "" XXX + SG_ CURRENT_DRAW_UB : 62|1@0+ (1,0) [0|0] "" XXX + SG_ SECONDARY_HEATER_STAT : 40|1@0+ (1,0) [0|0] "" XXX + SG_ CURRENT_DRAW : 55|8@0+ (0.5,0) [0|0] "Amps" XXX + +BO_ 947 BodyInformation_3_MS: 8 XXX + SG_ CamraDefog_B_Req_UB : 58|1@0+ (1,0) [0|0] "" XXX + SG_ TrStats_D_Actl_UB : 48|1@0+ (1,0) [0|0] "" XXX + SG_ RearFog_Lamp_Dbnce_UB : 49|1@0+ (1,0) [0|0] "" XXX + SG_ TrStats_D_Actl : 13|2@0+ (1,0) [0|0] "" XXX + SG_ CamraDefog_B_Req : 40|1@0+ (1,0) [0|0] "" XXX + SG_ RearFog_Lamp_Dbnce : 0|1@0+ (1,0) [0|0] "" XXX + SG_ CarMode : 53|4@0+ (1,0) [0|0] "" XXX + SG_ Day_Night_Status : 15|2@0+ (1,0) [0|0] "" XXX + SG_ Parklamp_Status : 3|2@0+ (1,0) [0|0] "" XXX + SG_ Dimming_Lvl : 31|8@0+ (1,0) [0|0] "" XXX + SG_ Litval : 23|8@0+ (1,0) [0|0] "" XXX + SG_ Mfs_Turn_Stalk_SW_Status : 11|2@0+ (1,0) [0|0] "" XXX + SG_ PwMdeExten_D_Actl : 63|5@0+ (1,0) [0|0] "" XXX + SG_ STR_WHL_ANGLE : 39|15@0+ (0.1,-1000.0) [0|0] "Degrees" XXX + SG_ Turn_Seq_Cmd_Right : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Turn_Seq_Cmd_Left : 5|2@0+ (1,0) [0|0] "" XXX + SG_ Smart_Wiper_Motor_Stat_UB : 8|1@0+ (1,0) [0|0] "" XXX + SG_ Smart_Wiper_Motor_Stat : 55|2@0+ (1,0) [0|0] "" XXX + SG_ Mfs_Turn_Stalk_SW_Status_UB : 9|1@0+ (1,0) [0|0] "" XXX + SG_ reserve : 1|1@0+ (1,0) [0|0] "" XXX + +BO_ 950 RKE_Packet: 8 XXX + SG_ RemoteKey_Packet_TIC : 7|32@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Packet_RollB : 55|8@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Packet_RollA : 47|8@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Packet_Ctrl : 39|8@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Packet_CkSum : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 951 TPM_Frame: 8 XXX + SG_ TirePress_Frame_Temp : 47|8@0+ (1,0) [0|0] "" XXX + SG_ TirePress_Frame_Status : 55|8@0+ (1,0) [0|0] "" XXX + SG_ TirePress_Frame_Press : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TirePress_Frame_ID : 7|32@0+ (1,0) [0|0] "" XXX + SG_ TirePress_Frame_CkSum : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 952 RKE_TPM_Info: 8 XXX + SG_ TirePress_HitRate_Ctrl : 15|1@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_HitRate_Ctrl : 14|1@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Antenna_Ctrl : 7|2@0+ (1,0) [0|0] "" XXX + SG_ TirePress_Filter_Ctrl : 5|2@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Filter_Ctrl : 3|2@0+ (1,0) [0|0] "" XXX + SG_ Modulation_Ctrl : 1|2@0+ (1,0) [0|0] "" XXX + +BO_ 953 RKE_Info: 8 XXX + SG_ RemoteKey_Info_TIC : 7|32@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Info_RollB : 55|8@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Info_RollA : 47|8@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Info_Ctrl : 39|8@0+ (1,0) [0|0] "" XXX + SG_ RemoteKey_Info_CkSum : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 954 Tire_Pressure_Info: 8 XXX + SG_ TirePress_Info_MaxInd : 47|8@0+ (1,0) [0|0] "" XXX + SG_ TirePress_Info_Index : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TirePress_Info_ID : 7|32@0+ (1,0) [0|0] "" XXX + +BO_ 956 Body_Information_7_MS: 8 XXX + SG_ GearLvrPos_D_Actl_UB : 21|1@0+ (1,0) [0|0] "" XXX + SG_ PrplWhlTot_Tq_Actl : 31|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + SG_ GearLvrPos_D_Actl : 7|4@0+ (1,0) [0|0] "" XXX + SG_ ApedPos_Pc_ActlArb : 15|10@0+ (0.1,0) [0|0] "%" XXX + SG_ PrplWhlTot_Tq_Actl_UB : 17|1@0+ (1,0) [0|0] "" XXX + SG_ EngOff_T_Actl : 47|16@0+ (1,0) [0|0] "seconds" XXX + SG_ ApedPos_Pc_ActlArb_UB : 20|1@0+ (1,0) [0|0] "" XXX + +BO_ 958 Rear_FoglampStat: 8 XXX + SG_ RearFog_Lamp_Ind : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 963 BCM_to_MS_Body: 8 XXX + SG_ LF_Low_Beam_CKT_CAN : 2|1@0+ (1,0) [0|0] "" XXX + SG_ IKT_Program_Status : 51|2@0+ (1,0) [0|0] "" XXX + SG_ Veh_Spd_Slow_Puddle_Status : 41|2@0+ (1,0) [0|0] "" XXX + SG_ Illuminated_Exit_Status : 43|2@0+ (1,0) [0|0] "" XXX + SG_ Illuminated_Entry_Status : 45|2@0+ (1,0) [0|0] "" XXX + SG_ Door_Courtesy_Light_Status : 47|2@0+ (1,0) [0|0] "" XXX + SG_ Courtesy_Demand_BSave_Stat : 33|2@0+ (1,0) [0|0] "" XXX + SG_ Alarm_Lights_Courtesy_Stat : 35|2@0+ (1,0) [0|0] "" XXX + SG_ Courtesy_Delay_Status : 37|2@0+ (1,0) [0|0] "" XXX + SG_ Courtesy_Mode_Status : 39|2@0+ (1,0) [0|0] "" XXX + SG_ Front_Fog_Light_SW_Status : 22|2@0+ (1,0) [0|0] "" XXX + SG_ Brake_Lamp_On_Status : 23|1@0+ (1,0) [0|0] "" XXX + SG_ ParkLamps_CKT_CAN : 8|1@0+ (1,0) [0|0] "" XXX + SG_ RF_Low_Beam_CKT_CAN : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Brk_Fluid_Lvl_Low : 15|2@0+ (1,0) [0|0] "" XXX + SG_ Park_Brake_Status : 4|1@0+ (1,0) [0|0] "" XXX + SG_ High_Beam_Indicator_Rqst : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Headlamp_On_Wrning_Cmd : 6|1@0+ (1,0) [0|0] "" XXX + SG_ Key_In_Ignition_Warn_Cmd : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Park_Brake_Chime_Rqst : 3|1@0+ (1,0) [0|0] "" XXX + SG_ Daytime_Running_Lamps : 0|1@0+ (1,0) [0|0] "" XXX + SG_ AutoHighBeam_Cmd : 18|2@0+ (1,0) [0|0] "" XXX + SG_ Perimeter_Alarm_Chime_Rqst : 20|2@0+ (1,0) [0|0] "" XXX + SG_ OCSSensrDataUpperLim_UB : 11|1@0+ (1,0) [0|0] "" XXX + SG_ OCSSensrDataLowerLim_UB : 12|1@0+ (1,0) [0|0] "" XXX + SG_ OCSSensrDataUpperLim : 63|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSensrDataLowerLim : 31|8@0+ (1,0) [0|0] "" XXX + SG_ AutoHighBeam_Cmd_UB : 16|1@0+ (1,0) [0|0] "" XXX + SG_ PrkBrkActv_B_Actl : 7|1@0+ (1,0) [0|0] "" XXX + SG_ Headlamp_Switch_Stat : 49|2@0+ (1,0) [0|0] "" XXX + SG_ Perimeter_Alarm_Inclin_Cmd : 53|2@0+ (1,0) [0|0] "" XXX + SG_ Perimeter_Alarm_Intrus_Cmd : 55|2@0+ (1,0) [0|0] "" XXX + +BO_ 964 BodyInformation_2_MS: 8 XXX + SG_ LockInhibit : 41|1@0+ (1,0) [0|0] "" XXX + SG_ MetricActvTe_B_Actl_UB : 12|1@0+ (1,0) [0|0] "" XXX + SG_ MetricActvTe_B_Actl : 14|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Liftgate_Mode_Cmd : 42|1@0+ (1,0) [0|0] "" XXX + SG_ AirAmb_Te_Actl : 55|10@0+ (0.25,-128.0) [0|0] "degC" XXX + SG_ EngClntTe_D_Qf : 47|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_Cmd : 26|2@0+ (1,0) [0|0] "" XXX + SG_ Side_Detect_Cmd : 28|2@0+ (1,0) [0|0] "" XXX + SG_ SAPPStatusCoding : 39|8@0+ (1,0) [0|0] "" XXX + SG_ Delay_Accy : 31|1@0+ (1,0) [0|0] "" XXX + SG_ Volume_Cutback : 7|1@0+ (1,0) [0|0] "" XXX + SG_ MetricActv_B_Actl : 0|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatTgate_B_Actl : 1|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatRr_B_Actl : 2|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatRl_B_Actl : 3|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatPsngr_B_Actl : 4|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatInnrTgate_B_Actl : 5|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatHood_B_Actl : 6|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatDrv_B_Actl : 10|1@0+ (1,0) [0|0] "" XXX + SG_ EngClnt_Te_Actl : 23|8@0+ (1,-60.0) [0|0] "degC" XXX + SG_ AirAmbTe_D_Qf_UB : 59|1@0+ (1,0) [0|0] "" XXX + SG_ Volume_Cutback_UB : 58|1@0+ (1,0) [0|0] "" XXX + SG_ Side_Detect_Cmd_UB : 57|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPStatusCoding_UB : 56|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Liftgate_Mode_Cmd_UB : 15|1@0+ (1,0) [0|0] "" XXX + SG_ MetricActv_B_Actl_UB : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_Cmd_UB : 11|1@0+ (1,0) [0|0] "" XXX + SG_ AirAmbTe_D_Qf : 61|2@0+ (1,0) [0|0] "" XXX + SG_ AirAmb_Te_Actl_UB : 40|1@0+ (1,0) [0|0] "" XXX + SG_ EngClnt_Te_Actl_UB : 24|1@0+ (1,0) [0|0] "" XXX + +BO_ 966 Delay_AccyM_for_P473: 8 XXX + SG_ Delay_Accy : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 967 CMPS_FDM_Info_StatusMS: 8 XXX + SG_ Segment_MSD_UB : 37|1@0+ (1,0) [0|0] "" XXX + SG_ Segment_LSD_UB : 36|1@0+ (1,0) [0|0] "" XXX + SG_ Compass_Display_UB : 35|1@0+ (1,0) [0|0] "" XXX + SG_ Segment_LSD : 15|8@0+ (1,0) [0|0] "" XXX + SG_ Segment_MSD : 7|8@0+ (1,0) [0|0] "" XXX + SG_ Cal_Icon : 21|1@0+ (1,0) [0|0] "" XXX + SG_ Zone_Icon : 22|1@0+ (1,0) [0|0] "" XXX + SG_ Compass_Display : 23|1@0+ (1,0) [0|0] "" XXX + SG_ Zone_Icon_UB : 34|1@0+ (1,0) [0|0] "" XXX + SG_ Cal_Icon_UB : 33|1@0+ (1,0) [0|0] "" XXX + +BO_ 968 EATC_FDM_Info_Status: 8 XXX + SG_ Outside_Rear_Temp_Digit3 : 47|4@0+ (1,0) [0|0] "BCD" XXX + SG_ Outside_Rear_Temp_Digit2 : 35|4@0+ (1,0) [0|0] "BCD" XXX + SG_ Outside_Rear_Temp_Digit1 : 39|4@0+ (1,0) [0|0] "BCD" XXX + SG_ EATC_Out_Rear_Units : 58|2@0+ (1,0) [0|0] "" XXX + SG_ Outside_Rear_Temp_Digit4 : 55|2@0+ (1,0) [0|0] "" XXX + SG_ EATC_RHS_Units : 60|2@0+ (1,0) [0|0] "" XXX + SG_ EATC_Fan_Speed : 51|3@0+ (1,0) [0|0] "" XXX + SG_ EATC_Outside_Rear_Display : 62|2@0+ (1,0) [0|0] "" XXX + SG_ RHS_Temp_Display_Digit2 : 31|8@0+ (1,0) [0|0] "ASCII" XXX + SG_ RHS_Temp_Display_Digit3 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ RHS_Temp_Display_Digit1 : 23|8@0+ (1,0) [0|0] "ASCII" XXX + SG_ EATC_RHS_Display : 63|1@0+ (1,0) [0|0] "" XXX + SG_ LHS_Temp_Display_Digit3 : 43|2@0+ (1,0) [0|0] "" XXX + SG_ LHS_Temp_Display_Digit2 : 15|8@0+ (1,0) [0|0] "ASCII" XXX + SG_ LHS_Temp_Display_Digit1 : 7|8@0+ (1,0) [0|0] "ASCII" XXX + SG_ EATC_LHS_Display : 48|1@0+ (1,0) [0|0] "" XXX + SG_ EATC_LHS_Units : 53|2@0+ (1,0) [0|0] "" XXX + +BO_ 969 Aux_Body_Ctrl_Mod_Status: 8 XXX + SG_ Perimeter_Alrm_Intrus_Stat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Turn_Outage_Stat_Rt_Rear : 15|2@0+ (1,0) [0|0] "" XXX + SG_ Turn_Outage_Stat_Left_Rear : 1|2@0+ (1,0) [0|0] "" XXX + SG_ Perimeter_Alrm_Inclin_Stat : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 976 Veh_Characteristic_Set_2: 8 XXX + SG_ VehMykey_Vl_LimRq_UB : 8|1@0+ (1,0) [0|0] "" XXX + SG_ CamraFrntStat_D_Stat : 21|2@0+ (1,0) [0|0] "" XXX + SG_ CamraZoomMan_D_Actl : 12|3@0+ (1,0) [0|0] "" XXX + SG_ CamZoomActiveState : 17|2@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlStat_D_Actl : 19|2@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlDyn_D_Actl : 39|2@0+ (1,0) [0|0] "" XXX + SG_ CamPDCGuidStat : 31|2@0+ (1,0) [0|0] "" XXX + SG_ VehMykey_Vl_LimRq : 14|1@0+ (1,0) [0|0] "" XXX + SG_ IgnKeyType_D_Actl : 4|4@0+ (1,0) [0|0] "" XXX + SG_ New_Module_Attn_Event : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Beltminder_Warn_Stats : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Attn_Info_Audio : 7|3@0+ (1,0) [0|0] "" XXX + +BO_ 977 ClmtCtrlSeat_SetCmd_LRPM: 8 XXX + SG_ ClmtCtrlSeat_SetCmd_LRP : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 978 ClmtCtrlSeat_SetStat_LRPM: 8 XXX + SG_ ClmtCtrlSeat_SetStat_LRP : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 979 ClmtCtrlSeat_SetCmd_RRPM: 8 XXX + SG_ ClmtCtrlSeat_SetCmd_RRP : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 980 ClmtCtrlSeat_SetStat_RRPM: 8 XXX + SG_ ClmtCtrlSeat_SetStat_RRP : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 981 Rear_HVAC_Control_Status: 8 XXX + SG_ Temp_Knob_Position : 23|9@0+ (1,0) [0|0] "Degrees CW" XXX + SG_ Rear_Lock_Ind_State : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Blower_Knob_Position : 7|9@0+ (1,0) [0|0] "Degrees CW" XXX + SG_ AUTO_Ind_State : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Panel_Mode_Ind_State : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Panel_Floor_Md_Ind_State : 10|2@0+ (1,0) [0|0] "" XXX + SG_ Floor_Mode_Ind_State : 8|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Status : 14|1@0+ (1,0) [0|0] "" XXX + +BO_ 982 Rear_HVAC_Control_Update: 8 XXX + SG_ Power_State_Commanded : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_Lock_Indicator : 15|1@0+ (1,0) [0|0] "" XXX + SG_ Panel_Floor_Mode_Indicator : 4|2@0+ (1,0) [0|0] "" XXX + SG_ R_Floor_Mode_Indicator : 2|1@0+ (1,0) [0|0] "" XXX + SG_ AUTO_Mode_Indicator : 1|2@0+ (1,0) [0|0] "" XXX + SG_ F_Panel_Mode_Indicator : 13|1@0+ (1,0) [0|0] "" XXX + SG_ R_Panel_Mode_Indicator : 12|2@0+ (1,0) [0|0] "" XXX + +BO_ 986 Personality_APIM_Data3_MS: 8 XXX + SG_ LightAmbIntSwtchInc_B : 22|1@0+ (1,0) [0|0] "" XXX + SG_ LightAmbIntSwtchDec_B : 21|1@0+ (1,0) [0|0] "" XXX + SG_ LightAmbIntsty_No_Rq : 15|8@0+ (1,0) [0|0] "% Intensity" XXX + SG_ LightAmbColor_No_Rq : 7|8@0+ (1,0) [0|0] "Color Index" XXX + SG_ LightAmbClrSwtchInc_B : 20|1@0+ (1,0) [0|0] "" XXX + SG_ LightAmbClrSwtchDec_B : 23|1@0+ (1,0) [0|0] "" XXX + +BO_ 987 RHVAC_Data: 8 XXX + SG_ CamraDefog_B_Actl : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 992 Personality_Data_MS: 8 XXX + SG_ PersSetupRestr_D_Actl : 45|2@0+ (1,0) [0|0] "" XXX + SG_ PersSetupAccessCtrl : 43|1@0+ (1,0) [0|0] "SES" XXX + SG_ PersSetup_No_Actl : 55|16@0+ (1,0) [0|0] "Number" XXX + SG_ MsgCntrPersIndex_D_Rq_UB : 47|1@0+ (1,0) [0|0] "" XXX + SG_ MsgCntrFeatNoRq_UB : 46|1@0+ (1,0) [0|0] "" XXX + SG_ MsgCntrFeatConfigRq_UB : 33|1@0+ (1,0) [0|0] "" XXX + SG_ MsgCntrDsplyOp_D_Rq_UB : 32|1@0+ (1,0) [0|0] "" XXX + SG_ MsgCntrPersIndex_D_Rq : 39|3@0+ (1,0) [0|0] "" XXX + SG_ MsgCntrFeatConfigRq : 23|16@0+ (1,0) [0|0] "" XXX + SG_ MsgCntrFeatNoRq : 7|16@0+ (1,0) [0|0] "Number" XXX + SG_ MsgCntrDsplyOp_D_Rq : 36|3@0+ (1,0) [0|0] "" XXX + +BO_ 993 Personality_DSM_Data: 8 XXX + SG_ PersIndexDsm_D_Actl : 47|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoDsmActl : 31|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigDsmActl : 15|16@0+ (1,0) [0|0] "" XXX + SG_ PersStore_D_Actl : 7|2@0+ (1,0) [0|0] "" XXX + SG_ MemSwtch_D_RqRecall : 5|3@0+ (1,0) [0|0] "" XXX + SG_ MemSwtch_D_RqAssoc : 2|3@0+ (1,0) [0|0] "" XXX + +BO_ 994 Personality_Data_MS_2: 8 XXX + SG_ RecallEvent_No_Cnt : 63|8@0+ (1,0) [0|0] "Counts" XXX + SG_ PersNo_D_Actl : 55|3@0+ (1,0) [0|0] "" XXX + SG_ PersNoPos_D_Actl : 44|3@0+ (1,0) [0|0] "" XXX + SG_ PersStore_D_Rq_UB : 41|1@0+ (1,0) [0|0] "" XXX + SG_ CtrStkPersIndex_D_Actl_UB : 40|1@0+ (1,0) [0|0] "" XXX + SG_ CtrStkFeatNoActl_UB : 52|1@0+ (1,0) [0|0] "" XXX + SG_ CtrStkFeatConfigActl_UB : 33|1@0+ (1,0) [0|0] "" XXX + SG_ CtrStkDsplyOp_D_Rq_UB : 32|1@0+ (1,0) [0|0] "" XXX + SG_ CtrStkPersIndex_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ CtrStkFeatNoActl : 23|16@0+ (1,0) [0|0] "" XXX + SG_ PersStore_D_Rq : 36|3@0+ (1,0) [0|0] "" XXX + SG_ CtrStkFeatConfigActl : 7|16@0+ (1,0) [0|0] "" XXX + SG_ CtrStkDsplyOp_D_Rq : 47|3@0+ (1,0) [0|0] "" XXX + +BO_ 996 Personality_HCMB_Data: 8 XXX + SG_ PersIndexHcmb_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoHcmbActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigHcmbActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 999 Personality_HVAC_Data: 8 XXX + SG_ LightAmbIntsty_No_Actl : 55|8@0+ (1,0) [0|0] "% Intensity" XXX + SG_ LightAmbColor_No_Actl : 47|8@0+ (1,0) [0|0] "Color Index" XXX + SG_ PersIndexHvac_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoHvacActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigHvacActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 1000 ACM_Status_Message: 8 XXX + SG_ Multimedia_System : 26|1@0+ (1,0) [0|0] "" XXX + +BO_ 1001 Personality_RFA_Data: 8 XXX + SG_ PersIndexRfa_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoRfaActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigRfaActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 1005 Personality_RHVAC_Data: 8 XXX + SG_ PersIndexRhvac_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoRhvacActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigRhvacActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 1006 Nav_HMI_Status: 8 XXX + SG_ Nav_Unit_Setting : 14|1@0+ (1,0) [0|0] "" XXX + SG_ Fuel_Econ_AFE_Reset_Req : 15|1@0+ (1,0) [0|0] "" XXX + SG_ DistanceBarSetting : 23|1@0+ (1,0) [0|0] "" XXX + SG_ CamraZoomMan_D_Rq : 22|3@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlStat_D_Rq : 19|1@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlDyn_D_Rq : 18|1@0+ (1,0) [0|0] "" XXX + SG_ CamAutoTowbarZoom : 17|1@0+ (1,0) [0|0] "" XXX + +BO_ 1023 Reserve_3FF_MKX_Audio: 8 XXX + SG_ reserve : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 1034 GGCC_Config_Mgmt_ID_1: 8 XXX + SG_ VehicleGGCCData : 7|64@0+ (1,0) [0|0] "mixed" XXX + +BO_ 1050 Climate_Control_Data: 8 XXX + SG_ SecondaryHeater_Rqst : 31|1@0+ (1,0) [0|0] "" XXX + SG_ Passenger_Sunload_Raw : 15|8@0+ (5.0,0) [0|0] "W/m^2" XXX + SG_ Driver_Sunload_Raw : 7|8@0+ (5.0,0) [0|0] "W/m^2" XXX + SG_ HvacEvap_Te_Rq : 43|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + SG_ HvacRemoteStrt_N_Rq : 47|4@0+ (100.0,450.0) [0|0] "RPM" XXX + SG_ Remote_Start_QuietMode : 28|1@0+ (1,0) [0|0] "" XXX + SG_ InCarTempQF : 30|2@0+ (1,0) [0|0] "" XXX + SG_ HvacAirCond_B_Rq : 27|1@0+ (1,0) [0|0] "" XXX + SG_ InCarTemp : 39|8@0+ (0.5,-57.0) [0|0] "degreesC" XXX + SG_ Outside_Air_Temp_Stat : 23|8@0+ (0.5,-40.0) [0|0] "Degrees C" XXX + SG_ HvacEvap_Te_Actl : 49|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + +BO_ 1059 Engine_Data_MS: 8 XXX + SG_ Res_UreaLvlLo_B_Dsply_UB : 35|1@0+ (1,0) [0|0] "" XXX + SG_ Res_UreaLvlLo_B_Dsply : 36|1@0+ (1,0) [0|0] "" XXX + SG_ Fuel_Level_State : 47|2@0+ (1,0) [0|0] "" XXX + SG_ AwdOffRoadMode_D_Stats_UB : 55|1@0+ (1,0) [0|0] "" XXX + SG_ AwdRnge_D_Actl_UB : 42|1@0+ (1,0) [0|0] "" XXX + SG_ RearDiffLckLamp_D_Rq_UB : 32|1@0+ (1,0) [0|0] "" XXX + SG_ AwdOffRoadMode_D_Stats : 41|2@0+ (1,0) [0|0] "" XXX + SG_ AwdRnge_D_Actl : 45|3@0+ (1,0) [0|0] "" XXX + SG_ RearDiffLckLamp_D_Rq : 34|2@0+ (1,0) [0|0] "" XXX + SG_ VEH_SPD : 7|16@0+ (0.01,-100.0) [0|0] "KPH" XXX + SG_ ENG_SPD : 23|16@0+ (0.25,0) [0|0] "RPM" XXX + SG_ Fuel_Level_State_UB : 37|1@0+ (1,0) [0|0] "" XXX + +BO_ 1061 Engine_Data_2_MS: 8 XXX + SG_ RstrnImpactEvntStatus_UB : 56|1@0+ (1,0) [0|0] "" XXX + SG_ EngAirIn_Te_Actl_UB : 60|1@0+ (1,0) [0|0] "" XXX + SG_ EngAirIn_Te_Actl : 55|10@0+ (0.25,-128.0) [0|0] "degC" XXX + SG_ ACCompressorDisp_UB : 61|1@0+ (1,0) [0|0] "" XXX + SG_ ACCompressorDisp : 46|7@0+ (1,0) [0|0] "%" XXX + SG_ RstrnImpactEvntStatus : 59|3@0+ (1,0) [0|0] "" XXX + SG_ EngAout_N_Actl_UB : 47|1@0+ (1,0) [0|0] "" XXX + SG_ EngAout_N_Actl : 28|13@0+ (2.0,0) [0|0] "rpm" XXX + SG_ VehVActlEng_D_Qf : 31|2@0+ (1,0) [0|0] "" XXX + SG_ Veh_V_ActlEng_UB : 29|1@0+ (1,0) [0|0] "" XXX + SG_ Veh_V_ActlEng : 15|16@0+ (0.01,0) [0|0] "kph" XXX + SG_ PwPck_D_Stat_UB : 3|1@0+ (1,0) [0|0] "" XXX + SG_ PwPck_D_Stat : 7|4@0+ (1,0) [0|0] "" XXX + +BO_ 1062 ACM_NAV_WHEEL_INFO: 8 XXX + SG_ WhlRotatRr_No_Cnt_UB : 63|1@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatRl_No_Cnt_UB : 40|1@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFr_No_Cnt_UB : 41|1@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFl_No_Cnt_UB : 42|1@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRr_D_Actl_UB : 44|1@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRl_D_Actl_UB : 45|1@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFr_D_Actl_UB : 46|1@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFl_D_Actl_UB : 47|1@0+ (1,0) [0|0] "" XXX + SG_ WHEEL_ROLLING_TIMESTAMP_UB : 62|1@0+ (1,0) [0|0] "" XXX + SG_ ACM_NAV_WHEEL_INFO_RESET : 43|1@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatRr_No_Cnt : 39|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatRl_No_Cnt : 31|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFr_No_Cnt : 23|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFl_No_Cnt : 15|8@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRr_D_Actl : 1|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRl_D_Actl : 3|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFr_D_Actl : 5|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFl_D_Actl : 7|2@0+ (1,0) [0|0] "" XXX + SG_ WHEEL_ROLLING_TIMESTAMP : 55|8@0+ (1,0) [0|0] "" XXX + +BO_ 1068 Battery_Mgmt_2_MS: 8 XXX + SG_ Shed_T_Eng_Off_B : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Shed_Level_Req : 15|3@0+ (1,0) [0|0] "" XXX + SG_ Shed_Feature_Group_ID : 7|5@0+ (1,0) [0|0] "" XXX + SG_ Shed_Drain_Eng_Off_B : 2|1@0+ (1,0) [0|0] "" XXX + SG_ Batt_Lo_SoC_B : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Batt_Crit_SoC_B : 0|1@0+ (1,0) [0|0] "" XXX + +BO_ 1125 GPS_Data_Nav_1: 8 XXX + SG_ GpsHsphLattSth_D_Actl : 25|2@0+ (1,0) [0|0] "" XXX + SG_ GpsHsphLongEast_D_Actl : 9|2@0+ (1,0) [0|0] "" XXX + SG_ GPS_Longitude_Minutes : 46|6@0+ (1,0) [0|0] "Minutes" XXX + SG_ GPS_Longitude_Min_dec : 55|14@0+ (0.0001,0) [0|0] "Minutes" XXX + SG_ GPS_Longitude_Degrees : 39|9@0+ (1,-179.0) [0|0] "Degrees" XXX + SG_ GPS_Latitude_Minutes : 15|6@0+ (1,0) [0|0] "Minutes" XXX + SG_ GPS_Latitude_Min_dec : 23|14@0+ (0.0001,0) [0|0] "Minutes" XXX + SG_ GPS_Latitude_Degrees : 7|8@0+ (1,-89.0) [0|0] "Degrees" XXX + +BO_ 1126 GPS_Data_Nav_2: 8 XXX + SG_ Gps_B_Falt : 2|1@0+ (1,0) [0|0] "" XXX + SG_ GpsUtcYr_No_Actl : 55|5@0+ (1,1.0) [0|0] "Year" XXX + SG_ GpsUtcMnth_No_Actl : 47|4@0+ (1,1.0) [0|0] "Month" XXX + SG_ GpsUtcDay_No_Actl : 37|5@0+ (1,1.0) [0|0] "Day" XXX + SG_ GPS_UTC_seconds : 23|6@0+ (1,0) [0|0] "seconds" XXX + SG_ GPS_UTC_minutes : 15|6@0+ (1,0) [0|0] "Minutes" XXX + SG_ GPS_UTC_hours : 7|5@0+ (1,0) [0|0] "Hours" XXX + SG_ GPS_Pdop : 31|5@0+ (0.2,0) [0|0] "" XXX + SG_ GPS_Compass_direction : 26|4@0+ (1,0) [0|0] "" XXX + SG_ GPS_Actual_vs_Infer_pos : 38|1@0+ (1,0) [0|0] "" XXX + +BO_ 1127 GPS_Data_Nav_3: 8 XXX + SG_ GPS_Vdop : 63|5@0+ (0.2,0) [0|0] "" XXX + SG_ GPS_Speed : 47|8@0+ (1,0) [0|0] "MPH" XXX + SG_ GPS_Sat_num_in_view : 7|5@0+ (1,0) [0|0] "" XXX + SG_ GPS_MSL_altitude : 15|12@0+ (10.0,-20460.0) [0|0] "feet" XXX + SG_ GPS_Heading : 31|16@0+ (0.01,0) [0|0] "Degrees" XXX + SG_ GPS_Hdop : 55|5@0+ (0.2,0) [0|0] "" XXX + SG_ GPS_dimension : 2|3@0+ (1,0) [0|0] "" XXX + +BO_ 1144 GPS_Data_Nav_4: 8 XXX + SG_ VehPos_L_Est : 39|32@0+ (0.01,0) [0|0] "meter" XXX + SG_ VehHead_W_Actl : 23|16@0+ (0.01,-327.68) [0|0] "degrees/second" XXX + SG_ VehHead_An_Est : 7|16@0+ (0.01,0) [0|0] "degrees" XXX diff --git a/opendbc_repo/opendbc/dbc/ford_cgea1_2_ptcan_2011.dbc b/opendbc_repo/opendbc/dbc/ford_cgea1_2_ptcan_2011.dbc new file mode 100644 index 000000000000000..128721cbbf76281 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/ford_cgea1_2_ptcan_2011.dbc @@ -0,0 +1,1487 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 65 Global_PATS_Control_Info: 8 XXX + SG_ immoControlData_T1 : 15|40@0+ (1,0) [0|0] "" XXX + SG_ immoControlCmd_T1 : 7|3@0+ (1,0) [0|0] "" XXX + +BO_ 66 Global_PATS_Control_Info2: 8 XXX + SG_ immoControlData_T2 : 15|40@0+ (1,0) [0|0] "" XXX + SG_ immoControlCmd_T2 : 7|3@0+ (1,0) [0|0] "" XXX + +BO_ 71 Global_PATS_Target_Info: 8 XXX + SG_ immoTarget1Status : 7|3@0+ (1,0) [0|0] "" XXX + SG_ immoTarget1Data : 15|40@0+ (1,0) [0|0] "" XXX + SG_ immoTarget1Cmd : 4|3@0+ (1,0) [0|0] "" XXX + +BO_ 72 Global_PATS_Target_Info_2: 8 XXX + SG_ immoTarget2Status : 7|3@0+ (1,0) [0|0] "" XXX + SG_ immoTarget2Data : 15|40@0+ (1,0) [0|0] "" XXX + SG_ immoTarget2Cmd : 4|3@0+ (1,0) [0|0] "" XXX + +BO_ 73 Global_PATS_SubTarget_FoE: 8 XXX + SG_ immoSubTarget1Data_T1 : 15|40@0+ (1,0) [0|0] "" XXX + SG_ immoSubTarget1Cmd_T1 : 7|3@0+ (1,0) [0|0] "" XXX + +BO_ 74 VehEmergencyData1: 8 XXX + SG_ VedsPasSideBag_D_Ltchd : 60|3@0+ (1,0) [0|0] "" XXX + SG_ VedsPasCrtnBag_D_Ltchd : 55|3@0+ (1,0) [0|0] "" XXX + SG_ VedsPasBelt_D_Ltchd : 52|3@0+ (1,0) [0|0] "" XXX + SG_ VedsPasBag_D_Ltchd : 47|3@0+ (1,0) [0|0] "" XXX + SG_ VedsMultiEvnt_D_Ltchd : 44|3@0+ (1,0) [0|0] "" XXX + SG_ VedsMaxDeltaV_D_Ltchd : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VedsKneeBag_D_Ltchd : 63|3@0+ (1,0) [0|0] "" XXX + SG_ VedsEvntType_D_Ltchd : 31|3@0+ (1,0) [0|0] "" XXX + SG_ VedsEvntRoll_D_Ltchd : 28|3@0+ (1,0) [0|0] "" XXX + SG_ VedsDrvSideBag_D_Ltchd : 23|3@0+ (1,0) [0|0] "" XXX + SG_ VedsDrvCrtnBag_D_Ltchd : 20|3@0+ (1,0) [0|0] "" XXX + SG_ VedsDrvBelt_D_Ltchd : 15|3@0+ (1,0) [0|0] "" XXX + SG_ VedsDrvBag_D_Ltchd : 12|3@0+ (1,0) [0|0] "" XXX + SG_ eCallNotification : 2|2@0+ (1,0) [0|0] "" XXX + +BO_ 75 VehEmergencyData2: 8 XXX + SG_ VedsRw3rBckl_D_Ltchd : 39|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw3mBckl_D_Ltchd : 31|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw3lBckl_D_Ltchd : 28|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw2rBckl_D_Ltchd : 23|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw2mBckl_D_Ltchd : 20|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw2lBckl_D_Ltchd : 15|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw1PasChld_D_Ltchd : 12|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw1PasBckl_D_Ltchd : 7|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw1DrvBckl_D_Ltchd : 4|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw2rRib_D_Ltchd : 47|3@0+ (1,0) [0|0] "" XXX + SG_ VedsRw2lRib_D_Ltchd : 36|3@0+ (1,0) [0|0] "" XXX + +BO_ 116 BrakeSnData_2_CG1: 8 XXX + SG_ VehDynamicsSOS : 55|1@0+ (1,0) [0|0] "" XXX + SG_ AwdLck_Tq_RqMx : 27|12@0+ (1,0) [0|0] "Nm" XXX + SG_ AwdLck_Tq_RqMn : 23|12@0+ (1,0) [0|0] "Nm" XXX + SG_ SteWhlComp_An_Est : 7|15@0+ (0.1,-1600.0) [0|0] "deg" XXX + SG_ StopLamp_B_RqBrk : 8|1@0+ (1,0) [0|0] "" XXX + SG_ BrkTerrMdeChng_D_Rdy : 45|3@0+ (1,0) [0|0] "" XXX + SG_ BrkTerrMde_D_Actl : 42|3@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCompAnEst_D_Qf : 47|2@0+ (1,0) [0|0] "" XXX + +BO_ 117 BrakeSnData_3_CG1: 8 XXX + SG_ HsaStat_D_Dsply : 35|3@0+ (1,0) [0|0] "" XXX + SG_ HsaTrnAout_Tq_Rq : 55|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + SG_ HsaStat_D_Actl : 38|3@0+ (1,0) [0|0] "" XXX + SG_ HsaRoad_Grad_Est : 32|9@0+ (0.5,-127.0) [0|0] "%" XXX + SG_ VehYawComp_W_Actl : 7|12@0+ (0.03663,-75.0) [0|0] "deg/s" XXX + SG_ VehYaw_W_Rq : 11|12@0+ (0.03663,-75.0) [0|0] "deg/s" XXX + SG_ VehSideSlip_An_Est : 31|9@0+ (0.002,-0.5) [0|0] "rad" XXX + +BO_ 124 BrakeSnData_4_CG1: 8 XXX + SG_ EngRun_D_ReqBrk : 10|2@0+ (1,0) [0|0] "" XXX + SG_ BrkTotTqRqArb_No_Cs : 23|8@0+ (1,0) [0|0] "" XXX + SG_ BrkTotTqRqArb_No_Cnt : 31|4@0+ (1,0) [0|0] "" XXX + SG_ BrkTot_Tq_RqArb : 7|13@0+ (4.0,0) [0|0] "Nm" XXX + SG_ BrkTot_Tq_Actl : 39|13@0+ (4.0,0) [0|0] "Nm" XXX + SG_ VehOverGnd_V_Est : 55|16@0+ (0.01,0) [0|0] "kph" XXX + +BO_ 129 Steering_Wheel_Data2: 8 XXX + SG_ SteWhlCtl_RSide_OK : 9|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_RSide_CursorUp : 8|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_RSide_CursorRt : 7|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_RSide_CursorLeft : 6|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_RSide_CursorDown : 5|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_LSide_OK : 4|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_LSide_CursorUp : 3|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_LSide_CursorRt : 2|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_LSide_CursorLeft : 1|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_LSide_CursorDown : 0|1@0+ (1,0) [0|0] "" XXX + +BO_ 130 EPAS_INFO: 8 XXX + SG_ SteMdule_U_Meas : 39|8@0+ (0.05,6.0) [0|0] "Volts" XXX + SG_ SteMdule_I_Est : 21|12@0+ (0.05,-64.0) [0|0] "Amps" XXX + SG_ EPAS_FAILURE : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SteeringColumnTorque : 7|8@0+ (0.0625,-8.0) [0|0] "Nm" XXX + SG_ SAPPAngleControlStat6 : 15|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat5 : 14|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat4 : 13|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat3 : 12|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat2 : 11|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat1 : 23|2@0+ (1,0) [0|0] "" XXX + +BO_ 131 Steering_Data: 8 XXX + SG_ SteWhlCtl_Mute : 38|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Mode : 24|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_OK : 23|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Phone : 22|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_End : 21|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Send : 20|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Voice_PTT : 19|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Seek_Left : 10|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Seek_Right : 9|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Media : 8|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Volume_Down : 6|1@0+ (1,0) [0|0] "" XXX + SG_ SteWhlCtl_Volume_Up : 7|1@0+ (1,0) [0|0] "" XXX + SG_ Smart_Wiper_Motor_Stat : 15|2@0+ (1,0) [0|0] "" XXX + SG_ Mfs_Turn_Stalk_SW_Status : 1|2@0+ (1,0) [0|0] "" XXX + SG_ HighBeam_FlashToPassSw : 3|2@0+ (1,0) [0|0] "" XXX + SG_ SteColumn_Status : 13|3@0+ (1,0) [0|0] "" XXX + SG_ SteCol_Manual_Override : 4|1@0+ (1,0) [0|0] "" XXX + SG_ CcButtnStat_D_Actl : 34|11@0+ (1,0) [0|0] "" XXX + SG_ HeatedWash_Mode_Stat : 55|3@0+ (1,0) [0|0] "" XXX + SG_ LaSwtchPos_D_Stat : 18|2@0+ (1,0) [0|0] "" XXX + +BO_ 132 Steering_Wheel_Data_CG1: 8 XXX + SG_ SteWhlRelInit_An_Sns : 7|15@0+ (0.1,-1600.0) [0|0] "deg" XXX + SG_ SteWhlRelCalib_An_Sns : 23|15@0+ (0.1,-1600.0) [0|0] "deg" XXX + SG_ SteWhlRelInit2_An_Sns : 55|16@0+ (0.1,-3200.0) [0|0] "deg" XXX + SG_ SteWhlAn_No_Cs : 39|8@0+ (1,0) [0|0] "" XXX + SG_ SteWhlAn_No_Cnt : 47|4@0+ (1,0) [0|0] "Counts" XXX + +BO_ 145 Yaw_Data: 8 XXX + SG_ VehYaw_W_Actl : 39|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + SG_ VehRol_W_Actl : 23|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + SG_ VehPtch_W_Actl : 7|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + +BO_ 146 Accel_Data: 8 XXX + SG_ VehVertAActl_D_Qf : 38|2@0+ (1,0) [0|0] "" XXX + SG_ VehLongAActl_D_Qf : 22|2@0+ (1,0) [0|0] "" XXX + SG_ VehLatAActl_D_Qf : 6|2@0+ (1,0) [0|0] "" XXX + SG_ VehVert_A_Actl : 36|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + SG_ VehLong_A_Actl : 20|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + SG_ VehLat_A_Actl : 4|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + +BO_ 258 Cluster_Legacy: 8 XXX + SG_ Veh_V_CompLimMx : 27|12@0+ (0.1,0) [0|0] "km/h" XXX + SG_ DISPLAY_SPEED_SCALING : 20|4@0+ (0.5,100.0) [0|0] "%" XXX + SG_ DISPLAY_SPEED_OFFSET : 23|3@0+ (0.5,0) [0|0] "kph" XXX + SG_ Reverse_Mirror_Cmd : 10|1@0+ (1,0) [0|0] "" XXX + SG_ Autolamp_Delay_Cmd : 7|8@0+ (1,0) [0|0] "Seconds" XXX + SG_ Running_Board_Cmd : 13|2@0+ (1,0) [0|0] "" XXX + SG_ Power_Liftgate_Mode_Cmd : 11|1@0+ (1,0) [0|0] "" XXX + +BO_ 259 Body_MsgCntr_Stat_CG1: 8 XXX + SG_ PE_PEPS_System_Stat : 47|8@0+ (1,0) [0|0] "" XXX + SG_ Keycode_Status : 11|20@0+ (1,0) [0|0] "" XXX + SG_ Autolamp_Delay_Stat : 7|8@0+ (1,0) [0|0] "Seconds" XXX + SG_ HvacEvap_Te_Rq_UB : 61|1@0+ (1,0) [0|0] "" XXX + SG_ HvacEvap_Te_Rq : 55|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + SG_ Remote_Start_QuietMode_UB : 33|1@0+ (1,0) [0|0] "" XXX + SG_ Remote_Start_QuietMode : 32|1@0+ (1,0) [0|0] "" XXX + +BO_ 264 Side_Detect_CmdM: 8 XXX + SG_ Cross_Traffic_Cmd : 5|2@0+ (1,0) [0|0] "" XXX + SG_ Side_Detect_Cmd : 7|2@0+ (1,0) [0|0] "" XXX + +BO_ 266 ParkAid_Audible_Warn_CmdM: 8 XXX + SG_ AutoPark_Cancel_Request : 15|2@0+ (1,0) [0|0] "" XXX + SG_ ParkAid_Audible_Warn_Cmd : 7|2@0+ (1,0) [0|0] "" XXX + SG_ ParkAid_Aud_Frt_Warn_Cmd : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 267 ParkAid_Audible_Warn_Stat: 8 XXX + SG_ RpaChime_D_Rq : 31|4@0+ (1,0) [0|0] "" XXX + SG_ FpaChime_D_Rq : 12|4@0+ (1,0) [0|0] "" XXX + SG_ SAPPStatusCoding : 23|8@0+ (1,0) [0|0] "" XXX + SG_ Volume_Cutback : 1|1@0+ (1,0) [0|0] "" XXX + SG_ ParkAid_Fault_Condition : 15|3@0+ (1,0) [0|0] "" XXX + SG_ ParkAid_Audible_Warn_Stat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ ParkAid_Aud_Frt_Trgt_Warn : 3|2@0+ (1,0) [0|0] "" XXX + SG_ ParkAid_Aud_Frt_Warn_Stat : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 292 ClmtCtrlSeatSet_Cmd_v2: 8 XXX + SG_ ClmtCtrlSeat_SetCmd_Dvr : 7|8@0+ (1,0) [0|0] "" XXX + SG_ ClmtCtrlSeat_SetCmd_Psgr : 15|8@0+ (1,0) [0|0] "" XXX + +BO_ 293 ClmtCtrlSeatSetStat_v2_HS: 8 XXX + SG_ ClmtCtrlSeat_SetStat_Psgr : 15|8@0+ (1,0) [0|0] "" XXX + SG_ ClmtCtrlSeat_SetStat_Dvr : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 336 TransData_1_CG1: 8 XXX + SG_ TrnAinIdl_N_RqMn : 34|11@0+ (2.0,0) [0|0] "rpm" XXX + SG_ TrnAin_N_RqMxPrtct : 23|10@0+ (25.0,0) [0|0] "rpm" XXX + SG_ TrnAin_Tq_RqFstMx : 29|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAin_Tq_RqSlwMxPrs : 7|11@0+ (1,-500.0) [0|0] "Nm" XXX + +BO_ 337 EngineData_1_CG1: 8 XXX + SG_ TrnEngBrk_B_Allw : 24|1@0+ (1,0) [0|0] "" XXX + SG_ TrnAout_W_ActlUnfilt : 23|15@0+ (0.1,0) [0|0] "rad/s" XXX + SG_ TrnIpcDsplyGear_D_Actl : 7|4@0+ (1,0) [0|0] "" XXX + SG_ TrnIpcDsplyMde_D_Stat : 13|2@0+ (1,0) [0|0] "" XXX + SG_ TrnIpcDsplyMde_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ TrnIpcDsplyGear_D_Stat : 9|2@0+ (1,0) [0|0] "" XXX + SG_ TurboBoostPressure : 55|16@0+ (0.01,0) [0|0] "bar" XXX + +BO_ 338 TransData_2_CG1: 8 XXX + SG_ GearPos_D_Actl : 55|4@0+ (1,0) [0|0] "" XXX + SG_ TrnAout2_Tq_Actl : 39|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + SG_ TrnTotTq_Rt_Actl : 23|16@0+ (0.001,0) [0|0] "" XXX + SG_ TrnGbox_Rt_Pred : 7|16@0+ (0.001,0) [0|0] "" XXX + +BO_ 339 EngineData_2_CG1: 8 XXX + SG_ TrnAin_Tq_MxSpcPdlEngN : 55|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAin_Tq_MnSpcEngN : 31|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ EngPtoEngag_B_Actl : 60|1@0+ (1,0) [0|0] "" XXX + SG_ TrnAin_N_SpcEcho : 4|13@0+ (2.0,0) [0|0] "rpm" XXX + +BO_ 340 EngineData_3_CG1: 8 XXX + SG_ AirAmb_Te_ActlFilt : 33|10@0+ (0.25,-128.0) [0|0] "deg C" XXX + SG_ EngAout_N_RqMxPrtct : 12|13@0+ (2.0,0) [0|0] "rpm" XXX + SG_ TqmTerrMdeChng_D_Rdy : 39|3@0+ (1,0) [0|0] "" XXX + SG_ EngAoutIdl_N_RqVsc : 7|11@0+ (2.0,0) [0|0] "rpm" XXX + SG_ TqmTerrMde_D_Actl : 36|3@0+ (1,0) [0|0] "" XXX + SG_ PrplWhlTotVrt_Tq_RqArb : 55|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + +BO_ 341 EngineData_11_CG1: 8 XXX + SG_ DieslPrtc_D_RqDsply : 42|3@0+ (1,0) [0|0] "" XXX + SG_ EngPullUpPullDown_D_Rq : 20|4@0+ (1,0) [0|0] "" XXX + SG_ TrnAin_Tq_RqDrv : 15|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ DieslPrtcRgen_D_Actl : 4|2@0+ (1,0) [0|0] "" XXX + SG_ DieslPrtcRgen_D_Rq : 7|3@0+ (1,0) [0|0] "" XXX + SG_ EngAout_Aa_Actl : 39|10@0+ (0.05,-25.6) [0|0] "rpm/ms" XXX + SG_ EngIgnIndTq_Rt_MnEc : 31|8@0+ (0.005,0) [0|0] "" XXX + SG_ EngFuelCutFull_B_Allw : 45|1@0+ (1,0) [0|0] "" XXX + SG_ EngStrtStopDis_B_Rq : 0|1@0+ (1,0) [0|0] "" XXX + SG_ PrplTqSys_D_Stat : 2|2@0+ (1,0) [0|0] "" XXX + SG_ EngAoutTqDtrb_B_Actl : 16|1@0+ (1,0) [0|0] "" XXX + SG_ EngTurboMde_D_Actl : 44|2@0+ (1,0) [0|0] "" XXX + SG_ EngTeColdPrtct_D_Stats : 54|2@0+ (1,0) [0|0] "" XXX + SG_ EXHAUST_OVERTEMP_PROTECT : 63|1@0+ (1,0) [0|0] "" XXX + SG_ EngExhOvrTe_B_RqDsply : 55|1@0+ (1,0) [0|0] "" XXX + +BO_ 342 Engine_Data_6: 8 XXX + SG_ EngOvrhtMitgActv_D_Ind : 36|2@0+ (1,0) [0|0] "" XXX + SG_ Res_UreaLvlLo_B_Dsply : 34|1@0+ (1,0) [0|0] "" XXX + SG_ EngClntTe_D_Qf : 33|2@0+ (1,0) [0|0] "" XXX + SG_ EngAcsyArcPmp_Tq_Actl : 63|8@0+ (0.5,0) [0|0] "Nm" XXX + SG_ EngOilLvlDsply_D_Rq : 43|4@0+ (1,0) [0|0] "" XXX + SG_ EngCtlAlive_No_Cnt : 47|4@0+ (1,0) [0|0] "" XXX + SG_ EngCtl_No_Cs : 55|8@0+ (1,0) [0|0] "" XXX + SG_ EngOil_Te_Actl : 15|8@0+ (1,-60.0) [0|0] "degC" XXX + SG_ EngClnt_Te_Actl : 7|8@0+ (1,-60.0) [0|0] "degC" XXX + +BO_ 343 EngineData_13_CG1: 8 XXX + SG_ EngStrtFail_B_Actl : 40|1@0+ (1,0) [0|0] "" XXX + SG_ EngStrt_B_Complt : 24|1@0+ (1,0) [0|0] "" XXX + SG_ EngStrtSpin_B_Rdy : 58|1@0+ (1,0) [0|0] "" XXX + SG_ EngWarmUp_B_Complt : 41|1@0+ (1,0) [0|0] "" XXX + SG_ EngAoutTqCtl_B_Falt : 8|1@0+ (1,0) [0|0] "" XXX + SG_ EngAoutActl_No_Cs : 23|8@0+ (1,0) [0|0] "" XXX + SG_ EngAoutActl_No_Cnt : 45|4@0+ (1,0) [0|0] "" XXX + SG_ VehVLim_V_RqArb : 39|9@0+ (0.5,0) [0|0] "kph" XXX + +BO_ 344 EngineData_14: 8 XXX + SG_ ApedPosScal_Pc_Actl : 9|10@0+ (0.1,0) [0|0] "%" XXX + SG_ ApedPosPcActl_No_Cs : 39|8@0+ (1,0) [0|0] "" XXX + SG_ ApedPosPcActl_No_Cnt : 13|4@0+ (1,0) [0|0] "" XXX + +BO_ 345 Engine_Data_7_CG1: 8 XXX + SG_ EngDecelFuelCut_B_Allw : 25|1@0+ (1,0) [0|0] "" XXX + SG_ FuelFlw_Vl_Dsply : 55|10@0+ (25.0,0) [0|0] "Micro_Liter" XXX + SG_ FuelFillInlet_B_Dsply : 32|1@0+ (1,0) [0|0] "" XXX + SG_ EngSrvcRqd_B_Rq : 24|1@0+ (1,0) [0|0] "" XXX + SG_ OdoCount : 47|8@0+ (0.2,0) [0|0] "Meters" XXX + SG_ EngOilLife_Pc_Actl : 39|7@0+ (1,0) [0|0] "%" XXX + SG_ AirAmbTe_D_Qf : 28|2@0+ (1,0) [0|0] "" XXX + SG_ EngTqSlwDly_T_Est : 23|11@0+ (1,0) [0|0] "ms" XXX + SG_ TrnKickDown_B_RqDrv : 26|1@0+ (1,0) [0|0] "" XXX + SG_ AirAmb_Te_Actl : 1|10@0+ (0.25,-128.0) [0|0] "degC" XXX + SG_ AirAmb_P_Actl : 7|6@0+ (10.0,500.0) [0|0] "mbar" XXX + SG_ FuelFilterLamp_B_Dsply : 56|1@0+ (1,0) [0|0] "" XXX + SG_ AirCondRec_B_Rq : 61|1@0+ (1,0) [0|0] "" XXX + SG_ AirCondEvdc_D_Stats : 60|3@0+ (1,0) [0|0] "" XXX + SG_ AirCondClutch_B_Stats : 57|1@0+ (1,0) [0|0] "" XXX + +BO_ 346 EngineData_4_CG1: 8 XXX + SG_ TrnAin_Tq_Rq : 12|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAin_Tq_RqWoMdfy : 55|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAin_Tq_ActlWoMdfy : 36|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAin_Tq_Actl : 7|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAinCtlN_B_Allw : 41|1@0+ (1,0) [0|0] "" XXX + SG_ TrnAinTq_D_Qf : 17|2@0+ (1,0) [0|0] "" XXX + +BO_ 348 EngineData_16_CG1: 8 XXX + SG_ EngOilLvlWarn_D_Rq1 : 50|3@0+ (1,0) [0|0] "" XXX + SG_ EngExhBrkOnLamp_B_Rq : 51|1@0+ (1,0) [0|0] "" XXX + SG_ EngExhBrkAutoLamp_B_Rq : 8|1@0+ (1,0) [0|0] "" XXX + SG_ EngAout_N_MxAllw : 36|13@0+ (2.0,0) [0|0] "rpm" XXX + SG_ EngAoutIdl_N_MnAllw : 31|11@0+ (1,0) [0|0] "rpm" XXX + SG_ EngAoutIdlRqEc_No_Cs : 23|8@0+ (1,0) [0|0] "" XXX + SG_ EngAoutIdlRqEc_No_Cnt : 12|4@0+ (1,0) [0|0] "" XXX + SG_ EngAoutIdl_N_RqEc : 7|11@0+ (2.0,0) [0|0] "rpm" XXX + SG_ EngExhBrkMde_D_Actl : 55|4@0+ (1,0) [0|0] "" XXX + +BO_ 349 EngineData_17_CG1: 8 XXX + SG_ EngResv_Tq_Actl : 52|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ EngAout_Tq_ActlSlw : 47|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ EngExhCat_Te_Est : 13|10@0+ (2.0,-60.0) [0|0] "degC" XXX + SG_ EngCylCutIndTq_Rt_Actl : 39|8@0+ (0.005,0) [0|0] "Nm" XXX + SG_ Eng_Aa_CalcEvntCyc : 7|10@0+ (0.05,-25.6) [0|0] "rpm/ms" XXX + SG_ Eng_Aa_CalcEvntCbust : 19|10@0+ (0.05,-25.6) [0|0] "rpm/ms" XXX + SG_ WaterInFuel : 25|1@0+ (1,0) [0|0] "" XXX + SG_ GlowIndication : 24|1@0+ (1,0) [0|0] "" XXX + +BO_ 350 EngineData_18_CG1: 8 XXX + SG_ EngAoutTqActl_D_Qf : 17|2@0+ (1,0) [0|0] "" XXX + SG_ EngAout_Tq_MnSpcNRtrd : 36|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ EngAout_Tq_Actl : 31|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ EngAoutLss_Tq_EstSpcN : 12|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ EngAout_Tq_MnSpcN : 7|11@0+ (1,-500.0) [0|0] "Nm" XXX + +BO_ 351 EngineData_19: 8 XXX + SG_ VehPreDelvr_V_LimMx : 15|16@0+ (0.01,0) [0|0] "kph" XXX + SG_ BattLo_U_MeasEngMdule : 7|8@0+ (0.1,0) [0|0] "V" XXX + SG_ EngStall_B_Actl : 47|1@0+ (1,0) [0|0] "" XXX + SG_ EngDashPotActv_B_Actl : 46|1@0+ (1,0) [0|0] "" XXX + SG_ EngAout_Tq_MnAllw : 42|11@0+ (1,-500.0) [0|0] "Nm" XXX + +BO_ 352 TransData_3_CG1: 8 XXX + SG_ TrnAinCtlN_N_RqMx : 7|13@0+ (2.0,0) [0|0] "rpm" XXX + SG_ TrnAin_Tq_RqSlwMxShif : 42|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAinCtlN_B_RqEnbl : 10|1@0+ (1,0) [0|0] "" XXX + SG_ TrnGboxIn_N_Actl : 23|13@0+ (2.0,0) [0|0] "rpm" XXX + +BO_ 353 Engine_Data_8: 8 XXX + SG_ TrnAinTqDtrb_B_Actl : 5|1@0+ (1,0) [0|0] "" XXX + SG_ TrnAin_Tq_MnSpcEngN : 34|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ EngAout_N_RqMnPrtct : 20|13@0+ (2.0,0) [0|0] "rpm" XXX + SG_ EngAout_N_MnAllw : 4|13@0+ (2.0,0) [0|0] "rpm" XXX + +BO_ 354 CGEA_Urea_Strategy_CG1: 8 XXX + SG_ UreaQltySys_D_RqDsply : 27|3@0+ (1,0) [0|0] "" XXX + SG_ UreaLvlTxt_D_RqDsply : 31|4@0+ (1,0) [0|0] "" XXX + SG_ VehUreaImmo_No_DsplyMx : 12|3@0+ (1,0) [0|0] "Counts" XXX + SG_ VehUreaWarn_V_DsplyMx : 23|7@0+ (1,0) [0|0] "km/h" XXX + SG_ VehUreaRnge_L_DsplyMx : 7|11@0+ (1,0) [0|0] "km" XXX + +BO_ 355 EngineData_10: 8 XXX + SG_ WhlRearDual_D_Stat : 57|2@0+ (1,0) [0|0] "" XXX + SG_ EngPtoMde_D_Actl : 60|3@0+ (1,0) [0|0] "" XXX + SG_ ManRgenVeh_V_MinAllw : 55|7@0+ (1,0) [0|0] "kilometer/hour" XXX + SG_ ManRgenTxt_D_RqDsply : 63|3@0+ (1,0) [0|0] "" XXX + SG_ ManRgenSoot_Pc_RqDsply : 39|7@0+ (1,0) [0|0] "%" XXX + SG_ ManRgenInhbt_T_RqDsply : 23|16@0+ (1,0) [0|0] "Minutes" XXX + SG_ ManRgenInhbt_Pc_Soot : 47|7@0+ (1,0) [0|0] "%" XXX + SG_ ManRgenInhbt_L_RqDsply : 7|16@0+ (1,0) [0|0] "kilometer" XXX + +BO_ 357 EngBrakeData: 8 XXX + SG_ CmbbDeny_B_ActlPrpl : 3|1@0+ (1,0) [0|0] "" XXX + SG_ BpedDrvAppl_No_Cs : 39|8@0+ (1,0) [0|0] "" XXX + SG_ BpedDrvAppl_No_Cnt : 27|4@0+ (1,0) [0|0] "" XXX + SG_ BpedDrvAppl_D_Actl : 31|2@0+ (1,0) [0|0] "" XXX + SG_ CmbbEngTqMn_B_Actl : 7|1@0+ (1,0) [0|0] "" XXX + SG_ Veh_V_DsplyCcSet : 23|8@0+ (1,0) [0|0] "" XXX + SG_ AccEngStat_D_Actl : 2|3@0+ (1,0) [0|0] "" XXX + SG_ CcMde_D_Actl : 13|3@0+ (1,0) [0|0] "" XXX + SG_ TrnAinTqDtrb_B_Actl : 6|1@0+ (1,0) [0|0] "" XXX + SG_ CcStat_D_Actl : 10|3@0+ (1,0) [0|0] "" XXX + SG_ CcOvrrdActv_B_Actl : 15|1@0+ (1,0) [0|0] "" XXX + SG_ PwPck_D_Stat : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 389 ACCDATA_CG1: 8 XXX + SG_ AccPrpl_A_Pred : 14|10@0+ (0.01,-5.0) [0|0] "m/s^2" XXX + SG_ AccBrkPrkEl_B_Rq : 41|1@0+ (1,0) [0|0] "" XXX + SG_ Cmbb_B_Enbl : 56|1@0+ (1,0) [0|0] "" XXX + SG_ CmbbOvrrd_B_RqDrv : 57|1@0+ (1,0) [0|0] "" XXX + SG_ CmbbDeny_B_Actl : 40|1@0+ (1,0) [0|0] "" XXX + SG_ AccVeh_V_Trg : 7|9@0+ (0.5,0) [0|0] "kph" XXX + SG_ CmbbEngTqMn_B_Rq : 58|1@0+ (1,0) [0|0] "" XXX + SG_ AccPrpl_A_Rq : 55|10@0+ (0.01,-5.0) [0|0] "m/s^2" XXX + SG_ AccDeny_B_Rq : 59|1@0+ (1,0) [0|0] "" XXX + SG_ AccCancl_B_Rq : 42|1@0+ (1,0) [0|0] "" XXX + SG_ AccBrkTot_A_Rq : 39|13@0+ (0.0039,-20.0) [0|0] "m/s^2" XXX + SG_ AccBrkPrchg_B_Rq : 60|1@0+ (1,0) [0|0] "" XXX + SG_ AccBrkDecel_B_Rq : 61|1@0+ (1,0) [0|0] "" XXX + +BO_ 392 HeadUpDisplayStat: 8 XXX + SG_ Hud_B_Falt : 5|1@0+ (1,0) [0|0] "" XXX + SG_ HudActv_B_Actl : 7|1@0+ (1,0) [0|0] "" XXX + SG_ Hud_B_Avail : 6|1@0+ (1,0) [0|0] "" XXX + +BO_ 393 ACCDATA_2_CG1: 8 XXX + SG_ ACC_AUTOBRAKE_CANCEL : 56|1@0+ (1,0) [0|0] "" XXX + SG_ ACC_RESUME_ACTIVE : 57|1@0+ (1,0) [0|0] "" XXX + SG_ FcwAudioWarn_B_Rq : 58|1@0+ (1,0) [0|0] "" XXX + SG_ CadsAudioMute_D_Rq : 61|2@0+ (1,0) [0|0] "" XXX + SG_ AccWarn_D_Dsply : 63|2@0+ (1,0) [0|0] "" XXX + SG_ HudDsplyIntns_No_Actl : 55|8@0+ (0.5,0) [0|0] "%" XXX + SG_ FcwVisblWarn_B_Rq : 40|1@0+ (1,0) [0|0] "" XXX + SG_ HudBlk3_B_Rq : 41|1@0+ (1,0) [0|0] "" XXX + SG_ HudBlk2_B_Rq : 43|1@0+ (1,0) [0|0] "" XXX + SG_ HudBlk1_B_Rq : 42|1@0+ (1,0) [0|0] "" XXX + SG_ HudFlashRate_D_Actl : 45|2@0+ (1,0) [0|0] "" XXX + SG_ CmbbBrkDecel_No_Cs : 39|8@0+ (1,0) [0|0] "" XXX + SG_ CmbbBrkDecel_A_Rq : 23|13@0+ (0.0039,-20.0) [0|0] "m/s^2" XXX + SG_ CmbbBrkPrchg_D_Rq : 47|2@0+ (1,0) [0|0] "" XXX + SG_ CmbbBrkDecel_B_Rq : 26|1@0+ (1,0) [0|0] "" XXX + SG_ CmbbBaSens_D_Rq : 25|2@0+ (1,0) [0|0] "" XXX + SG_ AccPrpl_V_Rq : 7|16@0+ (0.01,0) [0|0] "kph" XXX + +BO_ 394 ACCDATA_3: 8 XXX + SG_ CadsMntr_No_Chk : 55|8@0+ (1,0) [0|0] "" XXX + SG_ FcwDeny_B_Dsply : 10|1@0+ (1,0) [0|0] "" XXX + SG_ FdaWarn_B_Rq : 21|1@0+ (1,0) [0|0] "" XXX + SG_ FcwMemStat_B_Actl : 30|1@0+ (1,0) [0|0] "" XXX + SG_ AccTGap_B_Dsply : 35|1@0+ (1,0) [0|0] "" XXX + SG_ AccMsgTxt_D_Rq : 39|4@0+ (1,0) [0|0] "" XXX + SG_ CadsAlignIncplt_B_Actl : 29|1@0+ (1,0) [0|0] "" XXX + SG_ AccLowVMde_B_Dsply : 16|1@0+ (1,0) [0|0] "" XXX + SG_ AccFllwMde_B_Dsply : 17|1@0+ (1,0) [0|0] "" XXX + SG_ CadsRadrBlck_B_Actl : 22|1@0+ (1,0) [0|0] "" XXX + SG_ FdaStat_D_Dsply : 3|3@0+ (1,0) [0|0] "" XXX + SG_ FdaDeny_B_Dsply : 4|1@0+ (1,0) [0|0] "" XXX + SG_ AccTrgDist_D_Dsply : 28|4@0+ (1,0) [0|0] "" XXX + SG_ CadsChime_B_Rq : 24|1@0+ (1,0) [0|0] "" XXX + SG_ CmbbPostEvnt_B_Dsply : 15|1@0+ (1,0) [0|0] "" XXX + SG_ FcwCmbbSrvcRqd_B_Rq : 12|1@0+ (1,0) [0|0] "" XXX + SG_ AccStopMde_B_Dsply : 0|1@0+ (1,0) [0|0] "" XXX + SG_ CadsCamraBlck_B_Actl : 23|1@0+ (1,0) [0|0] "" XXX + SG_ FcwMemSens_D_Actl : 20|2@0+ (1,0) [0|0] "" XXX + SG_ FcwMemDfaltOn_B_Actl : 18|1@0+ (1,0) [0|0] "" XXX + SG_ AccSrvcRqd_B_Rq : 14|1@0+ (1,0) [0|0] "" XXX + SG_ FcwMsgTxt_D_Rq : 7|3@0+ (1,0) [0|0] "" XXX + SG_ FcwMemAudioOn_B_Actl : 9|1@0+ (1,0) [0|0] "" XXX + SG_ AccTGap_D_Dsply : 34|3@0+ (1,0) [0|0] "" XXX + SG_ AccMemEnbl_B_RqDrv : 42|1@0+ (1,0) [0|0] "" XXX + SG_ FdaMem_B_Stat : 41|1@0+ (1,0) [0|0] "" XXX + +BO_ 512 TorqueDataEngFlags: 8 XXX + SG_ BrkOnOffSwtch_D_Actl : 54|2@0+ (1,0) [0|0] "" XXX + SG_ PrplTqMnSat_B_Actl : 55|1@0+ (1,0) [0|0] "" XXX + SG_ PrplWhlTot_Tq_Rq : 39|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + SG_ PrplWhlTot_Tq_LimMn : 23|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + SG_ PrplWhlTot_Tq_Actl : 7|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + SG_ ACCompressorDisp : 63|7@0+ (1,0) [0|0] "%" XXX + +BO_ 513 EngVehicleSpThrottle_CG1: 8 XXX + SG_ ApedPos_PcRate_ActlArb : 63|8@0+ (0.04,-5.0) [0|0] "%/ms" XXX + SG_ Veh_V_RqCcSet : 45|9@0+ (0.5,0) [0|0] "kph" XXX + SG_ VehVActlEng_D_Qf : 9|2@0+ (1,0) [0|0] "" XXX + SG_ reserve : 10|1@0+ (1,0) [0|0] "" XXX + SG_ EngAout_N_Actl : 7|13@0+ (2.0,0) [0|0] "rpm" XXX + SG_ Veh_V_ActlEng : 23|16@0+ (0.01,0) [0|0] "kph" XXX + SG_ ApedPos_Pc_ActlArb : 39|10@0+ (0.1,0) [0|0] "%" XXX + SG_ ApedPosPcActl_D_Qf : 52|2@0+ (1,0) [0|0] "" XXX + SG_ Autostart_B_Stat : 50|1@0+ (1,0) [0|0] "" XXX + +BO_ 529 DesiredTorqBrk_CG1: 8 XXX + SG_ CmbbBrkDis_B_Actl : 56|1@0+ (1,0) [0|0] "" XXX + SG_ CMbbDeny_B_ActlBrk : 60|1@0+ (1,0) [0|0] "" XXX + SG_ RgenTqLimActv_B_Actl : 32|1@0+ (1,0) [0|0] "" XXX + SG_ CcDis_B_Cmd : 53|1@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrk_Pc_Rq : 39|7@0+ (1,0) [0|0] "%" XXX + SG_ RearDiffLck_Tq_RqMx : 23|12@0+ (1,0) [0|0] "Nm" XXX + SG_ VehLongOvrGnd_A_Est : 47|10@0+ (0.035,-17.9) [0|0] "m/s^2" XXX + SG_ StabCtlBrkActv_B_Actl : 27|1@0+ (1,0) [0|0] "" XXX + SG_ CmbbBrkPrchg_B_Actl : 59|1@0+ (1,0) [0|0] "" XXX + SG_ CmbbBrkDecel_B_Actl : 58|1@0+ (1,0) [0|0] "" XXX + SG_ CmbbBaSensInc_B_Actl : 57|1@0+ (1,0) [0|0] "" XXX + SG_ AccBrkWarm_B_Actl : 63|1@0+ (1,0) [0|0] "" XXX + SG_ AccBrkTotTqMn_B_Actl : 62|1@0+ (1,0) [0|0] "" XXX + SG_ AccBrkPrchgActv_B_Actl : 61|1@0+ (1,0) [0|0] "" XXX + SG_ AccBrkDis_B_Actl : 50|1@0+ (1,0) [0|0] "" XXX + SG_ AccBrkDeny_B_Actl : 49|1@0+ (1,0) [0|0] "" XXX + SG_ AccBrkActv_B_Actl : 48|1@0+ (1,0) [0|0] "" XXX + SG_ PrplDrgCtlActv_B_Actl : 52|1@0+ (1,0) [0|0] "" XXX + SG_ PrplWhlTot_Tq_RqMx : 7|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + SG_ AbsActv_B_Actl : 51|1@0+ (1,0) [0|0] "" XXX + +BO_ 533 WheelSpeed_CG1: 8 XXX + SG_ WhlRr_W_Meas : 55|15@0+ (0.01,0) [0|0] "rad/s" XXX + SG_ WhlRl_W_Meas : 39|15@0+ (0.01,0) [0|0] "rad/s" XXX + SG_ WhlFr_W_Meas : 23|15@0+ (0.01,0) [0|0] "rad/s" XXX + SG_ WhlFl_W_Meas : 7|15@0+ (0.01,0) [0|0] "rad/s" XXX + +BO_ 534 WheelData: 8 XXX + SG_ WhlRotatRr_No_Cnt : 23|8@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRr_D_Actl : 33|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRl_D_Actl : 39|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFr_D_Actl : 37|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFl_D_Actl : 35|2@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatRl_No_Cnt : 31|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFr_No_Cnt : 7|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFl_No_Cnt : 15|8@0+ (1,0) [0|0] "" XXX + SG_ WHEEL_ROLLING_TIMESTAMP : 47|8@0+ (1,0) [0|0] "" XXX + +BO_ 557 InfoCAN_22D: 8 XXX + SG_ Multimedia_System : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 560 TransGearData: 8 XXX + SG_ TrnIpcDsplyRng_D_Actl : 14|3@0+ (1,0) [0|0] "" XXX + SG_ TrnGbox_Rt_Actl : 47|16@0+ (0.001,0) [0|0] "" XXX + SG_ TrnShifMde_D_RqDrv : 3|3@0+ (1,0) [0|0] "" XXX + SG_ TrnSrvcRqd_B_Rq : 63|1@0+ (1,0) [0|0] "" XXX + SG_ GearPos_D_Trg : 7|4@0+ (1,0) [0|0] "" XXX + SG_ TrnCnvtClu_D_Actl : 11|2@0+ (1,0) [0|0] "" XXX + SG_ TrnShifActv_B_Actl : 0|1@0+ (1,0) [0|0] "" XXX + SG_ RtmTerrMdeChng_D_Rdy : 58|3@0+ (1,0) [0|0] "" XXX + SG_ RtmTerrMde_D_Actl : 61|3@0+ (1,0) [0|0] "" XXX + SG_ GearRvrseActv_B_Actl : 62|1@0+ (1,0) [0|0] "" XXX + SG_ GearLvrPos_D_Actl : 23|4@0+ (1,0) [0|0] "" XXX + SG_ GboxOil_Te_Actl : 31|8@0+ (1,-60.0) [0|0] "degC" XXX + +BO_ 561 TransGearData_2: 8 XXX + SG_ MtrGen1Aout_Tq_Rq : 53|14@0+ (0.1,-800.0) [0|0] "Nm" XXX + SG_ MtrGen1AoutTqRq_No_Cs : 7|8@0+ (1,0) [0|0] "" XXX + SG_ MtrGen1AoutTqRq_No_Cnt : 15|4@0+ (1,0) [0|0] "" XXX + SG_ CoolFanTrn_D_Rq : 31|5@0+ (1,0) [0|0] "" XXX + SG_ TrnMsgTxt_D_Rq : 39|4@0+ (1,0) [0|0] "" XXX + SG_ TrnMil_D_Rq : 26|2@0+ (1,0) [0|0] "" XXX + SG_ EngExhBrkTq_Pc_Rq : 23|7@0+ (1,0) [0|0] "%" XXX + +BO_ 562 TransGearData_3_CG1: 8 XXX + SG_ TrnPto_D_Rdy : 12|2@0+ (1,0) [0|0] "" XXX + SG_ TipInMgrInhbt_B_RqTrn : 41|1@0+ (1,0) [0|0] "" XXX + SG_ TrnAinIdl_Tq_Actl : 39|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAinLss_Tq_Est : 7|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAin_Tq_RqSlwMn : 23|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ GearEngag_D_Actl : 10|3@0+ (1,0) [0|0] "" XXX + SG_ TrnAinTqDtrb_B_Rq : 40|1@0+ (1,0) [0|0] "" XXX + SG_ TrnTotLss_Tq_Actl : 55|8@0+ (0.5,0) [0|0] "Nm" XXX + +BO_ 563 TransGearData_4_CG1: 8 XXX + SG_ TrnAinCtlN_N_RqMn : 20|13@0+ (2.0,0) [0|0] "rpm" XXX + SG_ TrnAinTqMn_No_Cs : 63|8@0+ (1,0) [0|0] "" XXX + SG_ TrnAinTqMn_No_Cnt : 11|4@0+ (1,0) [0|0] "" XXX + SG_ TrnAinRq_Pc_SpcPdl : 7|10@0+ (0.1,0) [0|0] "%" XXX + SG_ TrnAin_Tq_RqFstMn : 42|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ TrnAin_N_SpcEng : 39|13@0+ (2.0,0) [0|0] "rpm" XXX + +BO_ 570 Suspension_Stat: 8 XXX + SG_ CcdMsgTxt_D_RqDsply : 7|4@0+ (1,0) [0|0] "" XXX + SG_ SuspRear_L_Prev : 48|9@0+ (0.782779,-200.0) [0|0] "millimeter" XXX + SG_ SuspRear_L_Actl : 32|9@0+ (0.782779,-200.0) [0|0] "millimeter" XXX + SG_ SuspFrnt_L_Prev : 16|9@0+ (0.782779,-200.0) [0|0] "millimeter" XXX + SG_ SuspFrnt_L_Actl : 0|9@0+ (0.782779,-200.0) [0|0] "millimeter" XXX + +BO_ 571 ColumnLockData: 8 XXX + SG_ SteWhlLckMsgTxt_D_Rq : 7|2@0+ (1,0) [0|0] "" XXX + +BO_ 576 Body_Information_4_CG1: 8 XXX + SG_ HvacRec_Pc_Est_UB : 51|1@0+ (1,0) [0|0] "" XXX + SG_ HvacRec_Pc_Est : 38|7@0+ (1,0) [0|0] "%" XXX + SG_ HvacEngIdleInc_B_Rq_UB : 49|1@0+ (1,0) [0|0] "" XXX + SG_ HvacEngIdleInc_B_Rq : 53|1@0+ (1,0) [0|0] "" XXX + SG_ HvacAir_Flw_Est_UB : 52|1@0+ (1,0) [0|0] "" XXX + SG_ HvacAir_Flw_Est : 31|9@0+ (0.5,0) [0|0] "liter/second" XXX + SG_ AmbTempImpr_UB : 50|1@0+ (1,0) [0|0] "" XXX + SG_ AmbTempImpr : 47|10@0+ (0.25,-128.0) [0|0] "degreesC" XXX + SG_ DriverCrankingReq : 16|1@0+ (1,0) [0|0] "" XXX + SG_ Fcw_B_DenyMntr : 23|1@0+ (1,0) [0|0] "" XXX + SG_ EngOff_T_Actl : 7|16@0+ (1,0) [0|0] "seconds" XXX + SG_ CmbbMntr_B_Err : 22|1@0+ (1,0) [0|0] "" XXX + SG_ CmbbDeny_B_RqMntr : 21|1@0+ (1,0) [0|0] "" XXX + SG_ AccMntr_B_Err : 20|1@0+ (1,0) [0|0] "" XXX + SG_ AccDeny_B_RqMntr : 19|1@0+ (1,0) [0|0] "" XXX + +BO_ 592 EONV_Status: 8 XXX + SG_ EONV_FAULT : 59|1@0+ (1,0) [0|0] "" XXX + SG_ EONV_KAL_IC_RQST : 53|1@0+ (1,0) [0|0] "" XXX + SG_ EONV_T_STATUS : 61|2@0+ (1,0) [0|0] "" XXX + SG_ EONV_VREF_FLT : 62|1@0+ (1,0) [0|0] "" XXX + SG_ EONV_VBATT_FLT : 63|1@0+ (1,0) [0|0] "" XXX + SG_ EONV_CANISTER_VENT_FLT : 54|1@0+ (1,0) [0|0] "" XXX + SG_ EONV_CVS_CLOSED : 55|1@0+ (1,0) [0|0] "" XXX + SG_ EONV_BATT_VOLT : 23|16@0+ (0.0009765625,0) [0|0] "volts" XXX + SG_ EONV_TANK_FLT : 48|1@0+ (1,0) [0|0] "" XXX + SG_ EONV_TANK_PRESS : 7|16@0+ (0.001953125,-64.0) [0|0] "inches H2O" XXX + +BO_ 597 EONV_Control: 8 XXX + SG_ EONV_POS_DET_THRESHOLD : 23|16@0+ (0.001953125,-64.0) [0|0] "inches H2O" XXX + SG_ EONV_STAY_ALIVE : 15|1@0+ (1,0) [0|0] "" XXX + SG_ EONV_CVS_MODE : 7|3@0+ (1,0) [0|0] "" XXX + SG_ EONV_NEG_DET_THRESHOLD : 39|16@0+ (0.001953125,-64.0) [0|0] "inches H2O" XXX + SG_ EONV_MIL_ON : 14|1@0+ (1,0) [0|0] "" XXX + SG_ EonvMsgTxOff_B_Rq : 4|1@0+ (1,0) [0|0] "" XXX + +BO_ 608 Information4x4_CG1: 8 XXX + SG_ AwdRngeShifActv_B_Actl : 0|1@0+ (1,0) [0|0] "" XXX + SG_ TrnAout_Tq_RqMx : 47|13@0+ (1,-1250.0) [0|0] "Nm" XXX + SG_ AwdRngeFalt_D_Stat : 4|2@0+ (1,0) [0|0] "" XXX + SG_ AwdLck_Tq_Actl : 15|12@0+ (1,0) [0|0] "Nm" XXX + SG_ AwdRnge_D_Actl : 7|3@0+ (1,0) [0|0] "" XXX + SG_ AwdTerrMdeChng_D_Rdy : 50|3@0+ (1,0) [0|0] "" XXX + SG_ AwdTerrMde_D_Actl : 58|3@0+ (1,0) [0|0] "" XXX + SG_ AwdOffRoadMode_D_Stats : 25|2@0+ (1,0) [0|0] "" XXX + SG_ AwdStat_D_RqDsply : 63|5@0+ (1,0) [0|0] "" XXX + SG_ AwdLoLamp_D_RqDsply : 35|2@0+ (1,0) [0|0] "" XXX + SG_ AwdHiLamp_D_RqDsply : 19|2@0+ (1,0) [0|0] "" XXX + SG_ AwdAutoLamp_D_RqDsply : 17|2@0+ (1,0) [0|0] "" XXX + SG_ AwdLckLamp_D_RqDsply : 27|2@0+ (1,0) [0|0] "" XXX + SG_ AwdLck_D_Stat : 31|4@0+ (1,0) [0|0] "" XXX + SG_ Awd2wdLamp_D_RqDsply : 2|2@0+ (1,0) [0|0] "" XXX + +BO_ 609 AWD_4x4_Data: 8 XXX + SG_ AwdLck_Tq_Rq : 27|12@0+ (1,0) [0|0] "Nm" XXX + SG_ AwdSrvcRqd_B_Rq : 44|1@0+ (1,0) [0|0] "" XXX + +BO_ 613 PassengerSeatOCSInfo: 8 XXX + SG_ VehicleMYCalibrationId : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VehicleCalibrationId : 31|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSensrDataUpperLim : 15|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSensrDataLowerLim : 23|8@0+ (1,0) [0|0] "" XXX + SG_ OCSLevel2Error : 0|1@0+ (1,0) [0|0] "" XXX + SG_ ObjectEntrapped : 2|1@0+ (1,0) [0|0] "" XXX + SG_ OCSLevel1Error : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 736 FCIM_Button_Press_HS: 8 XXX + SG_ FCIM_Target_ID : 13|4@0+ (1,0) [0|0] "" XXX + SG_ FCIM_Button_Type : 7|8@0+ (1,0) [0|0] "" XXX + SG_ FCIM_Button_State : 15|2@0+ (1,0) [0|0] "" XXX + SG_ FCIM_Target_ID_UB : 23|1@0+ (1,0) [0|0] "" XXX + SG_ FCIM_Button_Type_UB : 9|1@0+ (1,0) [0|0] "" XXX + SG_ FCIM_Button_State_UB : 8|1@0+ (1,0) [0|0] "" XXX + +BO_ 806 Compressor_Req_HS: 8 XXX + SG_ HvacEvap_Te_Rq : 33|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + SG_ HvacEvap_Te_Actl : 17|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + SG_ HvacAirCond_B_Rq : 7|1@0+ (1,0) [0|0] "" XXX + SG_ HvacEvap_Te_Offst : 1|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + +BO_ 832 RCMStatusMessage: 8 XXX + SG_ eCallNotification : 2|2@0+ (1,0) [0|0] "" XXX + SG_ CrashNotification : 5|1@0+ (1,0) [0|0] "" XXX + SG_ ThirdRowBucklePsngr : 57|2@0+ (1,0) [0|0] "" XXX + SG_ ThirdRowBuckleMid : 59|2@0+ (1,0) [0|0] "" XXX + SG_ ThirdRowBuckleDriver : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBucklePsngr : 63|2@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBuckleMid : 49|2@0+ (1,0) [0|0] "" XXX + SG_ SecondRowBuckleDriver : 51|2@0+ (1,0) [0|0] "" XXX + SG_ FirstRowBuckleDriver : 55|2@0+ (1,0) [0|0] "" XXX + SG_ RstrnTotalEvntCnt : 43|4@0+ (1,0) [0|0] "" XXX + SG_ RstrnCurrentEvntCnt : 39|8@0+ (1,0) [0|0] "" XXX + SG_ RILReq : 15|2@0+ (1,0) [0|0] "" XXX + SG_ FuelCutoffReq : 13|4@0+ (1,0) [0|0] "" XXX + SG_ SeatbeltIndicatorReq : 9|1@0+ (1,0) [0|0] "" XXX + SG_ SeatbeltChimeReq : 8|1@0+ (1,0) [0|0] "" XXX + SG_ BeltMinderProgConfReq : 21|2@0+ (1,0) [0|0] "" XXX + SG_ BeltMinderLevelReq : 19|4@0+ (1,0) [0|0] "" XXX + SG_ FirstRowBucklePsngr : 53|2@0+ (1,0) [0|0] "" XXX + SG_ InfoLampReq : 29|1@0+ (1,0) [0|0] "" XXX + SG_ GenRedLampReq : 28|1@0+ (1,0) [0|0] "" XXX + SG_ RstrnTextMsgReq : 27|2@0+ (1,0) [0|0] "" XXX + SG_ OCSSerialNumRcvd : 3|1@0+ (1,0) [0|0] "" XXX + SG_ RstrnStatDeployEnbld : 6|1@0+ (1,0) [0|0] "" XXX + SG_ RstrnImpactEvntStatus : 46|3@0+ (1,0) [0|0] "" XXX + SG_ PassRstrnInd_Req : 25|2@0+ (1,0) [0|0] "" XXX + SG_ RstrnStatTrigEvnt : 7|1@0+ (1,0) [0|0] "" XXX + SG_ PsngrFrntDetct_D_Actl : 31|2@0+ (1,0) [0|0] "" XXX + SG_ Beltminder_Warn_Stats : 22|1@0+ (1,0) [0|0] "" XXX + SG_ EDRTriggerEvntSync : 47|1@0+ (1,0) [0|0] "" XXX + +BO_ 842 MassageSeat_Data1_HS: 8 XXX + SG_ SeatLmbrUpDrv_Pc_Actl : 38|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatLmbrMidDrv_Pc_Actl : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatLmbrLoDrv_Pc_Actl : 22|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatBlUpDrv_Pc_Actl : 14|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatBlLoDrv_Pc_Actl : 6|7@0+ (1,0) [0|0] "%" XXX + +BO_ 843 MassageSeat_Data2_HS: 8 XXX + SG_ SeatLmbrUpPsgr_Pc_Actl : 38|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatLmbrMidPsgr_Pc_Actl : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatLmbrLoPsgr_Pc_Actl : 22|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatBlUpPsgr_Pc_Actl : 14|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatBlLoPsgr_Pc_Actl : 6|7@0+ (1,0) [0|0] "%" XXX + +BO_ 844 MassageSeat_Stat1_HS: 8 XXX + SG_ StmsLmbrDrv_D_Stat : 17|2@0+ (1,0) [0|0] "" XXX + SG_ StmsCshnDrv_D_Stat : 19|2@0+ (1,0) [0|0] "" XXX + SG_ SeatSwtchDrv_B_Stat : 31|1@0+ (1,0) [0|0] "" XXX + SG_ SeatFnDrv_D_Stat : 23|3@0+ (1,0) [0|0] "" XXX + SG_ SeatAirAmb_P_Actl : 7|16@0+ (0.01,0) [0|0] "KiloPascal" XXX + SG_ SeatPDrv_B_Stat : 20|1@0+ (1,0) [0|0] "" XXX + +BO_ 845 MassageSeat_Stat2_HS: 8 XXX + SG_ StmsLmbrPsgr_D_Stat : 15|2@0+ (1,0) [0|0] "" XXX + SG_ StmsCshnPsgr_D_Stat : 13|2@0+ (1,0) [0|0] "" XXX + SG_ SeatSwtchPsgr_B_Stat : 11|1@0+ (1,0) [0|0] "" XXX + SG_ SeatPPsgr_B_Stat : 7|1@0+ (1,0) [0|0] "" XXX + SG_ SeatFnPsgr_D_Stat : 6|3@0+ (1,0) [0|0] "" XXX + SG_ PsgrMemFeedback_Rsp : 3|4@0+ (1,0) [0|0] "" XXX + +BO_ 846 MassageSeat_Req: 8 XXX + SG_ SeatFnPsgr_D_Rq : 15|3@0+ (1,0) [0|0] "" XXX + SG_ SeatFnDrv_D_Rq : 12|3@0+ (1,0) [0|0] "" XXX + SG_ SeatFnDfaltPsgr_B_Rq : 9|1@0+ (1,0) [0|0] "" XXX + SG_ SeatFnDfaltDrv_B_Rq : 8|1@0+ (1,0) [0|0] "" XXX + SG_ SeatFnChngPsgr_D_Rq : 7|2@0+ (1,0) [0|0] "" XXX + SG_ SeatFnChngDrv_D_Rq : 5|2@0+ (1,0) [0|0] "" XXX + SG_ PsgrMemory_Rq : 3|4@0+ (1,0) [0|0] "" XXX + +BO_ 848 RestraintsData: 8 XXX + SG_ PassRstrnInd_Stat_UB : 9|1@0+ (1,0) [0|0] "" XXX + SG_ SeatBltWrnChmeStat : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Seatbelt_IndctrStat : 4|3@0+ (1,0) [0|0] "" XXX + SG_ RILStat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ PassRstrnInd_Stat : 15|4@0+ (1,0) [0|0] "" XXX + +BO_ 849 MassageSeat_Data3_HS: 8 XXX + SG_ SeatCshnDrvRR_Pc_Actl : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnDrvRL_Pc_Actl : 22|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnDrvFR_Pc_Actl : 14|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnDrvFL_Pc_Actl : 6|7@0+ (1,0) [0|0] "%" XXX + +BO_ 850 MassageSeat_Data4_HS: 8 XXX + SG_ SeatCshnPsgrRR_Pc_Actl : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnPsgrRL_Pc_Actl : 22|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnPsgrFR_Pc_Actl : 14|7@0+ (1,0) [0|0] "%" XXX + SG_ SeatCshnPsgrFL_Pc_Actl : 6|7@0+ (1,0) [0|0] "%" XXX + +BO_ 853 EFP_CC_Status: 8 XXX + SG_ Save_My_Temp : 59|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Left_Temp_Setpt : 31|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RrDefrost_HtdMirrorReq : 60|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Control_Status : 16|1@0+ (1,0) [0|0] "" XXX + SG_ MultipleButtonPressReq : 63|3@0+ (1,0) [0|0] "" XXX + SG_ Rear_System_Mode_Req : 19|3@0+ (1,0) [0|0] "" XXX + SG_ Rear_Left_Temp_Setpt : 47|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ Recirc_Request : 23|2@0+ (1,0) [0|0] "" XXX + SG_ Front_Rt_Temp_Setpt : 39|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ AC_Request : 21|2@0+ (1,0) [0|0] "" XXX + SG_ Windshield_ModeRequest : 15|4@0+ (8.33,0) [0|0] "%" XXX + SG_ Panel_Mode_Request : 7|4@0+ (8.33,0) [0|0] "%" XXX + SG_ Overriding_ModeReq : 10|3@0+ (1,0) [0|0] "" XXX + SG_ Forced_Recirc_Req : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Floor_Mode_Request : 3|4@0+ (8.33,0) [0|0] "%" XXX + SG_ Rear_Right_Temp_Setpt : 55|8@0+ (1,0) [0|0] "Mixed" XXX + +BO_ 854 EFP_CC_Seat_Req_Stat: 8 XXX + SG_ Front_Rear_Blower_Req : 31|6@0+ (1,0) [0|0] "Detents" XXX + SG_ Pass_Rr_Cond_Seat_Req : 21|2@0+ (1,0) [0|0] "" XXX + SG_ Pass_Rr_Cond_Seat_Lvl : 8|3@0+ (1,0) [0|0] "" XXX + SG_ Pass_Fr_Cond_Seat_Req : 13|2@0+ (1,0) [0|0] "" XXX + SG_ Pass_Fr_Cond_Seat_Lvl : 11|3@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Rr_Cond_Seat_Req : 15|2@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Rr_Cond_Seat_Lvl : 2|3@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Fr_Cond_Seat_Req : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Fr_Cond_Seat_Lvl : 5|3@0+ (1,0) [0|0] "" XXX + +BO_ 855 RCCM_CC_Status_HS: 8 XXX + SG_ RrBlwrCondStLdShedStat : 25|2@0+ (1,0) [0|0] "" XXX + SG_ FrBlwrCondStLdShedStat : 20|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_Rr_Rt_TempSetpt : 63|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RCCM_Rr_Left_TempSetpt : 55|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RCCM_Fr_Rt_TempSetpt : 47|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RCCM_Fr_Rr_Blower_Req : 31|6@0+ (1,0) [0|0] "Detents" XXX + SG_ Panel_Mode_State : 7|4@0+ (8.33,0) [0|0] "%" XXX + SG_ RrDefHtdMirrLdShedStat : 18|2@0+ (1,0) [0|0] "" XXX + SG_ Windshield_Mode_State : 15|4@0+ (8.33,0) [0|0] "%" XXX + SG_ Recirc_Door_State : 11|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_System_Mode_State : 23|3@0+ (1,0) [0|0] "" XXX + SG_ Default_Defrost_State : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Auto_AC_Indicator_Temp : 16|1@0+ (1,0) [0|0] "" XXX + SG_ Floor_Mode_State : 3|4@0+ (8.33,0) [0|0] "%" XXX + SG_ RCCM_Fr_Left_TempSetpt : 39|8@0+ (1,0) [0|0] "Mixed" XXX + SG_ RrDefrost_HtdMirrState : 8|1@0+ (1,0) [0|0] "" XXX + +BO_ 856 RCCM_CC_Seat_Status_HS: 8 XXX + SG_ Active_My_Temp : 2|1@0+ (1,0) [0|0] "" XXX + SG_ CC_HtdStrWhl_Req : 24|1@0+ (1,0) [0|0] "" XXX + SG_ RCCM_PR_Cond_Seat_Lvl : 31|3@0+ (1,0) [0|0] "" XXX + SG_ RCCM_PR_Cond_Seat_Req : 28|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_PF_Cond_Seat_Req : 20|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_PF_Cond_Seat_Lvl : 23|3@0+ (1,0) [0|0] "" XXX + SG_ RCCM_DR_Cond_Seat_Req : 12|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_DR_Cond_Seat_Lvl : 15|3@0+ (1,0) [0|0] "" XXX + SG_ RCCM_DF_Cond_Seat_Req : 4|2@0+ (1,0) [0|0] "" XXX + SG_ RCCM_DF_Cond_Seat_Lvl : 7|3@0+ (1,0) [0|0] "" XXX + SG_ PassRrCondStLdShedStat : 26|2@0+ (1,0) [0|0] "" XXX + SG_ PassFrCondStLdShedStat : 18|2@0+ (1,0) [0|0] "" XXX + SG_ DrvRrCondStLdShedStat : 10|2@0+ (1,0) [0|0] "" XXX + SG_ DrvFrCondStLdShedStat : 1|2@0+ (1,0) [0|0] "" XXX + +BO_ 857 RCCM_CC_MBP_Press_Stat_HS: 8 XXX + SG_ MultBtnPushDsplyPass10 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ MultBtnPushDsplyPass1 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ Report_Active : 33|2@0+ (1,0) [0|0] "" XXX + SG_ Pass_Temp_Units : 35|1@0+ (1,0) [0|0] "" XXX + SG_ Front_Fan_Bars_Disply : 39|3@0+ (1,0) [0|0] "" XXX + SG_ Drvr_Temp_Units : 36|1@0+ (1,0) [0|0] "" XXX + SG_ MultBtnPushDsplyDrvr10 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ MultBtnPushDsplyDrvr1 : 15|8@0+ (1,0) [0|0] "" XXX + +BO_ 859 MFD_CC_Status_HS: 8 XXX + SG_ Rear_Mode_Bttn_Status : 38|1@0+ (1,0) [0|0] "" XXX + SG_ ConditionSt_ButtonStat : 20|5@0+ (1,0) [0|0] "" XXX + SG_ Driver_Set_Temp : 31|8@0+ (0.5,0) [0|0] "Degrees" XXX + SG_ Frt_System_Button_Stat : 7|5@0+ (1,0) [0|0] "" XXX + SG_ Rear_Blower_Bar_Status : 2|3@0+ (1,0) [0|0] "# of Bars" XXX + SG_ Rear_Fan_Button_Status : 13|2@0+ (1,0) [0|0] "" XXX + SG_ Rear_Man_Temp_Bar_Stat : 11|4@0+ (1,0) [0|0] "" XXX + SG_ Rear_Temp_Button_Status : 23|2@0+ (1,0) [0|0] "" XXX + SG_ Voice_Blower_Limit : 21|1@0+ (1,0) [0|0] "" XXX + +BO_ 860 EFP_CC_Info_Status: 8 XXX + SG_ Rear_Panel_Btn_State : 41|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Floor_Btn_State : 40|1@0+ (1,0) [0|0] "" XXX + SG_ HtdStrWhl_SftBtt_Stt : 39|2@0+ (1,0) [0|0] "" XXX + SG_ AC_Sft_Button_State : 23|2@0+ (1,0) [0|0] "" XXX + SG_ DrvRrCondSeatSftBttnSt : 47|3@0+ (1,0) [0|0] "" XXX + SG_ DrvFrCondSeatSftBtnStt : 37|3@0+ (1,0) [0|0] "" XXX + SG_ CC_RecircSBtn_St : 27|2@0+ (1,0) [0|0] "" XXX + SG_ CC_RrDefrSBtn_St : 24|1@0+ (1,0) [0|0] "" XXX + SG_ PasRrCondSeatSftBttnSt : 44|3@0+ (1,0) [0|0] "" XXX + SG_ PasFrCondSeatSftBtnStt : 34|3@0+ (1,0) [0|0] "" XXX + SG_ MyTemp_Soft_Bttn_State : 25|1@0+ (1,0) [0|0] "" XXX + SG_ CC_MaxACSBtn_St : 28|1@0+ (1,0) [0|0] "" XXX + SG_ RearPowerButtonState : 16|1@0+ (1,0) [0|0] "" XXX + SG_ RearCoolBarsDisplayed : 11|3@0+ (1,0) [0|0] "Bars_On" XXX + SG_ Rear_Sft_Control_Stat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ CC_RrNeutralBarDsp_St : 8|1@0+ (1,0) [0|0] "" XXX + SG_ CC_RrHeatBarsDsp_St : 31|3@0+ (1,0) [0|0] "Bars_On" XXX + SG_ Rear_Fan_Bars_Displayed : 19|3@0+ (1,0) [0|0] "" XXX + SG_ CC_RrCtrlBtn_St : 20|1@0+ (1,0) [0|0] "" XXX + SG_ Rear_Auto_Button_State : 21|1@0+ (1,0) [0|0] "" XXX + SG_ CC_FrPowerSBtn_St : 14|1@0+ (1,0) [0|0] "" XXX + SG_ CC_FrDefrostSBtn_St : 15|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_Soft_Btn_Stt : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_MODE_State : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Front_AUTO_FAN_State : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Dual_Button_State : 12|1@0+ (1,0) [0|0] "" XXX + SG_ CC_BarPnlSBtn_St : 5|1@0+ (1,0) [0|0] "" XXX + SG_ CC_BarPnFlrSBtn_St : 4|1@0+ (1,0) [0|0] "" XXX + SG_ CC_BarFlrWsSBtn_St : 2|1@0+ (1,0) [0|0] "" XXX + SG_ CC_BarDrvFlrSBtn_St : 3|1@0+ (1,0) [0|0] "" XXX + +BO_ 890 Active_Noise: 8 XXX + SG_ ANC_Chime_Supported : 4|2@0+ (1,0) [0|0] "" XXX + SG_ ActvNseAudio_D_Stat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ ActvNse_B_Actv : 5|1@0+ (1,0) [0|0] "" XXX + +BO_ 891 Active_Noise_Data: 8 XXX + SG_ CabnSndAmb_Db_Actl : 7|8@0+ (1,30.0) [0|0] "decibel" XXX + +BO_ 906 Body_Information_1: 8 XXX + SG_ CcdMde_D_Rq_UB : 0|1@0+ (1,0) [0|0] "" XXX + SG_ CcdMde_D_Rq : 7|2@0+ (1,0) [0|0] "" XXX + SG_ CarMode : 5|4@0+ (1,0) [0|0] "" XXX + SG_ SecondaryHeater_Rqst : 55|1@0+ (1,0) [0|0] "" XXX + SG_ Passenger_Sunload_Raw : 47|8@0+ (5.0,0) [0|0] "W/m^2" XXX + SG_ Driver_Sunload_Raw : 39|8@0+ (5.0,0) [0|0] "W/m^2" XXX + SG_ HvacEvap_Te_Actl_UB : 1|1@0+ (1,0) [0|0] "" XXX + SG_ HvacEvap_Te_Actl : 17|10@0+ (0.125,-50.0) [0|0] "Degrees C" XXX + SG_ SecondaryHeater_Rqst_UB : 18|1@0+ (1,0) [0|0] "" XXX + SG_ Outside_Air_Temp_Stat_UB : 23|1@0+ (1,0) [0|0] "" XXX + SG_ Outside_Air_Temp_Stat : 15|8@0+ (0.5,-40.0) [0|0] "Degrees C" XXX + SG_ Veh_Lock_Status : 54|2@0+ (1,0) [0|0] "" XXX + SG_ Veh_Lock_Requestor : 52|5@0+ (1,0) [0|0] "" XXX + SG_ Veh_Lock_EvNum : 63|8@0+ (1,0) [0|0] "Counts" XXX + SG_ immoIndicatorCmd : 22|4@0+ (1,0) [0|0] "" XXX + +BO_ 909 Body_Information_6: 8 XXX + SG_ PEBackupSlot_Stats_UB : 43|1@0+ (1,0) [0|0] "" XXX + SG_ PEBackupSlot_Stats : 25|2@0+ (1,0) [0|0] "" XXX + SG_ KeyMykeyTot_No_Cnt : 47|4@0+ (1,0) [0|0] "Counts" XXX + SG_ SideDetect_R_SysOpState_UB : 26|1@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_R_SysOpState : 28|2@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_R_SnsrState_UB : 29|1@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_R_SnsrState : 31|2@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_L_SysOpState_UB : 16|1@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_L_SysOpState : 18|2@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_L_SnsrState_UB : 19|1@0+ (1,0) [0|0] "" XXX + SG_ SideDetect_L_SnsrState : 21|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_R_SnState_UB : 8|1@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_R_SnState : 23|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_R_Op_State_UB : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_R_Op_State : 11|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_R_Alert_UB : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_R_Alert : 14|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_L_SnState_UB : 15|1@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_L_SnState : 1|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_L_Op_State_UB : 2|1@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_L_Op_State : 4|2@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_L_Alert_UB : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Cross_Traffic_L_Alert : 7|2@0+ (1,0) [0|0] "" XXX + SG_ IgnKeyType_D_Actl : 39|4@0+ (1,0) [0|0] "" XXX + SG_ KeyAdmnTot_No_Cnt : 35|4@0+ (1,0) [0|0] "Counts" XXX + +BO_ 936 ParkAid_Data: 8 XXX + SG_ SAPPErrorCoding : 23|8@0+ (1,0) [0|0] "" XXX + SG_ ExtSteeringAngleReq : 7|15@0+ (0.1,-1000.0) [0|0] "Degrees" XXX + SG_ EPASExtAngleStatReq : 8|1@0+ (1,0) [0|0] "" XXX + +BO_ 937 ParkAid_Range_to_Target: 8 XXX + SG_ RangeToClosestObstacle : 55|12@0+ (1,0) [0|0] "cm" XXX + SG_ RangeRearCornerRtSn : 35|12@0+ (1,0) [0|0] "cm" XXX + SG_ RangeRearCornerLeftSn : 31|12@0+ (1,0) [0|0] "cm" XXX + SG_ RangeRearCenterRtSn : 11|12@0+ (1,0) [0|0] "cm" XXX + SG_ RangeRearCenterLeftSn : 7|12@0+ (1,0) [0|0] "cm" XXX + +BO_ 939 ParkAid_Data_CG1: 8 XXX + SG_ EPASExtAngleStatReq : 7|1@0+ (1,0) [0|0] "" XXX + SG_ ExtSteeringAngleReq : 6|15@0+ (0.1,-1000.0) [0|0] "Degrees" XXX + SG_ SAPPErrorCoding : 23|8@0+ (1,0) [0|0] "" XXX + SG_ RangeToClosestObstacle : 27|12@0+ (1,0) [0|0] "cm" XXX + +BO_ 942 BodyInformation_2: 8 XXX + SG_ Easy_Entry_Exit_Stat : 14|2@0+ (1,0) [0|0] "" XXX + SG_ Memory_Feedback_Rqst : 15|1@0+ (1,0) [0|0] "" XXX + SG_ Delay_Accy : 41|1@0+ (1,0) [0|0] "" XXX + SG_ Fuel_Econ_AFE_Reset_Req_UB : 43|1@0+ (1,0) [0|0] "" XXX + SG_ Multimedia_System : 42|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatDrv_B_Actl : 7|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatHood_B_Actl : 6|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatInnrTgate_B_Actl : 5|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatPsngr_B_Actl : 4|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatRl_B_Actl : 3|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatRr_B_Actl : 2|1@0+ (1,0) [0|0] "" XXX + SG_ DrStatTgate_B_Actl : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Fuel_Econ_AFE_Reset_Req : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Nav_Unit_Setting : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Cancel_Auto_Movement : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Cancel_Auto_Movement_UB : 8|1@0+ (1,0) [0|0] "" XXX + SG_ DrvSeat_Stat : 34|3@0+ (1,0) [0|0] "" XXX + SG_ DrvSeat_Stat_UB : 10|1@0+ (1,0) [0|0] "" XXX + SG_ Easy_Entry_Rqst : 47|2@0+ (1,0) [0|0] "" XXX + SG_ Easy_Entry_Rqst_UB : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Multimedia_System_UB : 40|1@0+ (1,0) [0|0] "" XXX + SG_ Memory_Cmd : 39|4@0+ (1,0) [0|0] "" XXX + SG_ Memory_Cmd_UB : 35|1@0+ (1,0) [0|0] "" XXX + SG_ Memory_Feedback_Rqst_UB : 45|1@0+ (1,0) [0|0] "" XXX + SG_ Decklid_Ajar_Status : 44|1@0+ (1,0) [0|0] "" XXX + +BO_ 947 BodyInformation_3: 8 XXX + SG_ RearFog_Lamp_Ind_UB : 49|1@0+ (1,0) [0|0] "" XXX + SG_ RearFog_Lamp_Ind : 50|1@0+ (1,0) [0|0] "" XXX + SG_ PwMdeExten_D_Actl : 63|5@0+ (1,0) [0|0] "" XXX + SG_ Turn_Ind_Cmd_Right : 8|1@0+ (1,0) [0|0] "" XXX + SG_ Turn_Ind_Cmd_Left : 9|1@0+ (1,0) [0|0] "" XXX + SG_ Ignition_Switch_Stable : 1|2@0+ (1,0) [0|0] "" XXX + SG_ Parklamp_Status : 3|2@0+ (1,0) [0|0] "" XXX + SG_ Litval : 47|8@0+ (1,0) [0|0] "" XXX + SG_ Key_In_Ignition_Stat : 11|2@0+ (1,0) [0|0] "" XXX + SG_ Ignition_Status : 7|4@0+ (1,0) [0|0] "" XXX + SG_ Dimming_Lvl : 31|8@0+ (1,0) [0|0] "" XXX + SG_ Day_Night_Status : 15|2@0+ (1,0) [0|0] "" XXX + SG_ Remote_Start_Status : 13|2@0+ (1,0) [0|0] "" XXX + SG_ DRV_SELECT_STAT : 19|4@0+ (1,0) [0|0] "" XXX + SG_ PrkBrkActv_B_Actl : 55|1@0+ (1,0) [0|0] "" XXX + SG_ HtdStrWhl_SftBtt_State_UB : 51|1@0+ (1,0) [0|0] "" XXX + SG_ HtdStrWhl_SftBtt_State : 53|2@0+ (1,0) [0|0] "" XXX + SG_ HvacRemoteStrt_N_Rq_UB : 56|1@0+ (1,0) [0|0] "" XXX + SG_ HvacRemoteStrt_N_Rq : 23|4@0+ (100.0,450.0) [0|0] "RPM" XXX + SG_ HvacAirCond_B_Rq_UB : 57|1@0+ (1,0) [0|0] "" XXX + SG_ Remote_Start_Warn_Req : 54|1@0+ (1,0) [0|0] "" XXX + SG_ HvacAirCond_B_Rq : 58|1@0+ (1,0) [0|0] "" XXX + +BO_ 948 Tire_Pressure_Status: 8 XXX + SG_ Tire_Press_ILR_Stat2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ Tire_Press_IRR_Stat2 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ Tire_Press_LR_OLR_Stat2 : 19|4@0+ (1,0) [0|0] "" XXX + SG_ Tire_Press_RR_ORR_Stat2 : 23|4@0+ (1,0) [0|0] "" XXX + SG_ Tire_Press_RF_Stat2 : 11|4@0+ (1,0) [0|0] "" XXX + SG_ Tire_Press_LF_Stat2 : 15|4@0+ (1,0) [0|0] "" XXX + SG_ Tire_Press_System_Stat2 : 7|4@0+ (1,0) [0|0] "" XXX + SG_ Tire_Press_Telltale : 3|2@0+ (1,0) [0|0] "" XXX + +BO_ 949 Tire_Pressure_Data: 8 XXX + SG_ Tire_Press_RR_ORR_Data : 23|8@0+ (1,0) [0|0] "Psi" XXX + SG_ Tire_Press_RF_Data : 15|8@0+ (1,0) [0|0] "Psi" XXX + SG_ Tire_Press_LR_OLR_Data : 31|8@0+ (1,0) [0|0] "Psi" XXX + SG_ Tire_Press_IRR_Data : 39|8@0+ (1,0) [0|0] "Psi" XXX + SG_ Tire_Press_ILR_Data : 47|8@0+ (1,0) [0|0] "Psi" XXX + SG_ Tire_Press_LF_Data : 7|8@0+ (1,0) [0|0] "Psi" XXX + +BO_ 955 Smart_Headlamp_Stat: 8 XXX + SG_ Headlamp_Switch_Stat : 7|2@0+ (1,0) [0|0] "" XXX + SG_ Fog_Lamp_Dbnce : 5|2@0+ (1,0) [0|0] "" XXX + SG_ Digital_Dimmer_Sw_Stat : 3|3@0+ (1,0) [0|0] "" XXX + +BO_ 957 Rear_FogLamp: 8 XXX + SG_ RearFog_Lamp_Dbnce : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 963 BCM_to_HS_Body: 8 XXX + SG_ DrTgateChime_D_Rq_UB : 9|1@0+ (1,0) [0|0] "" XXX + SG_ DrTgateChime_D_Rq : 17|2@0+ (1,0) [0|0] "" XXX + SG_ CamraDefog_B_Actl : 4|1@0+ (1,0) [0|0] "" XXX + SG_ Reverse_Mirror_Stat : 61|2@0+ (1,0) [0|0] "" XXX + SG_ Power_Liftgate_Mode_Stat : 63|2@0+ (1,0) [0|0] "" XXX + SG_ IKT_Program_Status : 51|2@0+ (1,0) [0|0] "" XXX + SG_ Veh_Spd_Slow_Puddle_Status : 41|2@0+ (1,0) [0|0] "" XXX + SG_ Illuminated_Exit_Status : 43|2@0+ (1,0) [0|0] "" XXX + SG_ Illuminated_Entry_Status : 45|2@0+ (1,0) [0|0] "" XXX + SG_ Door_Courtesy_Light_Status : 47|2@0+ (1,0) [0|0] "" XXX + SG_ Courtesy_Demand_BSave_Stat : 33|2@0+ (1,0) [0|0] "" XXX + SG_ Alarm_Lights_Courtesy_Stat : 35|2@0+ (1,0) [0|0] "" XXX + SG_ Courtesy_Delay_Status : 37|2@0+ (1,0) [0|0] "" XXX + SG_ Courtesy_Mode_Status : 39|2@0+ (1,0) [0|0] "" XXX + SG_ Front_Fog_Light_SW_Status : 22|2@0+ (1,0) [0|0] "" XXX + SG_ Brake_Lamp_On_Status : 23|1@0+ (1,0) [0|0] "" XXX + SG_ LowBeam_CKT_CAN : 11|1@0+ (1,0) [0|0] "" XXX + SG_ ParkLamps_CKT_CAN : 8|1@0+ (1,0) [0|0] "" XXX + SG_ RF_Low_Beam_CKT_CAN : 13|1@0+ (1,0) [0|0] "" XXX + SG_ Brk_Fluid_Lvl_Low : 15|2@0+ (1,0) [0|0] "" XXX + SG_ LF_Low_Beam_CKT_CAN : 12|1@0+ (1,0) [0|0] "" XXX + SG_ High_Beam_Indicator_Rqst : 1|1@0+ (1,0) [0|0] "" XXX + SG_ Brake_Warn_Indicator_Rqst : 2|1@0+ (1,0) [0|0] "" XXX + SG_ Headlamp_On_Wrning_Cmd : 6|1@0+ (1,0) [0|0] "" XXX + SG_ Key_In_Ignition_Warn_Cmd : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Fog_Lamps_Rly_Ckt_CAN : 10|1@0+ (1,0) [0|0] "" XXX + SG_ Power_Liftgate_Mode_Stat_UB : 18|1@0+ (1,0) [0|0] "" XXX + SG_ Reverse_Mirror_Stat_UB : 7|1@0+ (1,0) [0|0] "" XXX + SG_ Park_Brake_Chime_Rqst : 3|1@0+ (1,0) [0|0] "" XXX + SG_ Daytime_Running_Lamps : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Running_Board_Stat_UB : 56|1@0+ (1,0) [0|0] "" XXX + SG_ Running_Board_Stat : 58|2@0+ (1,0) [0|0] "" XXX + SG_ Perimeter_Alarm_Chime_Rqst : 20|2@0+ (1,0) [0|0] "" XXX + +BO_ 967 CMPS_FDM_Info_Status: 8 XXX + SG_ CamraFrntStat_D_Stat : 41|2@0+ (1,0) [0|0] "" XXX + SG_ Zone_Icon_UB : 34|1@0+ (1,0) [0|0] "" XXX + SG_ GPS_Compass_direction : 47|4@0+ (1,0) [0|0] "" XXX + SG_ Segment_MSD_UB : 37|1@0+ (1,0) [0|0] "" XXX + SG_ Segment_LSD_UB : 36|1@0+ (1,0) [0|0] "" XXX + SG_ ExcessiveMagnetism : 32|1@0+ (1,0) [0|0] "" XXX + SG_ Compass_Display_UB : 35|1@0+ (1,0) [0|0] "" XXX + SG_ Segment_LSD : 15|8@0+ (1,0) [0|0] "" XXX + SG_ Segment_MSD : 7|8@0+ (1,0) [0|0] "" XXX + SG_ Cal_Icon : 21|1@0+ (1,0) [0|0] "" XXX + SG_ Zone_Icon : 22|1@0+ (1,0) [0|0] "" XXX + SG_ Compass_Display : 23|1@0+ (1,0) [0|0] "" XXX + SG_ Cal_Icon_UB : 33|1@0+ (1,0) [0|0] "" XXX + SG_ RearCameraDelayStat : 39|2@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlTow_D_Actl : 25|2@0+ (1,0) [0|0] "SE" XXX + SG_ CamZoomActiveState : 29|2@0+ (1,0) [0|0] "" XXX + SG_ CamraZoomMan_D_Actl : 18|3@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlStat_D_Actl : 27|2@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlDyn_D_Actl : 20|2@0+ (1,0) [0|0] "" XXX + SG_ CamPDCGuidStat : 31|2@0+ (1,0) [0|0] "" XXX + +BO_ 970 Lane_Assist_Data1: 8 XXX + SG_ LkaActvStats_D_Req : 7|3@0+ (1,0) [0|0] "" XXX + SG_ LdwActvStats_D_Req : 4|3@0+ (1,0) [0|0] "" XXX + SG_ LdwActvIntns_D_Req : 1|2@0+ (1,0) [0|0] "" XXX + +BO_ 971 Lane_Assist_Data2: 8 XXX + SG_ LaRefAng_No_Req : 19|12@0+ (0.05,-102.4) [0|0] "mrad" XXX + SG_ LaRampType_B_Req : 4|1@0+ (1,0) [0|0] "" XXX + SG_ LaCurvature_No_Calc : 3|12@0+ (5e-06,-0.01) [0|0] "1/m" XXX + +BO_ 972 Lane_Assist_Data3: 8 XXX + SG_ LaHandsOff_B_Actl : 7|1@0+ (1,0) [0|0] "" XXX + SG_ LaActDeny_B_Actl : 6|1@0+ (1,0) [0|0] "" XXX + SG_ LaActAvail_D_Actl : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 984 IPMA_Data: 8 XXX + SG_ LaSwtch_D_RqDrv : 45|1@0+ (1,0) [0|0] "" XXX + SG_ DasWarn_D_Dsply : 44|2@0+ (1,0) [0|0] "" XXX + SG_ DasStats_D_Dsply : 47|2@0+ (1,0) [0|0] "" XXX + SG_ DasAlrtLvl_D_Dsply : 55|3@0+ (1,0) [0|0] "" XXX + SG_ CamraStats_D_Dsply : 35|2@0+ (1,0) [0|0] "" XXX + SG_ CamraDefog_B_Req : 36|1@0+ (1,0) [0|0] "" XXX + SG_ LaSwtchStat_No_Actl : 63|1@0+ (1,0) [0|0] "" XXX + SG_ LaHandsOff_D_Dsply : 42|2@0+ (1,0) [0|0] "" XXX + SG_ LaDenyStats_B_Dsply : 40|1@0+ (1,0) [0|0] "" XXX + SG_ LaActvStats_D_Dsply : 52|5@0+ (1,0) [0|0] "" XXX + SG_ AhbcHiBeam_D_Rq : 33|2@0+ (1,0) [0|0] "" XXX + SG_ PersIndexIpma_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoIpmaActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigIpmaActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 986 Personality_APIM_Data3: 8 XXX + SG_ LightAmbIntSwtchInc_B : 22|1@0+ (1,0) [0|0] "" XXX + SG_ LightAmbIntSwtchDec_B : 21|1@0+ (1,0) [0|0] "" XXX + SG_ LightAmbIntsty_No_Rq : 15|8@0+ (1,0) [0|0] "% Intensity" XXX + SG_ LightAmbColor_No_Rq : 7|8@0+ (1,0) [0|0] "Color Index" XXX + SG_ LightAmbClrSwtchInc_B : 20|1@0+ (1,0) [0|0] "" XXX + SG_ LightAmbClrSwtchDec_B : 23|1@0+ (1,0) [0|0] "" XXX + +BO_ 991 Personality_VDM_Data: 8 XXX + SG_ PersIndexVdm_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoVdmActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigVdmActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 992 Personality_IPC_Data: 8 XXX + SG_ MsgCntrPersIndex_D_Rq : 39|3@0+ (1,0) [0|0] "" XXX + SG_ MsgCntrFeatConfigRq : 23|16@0+ (1,0) [0|0] "" XXX + SG_ MsgCntrFeatNoRq : 7|16@0+ (1,0) [0|0] "Number" XXX + SG_ MsgCntrDsplyOp_D_Rq : 36|3@0+ (1,0) [0|0] "" XXX + +BO_ 993 Personality_Data_HS: 8 XXX + SG_ PersSetupRestr_D_Actl : 21|2@0+ (1,0) [0|0] "" XXX + SG_ PersSetupAccessCtrl : 19|1@0+ (1,0) [0|0] "SES" XXX + SG_ PersSetup_No_Actl : 31|16@0+ (1,0) [0|0] "Number" XXX + SG_ PersConflict_D_Actl : 22|1@0+ (1,0) [0|0] "" XXX + SG_ AssocConfirm_D_Actl : 15|3@0+ (1,0) [0|0] "" XXX + SG_ RecallEvent_No_Cnt : 7|8@0+ (1,0) [0|0] "Counts" XXX + SG_ PersNo_D_Actl : 10|3@0+ (1,0) [0|0] "" XXX + SG_ PersStore_D_Actl_UB : 23|1@0+ (1,0) [0|0] "" XXX + SG_ PersStore_D_Actl : 12|2@0+ (1,0) [0|0] "" XXX + +BO_ 994 Personality_APIM_Data: 8 XXX + SG_ CamraOvrlTow_D_Rq : 42|1@0+ (1,0) [0|0] "" XXX + SG_ Pers4OptIn_B_Stats : 43|1@0+ (1,0) [0|0] "" XXX + SG_ Pers3OptIn_B_Stats : 33|1@0+ (1,0) [0|0] "" XXX + SG_ Pers2OptIn_B_Stats : 32|1@0+ (1,0) [0|0] "" XXX + SG_ Pers1OptIn_B_Stats : 44|1@0+ (1,0) [0|0] "" XXX + SG_ CtrStkPersIndex_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ CtrStkFeatNoActl : 23|16@0+ (1,0) [0|0] "" XXX + SG_ PersStore_D_Rq : 36|3@0+ (1,0) [0|0] "" XXX + SG_ CtrStkFeatConfigActl : 7|16@0+ (1,0) [0|0] "" XXX + SG_ CtrStkDsplyOp_D_Rq : 47|3@0+ (1,0) [0|0] "" XXX + +BO_ 995 Personality_BCM_Data: 8 XXX + SG_ PersIndexBcm_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoBcm_No_Actl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigBcmActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 996 Personality_HCMB_Data_HS: 8 XXX + SG_ PersIndexHcmb_D_Actl_UB : 34|1@0+ (1,0) [0|0] "" XXX + SG_ PersIndexHcmb_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoHcmbActl_UB : 35|1@0+ (1,0) [0|0] "" XXX + SG_ FeatNoHcmbActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigHcmbActl_UB : 36|1@0+ (1,0) [0|0] "" XXX + SG_ FeatConfigHcmbActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 997 Personality_CCM_Data: 8 XXX + SG_ PersIndexCcm_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoCcmActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigCcmActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 998 Personality_SCCM_Data: 8 XXX + SG_ PersIndexSccm_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoSccmActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigSccmActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 999 Personality_HVAC_Data_HS: 8 XXX + SG_ LightAmbIntsty_No_Actl_UB : 33|1@0+ (1,0) [0|0] "" XXX + SG_ LightAmbIntsty_No_Actl : 55|8@0+ (1,0) [0|0] "% Intensity" XXX + SG_ LightAmbColor_No_Actl_UB : 32|1@0+ (1,0) [0|0] "" XXX + SG_ LightAmbColor_No_Actl : 47|8@0+ (1,0) [0|0] "Color Index" XXX + SG_ PersIndexHvac_D_Actl_UB : 34|1@0+ (1,0) [0|0] "" XXX + SG_ FeatNoHvacActl_UB : 35|1@0+ (1,0) [0|0] "" XXX + SG_ FeatConfigHvacActl_UB : 36|1@0+ (1,0) [0|0] "" XXX + SG_ PersIndexHvac_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoHvacActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigHvacActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 1001 Personality_RFA_Data_HS: 8 XXX + SG_ PersIndexRfa_D_Actl_UB : 34|1@0+ (1,0) [0|0] "" XXX + SG_ FeatNoRfaActl_UB : 35|1@0+ (1,0) [0|0] "" XXX + SG_ FeatConfigRfaActl_UB : 36|1@0+ (1,0) [0|0] "" XXX + SG_ PersIndexRfa_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoRfaActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigRfaActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 1002 Personality_APIM_Data2: 8 XXX + SG_ PersIndexApim_D_Actl : 63|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoApimActl : 39|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigApimActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ CntrStkKeycodeActl : 7|16@0+ (1,0) [0|0] "" XXX + SG_ CntrStk_D_RqRecall : 52|3@0+ (1,0) [0|0] "" XXX + SG_ CntrStk_D_RqAssoc : 55|3@0+ (1,0) [0|0] "" XXX + +BO_ 1003 Personality_IPC_Data_2: 8 XXX + SG_ PersIndexIpc_D_Actl : 34|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoIpcActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigIpcActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 1004 Personality_DSM_Data_HS: 8 XXX + SG_ PersIndexDsm_D_Actl_UB : 34|1@0+ (1,0) [0|0] "" XXX + SG_ PersIndexDsm_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoDsmActl_UB : 35|1@0+ (1,0) [0|0] "" XXX + SG_ FeatNoDsmActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigDsmActl_UB : 36|1@0+ (1,0) [0|0] "" XXX + SG_ FeatConfigDsmActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 1005 Personality_RHVAC_Data_HS: 8 XXX + SG_ PersIndexRhvac_D_Actl_UB : 34|1@0+ (1,0) [0|0] "" XXX + SG_ FeatNoRhvacActl_UB : 33|1@0+ (1,0) [0|0] "" XXX + SG_ FeatConfigRhvacActl_UB : 32|1@0+ (1,0) [0|0] "" XXX + SG_ PersIndexRhvac_D_Actl : 39|3@0+ (1,0) [0|0] "" XXX + SG_ FeatNoRhvacActl : 23|16@0+ (1,0) [0|0] "Number" XXX + SG_ FeatConfigRhvacActl : 7|16@0+ (1,0) [0|0] "" XXX + +BO_ 1031 Diesel_Data_Legacy_1: 8 XXX + SG_ W2S_COMMAND : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TURBO_BOOST : 1|10@0+ (0.1,-30.0) [0|0] "PSI" XXX + SG_ IDLE_ENGINE_SHUTDOWN : 42|2@0+ (1,0) [0|0] "" XXX + +BO_ 1034 GGCC_Config_Mgmt_ID_1: 8 XXX + SG_ VehicleGGCCData : 7|64@0+ (1,0) [0|0] "mixed" XXX + +BO_ 1036 Desired_Torq_BrkSys_Stat: 8 XXX + SG_ BRK_TC_TEMPORARILY_UNAVAIL : 47|1@0+ (1,0) [0|0] "" XXX + SG_ TRLR_SWAY_EVNT_IN_PROGRESS : 22|1@0+ (1,0) [0|0] "" XXX + +BO_ 1043 ADAPTIVE_HEADLAMP_STAT: 8 XXX + SG_ ADAPTIVE_HEADLAMP_FAILURE : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 1044 AccelerationData: 8 XXX + SG_ VehVertComp_A_Actl : 1|10@0+ (0.01,-0.4) [0|0] "m/s^2" XXX + SG_ VehRolComp_W_Actl : 19|12@0+ (0.0002,-0.82) [0|0] "rad/s" XXX + SG_ VehYawNonLin_W_Rq : 51|12@0+ (0.03663,-75.0) [0|0] "deg/s" XXX + SG_ VehYawLin_W_Rq : 35|12@0+ (0.03663,-75.0) [0|0] "deg/s" XXX + +BO_ 1045 BrakeSysFeatures: 8 XXX + SG_ TCMode : 34|1@0+ (1,0) [0|0] "" XXX + SG_ DrvSlipCtlLamp_D_Rq : 63|2@0+ (1,0) [0|0] "" XXX + SG_ RSCMode : 48|1@0+ (1,0) [0|0] "" XXX + SG_ EBAMode : 40|1@0+ (1,0) [0|0] "" XXX + SG_ DrvAntiLckLamp_D_Rq : 17|2@0+ (1,0) [0|0] "" XXX + SG_ ChimeBrk_B_Rq : 38|1@0+ (1,0) [0|0] "" XXX + SG_ BrkLamp_B_Rq : 39|1@0+ (1,0) [0|0] "" XXX + SG_ VehVActlBrk_No_Cs : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VehVActlBrk_No_Cnt : 23|4@0+ (1,0) [0|0] "" XXX + SG_ Veh_V_ActlBrk : 7|16@0+ (0.01,0) [0|0] "kph" XXX + SG_ DrvSlipCtlMde_D_Ind : 33|2@0+ (1,0) [0|0] "" XXX + SG_ VehRol_An_Dsply : 55|7@0+ (1,-64.0) [0|0] "Degrees" XXX + SG_ VehPtch_An_Dsply : 47|7@0+ (1,-64.0) [0|0] "Degrees" XXX + SG_ VehVActlBrk_D_Qf : 19|2@0+ (1,0) [0|0] "" XXX + SG_ HILL_DESC_MC : 37|3@0+ (1,0) [0|0] "" XXX + +BO_ 1046 BrakeSysFeatures_2: 8 XXX + SG_ BpedMove_No_Cs : 23|8@0+ (1,0) [0|0] "" XXX + SG_ BpedMove_No_Cnt : 3|4@0+ (1,0) [0|0] "" XXX + SG_ BpedMove_D_Actl : 7|2@0+ (1,0) [0|0] "" XXX + SG_ AbsMduleAlive_No_Cnt : 39|4@0+ (1,0) [0|0] "" XXX + SG_ Abs_No_Cs : 31|8@0+ (1,0) [0|0] "" XXX + SG_ BrkAsst_B_Actl : 33|1@0+ (1,0) [0|0] "" XXX + SG_ StabCtlBrk_B_Avail : 4|1@0+ (1,0) [0|0] "" XXX + SG_ DrvHdcWarnInfo_D_Rq : 35|2@0+ (1,0) [0|0] "" XXX + SG_ DrvHdcMsg_D_Rq : 10|3@0+ (1,0) [0|0] "" XXX + SG_ DrvHdcLampInfo_D_Rq : 12|2@0+ (1,0) [0|0] "" XXX + SG_ Abs_B_Falt : 5|1@0+ (1,0) [0|0] "" XXX + SG_ VehLongComp_A_Actl : 49|10@0+ (0.035,-17.9) [0|0] "m/s^2" XXX + SG_ TRAILER_SWAY_CONFIG_STAT : 32|1@0+ (1,0) [0|0] "" XXX + SG_ VehLatComp_A_Actl : 47|10@0+ (0.035,-17.9) [0|0] "m/s^2" XXX + +BO_ 1047 TractionCtrlStatus_CG1: 8 XXX + SG_ EngEotcCtlMde_B_Ind : 3|1@0+ (1,0) [0|0] "" XXX + SG_ YawStabilityIndex : 48|9@0+ (1,-256.0) [0|0] "%" XXX + SG_ TCS_ENG_FAILD : 0|1@0+ (1,0) [0|0] "" XXX + SG_ TCS_ENG_ONLY_PRESENT : 1|1@0+ (1,0) [0|0] "" XXX + SG_ TCS_BRK_FAILD : 2|1@0+ (1,0) [0|0] "" XXX + SG_ PrplWhlTqRqMn_No_Cnt : 47|4@0+ (1,0) [0|0] "" XXX + SG_ PrplWhlTot_Tq_RqMn : 23|16@0+ (4.0,-131072.0) [0|0] "Nm" XXX + SG_ EngEotcCtlLamp_D_Rq : 9|2@0+ (1,0) [0|0] "" XXX + SG_ PrplWhlTqRqMn_No_Cs : 39|8@0+ (1,0) [0|0] "" XXX + SG_ HdcMde_D_Actl : 12|3@0+ (1,0) [0|0] "" XXX + SG_ VehicleDir_D_Est : 5|2@0+ (1,0) [0|0] "" XXX + SG_ TracCtlPtActv_B_Actl : 6|1@0+ (1,0) [0|0] "" XXX + +BO_ 1056 PowertrainData_1_CG1: 8 XXX + SG_ FUEL_ALCOHOL_PERCNT : 63|8@0+ (0.3937008,0) [0|0] "%" XXX + SG_ TrnTotTq_Rt_Est : 39|16@0+ (0.001,0) [0|0] "" XXX + SG_ TrnTotLss_Tq_Est : 31|8@0+ (0.5,0) [0|0] "Nm" XXX + SG_ ECMMILRequest : 9|2@0+ (1,0) [0|0] "" XXX + SG_ AirCondFluidHi_P_Actl : 55|8@0+ (0.125,0) [0|0] "bar" XXX + SG_ OilPressureWarning : 18|1@0+ (1,0) [0|0] "" XXX + SG_ CluPdlPos_Pc_Meas : 7|10@0+ (0.1,0) [0|0] "%" XXX + SG_ VehVLimStat_D_Actl : 12|3@0+ (1,0) [0|0] "" XXX + SG_ VehVLimActv_B_Actl : 13|1@0+ (1,0) [0|0] "" XXX + SG_ CluPdlPosPcMeas_D_Qf : 17|2@0+ (1,0) [0|0] "" XXX + SG_ CoolantFanStepAct : 23|5@0+ (1,0) [0|0] "Steps" XXX + +BO_ 1058 PowertrainData_2_CG1: 8 XXX + SG_ EngIdlShutDown_D_Stat : 19|2@0+ (1,0) [0|0] "" XXX + SG_ EngAout2_Tq_Actl : 55|11@0+ (1,-500.0) [0|0] "Nm" XXX + SG_ EngMsgTxt_D_Rq : 21|2@0+ (1,0) [0|0] "" XXX + SG_ EngClnt_Te_ActlDiag : 39|8@0+ (1,-40.0) [0|0] "degC" XXX + SG_ ThrPos_Pc_CalcDiag : 7|8@0+ (0.392157,0) [0|0] "%" XXX + SG_ EngLoad_Pc_CalcDiag : 47|8@0+ (0.392157,0) [0|0] "%" XXX + SG_ EngAirIn_Te_Actl : 15|10@0+ (0.25,-128.0) [0|0] "degC" XXX + SG_ ApedPos_Pc_ActlDiag : 31|8@0+ (0.392157,0) [0|0] "%" XXX + +BO_ 1064 StrgWheel_PolicePkg: 8 XXX + SG_ PoliceAux4Lamp_B_Rq : 4|1@0+ (1,0) [0|0] "" XXX + SG_ PoliceAux3Lamp_B_Rq : 5|1@0+ (1,0) [0|0] "" XXX + SG_ PoliceAux2Lamp_B_Rq : 6|1@0+ (1,0) [0|0] "" XXX + SG_ PoliceAux1Lamp_B_Rq : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 1067 Battery_Mgmt_1: 8 XXX + SG_ AlternatorExcDutyCycle : 31|5@0+ (3.22581,0) [0|0] "%" XXX + SG_ EngineEffStatus : 39|2@0+ (1,0) [0|0] "" XXX + SG_ AvailableCurrentAtIdle : 23|8@0+ (1,0) [0|0] "Amps" XXX + SG_ AvailableCurrent : 15|8@0+ (1,0) [0|0] "Amps" XXX + SG_ ActualCurrent : 7|8@0+ (1,0) [0|0] "Amps" XXX + SG_ NoAlternatorResponse : 26|1@0+ (1,0) [0|0] "" XXX + SG_ AlternatorTempFault : 25|1@0+ (1,0) [0|0] "" XXX + SG_ AlternatorMechFault : 24|1@0+ (1,0) [0|0] "" XXX + SG_ AlternatorElFault : 37|1@0+ (1,0) [0|0] "" XXX + +BO_ 1068 Battery_Mgmt_2: 8 XXX + SG_ ChargeMode : 39|3@0+ (1,0) [0|0] "" XXX + SG_ ChargeVoltageReq : 7|6@0+ (0.1,10.6) [0|0] "Volts" XXX + SG_ ChargeVoltageReqMax : 23|6@0+ (0.1,10.6) [0|0] "Volts" XXX + SG_ FrontBatteryTemp : 47|8@0+ (1,-60.0) [0|0] "DegC" XXX + SG_ IBoost_Msg : 52|4@0+ (1,0) [0|0] "" XXX + SG_ IdleSpeedIncrease_El : 8|1@0+ (1,0) [0|0] "" XXX + SG_ MaxLashStep : 11|3@0+ (0.1,0) [0|0] "Volts" XXX + SG_ PowerSystemStatus : 15|4@0+ (1,0) [0|0] "" XXX + SG_ Shed_T_Eng_Off_B : 17|1@0+ (1,0) [0|0] "" XXX + SG_ Shed_Level_Req : 55|3@0+ (1,0) [0|0] "" XXX + SG_ Shed_Feature_Group_ID : 36|5@0+ (1,0) [0|0] "" XXX + SG_ Shed_Drain_Eng_Off_B : 16|1@0+ (1,0) [0|0] "" XXX + SG_ Batt_Lo_SoC_B : 25|1@0+ (1,0) [0|0] "" XXX + SG_ VoltageRampRateUpMax : 31|6@0+ (0.1,0) [0|0] "Volts/sec" XXX + SG_ Batt_Crit_SoC_B : 24|1@0+ (1,0) [0|0] "" XXX + +BO_ 1069 Battery_Mgmt_3: 8 XXX + SG_ BSFault : 23|1@0+ (1,0) [0|0] "" XXX + SG_ BSBattSOC : 30|7@0+ (1,0) [0|0] "%" XXX + SG_ BSBattQDeltaRideAh : 38|15@0+ (0.0078125,-100.0) [0|0] "Ah" XXX + SG_ BSBattQCapAh : 22|7@0+ (1,0) [0|0] "Ah" XXX + SG_ BSBattCurrent : 5|14@0+ (0.0625,-512.0) [0|0] "Amps" XXX + SG_ BattULoState_D_Qlty : 7|2@0+ (1,0) [0|0] "" XXX + +BO_ 1072 Cluster_Information: 8 XXX + SG_ ManRgen_D_Rq : 5|2@0+ (1,0) [0|0] "" XXX + SG_ Easy_Entry_Exit_Cmd : 49|1@0+ (1,0) [0|0] "" XXX + SG_ KeyTypeChngMykey_D_Rq : 53|2@0+ (1,0) [0|0] "" XXX + SG_ DrvSlipCtlMde_B_Rq : 19|1@0+ (1,0) [0|0] "" XXX + SG_ MetricActv_B_Actl : 6|1@0+ (1,0) [0|0] "" XXX + SG_ LdwDfaltOn_B_Actl : 0|1@0+ (1,0) [0|0] "" XXX + SG_ Fda_B_Stat : 9|1@0+ (1,0) [0|0] "" XXX + SG_ ePRNDL_MODE : 8|1@0+ (1,0) [0|0] "" XXX + SG_ AccDeny_B_RqIpc : 7|1@0+ (1,0) [0|0] "" XXX + SG_ MetricActvTe_B_Actl : 23|1@0+ (1,0) [0|0] "" XXX + SG_ EngOilLife_B_RqReset : 18|1@0+ (1,0) [0|0] "" XXX + SG_ OdometerMasterValue : 31|24@0+ (1,0) [0|0] "km" XXX + SG_ New_Module_Attn_Event : 56|1@0+ (1,0) [0|0] "" XXX + SG_ TRAILER_SWAY_CONFIG_CMD : 60|1@0+ (1,0) [0|0] "" XXX + SG_ ParkDetect_Stat : 62|1@0+ (1,0) [0|0] "" XXX + SG_ Attn_Info_Audio : 59|3@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrkMde_D_Rq : 61|1@0+ (1,0) [0|0] "" XXX + SG_ TRAILER_BRAKE_CONFIG : 48|1@0+ (1,0) [0|0] "" XXX + SG_ VehMykey_Vl_LimRq : 63|1@0+ (1,0) [0|0] "" XXX + SG_ VehMykey_V_LimRqMx : 51|1@0+ (1,0) [0|0] "" XXX + SG_ EmgcyCallAsstMykey_Rq : 50|1@0+ (1,0) [0|0] "" XXX + SG_ DrvSlipCtlMde_D_Rq : 17|2@0+ (1,0) [0|0] "" XXX + SG_ AccEnbl_B_RqDrv : 20|1@0+ (1,0) [0|0] "" XXX + SG_ AutoHighBeam_Cmd : 55|2@0+ (1,0) [0|0] "" XXX + +BO_ 1075 Cluster_Information_3_CG1: 8 XXX + SG_ CamraFrntStat_D_Rq : 58|1@0+ (1,0) [0|0] "" XXX + SG_ DieslFuelBio_B_ActlDrv : 56|1@0+ (1,0) [0|0] "" XXX + SG_ RearCameraDelayCmd : 59|1@0+ (1,0) [0|0] "" XXX + SG_ UreaWarnReset : 60|1@0+ (1,0) [0|0] "" XXX + SG_ DistanceBarSetting : 49|1@0+ (1,0) [0|0] "" XXX + SG_ CamraZoomMan_D_Rq : 63|3@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlStat_D_Rq : 48|1@0+ (1,0) [0|0] "" XXX + SG_ CamraOvrlDyn_D_Rq : 25|1@0+ (1,0) [0|0] "" XXX + SG_ CamAutoTowbarZoom : 24|1@0+ (1,0) [0|0] "" XXX + SG_ FuelSecndActv_B_Actl : 39|1@0+ (1,0) [0|0] "" XXX + SG_ HILL_DESC_SW : 38|1@0+ (1,0) [0|0] "" XXX + SG_ FuelLvlPssvSide_No_Raw : 19|10@0+ (1,0) [0|0] "" XXX + SG_ SPDJBCompassCMDDecalibrate : 50|1@0+ (1,0) [0|0] "" XXX + SG_ SPDJBCompassCMDChangeZone : 51|1@0+ (1,0) [0|0] "" XXX + SG_ SPDJBCompassCmdDesiredZone : 55|4@0+ (1,0) [0|0] "" XXX + SG_ FUEL_SENSOR_NUM : 35|1@0+ (1,0) [0|0] "" XXX + SG_ W2S_LAMP_OK : 37|1@0+ (1,0) [0|0] "" XXX + SG_ Beltminder_Warn_Stats_IPC : 32|1@0+ (1,0) [0|0] "" XXX + SG_ FuelLvlActvSide_No_Raw : 13|10@0+ (1,0) [0|0] "" XXX + SG_ FuelLvl_Pc_Dsply : 7|10@0+ (0.108696,-5.22) [0|0] "%" XXX + SG_ FUEL_LVL_PER_MEAN : 47|8@0+ (0.434783,-5.22) [0|0] "% Indication" XXX + SG_ Fuel_Level_State : 34|2@0+ (1,0) [0|0] "" XXX + SG_ H2O_IN_FUEL_LAMP_OK_OBD : 36|1@0+ (1,0) [0|0] "" XXX + +BO_ 1093 TrailerBrakeInfo: 8 XXX + SG_ TrlrLampCnnct_B_Actl : 22|1@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrkActCnnct_B_Actl : 16|1@0+ (1,0) [0|0] "" XXX + SG_ StopLamp_B_RqTrlrBrk : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrkOut_No_Dsply : 3|4@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrkGain_No_Actl : 21|5@0+ (0.5,0) [0|0] "" XXX + SG_ TrlrBrkDsply_B_Rq : 6|1@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrkDcnnt_B_Actl : 5|1@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrkCtl_B_Falt : 4|1@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrkActCirct_B_Falt : 39|1@0+ (1,0) [0|0] "" XXX + SG_ TrlrBrkMde_D_Actl : 23|1@0+ (1,0) [0|0] "" XXX + +BO_ 1104 SHCM_Status: 8 XXX + SG_ CURRENT_DRAW : 15|8@0+ (0.5,0) [0|0] "Amps" XXX + SG_ SECONDARY_HEATER_STAT : 7|1@0+ (1,0) [0|0] "" XXX + +BO_ 1107 PassengerOCSSerialNum: 8 XXX + SG_ OCSSerialNoByte8 : 63|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSerialNoByte7 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSerialNoByte6 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSerialNoByte5 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSerialNoByte4 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSerialNoByte3 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSerialNoByte2 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ OCSSerialNoByte1 : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 1108 RCMSerialNumber: 8 XXX + SG_ RCMSerialNoByte8 : 63|8@0+ (1,0) [0|0] "" XXX + SG_ RCMSerialNoByte7 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ RCMSerialNoByte6 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ RCMSerialNoByte5 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ RCMSerialNoByte4 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ RCMSerialNoByte3 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ RCMSerialNoByte2 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ RCMSerialNoByte1 : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 1109 eCall_Info: 8 XXX + SG_ eCallConfirmation : 7|3@0+ (1,0) [0|0] "" XXX + +BO_ 1125 GPS_Data_Nav_1_HS: 8 XXX + SG_ GpsHsphLattSth_D_Actl : 25|2@0+ (1,0) [0|0] "" XXX + SG_ GpsHsphLongEast_D_Actl : 9|2@0+ (1,0) [0|0] "" XXX + SG_ GPS_Longitude_Minutes : 46|6@0+ (1,0) [0|0] "Minutes" XXX + SG_ GPS_Longitude_Min_dec : 55|14@0+ (0.0001,0) [0|0] "Minutes" XXX + SG_ GPS_Longitude_Degrees : 39|9@0+ (1,-179.0) [0|0] "Degrees" XXX + SG_ GPS_Latitude_Minutes : 15|6@0+ (1,0) [0|0] "Minutes" XXX + SG_ GPS_Latitude_Min_dec : 23|14@0+ (0.0001,0) [0|0] "Minutes" XXX + SG_ GPS_Latitude_Degrees : 7|8@0+ (1,-89.0) [0|0] "Degrees" XXX + +BO_ 1126 GPS_Data_Nav_2_HS: 8 XXX + SG_ Gps_B_Falt : 2|1@0+ (1,0) [0|0] "" XXX + SG_ GpsUtcYr_No_Actl : 55|5@0+ (1,1.0) [0|0] "Year" XXX + SG_ GpsUtcMnth_No_Actl : 47|4@0+ (1,1.0) [0|0] "Month" XXX + SG_ GpsUtcDay_No_Actl : 37|5@0+ (1,1.0) [0|0] "Day" XXX + SG_ GPS_UTC_seconds : 23|6@0+ (1,0) [0|0] "seconds" XXX + SG_ GPS_UTC_minutes : 15|6@0+ (1,0) [0|0] "Minutes" XXX + SG_ GPS_UTC_hours : 7|5@0+ (1,0) [0|0] "Hours" XXX + SG_ GPS_Pdop : 31|5@0+ (0.2,0) [0|0] "" XXX + SG_ GPS_Compass_direction : 26|4@0+ (1,0) [0|0] "" XXX + SG_ GPS_Actual_vs_Infer_pos : 38|1@0+ (1,0) [0|0] "" XXX + +BO_ 1127 GPS_Data_Nav_3_HS: 8 XXX + SG_ GPS_Vdop : 63|5@0+ (0.2,0) [0|0] "" XXX + SG_ GPS_Speed : 47|8@0+ (1,0) [0|0] "MPH" XXX + SG_ GPS_Sat_num_in_view : 7|5@0+ (1,0) [0|0] "" XXX + SG_ GPS_MSL_altitude : 15|12@0+ (10.0,-20460.0) [0|0] "feet" XXX + SG_ GPS_Heading : 31|16@0+ (0.01,0) [0|0] "Degrees" XXX + SG_ GPS_Hdop : 55|5@0+ (0.2,0) [0|0] "" XXX + SG_ GPS_dimension : 2|3@0+ (1,0) [0|0] "" XXX + +BO_ 1152 All_Terrain_Data: 8 XXX + SG_ HdcSwitchPos_B_Actl : 0|1@0+ (1,0) [0|0] "" XXX + SG_ TerrStat_D_RqDsply : 7|4@0+ (1,0) [0|0] "" XXX + SG_ TerrMde_D_RqDrv : 3|3@0+ (1,0) [0|0] "" XXX + +BO_ 1186 Information_4x4_2_CG1: 8 XXX + SG_ RearDiffFalt_D_Stat : 23|2@0+ (1,0) [0|0] "" XXX + SG_ RearDiffLck_Tq_Actl : 7|12@0+ (1,0) [0|0] "Nm" XXX + SG_ RearDiffLckMsg_D_Rq : 20|3@0+ (1,0) [0|0] "" XXX + SG_ AwdSrvcRqd_B_Rq : 21|1@0+ (1,0) [0|0] "" XXX + SG_ RearDiffLckLamp_D_Rq : 11|2@0+ (1,0) [0|0] "" XXX diff --git a/opendbc/ford_fusion_2018_adas.dbc b/opendbc_repo/opendbc/dbc/ford_fusion_2018_adas.dbc similarity index 100% rename from opendbc/ford_fusion_2018_adas.dbc rename to opendbc_repo/opendbc/dbc/ford_fusion_2018_adas.dbc diff --git a/opendbc_repo/opendbc/dbc/ford_fusion_2018_pt.dbc b/opendbc_repo/opendbc/dbc/ford_fusion_2018_pt.dbc new file mode 100644 index 000000000000000..c4b706d0647039e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/ford_fusion_2018_pt.dbc @@ -0,0 +1,139 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + +BO_ 130 EPAS_INFO: 8 XXX + SG_ SteMdule_U_Meas : 39|8@0+ (0.05,6.0) [0|0] "Volts" XXX + SG_ SteMdule_I_Est : 21|12@0+ (0.05,-64.0) [0|0] "Amps" XXX + SG_ EPAS_FAILURE : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SteeringColumnTorque : 7|8@0+ (0.0625,-8.0) [0|0] "Nm" XXX + SG_ SAPPAngleControlStat6 : 15|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat5 : 14|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat4 : 13|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat3 : 12|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat2 : 11|1@0+ (1,0) [0|0] "" XXX + SG_ SAPPAngleControlStat1 : 23|2@0+ (1,0) [0|0] "" XXX + +BO_ 118 Steering_Wheel_Data_CG1: 8 XXX + SG_ SteWhlRelInit_An_Sns : 6|15@0+ (0.1,-1600.0) [0|0] "deg" XXX + SG_ SteWhlRelCalib_An_Sns : 23|15@0+ (0.1,-1600.0) [0|0] "deg" XXX + SG_ SteWhlRelInit2_An_Sns : 55|16@0+ (0.1,-3200.0) [0|0] "deg" XXX + SG_ SteWhlAn_No_Cs : 39|8@0+ (1,0) [0|0] "" XXX + SG_ SteWhlAn_No_Cnt : 47|4@0+ (1,0) [0|0] "Counts" XXX + +BO_ 131 Steering_Buttons: 8 XXX + SG_ Right_Turn_Light : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Left_Turn_Light : 4|1@0+ (1,0) [0|0] "" XXX + SG_ Dist_Decr : 12|1@0+ (1,0) [0|0] "" XXX + SG_ Dist_Incr : 11|1@0+ (1,0) [0|0] "" XXX + SG_ Cancel : 8|1@0+ (1,0) [0|0] "" XXX + SG_ Resume : 29|1@0+ (1,0) [0|0] "" XXX + SG_ Set : 28|1@0+ (1,0) [0|0] "" XXX + SG_ Main : 38|1@0+ (1,0) [0|0] "" XXX + +BO_ 145 Yaw_Data: 8 XXX + SG_ VehYaw_W_Actl : 39|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + SG_ VehRol_W_Actl : 23|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + SG_ VehPtch_W_Actl : 7|16@0+ (0.0002,-6.5) [0|0] "rad/s" XXX + +BO_ 146 Accel_Data: 8 XXX + SG_ VehVertAActl_D_Qf : 38|2@0+ (1,0) [0|0] "" XXX + SG_ VehLongAActl_D_Qf : 22|2@0+ (1,0) [0|0] "" XXX + SG_ VehLatAActl_D_Qf : 6|2@0+ (1,0) [0|0] "" XXX + SG_ VehVert_A_Actl : 36|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + SG_ VehLong_A_Actl : 20|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + SG_ VehLat_A_Actl : 4|13@0+ (0.01,-40.0) [0|0] "m/s^2" XXX + +BO_ 357 Cruise_Status: 8 XXX + SG_ Brake_Drv_Appl : 5|1@0+ (1,0) [0|0] "" XXX + SG_ Cruise_State : 11|4@0+ (1,0) [0|0] "" XXX + SG_ Set_Speed : 23|8@0+ (1,0) [0|0] "" XXX + +BO_ 516 EngineData_14: 8 XXX + SG_ ApedPosScal_Pc_Actl : 1|10@0+ (0.1,0) [0|0] "%" XXX + +BO_ 535 WheelSpeed_CG1: 8 XXX + SG_ WhlRr_W_Meas : 55|14@0+ (0.04,0) [0|0] "rad/s" XXX + SG_ WhlRl_W_Meas : 39|14@0+ (0.04,0) [0|0] "rad/s" XXX + SG_ WhlFr_W_Meas : 23|14@0+ (0.04,0) [0|0] "rad/s" XXX + SG_ WhlFl_W_Meas : 7|14@0+ (0.04,0) [0|0] "rad/s" XXX + +BO_ 534 WheelData: 8 XXX + SG_ WhlRotatRr_No_Cnt : 23|8@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRr_D_Actl : 33|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirRl_D_Actl : 39|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFr_D_Actl : 37|2@0+ (1,0) [0|0] "" XXX + SG_ WhlDirFl_D_Actl : 35|2@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatRl_No_Cnt : 31|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFr_No_Cnt : 7|8@0+ (1,0) [0|0] "" XXX + SG_ WhlRotatFl_No_Cnt : 15|8@0+ (1,0) [0|0] "" XXX + SG_ WHEEL_ROLLING_TIMESTAMP : 47|8@0+ (1,0) [0|0] "" XXX + +BO_ 947 Doors: 8 XXX + SG_ Door_FL_Open : 61|1@0+ (1,0) [0|0] "" XXX + SG_ Door_FR_Open : 60|1@0+ (1,0) [0|0] "" XXX + SG_ Door_RL_Open : 48|1@0+ (1,0) [0|0] "" XXX + SG_ Door_RR_Open : 49|1@0+ (1,0) [0|0] "" XXX + +BO_ 963 BCM_to_HS_Body: 8 XXX + SG_ Brake_Lights : 8|1@0+ (1,0) [0|0] "" XXX + +BO_ 970 Lane_Keep_Assist_Control: 8 XXX + SG_ Lkas_Action : 7|4@0+ (1,0) [0|15] "" XXX + SG_ Lkas_Alert : 3|4@0+ (1,0) [0|15] "" XXX + SG_ Lane_Curvature : 15|12@0+ (5e-06,-0.01) [0|0] "1/m" XXX + SG_ Steer_Angle_Req : 19|12@0+ (0.04297,-88.00445) [0|0] "deg" XXX + +BO_ 972 Lane_Keep_Assist_Status: 8 XXX + SG_ LaHandsOff_B_Actl : 7|1@0+ (1,0) [0|0] "" XXX + SG_ LaActDeny_B_Actl : 6|1@0+ (1,0) [0|0] "" XXX + SG_ LaActAvail_D_Actl : 5|2@0+ (1,0) [0|0] "" XXX + +BO_ 984 Lane_Keep_Assist_Ui: 8 XXX + SG_ Set_Me_X80 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ Set_Me_X45 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ Lines_Hud : 55|4@0+ (1,0) [0|15] "" XXX + SG_ Hands_Warning_W_Chime : 50|1@0+ (1,0) [0|1] "" XXX + SG_ Hands_Warning : 49|1@0+ (1,0) [0|1] "" XXX + SG_ Set_Me_X30 : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 970 Lkas_Action "only vals 4, 5, 8, 9 seem to work. 4 and 5 are a bit smoother" ; + +VAL_ 357 Cruise_State 4 "active" 3 "standby" 0 "off" ; +VAL_ 970 Lkas_Action 15 "off" 9 "abrupt" 8 "abrupt2" 5 "smooth" 4 "smooth2" ; +VAL_ 970 Lkas_Alert 15 "no_alert" 3 "high_intensity" 2 "mid_intensity" 1 "low_intensity" ; +VAL_ 972 LaActAvail_D_Actl 3 "available" 2 "tbd" 1 "not_available" 0 "fault" ; +VAL_ 984 Lines_Hud 15 "none" 11 "grey_yellow" 8 "green_red" 7 "yellow_grey" 6 "grey_grey" 4 "red_green" 3 "green_green" ; diff --git a/opendbc/ford_lincoln_base_pt.dbc b/opendbc_repo/opendbc/dbc/ford_lincoln_base_pt.dbc similarity index 100% rename from opendbc/ford_lincoln_base_pt.dbc rename to opendbc_repo/opendbc/dbc/ford_lincoln_base_pt.dbc diff --git a/opendbc_repo/opendbc/dbc/generator/chrysler/.gitignore b/opendbc_repo/opendbc/dbc/generator/chrysler/.gitignore new file mode 100644 index 000000000000000..46fc4e0d88c4b6f --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/chrysler/.gitignore @@ -0,0 +1 @@ +_*generated.dbc diff --git a/opendbc_repo/opendbc/dbc/generator/chrysler/_stellantis_common.dbc b/opendbc_repo/opendbc/dbc/generator/chrysler/_stellantis_common.dbc new file mode 100644 index 000000000000000..df913561de2fad0 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/chrysler/_stellantis_common.dbc @@ -0,0 +1,185 @@ +BO_ 258 STEERING: 8 XXX + SG_ STEERING_ANGLE : 5|14@0+ (0.5,-2048) [-2048|2047] "deg" XXX + SG_ STEERING_RATE : 21|14@0+ (0.5,-2048) [-2048|2047] "deg/s" XXX + SG_ STEERING_ANGLE_HP : 48|4@1+ (0.1,-0.4) [-0.4|0.4] "deg" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 264 ECM_1: 8 XXX + SG_ ENGINE_RPM : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ ENGINE_TORQUE : 20|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ EXPECTED_ENGINE_TORQUE : 36|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 280 ECM_TRQ: 8 XXX + SG_ ENGINE_TORQ_MAX : 4|13@0+ (.25,-500) [-500|1547.5] "NM" XXX + SG_ ENGINE_TORQ_MIN : 20|13@0+ (.25,-500) [-500|1547.5] "NM" 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 + SG_ WHEEL_SPEED_RL : 37|14@0+ (0.5,0) [0|8191] "rpm" XXX + SG_ WHEEL_SPEED_RR : 53|14@0+ (0.5,0) [0|8191] "rpm" XXX + +BO_ 368 Transmission_Status: 8 XXX + SG_ Gear_State : 2|3@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 464 ORC_1: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 13|1@0+ (1,0) [0|1] "" XXX + +BO_ 500 DAS_3: 8 XXX + SG_ ENGINE_TORQUE_REQUEST : 4|13@0+ (0.25,-500) [-500|1547.5] "Nm" XXX + SG_ ENGINE_TORQUE_REQUEST_MAX : 7|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_STANDSTILL : 5|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_GO : 6|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_DECEL : 19|12@0+ (0.004885,-16) [-16|4] "m/s2" XXX + SG_ ACC_AVAILABLE : 20|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ACTIVE : 21|1@0+ (1,0) [0|1] "" 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_ 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_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 501 DAS_4: 8 XXX + SG_ ACC_SET_SPEED_KPH : 15|8@0+ (1,0) [0|3] "km/h" XXX + SG_ ACC_SET_SPEED_MPH : 23|8@0+ (1,0) [0|3] "mph" XXX + SG_ ACC_DISTANCE_CONFIG_1 : 1|2@0+ (1,0) [0|3] "" 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 + SG_ COLUMN_TORQUE : 2|11@0+ (1,-1024) [-1024|1023] "" XXX + SG_ TORQUE_OVERLAY_STATUS : 6|4@0+ (1,0) [0|15] "" XXX + SG_ EPS_TORQUE_MOTOR_RAW : 19|12@0+ (1,-2048) [-2048|2047] "" XXX + SG_ EPS_TORQUE_MOTOR : 34|11@0+ (1,-1024) [-1024|1023] "" XXX + SG_ LKAS_TEMPORARY_FAULT : 38|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_HAS_CONTROL_2 : 51|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 559 ECM_5: 8 XXX + SG_ Accelerator_Position : 0|8@1+ (0.4,0) [0|100] "%" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 571 CRUISE_BUTTONS: 3 XXX + SG_ ACC_Cancel : 0|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_Distance_Dec : 1|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_Accel : 2|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_Decel : 3|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_Resume : 4|1@0+ (1,0) [0|1] "" XXX + SG_ Cruise_OnOff : 6|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_OnOff : 7|1@1+ (1,0) [0|0] "" XXX + SG_ ACC_Distance_Inc : 8|1@1+ (1,0) [0|0] "" 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 + SG_ LEFT_STATUS : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 792 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 0|2@1+ (1,0) [0|3] "" XXX + SG_ HIGH_BEAM_PRESSED : 2|1@0+ (1,0) [0|3] "" XXX + +BO_ 820 BCM_1: 8 XXX + SG_ DOOR_OPEN_FL : 17|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 18|1@0+ (1,0) [0|1] "" 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"; +CM_ SG_ 264 EXPECTED_ENGINE_TORQUE "Expected Engine Torque based on target engine speed"; +CM_ SG_ 678 LKAS_ICON_COLOR "3 is yellow, 2 is green, 1 is white, 0 is null"; +CM_ SG_ 678 LKAS_LANE_LINES "0x01 transparent lines, 0x02 left white, 0x03 right white, 0x04 left yellow with car on top, 0x05 left yellow with car on top, 0x06 both white, 0x07 left yellow, 0x08 left yellow right white, 0x09 right yellow, 0x0a right yellow left white, 0x0b left yellow with car on top right white, 0x0c right yellow with car on top left white, (0x00, 0x0d, 0x0e, 0x0f) null"; +CM_ SG_ 678 LKAS_ALERTS "(0x01, 0x02) lane sense off, (0x03, 0x04, 0x06) place hands on steering wheel, 0x07 lane departure detected + place hands on steering wheel, (0x08, 0x09) lane sense unavailable + clean front windshield, 0x0b lane sense and auto high beam unavailable + clean front windshield, 0x0c lane sense unavailable + service required, (0x00, 0x05, 0x0a, 0x0d, 0x0e, 0x0f) null"; diff --git a/opendbc_repo/opendbc/dbc/generator/chrysler/_stellantis_common_ram.py b/opendbc_repo/opendbc/dbc/generator/chrysler/_stellantis_common_ram.py new file mode 100755 index 000000000000000..fa408f1315f34fe --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/chrysler/_stellantis_common_ram.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python3 +import os + +chrysler_to_ram = { + "_stellantis_common_ram_dt_generated.dbc": { + 258: 35, + 264: 37, + 268: 113, + 280: 181, + 284: 121, + 288: 123, + 320: 131, + 344: 139, + 368: 147, + 464: 464, + 500: 153, + 501: 232, + 544: 49, + 571: 177, + 559: 157, + 625: 163, + 669: 213, + 678: 250, + 720: 720, + 792: 792, + 820: 657, + }, + "_stellantis_common_ram_hd_generated.dbc": { + 571: 570, + 678: 629, + }, +} + +if __name__ == "__main__": + src = '_stellantis_common.dbc' + chrysler_path = os.path.dirname(os.path.realpath(__file__)) + + for out, addr_lookup in chrysler_to_ram.items(): + with open(os.path.join(chrysler_path, src), encoding='utf-8') as in_f, open(os.path.join(chrysler_path, out), 'w', encoding='utf-8') as out_f: + out_f.write(f'CM_ "Generated from {src}"\n\n') + + wrote_addrs = set() + for line in in_f.readlines(): + if line.startswith(('BO_', 'VAL_')): + sl = line.split(' ') + addr = int(sl[1]) + wrote_addrs.add(addr) + + sl[1] = str(addr_lookup.get(addr, addr)) + line = ' '.join(sl) + out_f.write(line) + + missing_addrs = set(addr_lookup.keys()) - wrote_addrs + assert len(missing_addrs) == 0, f"Missing addrs from {src}: {missing_addrs}" diff --git a/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_pacifica_2017_hybrid.dbc b/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_pacifica_2017_hybrid.dbc new file mode 100644 index 000000000000000..3f4b373843d1b82 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_pacifica_2017_hybrid.dbc @@ -0,0 +1,172 @@ +CM_ "IMPORT _stellantis_common.dbc"; + +BO_ 514 SPEED_1: 8 XXX + SG_ SPEED_LEFT : 7|12@0+ (0.071028,0) [0|65535] "m/s" XXX + SG_ SPEED_RIGHT : 23|12@0+ (0.071028,0) [0|1023] "m/s" XXX + +BO_ 653 BRAKE_MODULE: 2 XXX + SG_ BRAKE_PRESSURE : 15|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|4] "" XXX + +BO_ 746 GEAR: 5 XXX + SG_ PRNDL : 2|3@0+ (1,0) [0|7] "" XXX + SG_ GEAR_CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 31|4@0+ (1,0) [0|15] "" XXX + +BO_ 736 TRIP: 8 XXX + SG_ COUNTER : 7|16@0+ (1,0) [0|65535] "Meters" XXX + SG_ COUNTER_2 : 23|16@0+ (1,0) [0|65535] "Meters" XXX + +BO_ 658 LKAS_COMMAND: 6 XXX + SG_ COUNTER : 39|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 47|8@0+ (1,0) [0|255] "" XXX + SG_ STEERING_TORQUE : 2|11@0+ (1,-1024) [0|1] "" XXX + SG_ LKAS_CONTROL_BIT : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 AUTO_PARK_BUTTON: 8 XXX + SG_ AUTO_PARK_TOGGLE_2 : 8|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_TOGGLE_1 : 11|1@0+ (1,0) [0|1] "" XXX + SG_ INCREASING_UNKNOWN : 38|7@0+ (1,0) [0|15] "" XXX + +BO_ 719 AUTO_PARK_SIGNALS_1: 8 XXX + SG_ AUTO_PARK_UNKNOWN_1 : 7|16@0+ (1,0) [0|31] "" XXX + +BO_ 671 AUTO_PARK_REQUEST: 8 XXX + SG_ AUTO_PARK_CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_STATUS : 7|5@0+ (1,0) [0|15] "" XXX + SG_ AUTO_PARK_COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ AUTO_PARK_MODE : 22|2@0+ (1,0) [0|3] "" XXX + SG_ AUTO_PARK_CMD : 2|11@0+ (1,-1024) [0|1] "NM" XXX + +BO_ 784 AUTO_PARK_LESS_INTERESTING: 8 XXX + SG_ INCREASING_UNKNOWN : 55|8@0+ (1,0) [0|7] "" XXX + SG_ AUTO_PARK_PERPENDICULAR_2 : 61|1@0+ (1,0) [0|255] "" XXX + +BO_ 826 AUTO_PARK_SIGNALS_3: 8 XXX + SG_ AUTO_PARK_HAS_CONTROL_3 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HUMAN_HAS_CONTROL : 2|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_PARK_GEAR_1 : 27|4@0+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_GEAR_2 : 35|4@0+ (1,0) [0|15] "" XXX + SG_ AUTO_PARK_GEAR_3 : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 332 STEERING_2: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ ENERGY_RELATED : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ STEER_ANGLE_2 : 7|13@0+ (0.3187251,-1307.888) [-360|360] "deg" XXX + +BO_ 331 BRAKE_3: 8 XXX + SG_ BRAKE_RELATED_3 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 608 PARKSENSE_SIGNAL: 8 XXX + SG_ PARKSENSE_DISABLED : 34|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ IN_REVERSE : 10|1@0+ (1,0) [0|255] "" XXX + SG_ AUTO_PARK_HAS_CONTROL_1 : 16|1@0+ (1,0) [0|255] "" XXX + SG_ HUMAN_HAS_CONTROL : 17|1@0+ (1,0) [0|3] "" XXX + +BO_ 729 LKAS_HEARTBIT: 5 XXX + SG_ LKAS_STATUS_OK : 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 + +BO_ 825 AUDIBLE_BEEP_339: 2 XXX + SG_ BEEP_339 : 7|16@0+ (1,0) [0|65535] "" XXX + +BO_ 168 ACCEL_RELATED_a8: 8 XXX + SG_ ACCEL_RELATED : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 270 ACCEL_RELATED_10e: 8 XXX + SG_ ACCEL_OR_RPM : 7|16@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ELECTRIC_MOTOR : 23|16@0+ (1,0) [0|65535] "" XXX + +BO_ 291 ENERGY_RELATED_123: 8 XXX + SG_ ENERGY_GAIN_LOSS : 18|11@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ENERGY_SMOOTHER_CURVE : 35|12@0+ (1,0) [0|2047] "" XXX + +BO_ 294 ENERGY_RELATED_126: 8 XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_126_1 : 3|12@0+ (1,0) [0|4095] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ UNKNOWN_126_2 : 35|12@0+ (1,0) [0|4095] "" XXX + SG_ ENERGY_GAIN_LOSS_NOISY : 19|12@0+ (1,0) [0|2047] "" XXX + +BO_ 308 ACCEL_GAS_134: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ ACCEL_134 : 46|7@0+ (1,0) [0|127] "" XXX + +BO_ 532 ENERGY_RELATED_214: 8 XXX + SG_ NOISY_SLOWLY_DECREASING : 16|9@0+ (1,0) [0|255] "" XXX + SG_ ENERGY_RELATED : 0|9@0+ (1,0) [0|255] "" XXX + +BO_ 655 CHARGING_MAYBE_28F: 8 XXX + SG_ CHARGING : 1|2@0+ (1,0) [0|3] "" XXX + +BO_ 660 BRAKE_RELATED_294: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PERHAPS_294 : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 764 ACCEL_RELATED_2FC: 8 XXX + SG_ ACCEL_2FC : 13|6@0+ (1,0) [0|255] "" XXX + +BO_ 816 TRACTION_BUTTON: 8 XXX + SG_ TRACTION_OFF : 19|1@0+ (1,0) [0|3] "" XXX + SG_ TOGGLE_PARKSENSE : 52|1@0+ (1,0) [0|3] "" XXX + +BO_ 878 ACCEL_RELATED_36E: 8 XXX + SG_ ACCEL_OR_RPM_2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ACCEL_OR_RPM_1 : 7|8@0+ (1,0) [0|255] "" XXX + +BO_ 324 SPEED_2: 8 XXX + SG_ SPEED_2 : 31|16@0+ (0.01,0) [0|255] "m/s" XXX + +BO_ 832 UNKNOWN_340: 8 XXX + SG_ SPEED_DIGITAL : 63|8@0+ (1,0) [0|255] "mph" 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"; +CM_ SG_ 320 BRAKE_PRESSED_ACC "set when ACC brakes"; +CM_ SG_ 792 TURN_SIGNALS "1=Left, 2=Right"; +CM_ SG_ 264 ACCEL_PEDAL "not in ACC so seems to be actual pedal. Use for gasPressed"; +CM_ SG_ 544 LKAS_STATE "2 when autopark has control, 8 when is actuatable by lkas, 4 when there is a fault"; +CM_ SG_ 658 LKAS_STEERING_TORQUE "Most sent by stock system is 1024+-230. + is left. typically changes by 2 or 3 each 0.01s"; +CM_ SG_ 678 LKAS_ICON_COLOR "3 is yellow, 2 is green, 1 is white, 0 is null"; +CM_ SG_ 678 LKAS_LANE_LINES "0x01 transparent lines, 0x02 left white, 0x03 right white, 0x04 left yellow with car on top, 0x05 left yellow with car on top, 0x06 both white, 0x07 left yellow, 0x08 left yellow right white, 0x09 right yellow, 0x0a right yellow left white, 0x0b left yellow with car on top right white, 0x0c right yellow with car on top left white, (0x00, 0x0d, 0x0e, 0x0f) null"; +CM_ SG_ 678 LKAS_ALERTS "(0x01, 0x02) lane sense off, (0x03, 0x04, 0x06) place hands on steering wheel, 0x07 lane departure detected + place hands on steering wheel, (0x08, 0x09) lane sense unavailable + clean front windshield, 0x0b lane sense and auto high beam unavailable + clean front windshield, 0x0c lane sense unavailable + service required, (0x00, 0x05, 0x0a, 0x0d, 0x0e, 0x0f) null"; +CM_ SG_ 705 AUTO_PARK_TOGGLE_1 "set briefly when turning on or off self-parking"; +CM_ SG_ 671 AUTO_PARK_CMD "Request Appears to be in NM"; +CM_ SG_ 671 AUTO_PARK_STATUS "1 = IDLE / NO REQUEST 9 = START REQUEST 10 = REQUEST MODE 11 = REQUEST MODE"; +CM_ SG_ 826 AUTO_PARK_GEAR_1 "Reverse=0, Forward=f"; +CM_ SG_ 826 AUTO_PARK_GEAR_2 "Reverse=0, Forward=f"; +CM_ SG_ 826 AUTO_PARK_GEAR_3 "Reverse=0, Forward=f"; +CM_ SG_ 332 STEER_ANGLE_2 "slightly lags the other steer_angle signal. also more noisy."; +CM_ SG_ 608 PARKSENSE_DISABLED "set if parksense is disabled"; +CM_ SG_ 729 LKAS_STATUS_OK "Set to 0x0820 when LKAS system is plugged in."; +CM_ SG_ 825 BEEP_339 "sent every 0.5s. 0050 is no beep. To beep send 4355 or 4155. Used by ParkSense warning."; +CM_ SG_ 270 ELECTRIC_MOTOR "0x7fff indicates electric motor not in use"; +CM_ SG_ 291 ENERGY_GAIN_LOSS "unsure what this actually is"; +CM_ SG_ 291 ENERGY_SMOOTHER_CURVE "unsure what it is, but smoother"; +CM_ SG_ 308 ACCEL_134 "only set when human presses accel pedal"; +CM_ SG_ 532 NOISY_SLOWLY_DECREASING "perhaps battery but do not know"; +CM_ SG_ 816 TRACTION_OFF "set when traction off button is enabled"; +CM_ SG_ 816 TOGGLE_PARKSENSE "sending 3000071ec0ff9000 enables or disables parksense"; +CM_ SG_ 324 SPEED_2 "signal is approx half other speeds"; +CM_ SG_ 501 ACC_SPEED_CONFIG_KPH "speed configured for ACC"; +CM_ SG_ 501 ACC_SPEED_CONFIG_MPH "speed configured for ACC"; +CM_ SG_ 501 CRUISE_STATE "may just be an icon, but seems to indicate different cruise modes: ACC and Non-ACC and engaged state for both."; +CM_ SG_ 625 SPEED "zero on non-acc drives"; + +VAL_ 501 CRUISE_STATE 0 "Off" 1 "CC On" 2 "CC Engaged" 3 "ACC On" 4 "ACC Engaged"; +VAL_ 746 PRNDL 5 "L" 4 "D" 3 "N" 2 "R" 1 "P"; +VAL_ 792 TURN_SIGNALS 2 "Right" 1 "Left"; diff --git a/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_ram_dt.dbc b/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_ram_dt.dbc new file mode 100644 index 000000000000000..c9be635e1078066 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_ram_dt.dbc @@ -0,0 +1,57 @@ +CM_ "IMPORT _stellantis_common_ram_dt_generated.dbc"; + +BO_ 53 PCM_2: 8 XXX + SG_ ENG_TORQUE_REQ : 3|12@0+ (1,0) [0|7] "" XXX + SG_ ENG_TORQUE_OUT : 19|12@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + +BO_ 133 TCM_1: 8 XXX + SG_ SHIFT_PENDING : 2|1@0+ (1,0) [0|1] "" 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 + SG_ CHECKSUM : 63|8@0+ (1,0) [0|1] "" XXX + SG_ DRIVER_BRAKE : 15|8@0+ (1,0) [0|1] "" XXX + +BO_ 137 ESP_4: 8 XXX + SG_ Yaw_Rate : 7|16@0+ (0.01,-327.68) [-327.68|327.66] "deg/s" XXX + SG_ Acceleration : 32|8@1+ (0.08,-10.24) [-10.24|10.08] "m/s2" XXX + +BO_ 164 EPS_3: 8 XXX + SG_ DASM_FAULT : 34|1@0+ (1,0) [0|1] "" XXX + SG_ Activation_Status : 48|3@1+ (1,0) [0|1] "" XXX + SG_ Driver_Override : 35|1@0+ (1,0) [0|1] "" XXX + SG_ Hands_on_Wheel : 51|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 166 LKAS_COMMAND: 8 XXX + SG_ STEERING_TORQUE : 10|11@0+ (1,-1024) [0|1] "" XXX + SG_ LKAS_CONTROL_BIT : 24|3@1+ (1,0) [0|1] "" XXX + SG_ DASM_FAULT : 51|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 221 Center_Stack_1: 8 XXX + SG_ LKAS_Button : 53|1@1+ (1,0) [0|0] "" XXX + SG_ Traction_Button : 54|1@0+ (1,0) [0|1] "" XXX + +BO_ 650 Center_Stack_2: 8 XXX + SG_ LKAS_Button : 57|1@1+ (1,0) [0|0] "" XXX + + +CM_ SG_ 133 ACTUAL_GEAR "0xd = P, 0x1-8 = D (actual gear), 0xb = R or N?? TODO find R vs N"; +CM_ SG_ 153 ACC_Engaged "SENT BY FORWARD CAMERA 1 = ACTIVE, 3 = ENGAGED, 0 = DISENGAGED/OFF"; +CM_ SG_ 166 LKAS_CONTROL_BIT "0=IDLE, 1=HAS 2=LKAS 3=ABSD, 4=TJA, 7=SNA"; +CM_ SG_ 250 Auto_High_Beam "1 = HIGH BEAMS OK 0 = HIGH BEAMS OFF "; +CM_ SG_ 250 LKAS_LANE_LINES "9 = LEFT CAUTION, 11 = VERY LEFT CAUTION 10 = RIGHT CAUTION, 14 = VERY RIGHT, 4 = NO LINES DETECTED, 3 = LINES DETECTED, SYSTEM ACTIVE"; +CM_ SG_ 464 Driver_Seatbelt_Status "1 unbuckled 0 buckled"; +CM_ SG_ 792 High_Beam_Lever_Status "1 is high beam, 0 reg"; diff --git a/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_ram_hd.dbc b/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_ram_hd.dbc new file mode 100644 index 000000000000000..373c041667cf98f --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/chrysler/chrysler_ram_hd.dbc @@ -0,0 +1,17 @@ +CM_ "IMPORT _stellantis_common_ram_hd_generated.dbc"; + +BO_ 545 EPS_3: 8 XXX + SG_ DASM_FAULT : 34|1@0+ (1,0) [0|1] "" XXX + SG_ Activation_Status : 48|3@1+ (1,0) [0|1] "" XXX + SG_ Driver_Override : 35|1@0+ (1,0) [0|1] "" XXX + SG_ Hands_on_Wheel : 51|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 630 LKAS_COMMAND: 8 XXX + SG_ STEERING_TORQUE : 10|11@0+ (1,-1024) [0|1] "" XXX + SG_ LKAS_CONTROL_BIT : 24|3@1+ (1,0) [0|1] "" XXX + SG_ DASM_FAULT : 51|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + diff --git a/opendbc_repo/opendbc/dbc/generator/ford/FORD_CADS_64.sh b/opendbc_repo/opendbc/dbc/generator/ford/FORD_CADS_64.sh new file mode 100755 index 000000000000000..4732a854e55bf00 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/ford/FORD_CADS_64.sh @@ -0,0 +1,2845 @@ +#!/bin/bash + +OUT_FILENAME="../../FORD_CADS_64.dbc" + + +build_bo(){ +id=$1 +# bo=$(($id + 287)) +bo=$(expr $id + 287) + +len=64 +if [ "$id" = "22" ]; then + len=24 +fi + +cat <> ${OUT_FILENAME} +BO_ ${bo} MRR_Detection_0${id}: ${len} MRR +EOF + +build_bo_segment $id "01" +build_bo_segment $id "02" +build_bo_segment $id "03" +if [ "$id" != "22" ]; then + build_bo_segment $id "04" + build_bo_segment $id "05" + build_bo_segment $id "06" +fi +echo "" >> ${OUT_FILENAME} + +} + +build_bo_segment(){ + id=$1 + seg=$2 + base=$((($2 - 1)*72)) +cat <> ${OUT_FILENAME} + SG_ CAN_DET_CONFID_AZIMUTH_${id}_${seg} : $(expr $base + 33)|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_${id}_${seg} : $(expr $base + 56)|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_${id}_${seg} : $(expr $base + 48)|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_${id}_${seg} : $(expr $base + 49)|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_${id}_${seg} : $(expr $base + 0)|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_${id}_${seg} : $(expr $base + 47)|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_${id}_${seg} : $(expr $base + 31)|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_${id}_${seg} : $(expr $base + 15)|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_${id}_${seg} : $(expr $base + 7)|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_${id}_${seg} : $(expr $base + 17)|2@0+ (1,0) [0|3] "" IFV_VFP +EOF +} + + +build_ba(){ +id=$1 +# bo=$(($id + 287)) +ba=$(expr $id + 287) + +len=64 +if [ "$id" = "22" ]; then + len=24 +fi + +cat <> ${OUT_FILENAME} +BA_ "GenMsgSendType" BO_ ${ba} 1; +BA_ "GenMsgILSupport" BO_ ${ba} 1; +BA_ "GenMsgNrOfRepetition" BO_ ${ba} 0; +BA_ "GenMsgCycleTime" BO_ ${ba} 0; +BA_ "NetworkInitialization" BO_ ${ba} 0; +BA_ "GenMsgDelayTime" BO_ ${ba} 0; +EOF + +build_ba_segment $ba $id "01" +build_ba_segment $ba $id "02" +build_ba_segment $ba $id "03" +if [ "$id" != "22" ]; then + build_ba_segment $ba $id "04" + build_ba_segment $ba $id "05" + build_ba_segment $ba $id "06" +fi + +} + +build_ba_segment(){ + ba=$1 + id=$2 + seg=$3 + +cat <> ${OUT_FILENAME} +BA_ "GenSigVtEn" SG_ ${ba} CAN_DET_CONFID_AZIMUTH_${id}_${seg} "CAN_DET_CONFID_AZIMUTH_${id}_${seg}"; +BA_ "GenSigVtName" SG_ ${ba} CAN_DET_CONFID_AZIMUTH_${id}_${seg} "CAN_DET_CONFID_AZIMUTH_${id}_${seg}"; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_CONFID_AZIMUTH_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_CONFID_AZIMUTH_${id}_${seg} "CAN_DET_CONFID_AZIMUTH_${id}_${seg}"; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_SUPER_RES_TARGET_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_SUPER_RES_TARGET_${id}_${seg} "CAN_DET_SUPER_RES_TARGET_${id}_${seg}"; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_ND_TARGET_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_ND_TARGET_${id}_${seg} "CAN_DET_ND_TARGET_${id}_${seg}"; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_HOST_VEH_CLUTTER_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_HOST_VEH_CLUTTER_${id}_${seg} "CAN_DET_HOST_VEH_CLUTTER_${id}_${seg}"; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_VALID_LEVEL_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_VALID_LEVEL_${id}_${seg} "CAN_DET_VALID_LEVEL_${id}_${seg}"; +BA_ "GenSigStartValue" SG_ ${ba} CAN_DET_AZIMUTH_${id}_${seg} 0; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_AZIMUTH_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_AZIMUTH_${id}_${seg} "CAN_DET_AZIMUTH_${id}_${seg}"; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_RANGE_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_RANGE_${id}_${seg} "CAN_DET_RANGE_${id}_${seg}"; +BA_ "GenSigStartValue" SG_ ${ba} CAN_DET_RANGE_RATE_${id}_${seg} 0; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_RANGE_RATE_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_RANGE_RATE_${id}_${seg} "CAN_DET_RANGE_RATE_${id}_${seg}"; +BA_ "GenSigSendType" SG_ ${ba} CAN_DET_AMPLITUDE_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_DET_AMPLITUDE_${id}_${seg} "CAN_DET_AMPLITUDE_${id}_${seg}"; +BA_ "GenSigSendType" SG_ ${ba} CAN_SCAN_INDEX_2LSB_${id}_${seg} 0; +BA_ "GenSigCmt" SG_ ${ba} CAN_SCAN_INDEX_2LSB_${id}_${seg} "CAN_SCAN_INDEX_2LSB_${id}_${seg}"; +EOF +} + +build_val(){ +id=$1 +# bo=$(($id + 287)) +val=$(expr $id + 287) + +cat <> ${OUT_FILENAME} +VAL_ ${val} CAN_DET_CONFID_AZIMUTH_${id}_01 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ ${val} CAN_DET_CONFID_AZIMUTH_${id}_02 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ ${val} CAN_DET_CONFID_AZIMUTH_${id}_03 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +EOF +if [ "$id" != "22" ]; then +cat <> ${OUT_FILENAME} +VAL_ ${val} CAN_DET_CONFID_AZIMUTH_${id}_04 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ ${val} CAN_DET_CONFID_AZIMUTH_${id}_05 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ ${val} CAN_DET_CONFID_AZIMUTH_${id}_06 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +EOF +fi + +} + + +cat < ${OUT_FILENAME} +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: +BU_: MRR +BO_ 1073741824 VECTOR__INDEPENDENT_SIG_MSG: 0 Vector__XXX + SG_ New_Signal_943 : 0|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ CAN_SENSOR_VANGLE_OFFSET : 0|8@0+ (0.0625,-8) [-8|7.9375] "deg" Vector__XXX + SG_ CAN_SENSOR_FOV_VER : 0|8@0+ (1,0) [0|255] "deg" Vector__XXX + SG_ CAN_AUTO_ALIGN_VANGLE_QF : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_AUTO_ALIGN_VANGLE_REF : 0|10@0+ (0.03125,-10) [-10|21.9688] "deg" Vector__XXX + SG_ CAN_AUTO_ALIGN_VANGLE : 0|10@0+ (0.03125,-10) [-10|21.9688] "deg" Vector__XXX + SG_ CAN_MMIC_Temp4 : 0|8@0+ (1,-50) [-50|205] "C" Vector__XXX + SG_ CAN_MMIC_Temp3 : 0|8@0+ (1,-50) [-50|205] "C" Vector__XXX + SG_ CAN_MMIC_Temp2 : 0|8@0+ (1,-50) [-50|205] "C" Vector__XXX + SG_ CAN_Processor_Temp2 : 0|8@0+ (1,-50) [-50|205] "C" Vector__XXX + SG_ CAN_CHECKSUM : 0|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ CAN_COUNTER : 0|4@0+ (1,0) [0|15] "" Vector__XXX + SG_ CAN_VEHICLE_MODE : 0|4@0+ (1,0) [0|15] "" Vector__XXX + SG_ CAN_USC_CAL_VER_MAJOR : 0|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_USC_CAL_VER_MINOR : 0|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_SMC_CAL_VER_MAJOR : 0|16@0+ (1,0) [0|65535] "" Vector__XXX + SG_ CAN_HW_VERSION : 0|32@0+ (1,0) [0|4.29497e+09] "" Vector__XXX + SG_ CAN_FAC_TGT_MTG_SPACE_VER : 0|8@0+ (1,-128) [-128|127] "cm" Vector__XXX + SG_ CAN_ANGLE_MISALIGNMENT_VER : 0|10@0+ (0.03125,-10) [-10|21.9688] "deg" Vector__XXX + SG_ CAN_ANGLE_MOUNTING_VOFFSET : 0|8@0+ (0.0625,-8) [-8|7.9375] "deg" Vector__XXX + SG_ CAN_LATCH_FAULTS : 0|64@0+ (1,0) [0|100] "" Vector__XXX + SG_ CAN_ACTIVE_FAULTS : 0|64@0+ (1,0) [0|1.84467e+19] "" Vector__XXX + SG_ CAN_HISTORY_FAULTS : 0|64@0+ (1,0) [0|1.84467e+19] "" Vector__XXX + SG_ CAN_SERV_ALIGN_ENABLE : 0|1@0+ (1,0) [0|1] "" Vector__XXX + SG_ CAN_LONG_MOUNTING_OFFSET : 0|8@0+ (0.015625,-2) [-2|1.98438] "" Vector__XXX + SG_ CAN_BEAMWIDTH_VERT : 0|7@0+ (0.125,0) [0|15.875] "deg" Vector__XXX + SG_ CAN_VEHICLE_SPEED_CALC_QF : 0|2@0+ (1,0) [0|3] "" Vector__XXX + +BO_ 34 Active_Fault_Latched_2: 8 MRR + SG_ IPMA_PCAN_DataRangeCheck : 4|1@1+ (1,0) [0|1] "" External_Tool + SG_ IPMA_PCAN_MissingMsg : 3|1@1+ (1,0) [0|1] "" External_Tool + SG_ VINSignalCompareFailure : 2|1@1+ (1,0) [0|1] "" External_Tool + SG_ ModuleNotConfiguredError : 1|1@1+ (1,0) [0|1] "" External_Tool + SG_ CarCfgNotConfiguredError : 0|1@1+ (1,0) [0|1] "" External_Tool + +BO_ 33 Active_Fault_Latched_1: 8 MRR + SG_ Active_Flt_Latched_byte7_bit7 : 63|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte7_bit6 : 62|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte7_bit5 : 61|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte7_bit4 : 60|1@1+ (1,0) [0|1] "" External_Tool + SG_ ARMtoDSPChksumFault : 59|1@1+ (1,0) [0|1] "" External_Tool + SG_ DSPtoArmChksumFault : 58|1@1+ (1,0) [0|1] "" External_Tool + SG_ HostToArmChksumFault : 57|1@1+ (1,0) [0|1] "" External_Tool + SG_ ARMtoHostChksumFault : 56|1@1+ (1,0) [0|1] "" External_Tool + SG_ LoopBWOutOfRange : 55|1@1+ (1,0) [0|1] "" External_Tool + SG_ DSPOverrunFault : 54|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte6_bit5 : 53|1@1+ (1,0) [0|1] "" External_Tool + SG_ TuningSensitivityFault : 52|1@1+ (1,0) [0|1] "" External_Tool + SG_ SaturatedTuningFreqFault : 51|1@1+ (1,0) [0|1] "" External_Tool + SG_ LocalOscPowerFault : 50|1@1+ (1,0) [0|1] "" External_Tool + SG_ TransmitterPowerFault : 49|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte6_bit0 : 48|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte5_bit7 : 47|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte5_bit6 : 46|1@1+ (1,0) [0|1] "" External_Tool + SG_ XCVRDeviceSPIFault : 45|1@1+ (1,0) [0|1] "" External_Tool + SG_ FreqSynthesizerSPIFault : 44|1@1+ (1,0) [0|1] "" External_Tool + SG_ AnalogConverterDevicSPIFault : 43|1@1+ (1,0) [0|1] "" External_Tool + SG_ SidelobeBlockage : 42|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte5_bit1 : 41|1@1+ (1,0) [0|1] "" External_Tool + SG_ MNRBlocked : 40|1@1+ (1,0) [0|1] "" External_Tool + SG_ ECUTempHighFault : 39|1@1+ (1,0) [0|1] "" External_Tool + SG_ TransmitterTempHighFault : 38|1@1+ (1,0) [0|1] "" External_Tool + SG_ AlignmentRoutineFailedFault : 37|1@1+ (1,0) [0|1] "" External_Tool + SG_ UnreasonableRadarData : 36|1@1+ (1,0) [0|1] "" External_Tool + SG_ MicroprocessorTempHighFault : 35|1@1+ (1,0) [0|1] "" External_Tool + SG_ VerticalAlignmentOutOfRange : 34|1@1+ (1,0) [0|1] "" External_Tool + SG_ HorizontalAlignmentOutOfRange : 33|1@1+ (1,0) [0|1] "" External_Tool + SG_ FactoryAlignmentMode : 32|1@1+ (1,0) [0|1] "" External_Tool + SG_ BatteryLowFault : 31|1@1+ (1,0) [0|1] "" External_Tool + SG_ BatteryHighFault : 30|1@1+ (1,0) [0|1] "" External_Tool + SG_ v_1p25SupplyOutOfRange : 29|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte3_bit4 : 28|1@1+ (1,0) [0|1] "" External_Tool + SG_ ThermistorOutOfRange : 27|1@1+ (1,0) [0|1] "" External_Tool + SG_ v_3p3DACSupplyOutOfRange : 26|1@1+ (1,0) [0|1] "" External_Tool + SG_ v_3p3RAWSupplyOutOfRange : 25|1@1+ (1,0) [0|1] "" External_Tool + SG_ v_5_SupplyOutOfRange : 24|1@1+ (1,0) [0|1] "" External_Tool + SG_ TransmitterIDFault : 23|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit6 : 22|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit5 : 21|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit4 : 20|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit3 : 19|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte2_bit2 : 18|1@1+ (1,0) [0|1] "" External_Tool + SG_ PCANMissingMsgFault : 17|1@1+ (1,0) [0|1] "" External_Tool + SG_ PCANBusOff : 16|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte1_bit7 : 15|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte1_bit6 : 14|1@1+ (1,0) [0|1] "" External_Tool + SG_ InstructionSetCheckFault : 13|1@1+ (1,0) [0|1] "" External_Tool + SG_ StackOverflowFault : 12|1@1+ (1,0) [0|1] "" External_Tool + SG_ WatchdogFault : 11|1@1+ (1,0) [0|1] "" External_Tool + SG_ PLLLockFault : 10|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte1_bit1 : 9|1@1+ (1,0) [0|1] "" External_Tool + SG_ RAMMemoryTestFault : 8|1@1+ (1,0) [0|1] "" External_Tool + SG_ USCValidationFault : 7|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte0_bit6 : 6|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte0_bit5 : 5|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte0_bit4 : 4|1@1+ (1,0) [0|1] "" External_Tool + SG_ Active_Flt_Latched_byte0_bit3 : 3|1@1+ (1,0) [0|1] "" External_Tool + SG_ KeepAliveChecksumFault : 2|1@1+ (1,0) [0|1] "" External_Tool + SG_ ProgramCalibrationFlashChecksum : 1|1@1+ (1,0) [0|1] "" External_Tool + SG_ ApplicationFlashChecksumFault : 0|1@1+ (1,0) [0|1] "" External_Tool + +BO_ 500 XCP_MRR_DAQ_RESP: 8 MRR + SG_ MRR_xcp_daq_resp_byte7 : 63|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte6 : 55|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte5 : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte4 : 39|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte3 : 31|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte2 : 23|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte1 : 15|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_daq_resp_byte0 : 7|8@0+ (1,0) [0|255] "" External_Tool + +BO_ 499 XCP_MRR_DTO_RESP: 8 MRR + SG_ MRR_xcp_dto_resp_byte7 : 63|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte6 : 55|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte5 : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte4 : 39|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte3 : 31|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte2 : 23|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte1 : 15|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_dto_resp_byte0 : 7|8@0+ (1,0) [0|255] "" External_Tool + +BO_ 497 XCP_MRR_CTO_RESP: 8 MRR + SG_ MRR_xcp_cto_resp_byte7 : 63|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte6 : 55|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte5 : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte4 : 39|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte3 : 31|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte2 : 23|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte1 : 15|8@0+ (1,0) [0|255] "" External_Tool + SG_ MRR_xcp_cto_resp_byte0 : 7|8@0+ (1,0) [0|255] "" External_Tool + +BO_ 1900 Ford_Diag_Resp_Phys: 8 MRR + SG_ TesterPhysicalResCCM : 7|64@0+ (1,0) [0|1.84467e+19] "" IFV_Host + +BO_ 261 MRR_Status_SerialNumber: 8 MRR + SG_ CAN_SEQUENCE_NUMBER : 55|16@0+ (1,0) [0|65535] "" External_Tool + SG_ CAN_SERIAL_NUMBER : 7|40@0+ (1,0) [0|1.09951e+12] "" External_Tool + +BO_ 264 MRR_Status_SwVersion: 8 MRR + SG_ CAN_PBL_Field_Revision : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_PBL_Promote_Revision : 39|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_SW_Field_Revision : 23|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_SW_Promote_Revision : 15|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_SW_Release_Revision : 7|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_PBL_Release_Revision : 31|8@0+ (1,0) [0|255] "" External_Tool + +BO_ 373 MRR_Header_SensorPosition: 8 MRR + SG_ CAN_SENSOR_POLARITY : 55|1@0+ (1,0) [0|1] "" External_Tool + SG_ CAN_SENSOR_LAT_OFFSET : 39|16@0+ (0.01,0) [0|655.35] "cm" External_Tool + SG_ CAN_SENSOR_LONG_OFFSET : 23|16@0+ (0.01,0) [0|655.35] "cm" External_Tool + SG_ CAN_SENSOR_HANGLE_OFFSET : 7|8@0+ (0.0625,-8) [-8|7.9375] "deg" External_Tool + +BO_ 372 MRR_Header_SensorCoverage: 8 MRR + SG_ CAN_SENSOR_FOV_HOR : 39|8@0+ (1,0) [0|255] "deg" IFV_VFP + SG_ CAN_DOPPLER_COVERAGE : 23|8@0+ (1,-128) [-128|127] "m/s" IFV_VFP + SG_ CAN_RANGE_COVERAGE : 7|8@0+ (1,0) [0|255] "m" IFV_VFP + +BO_ 371 MRR_Header_AlignmentState: 8 MRR + SG_ CAN_AUTO_ALIGN_HANGLE_QF : 13|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_ALIGNMENT_STATUS : 51|4@0+ (1,0) [0|11] "" IFV_VFP + SG_ CAN_ALIGNMENT_STATE : 55|3@0+ (1,0) [0|7] "" IFV_VFP + SG_ CAN_AUTO_ALIGN_HANGLE_REF : 11|10@0+ (0.000341218,-0.174533) [-0.174533|0.174533] "rad" IFV_VFP + SG_ CAN_AUTO_ALIGN_HANGLE : 7|10@0+ (0.000341218,-0.174533) [-0.174533|0.174533] "rad" IFV_VFP + +BO_ 369 MRR_Header_Timestamps: 8 MRR + SG_ CAN_DET_TIME_SINCE_MEAS : 39|11@0+ (0.1,0) [0|204.7] "ms" IFV_Host + SG_ CAN_SENSOR_TIME_STAMP : 7|32@0+ (0.1,0) [0|4.29497e+08] "ms" IFV_VFP + +BO_ 368 MRR_Header_InformationDetections: 8 MRR + SG_ CAN_ALIGN_UPDATES_DONE : 55|16@0+ (1,0) [0|65535] "" IFV_VFP + SG_ CAN_SCAN_INDEX : 31|16@0+ (1,0) [0|65535] "" IFV_VFP + SG_ CAN_NUMBER_OF_DET : 47|8@0+ (1,0) [0|255] "" External_Tool + SG_ CAN_LOOK_ID : 23|2@0+ (1,0) [0|3] "" External_Tool + SG_ CAN_LOOK_INDEX : 7|16@0+ (1,0) [0|65535] "" External_Tool + +BO_ 265 MRR_Status_Temp_Volt: 8 MRR + SG_ CAN_BATT_VOLTS : 63|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_1_25_V : 55|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_5_V : 47|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_3_3_V_RAW : 31|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_3_3_V_DAC : 15|8@0+ (0.08,0) [0|20.4] "V" External_Tool + SG_ CAN_MMIC_Temp1 : 39|8@0+ (1,-50) [-50|205] "C" External_Tool + SG_ CAN_Processor_Thermistor : 23|8@0+ (1,-50) [-50|205] "C" External_Tool + SG_ CAN_Processor_Temp1 : 7|8@0+ (1,-50) [-50|205] "C" External_Tool + +EOF + +build_bo "04" + +cat <> ${OUT_FILENAME} +BO_ 351 MRR_Detection_064: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_64 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_64 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_64 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_64 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_64 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_64 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_64 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_64 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_64 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_64 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 350 MRR_Detection_063: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_63 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_63 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_63 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_63 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_63 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_63 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_63 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_63 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_63 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_63 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 349 MRR_Detection_062: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_62 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_62 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_62 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_62 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_62 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_62 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_62 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_62 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_62 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_62 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 348 MRR_Detection_061: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_61 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_61 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_61 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_61 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_61 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_61 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_61 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_61 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_61 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_61 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 347 MRR_Detection_060: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_60 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_60 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_60 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_60 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_60 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_60 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_60 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_60 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_60 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_60 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 346 MRR_Detection_059: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_59 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_59 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_59 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_59 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_59 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_59 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_59 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_59 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_59 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_59 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 345 MRR_Detection_058: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_58 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_58 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_58 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_58 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_58 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_58 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_58 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_58 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_58 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_58 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 344 MRR_Detection_057: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_57 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_57 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_57 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_57 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_57 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_57 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_57 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_57 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_57 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_57 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 343 MRR_Detection_056: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_56 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_56 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_56 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_56 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_56 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_56 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_56 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_56 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_56 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_56 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 342 MRR_Detection_055: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_55 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_55 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_55 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_55 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_55 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_55 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_55 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_55 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_55 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_55 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 335 MRR_Detection_048: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_48 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_48 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_48 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_48 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_48 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_48 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_48 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_48 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_48 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_48 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 334 MRR_Detection_047: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_47 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_47 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_47 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_47 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_47 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_47 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_47 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_47 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_47 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_47 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 333 MRR_Detection_046: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_46 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_46 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_46 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_46 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_46 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_46 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_46 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_46 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_46 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_46 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 332 MRR_Detection_045: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_45 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_45 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_45 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_45 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_45 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_45 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_45 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_45 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_45 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_45 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 331 MRR_Detection_044: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_44 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_44 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_44 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_44 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_44 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_44 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_44 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_44 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_44 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_44 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 330 MRR_Detection_043: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_43 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_43 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_43 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_43 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_43 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_43 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_43 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_43 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_43 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_43 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 329 MRR_Detection_042: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_42 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_42 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_42 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_42 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_42 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_42 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_42 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_42 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_42 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_42 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 328 MRR_Detection_041: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_41 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_41 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_41 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_41 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_41 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_41 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_41 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_41 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_41 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_41 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 327 MRR_Detection_040: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_40 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_40 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_40 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_40 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_40 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_40 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_40 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_40 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_40 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_40 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 325 MRR_Detection_038: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_38 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_38 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_38 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_38 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_38 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_38 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_38 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_38 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_38 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_38 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 324 MRR_Detection_037: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_37 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_37 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_37 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_37 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_37 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_37 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_37 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_37 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_37 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_37 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 323 MRR_Detection_036: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_36 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_36 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_36 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_36 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_36 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_36 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_36 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_36 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_36 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_36 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 322 MRR_Detection_035: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_35 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_35 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_35 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_35 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_35 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_35 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_35 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_35 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_35 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_35 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 321 MRR_Detection_034: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_34 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_34 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_34 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_34 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_34 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_34 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_34 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_34 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_34 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_34 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 320 MRR_Detection_033: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_33 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_33 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_33 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_33 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_33 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_33 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_33 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_33 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_33 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_33 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 319 MRR_Detection_032: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_32 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_32 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_32 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_32 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_32 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_32 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_32 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_32 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_32 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_32 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 318 MRR_Detection_031: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_31 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_31 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_31 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_31 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_31 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_31 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_31 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_31 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_31 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_31 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 317 MRR_Detection_030: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_30 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_30 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_30 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_30 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_30 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_30 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_30 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_30 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_30 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_30 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 316 MRR_Detection_029: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_29 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_29 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_29 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_29 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_29 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_29 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_29 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_29 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_29 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_29 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 314 MRR_Detection_027: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_27 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_27 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_27 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_27 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_27 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_27 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_27 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_27 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_27 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_27 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 313 MRR_Detection_026: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_26 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_26 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_26 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_26 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_26 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_26 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_26 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_26 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_26 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_26 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 312 MRR_Detection_025: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_25 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_25 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_25 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_25 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_25 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_25 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_25 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_25 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_25 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_25 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 311 MRR_Detection_024: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_24 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_24 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_24 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_24 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_24 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_24 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_24 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_24 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_24 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_24 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 310 MRR_Detection_023: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_23 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_23 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_23 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_23 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_23 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_23 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_23 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_23 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_23 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_23 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +EOF + +build_bo "22" +build_bo "21" +build_bo "20" +build_bo "19" +build_bo "18" + +cat <> ${OUT_FILENAME} +BO_ 341 MRR_Detection_054: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_54 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_54 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_54 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_54 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_54 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_54 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_54 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_54 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_54 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_54 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 340 MRR_Detection_053: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_53 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_53 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_53 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_53 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_53 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_53 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_53 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_53 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_53 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_53 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 339 MRR_Detection_052: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_52 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_52 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_52 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_52 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_52 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_52 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_52 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_52 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_52 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_52 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 338 MRR_Detection_051: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_51 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_51 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_51 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_51 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_51 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_51 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_51 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_51 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_51 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_51 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 337 MRR_Detection_050: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_50 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_50 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_50 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_50 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_50 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_50 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_50 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_50 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_50 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_50 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 336 MRR_Detection_049: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_49 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_49 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_49 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_49 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_49 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_49 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_49 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_49 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_49 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_49 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 326 MRR_Detection_039: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_39 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_39 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_39 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_39 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_39 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_39 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_39 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_39 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_39 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_39 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +BO_ 315 MRR_Detection_028: 8 MRR + SG_ CAN_DET_CONFID_AZIMUTH_28 : 33|2@0+ (1,0) [0|3] "" IFV_VFP + SG_ CAN_DET_SUPER_RES_TARGET_28 : 56|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_ND_TARGET_28 : 48|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_HOST_VEH_CLUTTER_28 : 49|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_VALID_LEVEL_28 : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_DET_AZIMUTH_28 : 47|14@0+ (0.0003834,-3.1416) [-3.1416|3.13964] "rad" IFV_VFP + SG_ CAN_DET_RANGE_28 : 31|14@0+ (0.015625,0) [0|255.984] "m" IFV_VFP + SG_ CAN_DET_RANGE_RATE_28 : 15|14@0+ (0.015625,-128) [-128|127.984] "m/s" IFV_VFP + SG_ CAN_DET_AMPLITUDE_28 : 7|7@0+ (1,-64) [-64|63] "dBsm" IFV_VFP + SG_ CAN_SCAN_INDEX_2LSB_28 : 17|2@0+ (1,0) [0|3] "" IFV_VFP + +EOF + +build_bo "17" +build_bo "16" +build_bo "15" +build_bo "14" +build_bo "13" +build_bo "12" +build_bo "11" +build_bo "10" +build_bo "09" +build_bo "08" +build_bo "07" +build_bo "06" +build_bo "05" +build_bo "03" +build_bo "02" + +cat <> ${OUT_FILENAME} +BO_ 256 MRR_Status_CANVersion: 8 MRR + SG_ CAN_USC_SECTION_COMPATIBILITY : 23|16@0+ (1,0) [0|65535] "" External_Tool + SG_ CAN_PCAN_MINOR_MRR : 7|8@0+ (1,0) [0|255] "" IFV_VFP + SG_ CAN_PCAN_MAJOR_MRR : 15|8@0+ (1,0) [0|255] "" IFV_VFP + +BO_ 257 MRR_Status_Radar: 8 MRR + SG_ CAN_INTERFERENCE_TYPE : 11|2@0+ (1,0) [0|3] "" IFV_Host + SG_ CAN_RECOMMEND_UNCONVERGE : 9|1@0+ (1,0) [0|1] "" IFV_Host + SG_ CAN_BLOCKAGE_SIDELOBE_FILTER_VAL : 15|4@0+ (1,0) [0|15] "" IFV_Host + SG_ CAN_RADAR_ALIGN_INCOMPLETE : 8|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_BLOCKAGE_SIDELOBE : 4|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_BLOCKAGE_MNR : 5|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_EXT_COND_NOK : 1|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_ALIGN_OUT_RANGE : 2|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_ALIGN_NOT_START : 0|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_OVERHEAT_ERROR : 3|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_RADAR_NOT_OP : 6|1@0+ (1,0) [0|1] "" IFV_VFP + SG_ CAN_XCVR_OPERATIONAL : 7|1@0+ (1,0) [0|1] "" IFV_VFP + +EOF + +build_bo "01" + +cat <> ${OUT_FILENAME} +BA_DEF_ SG_ "CrossOver_InfoCAN" ENUM "No","Yes"; +BA_DEF_ SG_ "CrossOver_LIN" ENUM "No","Yes","No","Yes"; +BA_DEF_ SG_ "UsedOnPgmDBC" ENUM "No","Yes","No","Yes","No","Yes"; +BA_DEF_ SG_ "ContentDependant" ENUM "No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ SG_ "GenSigTimeoutTime_RCM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_GWM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_OCS" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_ABS_ESC" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_CCM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_IPMA" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_TSTR" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_SCCM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_PSCM" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime__delete" INT 0 100000; +BA_DEF_ SG_ "GenSigTimeoutTime_Generic_BCM" INT 0 100000; +BA_DEF_ BO_ "NmMessage" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "DiagResponse" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "DiagRequest" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "TpTxIndex" INT 0 255; +BA_DEF_ BO_ "DiagState" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "TpApplType" STRING ; +BA_DEF_ BO_ "NmAsrMessage" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "Mulitplexer" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "ConfiguredTransmitter" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "EventRateOfChange" INT 10 10000; +BA_DEF_ BO_ "GenMsgHandlingTypeDoc" STRING ; +BA_DEF_ BO_ "GenMsgHandlingTypeCode" STRING ; +BA_DEF_ BO_ "GenMsgMarked" STRING ; +BA_DEF_ SG_ "GenSigMarked" STRING ; +BA_DEF_ SG_ "GenSigVtIndex" STRING ; +BA_DEF_ SG_ "GenSigVtName" STRING ; +BA_DEF_ SG_ "GenSigVtEn" STRING ; +BA_DEF_ SG_ "GenSigSNA" STRING ; +BA_DEF_ SG_ "GenSigCmt" STRING ; +BA_DEF_ BO_ "GenMsgCmt" STRING ; +BA_DEF_ SG_ "GenSigSendType" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType"; +BA_DEF_ SG_ "GenSigInactiveValue" INT 0 100000; +BA_DEF_ SG_ "GenSigMissingSourceValue" INT 0 1e+09; +BA_DEF_ SG_ "WakeupSignal" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes"; +BA_DEF_ SG_ "GenSigStartValue" INT 0 1e+09; +BA_DEF_ BO_ "GenMsgILSupport" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes"; +BA_DEF_ BO_ "NetworkInitializationCommand" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BO_ "GenMsgSendType" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType"; +BA_DEF_ BO_ "GenMsgCycleTime" INT 0 100000; +BA_DEF_ BO_ "GenMsgCycleTimeFast" INT 0 100000; +BA_DEF_ BO_ "GenMsgDelayTime" INT 0 1000; +BA_DEF_ BO_ "GenMsgNrOfRepetition" INT 0 100; +BA_DEF_ BO_ "GenMsgStartDelayTime" INT 0 10000; +BA_DEF_ BO_ "NetworkInitialization" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes"; +BA_DEF_ BO_ "MessageGateway" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes","No","Yes"; +BA_DEF_ BU_ "ILUsed" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BU_ "NetworkInitializationUsed" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes","No","Yes","No","Yes","No","Yes"; +BA_DEF_ BU_ "PowerType" ENUM "No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","No","Yes","Cyclic","OnWrite","vector_leerstring","OnChange","vector_leerstring","IfActive","vector_leerstring","NoSigSendType","No","Yes","No","Yes","No","Yes","FixedPeriodic","Event","EnabledPeriodic","NotUsed","NotUsed","EventPeriodic","NotUsed","NotUsed","NoMsgSendType","No","Yes","No","Yes","No","Yes","No","Yes","Switched","Latched","Sleep","vector_leerstring","vector_leerstring"; +BA_DEF_ BU_ "NodeStartUpTime" INT 0 10000; +BA_DEF_ BU_ "NodeWakeUpTime" INT 0 10000; +BA_DEF_ BO_ "GenMsgBackgroundColor" STRING ; +BA_DEF_ BO_ "GenMsgForegroundColor" STRING ; +BA_ "GenMsgCycleTime" BO_ 34 1000; +BA_ "GenMsgSendType" BO_ 34 0; +BA_ "GenSigVtEn" SG_ 34 IPMA_PCAN_DataRangeCheck "IPMA_PCAN_DataRangeCheck"; +BA_ "GenSigVtName" SG_ 34 IPMA_PCAN_DataRangeCheck "IPMA_PCAN_DataRangeCheck"; +BA_ "GenSigVtEn" SG_ 34 IPMA_PCAN_MissingMsg "IPMA_PCAN_MissingMsg"; +BA_ "GenSigVtName" SG_ 34 IPMA_PCAN_MissingMsg "IPMA_PCAN_MissingMsg"; +BA_ "GenSigVtEn" SG_ 34 VINSignalCompareFailure "VINSignalCompareFailure"; +BA_ "GenSigVtName" SG_ 34 VINSignalCompareFailure "VINSignalCompareFailure"; +BA_ "GenSigVtEn" SG_ 34 ModuleNotConfiguredError "ModuleNotConfiguredError"; +BA_ "GenSigVtName" SG_ 34 ModuleNotConfiguredError "ModuleNotConfiguredError"; +BA_ "GenSigVtEn" SG_ 34 CarCfgNotConfiguredError "CarCfgNotConfiguredError"; +BA_ "GenSigVtName" SG_ 34 CarCfgNotConfiguredError "CarCfgNotConfiguredError"; +BA_ "GenMsgCycleTime" BO_ 33 1000; +BA_ "GenMsgSendType" BO_ 33 0; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte7_bit7 "Active_Flt_Latched_byte7_bit7"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte7_bit7 "Active_Flt_Latched_byte7_bit7"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte7_bit6 "Active_Flt_Latched_byte7_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte7_bit6 "Active_Flt_Latched_byte7_bit6"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte7_bit5 "Active_Flt_Latched_byte7_bit5"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte7_bit5 "Active_Flt_Latched_byte7_bit5"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte7_bit4 "Active_Flt_Latched_byte7_bit4"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte7_bit4 "Active_Flt_Latched_byte7_bit4"; +BA_ "GenSigVtEn" SG_ 33 ARMtoDSPChksumFault "ARMtoDSPChksumFault"; +BA_ "GenSigVtName" SG_ 33 ARMtoDSPChksumFault "ARMtoDSPChksumFault"; +BA_ "GenSigVtEn" SG_ 33 DSPtoArmChksumFault "DSPtoArmChksumFault"; +BA_ "GenSigVtName" SG_ 33 DSPtoArmChksumFault "DSPtoArmChksumFault"; +BA_ "GenSigVtEn" SG_ 33 HostToArmChksumFault "HostToArmChksumFault"; +BA_ "GenSigVtName" SG_ 33 HostToArmChksumFault "HostToArmChksumFault"; +BA_ "GenSigVtEn" SG_ 33 ARMtoHostChksumFault "ARMtoHostChksumFault"; +BA_ "GenSigVtName" SG_ 33 ARMtoHostChksumFault "ARMtoHostChksumFault"; +BA_ "GenSigVtEn" SG_ 33 LoopBWOutOfRange "LoopBWOutOfRange"; +BA_ "GenSigVtName" SG_ 33 LoopBWOutOfRange "LoopBWOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 DSPOverrunFault "DSPOverrunFault"; +BA_ "GenSigVtName" SG_ 33 DSPOverrunFault "DSPOverrunFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte6_bit5 "Active_Flt_Latched_byte6_bit5"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte6_bit5 "Active_Flt_Latched_byte6_bit5"; +BA_ "GenSigVtEn" SG_ 33 TuningSensitivityFault "TuningSensitivityFault"; +BA_ "GenSigVtName" SG_ 33 TuningSensitivityFault "TuningSensitivityFault"; +BA_ "GenSigVtEn" SG_ 33 SaturatedTuningFreqFault "SaturatedTuningFreqFault"; +BA_ "GenSigVtName" SG_ 33 SaturatedTuningFreqFault "SaturatedTuningFreqFault"; +BA_ "GenSigVtEn" SG_ 33 LocalOscPowerFault "LocalOscPowerFault"; +BA_ "GenSigVtName" SG_ 33 LocalOscPowerFault "LocalOscPowerFault"; +BA_ "GenSigVtEn" SG_ 33 TransmitterPowerFault "TransmitterPowerFault"; +BA_ "GenSigVtName" SG_ 33 TransmitterPowerFault "TransmitterPowerFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte6_bit0 "Active_Flt_Latched_byte6_bit0"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte6_bit0 "Active_Flt_Latched_byte6_bit0"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte5_bit7 "Active_Flt_Latched_byte5_bit7"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte5_bit7 "Active_Flt_Latched_byte5_bit7"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte5_bit6 "Active_Flt_Latched_byte5_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte5_bit6 "Active_Flt_Latched_byte5_bit6"; +BA_ "GenSigVtEn" SG_ 33 XCVRDeviceSPIFault "XCVRDeviceSPIFault"; +BA_ "GenSigVtName" SG_ 33 XCVRDeviceSPIFault "XCVRDeviceSPIFault"; +BA_ "GenSigVtEn" SG_ 33 FreqSynthesizerSPIFault "FreqSynthesizerSPIFault"; +BA_ "GenSigVtName" SG_ 33 FreqSynthesizerSPIFault "FreqSynthesizerSPIFault"; +BA_ "GenSigVtEn" SG_ 33 AnalogConverterDevicSPIFault "AnalogConverterDevicSPIFault"; +BA_ "GenSigVtName" SG_ 33 AnalogConverterDevicSPIFault "AnalogConverterDevicSPIFault"; +BA_ "GenSigVtEn" SG_ 33 SidelobeBlockage "SidelobeBlockage"; +BA_ "GenSigVtName" SG_ 33 SidelobeBlockage "SidelobeBlockage"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte5_bit1 "Active_Flt_Latched_byte5_bit1"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte5_bit1 "Active_Flt_Latched_byte5_bit1"; +BA_ "GenSigVtEn" SG_ 33 MNRBlocked "MNRBlocked"; +BA_ "GenSigVtName" SG_ 33 MNRBlocked "MNRBlocked"; +BA_ "GenSigVtEn" SG_ 33 ECUTempHighFault "ECUTempHighFault"; +BA_ "GenSigVtName" SG_ 33 ECUTempHighFault "ECUTempHighFault"; +BA_ "GenSigVtEn" SG_ 33 TransmitterTempHighFault "TransmitterTempHighFault"; +BA_ "GenSigVtName" SG_ 33 TransmitterTempHighFault "TransmitterTempHighFault"; +BA_ "GenSigVtEn" SG_ 33 AlignmentRoutineFailedFault "AlignmentRoutineFailedFault"; +BA_ "GenSigVtName" SG_ 33 AlignmentRoutineFailedFault "AlignmentRoutineFailedFault"; +BA_ "GenSigVtEn" SG_ 33 UnreasonableRadarData "UnreasonableRadarData"; +BA_ "GenSigVtName" SG_ 33 UnreasonableRadarData "UnreasonableRadarData"; +BA_ "GenSigVtEn" SG_ 33 MicroprocessorTempHighFault "MicroprocessorTempHighFault"; +BA_ "GenSigVtName" SG_ 33 MicroprocessorTempHighFault "MicroprocessorTempHighFault"; +BA_ "GenSigVtEn" SG_ 33 VerticalAlignmentOutOfRange "VerticalAlignmentOutOfRange"; +BA_ "GenSigVtName" SG_ 33 VerticalAlignmentOutOfRange "VerticalAlignmentOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 HorizontalAlignmentOutOfRange "HorizontalAlignmentOutOfRange"; +BA_ "GenSigVtName" SG_ 33 HorizontalAlignmentOutOfRange "HorizontalAlignmentOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 FactoryAlignmentMode "FactoryAlignmentMode"; +BA_ "GenSigVtName" SG_ 33 FactoryAlignmentMode "FactoryAlignmentMode"; +BA_ "GenSigVtEn" SG_ 33 BatteryLowFault "BatteryLowFault"; +BA_ "GenSigVtName" SG_ 33 BatteryLowFault "BatteryLowFault"; +BA_ "GenSigVtEn" SG_ 33 BatteryHighFault "BatteryHighFault"; +BA_ "GenSigVtName" SG_ 33 BatteryHighFault "BatteryHighFault"; +BA_ "GenSigVtEn" SG_ 33 v_1p25SupplyOutOfRange "v_1p25SupplyOutOfRange"; +BA_ "GenSigVtName" SG_ 33 v_1p25SupplyOutOfRange "v_1p25SupplyOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte3_bit4 "Active_Flt_Latched_byte3_bit4"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte3_bit4 "Active_Flt_Latched_byte3_bit4"; +BA_ "GenSigVtEn" SG_ 33 ThermistorOutOfRange "ThermistorOutOfRange"; +BA_ "GenSigVtName" SG_ 33 ThermistorOutOfRange "ThermistorOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 v_3p3DACSupplyOutOfRange "v_3p3DACSupplyOutOfRange"; +BA_ "GenSigVtName" SG_ 33 v_3p3DACSupplyOutOfRange "v_3p3DACSupplyOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 v_3p3RAWSupplyOutOfRange "v_3p3RAWSupplyOutOfRange"; +BA_ "GenSigVtName" SG_ 33 v_3p3RAWSupplyOutOfRange "v_3p3RAWSupplyOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 v_5_SupplyOutOfRange "v_5_SupplyOutOfRange"; +BA_ "GenSigVtName" SG_ 33 v_5_SupplyOutOfRange "v_5_SupplyOutOfRange"; +BA_ "GenSigVtEn" SG_ 33 TransmitterIDFault "TransmitterIDFault"; +BA_ "GenSigVtName" SG_ 33 TransmitterIDFault "TransmitterIDFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit6 "Active_Flt_Latched_byte2_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit6 "Active_Flt_Latched_byte2_bit6"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit5 "Active_Flt_Latched_byte2_bit5"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit5 "Active_Flt_Latched_byte2_bit5"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit4 "Active_Flt_Latched_byte2_bit4"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit4 "Active_Flt_Latched_byte2_bit4"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit3 "Active_Flt_Latched_byte2_bit3"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit3 "Active_Flt_Latched_byte2_bit3"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte2_bit2 "Active_Flt_Latched_byte2_bit2"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte2_bit2 "Active_Flt_Latched_byte2_bit2"; +BA_ "GenSigVtEn" SG_ 33 PCANMissingMsgFault "PCANMissingMsgFault"; +BA_ "GenSigVtName" SG_ 33 PCANMissingMsgFault "PCANMissingMsgFault"; +BA_ "GenSigVtEn" SG_ 33 PCANBusOff "PCANBusOff"; +BA_ "GenSigVtName" SG_ 33 PCANBusOff "PCANBusOff"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte1_bit7 "Active_Flt_Latched_byte1_bit7"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte1_bit7 "Active_Flt_Latched_byte1_bit7"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte1_bit6 "Active_Flt_Latched_byte1_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte1_bit6 "Active_Flt_Latched_byte1_bit6"; +BA_ "GenSigVtEn" SG_ 33 InstructionSetCheckFault "InstructionSetCheckFault"; +BA_ "GenSigVtName" SG_ 33 InstructionSetCheckFault "InstructionSetCheckFault"; +BA_ "GenSigVtEn" SG_ 33 StackOverflowFault "StackOverflowFault"; +BA_ "GenSigVtName" SG_ 33 StackOverflowFault "StackOverflowFault"; +BA_ "GenSigVtEn" SG_ 33 WatchdogFault "WatchdogFault"; +BA_ "GenSigVtName" SG_ 33 WatchdogFault "WatchdogFault"; +BA_ "GenSigVtEn" SG_ 33 PLLLockFault "PLLLockFault"; +BA_ "GenSigVtName" SG_ 33 PLLLockFault "PLLLockFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte1_bit1 "Active_Flt_Latched_byte1_bit1"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte1_bit1 "Active_Flt_Latched_byte1_bit1"; +BA_ "GenSigVtEn" SG_ 33 RAMMemoryTestFault "RAMMemoryTestFault"; +BA_ "GenSigVtName" SG_ 33 RAMMemoryTestFault "RAMMemoryTestFault"; +BA_ "GenSigVtName" SG_ 33 USCValidationFault "USCValidationFault"; +BA_ "GenSigVtEn" SG_ 33 USCValidationFault "USCValidationFault"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte0_bit6 "Active_Flt_Latched_byte0_bit6"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte0_bit6 "Active_Flt_Latched_byte0_bit6"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte0_bit5 "Active_Flt_Latched_byte0_bit5"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte0_bit5 "Active_Flt_Latched_byte0_bit5"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte0_bit4 "Active_Flt_Latched_byte0_bit4"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte0_bit4 "Active_Flt_Latched_byte0_bit4"; +BA_ "GenSigVtEn" SG_ 33 Active_Flt_Latched_byte0_bit3 "Active_Flt_Latched_byte0_bit3"; +BA_ "GenSigVtName" SG_ 33 Active_Flt_Latched_byte0_bit3 "Active_Flt_Latched_byte0_bit3"; +BA_ "GenSigVtEn" SG_ 33 KeepAliveChecksumFault "KeepAliveChecksumFault"; +BA_ "GenSigVtName" SG_ 33 KeepAliveChecksumFault "KeepAliveChecksumFault"; +BA_ "GenSigVtEn" SG_ 33 ProgramCalibrationFlashChecksum "ProgramCalibrationFlashChecksum"; +BA_ "GenSigVtName" SG_ 33 ProgramCalibrationFlashChecksum "ProgramCalibrationFlashChecksum"; +BA_ "GenSigVtEn" SG_ 33 ApplicationFlashChecksumFault "ApplicationFlashChecksumFault"; +BA_ "GenSigVtName" SG_ 33 ApplicationFlashChecksumFault "ApplicationFlashChecksumFault"; +BA_ "GenMsgNrOfRepetition" BO_ 500 0; +BA_ "GenMsgSendType" BO_ 500 1; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte7 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte7 "MRR_xcp_daq_resp_byte7"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte6 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte6 "MRR_xcp_daq_resp_byte6"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte5 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte5 "MRR_xcp_daq_resp_byte5"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte4 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte4 "MRR_xcp_daq_resp_byte4"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte3 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte3 "MRR_xcp_daq_resp_byte3"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte2 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte2 "MRR_xcp_daq_resp_byte2"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte1 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte1 "MRR_xcp_daq_resp_byte1"; +BA_ "GenSigSendType" SG_ 500 MRR_xcp_daq_resp_byte0 0; +BA_ "GenSigCmt" SG_ 500 MRR_xcp_daq_resp_byte0 "MRR_xcp_daq_resp_byte0"; +BA_ "GenMsgNrOfRepetition" BO_ 499 0; +BA_ "GenMsgSendType" BO_ 499 1; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte7 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte7 "MRR_xcp_dto_resp_byte7"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte6 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte6 "MRR_xcp_dto_resp_byte6"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte5 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte5 "MRR_xcp_dto_resp_byte5"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte4 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte4 "MRR_xcp_dto_resp_byte4"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte3 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte3 "MRR_xcp_dto_resp_byte3"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte2 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte2 "MRR_xcp_dto_resp_byte2"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte1 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte1 "MRR_xcp_dto_resp_byte1"; +BA_ "GenSigSendType" SG_ 499 MRR_xcp_dto_resp_byte0 0; +BA_ "GenSigCmt" SG_ 499 MRR_xcp_dto_resp_byte0 "MRR_xcp_dto_resp_byte0"; +BA_ "GenMsgNrOfRepetition" BO_ 497 0; +BA_ "GenMsgSendType" BO_ 497 1; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte7 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte7 "MRR_xcp_cto_resp_byte7"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte6 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte6 "MRR_xcp_cto_resp_byte6"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte5 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte5 "MRR_xcp_cto_resp_byte5"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte4 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte4 "MRR_xcp_cto_resp_byte4"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte3 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte3 "MRR_xcp_cto_resp_byte3"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte2 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte2 "MRR_xcp_cto_resp_byte2"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte1 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte1 "MRR_xcp_cto_resp_byte1"; +BA_ "GenSigSendType" SG_ 497 MRR_xcp_cto_resp_byte0 0; +BA_ "GenSigCmt" SG_ 497 MRR_xcp_cto_resp_byte0 "MRR_xcp_cto_resp_byte0"; +BA_ "GenMsgSendType" BO_ 1900 1; +BA_ "GenMsgNrOfRepetition" BO_ 1900 0; +BA_ "DiagResponse" BO_ 1900 1; +BA_ "GenSigCmt" SG_ 1900 TesterPhysicalResCCM "TesterPhysicalResCCM"; +BA_ "GenSigSendType" SG_ 1900 TesterPhysicalResCCM 0; +BA_ "GenMsgSendType" BO_ 261 0; +BA_ "GenMsgCycleTime" BO_ 261 1000; +BA_ "GenMsgNrOfRepetition" BO_ 261 0; +BA_ "GenSigCmt" SG_ 261 CAN_SEQUENCE_NUMBER "CAN_SEQUENCE_NUMBER"; +BA_ "GenSigCmt" SG_ 261 CAN_SERIAL_NUMBER "CAN_SERIAL_NUMBER"; +BA_ "GenSigSendType" SG_ 261 CAN_SERIAL_NUMBER 0; +BA_ "GenMsgSendType" BO_ 264 1; +BA_ "GenMsgNrOfRepetition" BO_ 264 0; +BA_ "GenSigSendType" SG_ 264 CAN_PBL_Field_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_PBL_Promote_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_SW_Field_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_SW_Promote_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_SW_Release_Revision 0; +BA_ "GenSigSendType" SG_ 264 CAN_PBL_Release_Revision 0; +BA_ "GenMsgSendType" BO_ 373 1; +BA_ "NetworkInitialization" BO_ 373 0; +BA_ "GenMsgNrOfRepetition" BO_ 373 0; +BA_ "GenSigSendType" SG_ 373 CAN_SENSOR_POLARITY 0; +BA_ "GenSigCmt" SG_ 373 CAN_SENSOR_POLARITY "CAN_SENSOR_POLARITY"; +BA_ "GenSigSendType" SG_ 373 CAN_SENSOR_LAT_OFFSET 0; +BA_ "GenSigCmt" SG_ 373 CAN_SENSOR_LAT_OFFSET "CAN_SENSOR_LAT_OFFSET"; +BA_ "GenSigSendType" SG_ 373 CAN_SENSOR_LONG_OFFSET 0; +BA_ "GenSigCmt" SG_ 373 CAN_SENSOR_LONG_OFFSET "CAN_SENSOR_LONG_OFFSET"; +BA_ "GenSigSendType" SG_ 373 CAN_SENSOR_HANGLE_OFFSET 0; +BA_ "GenSigCmt" SG_ 373 CAN_SENSOR_HANGLE_OFFSET "CAN_SENSOR_HANGLE_OFFSET"; +BA_ "GenSigStartValue" SG_ 373 CAN_SENSOR_HANGLE_OFFSET 0; +BA_ "GenMsgSendType" BO_ 372 1; +BA_ "NetworkInitialization" BO_ 372 0; +BA_ "GenMsgNrOfRepetition" BO_ 372 0; +BA_ "GenSigSendType" SG_ 372 CAN_SENSOR_FOV_HOR 0; +BA_ "GenSigCmt" SG_ 372 CAN_SENSOR_FOV_HOR "CAN_SENSOR_FOV_HOR"; +BA_ "GenSigStartValue" SG_ 372 CAN_SENSOR_FOV_HOR 0; +BA_ "GenSigSendType" SG_ 372 CAN_DOPPLER_COVERAGE 0; +BA_ "GenSigCmt" SG_ 372 CAN_DOPPLER_COVERAGE "CAN_DOPPLER_COVERAGE"; +BA_ "GenSigStartValue" SG_ 372 CAN_DOPPLER_COVERAGE 0; +BA_ "GenSigSendType" SG_ 372 CAN_RANGE_COVERAGE 0; +BA_ "GenSigCmt" SG_ 372 CAN_RANGE_COVERAGE "CAN_RANGE_COVERAGE"; +BA_ "GenMsgSendType" BO_ 371 1; +BA_ "NetworkInitialization" BO_ 371 0; +BA_ "GenMsgNrOfRepetition" BO_ 371 0; +BA_ "GenSigVtEn" SG_ 371 CAN_AUTO_ALIGN_HANGLE_QF "CAN_AUTO_ALIGN_HANGLE_QF"; +BA_ "GenSigVtName" SG_ 371 CAN_AUTO_ALIGN_HANGLE_QF "CAN_AUTO_ALIGN_HANGLE_QF"; +BA_ "GenSigSendType" SG_ 371 CAN_AUTO_ALIGN_HANGLE_QF 0; +BA_ "GenSigCmt" SG_ 371 CAN_AUTO_ALIGN_HANGLE_QF "CAN_AUTO_ALIGN_HANGLE_QF"; +BA_ "GenSigVtEn" SG_ 371 CAN_ALIGNMENT_STATUS "CAN_ALIGNMENT_STATUS"; +BA_ "GenSigVtName" SG_ 371 CAN_ALIGNMENT_STATUS "CAN_ALIGNMENT_STATUS"; +BA_ "GenSigSendType" SG_ 371 CAN_ALIGNMENT_STATUS 0; +BA_ "GenSigCmt" SG_ 371 CAN_ALIGNMENT_STATUS "CAN_ALIGNMENT_STATUS"; +BA_ "GenSigVtEn" SG_ 371 CAN_ALIGNMENT_STATE "CAN_ALIGNMENT_STATE"; +BA_ "GenSigVtName" SG_ 371 CAN_ALIGNMENT_STATE "CAN_ALIGNMENT_STATE"; +BA_ "GenSigSendType" SG_ 371 CAN_ALIGNMENT_STATE 0; +BA_ "GenSigCmt" SG_ 371 CAN_ALIGNMENT_STATE "CAN_ALIGNMENT_STATE"; +BA_ "GenSigSendType" SG_ 371 CAN_AUTO_ALIGN_HANGLE_REF 0; +BA_ "GenSigStartValue" SG_ 371 CAN_AUTO_ALIGN_HANGLE_REF 0; +BA_ "GenSigCmt" SG_ 371 CAN_AUTO_ALIGN_HANGLE_REF "CAN_AUTO_ALIGN_HANGLE_REF"; +BA_ "GenSigStartValue" SG_ 371 CAN_AUTO_ALIGN_HANGLE 0; +BA_ "GenSigSendType" SG_ 371 CAN_AUTO_ALIGN_HANGLE 0; +BA_ "GenSigCmt" SG_ 371 CAN_AUTO_ALIGN_HANGLE "CAN_AUTO_ALIGN_HANGLE"; +BA_ "GenMsgSendType" BO_ 369 1; +BA_ "NetworkInitialization" BO_ 369 0; +BA_ "GenMsgNrOfRepetition" BO_ 369 0; +BA_ "GenSigCmt" SG_ 369 CAN_DET_TIME_SINCE_MEAS "CAN_DET_TIME_SINCE_MEAS"; +BA_ "GenSigSendType" SG_ 369 CAN_DET_TIME_SINCE_MEAS 0; +BA_ "GenSigSendType" SG_ 369 CAN_SENSOR_TIME_STAMP 0; +BA_ "GenSigCmt" SG_ 369 CAN_SENSOR_TIME_STAMP "CAN_SENSOR_TIME_STAMP"; +BA_ "GenMsgSendType" BO_ 368 1; +BA_ "NetworkInitialization" BO_ 368 0; +BA_ "GenMsgNrOfRepetition" BO_ 368 0; +BA_ "GenSigSendType" SG_ 368 CAN_ALIGN_UPDATES_DONE 0; +BA_ "GenSigCmt" SG_ 368 CAN_ALIGN_UPDATES_DONE "CAN_ALIGN_UPDATES_DONE"; +BA_ "GenSigSendType" SG_ 368 CAN_SCAN_INDEX 0; +BA_ "GenSigCmt" SG_ 368 CAN_SCAN_INDEX "CAN_SCAN_INDEX"; +BA_ "GenSigSendType" SG_ 368 CAN_NUMBER_OF_DET 0; +BA_ "GenSigCmt" SG_ 368 CAN_NUMBER_OF_DET "CAN_NUMBER_OF_DET"; +BA_ "GenSigSendType" SG_ 368 CAN_LOOK_ID 0; +BA_ "GenSigCmt" SG_ 368 CAN_LOOK_ID "CAN_LOOK_ID"; +BA_ "GenSigSendType" SG_ 368 CAN_LOOK_INDEX 0; +BA_ "GenSigCmt" SG_ 368 CAN_LOOK_INDEX "CAN_LOOK_INDEX"; +BA_ "GenMsgSendType" BO_ 265 1; +BA_ "NetworkInitialization" BO_ 265 0; +BA_ "GenMsgNrOfRepetition" BO_ 265 0; +BA_ "GenSigCmt" SG_ 265 CAN_BATT_VOLTS "CAN_BATT_VOLTS"; +BA_ "GenSigCmt" SG_ 265 CAN_1_25_V "CAN_1_25_V"; +BA_ "GenSigCmt" SG_ 265 CAN_5_V "CAN_5_V"; +BA_ "GenSigCmt" SG_ 265 CAN_3_3_V_RAW "CAN_3_3_V_RAW"; +BA_ "GenSigCmt" SG_ 265 CAN_3_3_V_DAC "CAN_3_3_V_DAC"; +BA_ "GenSigSendType" SG_ 265 CAN_MMIC_Temp1 0; +BA_ "GenSigCmt" SG_ 265 CAN_MMIC_Temp1 "CAN_MMIC_Temp1"; +BA_ "GenSigStartValue" SG_ 265 CAN_MMIC_Temp1 0; +BA_ "GenSigSendType" SG_ 265 CAN_Processor_Thermistor 0; +BA_ "GenSigCmt" SG_ 265 CAN_Processor_Thermistor "CAN_Processor_Thermistor"; +BA_ "GenSigStartValue" SG_ 265 CAN_Processor_Thermistor 0; +BA_ "GenSigSendType" SG_ 265 CAN_Processor_Temp1 0; +BA_ "GenSigCmt" SG_ 265 CAN_Processor_Temp1 "CAN_Processor_Temp1"; +BA_ "GenSigStartValue" SG_ 265 CAN_Processor_Temp1 0; +EOF + +build_ba "04" + +cat <> ${OUT_FILENAME} +BA_ "GenMsgSendType" BO_ 351 1; +BA_ "GenMsgILSupport" BO_ 351 1; +BA_ "GenMsgNrOfRepetition" BO_ 351 0; +BA_ "GenMsgCycleTime" BO_ 351 0; +BA_ "NetworkInitialization" BO_ 351 0; +BA_ "GenMsgDelayTime" BO_ 351 0; +BA_ "GenSigVtEn" SG_ 351 CAN_DET_CONFID_AZIMUTH_64 "CAN_DET_CONFID_AZIMUTH_64"; +BA_ "GenSigVtName" SG_ 351 CAN_DET_CONFID_AZIMUTH_64 "CAN_DET_CONFID_AZIMUTH_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_CONFID_AZIMUTH_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_CONFID_AZIMUTH_64 "CAN_DET_CONFID_AZIMUTH_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_SUPER_RES_TARGET_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_SUPER_RES_TARGET_64 "CAN_DET_SUPER_RES_TARGET_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_ND_TARGET_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_ND_TARGET_64 "CAN_DET_ND_TARGET_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_HOST_VEH_CLUTTER_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_HOST_VEH_CLUTTER_64 "CAN_DET_HOST_VEH_CLUTTER_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_VALID_LEVEL_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_VALID_LEVEL_64 "CAN_DET_VALID_LEVEL_64"; +BA_ "GenSigStartValue" SG_ 351 CAN_DET_AZIMUTH_64 0; +BA_ "GenSigSendType" SG_ 351 CAN_DET_AZIMUTH_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_AZIMUTH_64 "CAN_DET_AZIMUTH_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_RANGE_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_RANGE_64 "CAN_DET_RANGE_64"; +BA_ "GenSigStartValue" SG_ 351 CAN_DET_RANGE_RATE_64 0; +BA_ "GenSigSendType" SG_ 351 CAN_DET_RANGE_RATE_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_RANGE_RATE_64 "CAN_DET_RANGE_RATE_64"; +BA_ "GenSigSendType" SG_ 351 CAN_DET_AMPLITUDE_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_DET_AMPLITUDE_64 "CAN_DET_AMPLITUDE_64"; +BA_ "GenSigSendType" SG_ 351 CAN_SCAN_INDEX_2LSB_64 0; +BA_ "GenSigCmt" SG_ 351 CAN_SCAN_INDEX_2LSB_64 "CAN_SCAN_INDEX_2LSB_64"; +BA_ "GenMsgSendType" BO_ 350 1; +BA_ "GenMsgILSupport" BO_ 350 1; +BA_ "GenMsgNrOfRepetition" BO_ 350 0; +BA_ "GenMsgCycleTime" BO_ 350 0; +BA_ "NetworkInitialization" BO_ 350 0; +BA_ "GenMsgDelayTime" BO_ 350 0; +BA_ "GenSigVtEn" SG_ 350 CAN_DET_CONFID_AZIMUTH_63 "CAN_DET_CONFID_AZIMUTH_63"; +BA_ "GenSigVtName" SG_ 350 CAN_DET_CONFID_AZIMUTH_63 "CAN_DET_CONFID_AZIMUTH_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_CONFID_AZIMUTH_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_CONFID_AZIMUTH_63 "CAN_DET_CONFID_AZIMUTH_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_SUPER_RES_TARGET_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_SUPER_RES_TARGET_63 "CAN_DET_SUPER_RES_TARGET_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_ND_TARGET_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_ND_TARGET_63 "CAN_DET_ND_TARGET_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_HOST_VEH_CLUTTER_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_HOST_VEH_CLUTTER_63 "CAN_DET_HOST_VEH_CLUTTER_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_VALID_LEVEL_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_VALID_LEVEL_63 "CAN_DET_VALID_LEVEL_63"; +BA_ "GenSigStartValue" SG_ 350 CAN_DET_AZIMUTH_63 0; +BA_ "GenSigSendType" SG_ 350 CAN_DET_AZIMUTH_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_AZIMUTH_63 "CAN_DET_AZIMUTH_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_RANGE_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_RANGE_63 "CAN_DET_RANGE_63"; +BA_ "GenSigStartValue" SG_ 350 CAN_DET_RANGE_RATE_63 0; +BA_ "GenSigSendType" SG_ 350 CAN_DET_RANGE_RATE_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_RANGE_RATE_63 "CAN_DET_RANGE_RATE_63"; +BA_ "GenSigSendType" SG_ 350 CAN_DET_AMPLITUDE_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_DET_AMPLITUDE_63 "CAN_DET_AMPLITUDE_63"; +BA_ "GenSigSendType" SG_ 350 CAN_SCAN_INDEX_2LSB_63 0; +BA_ "GenSigCmt" SG_ 350 CAN_SCAN_INDEX_2LSB_63 "CAN_SCAN_INDEX_2LSB_63"; +BA_ "GenMsgSendType" BO_ 349 1; +BA_ "GenMsgILSupport" BO_ 349 1; +BA_ "GenMsgNrOfRepetition" BO_ 349 0; +BA_ "GenMsgCycleTime" BO_ 349 0; +BA_ "NetworkInitialization" BO_ 349 0; +BA_ "GenMsgDelayTime" BO_ 349 0; +BA_ "GenSigVtEn" SG_ 349 CAN_DET_CONFID_AZIMUTH_62 "CAN_DET_CONFID_AZIMUTH_62"; +BA_ "GenSigVtName" SG_ 349 CAN_DET_CONFID_AZIMUTH_62 "CAN_DET_CONFID_AZIMUTH_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_CONFID_AZIMUTH_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_CONFID_AZIMUTH_62 "CAN_DET_CONFID_AZIMUTH_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_SUPER_RES_TARGET_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_SUPER_RES_TARGET_62 "CAN_DET_SUPER_RES_TARGET_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_ND_TARGET_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_ND_TARGET_62 "CAN_DET_ND_TARGET_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_HOST_VEH_CLUTTER_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_HOST_VEH_CLUTTER_62 "CAN_DET_HOST_VEH_CLUTTER_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_VALID_LEVEL_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_VALID_LEVEL_62 "CAN_DET_VALID_LEVEL_62"; +BA_ "GenSigStartValue" SG_ 349 CAN_DET_AZIMUTH_62 0; +BA_ "GenSigSendType" SG_ 349 CAN_DET_AZIMUTH_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_AZIMUTH_62 "CAN_DET_AZIMUTH_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_RANGE_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_RANGE_62 "CAN_DET_RANGE_62"; +BA_ "GenSigStartValue" SG_ 349 CAN_DET_RANGE_RATE_62 0; +BA_ "GenSigSendType" SG_ 349 CAN_DET_RANGE_RATE_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_RANGE_RATE_62 "CAN_DET_RANGE_RATE_62"; +BA_ "GenSigSendType" SG_ 349 CAN_DET_AMPLITUDE_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_DET_AMPLITUDE_62 "CAN_DET_AMPLITUDE_62"; +BA_ "GenSigSendType" SG_ 349 CAN_SCAN_INDEX_2LSB_62 0; +BA_ "GenSigCmt" SG_ 349 CAN_SCAN_INDEX_2LSB_62 "CAN_SCAN_INDEX_2LSB_62"; +BA_ "GenMsgSendType" BO_ 348 1; +BA_ "GenMsgILSupport" BO_ 348 1; +BA_ "GenMsgNrOfRepetition" BO_ 348 0; +BA_ "GenMsgCycleTime" BO_ 348 0; +BA_ "NetworkInitialization" BO_ 348 0; +BA_ "GenMsgDelayTime" BO_ 348 0; +BA_ "GenSigVtEn" SG_ 348 CAN_DET_CONFID_AZIMUTH_61 "CAN_DET_CONFID_AZIMUTH_61"; +BA_ "GenSigVtName" SG_ 348 CAN_DET_CONFID_AZIMUTH_61 "CAN_DET_CONFID_AZIMUTH_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_CONFID_AZIMUTH_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_CONFID_AZIMUTH_61 "CAN_DET_CONFID_AZIMUTH_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_SUPER_RES_TARGET_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_SUPER_RES_TARGET_61 "CAN_DET_SUPER_RES_TARGET_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_ND_TARGET_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_ND_TARGET_61 "CAN_DET_ND_TARGET_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_HOST_VEH_CLUTTER_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_HOST_VEH_CLUTTER_61 "CAN_DET_HOST_VEH_CLUTTER_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_VALID_LEVEL_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_VALID_LEVEL_61 "CAN_DET_VALID_LEVEL_61"; +BA_ "GenSigStartValue" SG_ 348 CAN_DET_AZIMUTH_61 0; +BA_ "GenSigSendType" SG_ 348 CAN_DET_AZIMUTH_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_AZIMUTH_61 "CAN_DET_AZIMUTH_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_RANGE_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_RANGE_61 "CAN_DET_RANGE_61"; +BA_ "GenSigStartValue" SG_ 348 CAN_DET_RANGE_RATE_61 0; +BA_ "GenSigSendType" SG_ 348 CAN_DET_RANGE_RATE_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_RANGE_RATE_61 "CAN_DET_RANGE_RATE_61"; +BA_ "GenSigSendType" SG_ 348 CAN_DET_AMPLITUDE_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_DET_AMPLITUDE_61 "CAN_DET_AMPLITUDE_61"; +BA_ "GenSigSendType" SG_ 348 CAN_SCAN_INDEX_2LSB_61 0; +BA_ "GenSigCmt" SG_ 348 CAN_SCAN_INDEX_2LSB_61 "CAN_SCAN_INDEX_2LSB_61"; +BA_ "GenMsgSendType" BO_ 347 1; +BA_ "GenMsgILSupport" BO_ 347 1; +BA_ "GenMsgNrOfRepetition" BO_ 347 0; +BA_ "GenMsgCycleTime" BO_ 347 0; +BA_ "NetworkInitialization" BO_ 347 0; +BA_ "GenMsgDelayTime" BO_ 347 0; +BA_ "GenSigVtEn" SG_ 347 CAN_DET_CONFID_AZIMUTH_60 "CAN_DET_CONFID_AZIMUTH_60"; +BA_ "GenSigVtName" SG_ 347 CAN_DET_CONFID_AZIMUTH_60 "CAN_DET_CONFID_AZIMUTH_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_CONFID_AZIMUTH_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_CONFID_AZIMUTH_60 "CAN_DET_CONFID_AZIMUTH_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_SUPER_RES_TARGET_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_SUPER_RES_TARGET_60 "CAN_DET_SUPER_RES_TARGET_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_ND_TARGET_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_ND_TARGET_60 "CAN_DET_ND_TARGET_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_HOST_VEH_CLUTTER_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_HOST_VEH_CLUTTER_60 "CAN_DET_HOST_VEH_CLUTTER_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_VALID_LEVEL_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_VALID_LEVEL_60 "CAN_DET_VALID_LEVEL_60"; +BA_ "GenSigStartValue" SG_ 347 CAN_DET_AZIMUTH_60 0; +BA_ "GenSigSendType" SG_ 347 CAN_DET_AZIMUTH_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_AZIMUTH_60 "CAN_DET_AZIMUTH_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_RANGE_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_RANGE_60 "CAN_DET_RANGE_60"; +BA_ "GenSigStartValue" SG_ 347 CAN_DET_RANGE_RATE_60 0; +BA_ "GenSigSendType" SG_ 347 CAN_DET_RANGE_RATE_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_RANGE_RATE_60 "CAN_DET_RANGE_RATE_60"; +BA_ "GenSigSendType" SG_ 347 CAN_DET_AMPLITUDE_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_DET_AMPLITUDE_60 "CAN_DET_AMPLITUDE_60"; +BA_ "GenSigSendType" SG_ 347 CAN_SCAN_INDEX_2LSB_60 0; +BA_ "GenSigCmt" SG_ 347 CAN_SCAN_INDEX_2LSB_60 "CAN_SCAN_INDEX_2LSB_60"; +BA_ "GenMsgSendType" BO_ 346 1; +BA_ "GenMsgILSupport" BO_ 346 1; +BA_ "GenMsgNrOfRepetition" BO_ 346 0; +BA_ "GenMsgCycleTime" BO_ 346 0; +BA_ "NetworkInitialization" BO_ 346 0; +BA_ "GenMsgDelayTime" BO_ 346 0; +BA_ "GenSigVtEn" SG_ 346 CAN_DET_CONFID_AZIMUTH_59 "CAN_DET_CONFID_AZIMUTH_59"; +BA_ "GenSigVtName" SG_ 346 CAN_DET_CONFID_AZIMUTH_59 "CAN_DET_CONFID_AZIMUTH_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_CONFID_AZIMUTH_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_CONFID_AZIMUTH_59 "CAN_DET_CONFID_AZIMUTH_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_SUPER_RES_TARGET_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_SUPER_RES_TARGET_59 "CAN_DET_SUPER_RES_TARGET_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_ND_TARGET_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_ND_TARGET_59 "CAN_DET_ND_TARGET_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_HOST_VEH_CLUTTER_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_HOST_VEH_CLUTTER_59 "CAN_DET_HOST_VEH_CLUTTER_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_VALID_LEVEL_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_VALID_LEVEL_59 "CAN_DET_VALID_LEVEL_59"; +BA_ "GenSigStartValue" SG_ 346 CAN_DET_AZIMUTH_59 0; +BA_ "GenSigSendType" SG_ 346 CAN_DET_AZIMUTH_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_AZIMUTH_59 "CAN_DET_AZIMUTH_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_RANGE_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_RANGE_59 "CAN_DET_RANGE_59"; +BA_ "GenSigStartValue" SG_ 346 CAN_DET_RANGE_RATE_59 0; +BA_ "GenSigSendType" SG_ 346 CAN_DET_RANGE_RATE_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_RANGE_RATE_59 "CAN_DET_RANGE_RATE_59"; +BA_ "GenSigSendType" SG_ 346 CAN_DET_AMPLITUDE_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_DET_AMPLITUDE_59 "CAN_DET_AMPLITUDE_59"; +BA_ "GenSigSendType" SG_ 346 CAN_SCAN_INDEX_2LSB_59 0; +BA_ "GenSigCmt" SG_ 346 CAN_SCAN_INDEX_2LSB_59 "CAN_SCAN_INDEX_2LSB_59"; +BA_ "GenMsgSendType" BO_ 345 1; +BA_ "GenMsgILSupport" BO_ 345 1; +BA_ "GenMsgNrOfRepetition" BO_ 345 0; +BA_ "GenMsgCycleTime" BO_ 345 0; +BA_ "NetworkInitialization" BO_ 345 0; +BA_ "GenMsgDelayTime" BO_ 345 0; +BA_ "GenSigVtEn" SG_ 345 CAN_DET_CONFID_AZIMUTH_58 "CAN_DET_CONFID_AZIMUTH_58"; +BA_ "GenSigVtName" SG_ 345 CAN_DET_CONFID_AZIMUTH_58 "CAN_DET_CONFID_AZIMUTH_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_CONFID_AZIMUTH_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_CONFID_AZIMUTH_58 "CAN_DET_CONFID_AZIMUTH_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_SUPER_RES_TARGET_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_SUPER_RES_TARGET_58 "CAN_DET_SUPER_RES_TARGET_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_ND_TARGET_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_ND_TARGET_58 "CAN_DET_ND_TARGET_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_HOST_VEH_CLUTTER_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_HOST_VEH_CLUTTER_58 "CAN_DET_HOST_VEH_CLUTTER_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_VALID_LEVEL_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_VALID_LEVEL_58 "CAN_DET_VALID_LEVEL_58"; +BA_ "GenSigStartValue" SG_ 345 CAN_DET_AZIMUTH_58 0; +BA_ "GenSigSendType" SG_ 345 CAN_DET_AZIMUTH_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_AZIMUTH_58 "CAN_DET_AZIMUTH_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_RANGE_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_RANGE_58 "CAN_DET_RANGE_58"; +BA_ "GenSigStartValue" SG_ 345 CAN_DET_RANGE_RATE_58 0; +BA_ "GenSigSendType" SG_ 345 CAN_DET_RANGE_RATE_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_RANGE_RATE_58 "CAN_DET_RANGE_RATE_58"; +BA_ "GenSigSendType" SG_ 345 CAN_DET_AMPLITUDE_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_DET_AMPLITUDE_58 "CAN_DET_AMPLITUDE_58"; +BA_ "GenSigSendType" SG_ 345 CAN_SCAN_INDEX_2LSB_58 0; +BA_ "GenSigCmt" SG_ 345 CAN_SCAN_INDEX_2LSB_58 "CAN_SCAN_INDEX_2LSB_58"; +BA_ "GenMsgSendType" BO_ 344 1; +BA_ "GenMsgILSupport" BO_ 344 1; +BA_ "GenMsgNrOfRepetition" BO_ 344 0; +BA_ "GenMsgCycleTime" BO_ 344 0; +BA_ "NetworkInitialization" BO_ 344 0; +BA_ "GenMsgDelayTime" BO_ 344 0; +BA_ "GenSigVtEn" SG_ 344 CAN_DET_CONFID_AZIMUTH_57 "CAN_DET_CONFID_AZIMUTH_57"; +BA_ "GenSigVtName" SG_ 344 CAN_DET_CONFID_AZIMUTH_57 "CAN_DET_CONFID_AZIMUTH_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_CONFID_AZIMUTH_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_CONFID_AZIMUTH_57 "CAN_DET_CONFID_AZIMUTH_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_SUPER_RES_TARGET_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_SUPER_RES_TARGET_57 "CAN_DET_SUPER_RES_TARGET_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_ND_TARGET_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_ND_TARGET_57 "CAN_DET_ND_TARGET_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_HOST_VEH_CLUTTER_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_HOST_VEH_CLUTTER_57 "CAN_DET_HOST_VEH_CLUTTER_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_VALID_LEVEL_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_VALID_LEVEL_57 "CAN_DET_VALID_LEVEL_57"; +BA_ "GenSigStartValue" SG_ 344 CAN_DET_AZIMUTH_57 0; +BA_ "GenSigSendType" SG_ 344 CAN_DET_AZIMUTH_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_AZIMUTH_57 "CAN_DET_AZIMUTH_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_RANGE_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_RANGE_57 "CAN_DET_RANGE_57"; +BA_ "GenSigStartValue" SG_ 344 CAN_DET_RANGE_RATE_57 0; +BA_ "GenSigSendType" SG_ 344 CAN_DET_RANGE_RATE_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_RANGE_RATE_57 "CAN_DET_RANGE_RATE_57"; +BA_ "GenSigSendType" SG_ 344 CAN_DET_AMPLITUDE_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_DET_AMPLITUDE_57 "CAN_DET_AMPLITUDE_57"; +BA_ "GenSigSendType" SG_ 344 CAN_SCAN_INDEX_2LSB_57 0; +BA_ "GenSigCmt" SG_ 344 CAN_SCAN_INDEX_2LSB_57 "CAN_SCAN_INDEX_2LSB_57"; +BA_ "GenMsgSendType" BO_ 343 1; +BA_ "GenMsgILSupport" BO_ 343 1; +BA_ "GenMsgNrOfRepetition" BO_ 343 0; +BA_ "GenMsgCycleTime" BO_ 343 0; +BA_ "NetworkInitialization" BO_ 343 0; +BA_ "GenMsgDelayTime" BO_ 343 0; +BA_ "GenSigVtEn" SG_ 343 CAN_DET_CONFID_AZIMUTH_56 "CAN_DET_CONFID_AZIMUTH_56"; +BA_ "GenSigVtName" SG_ 343 CAN_DET_CONFID_AZIMUTH_56 "CAN_DET_CONFID_AZIMUTH_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_CONFID_AZIMUTH_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_CONFID_AZIMUTH_56 "CAN_DET_CONFID_AZIMUTH_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_SUPER_RES_TARGET_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_SUPER_RES_TARGET_56 "CAN_DET_SUPER_RES_TARGET_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_ND_TARGET_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_ND_TARGET_56 "CAN_DET_ND_TARGET_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_HOST_VEH_CLUTTER_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_HOST_VEH_CLUTTER_56 "CAN_DET_HOST_VEH_CLUTTER_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_VALID_LEVEL_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_VALID_LEVEL_56 "CAN_DET_VALID_LEVEL_56"; +BA_ "GenSigStartValue" SG_ 343 CAN_DET_AZIMUTH_56 0; +BA_ "GenSigSendType" SG_ 343 CAN_DET_AZIMUTH_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_AZIMUTH_56 "CAN_DET_AZIMUTH_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_RANGE_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_RANGE_56 "CAN_DET_RANGE_56"; +BA_ "GenSigStartValue" SG_ 343 CAN_DET_RANGE_RATE_56 0; +BA_ "GenSigSendType" SG_ 343 CAN_DET_RANGE_RATE_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_RANGE_RATE_56 "CAN_DET_RANGE_RATE_56"; +BA_ "GenSigSendType" SG_ 343 CAN_DET_AMPLITUDE_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_DET_AMPLITUDE_56 "CAN_DET_AMPLITUDE_56"; +BA_ "GenSigSendType" SG_ 343 CAN_SCAN_INDEX_2LSB_56 0; +BA_ "GenSigCmt" SG_ 343 CAN_SCAN_INDEX_2LSB_56 "CAN_SCAN_INDEX_2LSB_56"; +BA_ "GenMsgSendType" BO_ 342 1; +BA_ "GenMsgILSupport" BO_ 342 1; +BA_ "GenMsgNrOfRepetition" BO_ 342 0; +BA_ "GenMsgCycleTime" BO_ 342 0; +BA_ "NetworkInitialization" BO_ 342 0; +BA_ "GenMsgDelayTime" BO_ 342 0; +BA_ "GenSigVtEn" SG_ 342 CAN_DET_CONFID_AZIMUTH_55 "CAN_DET_CONFID_AZIMUTH_55"; +BA_ "GenSigVtName" SG_ 342 CAN_DET_CONFID_AZIMUTH_55 "CAN_DET_CONFID_AZIMUTH_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_CONFID_AZIMUTH_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_CONFID_AZIMUTH_55 "CAN_DET_CONFID_AZIMUTH_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_SUPER_RES_TARGET_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_SUPER_RES_TARGET_55 "CAN_DET_SUPER_RES_TARGET_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_ND_TARGET_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_ND_TARGET_55 "CAN_DET_ND_TARGET_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_HOST_VEH_CLUTTER_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_HOST_VEH_CLUTTER_55 "CAN_DET_HOST_VEH_CLUTTER_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_VALID_LEVEL_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_VALID_LEVEL_55 "CAN_DET_VALID_LEVEL_55"; +BA_ "GenSigStartValue" SG_ 342 CAN_DET_AZIMUTH_55 0; +BA_ "GenSigSendType" SG_ 342 CAN_DET_AZIMUTH_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_AZIMUTH_55 "CAN_DET_AZIMUTH_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_RANGE_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_RANGE_55 "CAN_DET_RANGE_55"; +BA_ "GenSigStartValue" SG_ 342 CAN_DET_RANGE_RATE_55 0; +BA_ "GenSigSendType" SG_ 342 CAN_DET_RANGE_RATE_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_RANGE_RATE_55 "CAN_DET_RANGE_RATE_55"; +BA_ "GenSigSendType" SG_ 342 CAN_DET_AMPLITUDE_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_DET_AMPLITUDE_55 "CAN_DET_AMPLITUDE_55"; +BA_ "GenSigSendType" SG_ 342 CAN_SCAN_INDEX_2LSB_55 0; +BA_ "GenSigCmt" SG_ 342 CAN_SCAN_INDEX_2LSB_55 "CAN_SCAN_INDEX_2LSB_55"; +BA_ "GenMsgSendType" BO_ 335 1; +BA_ "GenMsgILSupport" BO_ 335 1; +BA_ "GenMsgNrOfRepetition" BO_ 335 0; +BA_ "GenMsgCycleTime" BO_ 335 0; +BA_ "NetworkInitialization" BO_ 335 0; +BA_ "GenMsgDelayTime" BO_ 335 0; +BA_ "GenSigVtEn" SG_ 335 CAN_DET_CONFID_AZIMUTH_48 "CAN_DET_CONFID_AZIMUTH_48"; +BA_ "GenSigVtName" SG_ 335 CAN_DET_CONFID_AZIMUTH_48 "CAN_DET_CONFID_AZIMUTH_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_CONFID_AZIMUTH_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_CONFID_AZIMUTH_48 "CAN_DET_CONFID_AZIMUTH_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_SUPER_RES_TARGET_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_SUPER_RES_TARGET_48 "CAN_DET_SUPER_RES_TARGET_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_ND_TARGET_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_ND_TARGET_48 "CAN_DET_ND_TARGET_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_HOST_VEH_CLUTTER_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_HOST_VEH_CLUTTER_48 "CAN_DET_HOST_VEH_CLUTTER_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_VALID_LEVEL_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_VALID_LEVEL_48 "CAN_DET_VALID_LEVEL_48"; +BA_ "GenSigStartValue" SG_ 335 CAN_DET_AZIMUTH_48 0; +BA_ "GenSigSendType" SG_ 335 CAN_DET_AZIMUTH_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_AZIMUTH_48 "CAN_DET_AZIMUTH_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_RANGE_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_RANGE_48 "CAN_DET_RANGE_48"; +BA_ "GenSigStartValue" SG_ 335 CAN_DET_RANGE_RATE_48 0; +BA_ "GenSigSendType" SG_ 335 CAN_DET_RANGE_RATE_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_RANGE_RATE_48 "CAN_DET_RANGE_RATE_48"; +BA_ "GenSigSendType" SG_ 335 CAN_DET_AMPLITUDE_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_DET_AMPLITUDE_48 "CAN_DET_AMPLITUDE_48"; +BA_ "GenSigSendType" SG_ 335 CAN_SCAN_INDEX_2LSB_48 0; +BA_ "GenSigCmt" SG_ 335 CAN_SCAN_INDEX_2LSB_48 "CAN_SCAN_INDEX_2LSB_48"; +BA_ "GenMsgSendType" BO_ 334 1; +BA_ "GenMsgILSupport" BO_ 334 1; +BA_ "GenMsgNrOfRepetition" BO_ 334 0; +BA_ "GenMsgCycleTime" BO_ 334 0; +BA_ "NetworkInitialization" BO_ 334 0; +BA_ "GenMsgDelayTime" BO_ 334 0; +BA_ "GenSigVtEn" SG_ 334 CAN_DET_CONFID_AZIMUTH_47 "CAN_DET_CONFID_AZIMUTH_47"; +BA_ "GenSigVtName" SG_ 334 CAN_DET_CONFID_AZIMUTH_47 "CAN_DET_CONFID_AZIMUTH_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_CONFID_AZIMUTH_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_CONFID_AZIMUTH_47 "CAN_DET_CONFID_AZIMUTH_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_SUPER_RES_TARGET_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_SUPER_RES_TARGET_47 "CAN_DET_SUPER_RES_TARGET_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_ND_TARGET_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_ND_TARGET_47 "CAN_DET_ND_TARGET_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_HOST_VEH_CLUTTER_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_HOST_VEH_CLUTTER_47 "CAN_DET_HOST_VEH_CLUTTER_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_VALID_LEVEL_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_VALID_LEVEL_47 "CAN_DET_VALID_LEVEL_47"; +BA_ "GenSigStartValue" SG_ 334 CAN_DET_AZIMUTH_47 0; +BA_ "GenSigSendType" SG_ 334 CAN_DET_AZIMUTH_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_AZIMUTH_47 "CAN_DET_AZIMUTH_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_RANGE_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_RANGE_47 "CAN_DET_RANGE_47"; +BA_ "GenSigStartValue" SG_ 334 CAN_DET_RANGE_RATE_47 0; +BA_ "GenSigSendType" SG_ 334 CAN_DET_RANGE_RATE_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_RANGE_RATE_47 "CAN_DET_RANGE_RATE_47"; +BA_ "GenSigSendType" SG_ 334 CAN_DET_AMPLITUDE_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_DET_AMPLITUDE_47 "CAN_DET_AMPLITUDE_47"; +BA_ "GenSigSendType" SG_ 334 CAN_SCAN_INDEX_2LSB_47 0; +BA_ "GenSigCmt" SG_ 334 CAN_SCAN_INDEX_2LSB_47 "CAN_SCAN_INDEX_2LSB_47"; +BA_ "GenMsgSendType" BO_ 333 1; +BA_ "GenMsgILSupport" BO_ 333 1; +BA_ "GenMsgNrOfRepetition" BO_ 333 0; +BA_ "GenMsgCycleTime" BO_ 333 0; +BA_ "NetworkInitialization" BO_ 333 0; +BA_ "GenMsgDelayTime" BO_ 333 0; +BA_ "GenSigVtEn" SG_ 333 CAN_DET_CONFID_AZIMUTH_46 "CAN_DET_CONFID_AZIMUTH_46"; +BA_ "GenSigVtName" SG_ 333 CAN_DET_CONFID_AZIMUTH_46 "CAN_DET_CONFID_AZIMUTH_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_CONFID_AZIMUTH_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_CONFID_AZIMUTH_46 "CAN_DET_CONFID_AZIMUTH_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_SUPER_RES_TARGET_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_SUPER_RES_TARGET_46 "CAN_DET_SUPER_RES_TARGET_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_ND_TARGET_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_ND_TARGET_46 "CAN_DET_ND_TARGET_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_HOST_VEH_CLUTTER_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_HOST_VEH_CLUTTER_46 "CAN_DET_HOST_VEH_CLUTTER_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_VALID_LEVEL_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_VALID_LEVEL_46 "CAN_DET_VALID_LEVEL_46"; +BA_ "GenSigStartValue" SG_ 333 CAN_DET_AZIMUTH_46 0; +BA_ "GenSigSendType" SG_ 333 CAN_DET_AZIMUTH_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_AZIMUTH_46 "CAN_DET_AZIMUTH_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_RANGE_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_RANGE_46 "CAN_DET_RANGE_46"; +BA_ "GenSigStartValue" SG_ 333 CAN_DET_RANGE_RATE_46 0; +BA_ "GenSigSendType" SG_ 333 CAN_DET_RANGE_RATE_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_RANGE_RATE_46 "CAN_DET_RANGE_RATE_46"; +BA_ "GenSigSendType" SG_ 333 CAN_DET_AMPLITUDE_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_DET_AMPLITUDE_46 "CAN_DET_AMPLITUDE_46"; +BA_ "GenSigSendType" SG_ 333 CAN_SCAN_INDEX_2LSB_46 0; +BA_ "GenSigCmt" SG_ 333 CAN_SCAN_INDEX_2LSB_46 "CAN_SCAN_INDEX_2LSB_46"; +BA_ "GenMsgSendType" BO_ 332 1; +BA_ "GenMsgILSupport" BO_ 332 1; +BA_ "GenMsgNrOfRepetition" BO_ 332 0; +BA_ "GenMsgCycleTime" BO_ 332 0; +BA_ "NetworkInitialization" BO_ 332 0; +BA_ "GenMsgDelayTime" BO_ 332 0; +BA_ "GenSigVtEn" SG_ 332 CAN_DET_CONFID_AZIMUTH_45 "CAN_DET_CONFID_AZIMUTH_45"; +BA_ "GenSigVtName" SG_ 332 CAN_DET_CONFID_AZIMUTH_45 "CAN_DET_CONFID_AZIMUTH_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_CONFID_AZIMUTH_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_CONFID_AZIMUTH_45 "CAN_DET_CONFID_AZIMUTH_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_SUPER_RES_TARGET_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_SUPER_RES_TARGET_45 "CAN_DET_SUPER_RES_TARGET_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_ND_TARGET_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_ND_TARGET_45 "CAN_DET_ND_TARGET_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_HOST_VEH_CLUTTER_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_HOST_VEH_CLUTTER_45 "CAN_DET_HOST_VEH_CLUTTER_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_VALID_LEVEL_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_VALID_LEVEL_45 "CAN_DET_VALID_LEVEL_45"; +BA_ "GenSigStartValue" SG_ 332 CAN_DET_AZIMUTH_45 0; +BA_ "GenSigSendType" SG_ 332 CAN_DET_AZIMUTH_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_AZIMUTH_45 "CAN_DET_AZIMUTH_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_RANGE_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_RANGE_45 "CAN_DET_RANGE_45"; +BA_ "GenSigStartValue" SG_ 332 CAN_DET_RANGE_RATE_45 0; +BA_ "GenSigSendType" SG_ 332 CAN_DET_RANGE_RATE_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_RANGE_RATE_45 "CAN_DET_RANGE_RATE_45"; +BA_ "GenSigSendType" SG_ 332 CAN_DET_AMPLITUDE_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_DET_AMPLITUDE_45 "CAN_DET_AMPLITUDE_45"; +BA_ "GenSigSendType" SG_ 332 CAN_SCAN_INDEX_2LSB_45 0; +BA_ "GenSigCmt" SG_ 332 CAN_SCAN_INDEX_2LSB_45 "CAN_SCAN_INDEX_2LSB_45"; +BA_ "GenMsgSendType" BO_ 331 1; +BA_ "GenMsgILSupport" BO_ 331 1; +BA_ "GenMsgNrOfRepetition" BO_ 331 0; +BA_ "GenMsgCycleTime" BO_ 331 0; +BA_ "NetworkInitialization" BO_ 331 0; +BA_ "GenMsgDelayTime" BO_ 331 0; +BA_ "GenSigVtEn" SG_ 331 CAN_DET_CONFID_AZIMUTH_44 "CAN_DET_CONFID_AZIMUTH_44"; +BA_ "GenSigVtName" SG_ 331 CAN_DET_CONFID_AZIMUTH_44 "CAN_DET_CONFID_AZIMUTH_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_CONFID_AZIMUTH_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_CONFID_AZIMUTH_44 "CAN_DET_CONFID_AZIMUTH_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_SUPER_RES_TARGET_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_SUPER_RES_TARGET_44 "CAN_DET_SUPER_RES_TARGET_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_ND_TARGET_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_ND_TARGET_44 "CAN_DET_ND_TARGET_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_HOST_VEH_CLUTTER_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_HOST_VEH_CLUTTER_44 "CAN_DET_HOST_VEH_CLUTTER_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_VALID_LEVEL_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_VALID_LEVEL_44 "CAN_DET_VALID_LEVEL_44"; +BA_ "GenSigStartValue" SG_ 331 CAN_DET_AZIMUTH_44 0; +BA_ "GenSigSendType" SG_ 331 CAN_DET_AZIMUTH_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_AZIMUTH_44 "CAN_DET_AZIMUTH_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_RANGE_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_RANGE_44 "CAN_DET_RANGE_44"; +BA_ "GenSigStartValue" SG_ 331 CAN_DET_RANGE_RATE_44 0; +BA_ "GenSigSendType" SG_ 331 CAN_DET_RANGE_RATE_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_RANGE_RATE_44 "CAN_DET_RANGE_RATE_44"; +BA_ "GenSigSendType" SG_ 331 CAN_DET_AMPLITUDE_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_DET_AMPLITUDE_44 "CAN_DET_AMPLITUDE_44"; +BA_ "GenSigSendType" SG_ 331 CAN_SCAN_INDEX_2LSB_44 0; +BA_ "GenSigCmt" SG_ 331 CAN_SCAN_INDEX_2LSB_44 "CAN_SCAN_INDEX_2LSB_44"; +BA_ "GenMsgSendType" BO_ 330 1; +BA_ "GenMsgILSupport" BO_ 330 1; +BA_ "GenMsgNrOfRepetition" BO_ 330 0; +BA_ "GenMsgCycleTime" BO_ 330 0; +BA_ "NetworkInitialization" BO_ 330 0; +BA_ "GenMsgDelayTime" BO_ 330 0; +BA_ "GenSigVtEn" SG_ 330 CAN_DET_CONFID_AZIMUTH_43 "CAN_DET_CONFID_AZIMUTH_43"; +BA_ "GenSigVtName" SG_ 330 CAN_DET_CONFID_AZIMUTH_43 "CAN_DET_CONFID_AZIMUTH_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_CONFID_AZIMUTH_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_CONFID_AZIMUTH_43 "CAN_DET_CONFID_AZIMUTH_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_SUPER_RES_TARGET_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_SUPER_RES_TARGET_43 "CAN_DET_SUPER_RES_TARGET_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_ND_TARGET_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_ND_TARGET_43 "CAN_DET_ND_TARGET_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_HOST_VEH_CLUTTER_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_HOST_VEH_CLUTTER_43 "CAN_DET_HOST_VEH_CLUTTER_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_VALID_LEVEL_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_VALID_LEVEL_43 "CAN_DET_VALID_LEVEL_43"; +BA_ "GenSigStartValue" SG_ 330 CAN_DET_AZIMUTH_43 0; +BA_ "GenSigSendType" SG_ 330 CAN_DET_AZIMUTH_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_AZIMUTH_43 "CAN_DET_AZIMUTH_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_RANGE_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_RANGE_43 "CAN_DET_RANGE_43"; +BA_ "GenSigStartValue" SG_ 330 CAN_DET_RANGE_RATE_43 0; +BA_ "GenSigSendType" SG_ 330 CAN_DET_RANGE_RATE_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_RANGE_RATE_43 "CAN_DET_RANGE_RATE_43"; +BA_ "GenSigSendType" SG_ 330 CAN_DET_AMPLITUDE_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_DET_AMPLITUDE_43 "CAN_DET_AMPLITUDE_43"; +BA_ "GenSigSendType" SG_ 330 CAN_SCAN_INDEX_2LSB_43 0; +BA_ "GenSigCmt" SG_ 330 CAN_SCAN_INDEX_2LSB_43 "CAN_SCAN_INDEX_2LSB_43"; +BA_ "GenMsgSendType" BO_ 329 1; +BA_ "GenMsgILSupport" BO_ 329 1; +BA_ "GenMsgNrOfRepetition" BO_ 329 0; +BA_ "GenMsgCycleTime" BO_ 329 0; +BA_ "NetworkInitialization" BO_ 329 0; +BA_ "GenMsgDelayTime" BO_ 329 0; +BA_ "GenSigVtEn" SG_ 329 CAN_DET_CONFID_AZIMUTH_42 "CAN_DET_CONFID_AZIMUTH_42"; +BA_ "GenSigVtName" SG_ 329 CAN_DET_CONFID_AZIMUTH_42 "CAN_DET_CONFID_AZIMUTH_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_CONFID_AZIMUTH_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_CONFID_AZIMUTH_42 "CAN_DET_CONFID_AZIMUTH_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_SUPER_RES_TARGET_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_SUPER_RES_TARGET_42 "CAN_DET_SUPER_RES_TARGET_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_ND_TARGET_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_ND_TARGET_42 "CAN_DET_ND_TARGET_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_HOST_VEH_CLUTTER_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_HOST_VEH_CLUTTER_42 "CAN_DET_HOST_VEH_CLUTTER_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_VALID_LEVEL_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_VALID_LEVEL_42 "CAN_DET_VALID_LEVEL_42"; +BA_ "GenSigStartValue" SG_ 329 CAN_DET_AZIMUTH_42 0; +BA_ "GenSigSendType" SG_ 329 CAN_DET_AZIMUTH_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_AZIMUTH_42 "CAN_DET_AZIMUTH_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_RANGE_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_RANGE_42 "CAN_DET_RANGE_42"; +BA_ "GenSigStartValue" SG_ 329 CAN_DET_RANGE_RATE_42 0; +BA_ "GenSigSendType" SG_ 329 CAN_DET_RANGE_RATE_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_RANGE_RATE_42 "CAN_DET_RANGE_RATE_42"; +BA_ "GenSigSendType" SG_ 329 CAN_DET_AMPLITUDE_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_DET_AMPLITUDE_42 "CAN_DET_AMPLITUDE_42"; +BA_ "GenSigSendType" SG_ 329 CAN_SCAN_INDEX_2LSB_42 0; +BA_ "GenSigCmt" SG_ 329 CAN_SCAN_INDEX_2LSB_42 "CAN_SCAN_INDEX_2LSB_42"; +BA_ "GenMsgSendType" BO_ 328 1; +BA_ "GenMsgILSupport" BO_ 328 1; +BA_ "GenMsgNrOfRepetition" BO_ 328 0; +BA_ "GenMsgCycleTime" BO_ 328 0; +BA_ "NetworkInitialization" BO_ 328 0; +BA_ "GenMsgDelayTime" BO_ 328 0; +BA_ "GenSigVtEn" SG_ 328 CAN_DET_CONFID_AZIMUTH_41 "CAN_DET_CONFID_AZIMUTH_41"; +BA_ "GenSigVtName" SG_ 328 CAN_DET_CONFID_AZIMUTH_41 "CAN_DET_CONFID_AZIMUTH_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_CONFID_AZIMUTH_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_CONFID_AZIMUTH_41 "CAN_DET_CONFID_AZIMUTH_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_SUPER_RES_TARGET_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_SUPER_RES_TARGET_41 "CAN_DET_SUPER_RES_TARGET_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_ND_TARGET_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_ND_TARGET_41 "CAN_DET_ND_TARGET_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_HOST_VEH_CLUTTER_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_HOST_VEH_CLUTTER_41 "CAN_DET_HOST_VEH_CLUTTER_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_VALID_LEVEL_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_VALID_LEVEL_41 "CAN_DET_VALID_LEVEL_41"; +BA_ "GenSigStartValue" SG_ 328 CAN_DET_AZIMUTH_41 0; +BA_ "GenSigSendType" SG_ 328 CAN_DET_AZIMUTH_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_AZIMUTH_41 "CAN_DET_AZIMUTH_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_RANGE_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_RANGE_41 "CAN_DET_RANGE_41"; +BA_ "GenSigStartValue" SG_ 328 CAN_DET_RANGE_RATE_41 0; +BA_ "GenSigSendType" SG_ 328 CAN_DET_RANGE_RATE_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_RANGE_RATE_41 "CAN_DET_RANGE_RATE_41"; +BA_ "GenSigSendType" SG_ 328 CAN_DET_AMPLITUDE_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_DET_AMPLITUDE_41 "CAN_DET_AMPLITUDE_41"; +BA_ "GenSigSendType" SG_ 328 CAN_SCAN_INDEX_2LSB_41 0; +BA_ "GenSigCmt" SG_ 328 CAN_SCAN_INDEX_2LSB_41 "CAN_SCAN_INDEX_2LSB_41"; +BA_ "GenMsgSendType" BO_ 327 1; +BA_ "GenMsgILSupport" BO_ 327 1; +BA_ "GenMsgNrOfRepetition" BO_ 327 0; +BA_ "GenMsgCycleTime" BO_ 327 0; +BA_ "NetworkInitialization" BO_ 327 0; +BA_ "GenMsgDelayTime" BO_ 327 0; +BA_ "GenSigVtEn" SG_ 327 CAN_DET_CONFID_AZIMUTH_40 "CAN_DET_CONFID_AZIMUTH_40"; +BA_ "GenSigVtName" SG_ 327 CAN_DET_CONFID_AZIMUTH_40 "CAN_DET_CONFID_AZIMUTH_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_CONFID_AZIMUTH_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_CONFID_AZIMUTH_40 "CAN_DET_CONFID_AZIMUTH_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_SUPER_RES_TARGET_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_SUPER_RES_TARGET_40 "CAN_DET_SUPER_RES_TARGET_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_ND_TARGET_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_ND_TARGET_40 "CAN_DET_ND_TARGET_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_HOST_VEH_CLUTTER_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_HOST_VEH_CLUTTER_40 "CAN_DET_HOST_VEH_CLUTTER_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_VALID_LEVEL_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_VALID_LEVEL_40 "CAN_DET_VALID_LEVEL_40"; +BA_ "GenSigStartValue" SG_ 327 CAN_DET_AZIMUTH_40 0; +BA_ "GenSigSendType" SG_ 327 CAN_DET_AZIMUTH_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_AZIMUTH_40 "CAN_DET_AZIMUTH_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_RANGE_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_RANGE_40 "CAN_DET_RANGE_40"; +BA_ "GenSigStartValue" SG_ 327 CAN_DET_RANGE_RATE_40 0; +BA_ "GenSigSendType" SG_ 327 CAN_DET_RANGE_RATE_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_RANGE_RATE_40 "CAN_DET_RANGE_RATE_40"; +BA_ "GenSigSendType" SG_ 327 CAN_DET_AMPLITUDE_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_DET_AMPLITUDE_40 "CAN_DET_AMPLITUDE_40"; +BA_ "GenSigSendType" SG_ 327 CAN_SCAN_INDEX_2LSB_40 0; +BA_ "GenSigCmt" SG_ 327 CAN_SCAN_INDEX_2LSB_40 "CAN_SCAN_INDEX_2LSB_40"; +BA_ "GenMsgSendType" BO_ 325 1; +BA_ "GenMsgILSupport" BO_ 325 1; +BA_ "GenMsgNrOfRepetition" BO_ 325 0; +BA_ "GenMsgCycleTime" BO_ 325 0; +BA_ "NetworkInitialization" BO_ 325 0; +BA_ "GenMsgDelayTime" BO_ 325 0; +BA_ "GenSigVtEn" SG_ 325 CAN_DET_CONFID_AZIMUTH_38 "CAN_DET_CONFID_AZIMUTH_38"; +BA_ "GenSigVtName" SG_ 325 CAN_DET_CONFID_AZIMUTH_38 "CAN_DET_CONFID_AZIMUTH_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_CONFID_AZIMUTH_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_CONFID_AZIMUTH_38 "CAN_DET_CONFID_AZIMUTH_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_SUPER_RES_TARGET_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_SUPER_RES_TARGET_38 "CAN_DET_SUPER_RES_TARGET_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_ND_TARGET_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_ND_TARGET_38 "CAN_DET_ND_TARGET_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_HOST_VEH_CLUTTER_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_HOST_VEH_CLUTTER_38 "CAN_DET_HOST_VEH_CLUTTER_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_VALID_LEVEL_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_VALID_LEVEL_38 "CAN_DET_VALID_LEVEL_38"; +BA_ "GenSigStartValue" SG_ 325 CAN_DET_AZIMUTH_38 0; +BA_ "GenSigSendType" SG_ 325 CAN_DET_AZIMUTH_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_AZIMUTH_38 "CAN_DET_AZIMUTH_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_RANGE_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_RANGE_38 "CAN_DET_RANGE_38"; +BA_ "GenSigStartValue" SG_ 325 CAN_DET_RANGE_RATE_38 0; +BA_ "GenSigSendType" SG_ 325 CAN_DET_RANGE_RATE_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_RANGE_RATE_38 "CAN_DET_RANGE_RATE_38"; +BA_ "GenSigSendType" SG_ 325 CAN_DET_AMPLITUDE_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_DET_AMPLITUDE_38 "CAN_DET_AMPLITUDE_38"; +BA_ "GenSigSendType" SG_ 325 CAN_SCAN_INDEX_2LSB_38 0; +BA_ "GenSigCmt" SG_ 325 CAN_SCAN_INDEX_2LSB_38 "CAN_SCAN_INDEX_2LSB_38"; +BA_ "GenMsgSendType" BO_ 324 1; +BA_ "GenMsgILSupport" BO_ 324 1; +BA_ "GenMsgNrOfRepetition" BO_ 324 0; +BA_ "GenMsgCycleTime" BO_ 324 0; +BA_ "NetworkInitialization" BO_ 324 0; +BA_ "GenMsgDelayTime" BO_ 324 0; +BA_ "GenSigVtEn" SG_ 324 CAN_DET_CONFID_AZIMUTH_37 "CAN_DET_CONFID_AZIMUTH_37"; +BA_ "GenSigVtName" SG_ 324 CAN_DET_CONFID_AZIMUTH_37 "CAN_DET_CONFID_AZIMUTH_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_CONFID_AZIMUTH_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_CONFID_AZIMUTH_37 "CAN_DET_CONFID_AZIMUTH_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_SUPER_RES_TARGET_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_SUPER_RES_TARGET_37 "CAN_DET_SUPER_RES_TARGET_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_ND_TARGET_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_ND_TARGET_37 "CAN_DET_ND_TARGET_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_HOST_VEH_CLUTTER_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_HOST_VEH_CLUTTER_37 "CAN_DET_HOST_VEH_CLUTTER_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_VALID_LEVEL_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_VALID_LEVEL_37 "CAN_DET_VALID_LEVEL_37"; +BA_ "GenSigStartValue" SG_ 324 CAN_DET_AZIMUTH_37 0; +BA_ "GenSigSendType" SG_ 324 CAN_DET_AZIMUTH_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_AZIMUTH_37 "CAN_DET_AZIMUTH_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_RANGE_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_RANGE_37 "CAN_DET_RANGE_37"; +BA_ "GenSigStartValue" SG_ 324 CAN_DET_RANGE_RATE_37 0; +BA_ "GenSigSendType" SG_ 324 CAN_DET_RANGE_RATE_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_RANGE_RATE_37 "CAN_DET_RANGE_RATE_37"; +BA_ "GenSigSendType" SG_ 324 CAN_DET_AMPLITUDE_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_DET_AMPLITUDE_37 "CAN_DET_AMPLITUDE_37"; +BA_ "GenSigSendType" SG_ 324 CAN_SCAN_INDEX_2LSB_37 0; +BA_ "GenSigCmt" SG_ 324 CAN_SCAN_INDEX_2LSB_37 "CAN_SCAN_INDEX_2LSB_37"; +BA_ "GenMsgSendType" BO_ 323 1; +BA_ "GenMsgILSupport" BO_ 323 1; +BA_ "GenMsgNrOfRepetition" BO_ 323 0; +BA_ "GenMsgCycleTime" BO_ 323 0; +BA_ "NetworkInitialization" BO_ 323 0; +BA_ "GenMsgDelayTime" BO_ 323 0; +BA_ "GenSigVtEn" SG_ 323 CAN_DET_CONFID_AZIMUTH_36 "CAN_DET_CONFID_AZIMUTH_36"; +BA_ "GenSigVtName" SG_ 323 CAN_DET_CONFID_AZIMUTH_36 "CAN_DET_CONFID_AZIMUTH_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_CONFID_AZIMUTH_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_CONFID_AZIMUTH_36 "CAN_DET_CONFID_AZIMUTH_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_SUPER_RES_TARGET_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_SUPER_RES_TARGET_36 "CAN_DET_SUPER_RES_TARGET_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_ND_TARGET_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_ND_TARGET_36 "CAN_DET_ND_TARGET_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_HOST_VEH_CLUTTER_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_HOST_VEH_CLUTTER_36 "CAN_DET_HOST_VEH_CLUTTER_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_VALID_LEVEL_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_VALID_LEVEL_36 "CAN_DET_VALID_LEVEL_36"; +BA_ "GenSigStartValue" SG_ 323 CAN_DET_AZIMUTH_36 0; +BA_ "GenSigSendType" SG_ 323 CAN_DET_AZIMUTH_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_AZIMUTH_36 "CAN_DET_AZIMUTH_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_RANGE_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_RANGE_36 "CAN_DET_RANGE_36"; +BA_ "GenSigStartValue" SG_ 323 CAN_DET_RANGE_RATE_36 0; +BA_ "GenSigSendType" SG_ 323 CAN_DET_RANGE_RATE_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_RANGE_RATE_36 "CAN_DET_RANGE_RATE_36"; +BA_ "GenSigSendType" SG_ 323 CAN_DET_AMPLITUDE_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_DET_AMPLITUDE_36 "CAN_DET_AMPLITUDE_36"; +BA_ "GenSigSendType" SG_ 323 CAN_SCAN_INDEX_2LSB_36 0; +BA_ "GenSigCmt" SG_ 323 CAN_SCAN_INDEX_2LSB_36 "CAN_SCAN_INDEX_2LSB_36"; +BA_ "GenMsgSendType" BO_ 322 1; +BA_ "GenMsgILSupport" BO_ 322 1; +BA_ "GenMsgNrOfRepetition" BO_ 322 0; +BA_ "GenMsgCycleTime" BO_ 322 0; +BA_ "NetworkInitialization" BO_ 322 0; +BA_ "GenMsgDelayTime" BO_ 322 0; +BA_ "GenSigVtEn" SG_ 322 CAN_DET_CONFID_AZIMUTH_35 "CAN_DET_CONFID_AZIMUTH_35"; +BA_ "GenSigVtName" SG_ 322 CAN_DET_CONFID_AZIMUTH_35 "CAN_DET_CONFID_AZIMUTH_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_CONFID_AZIMUTH_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_CONFID_AZIMUTH_35 "CAN_DET_CONFID_AZIMUTH_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_SUPER_RES_TARGET_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_SUPER_RES_TARGET_35 "CAN_DET_SUPER_RES_TARGET_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_ND_TARGET_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_ND_TARGET_35 "CAN_DET_ND_TARGET_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_HOST_VEH_CLUTTER_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_HOST_VEH_CLUTTER_35 "CAN_DET_HOST_VEH_CLUTTER_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_VALID_LEVEL_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_VALID_LEVEL_35 "CAN_DET_VALID_LEVEL_35"; +BA_ "GenSigStartValue" SG_ 322 CAN_DET_AZIMUTH_35 0; +BA_ "GenSigSendType" SG_ 322 CAN_DET_AZIMUTH_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_AZIMUTH_35 "CAN_DET_AZIMUTH_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_RANGE_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_RANGE_35 "CAN_DET_RANGE_35"; +BA_ "GenSigStartValue" SG_ 322 CAN_DET_RANGE_RATE_35 0; +BA_ "GenSigSendType" SG_ 322 CAN_DET_RANGE_RATE_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_RANGE_RATE_35 "CAN_DET_RANGE_RATE_35"; +BA_ "GenSigSendType" SG_ 322 CAN_DET_AMPLITUDE_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_DET_AMPLITUDE_35 "CAN_DET_AMPLITUDE_35"; +BA_ "GenSigSendType" SG_ 322 CAN_SCAN_INDEX_2LSB_35 0; +BA_ "GenSigCmt" SG_ 322 CAN_SCAN_INDEX_2LSB_35 "CAN_SCAN_INDEX_2LSB_35"; +BA_ "GenMsgSendType" BO_ 321 1; +BA_ "GenMsgILSupport" BO_ 321 1; +BA_ "GenMsgNrOfRepetition" BO_ 321 0; +BA_ "GenMsgCycleTime" BO_ 321 0; +BA_ "NetworkInitialization" BO_ 321 0; +BA_ "GenMsgDelayTime" BO_ 321 0; +BA_ "GenSigVtEn" SG_ 321 CAN_DET_CONFID_AZIMUTH_34 "CAN_DET_CONFID_AZIMUTH_34"; +BA_ "GenSigVtName" SG_ 321 CAN_DET_CONFID_AZIMUTH_34 "CAN_DET_CONFID_AZIMUTH_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_CONFID_AZIMUTH_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_CONFID_AZIMUTH_34 "CAN_DET_CONFID_AZIMUTH_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_SUPER_RES_TARGET_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_SUPER_RES_TARGET_34 "CAN_DET_SUPER_RES_TARGET_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_ND_TARGET_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_ND_TARGET_34 "CAN_DET_ND_TARGET_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_HOST_VEH_CLUTTER_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_HOST_VEH_CLUTTER_34 "CAN_DET_HOST_VEH_CLUTTER_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_VALID_LEVEL_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_VALID_LEVEL_34 "CAN_DET_VALID_LEVEL_34"; +BA_ "GenSigStartValue" SG_ 321 CAN_DET_AZIMUTH_34 0; +BA_ "GenSigSendType" SG_ 321 CAN_DET_AZIMUTH_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_AZIMUTH_34 "CAN_DET_AZIMUTH_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_RANGE_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_RANGE_34 "CAN_DET_RANGE_34"; +BA_ "GenSigStartValue" SG_ 321 CAN_DET_RANGE_RATE_34 0; +BA_ "GenSigSendType" SG_ 321 CAN_DET_RANGE_RATE_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_RANGE_RATE_34 "CAN_DET_RANGE_RATE_34"; +BA_ "GenSigSendType" SG_ 321 CAN_DET_AMPLITUDE_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_DET_AMPLITUDE_34 "CAN_DET_AMPLITUDE_34"; +BA_ "GenSigSendType" SG_ 321 CAN_SCAN_INDEX_2LSB_34 0; +BA_ "GenSigCmt" SG_ 321 CAN_SCAN_INDEX_2LSB_34 "CAN_SCAN_INDEX_2LSB_34"; +BA_ "GenMsgSendType" BO_ 320 1; +BA_ "GenMsgILSupport" BO_ 320 1; +BA_ "GenMsgNrOfRepetition" BO_ 320 0; +BA_ "GenMsgCycleTime" BO_ 320 0; +BA_ "NetworkInitialization" BO_ 320 0; +BA_ "GenMsgDelayTime" BO_ 320 0; +BA_ "GenSigVtEn" SG_ 320 CAN_DET_CONFID_AZIMUTH_33 "CAN_DET_CONFID_AZIMUTH_33"; +BA_ "GenSigVtName" SG_ 320 CAN_DET_CONFID_AZIMUTH_33 "CAN_DET_CONFID_AZIMUTH_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_CONFID_AZIMUTH_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_CONFID_AZIMUTH_33 "CAN_DET_CONFID_AZIMUTH_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_SUPER_RES_TARGET_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_SUPER_RES_TARGET_33 "CAN_DET_SUPER_RES_TARGET_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_ND_TARGET_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_ND_TARGET_33 "CAN_DET_ND_TARGET_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_HOST_VEH_CLUTTER_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_HOST_VEH_CLUTTER_33 "CAN_DET_HOST_VEH_CLUTTER_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_VALID_LEVEL_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_VALID_LEVEL_33 "CAN_DET_VALID_LEVEL_33"; +BA_ "GenSigStartValue" SG_ 320 CAN_DET_AZIMUTH_33 0; +BA_ "GenSigSendType" SG_ 320 CAN_DET_AZIMUTH_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_AZIMUTH_33 "CAN_DET_AZIMUTH_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_RANGE_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_RANGE_33 "CAN_DET_RANGE_33"; +BA_ "GenSigStartValue" SG_ 320 CAN_DET_RANGE_RATE_33 0; +BA_ "GenSigSendType" SG_ 320 CAN_DET_RANGE_RATE_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_RANGE_RATE_33 "CAN_DET_RANGE_RATE_33"; +BA_ "GenSigSendType" SG_ 320 CAN_DET_AMPLITUDE_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_DET_AMPLITUDE_33 "CAN_DET_AMPLITUDE_33"; +BA_ "GenSigSendType" SG_ 320 CAN_SCAN_INDEX_2LSB_33 0; +BA_ "GenSigCmt" SG_ 320 CAN_SCAN_INDEX_2LSB_33 "CAN_SCAN_INDEX_2LSB_33"; +BA_ "GenMsgSendType" BO_ 319 1; +BA_ "GenMsgILSupport" BO_ 319 1; +BA_ "GenMsgNrOfRepetition" BO_ 319 0; +BA_ "GenMsgCycleTime" BO_ 319 0; +BA_ "NetworkInitialization" BO_ 319 0; +BA_ "GenMsgDelayTime" BO_ 319 0; +BA_ "GenSigVtEn" SG_ 319 CAN_DET_CONFID_AZIMUTH_32 "CAN_DET_CONFID_AZIMUTH_32"; +BA_ "GenSigVtName" SG_ 319 CAN_DET_CONFID_AZIMUTH_32 "CAN_DET_CONFID_AZIMUTH_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_CONFID_AZIMUTH_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_CONFID_AZIMUTH_32 "CAN_DET_CONFID_AZIMUTH_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_SUPER_RES_TARGET_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_SUPER_RES_TARGET_32 "CAN_DET_SUPER_RES_TARGET_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_ND_TARGET_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_ND_TARGET_32 "CAN_DET_ND_TARGET_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_HOST_VEH_CLUTTER_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_HOST_VEH_CLUTTER_32 "CAN_DET_HOST_VEH_CLUTTER_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_VALID_LEVEL_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_VALID_LEVEL_32 "CAN_DET_VALID_LEVEL_32"; +BA_ "GenSigStartValue" SG_ 319 CAN_DET_AZIMUTH_32 0; +BA_ "GenSigSendType" SG_ 319 CAN_DET_AZIMUTH_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_AZIMUTH_32 "CAN_DET_AZIMUTH_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_RANGE_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_RANGE_32 "CAN_DET_RANGE_32"; +BA_ "GenSigStartValue" SG_ 319 CAN_DET_RANGE_RATE_32 0; +BA_ "GenSigSendType" SG_ 319 CAN_DET_RANGE_RATE_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_RANGE_RATE_32 "CAN_DET_RANGE_RATE_32"; +BA_ "GenSigSendType" SG_ 319 CAN_DET_AMPLITUDE_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_DET_AMPLITUDE_32 "CAN_DET_AMPLITUDE_32"; +BA_ "GenSigSendType" SG_ 319 CAN_SCAN_INDEX_2LSB_32 0; +BA_ "GenSigCmt" SG_ 319 CAN_SCAN_INDEX_2LSB_32 "CAN_SCAN_INDEX_2LSB_32"; +BA_ "GenMsgSendType" BO_ 318 1; +BA_ "GenMsgILSupport" BO_ 318 1; +BA_ "GenMsgNrOfRepetition" BO_ 318 0; +BA_ "GenMsgCycleTime" BO_ 318 0; +BA_ "NetworkInitialization" BO_ 318 0; +BA_ "GenMsgDelayTime" BO_ 318 0; +BA_ "GenSigVtEn" SG_ 318 CAN_DET_CONFID_AZIMUTH_31 "CAN_DET_CONFID_AZIMUTH_31"; +BA_ "GenSigVtName" SG_ 318 CAN_DET_CONFID_AZIMUTH_31 "CAN_DET_CONFID_AZIMUTH_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_CONFID_AZIMUTH_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_CONFID_AZIMUTH_31 "CAN_DET_CONFID_AZIMUTH_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_SUPER_RES_TARGET_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_SUPER_RES_TARGET_31 "CAN_DET_SUPER_RES_TARGET_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_ND_TARGET_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_ND_TARGET_31 "CAN_DET_ND_TARGET_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_HOST_VEH_CLUTTER_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_HOST_VEH_CLUTTER_31 "CAN_DET_HOST_VEH_CLUTTER_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_VALID_LEVEL_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_VALID_LEVEL_31 "CAN_DET_VALID_LEVEL_31"; +BA_ "GenSigStartValue" SG_ 318 CAN_DET_AZIMUTH_31 0; +BA_ "GenSigSendType" SG_ 318 CAN_DET_AZIMUTH_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_AZIMUTH_31 "CAN_DET_AZIMUTH_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_RANGE_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_RANGE_31 "CAN_DET_RANGE_31"; +BA_ "GenSigStartValue" SG_ 318 CAN_DET_RANGE_RATE_31 0; +BA_ "GenSigSendType" SG_ 318 CAN_DET_RANGE_RATE_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_RANGE_RATE_31 "CAN_DET_RANGE_RATE_31"; +BA_ "GenSigSendType" SG_ 318 CAN_DET_AMPLITUDE_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_DET_AMPLITUDE_31 "CAN_DET_AMPLITUDE_31"; +BA_ "GenSigSendType" SG_ 318 CAN_SCAN_INDEX_2LSB_31 0; +BA_ "GenSigCmt" SG_ 318 CAN_SCAN_INDEX_2LSB_31 "CAN_SCAN_INDEX_2LSB_31"; +BA_ "GenMsgSendType" BO_ 317 1; +BA_ "GenMsgILSupport" BO_ 317 1; +BA_ "GenMsgNrOfRepetition" BO_ 317 0; +BA_ "GenMsgCycleTime" BO_ 317 0; +BA_ "NetworkInitialization" BO_ 317 0; +BA_ "GenMsgDelayTime" BO_ 317 0; +BA_ "GenSigVtEn" SG_ 317 CAN_DET_CONFID_AZIMUTH_30 "CAN_DET_CONFID_AZIMUTH_30"; +BA_ "GenSigVtName" SG_ 317 CAN_DET_CONFID_AZIMUTH_30 "CAN_DET_CONFID_AZIMUTH_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_CONFID_AZIMUTH_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_CONFID_AZIMUTH_30 "CAN_DET_CONFID_AZIMUTH_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_SUPER_RES_TARGET_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_SUPER_RES_TARGET_30 "CAN_DET_SUPER_RES_TARGET_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_ND_TARGET_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_ND_TARGET_30 "CAN_DET_ND_TARGET_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_HOST_VEH_CLUTTER_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_HOST_VEH_CLUTTER_30 "CAN_DET_HOST_VEH_CLUTTER_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_VALID_LEVEL_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_VALID_LEVEL_30 "CAN_DET_VALID_LEVEL_30"; +BA_ "GenSigStartValue" SG_ 317 CAN_DET_AZIMUTH_30 0; +BA_ "GenSigSendType" SG_ 317 CAN_DET_AZIMUTH_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_AZIMUTH_30 "CAN_DET_AZIMUTH_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_RANGE_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_RANGE_30 "CAN_DET_RANGE_30"; +BA_ "GenSigStartValue" SG_ 317 CAN_DET_RANGE_RATE_30 0; +BA_ "GenSigSendType" SG_ 317 CAN_DET_RANGE_RATE_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_RANGE_RATE_30 "CAN_DET_RANGE_RATE_30"; +BA_ "GenSigSendType" SG_ 317 CAN_DET_AMPLITUDE_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_DET_AMPLITUDE_30 "CAN_DET_AMPLITUDE_30"; +BA_ "GenSigSendType" SG_ 317 CAN_SCAN_INDEX_2LSB_30 0; +BA_ "GenSigCmt" SG_ 317 CAN_SCAN_INDEX_2LSB_30 "CAN_SCAN_INDEX_2LSB_30"; +BA_ "GenMsgSendType" BO_ 316 1; +BA_ "GenMsgILSupport" BO_ 316 1; +BA_ "GenMsgNrOfRepetition" BO_ 316 0; +BA_ "GenMsgCycleTime" BO_ 316 0; +BA_ "NetworkInitialization" BO_ 316 0; +BA_ "GenMsgDelayTime" BO_ 316 0; +BA_ "GenSigVtEn" SG_ 316 CAN_DET_CONFID_AZIMUTH_29 "CAN_DET_CONFID_AZIMUTH_29"; +BA_ "GenSigVtName" SG_ 316 CAN_DET_CONFID_AZIMUTH_29 "CAN_DET_CONFID_AZIMUTH_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_CONFID_AZIMUTH_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_CONFID_AZIMUTH_29 "CAN_DET_CONFID_AZIMUTH_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_SUPER_RES_TARGET_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_SUPER_RES_TARGET_29 "CAN_DET_SUPER_RES_TARGET_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_ND_TARGET_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_ND_TARGET_29 "CAN_DET_ND_TARGET_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_HOST_VEH_CLUTTER_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_HOST_VEH_CLUTTER_29 "CAN_DET_HOST_VEH_CLUTTER_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_VALID_LEVEL_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_VALID_LEVEL_29 "CAN_DET_VALID_LEVEL_29"; +BA_ "GenSigStartValue" SG_ 316 CAN_DET_AZIMUTH_29 0; +BA_ "GenSigSendType" SG_ 316 CAN_DET_AZIMUTH_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_AZIMUTH_29 "CAN_DET_AZIMUTH_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_RANGE_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_RANGE_29 "CAN_DET_RANGE_29"; +BA_ "GenSigStartValue" SG_ 316 CAN_DET_RANGE_RATE_29 0; +BA_ "GenSigSendType" SG_ 316 CAN_DET_RANGE_RATE_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_RANGE_RATE_29 "CAN_DET_RANGE_RATE_29"; +BA_ "GenSigSendType" SG_ 316 CAN_DET_AMPLITUDE_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_DET_AMPLITUDE_29 "CAN_DET_AMPLITUDE_29"; +BA_ "GenSigSendType" SG_ 316 CAN_SCAN_INDEX_2LSB_29 0; +BA_ "GenSigCmt" SG_ 316 CAN_SCAN_INDEX_2LSB_29 "CAN_SCAN_INDEX_2LSB_29"; +BA_ "GenMsgSendType" BO_ 314 1; +BA_ "GenMsgILSupport" BO_ 314 1; +BA_ "GenMsgNrOfRepetition" BO_ 314 0; +BA_ "GenMsgCycleTime" BO_ 314 0; +BA_ "NetworkInitialization" BO_ 314 0; +BA_ "GenMsgDelayTime" BO_ 314 0; +BA_ "GenSigVtEn" SG_ 314 CAN_DET_CONFID_AZIMUTH_27 "CAN_DET_CONFID_AZIMUTH_27"; +BA_ "GenSigVtName" SG_ 314 CAN_DET_CONFID_AZIMUTH_27 "CAN_DET_CONFID_AZIMUTH_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_CONFID_AZIMUTH_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_CONFID_AZIMUTH_27 "CAN_DET_CONFID_AZIMUTH_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_SUPER_RES_TARGET_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_SUPER_RES_TARGET_27 "CAN_DET_SUPER_RES_TARGET_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_ND_TARGET_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_ND_TARGET_27 "CAN_DET_ND_TARGET_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_HOST_VEH_CLUTTER_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_HOST_VEH_CLUTTER_27 "CAN_DET_HOST_VEH_CLUTTER_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_VALID_LEVEL_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_VALID_LEVEL_27 "CAN_DET_VALID_LEVEL_27"; +BA_ "GenSigStartValue" SG_ 314 CAN_DET_AZIMUTH_27 0; +BA_ "GenSigSendType" SG_ 314 CAN_DET_AZIMUTH_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_AZIMUTH_27 "CAN_DET_AZIMUTH_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_RANGE_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_RANGE_27 "CAN_DET_RANGE_27"; +BA_ "GenSigStartValue" SG_ 314 CAN_DET_RANGE_RATE_27 0; +BA_ "GenSigSendType" SG_ 314 CAN_DET_RANGE_RATE_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_RANGE_RATE_27 "CAN_DET_RANGE_RATE_27"; +BA_ "GenSigSendType" SG_ 314 CAN_DET_AMPLITUDE_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_DET_AMPLITUDE_27 "CAN_DET_AMPLITUDE_27"; +BA_ "GenSigSendType" SG_ 314 CAN_SCAN_INDEX_2LSB_27 0; +BA_ "GenSigCmt" SG_ 314 CAN_SCAN_INDEX_2LSB_27 "CAN_SCAN_INDEX_2LSB_27"; +BA_ "GenMsgSendType" BO_ 313 1; +BA_ "GenMsgILSupport" BO_ 313 1; +BA_ "GenMsgNrOfRepetition" BO_ 313 0; +BA_ "GenMsgCycleTime" BO_ 313 0; +BA_ "NetworkInitialization" BO_ 313 0; +BA_ "GenMsgDelayTime" BO_ 313 0; +BA_ "GenSigVtEn" SG_ 313 CAN_DET_CONFID_AZIMUTH_26 "CAN_DET_CONFID_AZIMUTH_26"; +BA_ "GenSigVtName" SG_ 313 CAN_DET_CONFID_AZIMUTH_26 "CAN_DET_CONFID_AZIMUTH_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_CONFID_AZIMUTH_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_CONFID_AZIMUTH_26 "CAN_DET_CONFID_AZIMUTH_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_SUPER_RES_TARGET_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_SUPER_RES_TARGET_26 "CAN_DET_SUPER_RES_TARGET_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_ND_TARGET_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_ND_TARGET_26 "CAN_DET_ND_TARGET_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_HOST_VEH_CLUTTER_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_HOST_VEH_CLUTTER_26 "CAN_DET_HOST_VEH_CLUTTER_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_VALID_LEVEL_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_VALID_LEVEL_26 "CAN_DET_VALID_LEVEL_26"; +BA_ "GenSigStartValue" SG_ 313 CAN_DET_AZIMUTH_26 0; +BA_ "GenSigSendType" SG_ 313 CAN_DET_AZIMUTH_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_AZIMUTH_26 "CAN_DET_AZIMUTH_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_RANGE_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_RANGE_26 "CAN_DET_RANGE_26"; +BA_ "GenSigStartValue" SG_ 313 CAN_DET_RANGE_RATE_26 0; +BA_ "GenSigSendType" SG_ 313 CAN_DET_RANGE_RATE_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_RANGE_RATE_26 "CAN_DET_RANGE_RATE_26"; +BA_ "GenSigSendType" SG_ 313 CAN_DET_AMPLITUDE_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_DET_AMPLITUDE_26 "CAN_DET_AMPLITUDE_26"; +BA_ "GenSigSendType" SG_ 313 CAN_SCAN_INDEX_2LSB_26 0; +BA_ "GenSigCmt" SG_ 313 CAN_SCAN_INDEX_2LSB_26 "CAN_SCAN_INDEX_2LSB_26"; +BA_ "GenMsgSendType" BO_ 312 1; +BA_ "GenMsgILSupport" BO_ 312 1; +BA_ "GenMsgNrOfRepetition" BO_ 312 0; +BA_ "GenMsgCycleTime" BO_ 312 0; +BA_ "NetworkInitialization" BO_ 312 0; +BA_ "GenMsgDelayTime" BO_ 312 0; +BA_ "GenSigVtEn" SG_ 312 CAN_DET_CONFID_AZIMUTH_25 "CAN_DET_CONFID_AZIMUTH_25"; +BA_ "GenSigVtName" SG_ 312 CAN_DET_CONFID_AZIMUTH_25 "CAN_DET_CONFID_AZIMUTH_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_CONFID_AZIMUTH_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_CONFID_AZIMUTH_25 "CAN_DET_CONFID_AZIMUTH_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_SUPER_RES_TARGET_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_SUPER_RES_TARGET_25 "CAN_DET_SUPER_RES_TARGET_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_ND_TARGET_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_ND_TARGET_25 "CAN_DET_ND_TARGET_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_HOST_VEH_CLUTTER_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_HOST_VEH_CLUTTER_25 "CAN_DET_HOST_VEH_CLUTTER_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_VALID_LEVEL_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_VALID_LEVEL_25 "CAN_DET_VALID_LEVEL_25"; +BA_ "GenSigStartValue" SG_ 312 CAN_DET_AZIMUTH_25 0; +BA_ "GenSigSendType" SG_ 312 CAN_DET_AZIMUTH_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_AZIMUTH_25 "CAN_DET_AZIMUTH_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_RANGE_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_RANGE_25 "CAN_DET_RANGE_25"; +BA_ "GenSigStartValue" SG_ 312 CAN_DET_RANGE_RATE_25 0; +BA_ "GenSigSendType" SG_ 312 CAN_DET_RANGE_RATE_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_RANGE_RATE_25 "CAN_DET_RANGE_RATE_25"; +BA_ "GenSigSendType" SG_ 312 CAN_DET_AMPLITUDE_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_DET_AMPLITUDE_25 "CAN_DET_AMPLITUDE_25"; +BA_ "GenSigSendType" SG_ 312 CAN_SCAN_INDEX_2LSB_25 0; +BA_ "GenSigCmt" SG_ 312 CAN_SCAN_INDEX_2LSB_25 "CAN_SCAN_INDEX_2LSB_25"; +BA_ "GenMsgSendType" BO_ 311 1; +BA_ "GenMsgILSupport" BO_ 311 1; +BA_ "GenMsgNrOfRepetition" BO_ 311 0; +BA_ "GenMsgCycleTime" BO_ 311 0; +BA_ "NetworkInitialization" BO_ 311 0; +BA_ "GenMsgDelayTime" BO_ 311 0; +BA_ "GenSigVtEn" SG_ 311 CAN_DET_CONFID_AZIMUTH_24 "CAN_DET_CONFID_AZIMUTH_24"; +BA_ "GenSigVtName" SG_ 311 CAN_DET_CONFID_AZIMUTH_24 "CAN_DET_CONFID_AZIMUTH_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_CONFID_AZIMUTH_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_CONFID_AZIMUTH_24 "CAN_DET_CONFID_AZIMUTH_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_SUPER_RES_TARGET_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_SUPER_RES_TARGET_24 "CAN_DET_SUPER_RES_TARGET_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_ND_TARGET_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_ND_TARGET_24 "CAN_DET_ND_TARGET_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_HOST_VEH_CLUTTER_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_HOST_VEH_CLUTTER_24 "CAN_DET_HOST_VEH_CLUTTER_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_VALID_LEVEL_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_VALID_LEVEL_24 "CAN_DET_VALID_LEVEL_24"; +BA_ "GenSigStartValue" SG_ 311 CAN_DET_AZIMUTH_24 0; +BA_ "GenSigSendType" SG_ 311 CAN_DET_AZIMUTH_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_AZIMUTH_24 "CAN_DET_AZIMUTH_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_RANGE_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_RANGE_24 "CAN_DET_RANGE_24"; +BA_ "GenSigStartValue" SG_ 311 CAN_DET_RANGE_RATE_24 0; +BA_ "GenSigSendType" SG_ 311 CAN_DET_RANGE_RATE_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_RANGE_RATE_24 "CAN_DET_RANGE_RATE_24"; +BA_ "GenSigSendType" SG_ 311 CAN_DET_AMPLITUDE_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_DET_AMPLITUDE_24 "CAN_DET_AMPLITUDE_24"; +BA_ "GenSigSendType" SG_ 311 CAN_SCAN_INDEX_2LSB_24 0; +BA_ "GenSigCmt" SG_ 311 CAN_SCAN_INDEX_2LSB_24 "CAN_SCAN_INDEX_2LSB_24"; +BA_ "GenMsgSendType" BO_ 310 1; +BA_ "GenMsgILSupport" BO_ 310 1; +BA_ "GenMsgNrOfRepetition" BO_ 310 0; +BA_ "GenMsgCycleTime" BO_ 310 0; +BA_ "NetworkInitialization" BO_ 310 0; +BA_ "GenMsgDelayTime" BO_ 310 0; +BA_ "GenSigVtEn" SG_ 310 CAN_DET_CONFID_AZIMUTH_23 "CAN_DET_CONFID_AZIMUTH_23"; +BA_ "GenSigVtName" SG_ 310 CAN_DET_CONFID_AZIMUTH_23 "CAN_DET_CONFID_AZIMUTH_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_CONFID_AZIMUTH_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_CONFID_AZIMUTH_23 "CAN_DET_CONFID_AZIMUTH_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_SUPER_RES_TARGET_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_SUPER_RES_TARGET_23 "CAN_DET_SUPER_RES_TARGET_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_ND_TARGET_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_ND_TARGET_23 "CAN_DET_ND_TARGET_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_HOST_VEH_CLUTTER_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_HOST_VEH_CLUTTER_23 "CAN_DET_HOST_VEH_CLUTTER_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_VALID_LEVEL_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_VALID_LEVEL_23 "CAN_DET_VALID_LEVEL_23"; +BA_ "GenSigStartValue" SG_ 310 CAN_DET_AZIMUTH_23 0; +BA_ "GenSigSendType" SG_ 310 CAN_DET_AZIMUTH_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_AZIMUTH_23 "CAN_DET_AZIMUTH_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_RANGE_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_RANGE_23 "CAN_DET_RANGE_23"; +BA_ "GenSigStartValue" SG_ 310 CAN_DET_RANGE_RATE_23 0; +BA_ "GenSigSendType" SG_ 310 CAN_DET_RANGE_RATE_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_RANGE_RATE_23 "CAN_DET_RANGE_RATE_23"; +BA_ "GenSigSendType" SG_ 310 CAN_DET_AMPLITUDE_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_DET_AMPLITUDE_23 "CAN_DET_AMPLITUDE_23"; +BA_ "GenSigSendType" SG_ 310 CAN_SCAN_INDEX_2LSB_23 0; +BA_ "GenSigCmt" SG_ 310 CAN_SCAN_INDEX_2LSB_23 "CAN_SCAN_INDEX_2LSB_23"; +EOF + +build_ba "22" +build_ba "21" +build_ba "20" +build_ba "19" +build_ba "18" + +cat <> ${OUT_FILENAME} +BA_ "GenMsgSendType" BO_ 341 1; +BA_ "GenMsgILSupport" BO_ 341 1; +BA_ "GenMsgNrOfRepetition" BO_ 341 0; +BA_ "GenMsgCycleTime" BO_ 341 0; +BA_ "NetworkInitialization" BO_ 341 0; +BA_ "GenMsgDelayTime" BO_ 341 0; +BA_ "GenSigVtEn" SG_ 341 CAN_DET_CONFID_AZIMUTH_54 "CAN_DET_CONFID_AZIMUTH_54"; +BA_ "GenSigVtName" SG_ 341 CAN_DET_CONFID_AZIMUTH_54 "CAN_DET_CONFID_AZIMUTH_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_CONFID_AZIMUTH_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_CONFID_AZIMUTH_54 "CAN_DET_CONFID_AZIMUTH_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_SUPER_RES_TARGET_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_SUPER_RES_TARGET_54 "CAN_DET_SUPER_RES_TARGET_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_ND_TARGET_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_ND_TARGET_54 "CAN_DET_ND_TARGET_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_HOST_VEH_CLUTTER_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_HOST_VEH_CLUTTER_54 "CAN_DET_HOST_VEH_CLUTTER_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_VALID_LEVEL_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_VALID_LEVEL_54 "CAN_DET_VALID_LEVEL_54"; +BA_ "GenSigStartValue" SG_ 341 CAN_DET_AZIMUTH_54 0; +BA_ "GenSigSendType" SG_ 341 CAN_DET_AZIMUTH_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_AZIMUTH_54 "CAN_DET_AZIMUTH_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_RANGE_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_RANGE_54 "CAN_DET_RANGE_54"; +BA_ "GenSigStartValue" SG_ 341 CAN_DET_RANGE_RATE_54 0; +BA_ "GenSigSendType" SG_ 341 CAN_DET_RANGE_RATE_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_RANGE_RATE_54 "CAN_DET_RANGE_RATE_54"; +BA_ "GenSigSendType" SG_ 341 CAN_DET_AMPLITUDE_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_DET_AMPLITUDE_54 "CAN_DET_AMPLITUDE_54"; +BA_ "GenSigSendType" SG_ 341 CAN_SCAN_INDEX_2LSB_54 0; +BA_ "GenSigCmt" SG_ 341 CAN_SCAN_INDEX_2LSB_54 "CAN_SCAN_INDEX_2LSB_54"; +BA_ "GenMsgSendType" BO_ 340 1; +BA_ "GenMsgILSupport" BO_ 340 1; +BA_ "GenMsgNrOfRepetition" BO_ 340 0; +BA_ "GenMsgCycleTime" BO_ 340 0; +BA_ "NetworkInitialization" BO_ 340 0; +BA_ "GenMsgDelayTime" BO_ 340 0; +BA_ "GenSigVtEn" SG_ 340 CAN_DET_CONFID_AZIMUTH_53 "CAN_DET_CONFID_AZIMUTH_53"; +BA_ "GenSigVtName" SG_ 340 CAN_DET_CONFID_AZIMUTH_53 "CAN_DET_CONFID_AZIMUTH_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_CONFID_AZIMUTH_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_CONFID_AZIMUTH_53 "CAN_DET_CONFID_AZIMUTH_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_SUPER_RES_TARGET_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_SUPER_RES_TARGET_53 "CAN_DET_SUPER_RES_TARGET_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_ND_TARGET_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_ND_TARGET_53 "CAN_DET_ND_TARGET_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_HOST_VEH_CLUTTER_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_HOST_VEH_CLUTTER_53 "CAN_DET_HOST_VEH_CLUTTER_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_VALID_LEVEL_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_VALID_LEVEL_53 "CAN_DET_VALID_LEVEL_53"; +BA_ "GenSigStartValue" SG_ 340 CAN_DET_AZIMUTH_53 0; +BA_ "GenSigSendType" SG_ 340 CAN_DET_AZIMUTH_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_AZIMUTH_53 "CAN_DET_AZIMUTH_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_RANGE_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_RANGE_53 "CAN_DET_RANGE_53"; +BA_ "GenSigStartValue" SG_ 340 CAN_DET_RANGE_RATE_53 0; +BA_ "GenSigSendType" SG_ 340 CAN_DET_RANGE_RATE_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_RANGE_RATE_53 "CAN_DET_RANGE_RATE_53"; +BA_ "GenSigSendType" SG_ 340 CAN_DET_AMPLITUDE_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_DET_AMPLITUDE_53 "CAN_DET_AMPLITUDE_53"; +BA_ "GenSigSendType" SG_ 340 CAN_SCAN_INDEX_2LSB_53 0; +BA_ "GenSigCmt" SG_ 340 CAN_SCAN_INDEX_2LSB_53 "CAN_SCAN_INDEX_2LSB_53"; +BA_ "GenMsgSendType" BO_ 339 1; +BA_ "GenMsgILSupport" BO_ 339 1; +BA_ "GenMsgNrOfRepetition" BO_ 339 0; +BA_ "GenMsgCycleTime" BO_ 339 0; +BA_ "NetworkInitialization" BO_ 339 0; +BA_ "GenMsgDelayTime" BO_ 339 0; +BA_ "GenSigVtEn" SG_ 339 CAN_DET_CONFID_AZIMUTH_52 "CAN_DET_CONFID_AZIMUTH_52"; +BA_ "GenSigVtName" SG_ 339 CAN_DET_CONFID_AZIMUTH_52 "CAN_DET_CONFID_AZIMUTH_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_CONFID_AZIMUTH_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_CONFID_AZIMUTH_52 "CAN_DET_CONFID_AZIMUTH_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_SUPER_RES_TARGET_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_SUPER_RES_TARGET_52 "CAN_DET_SUPER_RES_TARGET_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_ND_TARGET_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_ND_TARGET_52 "CAN_DET_ND_TARGET_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_HOST_VEH_CLUTTER_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_HOST_VEH_CLUTTER_52 "CAN_DET_HOST_VEH_CLUTTER_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_VALID_LEVEL_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_VALID_LEVEL_52 "CAN_DET_VALID_LEVEL_52"; +BA_ "GenSigStartValue" SG_ 339 CAN_DET_AZIMUTH_52 0; +BA_ "GenSigSendType" SG_ 339 CAN_DET_AZIMUTH_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_AZIMUTH_52 "CAN_DET_AZIMUTH_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_RANGE_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_RANGE_52 "CAN_DET_RANGE_52"; +BA_ "GenSigStartValue" SG_ 339 CAN_DET_RANGE_RATE_52 0; +BA_ "GenSigSendType" SG_ 339 CAN_DET_RANGE_RATE_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_RANGE_RATE_52 "CAN_DET_RANGE_RATE_52"; +BA_ "GenSigSendType" SG_ 339 CAN_DET_AMPLITUDE_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_DET_AMPLITUDE_52 "CAN_DET_AMPLITUDE_52"; +BA_ "GenSigSendType" SG_ 339 CAN_SCAN_INDEX_2LSB_52 0; +BA_ "GenSigCmt" SG_ 339 CAN_SCAN_INDEX_2LSB_52 "CAN_SCAN_INDEX_2LSB_52"; +BA_ "GenMsgSendType" BO_ 338 1; +BA_ "GenMsgILSupport" BO_ 338 1; +BA_ "GenMsgNrOfRepetition" BO_ 338 0; +BA_ "GenMsgCycleTime" BO_ 338 0; +BA_ "NetworkInitialization" BO_ 338 0; +BA_ "GenMsgDelayTime" BO_ 338 0; +BA_ "GenSigVtEn" SG_ 338 CAN_DET_CONFID_AZIMUTH_51 "CAN_DET_CONFID_AZIMUTH_51"; +BA_ "GenSigVtName" SG_ 338 CAN_DET_CONFID_AZIMUTH_51 "CAN_DET_CONFID_AZIMUTH_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_CONFID_AZIMUTH_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_CONFID_AZIMUTH_51 "CAN_DET_CONFID_AZIMUTH_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_SUPER_RES_TARGET_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_SUPER_RES_TARGET_51 "CAN_DET_SUPER_RES_TARGET_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_ND_TARGET_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_ND_TARGET_51 "CAN_DET_ND_TARGET_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_HOST_VEH_CLUTTER_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_HOST_VEH_CLUTTER_51 "CAN_DET_HOST_VEH_CLUTTER_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_VALID_LEVEL_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_VALID_LEVEL_51 "CAN_DET_VALID_LEVEL_51"; +BA_ "GenSigStartValue" SG_ 338 CAN_DET_AZIMUTH_51 0; +BA_ "GenSigSendType" SG_ 338 CAN_DET_AZIMUTH_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_AZIMUTH_51 "CAN_DET_AZIMUTH_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_RANGE_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_RANGE_51 "CAN_DET_RANGE_51"; +BA_ "GenSigStartValue" SG_ 338 CAN_DET_RANGE_RATE_51 0; +BA_ "GenSigSendType" SG_ 338 CAN_DET_RANGE_RATE_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_RANGE_RATE_51 "CAN_DET_RANGE_RATE_51"; +BA_ "GenSigSendType" SG_ 338 CAN_DET_AMPLITUDE_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_DET_AMPLITUDE_51 "CAN_DET_AMPLITUDE_51"; +BA_ "GenSigSendType" SG_ 338 CAN_SCAN_INDEX_2LSB_51 0; +BA_ "GenSigCmt" SG_ 338 CAN_SCAN_INDEX_2LSB_51 "CAN_SCAN_INDEX_2LSB_51"; +BA_ "GenMsgSendType" BO_ 337 1; +BA_ "GenMsgILSupport" BO_ 337 1; +BA_ "GenMsgNrOfRepetition" BO_ 337 0; +BA_ "GenMsgCycleTime" BO_ 337 0; +BA_ "NetworkInitialization" BO_ 337 0; +BA_ "GenMsgDelayTime" BO_ 337 0; +BA_ "GenSigVtEn" SG_ 337 CAN_DET_CONFID_AZIMUTH_50 "CAN_DET_CONFID_AZIMUTH_50"; +BA_ "GenSigVtName" SG_ 337 CAN_DET_CONFID_AZIMUTH_50 "CAN_DET_CONFID_AZIMUTH_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_CONFID_AZIMUTH_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_CONFID_AZIMUTH_50 "CAN_DET_CONFID_AZIMUTH_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_SUPER_RES_TARGET_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_SUPER_RES_TARGET_50 "CAN_DET_SUPER_RES_TARGET_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_ND_TARGET_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_ND_TARGET_50 "CAN_DET_ND_TARGET_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_HOST_VEH_CLUTTER_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_HOST_VEH_CLUTTER_50 "CAN_DET_HOST_VEH_CLUTTER_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_VALID_LEVEL_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_VALID_LEVEL_50 "CAN_DET_VALID_LEVEL_50"; +BA_ "GenSigStartValue" SG_ 337 CAN_DET_AZIMUTH_50 0; +BA_ "GenSigSendType" SG_ 337 CAN_DET_AZIMUTH_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_AZIMUTH_50 "CAN_DET_AZIMUTH_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_RANGE_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_RANGE_50 "CAN_DET_RANGE_50"; +BA_ "GenSigStartValue" SG_ 337 CAN_DET_RANGE_RATE_50 0; +BA_ "GenSigSendType" SG_ 337 CAN_DET_RANGE_RATE_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_RANGE_RATE_50 "CAN_DET_RANGE_RATE_50"; +BA_ "GenSigSendType" SG_ 337 CAN_DET_AMPLITUDE_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_DET_AMPLITUDE_50 "CAN_DET_AMPLITUDE_50"; +BA_ "GenSigSendType" SG_ 337 CAN_SCAN_INDEX_2LSB_50 0; +BA_ "GenSigCmt" SG_ 337 CAN_SCAN_INDEX_2LSB_50 "CAN_SCAN_INDEX_2LSB_50"; +BA_ "GenMsgSendType" BO_ 336 1; +BA_ "GenMsgILSupport" BO_ 336 1; +BA_ "GenMsgNrOfRepetition" BO_ 336 0; +BA_ "GenMsgCycleTime" BO_ 336 0; +BA_ "NetworkInitialization" BO_ 336 0; +BA_ "GenMsgDelayTime" BO_ 336 0; +BA_ "GenSigVtEn" SG_ 336 CAN_DET_CONFID_AZIMUTH_49 "CAN_DET_CONFID_AZIMUTH_49"; +BA_ "GenSigVtName" SG_ 336 CAN_DET_CONFID_AZIMUTH_49 "CAN_DET_CONFID_AZIMUTH_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_CONFID_AZIMUTH_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_CONFID_AZIMUTH_49 "CAN_DET_CONFID_AZIMUTH_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_SUPER_RES_TARGET_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_SUPER_RES_TARGET_49 "CAN_DET_SUPER_RES_TARGET_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_ND_TARGET_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_ND_TARGET_49 "CAN_DET_ND_TARGET_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_HOST_VEH_CLUTTER_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_HOST_VEH_CLUTTER_49 "CAN_DET_HOST_VEH_CLUTTER_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_VALID_LEVEL_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_VALID_LEVEL_49 "CAN_DET_VALID_LEVEL_49"; +BA_ "GenSigStartValue" SG_ 336 CAN_DET_AZIMUTH_49 0; +BA_ "GenSigSendType" SG_ 336 CAN_DET_AZIMUTH_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_AZIMUTH_49 "CAN_DET_AZIMUTH_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_RANGE_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_RANGE_49 "CAN_DET_RANGE_49"; +BA_ "GenSigStartValue" SG_ 336 CAN_DET_RANGE_RATE_49 0; +BA_ "GenSigSendType" SG_ 336 CAN_DET_RANGE_RATE_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_RANGE_RATE_49 "CAN_DET_RANGE_RATE_49"; +BA_ "GenSigSendType" SG_ 336 CAN_DET_AMPLITUDE_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_DET_AMPLITUDE_49 "CAN_DET_AMPLITUDE_49"; +BA_ "GenSigSendType" SG_ 336 CAN_SCAN_INDEX_2LSB_49 0; +BA_ "GenSigCmt" SG_ 336 CAN_SCAN_INDEX_2LSB_49 "CAN_SCAN_INDEX_2LSB_49"; +BA_ "GenMsgSendType" BO_ 326 1; +BA_ "GenMsgILSupport" BO_ 326 1; +BA_ "GenMsgNrOfRepetition" BO_ 326 0; +BA_ "GenMsgCycleTime" BO_ 326 0; +BA_ "NetworkInitialization" BO_ 326 0; +BA_ "GenMsgDelayTime" BO_ 326 0; +BA_ "GenSigVtEn" SG_ 326 CAN_DET_CONFID_AZIMUTH_39 "CAN_DET_CONFID_AZIMUTH_39"; +BA_ "GenSigVtName" SG_ 326 CAN_DET_CONFID_AZIMUTH_39 "CAN_DET_CONFID_AZIMUTH_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_CONFID_AZIMUTH_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_CONFID_AZIMUTH_39 "CAN_DET_CONFID_AZIMUTH_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_SUPER_RES_TARGET_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_SUPER_RES_TARGET_39 "CAN_DET_SUPER_RES_TARGET_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_ND_TARGET_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_ND_TARGET_39 "CAN_DET_ND_TARGET_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_HOST_VEH_CLUTTER_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_HOST_VEH_CLUTTER_39 "CAN_DET_HOST_VEH_CLUTTER_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_VALID_LEVEL_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_VALID_LEVEL_39 "CAN_DET_VALID_LEVEL_39"; +BA_ "GenSigStartValue" SG_ 326 CAN_DET_AZIMUTH_39 0; +BA_ "GenSigSendType" SG_ 326 CAN_DET_AZIMUTH_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_AZIMUTH_39 "CAN_DET_AZIMUTH_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_RANGE_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_RANGE_39 "CAN_DET_RANGE_39"; +BA_ "GenSigStartValue" SG_ 326 CAN_DET_RANGE_RATE_39 0; +BA_ "GenSigSendType" SG_ 326 CAN_DET_RANGE_RATE_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_RANGE_RATE_39 "CAN_DET_RANGE_RATE_39"; +BA_ "GenSigSendType" SG_ 326 CAN_DET_AMPLITUDE_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_DET_AMPLITUDE_39 "CAN_DET_AMPLITUDE_39"; +BA_ "GenSigSendType" SG_ 326 CAN_SCAN_INDEX_2LSB_39 0; +BA_ "GenSigCmt" SG_ 326 CAN_SCAN_INDEX_2LSB_39 "CAN_SCAN_INDEX_2LSB_39"; +BA_ "GenMsgSendType" BO_ 315 1; +BA_ "GenMsgILSupport" BO_ 315 1; +BA_ "GenMsgNrOfRepetition" BO_ 315 0; +BA_ "GenMsgCycleTime" BO_ 315 0; +BA_ "NetworkInitialization" BO_ 315 0; +BA_ "GenMsgDelayTime" BO_ 315 0; +BA_ "GenSigVtEn" SG_ 315 CAN_DET_CONFID_AZIMUTH_28 "CAN_DET_CONFID_AZIMUTH_28"; +BA_ "GenSigVtName" SG_ 315 CAN_DET_CONFID_AZIMUTH_28 "CAN_DET_CONFID_AZIMUTH_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_CONFID_AZIMUTH_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_CONFID_AZIMUTH_28 "CAN_DET_CONFID_AZIMUTH_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_SUPER_RES_TARGET_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_SUPER_RES_TARGET_28 "CAN_DET_SUPER_RES_TARGET_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_ND_TARGET_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_ND_TARGET_28 "CAN_DET_ND_TARGET_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_HOST_VEH_CLUTTER_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_HOST_VEH_CLUTTER_28 "CAN_DET_HOST_VEH_CLUTTER_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_VALID_LEVEL_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_VALID_LEVEL_28 "CAN_DET_VALID_LEVEL_28"; +BA_ "GenSigStartValue" SG_ 315 CAN_DET_AZIMUTH_28 0; +BA_ "GenSigSendType" SG_ 315 CAN_DET_AZIMUTH_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_AZIMUTH_28 "CAN_DET_AZIMUTH_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_RANGE_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_RANGE_28 "CAN_DET_RANGE_28"; +BA_ "GenSigStartValue" SG_ 315 CAN_DET_RANGE_RATE_28 0; +BA_ "GenSigSendType" SG_ 315 CAN_DET_RANGE_RATE_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_RANGE_RATE_28 "CAN_DET_RANGE_RATE_28"; +BA_ "GenSigSendType" SG_ 315 CAN_DET_AMPLITUDE_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_DET_AMPLITUDE_28 "CAN_DET_AMPLITUDE_28"; +BA_ "GenSigSendType" SG_ 315 CAN_SCAN_INDEX_2LSB_28 0; +BA_ "GenSigCmt" SG_ 315 CAN_SCAN_INDEX_2LSB_28 "CAN_SCAN_INDEX_2LSB_28"; +EOF + +build_ba "17" +build_ba "16" +build_ba "15" +build_ba "14" +build_ba "13" +build_ba "12" +build_ba "11" +build_ba "10" +build_ba "09" +build_ba "08" +build_ba "07" +build_ba "06" +build_ba "05" +build_ba "03" +build_ba "02" + +cat <> ${OUT_FILENAME} +BA_ "GenMsgSendType" BO_ 256 1; +BA_ "GenMsgILSupport" BO_ 256 1; +BA_ "GenMsgNrOfRepetition" BO_ 256 0; +BA_ "NetworkInitialization" BO_ 256 0; +BA_ "GenSigCmt" SG_ 256 CAN_PCAN_MINOR_MRR "CAN_PCAN_MINOR_MRR"; +BA_ "GenSigSendType" SG_ 256 CAN_PCAN_MINOR_MRR 0; +BA_ "GenSigCmt" SG_ 256 CAN_PCAN_MAJOR_MRR "CAN_PCAN_MAJOR_MRR"; +BA_ "GenSigSendType" SG_ 256 CAN_PCAN_MAJOR_MRR 0; +BA_ "GenMsgCycleTime" BO_ 257 30; +BA_ "GenMsgSendType" BO_ 257 0; +BA_ "GenMsgILSupport" BO_ 257 1; +BA_ "GenMsgNrOfRepetition" BO_ 257 0; +BA_ "NetworkInitialization" BO_ 257 0; +BA_ "GenSigCmt" SG_ 257 CAN_INTERFERENCE_TYPE "CAN_INTERFERENCE_TYPE"; +BA_ "GenSigVtEn" SG_ 257 CAN_INTERFERENCE_TYPE "CAN_INTERFERENCE_TYPE"; +BA_ "GenSigVtName" SG_ 257 CAN_INTERFERENCE_TYPE "CAN_INTERFERENCE_TYPE"; +BA_ "GenSigVtName" SG_ 257 CAN_RECOMMEND_UNCONVERGE "CAN_RECOMMEND_UNCONVERGE"; +BA_ "GenSigVtEn" SG_ 257 CAN_RECOMMEND_UNCONVERGE "CAN_RECOMMEND_UNCONVERGE"; +BA_ "GenSigCmt" SG_ 257 CAN_RECOMMEND_UNCONVERGE "CAN_RECOMMEND_UNCONVERGE"; +BA_ "GenSigStartValue" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL 0; +BA_ "GenSigSendType" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL 0; +BA_ "GenSigCmt" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL "CAN_BLOCKAGE_SIDELOBE_FILTER_VAL"; +BA_ "GenSigVtEn" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL "CAN_BLOCKAGE_SIDELOBE_FILTER_VAL"; +BA_ "GenSigVtName" SG_ 257 CAN_BLOCKAGE_SIDELOBE_FILTER_VAL "CAN_BLOCKAGE_SIDELOBE_FILTER_VAL"; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_ALIGN_INCOMPLETE "CAN_RADAR_ALIGN_INCOMPLETE"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_ALIGN_INCOMPLETE "CAN_RADAR_ALIGN_INCOMPLETE"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_ALIGN_INCOMPLETE "CAN_RADAR_ALIGN_INCOMPLETE"; +BA_ "GenSigCmt" SG_ 257 CAN_BLOCKAGE_SIDELOBE "CAN_BLOCKAGE_SIDELOBE"; +BA_ "GenSigVtEn" SG_ 257 CAN_BLOCKAGE_SIDELOBE "CAN_BLOCKAGE_SIDELOBE"; +BA_ "GenSigVtName" SG_ 257 CAN_BLOCKAGE_SIDELOBE "CAN_BLOCKAGE_SIDELOBE"; +BA_ "GenSigSendType" SG_ 257 CAN_BLOCKAGE_SIDELOBE 0; +BA_ "GenSigCmt" SG_ 257 CAN_BLOCKAGE_MNR "CAN_BLOCKAGE_MNR"; +BA_ "GenSigVtEn" SG_ 257 CAN_BLOCKAGE_MNR "CAN_BLOCKAGE_MNR"; +BA_ "GenSigVtName" SG_ 257 CAN_BLOCKAGE_MNR "CAN_BLOCKAGE_MNR"; +BA_ "GenSigSendType" SG_ 257 CAN_BLOCKAGE_MNR 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_EXT_COND_NOK "CAN_RADAR_EXT_COND_NOK"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_EXT_COND_NOK "CAN_RADAR_EXT_COND_NOK"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_EXT_COND_NOK "CAN_RADAR_EXT_COND_NOK"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_EXT_COND_NOK 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_ALIGN_OUT_RANGE "CAN_RADAR_ALIGN_OUT_RANGE"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_ALIGN_OUT_RANGE "CAN_RADAR_ALIGN_OUT_RANGE"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_ALIGN_OUT_RANGE "CAN_RADAR_ALIGN_OUT_RANGE"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_ALIGN_OUT_RANGE 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_ALIGN_NOT_START "CAN_RADAR_ALIGN_NOT_START"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_ALIGN_NOT_START "CAN_RADAR_ALIGN_NOT_START"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_ALIGN_NOT_START "CAN_RADAR_ALIGN_NOT_START"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_ALIGN_NOT_START 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_OVERHEAT_ERROR "CAN_RADAR_OVERHEAT_ERROR"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_OVERHEAT_ERROR "CAN_RADAR_OVERHEAT_ERROR"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_OVERHEAT_ERROR "CAN_RADAR_OVERHEAT_ERROR"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_OVERHEAT_ERROR 0; +BA_ "GenSigCmt" SG_ 257 CAN_RADAR_NOT_OP "CAN_RADAR_NOT_OP"; +BA_ "GenSigVtEn" SG_ 257 CAN_RADAR_NOT_OP "CAN_RADAR_NOT_OP"; +BA_ "GenSigVtName" SG_ 257 CAN_RADAR_NOT_OP "CAN_RADAR_NOT_OP"; +BA_ "GenSigSendType" SG_ 257 CAN_RADAR_NOT_OP 0; +BA_ "GenSigCmt" SG_ 257 CAN_XCVR_OPERATIONAL "CAN_XCVR_OPERATIONAL"; +BA_ "GenSigVtEn" SG_ 257 CAN_XCVR_OPERATIONAL "CAN_XCVR_OPERATIONAL"; +BA_ "GenSigVtName" SG_ 257 CAN_XCVR_OPERATIONAL "CAN_XCVR_OPERATIONAL"; +BA_ "GenSigSendType" SG_ 257 CAN_XCVR_OPERATIONAL 0; +EOF + +build_ba "01" + +cat <> ${OUT_FILENAME} +BA_DEF_DEF_ "CrossOver_InfoCAN" "No"; +BA_DEF_DEF_ "CrossOver_LIN" "No"; +BA_DEF_DEF_ "UsedOnPgmDBC" "Yes"; +BA_DEF_DEF_ "ContentDependant" "No"; +BA_DEF_DEF_ "GenSigTimeoutTime_RCM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_GWM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_OCS" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_ABS_ESC" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_CCM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_IPMA" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_TSTR" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_SCCM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_PSCM" 0; +BA_DEF_DEF_ "GenSigTimeoutTime__delete" 0; +BA_DEF_DEF_ "GenSigTimeoutTime_Generic_BCM" 0; +BA_DEF_DEF_ "NmMessage" "No"; +BA_DEF_DEF_ "DiagResponse" "No"; +BA_DEF_DEF_ "DiagRequest" "No"; +BA_DEF_DEF_ "TpTxIndex" 0; +BA_DEF_DEF_ "DiagState" "No"; +BA_DEF_DEF_ "TpApplType" ""; +BA_DEF_DEF_ "NmAsrMessage" "No"; +BA_DEF_DEF_ "Mulitplexer" "No"; +BA_DEF_DEF_ "ConfiguredTransmitter" "No"; +BA_DEF_DEF_ "EventRateOfChange" 10000; +BA_DEF_DEF_ "GenMsgHandlingTypeDoc" ""; +BA_DEF_DEF_ "GenMsgHandlingTypeCode" ""; +BA_DEF_DEF_ "GenMsgMarked" ""; +BA_DEF_DEF_ "GenSigMarked" ""; +BA_DEF_DEF_ "GenSigVtIndex" ""; +BA_DEF_DEF_ "GenSigVtName" ""; +BA_DEF_DEF_ "GenSigVtEn" ""; +BA_DEF_DEF_ "GenSigSNA" ""; +BA_DEF_DEF_ "GenSigCmt" ""; +BA_DEF_DEF_ "GenMsgCmt" ""; +BA_DEF_DEF_ "GenSigSendType" "NoSigSendType"; +BA_DEF_DEF_ "GenSigInactiveValue" 0; +BA_DEF_DEF_ "GenSigMissingSourceValue" 0; +BA_DEF_DEF_ "WakeupSignal" "No"; +BA_DEF_DEF_ "GenSigStartValue" 0; +BA_DEF_DEF_ "GenMsgILSupport" "Yes"; +BA_DEF_DEF_ "NetworkInitializationCommand" "No"; +BA_DEF_DEF_ "GenMsgSendType" "NoMsgSendType"; +BA_DEF_DEF_ "GenMsgCycleTime" 0; +BA_DEF_DEF_ "GenMsgCycleTimeFast" 0; +BA_DEF_DEF_ "GenMsgDelayTime" 0; +BA_DEF_DEF_ "GenMsgNrOfRepetition" 0; +BA_DEF_DEF_ "GenMsgStartDelayTime" 0; +BA_DEF_DEF_ "NetworkInitialization" "No"; +BA_DEF_DEF_ "MessageGateway" "No"; +BA_DEF_DEF_ "ILUsed" "Yes"; +BA_DEF_DEF_ "NetworkInitializationUsed" "No"; +BA_DEF_DEF_ "PowerType" "Switched"; +BA_DEF_DEF_ "NodeStartUpTime" 250; +BA_DEF_DEF_ "NodeWakeUpTime" 10; +BA_DEF_DEF_ "GenMsgBackgroundColor" "#ffffff"; +BA_DEF_DEF_ "GenMsgForegroundColor" "#000000"; +VAL_ 34 IPMA_PCAN_DataRangeCheck 1 "Fault Present" 0 "No Fault"; +VAL_ 34 IPMA_PCAN_MissingMsg 1 "Fault Present" 0 "No Fault "; +VAL_ 34 VINSignalCompareFailure 1 "Fault Present" 0 "No Fault"; +VAL_ 34 ModuleNotConfiguredError 1 "Fault Present" 0 "No Fault"; +VAL_ 34 CarCfgNotConfiguredError 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte7_bit7 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte7_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte7_bit5 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte7_bit4 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ARMtoDSPChksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 DSPtoArmChksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 HostToArmChksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ARMtoHostChksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 LoopBWOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 DSPOverrunFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte6_bit5 1 "Fault Present" 0 "No Fault"; +VAL_ 33 TuningSensitivityFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 SaturatedTuningFreqFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 LocalOscPowerFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 TransmitterPowerFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte6_bit0 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte5_bit7 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte5_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 XCVRDeviceSPIFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 FreqSynthesizerSPIFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 AnalogConverterDevicSPIFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 SidelobeBlockage 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte5_bit1 1 "Fault Present" 0 "No Fault"; +VAL_ 33 MNRBlocked 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ECUTempHighFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 TransmitterTempHighFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 AlignmentRoutineFailedFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 UnreasonableRadarData 1 "Fault Present" 0 "No Fault"; +VAL_ 33 MicroprocessorTempHighFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 VerticalAlignmentOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 HorizontalAlignmentOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 FactoryAlignmentMode 1 "Fault Present" 0 "No Fault"; +VAL_ 33 BatteryLowFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 BatteryHighFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 v_1p25SupplyOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte3_bit4 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ThermistorOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 v_3p3DACSupplyOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 v_3p3RAWSupplyOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 v_5_SupplyOutOfRange 1 "Fault Present" 0 "No Fault"; +VAL_ 33 TransmitterIDFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit5 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit4 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit3 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte2_bit2 1 "Fault Present" 0 "No Fault"; +VAL_ 33 PCANMissingMsgFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 PCANBusOff 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte1_bit7 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte1_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 InstructionSetCheckFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 StackOverflowFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 WatchdogFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 PLLLockFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte1_bit1 1 "Fault Present" 0 "No Fault"; +VAL_ 33 RAMMemoryTestFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 USCValidationFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte0_bit6 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte0_bit5 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte0_bit4 1 "Fault Present" 0 "No Fault"; +VAL_ 33 Active_Flt_Latched_byte0_bit3 1 "Fault Present" 0 "No Fault"; +VAL_ 33 KeepAliveChecksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ProgramCalibrationFlashChecksum 1 "Fault Present" 0 "No Fault"; +VAL_ 33 ApplicationFlashChecksumFault 1 "Fault Present" 0 "No Fault"; +VAL_ 371 CAN_AUTO_ALIGN_HANGLE_QF 3 "Accurate" 2 "Inaccurate" 1 "Temporarily undefined" 0 "Undefined"; +VAL_ 371 CAN_ALIGNMENT_STATUS 15 "Undefined_2" 14 "Undefined_1" 13 "Low Amplitude (Flat-plate only)" 12 "No Peak (Flat-plate only)" 11 "Fail Ver and Hor OutOfRange" 10 "Fail Vertical Align OutOfRange" 9 "Fail Horizontal Align OutOfRange" 8 "Fail Time Out" 7 "Fail Only Right Target Found" 6 "Fail Only Left Target Found" 5 "Fail Variance Too Large" 4 "Fail Deviation Too Large" 3 "Fail No Target" 2 "Success" 1 "Busy" 0 "Off"; +VAL_ 371 CAN_ALIGNMENT_STATE 6 "Static alignment flat-plate" 5 "Static alignment 2-target" 4 "Static alignment 1-target" 3 "Service alignment" 2 "Short track alignment" 1 "Auto alignment" 0 "Off"; +EOF + +build_val "04" + +cat <> ${OUT_FILENAME} +VAL_ 351 CAN_DET_CONFID_AZIMUTH_64 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 350 CAN_DET_CONFID_AZIMUTH_63 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 349 CAN_DET_CONFID_AZIMUTH_62 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 348 CAN_DET_CONFID_AZIMUTH_61 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 347 CAN_DET_CONFID_AZIMUTH_60 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 346 CAN_DET_CONFID_AZIMUTH_59 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 345 CAN_DET_CONFID_AZIMUTH_58 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 344 CAN_DET_CONFID_AZIMUTH_57 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 343 CAN_DET_CONFID_AZIMUTH_56 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 342 CAN_DET_CONFID_AZIMUTH_55 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 335 CAN_DET_CONFID_AZIMUTH_48 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 334 CAN_DET_CONFID_AZIMUTH_47 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 333 CAN_DET_CONFID_AZIMUTH_46 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 332 CAN_DET_CONFID_AZIMUTH_45 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 331 CAN_DET_CONFID_AZIMUTH_44 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 330 CAN_DET_CONFID_AZIMUTH_43 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 329 CAN_DET_CONFID_AZIMUTH_42 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 328 CAN_DET_CONFID_AZIMUTH_41 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 327 CAN_DET_CONFID_AZIMUTH_40 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 325 CAN_DET_CONFID_AZIMUTH_38 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 324 CAN_DET_CONFID_AZIMUTH_37 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 323 CAN_DET_CONFID_AZIMUTH_36 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 322 CAN_DET_CONFID_AZIMUTH_35 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 321 CAN_DET_CONFID_AZIMUTH_34 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 320 CAN_DET_CONFID_AZIMUTH_33 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 319 CAN_DET_CONFID_AZIMUTH_32 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 318 CAN_DET_CONFID_AZIMUTH_31 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 317 CAN_DET_CONFID_AZIMUTH_30 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 316 CAN_DET_CONFID_AZIMUTH_29 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 314 CAN_DET_CONFID_AZIMUTH_27 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 313 CAN_DET_CONFID_AZIMUTH_26 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 312 CAN_DET_CONFID_AZIMUTH_25 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 311 CAN_DET_CONFID_AZIMUTH_24 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 310 CAN_DET_CONFID_AZIMUTH_23 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +EOF + +build_val "22" +build_val "21" +build_val "20" +build_val "19" +build_val "18" + +cat <> ${OUT_FILENAME} +VAL_ 341 CAN_DET_CONFID_AZIMUTH_54 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 340 CAN_DET_CONFID_AZIMUTH_53 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 339 CAN_DET_CONFID_AZIMUTH_52 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 338 CAN_DET_CONFID_AZIMUTH_51 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 337 CAN_DET_CONFID_AZIMUTH_50 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 336 CAN_DET_CONFID_AZIMUTH_49 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 326 CAN_DET_CONFID_AZIMUTH_39 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +VAL_ 315 CAN_DET_CONFID_AZIMUTH_28 3 "Low" 2 "Medium_Low" 1 "Medium_High" 0 "High"; +EOF + +build_val "17" +build_val "16" +build_val "15" +build_val "14" +build_val "13" +build_val "12" +build_val "11" +build_val "10" +build_val "09" +build_val "08" +build_val "07" +build_val "06" +build_val "05" +build_val "03" +build_val "02" + +cat <> ${OUT_FILENAME} +VAL_ 257 CAN_INTERFERENCE_TYPE 2 "Star PD-Like" 1 "Slow FMCW" 0 "No Interference"; +VAL_ 257 CAN_RECOMMEND_UNCONVERGE 1 "Recommended" 0 "Not Recommended"; +VAL_ 257 CAN_RADAR_ALIGN_INCOMPLETE 1 "Alignment Incomplete" 0 "Alignment Completed"; +VAL_ 257 CAN_BLOCKAGE_SIDELOBE 1 "Radar Blockage" 0 "No Radar Blockage"; +VAL_ 257 CAN_BLOCKAGE_MNR 1 "Radar Blockage" 0 "No Radar Blockage"; +VAL_ 257 CAN_RADAR_EXT_COND_NOK 1 "Too high temp or insufficient pw" 0 "External conditions OK"; +VAL_ 257 CAN_RADAR_ALIGN_OUT_RANGE 1 "Radar out of range" 0 "Radar within range"; +VAL_ 257 CAN_RADAR_ALIGN_NOT_START 1 "Radar align not started" 0 "Radar align started"; +VAL_ 257 CAN_RADAR_OVERHEAT_ERROR 1 "Radar overheat condition" 0 "No Overheat"; +VAL_ 257 CAN_RADAR_NOT_OP 1 "Radar not operational" 0 "Radar operational"; +VAL_ 257 CAN_XCVR_OPERATIONAL 1 "On" 0 "Off "; +EOF + +build_val "01" \ No newline at end of file diff --git a/opendbc_repo/opendbc/dbc/generator/generator.py b/opendbc_repo/opendbc/dbc/generator/generator.py new file mode 100755 index 000000000000000..d0f41fc80abba0c --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/generator.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python3 +import os +import re +import glob +import subprocess + +generator_path = os.path.dirname(os.path.realpath(__file__)) +opendbc_root = os.path.join(generator_path, '../') +include_pattern = re.compile(r'CM_ "IMPORT (.*?)";\n') +generated_suffix = '_generated.dbc' + + +def read_dbc(src_dir: str, filename: str) -> str: + with open(os.path.join(src_dir, filename), encoding='utf-8') as file_in: + return file_in.read() + + +def create_dbc(src_dir: str, filename: str, output_path: str): + dbc_file_in = read_dbc(src_dir, filename) + + includes = include_pattern.findall(dbc_file_in) + + output_filename = filename.replace('.dbc', generated_suffix) + output_file_location = os.path.join(output_path, output_filename) + + with open(output_file_location, 'w', encoding='utf-8') as dbc_file_out: + dbc_file_out.write('CM_ "AUTOGENERATED FILE, DO NOT EDIT";\n') + + for include_filename in includes: + include_file_header = f'\n\nCM_ "Imported file {include_filename} starts here";\n' + dbc_file_out.write(include_file_header) + + include_file = read_dbc(src_dir, include_filename) + dbc_file_out.write(include_file) + + dbc_file_out.write(f'\nCM_ "{filename} starts here";\n') + + core_dbc = include_pattern.sub('', dbc_file_in) + dbc_file_out.write(core_dbc) + + +def create_all(output_path: str): + # clear out old DBCs + for f in glob.glob(f"{output_path}/*{generated_suffix}"): + os.remove(f) + + # run python generator scripts first + for f in glob.glob(f"{generator_path}/*/*.py"): + subprocess.check_call(f) + + for src_dir, _, filenames in os.walk(generator_path): + if src_dir == generator_path: + continue + + #print(src_dir) + for filename in filenames: + if filename.startswith('_') or not filename.endswith('.dbc'): + continue + + #print(filename) + create_dbc(src_dir, filename, output_path) + +if __name__ == "__main__": + create_all(opendbc_root) diff --git a/opendbc_repo/opendbc/dbc/generator/gm/_community.dbc b/opendbc_repo/opendbc/dbc/generator/gm/_community.dbc new file mode 100644 index 000000000000000..d8855b3594e69b6 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/gm/_community.dbc @@ -0,0 +1,15 @@ +BO_ 512 GAS_COMMAND: 6 NEO + SG_ GAS_COMMAND : 7|16@0+ (0.125677,-75.909) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.251976,-76.601) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.125677,-75.909) [0|1] "" NEO + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.251976,-76.601) [0|1] "" NEO + SG_ STATE : 39|4@0+ (1,0) [0|15] "" NEO + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" NEO + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" NEO + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; diff --git a/opendbc_repo/opendbc/dbc/generator/gm/gm_global_a_powertrain.dbc b/opendbc_repo/opendbc/dbc/generator/gm/gm_global_a_powertrain.dbc new file mode 100644 index 000000000000000..2dd72d36903db5e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/gm/gm_global_a_powertrain.dbc @@ -0,0 +1,355 @@ + +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: K16_BECM K73_TCIC K9_BCM K43_PSCM K17_EBCM K20_ECM K114B_HPCM NEO K124_ASCM EPB +VAL_TABLE_ TurnSignals 2 "Right Turn" 1 "Left Turn" 0 "None" ; +VAL_TABLE_ Intellibeam 1 "Active" 0 "Inactive" ; +VAL_TABLE_ HighBeamsActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ HighBeamsTemporary 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCLeadCar 1 "Present" 0 "Not Present" ; +VAL_TABLE_ ACCCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ BrakePedalPressed 1 "Pressed" 0 "Depressed" ; +VAL_TABLE_ DistanceButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ LKAButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_TABLE_ DriveModeButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ PRNDL 3 "Reverse" 2 "Drive" 1 "Neutral" 0 "Park" ; +VAL_TABLE_ ESPButton 1 "Active" 0 "Inactive" ; +VAL_TABLE_ DoorStatus 1 "Opened" 0 "Closed" ; +VAL_TABLE_ SeatBeltStatus 1 "Latched" 0 "Unlatched" ; +VAL_TABLE_ LKASteeringCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ ACCGapLevel 3 "Far" 2 "Med" 1 "Near" 0 "Inactive" ; +VAL_TABLE_ GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; +VAL_TABLE_ GasRegenCmdActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ; +VAL_TABLE_ HandsOffSWDetectionStatus 1 "Hands On" 0 "Hands Off" ; +VAL_TABLE_ HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ; + + +BO_ 189 EBCMRegenPaddle: 7 K17_EBCM + SG_ RegenPaddle : 7|4@0+ (1,0) [0|0] "" NEO + +BO_ 190 ECMAcceleratorPos: 6 K20_ECM + SG_ BrakePedalPos : 15|8@0+ (1,0) [0|0] "sticky" NEO + SG_ GasPedalAndAcc : 23|8@0+ (1,0) [0|0] "" NEO + +BO_ 201 ECMEngineStatus: 8 K20_ECM + SG_ EngineTPS : 39|8@0+ (0.392156863,0) [0|100.000000065] "%" NEO + SG_ EngineRPM : 15|16@0+ (0.25,0) [0|0] "RPM" NEO + SG_ CruiseMainOn : 29|1@0+ (1,0) [0|1] "" NEO + SG_ BrakePressed : 40|1@0+ (1,0) [0|1] "" NEO + SG_ Standstill : 2|1@0+ (1,0) [0|1] "" NEO + SG_ CruiseActive : 31|2@0+ (1,0) [0|3] "" NEO + +BO_ 209 EBCMBrakePedalSensors: 7 K17_EBCM + SG_ Counter1 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ Counter2 : 23|2@0+ (1,0) [0|3] "" XXX + SG_ BrakePedalPosition1 : 5|14@0+ (1,0) [0|16383] "" XXX + SG_ BrakePedalPosition2 : 21|14@0- (-1,0) [0|16383] "" XXX + SG_ BrakeNormalized1 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ BrakeNormalized2 : 47|8@0- (-1,0) [0|255] "" XXX + +BO_ 241 EBCMBrakePedalPosition: 6 K17_EBCM + SG_ BrakePressed : 1|1@0+ (1,0) [0|1] "" XXX + SG_ BrakePedalPosition : 15|8@0+ (1,0) [0|255] "" NEO + +BO_ 298 BCMDoorBeltStatus: 8 K9_BCM + SG_ RearLeftDoor : 8|1@0+ (1,0) [0|0] "" NEO + SG_ FrontLeftDoor : 9|1@0+ (1,0) [0|0] "" NEO + SG_ FrontRightDoor : 10|1@0+ (1,0) [0|0] "" NEO + SG_ RearRightDoor : 23|1@0+ (1,0) [0|0] "" NEO + SG_ LeftSeatBelt : 12|1@0+ (1,0) [0|0] "" NEO + SG_ RightSeatBelt : 53|1@0+ (1,0) [0|0] "" NEO + +BO_ 309 ECMPRDNL: 8 K20_ECM + SG_ PRNDL : 2|3@0+ (1,0) [0|0] "" NEO + SG_ ESPButton : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 320 BCMTurnSignals: 3 K9_BCM + SG_ TurnSignals : 19|2@0+ (1,0) [0|0] "" NEO + SG_ Intellibeam : 13|1@0+ (1,0) [0|1] "" XXX + 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 + SG_ TractionControlOn : 5|1@0+ (1,0) [0|0] "" NEO + SG_ MSG17D_AccPower : 35|12@0- (1,0) [0|0] "" NEO + +BO_ 384 ASCMLKASteeringCmd: 4 NEO + SG_ RollingCounter : 5|2@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdChecksum : 19|12@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmdActive : 3|1@0+ (1,0) [0|0] "" NEO + SG_ LKASteeringCmd : 2|11@0- (1,0) [0|0] "" NEO + +BO_ 388 PSCMStatus: 8 K43_PSCM + SG_ HandsOffSWDetectionMode : 20|2@0+ (1,0) [0|3] "" NEO + SG_ HandsOffSWlDetectionStatus : 21|1@0+ (1,0) [0|1] "" NEO + SG_ LKATorqueDeliveredStatus : 5|3@0+ (1,0) [0|7] "" NEO + SG_ LKADriverAppldTrq : 50|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO + SG_ LKATorqueDelivered : 18|11@0- (0.01,0) [0|1] "" NEO + SG_ LKATotalTorqueDelivered : 2|11@0- (0.01,0) [-10.24|10.23] "Nm" NEO + SG_ RollingCounter : 38|4@0+ (1,0) [0|15] "" XXX + SG_ PSCMStatusChecksum : 33|10@0+ (1,0) [0|1023] "" XXX + +BO_ 417 AcceleratorPedal: 7 XXX + SG_ AcceleratorPedal : 55|8@0+ (1,0) [0|0] "" NEO + +BO_ 451 GasAndAcc: 8 XXX + SG_ GasPedalAndAcc2 : 55|8@0+ (1,0) [0|0] "" NEO + +BO_ 452 AcceleratorPedal2: 8 XXX + SG_ CruiseState : 15|3@0+ (1,0) [0|7] "" NEO + SG_ AcceleratorPedal2 : 47|8@0+ (1,0) [0|0] "" NEO + +BO_ 481 ASCMSteeringButton: 7 K124_ASCM + SG_ DistanceButton : 22|1@0+ (1,0) [0|0] "" NEO + SG_ LKAButton : 23|1@0+ (1,0) [0|0] "" NEO + SG_ ACCAlwaysOne : 24|1@0+ (1,0) [0|1] "" XXX + SG_ ACCButtons : 46|3@0+ (1,0) [0|0] "" NEO + SG_ DriveModeButton : 39|1@0+ (1,0) [0|1] "" XXX + SG_ RollingCounter : 33|2@0+ (1,0) [0|3] "" NEO + SG_ SteeringButtonChecksum : 43|12@0+ (1,0) [0|255] "" NEO + +BO_ 485 PSCMSteeringAngle: 8 K43_PSCM + SG_ SteeringWheelAngle : 15|16@0- (0.0625,0) [-2047|2047] "deg" NEO + SG_ SteeringWheelRate : 27|12@0- (1,0) [-2047|2047] "deg/s" NEO + +BO_ 489 EBCMVehicleDynamic: 8 K17_EBCM + SG_ BrakePedalPressed : 6|1@0+ (1,0) [0|0] "" NEO + SG_ LateralAcceleration : 3|10@0- (0.161,0) [-2047|2047] "m/s2" NEO + SG_ YawRate : 35|12@0- (0.625,0) [0|1] "" NEO + SG_ YawRate2 : 51|12@0- (0.0625,0) [-2047|2047] "grad/s" NEO + +BO_ 352 BCMImmobilizer: 5 K9_BCM + SG_ ImmobilizerInfo : 7|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 497 BCMGeneralPlatformStatus: 8 K9_BCM + SG_ SystemPowerMode : 1|2@0+ (1,0) [0|3] "" XXX + SG_ SystemBackUpPowerMode : 5|2@0+ (1,0) [0|3] "" XXX + SG_ ParkBrakeSwActive : 36|1@0+ (1,0) [0|3] "" XXX + +BO_ 500 SportMode: 6 XXX + SG_ SnowIceMode : 9|1@0+ (1,0) [0|1] "" XXX + SG_ SportMode : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 501 ECMPRDNL2: 8 K20_ECM + SG_ TransmissionState : 48|4@1+ (1,0) [0|7] "" NEO + SG_ PRNDL2 : 27|4@0+ (1,0) [0|255] "" NEO + SG_ ManualMode : 41|1@0+ (1,0) [0|1] "" NEO + +BO_ 532 BRAKE_RELATED: 6 XXX + SG_ UserBrakePressure : 0|9@0+ (1,0) [0|511] "" XXX + +BO_ 560 EPBStatus: 8 EPB + SG_ EPBClosed : 12|1@0+ (1,0) [0|1] "" NEO + +BO_ 562 EBCMFrictionBrakeStatus: 8 K17_EBCM + SG_ FrictionBrakeUnavailable : 46|1@0+ (1,0) [0|1] "" XXX + +BO_ 608 SPEED_RELATED: 8 XXX + SG_ RollingCounter : 5|2@0+ (1,0) [0|0] "" XXX + SG_ ClusterSpeed : 31|8@0+ (1,0) [0|0] "" XXX + +BO_ 711 BECMBatteryVoltageCurrent: 6 K17_EBCM + SG_ HVBatteryVoltage : 31|12@0+ (0.125,0) [0|511.875] "V" NEO + SG_ HVBatteryCurrent : 12|13@0- (0.15,0) [-614.4|614.25] "A" NEO + +BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM + SG_ GasRegenAlwaysOne2 : 9|1@0+ (1,0) [0|1] "" NEO + SG_ GasRegenAlwaysOne : 14|1@0+ (1,0) [0|1] "" NEO + SG_ GasRegenChecksum : 47|24@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmdActiveInv : 32|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenFullStopActive : 13|1@0+ (1,0) [0|0] "" NEO + SG_ GasRegenCmdActive : 0|1@0+ (1,0) [0|0] "" NEO + SG_ RollingCounter : 7|2@0+ (1,0) [0|0] "" NEO + SG_ GasRegenAlwaysOne3 : 23|1@0+ (1,0) [0|1] "" NEO + SG_ GasRegenCmd : 22|12@0+ (1,0) [0|0] "" NEO + +BO_ 717 ASCM_2CD: 5 K124_ASCM + +BO_ 761 BRAKE_RELATED_2: 7 XXX + SG_ UserBrakePressure2 : 47|9@0+ (1,0) [0|511] "" XXX + +BO_ 789 EBCMFrictionBrakeCmd: 5 K124_ASCM + SG_ RollingCounter : 33|2@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeMode : 7|4@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeChecksum : 23|16@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeCmd : 3|12@0- (1,0) [0|0] "" NEO + +BO_ 800 AEBCmd: 6 K124_ASCM + SG_ RollingCounter : 5|2@0+ (1,0) [0|3] "" NEO + SG_ AEBChecksum : 27|20@0+ (1,0) [0|0] "" NEO + SG_ AEBCmdActive : 3|1@1+ (1,0) [0|1] "" NEO + SG_ AEBCmd : 2|11@0+ (1,0) [0|0] "" NEO + SG_ AEBCmd2 : 23|8@0+ (1,0) [0|0] "" NEO + +BO_ 810 TCICOnStarGPSPosition: 8 K73_TCIC + SG_ GPSLongitude : 39|32@0+ (1,-2147483648) [0|0] "milliarcsecond" NEO + SG_ GPSLatitude : 7|32@0+ (1,0) [0|0] "milliarcsecond" NEO + +BO_ 840 EBCMWheelSpdFront: 5 K17_EBCM + SG_ FLWheelSpd : 7|16@0+ (0.0311,0) [0|255] "km/h" NEO + 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_ 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 + +BO_ 880 ASCMActiveCruiseControlStatus: 6 K124_ASCM + SG_ ACCCruiseState : 8|3@1+ (1,0) [0|7] "" XXX + SG_ ACCLeadCar : 44|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCAlwaysOne2 : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCAlwaysOne : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCSpeedSetpoint : 19|12@0+ (0.0625,0) [0|255.9375] "km/h" NEO + SG_ ACCGapLevel : 21|2@0+ (1,0) [0|0] "" NEO + SG_ ACCResumeButton : 1|1@0+ (1,0) [0|0] "" NEO + SG_ ACCCmdActive : 23|1@0+ (1,0) [0|0] "" NEO + SG_ FCWAlert : 41|2@0+ (1,0) [0|3] "" XXX + +BO_ 967 EVDriveMode: 4 XXX + SG_ SinglePedalModeActive : 7|1@0+ (1,0) [0|1] "" XXX + SG_ SinglePedalModeRisingEdge : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SinglePedalModeFallingEdge : 22|1@0+ (1,0) [0|1] "" XXX + +BO_ 977 ECMCruiseControl: 8 K20_ECM + SG_ CruiseActive : 39|1@0+ (1,0) [0|3] "" NEO + SG_ CruiseSetSpeed : 19|12@0+ (0.0625,0) [0|0] "km/h" NEO + +BO_ 1001 ECMVehicleSpeed: 8 K20_ECM + SG_ VehicleSpeed : 7|16@0+ (0.01,0) [0|0] "mph" NEO + SG_ VehicleSpeedLeft : 39|16@0+ (0.01,0) [0|0] "mph" NEO + +BO_ 1033 ASCMKeepAlive: 7 NEO + SG_ ASCMKeepAliveAllZero : 7|56@0+ (1,0) [0|0] "" NEO + +BO_ 1034 ASCM_40A: 7 K124_ASCM + +BO_ 1217 ECMEngineCoolantTemp: 8 K20_ECM + SG_ EngineCoolantTemp : 23|8@0+ (1,-40) [0|0] "C" NEO + +BO_ 1249 VIN_Part2: 8 K20_ECM + SG_ VINPart2 : 7|64@0+ (1,0) [0|0] "" NEO + +BO_ 1296 ASCM_510: 4 K124_ASCM + +BO_ 1300 VIN_Part1: 8 K20_ECM + SG_ VINPart1 : 7|64@0+ (1,0) [0|0] "" NEO + +BO_ 1912 PSCM_778: 8 K43_PSCM + +BO_ 1930 ASCM_78A: 7 K124_ASCM + +BO_TX_BU_ 384 : K124_ASCM,NEO; +BO_TX_BU_ 880 : NEO,K124_ASCM; +BO_TX_BU_ 1033 : K124_ASCM,NEO; +BO_TX_BU_ 715 : NEO,K124_ASCM; +BO_TX_BU_ 789 : NEO,K124_ASCM; +BO_TX_BU_ 800 : NEO,K124_ASCM; + + +CM_ BU_ K16_BECM "Battery Energy Control Module"; +CM_ BU_ K73_TCIC "Telematics Communication Control Module"; +CM_ BU_ K9_BCM "Body Control Module"; +CM_ BU_ K43_PSCM "Power Steering Control Module"; +CM_ BU_ K17_EBCM "Electronic Brake Control Module"; +CM_ BU_ K20_ECM "Engine Control Module"; +CM_ BU_ K114B_HPCM "Hybrid Powertrain Control Module"; +CM_ BU_ NEO "Comma NEO"; +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"; +CM_ SG_ 562 FrictionBrakeUnavailable "1 when ACC brake control is unavailable. Stays high if brake command messages are blocked for a period of time"; +CM_ SG_ 497 SystemPowerMode "Describes ignition"; +CM_ SG_ 497 SystemBackUpPowerMode "Describes ignition + preconditioning mode, noisy"; +CM_ SG_ 501 PRNDL2 "When ManualMode is Active, Value is 13=L1 12=L2 11=L3 ... 4=L10"; +CM_ SG_ 532 UserBrakePressure "can be lower than other brake position signals when the brakes are pre-filled from ACC braking and the user presses on the brakes. user-only pressure?"; +CM_ SG_ 608 ClusterSpeed "Cluster speed signal seems to match dash on newer cars, but is a lower rate and can be noisier."; +CM_ SG_ 761 UserBrakePressure2 "Similar to BRAKE_RELATED->UserBrakePressure"; +CM_ SG_ 1001 VehicleSpeed "Spinouts show here on 2wd. Speed derived from right front wheel (drive tire)"; +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; +BA_ "UseGMParameterIDs" 0; +VAL_ 497 SystemPowerMode 3 "Crank Request" 2 "Run" 1 "Accessory" 0 "Off"; +VAL_ 497 SystemBackUpPowerMode 3 "Crank Request" 2 "Run" 1 "Accessory" 0 "Off"; +VAL_ 481 DistanceButton 1 "Active" 0 "Inactive" ; +VAL_ 481 LKAButton 1 "Active" 0 "Inactive" ; +VAL_ 481 ACCButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_ 481 DriveModeButton 1 "Active" 0 "Inactive" ; +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" ; +VAL_ 880 ACCResumeButton 1 "Pressed" 0 "Depressed" ; +VAL_ 880 ACCCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 388 HandsOffSWDetectionMode 2 "Failed" 1 "Enabled" 0 "Disabled" ; +VAL_ 388 HandsOffSWlDetectionStatus 1 "Hands On" 0 "Hands Off" ; +VAL_ 388 LKATorqueDeliveredStatus 3 "Failed" 2 "Temp. Limited" 1 "Active" 0 "Inactive" ; +VAL_ 489 BrakePedalPressed 1 "Pressed" 0 "Depressed" ; +VAL_ 715 GasRegenCmdActiveInv 1 "Inactive" 0 "Active" ; +VAL_ 715 GasRegenCmdActive 1 "Active" 0 "Inactive" ; +VAL_ 320 Intellibeam 1 "Active" 0 "Inactive" ; +VAL_ 320 HighBeamsActive 1 "Active" 0 "Inactive" ; +VAL_ 320 HighBeamsTemporary 1 "Active" 0 "Inactive" ; +VAL_ 501 PRNDL2 6 "L" 4 "D" 3 "N" 2 "R" 1 "P" 0 "Shifting"; +VAL_ 501 TransmissionState 11 "Shifting" 10 "Reverse" 9 "Forward" 8 "Disengaged"; +VAL_ 501 ManualMode 1 "Active" 0 "Inactive" diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_bosch_2018.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_bosch_2018.dbc new file mode 100644 index 000000000000000..b5e8c14d6cfced5 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_bosch_2018.dbc @@ -0,0 +1,232 @@ +BO_ 148 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 228 STEERING_CONTROL: 5 EON + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ STEER_DOWN_TO_ZERO : 38|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 229 BOSCH_SUPPLEMENTAL_1: 8 XXX + SG_ SET_ME_X04 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 8|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X80 : 16|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X10 : 24|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 232 BRAKE_HOLD: 7 XXX + SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX + SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX + SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 545 XXX_16: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 576 LEFT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 577 LEFT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 579 RIGHT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 580 RIGHT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 582 ADJACENT_LEFT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 583 ADJACENT_LEFT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 585 ADJACENT_RIGHT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 586 ADJACENT_RIGHT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ HUD_LEAD : 40|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_64 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH3 : 47|7@0+ (1,0) [0|127] "" XXX + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 576 LINE_DISTANCE_VISIBLE "Length of line visible, undecoded"; +CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, indicates location of the portion of the line furthest from the car, undecoded"; +CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; +CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; +CM_ SG_ 577 LINE_SOLID "1 = line is solid"; + +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_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; \ No newline at end of file diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_bosch_adas_2018.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_bosch_adas_2018.dbc new file mode 100644 index 000000000000000..dc8def55cb1d072 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_bosch_adas_2018.dbc @@ -0,0 +1,54 @@ +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ GAS_COMMAND : 7|16@0- (1,0) [0|0] "" XXX + SG_ ACCEL_COMMAND : 31|11@0- (0.01,0) [0|0] "m/s2" XXX + SG_ BRAKE_LIGHTS : 62|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_REQUEST : 34|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL : 35|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_RELEASE : 36|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_STATUS : 33|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_BRAKING : 47|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_PREPARE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; +CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; +CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; +CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_community.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_community.dbc new file mode 100644 index 000000000000000..8be69203ef86348 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_community.dbc @@ -0,0 +1,15 @@ +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_honda_common.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_honda_common.dbc new file mode 100644 index 000000000000000..d9feb98dc8ac9af --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_honda_common.dbc @@ -0,0 +1,163 @@ +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + SG_ CAR_SPEED : 7|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "mph" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ IMPERIAL_UNIT : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "kph" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF_2 : 36|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01_2 : 55|1@0+ (1,0) [0|1] "" BDY + SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" BDY + SG_ CHIME : 51|3@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY + SG_ ICONS : 63|2@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 780 PCM_SPEED "Used by Nidec"; +CM_ SG_ 780 PCM_GAS "Used by Nidec"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; + +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_nidec_common.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_nidec_common.dbc new file mode 100644 index 000000000000000..142508911dd65f8 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_nidec_common.dbc @@ -0,0 +1,93 @@ +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST_ALT : 11|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_X00 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_X00_2 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_1 : 31|1@0+ (1,0) [0|1] "" EBCM + SG_ AEB_REQ_1 : 29|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_REQ_2 : 26|3@0+ (1,0) [0|7] "" XXX + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ SET_ME_X00_3 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ AEB_STATUS : 41|2@0+ (1,0) [0|3] "" XXX + SG_ COMPUTER_BRAKE_ALT : 55|10@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; +CM_ SG_ 506 COMPUTER_BRAKE_ALT "Used by dual-can Nidec"; +CM_ SG_ 506 BRAKE_PUMP_REQUEST_ALT "Used by dual-can Nidec"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_steering_sensors_a.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_steering_sensors_a.dbc new file mode 100644 index 000000000000000..52805d6227d2f88 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_steering_sensors_a.dbc @@ -0,0 +1,9 @@ +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON diff --git a/opendbc_repo/opendbc/dbc/generator/honda/_steering_sensors_b.dbc b/opendbc_repo/opendbc/dbc/generator/honda/_steering_sensors_b.dbc new file mode 100644 index 000000000000000..35e9b27520ebc65 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/_steering_sensors_b.dbc @@ -0,0 +1,5 @@ +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON diff --git a/opendbc_repo/opendbc/dbc/generator/honda/acura_ilx_2016_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/acura_ilx_2016_can.dbc new file mode 100644 index 000000000000000..5a60a9c9e1ea532 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/acura_ilx_2016_can.dbc @@ -0,0 +1,50 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; +CM_ "IMPORT _steering_sensors_b.dbc"; + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; + +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_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; +VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2018_can.dbc new file mode 100644 index 000000000000000..06327f928f3a3ff --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2018_can.dbc @@ -0,0 +1,46 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; +CM_ "IMPORT _steering_sensors_b.dbc"; + +BO_ 392 GEARBOX: 6 XXX + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" XXX + SG_ GEAR_SHIFTER : 27|4@0+ (1,0) [0|15] "" EON + SG_ GEAR : 36|5@0+ (1,0) [0|31] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (-1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ PARKING_BRAKE_LIGHT : 2|1@0+ (1,0) [0|1] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 422 PARKING_BRAKE_LIGHT "Believe this is just the dash light for the parking break"; +VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ; +VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +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_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2020_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2020_can.dbc new file mode 100644 index 000000000000000..38a312c31165edb --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/acura_rdx_2020_can.dbc @@ -0,0 +1,32 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _bosch_2018.dbc"; +CM_ "IMPORT _bosch_adas_2018.dbc"; +CM_ "IMPORT _steering_sensors_b.dbc"; + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_accord_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_accord_2018_can.dbc new file mode 100644 index 000000000000000..e9f2fb41aaae79d --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_accord_2018_can.dbc @@ -0,0 +1,55 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _bosch_2018.dbc"; +CM_ "IMPORT _bosch_adas_2018.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 401 GEARBOX_15T: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 419 GEARBOX: 8 XXX + SG_ GEAR_SHIFTER : 24|8@1+ (1,0) [0|255] "" XXX + SG_ GEAR : 32|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 506 LEGACY_BRAKE_COMMAND: 8 ADAS + SG_ CHIME : 40|8@1+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +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_ 419 GEAR_SHIFTER 2 "S" 32 "D" 16 "N" 8 "R" 4 "P"; +VAL_ 419 GEAR 26 "S" 20 "D" 19 "N" 18 "R" 17 "P"; +VAL_ 545 ECON_ON_2 0 "off" 3 "on"; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none"; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none"; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_ex_2022_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_ex_2022_can.dbc new file mode 100644 index 000000000000000..bbe3eadb3197d25 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_ex_2022_can.dbc @@ -0,0 +1,107 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _bosch_2018.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 419 GEARBOX_ALT: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_FAULT : 22|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 456 ACC_CONTROL: 8 XXX + SG_ ACCEL_COMMAND : 7|12@0- (0.01,0) [0|0] "m/s^2" XXX + SG_ IDLESTOP_ALLOW : 8|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL : 9|1@0+ (1,0) [0|1] "" XXX + SG_ CONTROL_ON : 10|1@0+ (1,0) [0|1] "" XXX + SG_ BOH : 23|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_STATUS : 33|1@1+ (1,0) [0|7] "" XXX + SG_ AEB_BRAKING : 47|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_PREPARE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ FCW_1 : 24|1@1+ (1,0) [0|3] "" XXX + SG_ FCW_2 : 54|1@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 467 CRUISE_FAULT_STATUS: 8 XXX + SG_ CRUISE_FAULT : 3|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 477 GEARBOX_ALT_2: 8 XXX + SG_ GEAR_MT : 39|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 495 SPEED_LIMIT_DASH_DISPLAY: 8 ADAS + SG_ SPEED_LIMIT : 47|8@0+ (1,0) [0|255] "mph" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 829 LKAS_HUD: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ LANE_LINES : 36|2@0+ (1,0) [0|3] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +BO_ 882 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON + +BO_ 254913108 LKAS_HUD_2: 8 ADAS + SG_ COUNTER_2 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 5|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_BOH_1 : 15|6@0+ (1,0) [0|63] "" XXX + SG_ LEFT_LANE : 23|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LANE : 21|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_BOH_2 : 30|5@0+ (1,0) [0|31] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +CM_ 446 "If exists, describes cruise faults and what the PCM uses for brake press detection."; +CM_ SG_ 456 IDLESTOP_ALLOW "allows car to turn off engine at a standstill"; +CM_ SG_ 456 STANDSTILL "set to 1 when camera requests -4.0 m/s^2"; +CM_ SG_ 495 SPEED_LIMIT "Defaults to 0xFF if no speed limit found"; + +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_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P" 0 "B" ; +VAL_ 477 GEAR_MT 14 "reverse" 6 "6th" 5 "5th" 4 "4th" 3 "3rd" 2 "2nd" 1 "1st" 0 "Clutch"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc new file mode 100644 index 000000000000000..dc14d2968a3f691 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_hatchback_ex_2017_can.dbc @@ -0,0 +1,37 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _bosch_2018.dbc"; +CM_ "IMPORT _bosch_adas_2018.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 506 LEGACY_BRAKE_COMMAND: 8 ADAS + SG_ CHIME : 40|8@1+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON + +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_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_touring_2016_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_touring_2016_can.dbc new file mode 100644 index 000000000000000..89b6ceae3555cab --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_civic_touring_2016_can.dbc @@ -0,0 +1,95 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 493 HUD_SETTING: 5 XXX + SG_ IMPERIAL_UNIT : 5|1@0+ (1,0) [0|1] "" EON + +BO_ 545 ECON_STATUS: 6 XXX + SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; + +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" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_clarity_hybrid_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_clarity_hybrid_2018_can.dbc new file mode 100644 index 000000000000000..edeaa2999300b07 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_clarity_hybrid_2018_can.dbc @@ -0,0 +1,113 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 388 BRAKE_ERROR: 8 XXX + SG_ BRAKE_ERROR_1 : 32|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 34|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 545 ECON_STATUS: 6 XXX + SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 768 VEHICLE_STATE: 8 ADAS + SG_ SET_ME_XF9 : 7|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ VEHICLE_SPEED : 15|8@0+ (1,0) [0|255] "kph" Vector__XXX + SG_ SET_ME_X8A : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_XD0 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SALTED_WITH_IDX : 39|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 769 VEHICLE_STATE2: 8 ADAS + SG_ SET_ME_X5D : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X02 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X5F : 39|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +BO_ 1302 XXX_27: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; + +VAL_ 399 STEER_STATUS 5 "tmp_fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_body.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_body.dbc new file mode 100644 index 000000000000000..363b595817b64e2 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_body.dbc @@ -0,0 +1,10 @@ +BO_ 318291879 BSM_STATUS_RIGHT: 8 XXX + SG_ BSM_ALERT : 4|1@0+ (1,0) [0|1] "" XXX + SG_ BSM_MODE : 6|2@0+ (1,0) [0|3] "" XXX + +BO_ 318291615 BSM_STATUS_LEFT: 8 XXX + SG_ BSM_ALERT : 4|1@0+ (1,0) [0|1] "" XXX + SG_ BSM_MODE : 6|2@0+ (1,0) [0|3] "" XXX + +VAL_ 318291879 BSM_MODE 2 "blind_spot" 1 "cross_traffic" 0 "off"; +VAL_ 318291615 BSM_MODE 2 "blind_spot" 1 "cross_traffic" 0 "off"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_can.dbc new file mode 100644 index 000000000000000..fe2ae8f940d793f --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_ex_2017_can.dbc @@ -0,0 +1,40 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _bosch_2018.dbc"; +CM_ "IMPORT _bosch_adas_2018.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX + SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 47|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied"; +CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas"; + +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_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_executive_2016_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_executive_2016_can.dbc new file mode 100644 index 000000000000000..7d0af4921768d2f --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_executive_2016_can.dbc @@ -0,0 +1,51 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (-1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_TORQUE_MOTOR : 23|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00_2 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +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_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_touring_2016_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_touring_2016_can.dbc new file mode 100644 index 000000000000000..75fd63f3b0d603e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_crv_touring_2016_can.dbc @@ -0,0 +1,49 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; +CM_ "IMPORT _steering_sensors_b.dbc"; + +BO_ 399 STEER_STATUS: 6 EPS + SG_ STEER_TORQUE_SENSOR : 7|12@0- (-1,0) [-2047.5|2047.5] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_CONTROL_ACTIVE : 36|1@0+ (1,0) [0|1] "" EON + SG_ STEER_STATUS : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ STEER_TORQUE : 7|12@0- (1,0) [-768|768] "" EPS + SG_ SET_ME_X00 : 11|4@0+ (1,0) [0|15] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00_2 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; + +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_ 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_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_ex_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_ex_2018_can.dbc new file mode 100644 index 000000000000000..371ddd19a8aa97e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_ex_2018_can.dbc @@ -0,0 +1,59 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; +CM_ "IMPORT _steering_sensors_b.dbc"; + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ DRIVERS_DOOR_OPEN : 63|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; + +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_ 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_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_hybrid_2018_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_hybrid_2018_can.dbc new file mode 100644 index 000000000000000..fa445b34966291e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_fit_hybrid_2018_can.dbc @@ -0,0 +1,80 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 545 ECON_STATUS: 5 XXX + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; + +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_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_insight_ex_2019_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_insight_ex_2019_can.dbc new file mode 100644 index 000000000000000..79c6dc161788220 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_insight_ex_2019_can.dbc @@ -0,0 +1,19 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _bosch_2018.dbc"; +CM_ "IMPORT _bosch_adas_2018.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON + SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ BRAKE_ERROR_1 : 13|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 12|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +VAL_ 419 GEAR 10 "R" 1 "D" 0 "P"; +VAL_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P"; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_exl_2018.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_exl_2018.dbc new file mode 100644 index 000000000000000..7a37e0124fa510a --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_exl_2018.dbc @@ -0,0 +1,86 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; +CM_ "IMPORT _steering_sensors_b.dbc"; + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 450 EPB_STATUS: 8 XXX + SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +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_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc new file mode 100644 index 000000000000000..fed29d066496f1a --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc @@ -0,0 +1,74 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _nidec_common.dbc"; + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-2985|2985] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 43|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + +BO_ 401 GEARBOX: 8 PCM + SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON + SG_ GEAR : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 404 STEERING_CONTROL: 4 EON + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EPS + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EPS + SG_ STEER_TORQUE : 7|16@0- (-1,0) [-32767|32767] "" EPS + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ DRIVERS_DOOR_OPEN : 63|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 XXX + SG_ EPB_BRAKE_AND_PULL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EPB_STATE : 29|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; +VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 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_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; diff --git a/opendbc_repo/opendbc/dbc/generator/honda/honda_pilot_2023_can.dbc b/opendbc_repo/opendbc/dbc/generator/honda/honda_pilot_2023_can.dbc new file mode 100644 index 000000000000000..df84d623fbf1cbd --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/honda/honda_pilot_2023_can.dbc @@ -0,0 +1,86 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _bosch_2018.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 419 GEARBOX: 8 XXX + SG_ GEAR_SHIFTER : 24|8@1+ (1,0) [0|255] "" XXX + SG_ GEAR : 32|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ GAS_COMMAND : 7|16@0- (1,0) [0|0] "" XXX + SG_ ACCEL_COMMAND : 31|11@0- (0.01,0) [0|0] "m/s2" XXX + SG_ BRAKE_LIGHTS : 62|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_REQUEST : 34|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL : 35|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_RELEASE : 36|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_STATUS : 33|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_BRAKING : 47|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_PREPARE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 829 LKAS_HUD: 8 XXX + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" XXX + SG_ BOH : 6|7@0+ (1,0) [0|127] "" XXX + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" XXX + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" XXX + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DTC : 13|1@0+ (1,0) [0|1] "" XXX + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" XXX + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" XXX + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" XXX + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LANE_LINES : 36|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; +CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; +CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; +CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; +CM_ SG_ 829 LANE_LINES "related to lane lines on cluster, left/right white/green"; + +VAL_ 419 GEAR_SHIFTER 2 "S" 32 "D" 16 "N" 8 "R" 4 "P"; +VAL_ 419 GEAR 26 "S" 20 "D" 19 "N" 18 "R" 17 "P"; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 829 LANE_LINES 7 "both_lines_green" 6 "both_lines_white" 2 "left_line_white" 0 "no_lines"; diff --git a/opendbc_repo/opendbc/dbc/generator/hyundai/.gitignore b/opendbc_repo/opendbc/dbc/generator/hyundai/.gitignore new file mode 100644 index 000000000000000..81f73f3551c3b39 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/hyundai/.gitignore @@ -0,0 +1,2 @@ +hyundai_kia_mando_front_radar.dbc +hyundai_kia_mando_corner_radar.dbc diff --git a/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_kia_mando_corner_radar.py b/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_kia_mando_corner_radar.py new file mode 100755 index 000000000000000..aad417e32ac5185 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_kia_mando_corner_radar.py @@ -0,0 +1,170 @@ +#!/usr/bin/env python3 +from collections import namedtuple +import os + +if __name__ == "__main__": + dbc_name = os.path.basename(__file__).replace(".py", ".dbc") + hyundai_path = os.path.dirname(os.path.realpath(__file__)) + with open(os.path.join(hyundai_path, dbc_name), "w", encoding='utf-8') as f: + f.write(""" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX +""") + + for a in [0x100, 0x200]: + f.write(f""" +BO_ {a} RADAR_POINTS_METADATA_0x{a:x}: 64 RADAR + SG_ SIGNAL_1 : 0|32@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_2 : 32|32@1+ (1,0) [0|65535] "" XXX + SG_ SIGNAL_3 : 64|4@1+ (1,0) [0|15] "" XXX + SG_ SIGNAL_4 : 68|4@1+ (1,0) [0|15] "" XXX + SG_ RADAR_POINT_COUNT : 72|8@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_6 : 80|7@1+ (0.015625,0) [0|3] "" XXX + SG_ SIGNAL_7 : 87|1@1+ (1,0) [0|1] "" XXX + SG_ SIGNAL_8 : 88|3@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_9 : 91|5@1+ (0.0625,0) [0|31] "" XXX + SG_ SIGNAL_10 : 96|8@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_11 : 104|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_12 : 111|2@1+ (1,0) [0|65535] "" XXX + SG_ SIGNAL_13 : 113|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_14 : 120|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_15 : 127|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_16 : 130|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_17 : 133|2@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_18 : 134|1@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_19 : 135|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_20 : 138|8@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_21 : 146|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_22 : 148|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_23 : 149|4@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_24 : 153|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_25 : 154|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_26 : 157|2@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_27 : 158|7@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_28 : 165|7@1+ (0.015625,0) [0|31] "" XXX + SG_ SIGNAL_29 : 172|7@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_30 : 179|7@1+ (0.015625,0) [0|1] "" XXX + SG_ SIGNAL_31 : 186|4@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_32 : 190|14@1+ (0.015625,0) [0|15] "" XXX + SG_ SIGNAL_33 : 204|11@1+ (0.03125,0) [0|8191] "" XXX + SG_ SIGNAL_34 : 215|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_35 : 217|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_36 : 224|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_37 : 230|6@1+ (0.2,0) [0|31] "" XXX + SG_ SIGNAL_38 : 236|6@1+ (0.2,0) [0|7] "" XXX + SG_ SIGNAL_39 : 242|8@1+ (1,-90) [0|255] "" XXX + SG_ SIGNAL_40 : 250|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_41 : 256|8@1+ (0.25,0) [0|255] "" XXX + SG_ SIGNAL_42 : 264|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_43 : 267|12@1+ (0.01,0) [0|31] "" XXX + SG_ SIGNAL_44 : 279|32@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_45 : 311|1@1+ (1,0) [0|1] "" XXX + SG_ SIGNAL_46 : 312|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_47 : 314|32@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_48 : 346|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_49 : 352|7@1+ (0.25,0) [0|127] "" XXX + SG_ SIGNAL_50 : 359|6@1+ (0.03125,0) [0|31] "" XXX + SG_ SIGNAL_51 : 365|10@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_52 : 375|10@1+ (0.125,0) [0|63] "" XXX + SG_ SIGNAL_53 : 385|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_54 : 392|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_55 : 399|8@1+ (0.00390625,0) [0|31] "" XXX + SG_ SIGNAL_56 : 407|10@1+ (0.125,0) [0|63] "" XXX + SG_ SIGNAL_57 : 417|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_58 : 418|1@1+ (1,0) [0|3] "" XXX +""") + + # radar points are sent at 20 Hz in groups of 1 to 13 messages + # each message has 5 radar points for a total of 65 points max + # each radar point is 101 bits so the alignment is not consistent + RadarPointSignal = namedtuple("RadarPointSignal", ["name", "start", "length", "scale", "offset"]) + radar_point_signals = ( + RadarPointSignal("DISTANCE", 7, 14, 1/64, 0), + RadarPointSignal("", 21, 2, 1, 0), + RadarPointSignal("", 23, 8, 1/512, -127/512), + RadarPointSignal("REL_VELOCITY", 31, 13, 1/32, -66), + RadarPointSignal("", 44, 2, 1, 0), + RadarPointSignal("", 46, 2, 1, 0), + RadarPointSignal("AZIMUTH", 48, 12, 1/512, -2047/512), + RadarPointSignal("", 60, 2, 1, 0), + RadarPointSignal("", 62, 1, 1, 0), + RadarPointSignal("", 63, 7, 1, 0), + RadarPointSignal("", 70, 1, 1, 0), + RadarPointSignal("", 71, 6, 1, 0), + RadarPointSignal("", 77, 2, 1, 0), + RadarPointSignal("", 79, 8, 1/512, -127/512), + RadarPointSignal("", 87, 1, 1, 0), + RadarPointSignal("", 88, 2, 1, 0), + RadarPointSignal("", 90, 3, 1, 0), + # last 15 bits are controlled by LAYOUT_ID (seems to always zero, so below is layout 0) + RadarPointSignal("", 93, 6, 1, 0), + RadarPointSignal("", 99, 8, 1, 0), + RadarPointSignal("", 107, 1, 1, 0), + ) + radar_point_bit_count = sum([s.length for s in radar_point_signals]) + + for a in [0x101, 0x201]: + f.write(f""" +BO_ {a} RADAR_POINTS_0x{a:x}: 64 RADAR + SG_ MESSAGE_ID : 0|5@1+ (1,0) [0|31] "" XXX + SG_ LAYOUT_ID : 5|2@1+ (1,0) [0|3] "" XXX +""") + bit_idx = radar_point_signals[0].start + for i in range(5): + signal_idx = 1 + for sig in radar_point_signals: + if sig.name: + sig_name = f"POINT_{i+1}_{sig.name}" + else: + sig_name = f"POINT_{i+1}_SIGNAL_{signal_idx}" + signal_idx += 1 + + sig_start_idx = i * radar_point_bit_count + sig.start + assert bit_idx == sig_start_idx, f"signal overlap or gap!!! {bit_idx} != {sig_start_idx}" + min_val = round(sig.offset, 10) + max_val = round((2**sig.length - 1) * sig.scale + sig.offset, 10) + + f.write(f" SG_ {sig_name} : {sig_start_idx}|{sig.length}@1+ ({sig.scale},{sig.offset}) [{min_val}|{max_val}] \"\" XXX\n") + bit_idx += sig.length + + # checksum is across a group of 0x100/200 and 0x101/201 messages (no checksums inside the other messages) + # ccitt_crc16 = mkCrcFun(0x11021, initCrc=0xffff, xorOut=0x0000, rev=False) + for a in [0x104, 0x204]: + f.write(f""" +BO_ {a} RADAR_POINTS_CHECKSUM_0x{a:x}: 3 RADAR + SG_ CRC16 : 0|16@1+ (1,0) [0|65535] "" XXX +""") diff --git a/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_kia_mando_front_radar.py b/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_kia_mando_front_radar.py new file mode 100755 index 000000000000000..ee8dde64d472a6b --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/hyundai/hyundai_kia_mando_front_radar.py @@ -0,0 +1,61 @@ +#!/usr/bin/env python3 +import os + +if __name__ == "__main__": + dbc_name = os.path.basename(__file__).replace(".py", ".dbc") + hyundai_path = os.path.dirname(os.path.realpath(__file__)) + with open(os.path.join(hyundai_path, dbc_name), "w", encoding='utf-8') as f: + f.write(""" +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + """) + + # note: 0x501/0x502 seem to be special in 0x5XX range + for a in range(0x500, 0x500 + 32): + f.write(f""" +BO_ {a} RADAR_TRACK_{a:x}: 8 RADAR + SG_ UNKNOWN_1 : 7|8@0- (1,0) [-128|127] "" XXX + SG_ AZIMUTH : 12|10@0- (0.2,0) [-102.4|102.2] "" XXX + SG_ STATE : 15|3@0+ (1,0) [0|7] "" XXX + SG_ LONG_DIST : 18|11@0+ (0.1,0) [0|204.7] "" XXX + SG_ REL_ACCEL : 33|10@0- (0.02,0) [-10.24|10.22] "" XXX + SG_ ZEROS : 37|4@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 38|1@0+ (1,0) [0|1] "" XXX + SG_ STATE_3 : 39|1@0+ (1,0) [0|1] "" XXX + SG_ REL_SPEED : 53|14@0- (0.01,0) [-81.92|81.92] "" XXX + SG_ STATE_2 : 55|2@0+ (1,0) [0|3] "" XXX + """) diff --git a/opendbc_repo/opendbc/dbc/generator/nissan/_nissan_common.dbc b/opendbc_repo/opendbc/dbc/generator/nissan/_nissan_common.dbc new file mode 100644 index 000000000000000..6300ea94258aa09 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/nissan/_nissan_common.dbc @@ -0,0 +1,113 @@ +BO_ 2 STEER_ANGLE_SENSOR: 5 XXX + SG_ STEER_ANGLE_RATE : 16|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X07 : 24|8@1+ (1,0) [0|255] "" XXX + SG_ STEER_ANGLE : 0|16@1- (-0.1,0) [0|65535] "" XXX + SG_ COUNTER : 32|4@1+ (1,0) [0|15] "" XXX + +BO_ 361 LKAS: 8 XXX + SG_ MAX_TORQUE : 39|8@0+ (0.01,0) [0|255] "Nm" XXX + SG_ SET_0x80 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ LKA_ACTIVE : 52|1@0+ (1,0) [0|15] "" XXX + SG_ SET_0x80_2 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ DESIRED_ANGLE : 7|18@0+ (-0.01,1310) [-1311.43|1310] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 389 STEER_TORQUE_SENSOR: 8 XXX + SG_ LKAS_ACTIVE : 37|1@0+ (1,0) [0|3] "" XXX + SG_ STEER_TORQUE_LKAS : 47|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_ANGLE : 23|18@0+ (-0.01,1310) [0|262143] "" XXX + SG_ STEER_TORQUE_DRIVER : 7|12@0+ (-0.01,20.47) [0|4095] "Nm" XXX + SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|127] "" XXX + +BO_ 645 WHEEL_SPEEDS_REAR: 8 XXX + SG_ WHEEL_SPEED_RR : 7|16@0+ (0.005,0) [0|65535] "KPH" XXX + SG_ WHEEL_SPEED_RL : 23|16@0+ (0.005,0) [0|65535] "KPH" XXX + +BO_ 689 PROPILOT_HUD: 8 XXX + SG_ LARGE_WARNING_FLASHING : 9|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_RADAR_ERROR_FLASHING1 : 10|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_RADAR_ERROR_FLASHING2 : 11|1@0+ (1,0) [0|1] "" XXX + SG_ RIGHT_LANE_YELLOW_FLASH : 12|1@0+ (1,0) [0|1] "" XXX + SG_ LEFT_LANE_YELLOW_FLASH : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_CAR : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_CAR_ERROR : 15|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_RADAR_ERROR : 16|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_RADAR_ERROR_FLASHING : 17|1@0+ (1,0) [0|1] "" XXX + SG_ RIGHT_LANE_GREEN : 24|1@0+ (1,0) [0|1] "" XXX + SG_ LEFT_LANE_GREEN : 25|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_RADAR_ERROR_FLASHING3 : 27|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_ERROR_FLASHING : 29|1@0+ (1,0) [0|1] "" XXX + SG_ SAFETY_SHIELD_ACTIVE : 44|1@0+ (1,0) [0|1] "" XXX + SG_ LARGE_STEERING_WHEEL_ICON : 61|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LANE_GREEN_FLASH : 62|1@0+ (1,0) [0|1] "" XXX + SG_ LEFT_LANE_GREEN_FLASH : 63|1@0+ (1,0) [0|1] "" XXX + SG_ FOLLOW_DISTANCE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ AUDIBLE_TONE : 47|3@0+ (1,0) [0|8] "" XXX + SG_ SPEED_SET_ICON : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SMALL_STEERING_WHEEL_ICON : 42|3@0+ (1,0) [0|7] "" XXX + SG_ SET_SPEED : 39|8@0+ (1,0) [0|255] "" XXX + SG_ unknown02 : 1|2@0+ (1,0) [0|3] "" XXX + SG_ unknown05 : 5|2@0+ (1,0) [0|3] "" XXX + SG_ unknown08 : 8|7@0+ (1,0) [0|63] "" XXX + SG_ unknown26 : 26|1@0+ (1,0) [0|1] "" XXX + SG_ unknown28 : 28|1@0+ (1,0) [0|1] "" XXX + SG_ unknown31 : 31|2@0+ (1,0) [0|3] "" XXX + SG_ unknown43 : 43|1@0+ (1,0) [0|1] "" XXX + SG_ unknown55 : 55|8@0+ (1,0) [0|63] "" XXX + SG_ unknown59 : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 783 CRUISE_STATE: 3 XXX + SG_ CRUISE_ENABLED : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 1228 PROPILOT_HUD_INFO_MSG: 8 XXX + SG_ NA_HIGH_ACCEL_TEMP : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_RADAR_NA_HIGH_CABIN_TEMP : 8|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_RADAR_MALFUNCTION : 11|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_MALFUNCTION : 12|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_RADAR_MALFUNCTION : 13|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_RADAR_NA_CLEAN_REAR_CAMERA : 14|1@0+ (1,0) [0|1] "" XXX + SG_ NA_POOR_ROAD_CONDITIONS : 16|1@0+ (1,0) [0|1] "" XXX + SG_ CURRENTLY_UNAVAILABLE : 17|1@0+ (1,0) [0|1] "" XXX + SG_ SAFETY_SHIELD_OFF : 18|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_COLLISION_NA_FRONT_RADAR_OBSTRUCTION : 20|1@0+ (1,0) [0|1] "" XXX + SG_ PEDAL_MISSAPPLICATION_SYSTEM_ACTIVATED : 24|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_IMPACT_NA_RADAR_OBSTRUCTION : 25|1@0+ (1,0) [0|1] "" XXX + SG_ WARNING_DO_NOT_ENTER : 33|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_IMPACT_SYSTEM_OFF : 34|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_IMPACT_MALFUNCTION : 35|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_COLLISION_MALFUNCTION : 36|1@0+ (1,0) [0|1] "" XXX + SG_ SIDE_RADAR_MALFUNCTION2 : 37|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_MALFUNCTION2 : 38|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_RADAR_MALFUNCTION2 : 39|1@0+ (1,0) [0|1] "" XXX + SG_ PROPILOT_NA_MSGS : 42|3@0+ (1,0) [0|7] "" XXX + SG_ BOTTOM_MSG : 45|3@0+ (1,0) [0|7] "" XXX + SG_ HANDS_ON_WHEEL_WARNING : 47|1@0+ (1,0) [0|1] "" XXX + SG_ WARNING_STEP_ON_BRAKE_NOW : 51|1@0+ (1,0) [0|1] "" XXX + SG_ PROPILOT_NA_FRONT_CAMERA_OBSTRUCTED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ PROPILOT_NA_HIGH_CABIN_TEMP : 53|1@0+ (1,0) [0|1] "" XXX + SG_ WARNING_PROPILOT_MALFUNCTION : 54|1@0+ (1,0) [0|3] "" XXX + SG_ ACC_UNAVAILABLE_HIGH_CABIN_TEMP : 62|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_NA_FRONT_CAMERA_IMPARED : 63|1@0+ (1,0) [0|1] "" XXX + SG_ unknown07 : 7|7@0+ (1,0) [0|127] "" XXX + SG_ unknown10 : 10|2@0+ (1,0) [0|3] "" XXX + SG_ unknown15 : 15|1@0+ (1,0) [0|1] "" XXX + SG_ unknown23 : 23|3@0+ (1,0) [0|7] "" XXX + SG_ unknown19 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ unknown31 : 31|6@0+ (1,0) [0|63] "" XXX + SG_ unknown32 : 32|1@0+ (1,0) [0|1] "" XXX + SG_ unknown46 : 46|1@0+ (1,0) [0|1] "" XXX + SG_ unknown50 : 50|3@0+ (1,0) [0|7] "" XXX + SG_ unknown55 : 55|1@0+ (1,0) [0|1] "" XXX + SG_ unknown61 : 61|6@0+ (1,0) [0|63] "" XXX + +BO_ 1227 LKAS_SETTINGS: 8 XXX + SG_ LKAS_ENABLED : 51|1@0+ (1,0) [0|1] "" XXX + +VAL_ 1228 PROPILOT_NA_MSGS 0 "NO_MSG" 1 "NA_FRONT_CAMERA_IMPARED" 2 "STEERING_ASSIST_ON_STANDBY" 3 "NA_PARKING_ASSIST_ENABLED" 4 "STEER_ASSIST_CURRENTLY_NA" 5 "NA_BAD_WEATHER" 6 "NA_PARK_BRAKE_ON" 7 "NA_SEATBELT_NOT_FASTENED" ; +VAL_ 1228 BOTTOM_MSG 0 "OK_STEER_ASSIST_SETTINGS" 1 "NO_MSG" 2 "PRESS_SET_TO_SET_SPEED" 3 "PRESS_RES_SET_TO_CHANGE_SPEED" 4 "PRESS_RES_TO_RESTART" 5 "NO_MSG" 6 "CRUISE_NOT_AVAIL" 7 "NO_MSG" ; +VAL_ 689 FOLLOW_DISTANCE 0 "NO_FOLLOW_DISTANCE" 1 "FOLLOW_DISTANCE_1" 2 "FOLLOW_DISTANCE_2" 3 "FOLLOW_DISANCE_3" ; +VAL_ 689 AUDIBLE_TONE 0 "NO_TONE" 1 "CONT" 2 "FAST_BEEP_CONT" 3 "TRIPLE_FAST_BEEP_CONT" 4 "SLOW_BEEP_CONT" 5 "QUAD_SLOW_BEEP_CONT" 6 "SINGLE_BEEP_ONCE" 7 "DOUBLE_BEEP_ONCE" ; +VAL_ 689 SMALL_STEERING_WHEEL_ICON 0 "NO_ICON" 1 "GRAY_ICON" 2 "GRAY_ICON_FLASHING" 3 "GREEN_ICON" 4 "GREEN_ICON_FLASHING" 5 "RED_ICON" 6 "RED_ICON_FLASHING" 7 "YELLOW_ICON" ; +VAL_ 689 LARGE_STEERING_WHEEL_ICON 0 "NO_STEERINGWHEEL" 1 "GRAY_STEERINGWHEEL" 2 "GREEN_STEERINGWHEEL" 3 "GREEN_STEERINGWHEEL_FLASHING" ; diff --git a/opendbc_repo/opendbc/dbc/generator/nissan/nissan_leaf_2018.dbc b/opendbc_repo/opendbc/dbc/generator/nissan/nissan_leaf_2018.dbc new file mode 100644 index 000000000000000..3376c3784c431dc --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/nissan/nissan_leaf_2018.dbc @@ -0,0 +1,62 @@ +CM_ "IMPORT _nissan_common.dbc"; + +BO_ 42 SEATBELT: 8 XXX + SG_ SEATBELT_DRIVER_LATCHED : 27|1@1+ (1,0) [0|3] "" XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 26|1@0+ (1,0) [0|1] "" XXX + SG_ unknown2 : 31|4@0+ (1,0) [0|15] "" XXX + SG_ unknown3 : 24|2@1+ (1,0) [0|3] "" XXX + SG_ unknown1 : 7|24@0+ (1,0) [0|16777215] "" XXX + SG_ unknown4 : 39|16@0+ (1,0) [0|65535] "" XXX + +BO_ 460 BRAKE_PEDAL: 8 XXX + SG_ BRAKE_PEDAL : 7|8@0+ (1,0) [0|256] "" XXX + +BO_ 569 CRUISE_THROTTLE: 8 XXX + SG_ GAS_PEDAL_INVERTED : 15|8@0+ (1,0) [0|255] "" XXX + SG_ GAS_PEDAL : 7|8@0+ (1,0) [0|255] "" XXX + SG_ CRUISE_AVAILABLE : 17|1@0+ (1,0) [0|1] "" XXX + SG_ unsure1 : 23|6@0+ (1,0) [0|63] "" XXX + SG_ unsure2 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ unsure3 : 31|2@0+ (1,0) [0|3] "" XXX + SG_ NO_BUTTON_PRESSED : 29|1@0+ (1,0) [0|1] "" XXX + SG_ RES_BUTTON : 28|1@0+ (1,0) [0|1] "" XXX + SG_ SET_BUTTON : 27|1@0+ (1,0) [0|1] "" XXX + SG_ FOLLOW_DISTANCE_BUTTON : 26|1@0+ (1,0) [0|1] "" XXX + SG_ CANCEL_BUTTON : 25|1@0+ (1,0) [0|1] "" XXX + SG_ PROPILOT_BUTTON : 24|1@0+ (1,0) [0|1] "" XXX + SG_ USER_BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 32|2@1+ (1,0) [0|3] "" XXX + SG_ unsure5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ unsure6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ unsure7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 640 CANCEL_MSG: 8 XXX + SG_ CANCEL_SEATBELT : 1|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 7|6@0+ (1,0) [0|63] "" XXX + SG_ NEW_SIGNAL_2 : 0|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 15|56@0+ (1,0) [0|72057594037927940] "" XXX + +BO_ 644 WHEEL_SPEEDS_FRONT: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.005,0) [0|65535] "KPH" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.005,0) [0|65535] "KPH" XXX + +BO_ 852 ESP: 8 XXX + SG_ ESP_DISABLED : 38|1@0+ (1,0) [0|1] "" XXX + +BO_ 853 HUD_SETTINGS: 8 XXX + SG_ SPEED_MPH : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 856 LIGHTS: 8 XXX + SG_ LEFT_BLINKER : 17|1@0+ (1,0) [0|1] "" XXX + SG_ RIGHT_BLINKER : 18|1@0+ (1,0) [0|1] "" XXX + +BO_ 1057 GEARBOX: 3 XXX + SG_ GEAR_SHIFTER : 5|3@0+ (1,0) [0|255] "" XXX + +BO_ 1549 DOORS_LIGHTS: 8 XXX + SG_ DOOR_OPEN_FL : 3|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 4|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 5|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 6|1@0+ (1,0) [0|1] "" XXX + +VAL_ 1057 GEAR_SHIFTER 7 "B" 4 "D" 3 "N" 2 "R" 1 "P" ; diff --git a/opendbc_repo/opendbc/dbc/generator/nissan/nissan_x_trail_2017.dbc b/opendbc_repo/opendbc/dbc/generator/nissan/nissan_x_trail_2017.dbc new file mode 100644 index 000000000000000..46e6f9c99a03499 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/nissan/nissan_x_trail_2017.dbc @@ -0,0 +1,69 @@ +CM_ "IMPORT _nissan_common.dbc"; + +BO_ 348 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL_RAW : 26|11@0+ (1,0) [0|2047] "" XXX + SG_ GAS_PEDAL : 47|10@0+ (1,0) [0|1023] "" XXX + +BO_ 438 PRO_PILOT: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X03 : 33|2@0+ (1,0) [0|15] "" XXX + SG_ CRUISE_ACTIVATED : 38|1@0+ (1,0) [0|3] "" XXX + SG_ CRUISE_ON : 36|1@0+ (1,0) [0|255] "" XXX + SG_ STEER_STATUS : 51|1@0+ (1,0) [0|3] "" XXX + +BO_ 523 CRUISE_THROTTLE: 6 XXX + SG_ PROPILOT_BUTTON : 8|1@0+ (1,0) [0|1] "" XXX + SG_ CANCEL_BUTTON : 9|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL_INVERTED : 37|10@0+ (1,0) [0|1023] "" XXX + SG_ SET_BUTTON : 11|1@0+ (1,0) [0|1] "" XXX + SG_ RES_BUTTON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ FOLLOW_DISTANCE_BUTTON : 10|1@0+ (1,0) [0|1] "" XXX + SG_ NO_BUTTON_PRESSED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL : 31|10@0+ (1,0) [0|255] "" XXX + SG_ USER_BRAKE_PRESSED : 21|1@0+ (1,0) [0|1] "" XXX + SG_ USER_BRAKE_PRESSED_INVERTED : 22|1@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_2 : 23|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PRESSED_INVERTED : 20|1@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 17|2@0+ (1,0) [0|3] "" XXX + SG_ unsure1 : 7|10@0+ (1,0) [0|1023] "" XXX + SG_ unsure2 : 43|4@0+ (1,0) [0|1] "" XXX + SG_ unsure3 : 19|2@0+ (1,0) [0|3] "" XXX + +BO_ 665 ESP: 8 XXX + SG_ ESP_DISABLED : 24|1@0+ (1,0) [0|1] "" XXX + +BO_ 666 WHEEL_SPEEDS_FRONT: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.005,0) [0|65535] "KPH" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.005,0) [0|65535] "KPH" XXX + +BO_ 768 STEER_TORQUE_SENSOR2: 2 XXX + SG_ STEERING_TORQUE : 6|7@0+ (1,0) [0|127] "" XXX + SG_ STEERING_PRESSED : 15|1@0+ (-1,1) [0|7] "" XXX + +BO_ 1055 GEARBOX: 2 XXX + SG_ SPORTS_MODE : 13|1@0+ (1,0) [0|1] "" XXX + SG_ GEAR_SHIFTER : 5|3@0+ (1,0) [0|255] "" XXX + +BO_ 1107 LIGHTS: 8 XXX + SG_ RIGHT_BLINKER : 12|1@0+ (1,0) [0|1] "" XXX + SG_ LEFT_BLINKER : 11|1@0+ (1,0) [0|1] "" XXX + SG_ HEADLIGHTS : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 1108 DOORS_LIGHTS: 8 XXX + SG_ DOOR_CLOSED_RR : 40|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 41|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_FL : 44|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_FR : 46|1@0+ (1,0) [0|3] "" XXX + SG_ DOOR_OPEN_FR : 47|1@0+ (1,0) [0|3] "" XXX + SG_ BOOT_OPEN : 55|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHT : 54|1@0+ (1,0) [0|1] "" XXX + SG_ USER_BRAKE_PRESSED : 23|1@0+ (1,0) [0|1] "" XXX + +BO_ 1273 HUD: 7 XXX + SG_ SEATBELT_DRIVER_LATCHED : 25|1@0+ (1,0) [0|1] "" XXX + SG_ SPEED_MPH : 5|1@0+ (1,0) [0|1] "" XXX + +VAL_ 1055 GEAR_SHIFTER 6 "L" 4 "D" 3 "N" 2 "R" 1 "P" ; diff --git a/opendbc_repo/opendbc/dbc/generator/subaru/_subaru_global.dbc b/opendbc_repo/opendbc/dbc/generator/subaru/_subaru_global.dbc new file mode 100644 index 000000000000000..69c836193854a19 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/subaru/_subaru_global.dbc @@ -0,0 +1,302 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX X + + +BO_ 2 Steering: 8 XXX + SG_ Steering_Angle : 7|16@0- (0.1,0) [0|65535] "" XXX + SG_ COUNTER : 25|3@1+ (1,0) [0|7] "" XXX + SG_ CHECKSUM : 32|8@1+ (1,0) [0|255] "" XXX + +BO_ 64 Throttle: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Signal1 : 12|4@1+ (1,0) [0|15] "" XXX + SG_ Engine_RPM : 16|12@1+ (1,0) [0|4095] "" XXX + SG_ Signal2 : 28|4@1+ (1,0) [0|15] "" XXX + SG_ Throttle_Pedal : 32|8@1+ (1,0) [0|255] "" XXX + SG_ Throttle_Cruise : 40|8@1+ (1,0) [0|255] "" XXX + SG_ Throttle_Combo : 48|8@1+ (1,0) [0|255] "" XXX + SG_ Signal3 : 56|4@1+ (1,0) [0|15] "" XXX + SG_ Off_Accel : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 316 Brake_Status: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Signal1 : 12|46@1+ (1,0) [0|1] "" XXX + SG_ ES_Brake : 58|1@1+ (1,0) [0|1] "" XXX + SG_ Signal2 : 59|3@1+ (1,0) [0|1] "" XXX + SG_ Brake : 62|1@1+ (1,0) [0|1] "" XXX + SG_ Signal3 : 63|1@1+ (1,0) [0|1] "" XXX + +BO_ 326 Cruise_Buttons: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Signal1 : 12|30@1+ (1,0) [0|1073741823] "" XXX + SG_ Main : 42|1@1+ (1,0) [0|1] "" XXX + SG_ Set : 43|1@1+ (1,0) [0|1] "" XXX + SG_ Resume : 44|1@1+ (1,0) [0|1] "" XXX + SG_ Signal2 : 45|19@1+ (1,0) [0|524287] "" XXX + +BO_ 315 G_Sensor: 8 XXX + SG_ Lateral : 48|8@1- (-0.1,0) [0|255] "m/s2" XXX + SG_ Longitudinal : 56|8@1- (-0.1,0) [0|255] "m/s2" XXX + +BO_ 314 Wheel_Speeds: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ FR : 12|13@1+ (0.057,0) [0|255] "kph" XXX + SG_ RR : 25|13@1+ (0.057,0) [0|255] "kph" XXX + SG_ FL : 51|13@1+ (0.057,0) [0|255] "kph" XXX + SG_ RL : 38|13@1+ (0.057,0) [0|255] "kph" XXX + +BO_ 280 Steering_Torque_2: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Steer_Torque_Output : 13|11@1- (-10,0) [0|255] "" XXX + SG_ Signal1 : 24|8@1+ (1,0) [0|511] "" XXX + SG_ Steer_Torque_Sensor : 45|11@1- (-1,0) [0|255] "" XXX + SG_ Steering_Active : 61|1@0+ (1,0) [0|1] "" XXX + SG_ Steering_Disabled : 63|1@1+ (1,0) [0|1] "" XXX + +BO_ 281 Steering_Torque: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Steer_Error_1 : 12|1@0+ (1,0) [0|1] "" XXX + SG_ Steer_Torque_Sensor : 16|11@1- (-1,0) [-1000|1000] "" XXX + SG_ Steer_Error_2 : 28|1@1+ (1,0) [0|1] "" XXX + SG_ Steer_Warning : 29|1@1+ (1,0) [0|1] "" XXX + SG_ Steering_Angle : 32|16@1- (-0.0217,0) [-600|600] "" X + SG_ Steer_Torque_Output : 48|11@1- (-10,0) [-1000|1000] "" XXX + +BO_ 282 Steering_2: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|1] "" XXX + SG_ Steering_Angle : 24|17@1- (-0.01,0) [0|1] "" XXX + +BO_ 312 Brake_Pressure_L_R: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Brake_1 : 48|8@1+ (1,0) [0|255] "" XXX + SG_ Brake_2 : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 313 Brake_Pedal: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Signal1 : 12|4@1+ (1,0) [0|15] "" XXX + SG_ Speed : 16|12@1+ (0.05625,0) [0|255] "kph" XXX + SG_ Signal2 : 28|6@1+ (1,0) [0|63] "" XXX + SG_ Brake_Lights : 34|1@1+ (1,0) [0|1] "" XXX + SG_ Signal3 : 35|1@1+ (1,0) [0|1] "" XXX + SG_ Brake_Pedal : 36|12@1+ (1,0) [0|4095] "" XXX + SG_ Signal4 : 48|16@1+ (1,0) [0|65535] "" XXX + +BO_ 372 Engine_Stop_Start: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX + SG_ STOP_START_STATE : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 290 ES_LKAS: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ SET_1 : 12|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_Output : 16|13@1- (-1,0) [-8191|8191] "" XXX + SG_ LKAS_Request : 29|1@0+ (1,0) [0|1] "" XXX + +BO_ 292 ES_LKAS_ANGLE: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Request : 12|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Output : 40|17@1- (-0.01,0) [0|1] "deg" XXX + SG_ SET_3 : 60|2@1+ (1,0) [0|1] "" XXX + +BO_ 544 ES_Brake: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Signal1 : 12|4@1+ (1,0) [0|15] "" XXX + SG_ Brake_Pressure : 16|16@1+ (1,0) [0|65535] "" XXX + SG_ AEB_Status : 32|4@1+ (1,0) [0|15] "" XXX + SG_ Cruise_Brake_Lights : 36|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Brake_Fault : 37|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Brake_Active : 38|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 39|1@1+ (1,0) [0|1] "" XXX + SG_ Signal3 : 40|24@1+ (1,0) [0|16777215] "" XXX + +BO_ 577 Cruise_Status: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Cruise_Set_Speed : 51|12@0+ (1,0) [0|120] "" XXX + SG_ Cruise_On : 54|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 55|1@1+ (1,0) [0|1] "" XXX + +BO_ 552 BSD_RCTA: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ R_ADJACENT : 48|1@1+ (1,0) [0|1] "" XXX + SG_ L_ADJACENT : 49|1@1+ (1,0) [0|1] "" XXX + SG_ R_APPROACHING : 58|1@1+ (1,0) [0|1] "" XXX + SG_ L_APPROACHING : 59|1@1+ (1,0) [0|1] "" XXX + +BO_ 912 Dashlights: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ UNITS : 24|1@1+ (1,0) [0|1] "" XXX + SG_ ICY_ROAD : 32|2@1+ (1,0) [0|3] "" XXX + SG_ SEATBELT_FL : 48|1@1+ (1,0) [0|1] "" XXX + SG_ LEFT_BLINKER : 50|1@1+ (1,0) [0|1] "" XXX + SG_ RIGHT_BLINKER : 51|1@1+ (1,0) [0|1] "" XXX + SG_ STOP_START : 54|1@0+ (1,0) [0|1] "" XXX + +BO_ 940 BodyInfo: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ DOOR_OPEN_FL : 32|1@1+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 33|1@1+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 34|1@1+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 35|1@1+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_TRUNK : 36|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE : 54|1@1+ (1,0) [0|1] "" XXX + SG_ DASH_BTN_LIGHTS : 56|1@0+ (1,0) [0|1] "" XXX + SG_ LOWBEAM : 57|1@1+ (1,0) [0|1] "" XXX + SG_ HIGHBEAM : 58|1@1+ (1,0) [0|1] "" XXX + SG_ FOG_LIGHTS : 60|1@1+ (1,0) [0|1] "" XXX + SG_ WIPERS : 62|1@0+ (1,0) [0|1] "" XXX + +BO_ 801 ES_DashStatus: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ PCB_Off : 12|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_Off : 13|1@1+ (1,0) [0|1] "" XXX + SG_ Signal1 : 14|2@1+ (1,0) [0|3] "" XXX + SG_ Cruise_State_Msg : 16|4@1+ (1,0) [0|15] "" XXX + SG_ LKAS_State_Msg : 20|3@1+ (1,0) [0|7] "" XXX + SG_ Signal2 : 23|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Soft_Disable : 24|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Status_Msg : 25|2@1+ (1,0) [0|3] "" XXX + SG_ Signal3 : 27|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Distance : 28|3@1+ (1,0) [0|7] "" XXX + SG_ Signal4 : 31|1@1+ (1,0) [0|1] "" XXX + SG_ Conventional_Cruise : 32|1@1+ (1,0) [0|1] "" XXX + SG_ Signal5 : 33|2@1+ (1,0) [0|3] "" XXX + SG_ Cruise_Disengaged : 35|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 36|1@1+ (1,0) [0|1] "" XXX + SG_ Signal6 : 37|3@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Set_Speed : 40|8@1+ (1,0) [0|255] "" XXX + SG_ Cruise_Fault : 48|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_On : 49|1@1+ (1,0) [0|1] "" XXX + SG_ Display_Own_Car : 50|1@1+ (1,0) [0|1] "" XXX + SG_ Brake_Lights : 51|1@1+ (1,0) [0|1] "" XXX + SG_ Car_Follow : 52|1@1+ (1,0) [0|1] "" XXX + SG_ Signal7 : 53|3@1+ (1,0) [0|1] "" XXX + SG_ Far_Distance : 56|4@1+ (5,0) [0|75] "m" XXX + SG_ Cruise_State : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 802 ES_LKAS_State: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ LKAS_Alert_Msg : 12|3@1+ (1,0) [0|7] "" XXX + SG_ Signal1 : 15|2@1+ (1,0) [0|3] "" XXX + SG_ LKAS_ACTIVE : 17|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Dash_State : 18|2@1+ (1,0) [0|2] "" XXX + SG_ Signal2 : 20|3@1+ (1,0) [0|7] "" XXX + SG_ Backward_Speed_Limit_Menu : 23|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Left_Line_Enable : 24|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Left_Line_Light_Blink : 25|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Right_Line_Enable : 26|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Right_Line_Light_Blink : 27|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Left_Line_Visible : 28|2@1+ (1,0) [0|3] "" XXX + SG_ LKAS_Right_Line_Visible : 30|2@1+ (1,0) [0|3] "" XXX + SG_ LKAS_Alert : 32|5@1+ (1,0) [0|31] "" XXX + SG_ Signal3 : 37|27@1+ (1,0) [0|1] "" XXX + +BO_ 803 ES_Infotainment: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ LKAS_Blue_Lines : 15|4@0+ (1,0) [0|15] "" XXX + SG_ Signal1 : 19|4@0+ (1,0) [0|15] "" XXX + SG_ LKAS_State_Infotainment : 22|3@0+ (1,0) [0|7] "" XXX + SG_ Signal2 : 24|1@0+ (1,0) [0|1] "" XXX + +BO_ 722 AC_State: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ AC_Mode : 37|3@1+ (1,0) [0|1] "" XXX + SG_ AC_ON : 24|2@1+ (1,0) [0|1] "" XXX + +BO_ 1677 Dash_State: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Units : 29|3@1+ (1,0) [0|7] "" XXX + +BO_ 554 ES_HighBeamAssist: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ HBA_Available : 13|1@0+ (1,0) [0|1] "" XXX + +BO_ 805 ES_STATIC_1: 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 : 23|2@0+ (1,0) [0|3] "" XXX + +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"; +CM_ SG_ 544 Cruise_Brake_Lights "1 = switch on brake lights"; +CM_ SG_ 544 Brake_Pressure "Winds down after cruise disabled. Also can be non-zero when likely preparing for AEB"; +CM_ SG_ 544 Signal3 "Usually goes to 2 if AEB_Status is 4"; +CM_ SG_ 544 AEB_Status "Occasionally is 4 instead of 8 while Brake_Pressure is non-zero, unsure why"; +CM_ SG_ 801 PCB_Off "Pre-Collision Braking off"; +CM_ SG_ 801 Brake_Lights "Driver or Cruise brake on"; +CM_ SG_ 801 Cruise_State "0 = Normal, 1 = Hold+User Brake, 2 = Ready, 3 = Hold"; +CM_ SG_ 801 Far_Distance "1=0-5m, 2=5-10m, 3=10-15m, 4=15-20m, 5=20-25m, 6=25-30m, 7=30-35m, 8=35-40m, 9=40-45m, 10=45-50m, 11=50-55m, 12=55-60m, 13=60-65m, 14=65-70m, 15=75m+"; +CM_ SG_ 801 LKAS_State_Msg "1 = LKAS_Off_Sharp_Curve, 2 = Keep_Hands_On_Steering_wheel_disabled, 3 = LKAS_Off, 4 = LKAS_Off_Too_Slow, 5 = LKAS_Off_Too_Fast"; +CM_ SG_ 801 Cruise_State_Msg "1 = Cruise_Off_Steep_Slope, 2 = Cruise_lvl1_eco, 3 = Cruise_lvl2_comfort, 4 = Cruise_off_empty_reason, 5 = Cruise_off, 6 = Cruise_Unable_to_set, 7 = Cruise_Unable_to_set_brakes_applied, 8 = Eyesight_not_ready, 9 = Cruise_lvl3_standard, 10 = Cruise_lvl4_dynamic, 11 = Cruise_Unable_to_set_steep_slope"; +CM_ SG_ 801 Cruise_Soft_Disable "Eyesight soft disable (eg direct sunlight)"; +CM_ SG_ 801 Cruise_Status_Msg "1 = Disabled_Bad_Visibility, 2 = Disabled_Check_Manual"; +CM_ SG_ 802 LKAS_ACTIVE "Turns on the full LKAS dash display"; +CM_ SG_ 802 LKAS_Alert_Msg "1 = Keep_Hands_On_Wheel, 6 = Pre_Collision_Braking, 7 = Keep_Hands_On_Wheel_Off"; +CM_ SG_ 802 LKAS_Alert "1 = FCW_Cont_Beep, 2 = FCW_Repeated_Beep, 3 = Throttle_Management_Activated_Warning, 4 = Throttle_Management_Activated_Alert, 5 = Pre_Collision_Activated_Alert, 8 = Traffic_Light_Ahead, 9 = Apply_Brake_to_Hold Position, 11 = LDW_Right, 12 = LDW_Left, 13 = Stay_Alert, 14 = Lead_Vehicle_Start_Alert, 18 = Keep_Hands_On_Steering_Alert, 24 = Audio_Beep, 25 = Audio_Lead_Car_Change, 26 = Audio_ACC_Disengaged, 27 = Audio_LKAS_disabled, 28 = Audio_Ding_Ding, 30 = Audio_Repeated_Beep"; +CM_ SG_ 802 LKAS_Left_Line_Visible "0 = Off, 1 = White, 2 = Green, 3 = Orange"; +CM_ SG_ 802 LKAS_Dash_State "0 = Off, 1 = Ready, 2 = Active"; +CM_ SG_ 802 LKAS_Right_Line_Visible "0 = Off, 1 = White, 2 = Green, 3 = Orange"; +CM_ SG_ 912 UNITS "0 = Metric, 1 = Imperial"; +CM_ SG_ 912 ICY_ROAD "1 = DASHLIGHT ON, 2 = WARNING, 3 = OFF"; +VAL_ 544 AEB_Status 12 "AEB related" 8 "AEB actuation" 4 "AEB related" 0 "No AEB actuation"; diff --git a/opendbc_repo/opendbc/dbc/generator/subaru/_subaru_preglobal_2015.dbc b/opendbc_repo/opendbc/dbc/generator/subaru/_subaru_preglobal_2015.dbc new file mode 100644 index 000000000000000..2cc56e1d40bf4ca --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/subaru/_subaru_preglobal_2015.dbc @@ -0,0 +1,245 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX X + + +BO_ 2 Steering: 8 XXX + SG_ Steering_Angle : 7|16@0- (0.1,0) [-500|500] "degree" XXX + SG_ COUNTER : 27|3@0+ (1,0) [0|7] "" XXX + SG_ Checksum : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 208 G_Sensor: 8 XXX + SG_ Steering_Angle : 0|16@1- (-0.1,0) [-500|500] "" XXX + SG_ Lateral : 16|16@1- (-0.0035,1) [-255|255] "" XXX + SG_ Longitudinal : 48|16@1- (-0.00035,0) [-255|255] "" XXX + +BO_ 209 Brake_Pedal: 8 XXX + SG_ Speed : 0|16@1+ (0.05625,0) [0|255] "KPH" XXX + SG_ Brake_Pedal : 16|8@1+ (1,0) [0|255] "" XXX + +BO_ 210 Brake_2: 8 XXX + SG_ Brake_Light : 35|1@1+ (1,0) [0|1] "" XXX + SG_ Brake_Related : 36|1@1+ (1,0) [0|1] "" XXX + SG_ Right_Brake : 48|8@1+ (1,0) [0|255] "" XXX + SG_ Left_Brake : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 211 Brake_Type: 8 XXX + SG_ Brake_Light : 21|1@1+ (1,0) [0|1] "" XXX + SG_ Speed_Counter : 32|8@1+ (1,0) [0|255] "" XXX + SG_ Brake_Cruise_On : 42|1@1+ (1,0) [0|1] "" XXX + SG_ Brake_Pedal_On : 46|1@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 48|8@1+ (1,0) [0|255] "" XXX + +BO_ 212 Wheel_Speeds: 8 XXX + SG_ FL : 0|16@1+ (0.0592,0) [0|255] "KPH" XXX + SG_ FR : 16|16@1+ (0.0592,0) [0|255] "KPH" XXX + SG_ RL : 32|16@1+ (0.0592,0) [0|255] "KPH" XXX + SG_ RR : 48|16@1+ (0.0592,0) [0|255] "KPH" XXX + +BO_ 320 Throttle: 8 XXX + SG_ Throttle_Pedal : 0|8@1+ (0.392157,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Signal1 : 12|2@1+ (1,0) [0|7] "" XXX + SG_ Not_Full_Throttle : 14|1@1+ (1,0) [0|1] "" XXX + SG_ Signal2 : 15|1@1+ (1,0) [0|1] "" XXX + SG_ Engine_RPM : 16|14@1+ (1,0) [0|32767] "" XXX + SG_ Off_Throttle : 30|1@1+ (1,0) [0|1] "" XXX + SG_ Signal3 : 31|1@1+ (1,0) [0|1] "" XXX + SG_ Throttle_Cruise : 32|8@1+ (1,0) [0|255] "" XXX + SG_ Throttle_Combo : 40|8@1+ (1,0) [0|255] "" XXX + SG_ Throttle_Body : 48|8@1+ (1,0) [0|255] "" XXX + SG_ Off_Throttle_2 : 56|1@1+ (1,0) [0|1] "" XXX + SG_ Signal4 : 57|7@1+ (1,0) [0|127] "" XXX + +BO_ 321 Engine: 8 XXX + SG_ Engine_Torque : 0|15@1+ (1,0) [0|255] "" XXX + SG_ Engine_Stop : 15|1@1+ (1,0) [0|1] "" XXX + SG_ Wheel_Torque : 16|12@1+ (1,0) [0|4095] "" XXX + SG_ Engine_RPM : 32|12@1+ (1,0) [0|8191] "" XXX + +BO_ 324 CruiseControl: 8 XXX + SG_ OnOffButton : 2|1@1+ (1,0) [0|1] "" XXX + SG_ SET_BUTTON : 3|1@1+ (1,0) [0|1] "" XXX + SG_ RES_BUTTON : 4|1@1+ (1,0) [0|1] "" XXX + SG_ Button : 13|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_On : 48|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 49|1@1+ (1,0) [0|1] "" XXX + SG_ Brake_Pedal_On : 51|1@1+ (1,0) [0|1] "" XXX + +BO_ 328 Transmission: 8 XXX + SG_ Manual_Gear : 4|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Transmission_Engine : 16|15@1+ (1,0) [0|65535] "" XXX + SG_ Gear : 48|4@1+ (1,0) [0|15] "" XXX + SG_ Gear_2 : 52|4@1+ (1,0) [0|15] "" XXX + SG_ Paddle_Shift : 60|2@1+ (1,0) [0|3] "" XXX + +BO_ 329 CVT_Ratio: 8 XXX + +BO_ 336 Brake_Pressure: 8 XXX + SG_ Brake_Pressure_Right : 0|8@1+ (1,0) [0|255] "" XXX + SG_ Brake_Pressure_Left : 8|8@1+ (1,0) [0|255] "" XXX + +BO_ 338 Stalk: 8 XXX + SG_ COUNTER : 12|4@1+ (1,0) [0|15] "" XXX + SG_ Brake_Light : 52|1@1+ (1,0) [0|1] "" XXX + SG_ Runlights : 58|1@1+ (1,0) [0|1] "" XXX + SG_ Headlights : 59|1@1+ (1,0) [0|1] "" XXX + SG_ Highbeam : 60|1@1+ (1,0) [0|1] "" XXX + SG_ Wiper : 62|1@1+ (1,0) [0|1] "" XXX + +BO_ 352 ES_Brake: 8 XXX + SG_ Brake_Pressure : 0|16@1+ (1,0) [0|255] "" XXX + SG_ Cruise_Brake_Lights : 20|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Fault : 21|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Brake_Active : 22|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 23|1@1+ (1,0) [0|1] "" XXX + SG_ SET_1 : 45|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 48|3@1+ (1,0) [0|7] "" XXX + SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 353 ES_Distance: 8 XXX + SG_ Cruise_Throttle : 0|12@1+ (1,0) [0|4095] "" XXX + SG_ Signal1 : 12|4@1+ (1,0) [0|15] "" XXX + SG_ Car_Follow : 16|1@1+ (1,0) [0|1] "" XXX + SG_ Signal2 : 17|3@1+ (1,0) [0|7] "" XXX + SG_ Cruise_Brake_Active : 20|1@1+ (1,0) [0|1] "" XXX + SG_ Distance_Swap : 21|1@1+ (1,0) [0|1] "" XXX + SG_ Standstill : 22|1@1+ (1,0) [0|1] "" XXX + SG_ Signal3 : 23|1@1+ (1,0) [0|1] "" XXX + SG_ Close_Distance : 24|8@1+ (0.019607,0) [0|5] "m" XXX + SG_ Signal4 : 32|9@1+ (1,0) [0|255] "" XXX + SG_ Standstill_2 : 41|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Fault : 42|1@1+ (1,0) [0|1] "" XXX + SG_ Signal5 : 43|1@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 44|3@1+ (1,0) [0|7] "" XXX + SG_ Signal6 : 47|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Button : 48|3@1+ (1,0) [0|7] "" XXX + SG_ Signal7 : 51|5@1+ (1,0) [0|31] "" XXX + SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 354 ES_Status: 8 XXX + SG_ Brake : 8|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 9|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_RPM : 16|16@1+ (1,0) [0|65535] "" XXX + SG_ Checksum : 32|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 48|3@1+ (1,0) [0|7] "" XXX + +BO_ 356 ES_LKAS: 8 XXX + SG_ COUNTER : 0|3@1+ (1,0) [0|7] "" XXX + SG_ LKAS_Command : 8|13@1- (-1,0) [-4096|4096] "" XXX + SG_ LKAS_Active : 24|1@1+ (1,0) [0|1] "" XXX + SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 359 ES_LDW: 8 XXX + SG_ All_depart_2015 : 0|1@1+ (1,0) [0|1] "" XXX + SG_ Right_Line_2017 : 24|1@1+ (1,0) [0|1] "" XXX + SG_ Left_Line_2017 : 25|1@1+ (1,0) [0|1] "" XXX + SG_ Sig1All_Depart : 28|1@1+ (1,0) [0|1] "" XXX + SG_ Sig2All_Depart : 31|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Inactive_2017 : 36|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_Active : 37|1@1+ (1,0) [0|1] "" XXX + SG_ Sig1Right_Depart : 48|1@1+ (1,0) [0|1] "" XXX + SG_ Sig1Right_Depart_Front : 49|1@1+ (1,0) [0|1] "" XXX + SG_ Sig2Right_Depart : 50|1@1+ (1,0) [0|1] "" XXX + SG_ Left_Depart_Front : 51|1@1+ (1,0) [0|1] "" XXX + SG_ Sig3All_Depart : 52|1@1+ (1,0) [0|1] "" XXX + +BO_ 604 BSD_RCTA: 8 XXX + SG_ COUNTER : 0|3@1+ (1,0) [0|7] "" XXX + SG_ State : 5|1@1+ (1,0) [0|1] "" XXX + SG_ R_ADJACENT : 32|1@1+ (1,0) [0|1] "" XXX + SG_ L_ADJACENT : 33|1@1+ (1,0) [0|1] "" XXX + SG_ R_APPROACHING : 42|1@1+ (1,0) [0|1] "" XXX + SG_ L_APPROACHING : 43|1@1+ (1,0) [0|1] "" XXX + SG_ R_RCTA : 46|1@1+ (1,0) [0|1] "" XXX + SG_ L_RCTA : 47|1@1+ (1,0) [0|1] "" XXX + +BO_ 642 Dashlights: 8 XXX + SG_ COUNTER : 12|4@1+ (1,0) [0|15] "" XXX + SG_ SEATBELT_FL : 40|1@1+ (1,0) [0|1] "" XXX + SG_ LEFT_BLINKER : 44|1@1+ (1,0) [0|1] "" XXX + SG_ RIGHT_BLINKER : 45|1@1+ (1,0) [0|1] "" XXX + +BO_ 880 Steering_Torque_2: 8 XXX + SG_ Steering_Voltage_Flat : 0|8@1+ (1,0) [0|255] "" XXX + SG_ Steer_Torque_Sensor : 29|11@1- (-1,0) [-1000|1000] "" XXX + SG_ COUNTER : 40|4@1+ (1,0) [0|15] "" XXX + +BO_ 884 BodyInfo: 8 XXX + SG_ DOOR_OPEN_FR : 24|1@1+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 25|1@1+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 26|1@1+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 27|1@1+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_Hatch : 28|1@1+ (1,0) [0|1] "" XXX + +BO_ 864 Engine_Temp: 8 XXX + SG_ Oil_Temp : 16|8@1+ (1,-40) [0|255] "" XXX + SG_ Coolant_Temp : 24|8@1+ (1,-40) [0|255] "" XXX + SG_ Cruise_Activated : 45|1@1+ (1,0) [0|1] "" XXX + SG_ Saved_Speed : 56|8@1+ (1,0) [0|255] "" XXX + +BO_ 866 Fuel: 8 XXX + +BO_ 977 Dash_State2: 8 XXX + SG_ UNITS : 15|1@1+ (1,0) [0|1] "" XXX + +BO_ 1745 Dash_State: 8 XXX + SG_ Units : 15|1@1+ (1,0) [0|1] "" XXX + +CM_ SG_ 320 Off_Throttle_2 "Less sensitive"; +CM_ SG_ 320 Throttle_Body "Throttle related"; +CM_ SG_ 328 Gear "15 = P, 14 = R, 0 = N, 1-6=gear"; +CM_ SG_ 328 Gear_2 "15 = P, 14 = R, 0 = N, 1-6=gear"; +CM_ SG_ 353 Cruise_Button "1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 resume deep"; +CM_ SG_ 354 RPM "20hz version of Transmission_Engine under Transmission"; +CM_ SG_ 359 Sig1Right_Depart "right depart, hill steep and seatbelt disengage"; +CM_ SG_ 359 LKAS_Inactive_2017 "1 when not steering, 0 when lkas steering"; +CM_ SG_ 359 Sig1Right_Depart_Front "object in front, right depart, hill steep and seatbelt disengage alert "; +CM_ SG_ 359 Left_Depart_Front "warning after acceleration into car in front and left depart"; +CM_ SG_ 359 Sig1All_Depart "Left and right depart"; +CM_ SG_ 359 Sig2All_Depart "Left and right depart"; +CM_ SG_ 359 All_depart_2015 "always 1 on 2017"; +CM_ SG_ 604 R_APPROACHING "Faster car approaching in far right lane"; +CM_ SG_ 604 L_APPROACHING "Faster car approaching in far left lane"; +CM_ SG_ 604 R_RCTA "Rear cross traffic alert, only when in R gear"; +CM_ SG_ 604 L_RCTA "Rear cross traffic alert, only when in R gear"; +CM_ SG_ 642 COUNTER "Affected by signals"; +CM_ SG_ 642 SEATBELT_FL "Driver seatbelt"; +CM_ SG_ 880 Steering_Voltage_Flat "receives later than 371"; +CM_ SG_ 977 UNITS "0 = Metric, 1 = Imperial"; + +VAL_ 328 Gear 0 "N" 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 14 "R" 15 "P"; diff --git a/opendbc_repo/opendbc/dbc/generator/subaru/subaru_forester_2017.dbc b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_forester_2017.dbc new file mode 100644 index 000000000000000..6d5d46bc9ab57e6 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_forester_2017.dbc @@ -0,0 +1,18 @@ +CM_ "IMPORT _subaru_preglobal_2015.dbc"; + +BO_ 355 ES_DashStatus: 8 XXX + SG_ Not_Ready_Startup : 4|2@1+ (1,0) [0|3] "" XXX + SG_ Cruise_On : 16|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 17|1@0+ (1,0) [0|1] "" XXX + SG_ Cruise_Set_Speed : 24|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 40|3@1+ (1,0) [0|7] "" XXX + SG_ Brake : 43|1@1+ (1,0) [0|1] "" XXX + SG_ Car_Follow : 54|1@1+ (1,0) [0|1] "" XXX + SG_ Far_Distance : 56|4@1+ (5,0) [0|75] "m" XXX + +BO_ 881 Steering_Torque: 8 XXX + SG_ Steering_Motor_Flat : 0|10@1+ (32,0) [0|1000] "" XXX + SG_ Steer_Torque_Output : 16|11@1- (-32,0) [-1000|1000] "" XXX + SG_ Steer_Error_1 : 27|1@1+ (1,0) [0|1] "" XXX + SG_ Steer_Torque_Sensor : 29|11@1- (-1,0) [-1000|1000] "" XXX + SG_ Steering_Angle : 40|16@1- (-0.033,0) [-600|600] "" XXX diff --git a/opendbc_repo/opendbc/dbc/generator/subaru/subaru_global_2017.dbc b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_global_2017.dbc new file mode 100644 index 000000000000000..83a36ff8f732ace --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_global_2017.dbc @@ -0,0 +1,65 @@ +CM_ "IMPORT _subaru_global.dbc"; + +BO_ 72 Transmission: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Gear : 24|8@1+ (1,0) [0|255] "" XXX + SG_ RPM : 40|15@1+ (1,0) [0|65535] "" XXX + +BO_ 73 CVT: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ CVT_Gear : 24|8@1+ (1,0) [0|255] "" XXX + +BO_ 545 ES_Distance: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" 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|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 + SG_ Signal7 : 35|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Brake_Active : 36|1@1+ (1,0) [0|1] "" XXX + SG_ Distance_Swap : 37|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_EPB : 38|1@1+ (1,0) [0|1] "" XXX + SG_ Signal4 : 39|1@0+ (1,0) [0|1] "" XXX + SG_ Close_Distance : 40|8@1+ (0.019607,0) [0|5] "m" XXX + SG_ Signal5 : 48|8@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Cancel : 56|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Set : 57|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Resume : 58|1@1+ (1,0) [0|1] "" XXX + SG_ Signal6 : 59|5@1+ (1,0) [0|1] "" XXX + +BO_ 546 ES_Status: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" 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|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 + SG_ Signal3 : 32|32@1+ (1,0) [0|1] "" XXX + +BO_ 576 CruiseControl: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Signal1 : 12|28@1+ (1,0) [0|268435455] "" XXX + SG_ Cruise_On : 40|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 41|1@1+ (1,0) [0|1] "" XXX + SG_ Signal2 : 42|22@1+ (1,0) [0|4194303] "" XXX + +CM_ SG_ 545 Cruise_Throttle "RPM-like output signal"; +CM_ SG_ 545 Cruise_EPB "1 = Electric Parking Brake set"; +CM_ SG_ 545 Distance_Swap "Switch from Close to Far distance"; +CM_ SG_ 545 Cruise_Soft_Disable "Eyesight Temporary disable, sets CruiseControl Activated = 0"; +CM_ SG_ 546 Cruise_RPM "ES RPM output for ECM and TCM"; +CM_ SG_ 546 Signal3 "0 when cruise_activated = 1"; +CM_ SG_ 803 Signal1 "Seems to be static, set only on some cars"; +CM_ SG_ 803 Signal2 "Seems to be static, set only on some cars"; +VAL_ 803 LKAS_Blue_Lines 0 "no modifier" 2 "changes lines to blue"; +VAL_ 803 LKAS_State_Infotainment 0 "none" 2 "Obstacle Detected" 3 "Keep Hands On Wheel" 4 "Keep Hands On Wheel Off"; +VAL_ 72 Gear 2 "N" 3 "R" 4 "P" 121 "D" 137 "1" 145 "2" 153 "3" 161 "4" 169 "5" 177 "6"; diff --git a/opendbc_repo/opendbc/dbc/generator/subaru/subaru_global_2020_hybrid.dbc b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_global_2020_hybrid.dbc new file mode 100644 index 000000000000000..a4dbe9c37df8f6e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_global_2020_hybrid.dbc @@ -0,0 +1,18 @@ +CM_ "IMPORT _subaru_global.dbc"; + +BO_ 39 Cruise_Status_2: 8 XXX + SG_ Cruise_Activated : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 295 Transmission: 8 XXX + SG_ Gear : 44|4@1+ (1,0) [0|15] "" XXX + +BO_ 360 Throttle_Hybrid: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Throttle_Pedal : 32|8@1+ (1,0) [0|255] "" XXX + +BO_ 550 Brake_Hybrid: 8 XXX + SG_ Brake_Pedal : 24|8@1+ (1,0) [0|1] "" XXX + SG_ Brake : 37|1@1+ (1,0) [0|1] "" XXX + +VAL_ 295 Gear 0 "P" 1 "R" 3 "D"; diff --git a/opendbc_repo/opendbc/dbc/generator/subaru/subaru_outback_2015.dbc b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_outback_2015.dbc new file mode 100644 index 000000000000000..cc1fa16d19e76de --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_outback_2015.dbc @@ -0,0 +1,30 @@ +CM_ "IMPORT _subaru_preglobal_2015.dbc"; + +BO_ 358 ES_DashStatus: 8 XXX + SG_ Not_Ready_Startup : 0|3@1+ (1,0) [0|7] "" XXX + SG_ Seatbelt_Disengage : 12|2@1+ (1,0) [0|3] "" XXX + SG_ Disengage_Alert : 14|2@1+ (1,0) [0|3] "" XXX + SG_ Cruise_On : 16|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 17|1@1+ (1,0) [0|1] "" XXX + SG_ Signal1 : 18|1@1+ (1,0) [0|1] "" XXX + SG_ WHEELS_MOVING_2015 : 19|1@1+ (1,0) [0|1] "" XXX + SG_ Driver_Input : 20|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Distance : 21|3@1+ (1,0) [0|7] "" XXX + SG_ Cruise_Set_Speed : 24|8@1+ (1,0) [0|255] "" XXX + SG_ Cruise_Fault : 32|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_On_2 : 34|1@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 37|3@1+ (1,0) [0|7] "" XXX + SG_ Steep_Hill_Disengage : 44|1@1+ (1,0) [0|3] "" XXX + SG_ Car_Follow : 46|1@1+ (1,0) [0|1] "" XXX + SG_ Far_Distance : 48|4@1+ (5,0) [0|75] "m" XXX + +BO_ 881 Steering_Torque: 8 XXX + SG_ Steering_Motor_Flat : 0|10@1+ (32,0) [0|1000] "" XXX + SG_ Steer_Torque_Output : 16|11@1- (-32,0) [-1000|1000] "" XXX + SG_ Steer_Error_1 : 27|1@1+ (1,0) [0|1] "" XXX + SG_ Steer_Torque_Sensor : 29|11@1- (1,0) [-1000|1000] "" XXX + SG_ Steering_Angle : 40|16@1- (-0.033,0) [-600|600] "" XXX + +CM_ SG_ 358 Disengage_Alert "seatbelt and steep hill disengage"; +CM_ SG_ 358 Cruise_Fault "No engagement until restart"; +CM_ SG_ 358 Car_Follow "lead car detected"; diff --git a/opendbc_repo/opendbc/dbc/generator/subaru/subaru_outback_2019.dbc b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_outback_2019.dbc new file mode 100644 index 000000000000000..d886954cfe7771f --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/subaru/subaru_outback_2019.dbc @@ -0,0 +1,30 @@ +CM_ "IMPORT _subaru_preglobal_2015.dbc"; + +BO_ 358 ES_DashStatus: 8 XXX + SG_ Not_Ready_Startup : 0|3@1+ (1,0) [0|7] "" XXX + SG_ Seatbelt_Disengage : 12|2@1+ (1,0) [0|3] "" XXX + SG_ Disengage_Alert : 14|2@1+ (1,0) [0|3] "" XXX + SG_ Cruise_On : 16|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 17|1@1+ (1,0) [0|1] "" XXX + SG_ Signal1 : 18|1@1+ (1,0) [0|1] "" XXX + SG_ WHEELS_MOVING_2015 : 19|1@1+ (1,0) [0|1] "" XXX + SG_ Driver_Input : 20|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Distance : 21|3@1+ (1,0) [0|7] "" XXX + SG_ Cruise_Set_Speed : 24|8@1+ (1,0) [0|255] "" XXX + SG_ Cruise_Fault : 32|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_On_2 : 34|1@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 37|3@1+ (1,0) [0|7] "" XXX + SG_ Steep_Hill_Disengage : 44|1@1+ (1,0) [0|3] "" XXX + SG_ Car_Follow : 46|1@1+ (1,0) [0|1] "" XXX + SG_ Far_Distance : 48|4@1+ (5,0) [0|75] "m" XXX + +BO_ 881 Steering_Torque: 8 XXX + SG_ Steering_Motor_Flat : 0|10@1+ (32,0) [0|1000] "" XXX + SG_ Steer_Torque_Output : 16|11@1- (-32,0) [-1000|1000] "" XXX + SG_ Steer_Error_1 : 27|1@1+ (1,0) [0|1] "" XXX + SG_ Steer_Torque_Sensor : 29|11@1- (-1,0) [-1000|1000] "" XXX + SG_ Steering_Angle : 40|16@1- (-0.033,0) [-600|600] "" XXX + +CM_ SG_ 358 Disengage_Alert "seatbelt and steep hill disengage"; +CM_ SG_ 358 Cruise_Fault "No engagement until restart"; +CM_ SG_ 358 Car_Follow "lead car detected"; diff --git a/opendbc_repo/opendbc/dbc/generator/tesla/.gitignore b/opendbc_repo/opendbc/dbc/generator/tesla/.gitignore new file mode 100644 index 000000000000000..554aeeaf242e7a9 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/tesla/.gitignore @@ -0,0 +1 @@ +*.dbc \ No newline at end of file diff --git a/opendbc_repo/opendbc/dbc/generator/tesla/radar_common.py b/opendbc_repo/opendbc/dbc/generator/tesla/radar_common.py new file mode 100755 index 000000000000000..737c203b026dad3 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/tesla/radar_common.py @@ -0,0 +1,38 @@ +#!/usr/bin/env python3 + +def get_radar_point_definition(base_id, base_name): + return f""" +BO_ {base_id} {base_name}_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ {base_id+1} {base_name}_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot +""" + +def get_val_definition(base_id): + return f""" +VAL_ {base_id+1} MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ {base_id+1} Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 \ +"RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ;""" \ No newline at end of file diff --git a/opendbc_repo/opendbc/dbc/generator/tesla/tesla_radar_bosch.py b/opendbc_repo/opendbc/dbc/generator/tesla/tesla_radar_bosch.py new file mode 100755 index 000000000000000..6518c274369ef17 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/tesla/tesla_radar_bosch.py @@ -0,0 +1,282 @@ +#!/usr/bin/env python3 + +import os +from opendbc.dbc.generator.tesla.radar_common import get_radar_point_definition, get_val_definition + +if __name__ == "__main__": + dbc_name = os.path.basename(__file__).replace(".py", ".dbc") + tesla_path = os.path.dirname(os.path.realpath(__file__)) + with open(os.path.join(tesla_path, dbc_name), "w", encoding='utf-8') as f: + f.write(""" +VERSION "" + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: Autopilot Radar Diag + + +BO_ 769 TeslaRadarSguInfo: 8 Radar + SG_ RADC_VerticalMisalignment : 0|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_SCUTemperature : 8|8@1+ (1,-128) [-128|127] "" Autopilot + SG_ RADC_VMA_Plaus : 16|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_SGU_ITC : 24|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_HorizontMisalignment : 32|12@1+ (1,0) [0|4096] "" Autopilot + SG_ RADC_SensorDirty : 44|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_HWFail : 45|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_SGUFail : 46|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_SGUInfoConsistBit : 47|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 770 TeslaRadarTguInfo: 8 Radar + SG_ RADC_ACCTargObj1_sguIndex : 0|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj2_sguIndex : 6|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj3_sguIndex : 12|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj4_sguIndex : 18|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj5_sguIndex : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ unused30 : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_TGUInfoConsistBit : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_ACCTargObj1_dBPower : 32|16@1+ (1,0) [0|65535] "" Autopilot + SG_ RADC_ACCTargObj5_dBPower : 48|16@1+ (1,0) [0|65535] "" Autopilot + +BO_ 1281 TeslaRadarAlertMatrix: 8 Radar + SG_ RADC_a001_ecuInternalPerf : 0|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a002_flashPerformance : 1|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a003_vBatHigh : 2|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a004_adjustmentNotDone : 3|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a005_adjustmentReq : 4|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a006_adjustmentNotOk : 5|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a007_sensorBlinded : 6|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a008_plantModeActive : 7|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a009_configMismatch : 8|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a010_canBusOff : 9|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a011_bdyMIA : 10|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a012_espMIA : 11|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a013_gtwMIA : 12|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a014_sccmMIA : 13|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a015_adasMIA : 14|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a016_bdyInvalidCount : 15|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a017_adasInvalidCount : 16|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a018_espInvalidCount : 17|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a019_sccmInvalidCount : 18|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a020_bdyInvalidChkSm : 19|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a021_espInvalidChkSm : 20|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a022_sccmInvalidChkSm : 21|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a023_sccmInvalidChkSm : 22|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a024_absValidity : 23|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a025_ambTValidity : 24|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a026_brakeValidity : 25|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a027_CntryCdValidity : 26|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a028_espValidity : 27|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a029_longAccOffValidity : 28|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a030_longAccValidity : 29|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a031_odoValidity : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a032_gearValidity : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a033_steerAngValidity : 32|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a034_steerAngSpdValidity : 33|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a035_indctrValidity : 34|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a036_vehStandStillValidity : 35|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a037_vinValidity : 36|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a038_whlRotValidity : 37|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a039_whlSpdValidity : 38|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a040_whlStandStillValidity : 39|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a041_wiperValidity : 40|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a042_xwdValidity : 41|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a043_yawOffValidity : 42|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a044_yawValidity : 43|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a045_bsdSanity : 44|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a046_rctaSanity : 45|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a047_lcwSanity : 46|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a048_steerAngOffSanity : 47|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a049_tireSizeSanity : 48|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a050_velocitySanity : 49|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a051_yawSanity : 50|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a052_radomeHtrInop : 51|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a053_espmodValidity : 52|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a054_gtwmodValidity : 53|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a055_stwmodValidity : 54|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a056_bcmodValidity : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a057_dimodValidity : 56|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a058_opmodValidity : 57|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a059_drmiInvalidChkSm : 58|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a060_drmiInvalidCount : 59|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a061_radPositionMismatch : 60|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a062_strRackMismatch : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ unused62 : 62|2@1+ (1,0) [0|3] "" Autopilot +""") + + M_RANGE = range(0x310, 0x36D + 1, 3) + for i, base_id in enumerate(M_RANGE): + f.write(get_radar_point_definition(base_id, f"RadarPoint{i}")) + + L_RANGE = range(0x371, 0x37D + 1, 3) + for i, base_id in enumerate(L_RANGE): + f.write(get_radar_point_definition(base_id, f"ProcessedRadarPoint{i+1}")) + + f.write(""" +BO_ 697 VIN_VIP_405HS: 8 Autopilot + SG_ VIN_MuxID M : 0|8@1+ (1,0) [0|0] "" Radar + SG_ VIN_Part1 m16 : 47|24@0+ (1,0) [0|16777215] "" Radar + SG_ VIN_Part2 m17 : 15|56@0+ (1,0) [0|7.2057594038E+16] "" Radar + SG_ VIN_Part3 m18 : 15|56@0+ (1,0) [0|7.2057594038E+16] "" Radar + +BO_ 681 Msg2A9_GTW_carConfig: 8 Autopilot + SG_ Msg2A9_Always0x02 : 48|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x10 : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x16 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x41 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Value1_0x02 : 0|3@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_FourWheelDrive : 3|2@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Value2_0x02 : 5|3@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x43 : 16|8@1+ (1,0) [0|0] "" Radar + +BO_ 409 Msg199_STW_ANGLHP_STAT: 8 Autopilot + SG_ Msg199Always0x04 : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x20 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x2F : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x67 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0xFF : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 361 Msg169_ESP_wheelSpeeds: 8 Autopilot + SG_ ESP_wheelSpeedFrL_HS : 0|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedFrR_HS : 13|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedReL_HS : 26|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedReR_HS : 39|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ Msg169Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg169Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 345 Msg159_ESP_C: 8 Autopilot + SG_ Msg159Always0x3A : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xA5 : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xCF : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xF4 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Counter : 44|4@1+ (1,0) [0|0] "" Radar + SG_ Msg159Checksum : 24|8@1+ (1,0) [0|0] "" Radar + +BO_ 329 Msg149_ESP_145h: 8 Autopilot + SG_ Msg149Always0x02 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x04 : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x26 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x6A : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0xAA : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0xF : 48|4@1+ (1,0) [0|0] "" Radar + SG_ Msg149Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 297 Msg129_ESP_115h: 6 Autopilot + SG_ Msg129Always0x20 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg129Checksum : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg129Counter : 36|4@1+ (1,0) [0|0] "" Radar + +BO_ 281 Msg119_DI_torque2: 6 Autopilot + SG_ Msg119Always0x11 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0x1F : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0x8 : 36|4@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0xF4 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0xFF : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Checksum : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Counter : 32|4@1+ (1,0) [0|0] "" Radar + +BO_ 265 Msg109_DI_torque1: 8 Autopilot + SG_ Msg109Always0x80 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg109Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg109Counter : 13|3@1+ (1,0) [0|0] "" Radar + +BO_ 521 Msg209_GTW_odo: 8 Autopilot + SG_ Msg209Always0x61 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x94 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x52 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x13 : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x03 : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x80 : 48|8@1+ (1,0) [0|0] "" Radar + +BO_ 537 Msg219_STW_ACTN_RQ: 8 Autopilot + SG_ Msg219Counter : 52|4@1+ (1,0) [0|15] "" Radar + SG_ Msg219CRC : 56|8@1+ (1,0) [0|0] "" Radar + +BO_ 425 Msg1A9_DI_espControl: 5 Autopilot + SG_ Msg1A9Always0x0C : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg1A9Counter : 28|4@1+ (1,0) [0|0] "" Radar + SG_ Msg1A9Checksum : 32|8@1+ (1,0) [0|0] "" Radar + +BO_ 729 Msg2D9_BC_status : 8 Autopilot + SG_ Msg2D9Always0x80 : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2D9Always0x40 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2D9Always0x83 : 16|8@1+ (1,0) [0|0] "" Radar + +BO_ 1601 UDS_radarRequest: 8 Diag + SG_ UDS_radarRequestData : 7|64@0+ (1,0) [0|0] "" Radar + +BO_ 1617 Radar_udsResponse: 8 Radar + SG_ Radar_udsResponseData : 7|64@0+ (1,0) [0|0] "" Diag + +CM_ BO_ 697 "Start with MuxID 0x12, then 0x11 and finally 0x10 (VIN is then transmitted in the reverse order)"; +CM_ BO_ 681 "Message sent every 1000 ms. All fixed bytes, no checksum, the byte for RWD or AWD needs to match VIN config"; +CM_ BO_ 409 "Message sent every 10ms. Checksum : use all first 7 bytes with the SAE J1850 CRC algo"; +CM_ BO_ 361 "Message sent every 10ms. Checksum : Sum of all first 7 bytes + 0x76"; +CM_ BO_ 345 "Message sent every 20ms. Checksum : Sum of all first bytes + 0xc; place checksum in 4th octet"; +CM_ BO_ 329 "Message sent every 20ms. Checksum : Sum of all first 7 bytes + 0x46"; +CM_ BO_ 297 "Message sent every 20ms. Checksum : Sum of all first 5 bytes + 0x16"; +CM_ BO_ 281 "Message sent every 10ms. Checksum : Sum of all first 5 bytes + 0x17"; +CM_ BO_ 265 "Message sent every 10ms. Checksum : Sum of all first 7 bytes + 0x7"; +CM_ BO_ 521 "Message sent every 100ms. All fixed bytes, no checksum."; +CM_ BO_ 537 "Message sent every 100ms. Checksum : use all first 7 bytes with the SAE J1850 CRC algo"; +CM_ BO_ 425 "Message sent every 20ms. Checksum : Sum of all first 4 bytes + 0x38"; +CM_ BO_ 729 "Message sent every 1000ms. All fixed bytes, no checksum."; + +BA_DEF_ "BusType" STRING ; +BA_DEF_ BO_ "GenMsgCycleTime" INT 0 0; +BA_DEF_ SG_ "FieldType" STRING ; + +BA_DEF_DEF_ "BusType" "CAN"; +BA_DEF_DEF_ "FieldType" ""; +BA_DEF_DEF_ "GenMsgCycleTime" 0; + +BA_ "GenMsgCycleTime" BO_ 697 250; +BA_ "GenMsgCycleTime" BO_ 681 1000; +BA_ "GenMsgCycleTime" BO_ 409 10; +BA_ "GenMsgCycleTime" BO_ 361 10; +BA_ "GenMsgCycleTime" BO_ 345 20; +BA_ "GenMsgCycleTime" BO_ 329 20; +BA_ "GenMsgCycleTime" BO_ 297 20; +BA_ "GenMsgCycleTime" BO_ 281 10; +BA_ "GenMsgCycleTime" BO_ 265 10; +BA_ "GenMsgCycleTime" BO_ 521 100; +BA_ "GenMsgCycleTime" BO_ 537 100; +BA_ "GenMsgCycleTime" BO_ 425 20; +BA_ "GenMsgCycleTime" BO_ 729 1000; + +VAL_ 681 Msg2A9_FourWheelDrive 3 "SNA" 2 "UNUSED" 1 "4WD" 0 "2WD" ;""") + + for base_id in list(M_RANGE) + list(L_RANGE): + f.write(get_val_definition(base_id)) diff --git a/opendbc_repo/opendbc/dbc/generator/tesla/tesla_radar_continental.py b/opendbc_repo/opendbc/dbc/generator/tesla/tesla_radar_continental.py new file mode 100755 index 000000000000000..1279bf1f210ea36 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/tesla/tesla_radar_continental.py @@ -0,0 +1,77 @@ +#!/usr/bin/env python3 + +import os +from opendbc.dbc.generator.tesla.radar_common import get_radar_point_definition, get_val_definition + +if __name__ == "__main__": + dbc_name = os.path.basename(__file__).replace(".py", ".dbc") + tesla_path = os.path.dirname(os.path.realpath(__file__)) + with open(os.path.join(tesla_path, dbc_name), "w", encoding='utf-8') as f: + f.write(""" +VERSION "" + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: Autopilot Radar Diag + +BO_ 1025 RadarStatus: 8 Radar + SG_ carparkDetected : 29|1@1+ (1,0) [0|1] "" Autopilot + SG_ decreaseBlockage : 25|1@1+ (1,0) [0|1] "" Autopilot + SG_ horizontMisalignment : 8|12@1+ (0.00012207,-0.25) [-0.25|0.249878] "rad" Autopilot + SG_ increaseBlockage : 24|1@1+ (1,0) [0|1] "" Autopilot + SG_ lowPowerMode : 20|2@1+ (1,0) [0|3] "" Autopilot + SG_ powerOnSelfTest : 22|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorBlocked : 26|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorInfoConsistBit : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorReplace : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ shortTermUnavailable : 23|1@1+ (1,0) [0|1] "" Autopilot + SG_ tunnelDetected : 28|1@1+ (1,0) [0|1] "" Autopilot + SG_ vehDynamicsError : 27|1@1+ (1,0) [0|1] "" Autopilot + SG_ verticalMisalignment : 0|8@1+ (0.00195313,-0.25) [-0.25|0.248047] "rad" Autopilot + +BO_ 1617 Radar_udsResponse: 8 Radar + SG_ Radar_udsResponseData : 7|64@0+ (1,0) [0|1.84467e+19] "" Diag + +BO_ 1601 UDS_radcRequest: 8 Diag + SG_ UDS_radcRequestData : 7|64@0+ (1,0) [0|1.84467e+19] "" Radar +""") + + POINT_RANGE = range(0x410, 0x45E + 1, 2) + for i, base_id in enumerate(POINT_RANGE): + f.write(get_radar_point_definition(base_id, f"RadarPoint{i}")) + + f.write(""" +VAL_ 1025 lowPowerMode 1 "COMMANDED_LOW_POWER" 0 "DEFAULT_LOW_POWER" 2 "NORMAL_POWER" 3 "SNA";""") + + for base_id in list(POINT_RANGE): + f.write(get_val_definition(base_id)) diff --git a/opendbc_repo/opendbc/dbc/generator/test_generator.py b/opendbc_repo/opendbc/dbc/generator/test_generator.py new file mode 100755 index 000000000000000..1cfc70128b13c58 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/test_generator.py @@ -0,0 +1,22 @@ +#!/usr/bin/env python3 +import os +import filecmp +import tempfile +from opendbc.dbc.generator.generator import create_all, opendbc_root + + +def test_generator(): + with tempfile.TemporaryDirectory() as d: + create_all(d) + + ignore = [f for f in os.listdir(opendbc_root) if not f.endswith('_generated.dbc')] + comp = filecmp.dircmp(opendbc_root, d, ignore=ignore) + + err = "Generated DBC mismatch\n\n" + err += f"Different files: {comp.diff_files}\n\n" + err += "Run opendbc/dbc/generator/generator.py to regenerate DBC files." + assert len(comp.diff_files) == 0, err + + +if __name__ == "__main__": + test_generator() diff --git a/opendbc_repo/opendbc/dbc/generator/toyota/_community.dbc b/opendbc_repo/opendbc/dbc/generator/toyota/_community.dbc new file mode 100644 index 000000000000000..58bcfd3be46f17e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/toyota/_community.dbc @@ -0,0 +1,41 @@ +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + +BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX + SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX + +CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; + +BO_ 767 SDSU: 8 XXX + SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STATE : 23|4@0+ (1,0) [0|15] "" XXX + +CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS-P Toyotas. Learn more: https://github.com/RetroPilot/ocelot/tree/main/firmware/smart_dsu"; +CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; + +VAL_ 767 STATE 7 "STATE_AEB_CTRL" 6 "FAULT_INVALID" 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; diff --git a/opendbc_repo/opendbc/dbc/generator/toyota/_toyota_2017.dbc b/opendbc_repo/opendbc/dbc/generator/toyota/_toyota_2017.dbc new file mode 100644 index 000000000000000..52bf3eb575934a2 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/toyota/_toyota_2017.dbc @@ -0,0 +1,603 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX DSU HCU EPS IPAS CGW BGM + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX + SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/s" XXX + SG_ ACCEL_X : 17|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 119 ENG2F41: 6 CGW + SG_ FDRV : 7|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ FDRVREAL : 23|13@0- (10,0) [0|0] "N" Vector__XXX + SG_ XAECT : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XFDRVCOL : 38|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVSELP : 34|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F41S : 47|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 120 ENG2F42: 4 CGW + SG_ FAVLMCHH : 7|16@0- (2,0) [0|0] "N" Vector__XX228X + SG_ CCRNG : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVTYPD : 22|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ GEARHD : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F42S : 31|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_FORCE : 23|8@0+ (40,0) [0|10200] "N" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + +BO_ 180 SPEED: 8 XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "km/h" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 295 GEAR_PACKET_HYBRID: 8 XXX + SG_ FDRVREAL : 26|11@0- (25,0) [-25600|25575] "N" XXX + SG_ UNKNOWN : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 353 DSU_SPEED: 7 XXX + SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "km/h" XXX + +BO_ 452 ENGINE_RPM: 8 CGW + SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS + SG_ ENGINE_RUNNING : 27|1@0+ (1,0) [0|1] "" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_BRAKING : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.0009765625,0) [-20|20] "m/s^2" XXX + SG_ NEUTRAL_FORCE : 39|16@0- (2,0) [-65536|65534] "N" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ BRAKE_PRESSED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PCM_FOLLOW_DISTANCE : 12|2@0+ (1,0) [0|3] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "" XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "km/h" XXX + SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 552 VSC1S29: 4 CGW + SG_ ICBACT : 7|1@0+ (1,0) [0|0] "" DS1 + SG_ DVS0PCS : 6|15@0- (0.001,0) [0|0] "m/s^2" DS1 + SG_ SM228 : 31|8@0+ (1,0) [0|0] "" DS1 + +BO_ 560 BRAKE_2: 7 XXX + SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL_HYBRID: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX + SG_ STEER_ANGLE_INITIALIZING : 3|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 7 DSU + SG_ _COUNTER : 7|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX + SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX + SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX + SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX + SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 705 GAS_PEDAL: 8 XXX + SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM + +BO_ 740 STEERING_LKA: 5 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 800 VSC1S07: 8 CGW + SG_ FBKRLY : 6|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCM : 4|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCSFT : 3|1@0+ (1,0) [0|0] "" DS1 + SG_ FABS : 2|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ TSVSC : 1|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCL : 0|1@0+ (1,0) [0|0] "" DS1 + SG_ RQCSTBKB : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PSBSTBY : 14|1@0+ (1,0) [0|0] "" DS1 + SG_ P2BRXMK : 13|1@0+ (1,0) [0|0] "" DS1 + SG_ MCC : 11|1@0+ (1,0) [0|0] "" DS1 + SG_ RQBKB : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRSTOP : 9|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ BRKON : 8|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ ASLP : 23|8@0- (1,0) [0|0] "deg" DS1 + SG_ BRTYPACC : 31|2@0+ (1,0) [0|0] "" DS1 + SG_ BRKABT3 : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT2 : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT1 : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GVC : 39|8@0- (0.04,0) [0|0] "m/s^2" DS1 + SG_ XGVCINV : 43|1@0+ (1,0) [0|0] "" DS1 + SG_ S07CNT : 52|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSBRSTA : 50|2@0+ (1,0) [0|0] "" DS1 + SG_ VSC07SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU + SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX + SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX + SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX + SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX + SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_VEHICLE_STOPPED : 29|1@0+ (1,0) [0|0] "" DSU + SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX + SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 836 PRE_COLLISION_2: 8 DSU + SG_ DSS1GDRV : 7|10@0- (0.1,0) [0|0] "m/s^2" Vector__XXX + SG_ PCSALM : 17|1@0+ (1,0) [0|0] "" FCM + SG_ IBTRGR : 27|1@0+ (1,0) [0|0] "" FCM + SG_ PBATRGR : 30|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PREFILL : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVSTRGR : 36|1@0+ (1,0) [0|0] "" SCS + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 865 CLUTCH: 8 XXX + SG_ ACC_FAULTED : 32|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_PEDAL_ALT : 23|8@0+ (0.005,0) [0|1] "" XXX + SG_ CLUTCH_RELEASED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 48|16@1+ (0.0002,-6.5536) [-6.5536|6.5534] "" XXX + +BO_ 869 DSU_CRUISE : 7 DSU + SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX + SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX + SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX + SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX + SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX + SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ TEMP_ACC_FAULTED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX + +BO_ 956 GEAR_PACKET: 8 XXX + SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + SG_ SPORT_GEAR_ON : 33|1@0+ (1,0) [0|1] "" XXX + SG_ SPORT_GEAR : 38|3@0+ (1,0) [0|7] "" XXX + SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX + SG_ B_GEAR_ENGAGED : 41|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_ENGAGED : 47|1@0+ (1,0) [0|1] "" XXX + +BO_ 1005 REVERSE_CAMERA_STATE: 2 BGM + SG_ REVERSE_CAMERA_GUIDELINES : 9|2@0+ (1,0) [1|3] "" XXX + +BO_ 1009 PCM_CRUISE_ALT: 8 XXX + SG_ PCM_FOLLOW_DISTANCE : 4|2@1+ (1,0) [0|3] "" XXX + SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX + SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX + SG_ UI_SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + +BO_ 1041 PCS_HUD: 8 DSU + SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX + SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX + SG_ PCS_DUST : 34|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_TEMP : 35|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_DUST2 : 41|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_TEMP2 : 42|1@0+ (1,0) [0|0] "" XXX + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX + SG_ FRD_ADJ : 53|3@0+ (1,0) [0|0] "" XXX + SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 DSU + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_STATUS : 7|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LDW_EXIST : 10|1@0+ (1,0) [0|1] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE_QUIET : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE : 16|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY : 18|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SA_TOGGLE : 20|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_MESSAGES : 23|3@0+ (1,0) [0|1] "" XXX + SG_ LDA_ON_MESSAGE : 31|2@0+ (1,0) [0|3] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_TOGGLE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_SENSITIVITY : 45|2@0+ (1,0) [0|3] "" XXX + SG_ TAKE_CONTROL : 46|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_FRONT_CAMERA_BLOCKED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_BUZZER : 50|2@0+ (1,0) [0|0] "" XXX + SG_ LANE_SWAY_FLD : 53|3@0+ (1,0) [0|7] "" XXX + SG_ LANE_SWAY_WARNING : 55|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 42|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1043 TIME : 8 CGW + SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX + SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX + SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX + SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX + SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX + SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX + SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX + SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX + SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX + +BO_ 1044 AUTO_HIGH_BEAM: 8 FCM + SG_ AHB_DUTY : 47|8@0+ (0.5,0) [0|0] "%" Vector__XXX + SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1056 VSC1S08: 8 CGW + SG_ YR1Z : 7|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ YR2Z : 23|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ GL1Z : 39|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ GL2Z : 47|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ YRGSDIR : 55|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,SCS + SG_ GLZS : 51|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ YRZF : 50|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZS : 49|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZKS : 48|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ VSC08SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + +BO_ 1083 AUTOPARK_STATUS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "km/h" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +BO_ 1408 VIN_PART_1: 8 CGW + SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1409 VIN_PART_2: 8 CGW + SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1410 VIN_PART_3: 8 CGW + SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX + SG_ UI_SPEED : 23|8@0+ (1,0) [0|255] "" XXX + SG_ METER_SLIDER_BRIGHTNESS_PCT : 30|7@0+ (1,0) [12|100] "%" XXX + SG_ METER_SLIDER_LOW_BRIGHTNESS : 37|1@0+ (1,0) [0|1] "" XXX + SG_ METER_SLIDER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ UNITS : 63|3@0+ (1,0) [1|4] "" XXX + +BO_ 1553 UI_SETTING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + SG_ ODOMETER : 39|32@0+ (1,0) [0|1048575] "" XXX + +BO_ 1556 BLINKERS_STATE: 8 XXX + SG_ BLINKER_BUTTON_PRESSED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 BODY_CONTROL_STATE: 8 XXX + SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX + SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX + +BO_ 1571 CERTIFICATION_ECU: 8 CGW + SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX + SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX + SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX + +BO_ 1592 DOOR_LOCKS: 8 XXX + SG_ LOCK_STATUS_CHANGED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX + SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX + +BO_ 1779 ADAS_TOGGLE_STATE: 8 XXX + SG_ OK_BUTTON_PRESSED : 15|1@0+ (1,0) [0|1] "" BCM + SG_ SWS_TOGGLE_CMD : 24|1@0+ (1,0) [0|1] "" XXX + SG_ SWS_SENSITIVITY_CMD : 26|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_ON_CMD : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_OFF_CMD : 29|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY_HI_CMD : 30|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY_STD_CMD : 31|1@0+ (1,0) [0|1] "" XXX + SG_ IPAS_TOGGLE : 34|1@0+ (1,0) [0|1] "" XXX + SG_ BSM_TOGGLE_CMD : 37|1@0+ (1,0) [0|1] "" XXX + SG_ IPAS_SONAR_TOGGLE : 38|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_TOGGLE_CMD : 40|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_SENSITIVITY_CMD : 41|1@0+ (1,0) [0|1] "" XXX + +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 36 ACCEL_X "x-axis accel"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 119 FDRVREAL "ICE only: force applied by wheels from the engine. includes creeping force, regen, and engine braking"; +CM_ SG_ 166 BRAKE_FORCE "hybrid only: force applied by friction brakes from user or ACC command"; +CM_ SG_ 295 FDRVREAL "hybrid only: force applied by wheels from the engine and/or electric motors. includes creeping force, regen, and engine braking"; +CM_ SG_ 466 NEUTRAL_FORCE "force in newtons the engine/electric motors are applying without any acceleration commands or user input"; +CM_ SG_ 466 ACC_BRAKING "whether brakes are being actuated from ACC command"; +CM_ SG_ 466 ACCEL_NET "net negative acceleration (braking) applied by the system if on flat ground"; +CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; +CM_ SG_ 467 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement"; +CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 643 _COUNTER "only used on cars that use this msg for cruise control"; +CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; +CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 800 SLOPE_ANGLE "potentially used by the PCM to compensate for road pitch"; +CM_ SG_ 800 ACCEL "filtered ego acceleration"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; +CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; +CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; +CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; +CM_ SG_ 835 DISTANCE "Cycle through ACC following distance from long, mid, short when set to 1"; +CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; +CM_ SG_ 835 LEAD_VEHICLE_STOPPED "Set to 1 when lead is stopped, likely only used in older TSS-P vehicles"; +CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; +CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; +CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; +CM_ SG_ 865 GAS_PEDAL_ALT "copy of main GAS_PEDAL. Both use 8 bits. Might indicate that this message is for pedals."; +CM_ SG_ 865 CLUTCH_RELEASED "boolean of clutch for 6MT."; +CM_ SG_ 865 ACCEL_NET "net positive acceleration (gas) applied by the system if on flat ground, may not include creeping force"; +CM_ SG_ 865 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement. Also describes a lockout when the ACC_CONTROL->ACC_MALFUNCTION bit is set."; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in the vehicle's UI with the vehicle's unit"; +CM_ SG_ 921 TEMP_ACC_FAULTED "1 when the UI is displaying or playing fault-related alerts or sounds. Also 1 when pressing main on."; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 956 GEAR "on 6MT, only R shows."; +CM_ SG_ 1009 UI_SET_SPEED "units seem to be whatever the car is set to"; +CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; +CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; +CM_ SG_ 1041 PCS_DUST "alert: Front Camera Low Visibility Unavailable See Owner's Manual"; +CM_ SG_ 1041 PCS_DUST2 "alert: Pre-Collision System Radar Sensor Blocked Unavailable Clean Radar Sensor"; +CM_ SG_ 1041 PCS_TEMP "alert: Front Camera Out of Temperature Range Unavailable Wait until Normal Temperature"; +CM_ SG_ 1041 PCS_TEMP2 "alert: Pre-Collision System Out of Temperature Range Unavailable See Owner's Manual"; +CM_ SG_ 1041 FRD_ADJ "alert: ERROR ADJUSTING FRONT RADAR BEAM"; +CM_ SG_ 1042 LDA_SA_TOGGLE "LDA Steering Assist Toggle"; +CM_ SG_ 1042 LDW_EXIST "Unclear what this is, it's usually set to 0"; +CM_ SG_ 1042 LDA_SENSITIVITY "LDA Sensitivity"; +CM_ SG_ 1042 LDA_ON_MESSAGE "Display LDA Turned ON message"; +CM_ SG_ 1042 REPEATED_BEEPS "LDA audible warning"; +CM_ SG_ 1042 LDA_UNAVAILABLE_QUIET "LDA toggles and sensitivity settings are greyed out if set to 1"; +CM_ SG_ 1042 LDA_MESSAGES "Various LDA Messages"; +CM_ SG_ 1042 LDA_FRONT_CAMERA_BLOCKED "originally LDAFCVB, LDA related settings are greyed out if set to 1"; +CM_ SG_ 1042 TAKE_CONTROL "Please Control Steering Wheel warning"; +CM_ SG_ 1042 LANE_SWAY_TOGGLE "Lane Sway Warning System SWS Switch"; +CM_ SG_ 1042 LANE_SWAY_WARNING "Lane Sway Warning System Triggered"; +CM_ SG_ 1042 LANE_SWAY_FLD "Unknown signal for Lane Sway Warning System, set to 7 on stock system when SWS is enabled, 0 when SWS is disabled"; +CM_ SG_ 1042 LANE_SWAY_BUZZER "Similar to TWO_BEEPS"; +CM_ SG_ 1042 SET_ME_X01 "empty bit on leaked dbc, always set to 1 during normal operations"; +CM_ SG_ 1042 SET_ME_X02 "empty bit on leaked dbc, always set to 2 during normal operations"; +CM_ SG_ 1083 STATE "when the dashboard button is pressed, the value changes from zero to non-zero"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; +CM_ SG_ 1552 UI_SPEED "Does not appear to match dash"; +CM_ SG_ 1552 METER_SLIDER_BRIGHTNESS_PCT "Combination display brightness setting, scales from 12 per cent to 100 per cent, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1552 METER_SLIDER_LOW_BRIGHTNESS "Combination display low brightness mode, also controls footwell lighting"; +CM_ SG_ 1552 METER_SLIDER_DIMMED "Combination display slider not at max, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; +CM_ SG_ 1592 LOCK_STATUS_CHANGED "1 on rising edge of lock/unlocking"; +CM_ SG_ 1592 LOCK_STATUS "The next 3 bits always seem to follow this signal."; +CM_ SG_ 1592 LOCKED_VIA_KEYFOB "1 for as long as car is locked with key fob or door handle touch"; + +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; +VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; +VAL_ 467 PCM_FOLLOW_DISTANCE 1 "far" 2 "medium" 3 "close"; +VAL_ 614 STATE 3 "enabled" 1 "disabled"; +VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; +VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; +VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; +VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; +VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; +VAL_ 865 CLUTCH_RELEASED 0 "clutch pressed any amount" 1 "clutch released" +VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 921 DISTANCE_LINES 0 "not displayed" 1 "close" 2 "medium" 3 "far"; +VAL_ 956 SPORT_ON 0 "off" 1 "on"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; +VAL_ 956 SPORT_GEAR 1 "S1" 2 "S2" 3 "S3" 4 "S4" 5 "S5" 6 "S6"; +VAL_ 956 ECON_ON 0 "off" 1 "on"; +VAL_ 956 B_GEAR_ENGAGED 0 "off" 1 "on"; +VAL_ 956 DRIVE_ENGAGED 0 "off" 1 "on"; +VAL_ 1005 REVERSE_CAMERA_GUIDELINES 3 "No guidelines" 2 "Static guidelines" 1 "Active guidelines"; +VAL_ 1009 PCM_FOLLOW_DISTANCE 1 "far" 2 "medium" 3 "close"; +VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; +VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; +VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; +VAL_ 1042 BARRIERS 3 "left" 2 "right" 1 "both" 0 "none"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LKAS_STATUS 1 "on" 0 "off"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LDA_ON_MESSAGE 2 "Lane Departure Alert Turned ON, Steering Assist Inactive" 1 "Lane Departure Alert Turned ON, Steering Assist Active" 0 "clear"; +VAL_ 1042 LDA_SA_TOGGLE 2 "steering assist off" 1 "steering assist on"; +VAL_ 1042 LDA_SENSITIVITY 2 "standard" 1 "high" 0 "undefined"; +VAL_ 1042 LDA_MESSAGES 4 "lda unavailable at this speed" 1 "lda unavailable below approx 50km/h" 0 "ok"; +VAL_ 1042 LDA_FRONT_CAMERA_BLOCKED 1 "lda unavailable" 0 "ok"; +VAL_ 1042 TAKE_CONTROL 1 "take control" 0 "ok"; +VAL_ 1042 LANE_SWAY_WARNING 3 "ok" 2 "orange please take a break" 1 "prompt would you like to take a break" 0 "ok"; +VAL_ 1042 LANE_SWAY_BUZZER 3 "ok" 2 "beep twice" 1 "beep twice" 0 "ok"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; +VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1552 METER_SLIDER_LOW_BRIGHTNESS 1 "Low brightness mode, footwell lights off" 0 "Normal mode, footwell lights on"; +VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; +VAL_ 1552 UNITS 1 "km (km/L)" 2 "km (L/100km)" 3 "miles (MPG US)" 4 "miles (MPG Imperial)"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1556 BLINKER_BUTTON_PRESSED 1 "button pressed" 0 "not pressed"; +VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; diff --git a/opendbc_repo/opendbc/dbc/generator/toyota/toyota_new_mc_pt.dbc b/opendbc_repo/opendbc/dbc/generator/toyota/toyota_new_mc_pt.dbc new file mode 100644 index 000000000000000..91a8723f5a96920 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/toyota/toyota_new_mc_pt.dbc @@ -0,0 +1,21 @@ +CM_ "IMPORT _toyota_2017.dbc"; + +BO_ 548 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX + SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 1178 BRAKE_RELATED: 8 XXX + SG_ BRAKE_PRESSED : 48|1@0+ (1,0) [0|1] "" XXX + +CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; + +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc_repo/opendbc/dbc/generator/toyota/toyota_nodsu_pt.dbc b/opendbc_repo/opendbc/dbc/generator/toyota/toyota_nodsu_pt.dbc new file mode 100644 index 000000000000000..1e2d2f9e4bad92c --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/toyota/toyota_nodsu_pt.dbc @@ -0,0 +1,77 @@ +CM_ "IMPORT _toyota_2017.dbc"; + +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_ 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 + SG_ LKA_ACTIVE : 26|1@0+ (1,0) [0|1] "" XXX + SG_ CLEAR_HOLD_STEERING_ALERT : 30|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ LTA_STATE : 15|5@0+ (1,0) [0|31] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 881 LTA_RELATED: 8 FCM + SG_ GAS_PEDAL : 15|8@0+ (0.005,0) [0|1] "" XXX + SG_ STEER_ANGLE : 23|16@0- (0.0573,0) [-500|500] "" XXX + SG_ TURN_SIGNALS : 35|2@0+ (1,0) [0|3] "" XXX + SG_ UNKNOWN_2 : 58|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SA_TOGGLE : 59|1@0+ (1,0) [0|1] "" XXX + SG_ LTA_STEER_REQUEST : 60|1@0+ (1,0) [0|1] "" XXX + SG_ UNKNOWN : 61|1@0+ (1,0) [0|1] "" XXX + SG_ STEERING_PRESSED : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 1014 BSM: 8 XXX + SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX + SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX + SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX + SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" 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 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"; +CM_ SG_ 401 STEER_REQUEST "enable bit for steering, 1 to steer, 0 to not"; +CM_ SG_ 401 STEER_REQUEST_2 "enable bit for steering, 1 to steer, 0 to not"; +CM_ SG_ 401 LKA_ACTIVE "1 when using LTA for LKA"; +CM_ SG_ 401 SETME_X1 "usually 1, seen at 0 on some South American Corollas indicating lack of stock Lane Tracing Assist"; +CM_ SG_ 401 SETME_X3 "almost completely correlates with Toyota Safety Sense version, but may instead describe max torque when using LTA. if TSS 2.5 or 2022 RAV4, this is always 1. if TSS 2.0 this is always 3 (or 0 on Alphard, Highlander, NX)"; +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 881 GAS_PEDAL "not set on all cars, only seen on TSS 2.5 Camry Hybrid so far"; +CM_ SG_ 881 STEER_ANGLE "matches STEER_TORQUE_SENSOR->STEER_ANGLE"; +CM_ SG_ 881 TURN_SIGNALS "flipped on some cars"; +CM_ SG_ 881 LDA_SA_TOGGLE "not applicable for all cars"; +CM_ SG_ 881 LTA_STEER_REQUEST "only applicable for TSS 2.5: matches STEERING_LTA->STEER_REQUEST"; +CM_ SG_ 881 UNKNOWN "related to steering wheel angle"; +CM_ SG_ 881 STEERING_PRESSED "only applicable for TSS 2.5: low sensitivity steering wheel pressed by driver signal"; +CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility"; +CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility"; + +VAL_ 401 SETME_X3 3 "TSS 2.0" 1 "TSS 2.5 or 2022 RAV4" 0 "TSS 2.0 on Alphard, Highlander, NX"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 17 "permanent_fault" 11 "lka_missing_unavailable2" 9 "temporary_fault2" 5 "active" 3 "lka_missing_unavailable" 1 "standby"; +VAL_ 610 LTA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 3 "lta_missing_unavailable" 1 "standby"; diff --git a/opendbc_repo/opendbc/dbc/generator/toyota/toyota_rav4_prime.dbc b/opendbc_repo/opendbc/dbc/generator/toyota/toyota_rav4_prime.dbc new file mode 100644 index 000000000000000..3ad3da4373262f1 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/toyota/toyota_rav4_prime.dbc @@ -0,0 +1,478 @@ +VERSION "" + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX DSU HCU EPS IPAS CGW BGM + +BO_ 15 SECOC_SYNCHRONIZATION: 8 XXX + SG_ TRIP_CNT : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ RESET_CNT : 23|20@0+ (1,0) [0|65535] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + +BO_ 257 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_PRESSURE_1 : 31|8@0+ (1,0) [0|15] "" XXX + SG_ BRAKE_PRESSURE_2 : 61|6@0+ (1,0) [0|63] "" XXX + +BO_ 278 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL_ACC : 7|8@0+ (0.005,0) [0|255] "" XXX + SG_ GAS_PEDAL_USER : 15|8@0+ (0.005,0) [0|255] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 295 GEAR_PACKET_HYBRID: 8 XXX + SG_ CAR_MOVEMENT : 25|10@0- (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 305 STEERING_LTA_2: 8 XXX + SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_REQUEST : 3|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 13|6@0+ (1,0) [0|63] "" XXX + SG_ STEER_ANGLE_CMD : 23|16@0- (0.0573,0) [0|65535] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 353 DSU_SPEED: 7 XXX + SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "km/h" XXX + +BO_ 374 PCM_CRUISE: 8 XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_STATE : 31|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 375 PCM_CRUISE_3: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0- (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_6 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_7 : 21|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_5 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_RELEASED : 30|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 31|1@0+ (1,0) [0|1] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 387 ACC_CONTROL_2: 8 XXX + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 401 STEERING_LTA: 8 XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX + SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" 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 + SG_ LKA_ACTIVE : 26|1@0+ (1,0) [0|1] "" XXX + SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX + SG_ CLEAR_HOLD_STEERING_ALERT : 30|1@0+ (1,0) [0|1] "" XXX + SG_ PERCENTAGE : 39|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_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 418 CRUISE_RELATED: 8 XXX + SG_ CRUISE_ACTIVE : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ BRAKE_PRESSED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PCM_FOLLOW_DISTANCE : 12|2@0+ (1,0) [0|3] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "" XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "km/h" XXX + SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_ANGLE_INITIALIZING : 3|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1,0) [-32768|32767] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LTA_STATE : 15|5@0+ (1,0) [0|31] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 DSU + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 740 STEERING_LKA: 8 XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU + SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX + SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX + SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX + SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX + SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX + SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX + SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 836 PRE_COLLISION_2: 8 DSU + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 881 LTA_RELATED: 8 FCM + SG_ GAS_PEDAL : 15|8@0+ (0.005,0) [0|1] "" XXX + SG_ STEER_ANGLE : 23|16@0- (0.0573,0) [-500|500] "" XXX + SG_ TURN_SIGNALS : 35|2@0+ (1,0) [0|3] "" XXX + SG_ UNKNOWN_2 : 58|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SA_TOGGLE : 59|1@0+ (1,0) [0|1] "" XXX + SG_ LTA_STEER_REQUEST : 60|1@0+ (1,0) [0|1] "" XXX + SG_ UNKNOWN : 61|1@0+ (1,0) [0|1] "" XXX + SG_ STEERING_PRESSED : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ TEMP_ACC_FAULTED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX + +BO_ 1014 BSM: 8 XXX + SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX + SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX + SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX + SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX + SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + +BO_ 1041 PCS_HUD: 8 DSU + SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX + SG_ PCS_DUST : 34|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_TEMP : 35|1@0+ (1,0) [0|0] "" XXX + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_DUST2 : 41|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_TEMP2 : 42|1@0+ (1,0) [0|0] "" XXX + SG_ FRD_ADJ : 53|3@0+ (1,0) [0|0] "" XXX + SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 DSU + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_STATUS : 7|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LDW_EXIST : 10|1@0+ (1,0) [0|1] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE_QUIET : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE : 16|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY : 18|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SA_TOGGLE : 20|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_MESSAGES : 23|3@0+ (1,0) [0|1] "" XXX + SG_ LDA_ON_MESSAGE : 31|2@0+ (1,0) [0|3] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X01 : 42|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_TOGGLE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_SENSITIVITY : 45|2@0+ (1,0) [0|3] "" XXX + SG_ TAKE_CONTROL : 46|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_FRONT_CAMERA_BLOCKED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_BUZZER : 50|2@0+ (1,0) [0|0] "" XXX + SG_ LANE_SWAY_FLD : 53|3@0+ (1,0) [0|7] "" XXX + SG_ LANE_SWAY_WARNING : 55|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1044 AUTO_HIGH_BEAM: 8 FCM + SG_ AHB_DUTY : 47|8@0+ (0.5,0) [0|0] "%" Vector__XXX + SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "km/h" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX + SG_ UI_SPEED : 23|8@0+ (1,0) [0|255] "" XXX + SG_ METER_SLIDER_BRIGHTNESS_PCT : 30|7@0+ (1,0) [12|100] "%" XXX + SG_ METER_SLIDER_LOW_BRIGHTNESS : 37|1@0+ (1,0) [0|1] "" XXX + SG_ METER_SLIDER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ UNITS : 63|3@0+ (1,0) [1|4] "" XXX + +BO_ 1553 UI_SETTING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + SG_ ODOMETER : 39|32@0+ (1,0) [0|1048575] "" XXX + +BO_ 1556 BLINKERS_STATE: 8 XXX + SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 BODY_CONTROL_STATE: 8 XXX + SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX + SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1571 CERTIFICATION_ECU: 8 CGW + SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX + SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX + SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX + +BO_ 1592 DOOR_LOCKS: 8 XXX + SG_ LOCK_STATUS_CHANGED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX + SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX + +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 305 STEER_ANGLE_CMD "Used in place of STEERING_LTA.STEER_ANGLE_CMD on SecOC cars"; +CM_ SG_ 387 ACCEL_CMD "Used in place of ACC_CONTROL.ACCEL_CMD on SecOC cars"; +CM_ SG_ 401 STEER_REQUEST "enable bit for steering, 1 to steer, 0 to not"; +CM_ SG_ 401 SETME_X1 "usually 1, seen at 0 on some South American Corollas indicating lack of stock Lane Tracing Assist"; +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 STEER_REQUEST_2 "enable bit for steering, 1 to steer, 0 to not"; +CM_ SG_ 401 LKA_ACTIVE "1 when using LTA for LKA"; +CM_ SG_ 401 SETME_X3 "almost completely correlates with Toyota Safety Sense version, but may instead describe max torque when using LTA. if TSS 2.5 or 2022 RAV4, this is always 1. if TSS 2.0 this is always 3 (or 0 on Alphard, Highlander, NX)"; +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"; +CM_ SG_ 401 PERCENTAGE "driver override percentage (0-100), very close to steeringPressed in OP"; +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_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; +CM_ SG_ 467 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; +CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; +CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; +CM_ SG_ 835 DISTANCE "Cycle through ACC following distance from long, mid, short when set to 1"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; +CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; +CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; +CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; +CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; +CM_ SG_ 881 GAS_PEDAL "not set on all cars, only seen on TSS 2.5 Camry Hybrid so far"; +CM_ SG_ 881 STEER_ANGLE "matches STEER_TORQUE_SENSOR->STEER_ANGLE"; +CM_ SG_ 881 TURN_SIGNALS "flipped on some cars"; +CM_ SG_ 881 LDA_SA_TOGGLE "not applicable for all cars"; +CM_ SG_ 881 LTA_STEER_REQUEST "only applicable for TSS 2.5: matches STEERING_LTA->STEER_REQUEST"; +CM_ SG_ 881 UNKNOWN "related to steering wheel angle"; +CM_ SG_ 881 STEERING_PRESSED "only applicable for TSS 2.5: low sensitivity steering wheel pressed by driver signal"; +CM_ SG_ 921 TEMP_ACC_FAULTED "1 when the UI is displaying or playing fault-related alerts or sounds. Also 1 when pressing main on."; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in the vehicle's UI with the vehicle's unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility"; +CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility"; +CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; +CM_ SG_ 1041 PCS_DUST "alert: Front Camera Low Visibility Unavailable See Owner's Manual"; +CM_ SG_ 1041 PCS_TEMP "alert: Front Camera Out of Temperature Range Unavailable Wait until Normal Temperature"; +CM_ SG_ 1041 PCS_DUST2 "alert: Pre-Collision System Radar Sensor Blocked Unavailable Clean Radar Sensor"; +CM_ SG_ 1041 PCS_TEMP2 "alert: Pre-Collision System Out of Temperature Range Unavailable See Owner's Manual"; +CM_ SG_ 1041 FRD_ADJ "alert: ERROR ADJUSTING FRONT RADAR BEAM"; +CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; +CM_ SG_ 1042 LDW_EXIST "Unclear what this is, it's usually set to 0"; +CM_ SG_ 1042 LDA_UNAVAILABLE_QUIET "LDA toggles and sensitivity settings are greyed out if set to 1"; +CM_ SG_ 1042 LDA_SENSITIVITY "LDA Sensitivity"; +CM_ SG_ 1042 LDA_SA_TOGGLE "LDA Steering Assist Toggle"; +CM_ SG_ 1042 LDA_MESSAGES "Various LDA Messages"; +CM_ SG_ 1042 LDA_ON_MESSAGE "Display LDA Turned ON message"; +CM_ SG_ 1042 REPEATED_BEEPS "LDA audible warning"; +CM_ SG_ 1042 SET_ME_X01 "empty bit on leaked dbc, always set to 1 during normal operations"; +CM_ SG_ 1042 LANE_SWAY_TOGGLE "Lane Sway Warning System SWS Switch"; +CM_ SG_ 1042 TAKE_CONTROL "Please Control Steering Wheel warning"; +CM_ SG_ 1042 LDA_FRONT_CAMERA_BLOCKED "originally LDAFCVB, LDA related settings are greyed out if set to 1"; +CM_ SG_ 1042 LANE_SWAY_BUZZER "Similar to TWO_BEEPS"; +CM_ SG_ 1042 LANE_SWAY_FLD "Unknown signal for Lane Sway Warning System, set to 7 on stock system when SWS is enabled, 0 when SWS is disabled"; +CM_ SG_ 1042 LANE_SWAY_WARNING "Lane Sway Warning System Triggered"; +CM_ SG_ 1042 SET_ME_X02 "empty bit on leaked dbc, always set to 2 during normal operations"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; +CM_ SG_ 1552 UI_SPEED "Does not appear to match dash"; +CM_ SG_ 1552 METER_SLIDER_BRIGHTNESS_PCT "Combination display brightness setting, scales from 12 per cent to 100 per cent, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1552 METER_SLIDER_LOW_BRIGHTNESS "Combination display low brightness mode, also controls footwell lighting"; +CM_ SG_ 1552 METER_SLIDER_DIMMED "Combination display slider not at max, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; +CM_ SG_ 1592 LOCK_STATUS_CHANGED "1 on rising edge of lock/unlocking"; +CM_ SG_ 1592 LOCK_STATUS "The next 3 bits always seem to follow this signal."; +CM_ SG_ 1592 LOCKED_VIA_KEYFOB "1 for as long as car is locked with key fob or door handle touch"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 401 SETME_X3 3 "TSS 2.0" 1 "TSS 2.5 or 2022 RAV4" 0 "TSS 2.0 on Alphard, Highlander, NX"; +VAL_ 467 PCM_FOLLOW_DISTANCE 1 "far" 2 "medium" 3 "close"; +VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LTA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 3 "lta_missing_unavailable" 1 "standby"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 17 "permanent_fault" 11 "lka_missing_unavailable2" 9 "temporary_fault2" 5 "active" 3 "lka_missing_unavailable" 1 "standby"; +VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; +VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; +VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; +VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; +VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; +VAL_ 1042 BARRIERS 3 "left" 2 "right" 1 "both" 0 "none"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LKAS_STATUS 1 "on" 0 "off"; +VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; +VAL_ 1042 LDA_SENSITIVITY 2 "standard" 1 "high" 0 "undefined"; +VAL_ 1042 LDA_SA_TOGGLE 2 "steering assist off" 1 "steering assist on"; +VAL_ 1042 LDA_MESSAGES 4 "lda unavailable at this speed" 1 "lda unavailable below approx 50km/h" 0 "ok"; +VAL_ 1042 LDA_ON_MESSAGE 2 "Lane Departure Alert Turned ON, Steering Assist Inactive" 1 "Lane Departure Alert Turned ON, Steering Assist Active" 0 "clear"; +VAL_ 1042 TAKE_CONTROL 1 "take control" 0 "ok"; +VAL_ 1042 LDA_FRONT_CAMERA_BLOCKED 1 "lda unavailable" 0 "ok"; +VAL_ 1042 LANE_SWAY_BUZZER 3 "ok" 2 "beep twice" 1 "beep twice" 0 "ok"; +VAL_ 1042 LANE_SWAY_WARNING 3 "ok" 2 "orange please take a break" 1 "prompt would you like to take a break" 0 "ok"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; +VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1552 METER_SLIDER_LOW_BRIGHTNESS 1 "Low brightness mode, footwell lights off" 0 "Normal mode, footwell lights on"; +VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; +VAL_ 1552 UNITS 1 "km (km/L)" 2 "km (L/100km)" 3 "miles (MPG US)" 4 "miles (MPG Imperial)"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; diff --git a/opendbc_repo/opendbc/dbc/generator/toyota/toyota_tnga_k_pt.dbc b/opendbc_repo/opendbc/dbc/generator/toyota/toyota_tnga_k_pt.dbc new file mode 100644 index 000000000000000..a06469c372aa87e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/generator/toyota/toyota_tnga_k_pt.dbc @@ -0,0 +1,19 @@ +CM_ "IMPORT _toyota_2017.dbc"; + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; + +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/gm_global_a_chassis.dbc b/opendbc_repo/opendbc/dbc/gm_global_a_chassis.dbc similarity index 100% rename from opendbc/gm_global_a_chassis.dbc rename to opendbc_repo/opendbc/dbc/gm_global_a_chassis.dbc diff --git a/opendbc_repo/opendbc/dbc/gm_global_a_high_voltage_management.dbc b/opendbc_repo/opendbc/dbc/gm_global_a_high_voltage_management.dbc new file mode 100644 index 000000000000000..60729e56921e6fb --- /dev/null +++ b/opendbc_repo/opendbc/dbc/gm_global_a_high_voltage_management.dbc @@ -0,0 +1,196 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: +BU_: K16_BECM K114B_HPCM T18_BatteryCharger +BO_ 512 Battery_Module_1: 8 K16_BECM + SG_ Voltage_1_0_A m0 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_0_B m0 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_0_C m0 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_1_A m1 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_1_B m1 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_1_C m1 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_2_A m2 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_2_B m2 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_2_C m2 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_3_A m3 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_3_B m3 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_3_C m3 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_4_A m4 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_4_B m4 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_4_C m4 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_5_A m5 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_5_B m5 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_5_C m5 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_6_A m6 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_6_B m6 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_6_C m6 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_7_A m7 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_7_B m7 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_1_7_C m7 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Cell_Bank_Number_1 M : 55|3@0+ (1,0) [0|0] "" K16_BECM + +BO_ 514 Battery_Module_2: 8 K16_BECM + SG_ Voltage_2_0_A m0 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_0_B m0 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_0_C m0 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_1_A m1 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_1_B m1 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_1_C m1 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_2_A m2 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_2_B m2 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_2_C m2 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_3_A m3 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_3_B m3 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_3_C m3 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_4_A m4 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_4_B m4 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_4_C m4 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_5_A m5 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_5_B m5 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_5_C m5 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_6_A m6 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_6_B m6 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_6_C m6 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_7_A m7 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_7_B m7 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_2_7_C m7 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Cell_Bank_Number_2 M : 55|3@0+ (1,0) [0|0] "" K16_BECM + +BO_ 516 Battery_Module_3: 8 K16_BECM + SG_ Voltage_3_0_A m0 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_0_B m0 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_0_C m0 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_1_A m1 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_1_B m1 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_1_C m1 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_2_A m2 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_2_B m2 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_2_C m2 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_3_A m3 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_3_B m3 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_3_C m3 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_4_A m4 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_4_B m4 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_4_C m4 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_5_A m5 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_5_B m5 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_5_C m5 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_6_A m6 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_6_B m6 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_6_C m6 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_7_A m7 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_7_B m7 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_3_7_C m7 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Cell_Bank_Number_3 M : 55|3@0+ (1,0) [0|0] "" K16_BECM + +BO_ 518 Battery_Module_4: 8 K16_BECM + SG_ Voltage_4_0_A m0 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_0_B m0 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_0_C m0 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_1_A m1 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_1_B m1 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_1_C m1 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_2_A m2 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_2_B m2 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_2_C m2 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_3_A m3 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_3_B m3 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_3_C m3 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_4_A m4 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_4_B m4 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_4_C m4 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_5_A m5 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_5_B m5 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_5_C m5 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_6_A m6 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_6_B m6 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_6_C m6 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_7_A m7 : 4|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_7_B m7 : 20|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Voltage_4_7_C m7 : 39|12@0+ (0.00125,0) [0|0] "V" K16_BECM + SG_ Cell_Bank_Number_4 M : 55|3@0+ (1,0) [0|0] "" K16_BECM + +BO_ 528 Pack_Stats: 8 K16_BECM + SG_ Pack_Voltage : 7|12@0+ (0.125,0) [0|0] "V" K16_BECM + SG_ Pack_Current : 23|8@0- (0.1,-0.1) [0|0] "A" K16_BECM + +BO_ 530 Charger_stats: 6 T18_BatteryCharger + SG_ Charger_HV_Current : 7|13@0+ (0.05,0) [0|0] "A" K16_BECM + SG_ HV_Voltage : 10|10@0+ (0.5,0) [0|0] "V" K16_BECM + SG_ LV_Current : 16|8@0+ (0.2,0) [0|0] "A" K16_BECM + SG_ LV_Voltage : 24|8@0+ (0.1,0) [0|0] "V" K16_BECM + +BO_ 770 Battery_temp: 8 K16_BECM + SG_ Temp_A m0 : 8|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Temp_B m0 : 16|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Temp_C m0 : 24|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Temp_D m0 : 32|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Temp_E m0 : 40|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Temp_F m0 : 48|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Temp_G m1 : 8|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Temp_H m1 : 16|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Temp_I m1 : 24|8@1+ (0.5,-40) [0|0] "C" K16_BECM + SG_ Switch M : 2|1@1+ (1,0) [0|0] "" K16_BECM + +BO_ 782 Charger_Command: 1 T18_BatteryCharger + SG_ Command : 0|8@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 772 Charger_parameters: 4 T18_BatteryCharger + SG_ Unknown : 0|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ Current : 8|8@1+ (0.05,0) [0|0] "A" Vector__XXX + SG_ Voltage : 23|16@0+ (0.5,0) [0|0] "V" Vector__XXX + +BO_ 1120 Coolant_Temp: 4 K16_BECM + SG_ Inlet_Coolant_Temp : 1|10@0+ (0.125,-40) [0|0] "" Vector__XXX + SG_ Outlet_Coolant_Temp : 17|10@0+ (0.125,-40) [0|0] "" Vector__XXX + +BO_ 778 AC_Stats: 7 T18_BatteryCharger + SG_ Mains_Voltage : 10|2@0+ (1,0) [0|0] "V" Vector__XXX + SG_ Total_Charge : 19|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 776 Charger_status: 5 T18_BatteryCharger + SG_ Status : 20|3@1+ (1,0) [0|0] "" Vector__XXX + +BA_DEF_ BO_ "GenMsgBackgroundColor" STRING ; +BA_DEF_ BO_ "GenMsgForegroundColor" STRING ; +BA_DEF_ BO_ "isj1939dbc" INT 0 0; +BA_DEF_DEF_ "GenMsgBackgroundColor" "#ffffff"; +BA_DEF_DEF_ "GenMsgForegroundColor" "#000000"; +BA_DEF_DEF_ "isj1939dbc" 0; +CM_ BU_ K16_BECM "Battery Energy Control Module"; +CM_ BU_ K114B_HPCM "Hybrid Powertrain Control Module"; +CM_ BU_ T18_BatteryCharger "Battery Charger"; +VAL_ 782 Command 1 "12V_Only" 2 "HV_Only" 3 "12V_and_HV"; +VAL_ 778 Mains_Voltage 0 "Unplugged" 1 "110V" 3 "220V"; +VAL_ 776 Status 0 "Off" 5 "LV_Only" 7 "HV_and_LV" 3 "HV_Only"; diff --git a/opendbc_repo/opendbc/dbc/gm_global_a_lowspeed.dbc b/opendbc_repo/opendbc/dbc/gm_global_a_lowspeed.dbc new file mode 100644 index 000000000000000..524eeed8be5c434 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/gm_global_a_lowspeed.dbc @@ -0,0 +1,118 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: GMLAN NEO +VAL_TABLE_ GearShifter 3 "Park" 0 "Drive/Low" ; +VAL_TABLE_ DriverDoorStatus 1 "Opened" 0 "Closed" ; +VAL_TABLE_ LKAGapButton 2 "???" 1 "??" 0 "None" ; +VAL_TABLE_ CruiseButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_TABLE_ CruiseControlActive 1 "Active" 0 "Inactive" ; +VAL_TABLE_ BlinkerStatus 1 "Active" 0 "Inactive" ; + + +BO_ 274923520 DriverDoorStatus: 1 GMLAN + SG_ DriverDoorOpened : 0|1@0+ (1,0) [0|0] "" NEO + +BO_ 272629760 Chime: 5 NEO + SG_ ChimeType : 7|8@0+ (1,0) [0|0] "" GMLAN + SG_ ChimeRepeat : 23|8@0+ (1,0) [0|0] "" GMLAN + SG_ ChimeDuration : 15|8@0+ (1,0) [0|0] "" GMLAN + SG_ ChimeByte5 : 39|8@0+ (1,0) [0|0] "" GMLAN + SG_ ChimeByte4 : 31|8@0+ (1,0) [0|0] "" GMLAN + +BO_ 270581760 BlinkerStatus: 5 GMLAN + SG_ RightBlinker : 6|1@0+ (1,0) [0|0] "" NEO + SG_ LeftBlinker : 7|1@0+ (1,0) [0|0] "" NEO + SG_ BlinkerLight : 25|1@0+ (1,0) [0|0] "" NEO + +BO_ 270794752 SteeringWheelAngle: 8 GMLAN + SG_ SteeringWheelAngle : 39|16@0- (0.0625,0) [-540|540] "deg" NEO + +BO_ 271368192 GearShifter: 8 GMLAN + SG_ GearShifter : 17|2@0+ (1,0) [0|3] "" NEO + +BO_ 271360000 GasPedalRegenCruise: 8 GMLAN + SG_ CruiseControlActive : 56|1@0+ (1,0) [0|0] "" GMLAN + SG_ MaxRegen : 12|1@0+ (1,0) [0|1] "" GMLAN,NEO + SG_ GasPedal : 47|8@0+ (1,0) [0|254] "" GMLAN,NEO + SG_ GearShifter2NotUsed : 55|8@0+ (1,0) [0|255] "" GMLAN,NEO + +BO_ 270860288 BrakePedal: 2 GMLAN + SG_ BrakeLevel : 2|2@0+ (1,0) [0|3] "" NEO + SG_ BrakeSensor : 15|8@0+ (1,0) [0|255] "" NEO + +BO_ 275480576 WheelSpeed: 8 GMLAN + SG_ WheelSpeedFL : 7|16@0+ (0.01,0) [0|70] "yd/s" NEO + SG_ WheelSpeedFR : 39|16@0+ (0.01,0) [0|70] "yd/s" NEO + SG_ WheelSpeedRL : 23|16@0+ (0.01,0) [0|70] "yd/s" NEO + SG_ WheelSpeedRR : 55|16@0+ (0.01,0) [0|70] "yd/s" NEO + +BO_ 270598144 VehicleSpeed: 8 GMLAN + SG_ VehicleSpeed1 : 7|16@0+ (0.01,0) [0|100] "mph" NEO + SG_ VehicleSpeed2 : 39|16@0+ (0.01,0) [0|100] "mph" NEO + +BO_ 276135936 CruiseButtons: 3 GMLAN + SG_ CruiseButtons : 3|3@0+ (1,0) [0|12] "" NEO + +BO_ 276127744 CruiseButtons2: 1 GMLAN + SG_ LKAGapButton : 1|2@0+ (1,0) [0|2] "" NEO + +BO_ 275955897 LeftRadar: 2 GMLAN + SG_ BSM_Indicator_Light : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 275980379 RightRadar: 2 GMLAN + SG_ BSM_Indicator_Light : 0|1@0+ (1,0) [0|1] "" XXX + + + +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "BusType" "CAN"; +BA_ "ProtocolType" "GMLAN"; +VAL_ 274923520 DriverDoorOpened 1 "Opened" 0 "Closed" ; +VAL_ 270581760 RightBlinker 1 "Active" 0 "Inactive" ; +VAL_ 270581760 LeftBlinker 1 "Active" 0 "Inactive" ; +VAL_ 270581760 BlinkerLight 1 "Active" 0 "Inactive" ; +VAL_ 271368192 GearShifter 3 "Park" 0 "Drive/Low" ; +VAL_ 271360000 CruiseControlActive 1 "Active" 0 "Inactive" ; +VAL_ 276135936 CruiseButtons 6 "Cancel" 5 "Main" 3 "Set" 2 "Resume" 1 "None" ; +VAL_ 276127744 LKAGapButton 2 "???" 1 "??" 0 "None" ; +VAL_ 275955897 BSM_Indicator_Light 0 "Disabled" 1 "Enabled"; +VAL_ 275980379 BSM_Indicator_Right 0 "Disabled" 1 "Enabled"; + diff --git a/opendbc_repo/opendbc/dbc/gm_global_a_lowspeed_1818125.dbc b/opendbc_repo/opendbc/dbc/gm_global_a_lowspeed_1818125.dbc new file mode 100644 index 000000000000000..3f5b15e6f29edf9 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/gm_global_a_lowspeed_1818125.dbc @@ -0,0 +1,3993 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 2152177664 OTA_Electric_Pwr_Readiness_LS: 1 XXX + SG_ RmtRflshElecPwrRdness : 7|8@0+ (0.025,0) [0|6.375] "AmpHour" XXX + +BO_ 2152013824 Smart_High_Beam_Cust_LS: 1 XXX + SG_ SmrtHgBmAstCstSetAvail : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SmrtHgBmAstCstCurrSetVal : 7|3@0+ (1,0) [0|7] "" XXX + +BO_ 2159255552 ODI_CenterStack_2_BCM_LS: 8 XXX + SG_ ODI_CntrStck2BCM : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159247360 ODI_BCM_2_CenterStack_LS: 8 XXX + SG_ ODI_BCM2CntrStck : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2152046592 Remote_Climate_Control_Req_LS: 5 XXX + SG_ RmClmCtrlHMIActIndReq : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RmClmCtrlRcrcSetReq : 3|3@0+ (1,0) [0|7] "" XXX + SG_ RmClmCtrlACSetReq : 10|3@0+ (1,0) [0|7] "" XXX + SG_ RmClmCtrlFrntFanStReq : 15|5@0+ (1,0) [0|31] "" XXX + SG_ RmClmCtrlFLAirDtStReq : 19|4@0+ (1,0) [0|15] "" XXX + SG_ RmClmCtrlClmModSetReq : 23|4@0+ (1,0) [0|15] "" XXX + SG_ RmClmCtrlLtSTempStReq : 29|6@0+ (1,0) [0|63] "" XXX + SG_ RmClmCtrlRrDfgSetReq : 31|2@0+ (1,0) [0|3] "" XXX + SG_ RmClmCtrlRtSTempStReq : 37|6@0+ (1,0) [0|63] "" XXX + SG_ RmClmCtrlSyncSetReq : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 2152030208 Tuner_Frequency_Request_LS: 8 XXX + SG_ TnrFrqBndReq : 3|4@0+ (1,0) [0|15] "" XXX + SG_ TnrFrqChnlReq : 15|56@0+ (1,0) [0|1] "" XXX + +BO_ 2150531072 Regen_Power_Ind_LS: 4 XXX + SG_ RegPwrLmtdDspPrcnt : 0|9@0- (0.392157,0) [-100.392192|100.000035] "%" XXX + SG_ RegPwrLmtdDspPrcntVs : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RegPwrLmtdIO : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151833600 Heated_Wndshild_CstmrIhbt_Req_LS: 1 XXX + SG_ HtdFrntWSCustRqIhbt : 5|1@0+ (1,0) [0|1] "" XXX + SG_ HtdFrntWSDispReq : 7|2@0+ (1,0) [0|3] "" XXX + +BO_ 2151817216 Heated_Wndshild_Cstmr_Req_LS: 1 XXX + SG_ HtdFrntWSCustRq : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151849984 Seat_Level_Setting_Request_LS: 2 XXX + SG_ AutoThrmlStPasLvlStRq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ AutoThrmlStDrvLvStRq : 5|3@0+ (1,0) [0|7] "" XXX + SG_ AutoThrmlStPassMdStRq : 7|2@0+ (1,0) [0|3] "" XXX + SG_ AutoThrmlStDrvMdStRq : 15|2@0+ (1,0) [0|3] "" XXX + +BO_ 2153897984 ARB_OpMode_Customization_LS: 1 XXX + SG_ RunBrdExtdFtrAvail : 3|1@0+ (1,0) [0|1] "" XXX + SG_ RunBrdOpMdCstCurrStVal : 6|3@0+ (1,0) [0|7] "" XXX + SG_ RunBrdOpMdCstStAvail : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151702528 Lane_Keeping_Assist_LS: 2 XXX + SG_ LnKpngAstRecfblIndRq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ LnMrkngIndLft : 4|2@0+ (1,0) [0|3] "" XXX + SG_ LnKepAsstStIndLft : 7|3@0+ (1,0) [0|7] "" XXX + SG_ LnMrkngIndRgt : 12|2@0+ (1,0) [0|3] "" XXX + SG_ LnKepAsstStIndRgt : 15|3@0+ (1,0) [0|7] "" XXX + +BO_ 2156986368 PassPhrase_3_AMM_LS: 8 XXX + SG_ WiFiPssPhrsDgts17to24_Mp : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2156978176 PassPhrase_2_AMM_LS: 8 XXX + SG_ WiFiPssPhrsDgts9to16_Mp : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2156969984 PassPhrase_1_AMM_LS: 8 XXX + SG_ WiFiPssPhrsDgts1to8_Mp : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2150236160 Unlock_Key_Store_Crypt_2_LS: 8 XXX + SG_ UlckKyStrCrptoDt2Group : 4|61@0+ (1,0) [0|0] "" XXX + SG_ UlckKyStrCrptoDt2 : 3|60@0+ (1,0) [0|1.15292150460685E+018] "" XXX + SG_ UlckKyStrCrptoDt2M : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150170624 Unlock_Key_Store_Crypt_1_LS: 8 XXX + SG_ UlckKyStrCrptoDt1Group : 4|61@0+ (1,0) [0|0] "" XXX + SG_ UlckKyStrCrptoDt1 : 3|60@0+ (1,0) [0|1.15292150460685E+018] "" XXX + SG_ UlckKyStrCrptoDt1M : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155126784 Drvr_Seat_Rearward_Movmnt_LS: 1 XXX + SG_ DrvrSetRrwrdMvmnt : 7|3@0+ (1,0) [0|7] "" XXX + +BO_ 2154725376 Auxiliary_Heater_LS: 1 XXX + SG_ AuxHtrAtv378 : 6|1@0+ (1,0) [0|1] "" XXX + SG_ AuxHtrRq : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2157051904 WiFi_Station_AMM_LS: 5 XXX + SG_ WiFiStatnMpReq : 1|34@0+ (1,0) [0|0] "" XXX + SG_ WSMR_WiFiAssnReq : 1|2@0+ (1,0) [0|3] "" XXX + SG_ WSMR_WiFiStnMpMACAddr : 15|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2156994560 WiFi_AP_Data_AMM_LS: 2 XXX + SG_ WiFiAccsPntData_Mp : 0|9@0+ (1,0) [0|0] "" XXX + SG_ WAPDM_WiFiEnStat : 0|1@0+ (1,0) [0|1] "" XXX + SG_ WAPDM_EncrptnType : 11|4@0+ (1,0) [0|15] "" XXX + SG_ WAPDM_SecurityType : 15|4@0+ (1,0) [0|15] "" XXX + +BO_ 2158133248 Hill_Top_Customization_LS: 6 XXX + SG_ HTRCsStAvail : 0|1@0+ (1,0) [0|1] "" XXX + SG_ HTRCsAvail : 7|7@0+ (1,0) [0|0] "" XXX + SG_ HTRCA_Res3Avail : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HTRCA_Res2Avail : 2|1@0+ (1,0) [0|1] "" XXX + SG_ HTRCA_Res1Avail : 3|1@0+ (1,0) [0|1] "" XXX + SG_ HTRCA_OnAwAvail : 4|1@0+ (1,0) [0|1] "" XXX + SG_ HTRCA_OnHmAvail : 5|1@0+ (1,0) [0|1] "" XXX + SG_ HTRCA_OnAvail : 6|1@0+ (1,0) [0|1] "" XXX + SG_ HTRCA_OffAvail : 7|1@0+ (1,0) [0|1] "" XXX + SG_ HTRCsCrStVal : 10|3@0+ (1,0) [0|7] "" XXX + SG_ HVDpltnMdMxCnfdcRgExt : 21|14@0+ (0.1,0) [0|1638.3] "km" XXX + SG_ HVDpltnMdMiCnfdcRgExt : 37|14@0+ (0.1,0) [0|1638.3] "km" XXX + +BO_ 2154651648 Telematics_Audio_Control_LS: 1 XXX + SG_ TeleAudCtl : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TAC_AudConctOutcm : 3|4@0+ (1,0) [0|15] "" XXX + SG_ TAC_AudChConctStat : 7|4@0+ (1,0) [0|15] "" XXX + +BO_ 2154635264 Telematics_Audio_Request_LS: 1 XXX + SG_ TeleAudReq : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TAR_AudSrcStat : 3|4@0+ (1,0) [0|15] "" XXX + SG_ TAR_AudConctReq : 7|4@0+ (1,0) [0|15] "" XXX + +BO_ 2152529920 LVM_Audio_Video_Command_LS: 2 XXX + SG_ LowVolModAudVidCmd : 5|14@0+ (1,0) [0|0] "" XXX + SG_ LVMAVC_StreoAudRsp : 0|2@0+ (1,0) [0|3] "" XXX + SG_ LVMAVC_PrmtAudRsp : 2|2@0+ (1,0) [0|3] "" XXX + SG_ LVMAVC_RemtEnbl : 5|3@0+ (1,0) [0|7] "" XXX + SG_ LVMAVC_SpchRcgnAval : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LVMAVC_RemSpchRcgnActn : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LVMAVC_RemSpchRcgnID : 14|3@0+ (1,0) [0|7] "" XXX + +BO_ 2152513536 LVM_Audio_Video_Req_LS: 2 XXX + SG_ LowVolModAudVidReq : 0|9@0+ (1,0) [0|0] "" XXX + SG_ LVMAVR_DispReq : 0|3@0+ (1,0) [0|7] "" XXX + SG_ LVMAVR_SpchRcgnAct : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LVMAVR_PrmtAudReq : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LVMAVR_StreoAudReq : 13|2@0+ (1,0) [0|3] "" XXX + +BO_ 2154889216 Cluster_HMI_Animation_Req_LS: 1 XXX + SG_ ClstrHMIAnmReq : 7|3@0+ (1,0) [0|7] "" XXX + +BO_ 2154872832 Infotainment_Activation_Req_LS: 1 XXX + SG_ RmRflshUpdtAvail : 6|1@0+ (1,0) [0|1] "" XXX + SG_ InfoActvnReq : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2156961792 SSID_AMM_3_LS: 8 XXX + SG_ WiFiSSIDDgts17to24_Mp : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2154569728 Infotainment_System_State_LS: 1 XXX + SG_ InfotnmntSysSt : 7|5@0+ (1,0) [0|31] "" XXX + +BO_ 2151931904 Custom_Launch_Ctrl_LS: 8 XXX + SG_ LnchCtrlMdStat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ LnchCtrlWhlSlpStat : 7|5@0+ (1,0) [0|31] "" XXX + SG_ PTExPrtclFltWrng3IO : 8|1@0+ (1,0) [0|1] "" XXX + SG_ AWDRecmndIO : 9|1@0+ (1,0) [0|1] "" XXX + SG_ LnchCtrlEngRPMStat : 15|6@0+ (1,0) [0|63] "" XXX + SG_ ACCSysSltdMd : 17|2@0+ (1,0) [0|3] "" XXX + SG_ VehSpdCntlSystmType : 20|3@0+ (1,0) [0|7] "" XXX + SG_ PTExPartFltManRegStat : 23|3@0+ (1,0) [0|7] "" XXX + SG_ TCSTempDsblReqIO : 24|1@0+ (1,0) [0|1] "" XXX + SG_ VehStbCmptvMdCstAvl : 25|1@0+ (1,0) [0|1] "" XXX + SG_ VehStbEnmntCstAvl : 26|1@0+ (1,0) [0|1] "" XXX + SG_ TCSysCstAvl : 27|1@0+ (1,0) [0|1] "" XXX + SG_ VehStbCmptvMdCurSt : 28|1@0+ (1,0) [0|1] "" XXX + SG_ ElctShfPriLtdPerfMdIO : 29|1@0+ (1,0) [0|1] "" XXX + SG_ RegVltCtlEngyRcvryAct : 30|1@0+ (1,0) [0|1] "" XXX + SG_ ACCSysSltdMdDispIO : 31|1@0+ (1,0) [0|1] "" XXX + SG_ LnchCtrlTmrVal : 35|4@0+ (1,0) [0|15] "" XXX + SG_ VehStbEnhmntCurSt : 36|1@0+ (1,0) [0|1] "" XXX + SG_ TCSysCurSt : 37|1@0+ (1,0) [0|1] "" XXX + SG_ TracAndStbScrnCnfg : 39|2@0+ (1,0) [0|3] "" XXX + SG_ BiFuelRflGaslinIndReq : 42|3@0+ (1,0) [0|7] "" XXX + SG_ AutoShtdwnIO : 43|1@0+ (1,0) [0|1] "" XXX + SG_ LnchCtrlBrkPresVal : 47|4@0+ (10,0) [0|150] "%" XXX + SG_ AutoShtdwnTmr : 55|8@0+ (1,0) [0|255] "min" XXX + SG_ FuelMdTrnstnIndReq : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2150244352 HMI_EngyConsmpHistGrph_1_LS: 8 XXX + SG_ EngyCnsHsGrphDspDtVal : 7|55@0+ (1,0) [0|0] "" XXX + SG_ ECHGDDV_Col1 : 2|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_EngyConsAvg : 7|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col3 : 8|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col2 : 13|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col4 : 19|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col6 : 25|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col5 : 30|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col7 : 36|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col9 : 42|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col8 : 47|5@0+ (1,0) [0|31] "" XXX + SG_ ECHGDDV_Col10 : 53|5@0+ (1,0) [0|31] "" XXX + +BO_ 2156953600 SSID_AMM_2_LS: 8 XXX + SG_ WiFiSSIDDgts9to16_Mp : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2151686144 SD_Card_LS: 2 XXX + SG_ SDCrdFullIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SDCrdErrIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ NoSDCrdPrIO : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155028480 Lane_Change_Threat_LS: 2 XXX + SG_ RgtLnChgThrt : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RtLnChngThrtAprchSpd : 15|8@0- (1,0) [-128|127] "km/h" XXX + +BO_ 2151915520 HMI_Display_LS: 8 XXX + SG_ AHDisbldDrOpnIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ AHDisbldStbltIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ AHAppBrkPedlIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ AHServcIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ShfToPrkBfExtngIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ AHEnbld : 5|1@0+ (1,0) [0|1] "" XXX + SG_ AHAct : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ESPDrvrIlkShfAtdIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ ESPTransMalfIO : 9|1@0+ (1,0) [0|1] "" XXX + SG_ ESPRngInvldReqIO : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ESPPrkInvldReqIO : 11|1@0+ (1,0) [0|1] "" XXX + SG_ ESPHldShfLvrToEngRgIO : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ESPDrvrPrkIlkSftAtdIO : 13|1@0+ (1,0) [0|1] "" XXX + SG_ EngIntkArBstPrExtRngGroup : 14|15@0+ (1,0) [0|0] "" XXX + SG_ EngIntkArBstPrExtRng : 8|9@0+ (1,-110) [-110|401] "kPa" XXX + SG_ EngIntkArBstPrExtRngV : 14|1@0+ (1,0) [0|1] "" XXX + SG_ ElcTransRngSlctVDA : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ElecShfRngDispRCExtd : 27|4@0+ (1,0) [0|15] "" XXX + SG_ ElecShfRngDisp : 31|4@0+ (1,0) [0|15] "" XXX + SG_ DrvEffInd : 39|8@0- (0.78125,0) [-100|99.21875] "%" XXX + SG_ ESPShfToDrvTryAgnIO : 43|1@0+ (1,0) [0|1] "" XXX + SG_ ESPTrnVehOffFrPrkIO : 44|1@0+ (1,0) [0|1] "" XXX + SG_ ESPTrnsCtlrMalfIO : 45|1@0+ (1,0) [0|1] "" XXX + SG_ ElcShfPriTwoGrsSlInRq : 47|2@0+ (1,0) [0|3] "" XXX + +BO_ 2152153088 Right_Rear_Seat_Display_Stats_LS: 6 XXX + SG_ RRStCtlDispStat : 3|44@0+ (1,0) [0|0] "" XXX + SG_ RRSCDS_MassgTyp : 1|4@0+ (1,0) [0|15] "" XXX + SG_ RRSCDS_Massg : 3|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_HdrstFwdRrwd : 8|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_HdrstUpDn : 10|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_MassgIntsty : 13|3@0+ (1,0) [0|7] "" XXX + SG_ RRSCDS_HdrstTltFwdRr : 17|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_HdrstWngInOt : 19|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_HdrstFdRrUDn : 22|3@0+ (1,0) [0|7] "" XXX + SG_ RRSCDS_LmbrUDnFdRr : 25|3@0+ (1,0) [0|7] "" XXX + SG_ RRSCDS_LmbrFwdRr : 27|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_LmbrUpDwn : 29|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_UprShldrFdRr : 31|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_BkCshBlstInOt : 34|3@0+ (1,0) [0|7] "" XXX + SG_ RRSCDS_CshBlstrInOut : 36|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_BkBlstrInOut : 38|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_UnsdRsrvd : 42|3@0+ (1,0) [0|7] "" XXX + SG_ RRSCDS_DispReq : 43|1@0+ (1,0) [0|1] "" XXX + SG_ RRSCDS_DispSz : 45|2@0+ (1,0) [0|3] "" XXX + SG_ RRSCDS_CshLgAdjFdRr : 47|2@0+ (1,0) [0|3] "" XXX + +BO_ 2152136704 Right_Rear_Seat_Massage_LS: 8 XXX + SG_ RRStMassgPrty : 7|64@0+ (1,0) [0|0] "" XXX + SG_ RRSMP_Type2 : 3|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type1 : 7|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type4 : 11|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type3 : 15|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type6 : 19|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type5 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type8 : 27|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type7 : 31|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type10 : 35|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type9 : 39|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type12 : 43|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type11 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type14 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_Type13 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ RRSMP_UnsdRsrvd : 56|1@0+ (1,0) [0|1] "" XXX + SG_ RRSMP_MaxDispVal : 59|3@0+ (1,0) [0|7] "" XXX + SG_ RRSMP_Type15 : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2152120320 Right_Rear_Seat_Actuator_LS: 8 XXX + SG_ RRStActPrty : 7|64@0+ (1,0) [0|0] "" XXX + SG_ RRSAP_HdrstUpDn : 3|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_Massg : 7|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_HdrstUpDnFdRr : 11|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_HdrstFwdRrwd : 15|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_HdrstTltFwdRr : 19|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_HdrstWngsInOut : 23|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_LmbrUpDwn : 27|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_UprShldrFwdRr : 31|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_LmbrUpDnFdRr : 35|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_LmbrFwdRr : 39|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_CshBlstrInOut : 43|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_BkBlstrInOut : 47|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_CshLgthAdjFdRr : 51|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_BkCshBlstrInOut : 55|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_UnsdRsrvd : 59|4@0+ (1,0) [0|15] "" XXX + SG_ RRSAP_DispSz : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2152103936 Left_Rear_Seat_Display_Status_LS: 6 XXX + SG_ LRStCtlDispStat : 3|44@0+ (1,0) [0|0] "" XXX + SG_ LRSCDS_MassgTyp : 1|4@0+ (1,0) [0|15] "" XXX + SG_ LRSCDS_Massg : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_HdrstFwdRrwd : 8|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_HdrstUpDn : 10|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_MassgIntsty : 13|3@0+ (1,0) [0|7] "" XXX + SG_ LRSCDS_HdrstTltFwdRr : 17|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_HdrstWngInOt : 19|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_HdrstFdRrUDn : 22|3@0+ (1,0) [0|7] "" XXX + SG_ LRSCDS_LmbrUDnFdRr : 25|3@0+ (1,0) [0|7] "" XXX + SG_ LRSCDS_LmbrFwdRr : 27|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_LmbrUpDwn : 29|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_UprShldrFdRr : 31|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_BkCshBlstInOt : 34|3@0+ (1,0) [0|7] "" XXX + SG_ LRSCDS_CshBlstrInOut : 36|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_BkBlstrInOut : 38|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_UnsdRsrvd : 42|3@0+ (1,0) [0|7] "" XXX + SG_ LRSCDS_DispReq : 43|1@0+ (1,0) [0|1] "" XXX + SG_ LRSCDS_DispSz : 45|2@0+ (1,0) [0|3] "" XXX + SG_ LRSCDS_CshLgAdjFdRr : 47|2@0+ (1,0) [0|3] "" XXX + +BO_ 2152087552 Left_Rear_Seat_Massage_LS: 8 XXX + SG_ LRStMassgPrty : 7|64@0+ (1,0) [0|0] "" XXX + SG_ LRSMP_Type2 : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type1 : 7|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type4 : 11|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type3 : 15|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type6 : 19|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type5 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type8 : 27|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type7 : 31|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type10 : 35|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type9 : 39|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type12 : 43|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type11 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type14 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_Type13 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ LRSMP_UnsdRsrvd : 56|1@0+ (1,0) [0|1] "" XXX + SG_ LRSMP_MaxDispVal : 59|3@0+ (1,0) [0|7] "" XXX + SG_ LRSMP_Type15 : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2152071168 Left_Rear_Seat_Actuator_LS: 8 XXX + SG_ LRStActPrty : 7|64@0+ (1,0) [0|0] "" XXX + SG_ LRSAP_HdrstUpDn : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_Massg : 7|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_HdrstUpDnFdRr : 11|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_HdrstFwdRrwd : 15|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_HdrstTltFwdRr : 19|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_HdrstWngsInOut : 23|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_LmbrUpDwn : 27|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_UprShldrFwdRr : 31|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_LmbrUpDnFdRr : 35|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_LmbrFwdRr : 39|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_CshBlstrInOut : 43|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_BkBlstrInOut : 47|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_CshLgthAdjFdRr : 51|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_BkCshBlstrInOut : 55|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_UnsdRsrvd : 59|4@0+ (1,0) [0|15] "" XXX + SG_ LRSAP_DispSz : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2153947136 Remote_Reflash_Stat_LS: 1 XXX + SG_ RmtRflshMdAct : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2152628224 OnBoard_Tester_Response_LS: 2 XXX + SG_ OBTCResp : 2|11@0+ (1,0) [0|0] "" XXX + SG_ OBTCR_Stat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ OBTCR_ReqstrID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ OBTCMstrStat : 5|3@0+ (1,0) [0|7] "" XXX + +BO_ 2152112128 Performanc_Mode_Vis_Scrn_Stat_LS: 5 XXX + SG_ PerfMdVislztnScrnStat : 0|33@0+ (1,0) [0|0] "" XXX + SG_ PMVSS_Snd : 0|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_Trans : 10|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_Eng : 13|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_Drvln : 17|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_Susp : 20|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_Strng : 23|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_PsngrSeat : 24|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_DrvrSeat : 27|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_AdptCrsCnt : 30|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_Disps : 34|3@0+ (1,0) [0|7] "" XXX + SG_ PMVSS_Exhst : 37|3@0+ (1,0) [0|7] "" XXX + SG_ PerfMdMainMenuType : 3|3@0+ (1,0) [0|7] "" XXX + +BO_ 2152775680 Front_360_Camera_On_LS: 3 XXX + SG_ DispFrt360CamOn : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RrPedDetCstStAvl : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RrPedDetCstStVal : 4|3@0+ (1,0) [0|7] "" XXX + SG_ RrPdDetHptcStVbRqSeqN : 6|2@0+ (1,0) [0|3] "" XXX + SG_ TrgdVidRecFetrPrsnt : 7|1@0+ (1,0) [0|1] "" XXX + SG_ RrPdDetHptcStVbRq : 13|6@0+ (1,0) [0|63] "Pulse" XXX + SG_ DispTrgdVidOn : 14|1@0+ (1,0) [0|1] "" XXX + SG_ a_360DegVidFetrPrsnt : 15|1@0+ (1,0) [0|1] "" XXX + SG_ DispSmrtTwVidOn : 16|1@0+ (1,0) [0|1] "" XXX + SG_ RrPedDetCstAvail : 23|7@0+ (1,0) [0|0] "" XXX + SG_ RPDCA_Resrv3Avail : 17|1@0+ (1,0) [0|1] "" XXX + SG_ RPDCA_Resrv2Avail : 18|1@0+ (1,0) [0|1] "" XXX + SG_ RPDCA_Resrv1Avail : 19|1@0+ (1,0) [0|1] "" XXX + SG_ RPDCA_AlrtBrkAvail : 20|1@0+ (1,0) [0|1] "" XXX + SG_ RPDCA_AlrtAvail : 21|1@0+ (1,0) [0|1] "" XXX + SG_ RPDCA_OnAvail : 22|1@0+ (1,0) [0|1] "" XXX + SG_ RPDCA_OfAvail : 23|1@0+ (1,0) [0|1] "" XXX + +BO_ 2153857024 Teen_Driver_Event_Report_2_LS: 8 XXX + SG_ TnDrvRptCrdAvlDspDat : 6|13@0+ (1,0) [0|0] "" XXX + SG_ TDRCADD_FCHdwyAlrt : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_ABSAtvEvt : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_StCtrlEvnts : 2|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_TrCtrlEvnts : 3|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_OvSpdEvnt : 4|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_DistDrvn : 5|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_MaxSpd : 6|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_LDWEvnts : 10|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_WOTEvnts : 11|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_DrwDrvAlrt : 12|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_FCMBrEvts : 13|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_RCMBrEvts : 14|1@0+ (1,0) [0|1] "" XXX + SG_ TDRCADD_FCImntAlrts : 15|1@0+ (1,0) [0|1] "" XXX + SG_ TeenDrvWOTEvntsRpt : 9|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TnDrvABSAtvEvntsRpt : 31|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TnDrvStblCtrlEvntsRpt : 37|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TnDrvDrowDrvAlrtsRpt : 43|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TnDrvTrCtrlEvntsRpt : 49|10@0+ (1,0) [0|1023] "counts" XXX + +BO_ 2153865216 Teen_Driver_Customization_Req_LS: 4 XXX + SG_ TeenDrvReq : 3|4@0+ (1,0) [0|15] "" XXX + SG_ TDOvSpdWrnCstStReq : 12|5@0+ (1,0) [0|0] "" XXX + SG_ TDOWCSR_DecSwAct : 8|1@0+ (1,0) [0|1] "" XXX + SG_ TDOWCSR_IncSwAct : 9|1@0+ (1,0) [0|1] "" XXX + SG_ TDOWCSR_StatReq : 12|3@0+ (1,0) [0|7] "" XXX + SG_ TnDrvSpdLmtCstStReq : 15|3@0+ (1,0) [0|7] "" XXX + SG_ TeenDrvPinCd : 23|16@0+ (1,0) [0|39321] "" XXX + +BO_ 2153840640 Teen_Driver_Event_Report_1_LS: 8 XXX + SG_ TDFwdClnHdwyAlrtsRpt : 5|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TnDrvDRLOffUnbIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvALCOffUnbIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ TDFwdClnImntAlrtsRpt : 11|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TDFwdClnMtgnBrEvRpt : 17|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TDRevClnMtgnBrEvRpt : 39|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TeenDrvMaxSpdRpt : 45|12@0+ (0.0625,0) [0|255.9375] "km/h" XXX + SG_ TeenDrvLDWEvntsRpt : 49|10@0+ (1,0) [0|1023] "counts" XXX + +BO_ 2153824256 Teen_Driver_Control_Info_LS: 8 XXX + SG_ TnDrvSpdLmtCstCrStVl : 2|11@0+ (1,0) [0|0] "" XXX + SG_ TDSLCCSV_SpLmtStat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ TDSLCCSV_SpLmDisVl : 15|8@0+ (2,0) [0|510] "km/h" XXX + SG_ TnDrvSpdLmtCstStAvl : 3|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvOvrSpdIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvGapAdjUnbIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ TeenDrvPINStrd : 6|1@0+ (1,0) [0|1] "" XXX + SG_ TeenDrvFtrAvl : 7|1@0+ (1,0) [0|1] "" XXX + SG_ TDOvSpdWrnCstCrStVl : 22|15@0+ (1,0) [0|0] "" XXX + SG_ TDOWCCSV_CrStVl : 19|12@0+ (0.0625,0) [0|255.9375] "km/h" XXX + SG_ TDOWCCSV_CrStat : 22|3@0+ (1,0) [0|7] "" XXX + SG_ TDOvSpdWrnCstStAvl : 23|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvOvSpdEvntsRpt : 33|10@0+ (1,0) [0|1023] "counts" XXX + SG_ TeenDrvRsp : 37|4@0+ (1,0) [0|15] "" XXX + SG_ TeenDrvAct : 38|1@0+ (1,0) [0|1] "" XXX + SG_ TeenDrvAccelLimIO : 39|1@0+ (1,0) [0|1] "" XXX + SG_ TeenDrvDistDrvnRpt : 55|16@0+ (1,0) [0|65535] "km" XXX + +BO_ 2155151360 Psngr_Seat_Massage_Priority_LS: 8 XXX + SG_ PsngrStMassgPrty : 7|64@0+ (1,0) [0|0] "" XXX + SG_ PSMP_Type2 : 3|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type1 : 7|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type4 : 11|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type3 : 15|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type6 : 19|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type5 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type8 : 27|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type7 : 31|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type10 : 35|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type9 : 39|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type12 : 43|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type11 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type14 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_Type13 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ PSMP_UnsdRsrvd : 56|1@0+ (1,0) [0|1] "" XXX + SG_ PSMP_MaxDispVal : 59|3@0+ (1,0) [0|7] "" XXX + SG_ PSMP_Type15 : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2155134976 Psngr_Seat_Control_Disp_Stat_LS: 6 XXX + SG_ PsngrStCtlDispStat : 3|44@0+ (1,0) [0|0] "" XXX + SG_ PSCDS_MassgTyp : 1|4@0+ (1,0) [0|15] "" XXX + SG_ PSCDS_Massg : 3|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_HdrstFwdRrwd : 8|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_HdrstUpDn : 10|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_MassgIntsty : 13|3@0+ (1,0) [0|7] "" XXX + SG_ PSCDS_HdrstTltFwdRr : 17|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_HdrstWngInOt : 19|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_HdrstUDnFdRr : 22|3@0+ (1,0) [0|7] "" XXX + SG_ PSCDS_LmbrUDnFdRr : 25|3@0+ (1,0) [0|7] "" XXX + SG_ PSCDS_LmbrFwdRr : 27|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_LmbrUpDwn : 29|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_UprShldrFdRr : 31|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_BkCshBlstInOt : 34|3@0+ (1,0) [0|7] "" XXX + SG_ PSCDS_CshBlstrInOut : 36|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_BkBlstrInOut : 38|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_UnsdRsrvd : 42|3@0+ (1,0) [0|7] "" XXX + SG_ PSCDS_DispReq : 43|1@0+ (1,0) [0|1] "" XXX + SG_ PSCDS_DispSz : 45|2@0+ (1,0) [0|3] "" XXX + SG_ PSCDS_CshLgAdjFdRr : 47|2@0+ (1,0) [0|3] "" XXX + SG_ PsngrSetRrwdMvmnt : 6|3@0+ (1,0) [0|7] "" XXX + +BO_ 2155118592 Psngr_Seat_Actuator_Priority_LS: 8 XXX + SG_ PsngrStActPrty : 7|64@0+ (1,0) [0|0] "" XXX + SG_ PSAP_HdrstUpDn : 3|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_Massg : 7|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_HdrstUpDnFdRr : 11|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_HdrstFwdRrwd : 15|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_HdrstTltFwdRr : 19|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_HdrstWngsInOut : 23|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_LmbrUpDwn : 27|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_UprShldrFwdRr : 31|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_LmbrUpDnFdRr : 35|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_LmbrFwdRr : 39|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_CshBlstrInOut : 43|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_BkBlstrInOut : 47|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_CshLgthAdjFdRr : 51|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_BkCshBlstrInOut : 55|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_UnsdRsrvd : 59|4@0+ (1,0) [0|15] "" XXX + SG_ PSAP_DispSz : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2155102208 Driver_Seat_Massage_Priority_LS: 8 XXX + SG_ DrvStMassgPrty : 7|64@0+ (1,0) [0|0] "" XXX + SG_ DSMP_Type2 : 3|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type1 : 7|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type4 : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type3 : 15|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type6 : 19|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type5 : 23|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type8 : 27|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type7 : 31|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type10 : 35|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type9 : 39|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type12 : 43|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type11 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type14 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_Type13 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ DSMP_UnsdRsrvd : 56|1@0+ (1,0) [0|1] "" XXX + SG_ DSMP_MaxDispVal : 59|3@0+ (1,0) [0|7] "" XXX + SG_ DSMP_Type15 : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2155085824 Driver_Seat_Control_Disp_Stat_LS: 8 XXX + SG_ DrvStCtlDispStat : 3|44@0+ (1,0) [0|0] "" XXX + SG_ DSCDS_MassgTyp : 1|4@0+ (1,0) [0|15] "" XXX + SG_ DSCDS_Massg : 3|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_HdrstFwdRrwd : 8|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_HdrstUpDn : 10|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_MassgIntsty : 13|3@0+ (1,0) [0|7] "" XXX + SG_ DSCDS_HdrstTltFwdRr : 17|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_HdrstWngInOt : 19|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_HdrstUDnFdRr : 22|3@0+ (1,0) [0|7] "" XXX + SG_ DSCDS_LmbrUDnFdRr : 25|3@0+ (1,0) [0|7] "" XXX + SG_ DSCDS_LmbrFwdRr : 27|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_LmbrUpDwn : 29|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_UprShldrFdRr : 31|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_BkCshBlstInOt : 34|3@0+ (1,0) [0|7] "" XXX + SG_ DSCDS_CshBlstrInOut : 36|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_BkBlstrInOut : 38|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_UnsdRsrvd : 42|3@0+ (1,0) [0|7] "" XXX + SG_ DSCDS_DispReq : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DSCDS_DispSz : 45|2@0+ (1,0) [0|3] "" XXX + SG_ DSCDS_CshLgAdjFdRr : 47|2@0+ (1,0) [0|3] "" XXX + SG_ CPMAPINFO4 : 5|1@0+ (1,0) [0|1] "" XXX + SG_ StrgColCommsFlt : 7|2@0+ (1,0) [0|3] "" XXX + SG_ StrgColInOutPos : 55|8@0+ (1,0) [0|255] "" XXX + SG_ StrgColUpDwnPos : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2155069440 Driver_Seat_Actuator_Priority_LS: 8 XXX + SG_ DrvStActPrty : 7|64@0+ (1,0) [0|0] "" XXX + SG_ DSAP_HdrstUpDn : 3|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_Massg : 7|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_HdrstUpDnFdRr : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_HdrstFwdRrwd : 15|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_HdrstTltFwdRr : 19|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_HdrstWngsInOut : 23|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_LmbrUpDwn : 27|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_UprShldrFwdRr : 31|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_LmbrUpDnFdRr : 35|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_LmbrFwdRr : 39|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_CshBlstrInOut : 43|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_BkBlstrInOut : 47|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_CshLgthAdjFdRr : 51|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_BkCshBlstrInOut : 55|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_UnsdRsrvd : 59|4@0+ (1,0) [0|15] "" XXX + SG_ DSAP_DispSz : 63|4@0+ (1,0) [0|15] "" XXX + +BO_ 2156937216 PassPhrase_Digits_17_to_24_LS: 8 XXX + SG_ WiFiPssPhrsDgts17to24 : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2156929024 PassPhrase_Digits_9_to_16_LS: 8 XXX + SG_ WiFiPssPhrsDgts9to16 : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2156920832 PassPhrase_Digits_1_to_8_LS: 8 XXX + SG_ WiFiPssPhrsDgts1to8 : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2156871680 SSID_Digits_17_to_24_LS: 8 XXX + SG_ WiFiSSIDDgts17to24 : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2156863488 SSID_Digits_9_to_16_LS: 8 XXX + SG_ WiFiSSIDDgts9to16 : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2156855296 SSID_Digits_1_to_8_LS: 8 XXX + SG_ WiFiSSIDDgts1to8 : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2152480768 Perfr_Data_Recorder_Lap_Info_LS: 6 XXX + SG_ PerfDatRecBstLpInfo : 2|19@0+ (1,0) [0|0] "" XXX + SG_ PDRBLI_BstLpTmMins : 2|6@0+ (1,0) [0|63] "min" XXX + SG_ PDRBLI_BstLpTmSecs : 12|6@0+ (1,0) [0|63] "sec" XXX + SG_ PDRBLI_BstLpTm100s : 22|7@0+ (0.01,0) [0|1.27] "sec" XXX + SG_ PerfDatRecLstLpInfo : 26|19@0+ (1,0) [0|0] "" XXX + SG_ PDRLLI_LstLpTmMins : 26|6@0+ (1,0) [0|63] "min" XXX + SG_ PDRLLI_LstLpTmSecs : 36|6@0+ (1,0) [0|63] "sec" XXX + SG_ PDRLLI_LstLpTm100s : 46|7@0+ (0.01,0) [0|1.27] "sec" XXX + +BO_ 2152497152 Perf_Data_Recroder_RT_Info_LS: 4 XXX + SG_ PerfDatRecRltmInfo : 1|26@0+ (1,0) [0|0] "" XXX + SG_ PDRRI_CrLpTmMins : 1|6@0+ (1,0) [0|63] "min" XXX + SG_ PDRRI_CrLpTmSecs : 11|6@0+ (1,0) [0|63] "" XXX + SG_ PDRRI_LpDiffTmSecs : 17|6@0+ (1,0) [0|63] "sec" XXX + SG_ PDRRI_CrLpTm10sSec : 21|4@0+ (0.1,0) [0|1.5] "sec" XXX + SG_ PDRRI_LpDiffTm10s : 27|4@0+ (0.1,0) [0|1.5] "sec" XXX + +BO_ 2153791488 ARB_State_LS: 1 XXX + SG_ ArtcldRngBrdSt : 2|3@0+ (1,0) [0|7] "" XXX + +BO_ 2149883904 BluetoothTetheringPairingRsp_LS: 7 XXX + SG_ BTTethrngPrngRsp : 4|53@0+ (1,0) [0|0] "" XXX + SG_ BTPR_RspInfoAvail : 0|1@0+ (1,0) [0|1] "" XXX + SG_ BTPR_RspStat : 4|4@0+ (1,0) [0|15] "" XXX + SG_ BTPR_RspVal : 15|48@0+ (1,0) [0|281474976710655] "" XXX + +BO_ 2150252544 HMI_EngyConsmpHistGrph_LS: 8 XXX + SG_ EngyConsmpHistGrph : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ECHG_EngyCnsmdAvg : 4|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_MeasUnit : 7|3@0+ (1,0) [0|7] "" XXX + SG_ ECHG_Column02 : 10|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column01 : 15|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column04 : 16|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column03 : 21|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column05 : 27|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column07 : 33|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column06 : 38|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column08 : 44|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column10 : 50|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_Column09 : 55|5@0+ (1,0) [0|31] "" XXX + SG_ ECHG_YAxisMaxVal : 58|3@0+ (1,0) [0|7] "" XXX + SG_ ECHG_XAxisTkMrkIntvl : 61|3@0+ (1,0) [0|7] "" XXX + +BO_ 2150391808 HMI_Hourmeter_Data_LS: 6 XXX + SG_ EngIdlAtvTm : 7|24@0+ (1,0) [0|16777215] "min" XXX + SG_ EngRunAtvTm : 31|24@0+ (1,0) [0|16777215] "min" XXX + +BO_ 2155913216 Diesel_Information_2_LS: 7 XXX + SG_ DslExhFldRmngDstHRsGroup : 7|16@0+ (1,0) [0|0] "" XXX + SG_ DslExhFldRmngDstHRs : 6|15@0+ (2,0) [0|65534] "km" XXX + SG_ DslExhFldRmngDstHRsV : 7|1@0+ (1,0) [0|1] "" XXX + SG_ DslExhFluidLvlPrcntGroup : 16|9@0+ (1,0) [0|0] "" XXX + SG_ DslExhFluidLvlPrcntV : 16|1@0+ (1,0) [0|1] "" XXX + SG_ DslExhFluidLvlPrcnt : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ DslEmnsOBDMrkt : 18|2@0+ (1,0) [0|3] "" XXX + SG_ PedFrndlyAlrtCsCrStVal : 21|3@0+ (1,0) [0|7] "" XXX + SG_ PedFrndlyAlrtCsSetAvl : 22|1@0+ (1,0) [0|1] "" XXX + SG_ PedFrndlyAlrtStat : 39|24@0+ (1,0) [0|0] "" XXX + SG_ PFAS_PFACrsOvrSpd : 34|8@0+ (1,0) [0|255] "km/h" XXX + SG_ PFAS_PFARevSnd : 36|2@0+ (1,0) [0|3] "" XXX + SG_ PFAS_PFAFwdSnd : 38|2@0+ (1,0) [0|3] "" XXX + SG_ PFAS_PFASndGenEn : 39|1@0+ (1,0) [0|1] "" XXX + SG_ PFAS_PFASndVolCtrl : 42|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ PFAS_SrvPedAlrtIO : 48|1@0+ (1,0) [0|1] "" XXX + SG_ PFAS_PFASysStat : 50|2@0+ (1,0) [0|3] "" XXX + +BO_ 2034 CCP_Data_Transmission_Object_LS: 8 XXX + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2032 CCP_Command_Receive_Object_LS: 8 XXX + SG_ DgnInf : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2152095744 HSGMLAN_Customization_Setings_LS: 5 XXX + SG_ DrvlnPerfMdCustAvl : 5|6@0+ (1,0) [0|0] "" XXX + SG_ DPMCA_DrvlPrfMd6Avl : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DrvlPrfMd5Avl : 1|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DrvlPrfMd4Avl : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DrvlPrfMd3Avl : 3|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DrvlPrfMd2Avl : 4|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DrvlPrfMd1Avl : 5|1@0+ (1,0) [0|1] "" XXX + SG_ DispPerfCustMdAvl : 13|6@0+ (1,0) [0|0] "" XXX + SG_ DPMCA_DispPrfMd6Avl : 8|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DispPrfMd5Avl : 9|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DispPrfMd4Avl : 10|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DispPrfMd3Avl : 11|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DispPrfMd2Avl : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DPMCA_DispPrfMd1Avl : 13|1@0+ (1,0) [0|1] "" XXX + SG_ SndPerfMdCustAvl : 21|6@0+ (1,0) [0|0] "" XXX + SG_ SPMCA_SndPrfMd6Avl : 16|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SndPrfMd5Avl : 17|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SndPrfMd4Avl : 18|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SndPrfMd3Avl : 19|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SndPrfMd2Avl : 20|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SndPrfMd1Avl : 21|1@0+ (1,0) [0|1] "" XXX + SG_ StrPerfMdCustAvl : 29|6@0+ (1,0) [0|0] "" XXX + SG_ SPMCA_StrPrfMd6Avl : 24|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_StrPrfMd5Avl : 25|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_StrPrfMd4Avl : 26|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_StrPrfMd3Avl : 27|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_StrPrfMd2Avl : 28|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_StrPrfMd1Avl : 29|1@0+ (1,0) [0|1] "" XXX + SG_ SusPerfMdCustAvl : 37|6@0+ (1,0) [0|0] "" XXX + SG_ SPMCA_SusPrfMd6Avl : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SusPrfMd5Avl : 33|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SusPrfMd4Avl : 34|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SusPrfMd3Avl : 35|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SusPrfMd2Avl : 36|1@0+ (1,0) [0|1] "" XXX + SG_ SPMCA_SusPrfMd1Avl : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 2156945408 SSID_AMM_1_LS: 8 XXX + SG_ WiFiSSIDDgts1to8_Mp : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2152611840 OnBoard_Tester_Request_LS: 2 XXX + SG_ OBTCReq : 4|5@0+ (1,0) [0|0] "" XXX + SG_ OBTCR_Prty : 3|4@0+ (1,0) [0|15] "" XXX + SG_ OBTCR_Actv : 4|1@0+ (1,0) [0|1] "" XXX + SG_ OBTCReqstrStat : 7|3@0+ (1,0) [0|7] "" XXX + SG_ OBTCReqstrID : 15|8@0+ (1,0) [0|255] "" XXX + +BO_ 2153308160 Hyb_Redundant_Batt_Data2_LS: 4 XXX + SG_ RdHVltBatPckCrntGroup : 6|15@0+ (1,0) [0|0] "" XXX + SG_ RdHVltBatPckCrnt : 4|13@0- (0.15,0) [-614.4|614.25] "A" XXX + SG_ RdHVltBatPckCrntV : 5|1@0+ (1,0) [0|1] "" XXX + SG_ RdHVltBatPckCrntM : 6|1@0+ (1,0) [0|1] "" XXX + SG_ RdHVltBatPckVltGroup : 21|14@0+ (1,0) [0|0] "" XXX + SG_ RdHVltBatPckVlt : 19|12@0+ (0.125,0) [0|511.875] "V" XXX + SG_ RdHVltBatPckVltV : 20|1@0+ (1,0) [0|1] "" XXX + SG_ RdHVltBatPckVltM : 21|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155970560 HVAC_PowerManager_Status_LS: 1 XXX + SG_ ClmCntLdShdLvlRq : 3|4@0+ (1,0) [0|15] "" XXX + SG_ ClmCntBatSaverIO : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151178240 Lighting_Customization_Rqst_1_LS: 4 XXX + SG_ LtRtHnTrGPSCstStRq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ LtRtHnTrCstStReq : 5|3@0+ (1,0) [0|7] "" XXX + SG_ AutHgBmAsSnCsStRq : 10|3@0+ (1,0) [0|7] "" XXX + SG_ AutHgBmAstCstStRq : 13|3@0+ (1,0) [0|7] "" XXX + SG_ AdpHgBmAsSnCsStRq : 18|3@0+ (1,0) [0|7] "" XXX + SG_ AdpHgBmAstCstStRq : 21|3@0+ (1,0) [0|7] "" XXX + SG_ AFLGPSCstStReq : 26|3@0+ (1,0) [0|7] "" XXX + SG_ AFLCstStReq : 29|3@0+ (1,0) [0|7] "" XXX + +BO_ 2154790912 Lighting_Customization_Info_2_LS: 2 XXX + SG_ AutHgBmAsCsCrStVal : 2|3@0+ (1,0) [0|7] "" XXX + SG_ AutHgBmAsSnCsCrStVa : 5|3@0+ (1,0) [0|7] "" XXX + SG_ AutHgBmAsCsStAvl : 6|1@0+ (1,0) [0|1] "" XXX + SG_ AutHgBmAsSnCsStAvl : 7|1@0+ (1,0) [0|1] "" XXX + SG_ AdpHgBmAsCsCrStVal : 10|3@0+ (1,0) [0|7] "" XXX + SG_ AdpHgBmAsSnCsCrStVal : 13|3@0+ (1,0) [0|7] "" XXX + SG_ AdpHgBmAsCsStAvl : 14|1@0+ (1,0) [0|1] "" XXX + SG_ AdpHgBmAsSnCsStAvl : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151292928 V2V_Customization_Menu_LS: 5 XXX + SG_ TrfRdsdInfCsStAvail : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CntdVehBrkAltCsStAvl : 1|1@0+ (1,0) [0|1] "" XXX + SG_ IntrStopAlrtCsSetAvl : 2|1@0+ (1,0) [0|1] "" XXX + SG_ IntrStAlrtCsCrSetVal : 5|3@0+ (1,0) [0|7] "" XXX + SG_ TrfRdsdInfCsCrStVal : 10|3@0+ (1,0) [0|7] "" XXX + SG_ CntdVehBrAltCsCrStVal : 13|3@0+ (1,0) [0|7] "" XXX + SG_ IntrStAlrtCsAvail : 22|7@0+ (1,0) [0|0] "" XXX + SG_ ISACA_Resrv4Avail : 16|1@0+ (1,0) [0|1] "" XXX + SG_ ISACA_Resrv3Avail : 17|1@0+ (1,0) [0|1] "" XXX + SG_ ISACA_Resrv2Avail : 18|1@0+ (1,0) [0|1] "" XXX + SG_ ISACA_Resrv1Avail : 19|1@0+ (1,0) [0|1] "" XXX + SG_ ISACA_AlrtBrkAvail : 20|1@0+ (1,0) [0|1] "" XXX + SG_ ISACA_AlrtAvail : 21|1@0+ (1,0) [0|1] "" XXX + SG_ ISACA_OfAvail : 22|1@0+ (1,0) [0|1] "" XXX + SG_ CntdVehBrkAlrtCsAvail : 30|7@0+ (1,0) [0|0] "" XXX + SG_ CVBACA_Resrv5Avail : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CVBACA_Resrv4Avail : 25|1@0+ (1,0) [0|1] "" XXX + SG_ CVBACA_Resrv3Avail : 26|1@0+ (1,0) [0|1] "" XXX + SG_ CVBACA_Resrv2Avail : 27|1@0+ (1,0) [0|1] "" XXX + SG_ CVBACA_Resrv1Avail : 28|1@0+ (1,0) [0|1] "" XXX + SG_ CVBACA_OnAvail : 29|1@0+ (1,0) [0|1] "" XXX + SG_ CVBACA_OfAvail : 30|1@0+ (1,0) [0|1] "" XXX + SG_ TrfRdsdInfCsAvail : 38|7@0+ (1,0) [0|0] "" XXX + SG_ TRICA_Resrv5Avail : 32|1@0+ (1,0) [0|1] "" XXX + SG_ TRICA_Resrv4Avail : 33|1@0+ (1,0) [0|1] "" XXX + SG_ TRICA_Resrv3Avail : 34|1@0+ (1,0) [0|1] "" XXX + SG_ TRICA_Resrv2Avail : 35|1@0+ (1,0) [0|1] "" XXX + SG_ TRICA_Resrv1Avail : 36|1@0+ (1,0) [0|1] "" XXX + SG_ TRICA_OnAvail : 37|1@0+ (1,0) [0|1] "" XXX + SG_ TRICA_OfAvail : 38|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151464960 V2V_Warnings_LS: 5 XXX + SG_ V2VWrngIndReq : 4|5@0+ (1,0) [0|31] "" XXX + SG_ V2VWrngDirctn : 7|3@0+ (1,0) [0|7] "" XXX + SG_ V2VWrngDistRemng : 9|10@0+ (1,0) [0|1023] "" XXX + SG_ V2VTrfLghtInfo : 28|13@0+ (1,0) [0|0] "" XXX + SG_ V2VTLI_TrfLghtTmPhsSw : 28|6@0+ (1,0) [0|63] "" XXX + SG_ V2VTLI_TrfLghtMntngDirctn : 32|1@0+ (1,0) [0|1] "" XXX + SG_ V2VTLI_TrfLghtValDirctn : 34|2@0+ (1,0) [0|3] "" XXX + SG_ V2VTLI_TrfLghtPhsArivl : 36|2@0+ (1,0) [0|3] "" XXX + SG_ V2VTLI_TrfLghtActlPhs : 38|2@0+ (1,0) [0|3] "" XXX + SG_ V2VSrvIndReq : 30|2@0+ (1,0) [0|3] "" XXX + +BO_ 2151448576 V2V_Seat_Vib_Request_LS: 3 XXX + SG_ V2VSysHptcStVibReq : 5|6@0+ (1,0) [0|63] "" XXX + SG_ V2VSysHptStVibRqSN : 7|2@0+ (1,0) [0|3] "" XXX + SG_ V2VSyLftHptStVbRq : 13|6@0+ (1,0) [0|63] "" XXX + SG_ V2VSyLftHptStVbRqSN : 15|2@0+ (1,0) [0|3] "" XXX + SG_ V2VSyRghtHptStVbRq : 21|6@0+ (1,0) [0|63] "" XXX + SG_ V2VSyRghtHptStVbRqSN : 23|2@0+ (1,0) [0|3] "" XXX + +BO_ 2153930752 Lane_Centering_Convenience_LS: 3 XXX + SG_ LCWrnIndReq : 4|5@0+ (1,0) [0|31] "" XXX + SG_ LCCDrvrAwrnsIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ LnCntrVhlStpd : 6|1@0+ (1,0) [0|1] "" XXX + SG_ LnCntrNonRspDrvrCnd : 7|1@0+ (1,0) [0|1] "" XXX + SG_ LCConvMsgIndreq : 12|5@0+ (1,0) [0|31] "" XXX + SG_ LCCIndReq : 15|3@0+ (1,0) [0|7] "" XXX + SG_ LnCntrEsclnStat : 17|2@0+ (1,0) [0|3] "" XXX + SG_ LnCntrSpchPrmtReq : 19|2@0+ (1,0) [0|3] "" XXX + SG_ LnCntrngCtlIcnLoctn : 23|4@0- (1,0) [-8|7] "" XXX + +BO_ 2153889792 Lane_Centering_Arrow_LS: 5 XXX + SG_ LCArrwBlk1Act : 0|1@0+ (1,0) [0|1] "" XXX + SG_ LCArrwBlk2Act : 1|1@0+ (1,0) [0|1] "" XXX + SG_ LCArrwBlk3Act : 2|1@0+ (1,0) [0|1] "" XXX + SG_ LCArrwBlk4Act : 3|1@0+ (1,0) [0|1] "" XXX + SG_ LCArrwBlk5Act : 4|1@0+ (1,0) [0|1] "" XXX + SG_ LCArrwBlk2Offst : 15|8@0- (1,0) [-128|127] "" XXX + SG_ LCArrwBlk3Offst : 23|8@0- (1,0) [-128|127] "" XXX + SG_ LCArrwBlk4Offst : 31|8@0- (1,0) [-128|127] "" XXX + SG_ LCArrwBlk5Offst : 39|8@0- (1,0) [-128|127] "" XXX + +BO_ 2153914368 Energy_Usage_LS: 7 XXX + SG_ EngyUsgScrScal : 7|56@0+ (1,0) [0|0] "" XXX + SG_ EUSS_OTEgUgScrMxScVal : 0|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUSS_OTEgUgScrMnScVal : 7|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUSS_ITEgUgScrMnScVal : 9|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUSS_ITEgUgScrMxScVal : 18|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUSS_TcEgUgScrMnScVal : 27|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUSS_TcEgUgScrMxScVal : 36|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUSS_TrEgUgScrMnScVal : 45|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUSS_TrEgUgScrMxScVal : 54|7@0- (0.1,0) [-5|5] "" XXX + +BO_ 2151882752 PTO_Customization_Request_LS: 3 XXX + SG_ PTOTpStpSpdCsStReq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ PTOEngRnTmrCsStRq : 11|4@0+ (1,0) [0|15] "" XXX + SG_ PTOStdbySpdCsStReq : 14|3@0+ (1,0) [0|7] "" XXX + SG_ PTOSet1SpdCsStReq : 19|4@0+ (1,0) [0|15] "" XXX + SG_ PTOSet2SpdCsStReq : 23|4@0+ (1,0) [0|15] "" XXX + +BO_ 2151899136 PTO_Status_LS: 5 XXX + SG_ PTORelBrkPedIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ PTORelAccPedIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PTORedEngSpdIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PTOPrsRelCltPedIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PTOPrsRelBrkPedIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PTOEngmntStatInd : 6|2@0+ (1,0) [0|3] "" XXX + SG_ PTODisengCrsCntlIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ PTOSet1SpdCsStAvl : 8|1@0+ (1,0) [0|1] "" XXX + SG_ PTOSet2SpdCsStAvl : 9|1@0+ (1,0) [0|1] "" XXX + SG_ PTOTpStpSpdCsStAvl : 10|1@0+ (1,0) [0|1] "" XXX + SG_ PTOEngRnTmrCsStAvl : 11|1@0+ (1,0) [0|1] "" XXX + SG_ PTOStdbySpdCsStAvl : 12|1@0+ (1,0) [0|1] "" XXX + SG_ PTOTransInGearIO : 13|1@0+ (1,0) [0|1] "" XXX + SG_ PTOSetPrkBrkIO : 14|1@0+ (1,0) [0|1] "" XXX + SG_ PTORelCltPedIO : 15|1@0+ (1,0) [0|1] "" XXX + SG_ PTOStdbSpdCsCrStVal : 18|3@0+ (1,0) [0|7] "" XXX + SG_ PTOGroup : 20|2@0+ (1,0) [0|0] "" XXX + SG_ PTOVDA : 19|1@0+ (1,0) [0|1] "" XXX + SG_ PTOVDM : 20|1@0+ (1,0) [0|1] "" XXX + SG_ PTOManTransInGrIO : 21|1@0+ (1,0) [0|1] "" XXX + SG_ PTOAccelUpnBrkRelIO : 22|1@0+ (1,0) [0|1] "" XXX + SG_ PTOEngUpnBrkRelIO : 23|1@0+ (1,0) [0|1] "" XXX + SG_ PTOTpStSpdCsCrStVal : 26|3@0+ (1,0) [0|7] "" XXX + SG_ PTOEnRnTmCsCrStVal : 30|4@0+ (1,0) [0|15] "" XXX + SG_ PTOServIndOn : 31|1@0+ (1,0) [0|1] "" XXX + SG_ PTOSet1SpdCsCrStVal : 35|4@0+ (1,0) [0|15] "" XXX + SG_ PTOSet2SpdCsCrStVal : 39|4@0+ (1,0) [0|15] "" XXX + +BO_ 2150580224 HMI_UtlChrgIntrfr_Indication_LS: 5 XXX + SG_ CstmrNonUsblSOCGroup : 1|10@0+ (1,0) [0|0] "" XXX + SG_ CstmrNonUsblSOCV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ CstmrNonUsblSOC : 15|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ CstNonUsbSOCDspLvl : 23|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ PrpDspTtlPwrLvlPct : 24|9@0- (0.392157,0) [-100.392192|100.000035] "%" XXX + +BO_ 2151735296 Rear_Cross_Traffic_Alert_Ind_LS: 1 XXX + SG_ RrCrsTrfcAlrtOffIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ LnChgAlrtOffIndOn : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RtRrCrsTrfcAlrtEnbld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RtSBZAlrtEnbld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ RtLnChgAlrtEnbld : 4|1@0+ (1,0) [0|1] "" XXX + SG_ RtSdDetSysTmpDsbld : 5|1@0+ (1,0) [0|1] "" XXX + SG_ RtSdDetSysServDsbld : 6|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151792640 Rear_Cross_Traffic_Alert_Rght_LS: 5 XXX + SG_ RrCTfcRHptcStRqSqN : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RrCTfcRHptcStReq : 7|6@0+ (1,0) [0|63] "" XXX + SG_ RrCrsTrfAltRgtIndCtrl : 34|3@0+ (1,0) [0|0] "" XXX + SG_ RCTARIC_IndReq : 33|2@0+ (1,0) [0|3] "" XXX + SG_ RCTARIC_Indctr1Act : 34|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149826560 FCA_VisionBased_Info_2_LS: 4 XXX + SG_ FCAGpStng : 2|3@0+ (1,0) [0|7] "" XXX + SG_ FCAHdwyStngIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ FCACrusCtrlCnclReqd : 4|1@0+ (1,0) [0|1] "" XXX + SG_ FCABrkPrflReq : 5|1@0+ (1,0) [0|1] "" XXX + SG_ FwdClnAlrtOffIO11E : 6|1@0+ (1,0) [0|1] "" XXX + SG_ FwdClnAlrtPr11E : 7|1@0+ (1,0) [0|1] "" XXX + SG_ SpdLmtVsnFsdSpdGroup : 15|15@0+ (1,0) [0|0] "" XXX + SG_ SpdLmtVsnFsdSpd : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SpdLmtVsnFsdSpdM : 17|1@0+ (1,0) [0|1] "" XXX + SG_ FwdObjAlrtInd11E : 16|9@0+ (1,0) [0|0] "" XXX + SG_ FOAI_AlrtChmIhbRq11E : 16|1@0+ (1,0) [0|1] "" XXX + SG_ FOAI_VehAhdIndRq11E : 27|4@0+ (1,0) [0|15] "" XXX + SG_ FOAI_AlrtWrnIndRq11E : 31|4@0+ (1,0) [0|15] "" XXX + SG_ SpdLmtVnFsSpdNwDet : 18|1@0+ (1,0) [0|1] "" XXX + SG_ SpdLmtVsnFsdSpdUnt : 19|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149957632 Park_Assist_ESSprocess_Info_LS: 1 XXX + SG_ ClsnMtgtnInhbtd : 0|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstInhbtReq : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstRrObjSnsngRqAct : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstOprtrDsrdStat : 4|2@0+ (1,0) [0|3] "" XXX + +BO_ 2149941248 Park_Assist_ESSbased_Info_LS: 5 XXX + SG_ PrkAstRrExtdDstUnfltd : 3|12@0+ (0.01,0) [0|40.95] "m" XXX + SG_ PrkAstRrSysStatUnfltd : 5|2@0+ (1,0) [0|3] "" XXX + SG_ PrkAstFntnSnsDstrbdIO : 16|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstFntnSnrsBlkd : 17|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstFntnFld : 18|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstFntnDsbldIO : 19|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstFntnClnPrkAstIO : 20|1@0+ (1,0) [0|1] "" XXX + SG_ ClsnMtgtnInhbtReqtd : 21|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstRrObjSnsngAct : 22|1@0+ (1,0) [0|1] "" XXX + SG_ PARrRgn3ObjStatUnfltd : 27|4@0+ (1,0) [0|15] "" XXX + SG_ PARrRgn4ObjStatUnfltd : 31|4@0+ (1,0) [0|15] "" XXX + SG_ PARrRgn1ObjStatUnfltd : 35|4@0+ (1,0) [0|15] "" XXX + SG_ PARrRgn2ObjStatUnfltd : 39|4@0+ (1,0) [0|15] "" XXX + +BO_ 2156314624 High_Volt_Time_Based_Chrg_LS: 8 XXX + SG_ TODCNxtPlnndDprtrTm : 5|14@0+ (1,0) [0|0] "" XXX + SG_ TODCNPDT_Hr : 2|5@0+ (1,0) [0|31] "Hour" XXX + SG_ TODCNPDT_DyOfWk : 5|3@0+ (1,0) [0|7] "" XXX + SG_ TODCNPDT_Min : 13|6@0+ (1,0) [0|63] "Minute" XXX + SG_ OffBrdCSFltDtctd : 6|1@0+ (1,0) [0|1] "" XXX + SG_ OBVhCsACChgRqBnVs : 7|1@0+ (1,0) [0|1] "" XXX + SG_ HVChgSyChgLvlPrfDt : 16|25@0+ (1,0) [0|0] "" XXX + SG_ HVCSCLPD_UsrIntTyp : 16|2@0+ (1,0) [0|3] "" XXX + SG_ HVCSCLPD_NrmChrgC : 27|5@0+ (1,0) [0|31] "A" XXX + SG_ HVCSCLPD_ChgLvlPfS : 30|3@0+ (1,0) [0|7] "" XXX + SG_ HVCSCLPD_RdCrntLv2 : 33|5@0+ (1,0) [0|31] "A" XXX + SG_ HVCSCLPD_RdCrntLv1 : 38|5@0+ (1,0) [0|31] "A" XXX + SG_ HVCSCLPD_RdCrntLv3 : 44|5@0+ (1,0) [0|31] "A" XXX + SG_ HVChrgAbrtRsn : 19|3@0+ (1,0) [0|7] "" XXX + SG_ TODCOpMd : 22|3@0+ (1,0) [0|7] "" XXX + SG_ HVChrgSysSplyFltIO : 23|1@0+ (1,0) [0|1] "" XXX + SG_ TODCDspMnPgTmpOr : 52|5@0+ (1,0) [0|0] "" XXX + SG_ TODCDMPTO_TpOvR : 51|4@0+ (1,0) [0|15] "" XXX + SG_ TODCDMPTO_CmPgR : 52|1@0+ (1,0) [0|1] "" XXX + SG_ HVChrgSysStNot : 55|3@0+ (1,0) [0|7] "" XXX + SG_ HVBatBlkSOC : 63|8@0+ (0.392157,0) [0|100.000035] "%" XXX + +BO_ 2150449152 Engine_Information_5_LS: 4 XXX + SG_ SrvcFlSysPrkInOpnArIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvTrCtrlOffUnbIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvStblCtrlOffUnbIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ InActFuelMdFuelLvlIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ FuelSysNEmsRltMalfAct : 4|1@0+ (1,0) [0|1] "" XXX + SG_ EngInltSpcfcHmdtyGroup : 7|16@0+ (1,0) [0|0] "" XXX + SG_ EngInltSpcfcHmdtyM : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EngInltSpcfcHmdtyV : 7|1@0+ (1,0) [0|1] "" XXX + SG_ EngInltSpcfcHmdty : 15|8@0+ (0.0196078,0) [0|4.999989] "% water" XXX + SG_ AutoStpInhbtRsnInd : 23|8@0+ (1,0) [0|0] "" XXX + SG_ ASIRI_Indication08 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ ASIRI_Indication07 : 17|1@0+ (1,0) [0|1] "" XXX + SG_ ASIRI_Indication06 : 18|1@0+ (1,0) [0|1] "" XXX + SG_ ASIRI_Indication05 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ ASIRI_Indication04 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ ASIRI_Indication03 : 21|1@0+ (1,0) [0|1] "" XXX + SG_ ASIRI_Indication02 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ ASIRI_Indication01 : 23|1@0+ (1,0) [0|1] "" XXX + SG_ SpdLmtrSttngTypAct : 25|2@0+ (1,0) [0|3] "" XXX + SG_ ManTransIndReq : 28|3@0+ (1,0) [0|7] "" XXX + SG_ ESPDrvrExtIO : 29|1@0+ (1,0) [0|1] "" XXX + SG_ ESPDrvrDrStIndtrmntIO : 30|1@0+ (1,0) [0|1] "" XXX + SG_ ESPAutoPrkIO : 31|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149810176 FCA_VisionBased_Info_1_LS: 1 XXX + SG_ FCAHptcStVbnRqSeqN : 1|2@0+ (1,0) [0|3] "" XXX + SG_ FCAHptcStVbnReq : 7|6@0+ (1,0) [0|63] "" XXX + +BO_ 2149793792 FCA_VisionBased_Info_LS: 6 XXX + SG_ FwdClnAlrtCustCrntSetngVal : 3|3@0+ (1,0) [0|7] "" XXX + SG_ FCACustStngAvlbl : 6|1@0+ (1,0) [0|1] "" XXX + SG_ VhlAhdDstIndReq : 26|19@0+ (1,0) [0|0] "" XXX + SG_ VADIR_IndLvl : 26|4@0+ (1,0) [0|15] "" XXX + SG_ VADIR_FlwTme : 38|7@0+ (0.1,0) [0|12.7] "s" XXX + SG_ VADIR_FlwDst : 47|8@0+ (1,0) [0|255] "m" XXX + +BO_ 2150080512 Aux_Coolant_Heater_Status_LS: 8 XXX + SG_ EngAstHtDfrdHtMdAct : 0|1@0+ (1,0) [0|1] "" XXX + SG_ LBCCsCrStVal : 2|2@0+ (1,0) [0|3] "" XXX + SG_ AuxClntHtrVlvStat : 5|3@0+ (1,0) [0|7] "" XXX + SG_ LBCChrgLvlPrfExpIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ LBCCsStAvl : 7|1@0+ (1,0) [0|1] "" XXX + SG_ LBCCstmrDaRstResp : 12|5@0+ (1,0) [0|0] "" XXX + SG_ LBCCDRR_PosNumbr : 10|3@0+ (1,0) [0|7] "" XXX + SG_ LBCCDRR_ClrStrdPosResp : 12|2@0+ (1,0) [0|3] "" XXX + SG_ LBCPosStgStat : 20|5@0+ (1,0) [0|0] "" XXX + SG_ LBCPSS_PosUpdtLct : 18|3@0+ (1,0) [0|7] "" XXX + SG_ LBCPSS_PosUpdtStat : 20|2@0+ (1,0) [0|3] "" XXX + SG_ LBCVehLctStat : 27|4@0+ (1,0) [0|0] "" XXX + SG_ LBCVLS_VehGPSLct : 26|3@0+ (1,0) [0|7] "" XXX + SG_ LBCVLS_VehGPSLctV : 27|1@0+ (1,0) [0|1] "" XXX + SG_ LBCCstmrFdbk : 31|4@0+ (1,0) [0|0] "" XXX + SG_ LBCCF_Lct4PosStrdIO : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LBCCF_Lct3PosStrdIO : 29|1@0+ (1,0) [0|1] "" XXX + SG_ LBCCF_Lct2PosStrdIO : 30|1@0+ (1,0) [0|1] "" XXX + SG_ LBCCF_Lct1PosStrdIO : 31|1@0+ (1,0) [0|1] "" XXX + SG_ ChrgCyclElecEngyEcnEq : 35|12@0+ (0.1,0) [0|409.5] "km/l" XXX + SG_ ChrgCyclOvrlEngyEcnEq : 51|12@0+ (0.1,0) [0|409.5] "km/l" XXX + +BO_ 2153873408 Heated_Steering_Whl_Rqsted_LS: 1 XXX + SG_ MnlHtdStWhlRqstd : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2152128512 Performance_Mode_Cust_Setings_LS: 4 XXX + SG_ ACCPerfMdCustAvl : 5|6@0+ (1,0) [0|0] "" XXX + SG_ ACCPMCA_ACCPrfMd6Avl : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ACCPMCA_ACCPrfMd5Avl : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ACCPMCA_ACCPrfMd4Avl : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ACCPMCA_ACCPrfMd3Avl : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ACCPMCA_ACCPrfMd2Avl : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ACCPMCA_ACCPrfMd1Avl : 5|1@0+ (1,0) [0|1] "" XXX + SG_ DrvrStPerfMdCustAvl : 13|6@0+ (1,0) [0|0] "" XXX + SG_ DSPMCA_DrvrStPrfMd6Avl : 8|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvrStPrfMd5Avl : 9|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvrStPrfMd4Avl : 10|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvrStPrfMd3Avl : 11|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvrStPrfMd2Avl : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvrStPrfMd1Avl : 13|1@0+ (1,0) [0|1] "" XXX + SG_ PsngStPerfMdCustAvl : 21|6@0+ (1,0) [0|0] "" XXX + SG_ PSPMCA_PsngStPrfMd6Avl : 16|1@0+ (1,0) [0|1] "" XXX + SG_ PSPMCA_PsngStPrfMd5Avl : 17|1@0+ (1,0) [0|1] "" XXX + SG_ PSPMCA_PsngStPrfMd4Avl : 18|1@0+ (1,0) [0|1] "" XXX + SG_ PSPMCA_PsngStPrfMd3Avl : 19|1@0+ (1,0) [0|1] "" XXX + SG_ PSPMCA_PsngStPrfMd2Avl : 20|1@0+ (1,0) [0|1] "" XXX + SG_ PSPMCA_PsngStPrfMd1Avl : 21|1@0+ (1,0) [0|1] "" XXX + SG_ DrvStyPerfMdCustAvl : 30|7@0+ (1,0) [0|0] "" XXX + SG_ DSPMCA_DrvStyPrfMd7Avl : 24|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvStyPrfMd6Avl : 25|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvStyPrfMd5Avl : 26|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvStyPrfMd4Avl : 27|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvStyPrfMd3Avl : 28|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvStyPrfMd2Avl : 29|1@0+ (1,0) [0|1] "" XXX + SG_ DSPMCA_DrvStyPrfMd1Avl : 30|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151997440 Driver_Drowsiness_Dtctn_Stat_LS: 5 XXX + SG_ DrvDrowSysIndRq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ DrvDrwDetCsCrStVal : 5|3@0+ (1,0) [0|7] "" XXX + SG_ DrvDrowDetCstStAvl : 6|1@0+ (1,0) [0|1] "" XXX + SG_ DrvDrsnHptcStRqSeqN : 9|2@0+ (1,0) [0|3] "" XXX + SG_ DrDrwSysHptcStVbnRq : 15|6@0+ (1,0) [0|63] "" XXX + +BO_ 2156331008 High_Voltage_EnergyMgmt_Ctrl_LS: 7 XXX + SG_ LwRngLVLdShdRq : 1|2@0+ (1,0) [0|3] "" XXX + SG_ HVDpltnMdMxCnfdcRg : 11|12@0+ (0.1,0) [0|409.5] "km" XXX + SG_ HVDpltnMdMiCnfdcRg : 27|12@0+ (0.1,0) [0|409.5] "km" XXX + SG_ HVDpltnMdMxGugRg : 43|12@0+ (0.1,0) [0|409.5] "km" XXX + +BO_ 2151776256 Rear_Cross_Traffic_Alert_Left_LS: 5 XXX + SG_ RrCTfcLHptcStRqSeqN : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RrCTfcLHptcStReq : 7|6@0+ (1,0) [0|63] "" XXX + SG_ RrCrsTrfAltLftIndCtrl : 34|3@0+ (1,0) [0|0] "" XXX + SG_ RCTALIC_IndReq : 33|2@0+ (1,0) [0|3] "" XXX + SG_ RCTALIC_Indctr1Act : 34|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154774528 Lighting_Customization_Info_1_LS: 1 XXX + SG_ LtRtHnTrCstStVal : 2|3@0+ (1,0) [0|7] "" XXX + SG_ LtRtHnTrGPCsCrStVal : 5|3@0+ (1,0) [0|7] "" XXX + SG_ LtRtHnTrCstStAvail : 6|1@0+ (1,0) [0|1] "" XXX + SG_ LtRtHnTrGPSCsStAvl : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150375424 Eng_Maintenance_Mode_Strt_Req_LS: 3 XXX + SG_ MntnceMdStEngRq : 0|1@0+ (1,0) [0|1] "" XXX + SG_ EngAstHtCstStRq : 3|3@0+ (1,0) [0|7] "" XXX + SG_ EngAstHtPlgInCstStRq : 6|3@0+ (1,0) [0|7] "" XXX + SG_ DsplTrnsShftLvrLckRqd : 7|1@0+ (1,0) [0|1] "" XXX + SG_ EngyCnsHistGrphRstRq : 8|1@0+ (1,0) [0|1] "" XXX + SG_ USBProgInPrgrs : 9|1@0+ (1,0) [0|1] "" XXX + SG_ LBCPosMdfcReq : 12|3@0+ (1,0) [0|7] "" XXX + SG_ LBCCsStReq : 14|2@0+ (1,0) [0|3] "" XXX + SG_ LBCCstmrDaRstReq : 20|5@0+ (1,0) [0|0] "" XXX + SG_ LBCCDRR_PosNum : 18|3@0+ (1,0) [0|7] "" XXX + SG_ LBCCDRR_ClrStrdPosReq : 20|2@0+ (1,0) [0|3] "" XXX + +BO_ 2150383616 Engine_Maintenance_Mode_Req_LS: 8 XXX + SG_ MntnceMdDsplyRq : 3|4@0+ (1,0) [0|15] "" XXX + SG_ EngMntnceMdAct : 4|1@0+ (1,0) [0|1] "" XXX + SG_ EngMntncePrcntCpl : 15|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ EngPrpDspPwrLvlPct : 23|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ EstElecPrpCap : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ PrpCapDspOpPs : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ PrpDspTtlPwr : 45|13@0+ (0.5,-326.6) [-326.6|3768.9] "kW" XXX + SG_ BatPrpDspPwrLvlPct : 48|9@0- (0.392157,0) [-100.392192|100.000035] "%" XXX + +BO_ 2151981056 Drive_Cycle_Efficiency_LS: 8 XXX + SG_ DstTrvldDt : 7|51@0+ (1,0) [0|0] "" XXX + SG_ DTD_BattPrpDstTrvld : 7|17@0+ (0.015625,0) [0|2047.984375] "km" XXX + SG_ DTD_FuelPrpDstTrvld : 22|17@0+ (0.015625,0) [0|2047.984375] "km" XXX + SG_ DTD_DrvCyclDstTrvld : 37|17@0+ (0.015625,0) [0|2047.984375] "km" XXX + SG_ DrvCyclBatPropRat : 50|11@0+ (0.048852,0) [0|100.000044] "%" XXX + +BO_ 2151964672 Drive_Cycle_Energy_Efficiency_LS: 8 XXX + SG_ DrvCyclBatCondEnrgEfncy : 7|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ DrvCyclCbnCondEnrgEfncy : 23|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ DrvCyclDrvStEnrgEfncy : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ DrvCyclTtlEnrgEfncy : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ DrvCyclFuelEnmy : 47|12@0+ (0.1,0) [0|409.5] "km/liters" XXX + SG_ DrvCyclFuelUsd : 51|12@0+ (0.125,0) [0|511.875] "liters" XXX + +BO_ 2156298240 High_Volt_Batt_Time_Pwr_Chrg_LS: 8 XXX + SG_ HVBatCmpltTmHghPwrChrg : 7|14@0+ (1,0) [0|0] "" XXX + SG_ HVBCTHPC_HrOfDy : 4|5@0+ (1,0) [0|31] "Hour" XXX + SG_ HVBCTHPC_DyOfWk : 7|3@0+ (1,0) [0|7] "" XXX + SG_ HVBCTHPC_MntOfHr : 15|6@0+ (1,0) [0|63] "Minute" XXX + SG_ HVBatCmpltTmLwPwrChrg : 9|14@0+ (1,0) [0|0] "" XXX + SG_ HVBCTLPC_DyOfWk : 9|3@0+ (1,0) [0|7] "" XXX + SG_ HVBCTLPC_MntOfHr : 17|6@0+ (1,0) [0|63] "Minute" XXX + SG_ HVBCTLPC_HrOfDy : 22|5@0+ (1,0) [0|31] "Hour" XXX + SG_ HVBatStrTmHghPwrChrg : 27|14@0+ (1,0) [0|0] "" XXX + SG_ HVBSTHPC_HrOfDy : 24|5@0+ (1,0) [0|31] "Hour" XXX + SG_ HVBSTHPC_DyOfWk : 27|3@0+ (1,0) [0|7] "" XXX + SG_ HVBSTHPC_MntOfHr : 35|6@0+ (1,0) [0|63] "Minute" XXX + SG_ HVBatStrTmLwPwrChrg : 45|14@0+ (1,0) [0|0] "" XXX + SG_ HVBSTLPC_HrOfDy : 42|5@0+ (1,0) [0|31] "Hour" XXX + SG_ HVBSTLPC_DyOfWk : 45|3@0+ (1,0) [0|7] "" XXX + SG_ HVBSTLPC_MntOfHr : 53|6@0+ (1,0) [0|63] "Minute" XXX + SG_ HVChrgSysDpTmExdSt : 58|3@0+ (1,0) [0|0] "" XXX + SG_ HVCSDTES_NPDTIO : 56|1@0+ (1,0) [0|1] "" XXX + SG_ HVCSDTES_HiPwrCIO : 57|1@0+ (1,0) [0|1] "" XXX + SG_ HVCSDTES_LoPwrCIO : 58|1@0+ (1,0) [0|1] "" XXX + SG_ HTRActvIndOn : 59|1@0+ (1,0) [0|1] "" XXX + SG_ InsfcntTmTFlChrgIO : 60|1@0+ (1,0) [0|1] "" XXX + SG_ InvldHMIEtrIO : 61|1@0+ (1,0) [0|1] "" XXX + SG_ HVBatChrgCrdAlrtReq : 63|2@0+ (1,0) [0|3] "" XXX + +BO_ 2149924864 Drv_Pref_Mode_Switch_Status_LS: 8 XXX + SG_ DrvSelMd1Stat : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd1ReqDnd : 1|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd2Stat : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd2ReqDnd : 3|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd3Stat : 4|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd3ReqDnd : 5|1@0+ (1,0) [0|1] "" XXX + SG_ HilRlbkCtrlActIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ FwdClnMtgnBrkReqAct : 7|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMdSelnStat : 8|17@0+ (1,0) [0|0] "" XXX + SG_ DSMSS_DrvSelMd1Un : 8|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd1Pn : 16|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd8Un : 17|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd7Un : 18|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd6Un : 19|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd5Un : 20|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd4Un : 21|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd3Un : 22|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd2Un : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd0Pn : 24|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd8Pn : 25|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd7Pn : 26|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd6Pn : 27|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd5Pn : 28|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd4Pn : 29|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd3Pn : 30|1@0+ (1,0) [0|1] "" XXX + SG_ DSMSS_DrvSelMd2Pn : 31|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd4Stat : 9|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd4ReqDnd : 10|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd5Stat : 11|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd5ReqDnd : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd6Stat : 13|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd6ReqDnd : 14|1@0+ (1,0) [0|1] "" XXX + SG_ PTOMobModTrnsInGrIO : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ECODrvAsstDsplyStat : 34|11@0+ (1,0) [0|0] "" XXX + SG_ EDADS_ShftIndStat : 33|2@0+ (1,0) [0|3] "" XXX + SG_ EDADS_EcoDrvShftIO : 34|1@0+ (1,0) [0|1] "" XXX + SG_ EDADS_RcmndtFwdGr : 43|4@0+ (1,0) [0|15] "" XXX + SG_ EDADS_CrntFwdMsdG : 47|4@0+ (1,0) [0|15] "" XXX + SG_ DrvSelMd7Stat : 35|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd7ReqDnd : 36|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd8Stat : 37|1@0+ (1,0) [0|1] "" XXX + SG_ DrvSelMd8ReqDnd : 38|1@0+ (1,0) [0|1] "" XXX + SG_ FstIdlMdAct : 39|1@0+ (1,0) [0|1] "" XXX + SG_ DsplyPerfMdRq : 50|3@0+ (1,0) [0|7] "" XXX + SG_ TireLFLowTracIO : 51|1@0+ (1,0) [0|1] "" XXX + SG_ TireLRLowTracIO : 52|1@0+ (1,0) [0|1] "" XXX + SG_ TireRFLowTracIO : 53|1@0+ (1,0) [0|1] "" XXX + SG_ TireRRLowTracIO : 54|1@0+ (1,0) [0|1] "" XXX + SG_ a_12VBatSysUnstab : 55|1@0+ (1,0) [0|1] "" XXX + SG_ ColPrepSysCustAvail : 62|7@0+ (1,0) [0|0] "" XXX + SG_ CPSCA_Resrv3Avail : 56|1@0+ (1,0) [0|1] "" XXX + SG_ CPSCA_Resrv2Avail : 57|1@0+ (1,0) [0|1] "" XXX + SG_ CPSCA_Resrv1Avail : 58|1@0+ (1,0) [0|1] "" XXX + SG_ CPSCA_AlrtBrkStrAvail : 59|1@0+ (1,0) [0|1] "" XXX + SG_ CPSCA_AlrtBrkAvail : 60|1@0+ (1,0) [0|1] "" XXX + SG_ CPSCA_AlrtAvail : 61|1@0+ (1,0) [0|1] "" XXX + SG_ CPSCA_OffAvail : 62|1@0+ (1,0) [0|1] "" XXX + +BO_ 2152054784 HMI_Disp_Hyb_Animation_Status_LS: 1 XXX + SG_ AnmStrtReq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ IntPnlClstrAnmtStat : 5|3@0+ (1,0) [0|7] "" XXX + SG_ FuelEconMetDispUnts : 6|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150301696 HMI_Animation_Initiator_LS: 1 XXX + SG_ WlcAnmReq : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150563840 HMI_AnimationHybridRadio_LS: 3 XXX + SG_ RadAnmtStat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ RadAudQueStat : 5|3@0+ (1,0) [0|7] "" XXX + SG_ DrStStatDispAct : 6|1@0+ (1,0) [0|1] "" XXX + SG_ PsStStatDispAct : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154758144 Auxiliary_Heater_Active_LS: 1 XXX + SG_ ChldLckOtSwAct : 1|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154577920 Amp_Sink_Stat_LS: 2 XXX + SG_ AmpSnkStat : 4|13@0+ (1,0) [0|0] "" XXX + SG_ ASS_SurndAvail : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPAvail : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_VehNoisCmpnAvail : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_PhLckdLpLckd : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_MtxSnkMutStat : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPMd7Prsnt : 8|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPMd6Prsnt : 9|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPMd5Prsnt : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPMd4Prsnt : 11|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPMd3Prsnt : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPMd2Prsnt : 13|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPMd1Prsnt : 14|1@0+ (1,0) [0|1] "" XXX + SG_ ASS_DSPMd0Prsnt : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154594304 Amp_Settings_Tone_Ctrl_LS: 5 XXX + SG_ AmpSetTonCtrl : 1|34@0+ (1,0) [0|0] "" XXX + SG_ ASTC_ChimSnkLvl : 1|8@0+ (0.5,-127.5) [-127.5|0] "dB" XXX + SG_ ASTC_ChimSnkSpkrPos : 9|4@0+ (1,0) [0|15] "" XXX + SG_ ASTC_SurndLvl : 21|6@0- (1,0) [-32|31] "" XXX + SG_ ASTC_MtxSnkMutRmpTm : 25|8@0+ (5,0) [0|1275] "ms" XXX + SG_ ASTC_MtxSnkMut : 26|1@0+ (1,0) [0|1] "" XXX + SG_ ASTC_DSPMd : 30|4@0+ (1,0) [0|15] "" XXX + SG_ ASTC_VehNoisCmpnAct : 31|1@0+ (1,0) [0|1] "" XXX + SG_ ASTC_GblAudSnkMut : 32|1@0+ (1,0) [0|1] "" XXX + SG_ ASTC_AmpLwPwrSt : 33|1@0+ (1,0) [0|1] "" XXX + SG_ InfotnBkltngConfigSt : 3|2@0+ (1,0) [0|3] "" XXX + +BO_ 2154586112 Amp_Settings_Sink_Lvl_Ctrl_LS: 8 XXX + SG_ AmpSetSnkLvlCtrl : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ASSLC_MtxSnkLvl : 7|8@0+ (0.5,-127.5) [-127.5|0] "dB" XXX + SG_ ASSLC_MxPrmtSnkLvl : 15|8@0+ (0.5,-127.5) [-127.5|0] "dB" XXX + SG_ ASSLC_AudFdbkSnkLvl : 23|8@0+ (0.5,-127.5) [-127.5|0] "dB" XXX + SG_ ASSLC_FvSnkLvl : 31|8@0+ (0.5,-127.5) [-127.5|0] "dB" XXX + SG_ ASSLC_MtxSnkFd : 33|6@0- (1,0) [-32|31] "" XXX + SG_ ASSLC_MtxSnkBal : 39|6@0- (1,0) [-32|31] "" XXX + SG_ ASSLC_MtxSnkBass : 43|6@0- (1,0) [-32|31] "" XXX + SG_ ASSLC_MtxSnkMdrng : 53|6@0- (1,0) [-32|31] "" XXX + SG_ ASSLC_AutoLdnsCmpnAct : 56|1@0+ (1,0) [0|1] "" XXX + SG_ ASSLC_VcSrcActOnMtx : 57|1@0+ (1,0) [0|1] "" XXX + SG_ ASSLC_MtxSnkTrbl : 63|6@0- (1,0) [-32|31] "" XXX + +BO_ 2152857600 ACC_TrafficJam_RouteSpd_Stat_LS: 3 XXX + SG_ ACCRteSpdDrvIntvReq : 1|2@0+ (1,0) [0|3] "" XXX + SG_ ACCTrfcJamAstActStat : 10|3@0+ (1,0) [0|7] "" XXX + SG_ ACCRteSpdAdaptStat : 12|2@0+ (1,0) [0|3] "" XXX + SG_ ACCGrnMdStat : 14|2@0+ (1,0) [0|3] "" XXX + SG_ ACCTrfcJamAstRmnTm : 23|8@0+ (1,0) [0|255] "sec" XXX + +BO_ 2158149632 High_Volt_Bat_Time_Bsd_Rsp_1_LS: 7 XXX + SG_ HVBatTmBsSsnChRsp : 0|14@0+ (1,0) [0|0] "" XXX + SG_ HVBTBSCR_SsnStat : 0|2@0+ (1,0) [0|3] "" XXX + SG_ HVBTBSCR_SsnMthStat : 11|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBSCR_SsnSlctStat : 14|3@0+ (1,0) [0|7] "" XXX + SG_ HVBTBSCR_SsnDyStat : 23|5@0+ (1,0) [0|31] "day" XXX + SG_ HVBatTmBsChrgStRsp : 3|3@0+ (1,0) [0|7] "" XXX + SG_ HVBatCrgDspStat : 6|3@0+ (1,0) [0|7] "" XXX + SG_ HVBatTmBsChrgRtRsp : 17|10@0+ (1,0) [0|0] "" XXX + SG_ HVBTBCRS_ChRtEnblStat : 17|2@0+ (1,0) [0|3] "" XXX + SG_ HVBTBCRS_ChRtSlctStat : 27|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBCRS_ChRtDStat : 31|4@0+ (1,0) [0|15] "" XXX + SG_ EngyCnsHsGrphCnfgDt : 36|13@0+ (1,0) [0|0] "" XXX + SG_ ECHGCD_YAxMaxVal : 32|6@0+ (4,0) [0|252] "" XXX + SG_ ECHGCD_MeasUt : 36|4@0+ (1,0) [0|15] "" XXX + SG_ ECHGCD_XAxTkMrkInterv : 42|3@0+ (1,0) [0|7] "" XXX + SG_ EgyCnsHstGphInsEgyCns : 55|5@0+ (1,0) [0|31] "" XXX + +BO_ 2158116864 High_Volt_Bat_Time_Bsd_Rsp_LS: 8 XXX + SG_ OBHVBCMinsRmng : 5|6@0+ (1,0) [0|63] "" XXX + SG_ OBHVBCCompTmDispFrmt : 7|2@0+ (1,0) [0|3] "" XXX + SG_ HVBatTmBsDelChrgRsp : 12|21@0+ (1,0) [0|0] "" XXX + SG_ HVBTBDCRS_DlChHRsp : 12|5@0+ (1,0) [0|31] "hr" XXX + SG_ HVBTBDCRS_DlChSlctStat : 19|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBDCRS_DlChDStat : 23|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBDCRS_DlChMHRsp : 29|6@0+ (1,0) [0|63] "min" XXX + SG_ HVBTBDCRS_DlChSsnStat : 31|2@0+ (1,0) [0|3] "" XXX + SG_ HVBatTmBsRtChrgRsp : 34|27@0+ (1,0) [0|0] "" XXX + SG_ HVBTBRCR_RtChMHRsp : 32|6@0+ (1,0) [0|63] "min" XXX + SG_ HVBTBRCR_RtChSsnStat : 34|2@0+ (1,0) [0|3] "" XXX + SG_ HVBTBRCR_RtChSlctStat : 42|3@0+ (1,0) [0|7] "" XXX + SG_ HVBTBRCR_RtChDStat : 50|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBRCR_RtChHRsp : 55|5@0+ (1,0) [0|31] "hr" XXX + SG_ HVBTBRCR_RtCHSlctTblRwStat : 58|3@0+ (1,0) [0|7] "rows" XXX + SG_ HVBTBRCR_RtChSlRtStat : 62|4@0+ (1,0) [0|15] "" XXX + +BO_ 2156281856 High_Volt_Bat_Time_Bsd_Req_1_LS: 7 XXX + SG_ HVBatTmBsSsnChStReq : 0|14@0+ (1,0) [0|0] "" XXX + SG_ HVBTBSCSR_SsnStReq : 0|2@0+ (1,0) [0|3] "" XXX + SG_ HVBTBSCSR_SsnMthStReq : 11|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBSCSR_SsnSlStReq : 14|3@0+ (1,0) [0|7] "" XXX + SG_ HVBTBSCSR_SsnDayStReq : 23|5@0+ (1,0) [0|31] "day" XXX + SG_ HVBatTmBsChrgMdReq : 3|3@0+ (1,0) [0|7] "" XXX + SG_ HVChgSyChgLvlPrfSt : 6|3@0+ (1,0) [0|7] "" XXX + SG_ StTODChrgTmpOvrd : 7|1@0+ (1,0) [0|1] "" XXX + SG_ HVBatTmBsChrgRtStReq : 17|10@0+ (1,0) [0|0] "" XXX + SG_ HVBTBCRSR_ChRtEnblStReq : 17|2@0+ (1,0) [0|3] "" XXX + SG_ HVBTBCRSR_ChRtSlStReq : 27|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBCRSR_ChRtDStReq : 31|4@0+ (1,0) [0|15] "" XXX + SG_ TmpOvdNxtPlnDptTmRq : 32|17@0+ (1,0) [0|0] "" XXX + SG_ TONPDTR_StTmpOvrAtv : 32|2@0+ (1,0) [0|3] "" XXX + SG_ TONPDTR_HrOfDy : 42|5@0+ (1,0) [0|31] "Hour" XXX + SG_ TONPDTR_DyOfWk : 46|4@0+ (1,0) [0|15] "" XXX + SG_ TONPDTR_MntOfHr : 53|6@0+ (1,0) [0|63] "Minute" XXX + SG_ RtBsChrgCmplnTmPrfReq : 34|2@0+ (1,0) [0|3] "" XXX + SG_ HTRCsStReq : 37|3@0+ (1,0) [0|7] "" XXX + +BO_ 2156265472 High_Volt_Bat_Time_Bsd_Req_LS: 8 XXX + SG_ ChgCdTfAlCzStRq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ ChgPwLsAlCzStRq : 5|3@0+ (1,0) [0|7] "" XXX + SG_ PrtyChrgRq : 7|2@0+ (1,0) [0|3] "" XXX + SG_ HVBatTmBsDlChStReq : 12|21@0+ (1,0) [0|0] "" XXX + SG_ HVBTBDCSRQ_DlChHStReq : 12|5@0+ (1,0) [0|31] "hr" XXX + SG_ HVBTBDCSRQ_DlChSlStReq : 19|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBDCSRQ_DlChDStReq : 23|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBDCSRQ_DlChMHStReq : 29|6@0+ (1,0) [0|63] "min" XXX + SG_ HVBTBDCSRQ_DlChSsnStReq : 31|2@0+ (1,0) [0|3] "" XXX + SG_ ChgSysAudInCsStReq : 15|3@0+ (1,0) [0|7] "" XXX + SG_ HVBatTmBsRtChrgStReq : 34|27@0+ (1,0) [0|0] "" XXX + SG_ HVBTBRCSR_RtChDStReq : 34|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBRCSR_RtChSlStReq : 42|3@0+ (1,0) [0|7] "" XXX + SG_ HVBTBRCSR_RtChSlRtStReq : 46|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBRCSR_RtChMHStReq : 48|6@0+ (1,0) [0|63] "min" XXX + SG_ HVBTBRCSR_RtChSsnStReq : 50|2@0+ (1,0) [0|3] "" XXX + SG_ HVBTBRCSR_RtChHStReq : 55|5@0+ (1,0) [0|31] "hr" XXX + SG_ HVBTBRCSR_RtChSlTbRwReq : 58|3@0+ (1,0) [0|7] "rows" XXX + SG_ OffBrdHVCVehCsChRq : 35|1@0+ (1,0) [0|1] "" XXX + SG_ EngyUsgScrnMeasUtStat : 39|4@0+ (1,0) [0|15] "" XXX + +BO_ 2150113280 Energy_Storage_System_LS: 8 XXX + SG_ EngyStgSysActCoolEnb : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DrvCycElEnrgUsd : 21|14@0+ (0.36,0) [0|5897.88] "MJ" XXX + SG_ DrvCyclElecEngyEcon : 32|9@0+ (0.1,0) [0|51.1] "" XXX + SG_ HVChrgInhbRsn : 36|4@0+ (1,0) [0|15] "" XXX + SG_ DrvCyclTrpDstTrvld : 54|15@0+ (0.1,0) [0|3276.7] "km" XXX + +BO_ 2150055936 Climate_Control_Status_LS: 5 XXX + SG_ ClmtCtrlUpprPwrLmt : 7|8@0+ (0.1,0) [0|25.5] "kW" XXX + SG_ ClmtCtrlLwrPwrLmt : 15|8@0+ (0.1,0) [0|25.5] "kW" XXX + SG_ ClimCtrlHVDvcShtdwnCmd : 16|1@0+ (1,0) [0|1] "" XXX + SG_ ClmCntCmpPwrUsdClc : 39|8@0+ (0.04,0) [0|10.2] "kW" XXX + +BO_ 2150039552 Thrml_Ref_Compressor_Status_LS: 5 XXX + SG_ ThrmlRefCompStat : 3|4@0+ (1,0) [0|15] "" XXX + SG_ EvpCorOtltAirTmpCalcdGroup : 4|13@0+ (1,0) [0|0] "" XXX + SG_ EvpCorOtltAirTmpCalcdV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ EvpCorOtltAirTmpCalcd : 15|8@0+ (0.5,-40) [-40|87.5] "deg C" XXX + SG_ ThrmlRefCompSpdGroup : 22|15@0+ (1,0) [0|0] "" XXX + SG_ ThrmlRefCompSpd : 21|14@0+ (1,0) [0|16383] "rpm" XXX + SG_ ThrmlRefCompSpdV : 22|1@0+ (1,0) [0|1] "" XXX + SG_ ThrmlRfCmpOvTmpFltPr : 23|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154856448 Humidity_Sensor_Status_LS: 5 XXX + SG_ HmdtySnsrGlssTemp : 1|10@0+ (0.146628,-50) [-50|100.000444] "deg C" XXX + SG_ HmdtySnsrTemp : 17|10@0+ (0.146628,-50) [-50|100.000444] "deg C" XXX + SG_ HmdtySnsrRltvHmdty : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + +BO_ 2151342080 Park_Assistant_Right_Status_LS: 2 XXX + SG_ PARtRgn1ObjStat : 3|4@0+ (1,0) [0|15] "" XXX + SG_ PrkAstRtSysStat : 5|2@0+ (1,0) [0|3] "" XXX + SG_ PARtRgn3ObjStat : 11|4@0+ (1,0) [0|15] "" XXX + SG_ PARtRgn2ObjStat : 15|4@0+ (1,0) [0|15] "" XXX + +BO_ 2151325696 Park_Assistant_Left_Status_LS: 2 XXX + SG_ PALtRgn1ObjStat : 3|4@0+ (1,0) [0|15] "" XXX + SG_ PrkAstLtSysStat : 5|2@0+ (1,0) [0|3] "" XXX + SG_ PALtRgn3ObjStat : 11|4@0+ (1,0) [0|15] "" XXX + SG_ PALtRgn2ObjStat : 15|4@0+ (1,0) [0|15] "" XXX + +BO_ 2151809024 Drv_Cycl_Elec_Enrgy_Consumd_LS: 8 XXX + SG_ DrvCycElecEngySt5 : 5|14@0+ (0.36,0) [0|5897.88] "MJ" XXX + SG_ DrvCycElecEngyCnsmd : 23|32@0+ (1,0) [0|0] "" XXX + SG_ DCEEC_EngyPct1 : 23|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ DCEEC_EngyPct2 : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ DCEEC_EngyPct3 : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ DCEEC_EngyPct4 : 47|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ ElecEngyEconAvg : 48|9@0+ (0.1,0) [0|51.1] "" XXX + +BO_ 2151858176 Drv_Cycl_Elec_Enrgy_States_LS: 8 XXX + SG_ DrvCycElecEngySt1 : 5|14@0+ (0.36,0) [0|5897.88] "MJ" XXX + SG_ DrvCycElecEngySt2 : 21|14@0+ (0.36,0) [0|5897.88] "MJ" XXX + SG_ DrvCycElecEngySt3 : 37|14@0+ (0.36,0) [0|5897.88] "MJ" XXX + SG_ DrvCycElecEngySt4 : 53|14@0+ (0.36,0) [0|5897.88] "MJ" XXX + +BO_ 2150547456 HMI_Hybrid_Vehicle_Status_LS: 8 XXX + SG_ HVDpltnMdRng : 0|16@0+ (0.015625,0) [0|1023.984375] "km" XXX + SG_ VehChrgMdSt : 3|3@0+ (1,0) [0|7] "" XXX + SG_ GrnAudQueReq : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SvcHybChrgSysIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ HVBatChrgCrdConnIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ CntrsOpnUndrTmpIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ OffBrdHVCVehCplrLkd : 16|1@0+ (1,0) [0|1] "" XXX + SG_ HVBatLimDTmpInd : 25|2@0+ (1,0) [0|3] "" XXX + SG_ OffBrdHVCVehPwrDrtd : 26|1@0+ (1,0) [0|1] "" XXX + SG_ HVChrgrSysStat : 29|3@0+ (1,0) [0|7] "" XXX + SG_ HVChrgrCplrStat : 31|2@0+ (1,0) [0|3] "" XXX + SG_ ChgrSysAdblIndReq : 33|2@0+ (1,0) [0|3] "" XXX + SG_ HVBatOutOfEnrgyInd : 36|3@0+ (1,0) [0|7] "" XXX + SG_ OffBrdHVBlkChrgCmp : 37|1@0+ (1,0) [0|1] "" XXX + SG_ ElecPrplsnMtrOvrSpdIO : 38|1@0+ (1,0) [0|1] "" XXX + SG_ HVBatCntctrsOpnIO : 39|1@0+ (1,0) [0|1] "" XXX + SG_ HVDpltnMdCnfdcTrndg : 47|8@0- (0.787402,0) [-100.787456|100.000054] "%" XXX + SG_ OffBrdHVBlkChgCpltTm : 53|14@0+ (1,0) [0|0] "" XXX + SG_ OBHVBCCT_HrofDay : 50|5@0+ (1,0) [0|31] "" XXX + SG_ OBHVBCCT_DayofWk : 53|3@0+ (1,0) [0|7] "" XXX + SG_ OBHVBCCT_MinofHr : 61|6@0+ (1,0) [0|63] "" XXX + SG_ OffBrdHVCVehPwrLvl : 55|2@0+ (1,0) [0|3] "" XXX + +BO_ 2151489536 CSV_EOCM_R_Indications_LS: 1 XXX + SG_ RVBShtToPrkBfExtngVehIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RVBAutoBrkRlsIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ NVSysStat : 4|3@0+ (1,0) [0|7] "" XXX + +BO_ 2149761024 Chassis_Information_2_LS: 6 XXX + SG_ PerfTrcCrnExStngVal : 4|5@0+ (1,0) [0|31] "" XXX + SG_ ActVehAccelGroup : 5|22@0+ (1,0) [0|0] "" XXX + SG_ ActVehAccelV : 5|1@0+ (1,0) [0|1] "" XXX + SG_ ActVehAccel : 11|12@0- (0.01,0) [-20.48|20.47] "m/s^2" XXX + SG_ TrlrStabAstActIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ElvtdIdlCstStAvl : 7|1@0+ (1,0) [0|1] "" XXX + SG_ ElvtdIdlCstCrStVal : 13|2@0+ (1,0) [0|3] "" XXX + SG_ TrnsCltchThrmlProtIndR : 27|20@0+ (1,0) [0|0] "" XXX + SG_ TCTPIR_DrvNotfn : 27|4@0+ (1,0) [0|15] "" XXX + SG_ TCTPIR_TnsEsClTmpD : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ TCTPIR_TnsEsClCDwT : 47|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ PsngStPerfMdCsCrStVal : 30|3@0+ (1,0) [0|7] "" XXX + SG_ PsngStPerfMdCsStAvl : 31|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155012096 SBZA_Right_Status_LS: 1 XXX + SG_ SODTmpUnavlbleIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SODSnsClnRqdIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ SODRtIndCntl : 6|5@0+ (1,0) [0|0] "" XXX + SG_ SODRIC_Ind3 : 2|1@0+ (1,0) [0|1] "" XXX + SG_ SODRIC_Ind2 : 3|1@0+ (1,0) [0|1] "" XXX + SG_ SODRIC_Ind1 : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SODRIC_IndReq : 6|2@0+ (1,0) [0|3] "" XXX + SG_ SrvSODSysIO : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150514688 Power_Slidining_Door_Status_LS: 1 XXX + SG_ SldngDrRgtStat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ SldngDrLftStat : 5|3@0+ (1,0) [0|7] "" XXX + SG_ PwrSldngDrUnavlblIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ SdClsrObstclDtctdStat : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2158067712 Video_Master_Info_2_LS: 5 XXX + SG_ TchScnDsplUsrActnExt : 1|34@0+ (1,0) [0|0] "" XXX + SG_ TSDUAE_RotBtnPsh : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TSDUAE_ScrnPrsdRq : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TSDUAE_GrphStrkInfRq : 15|8@0+ (1,0) [0|255] "" XXX + SG_ TSDUAE_XCoOdntRq : 23|8@0+ (1,0) [0|255] "" XXX + SG_ TSDUAE_YCoOdntRq : 31|8@0+ (1,0) [0|255] "" XXX + SG_ TSDUAE_RotEnc : 39|8@0- (1,0) [-128|127] "Detentions" XXX + +BO_ 2158051328 Video_Master_Info_1_LS: 5 XXX + SG_ RemRcvrSrcInpCmd : 3|4@0+ (1,0) [0|15] "" XXX + SG_ VidMstrDsplyMd : 5|2@0+ (1,0) [0|3] "" XXX + SG_ VidSrcUICntrlStat : 6|1@0+ (1,0) [0|1] "" XXX + SG_ RmtRcvrTunCmnd : 12|5@0+ (1,0) [0|31] "" XXX + SG_ VidMstrArbCmd : 15|3@0+ (1,0) [0|7] "" XXX + SG_ RmtRcvrTunVal : 23|16@0- (1,0) [-32768|32767] "" XXX + SG_ VidMstrSrcType : 36|5@0+ (1,0) [0|31] "" XXX + SG_ TVDspCmd : 39|3@0+ (1,0) [0|7] "" XXX + +BO_ 2158034944 TV_Tuner_Info_LS: 6 XXX + SG_ VidSrcCompFormatER : 3|4@0+ (1,0) [0|15] "" XXX + SG_ CurntTVStnServc : 6|3@0+ (1,0) [0|7] "" XXX + SG_ CurntTVStnQual : 7|1@0+ (1,0) [0|1] "" XXX + SG_ RmtRcvrCmndStat : 10|3@0+ (1,0) [0|7] "" XXX + SG_ RmtRecvtDataTyp : 13|3@0+ (1,0) [0|7] "" XXX + SG_ RmtRcvrTunStat : 14|1@0+ (1,0) [0|1] "" XXX + SG_ TVTunerPres : 15|1@0+ (1,0) [0|1] "" XXX + SG_ RmtRcvrPrgrmServID : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ VidSrcStatCode : 35|4@0+ (1,0) [0|15] "" XXX + SG_ RemRcvrSrcInpStat : 39|4@0+ (1,0) [0|15] "" XXX + SG_ VidSrcType : 44|5@0+ (1,0) [0|31] "" XXX + +BO_ 2158018560 TV_Station_Name_LS: 8 XXX + SG_ TVStatNmeChar1_8 : 7|64@0+ (1,0) [0|0] "" XXX + +BO_ 2156838912 WiFi_Station_LS: 7 XXX + SG_ WiFiStationResp : 3|52@0+ (1,0) [0|0] "" XXX + SG_ WSR_WiFiAssnStat : 3|4@0+ (1,0) [0|15] "" XXX + SG_ WSR_WiFiStnMACAddr : 15|48@0+ (1,0) [0|281474976710655] "" XXX + +BO_ 2156822528 WiFi_AP_Data_LS: 2 XXX + SG_ WiFiAccsPntData : 0|9@0+ (1,0) [0|0] "" XXX + SG_ WAPD_IHUWiFiEnStat : 0|1@0+ (1,0) [0|1] "" XXX + SG_ WAPD_EncrptnType : 11|4@0+ (1,0) [0|15] "" XXX + SG_ WAPD_SecurityType : 15|4@0+ (1,0) [0|15] "" XXX + +BO_ 2151948288 Driver_Drow_Det_Cst_Rqst_LS: 1 XXX + SG_ DrvDrowDetCstStRq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ RunBrdOpMdCstStReq : 7|3@0+ (1,0) [0|7] "" XXX + +BO_ 2158002176 XM_Radio_Service_LS: 1 XXX + SG_ CurntStnServc : 2|3@0+ (1,0) [0|7] "" XXX + SG_ SrvcPrvdr : 5|3@0+ (1,0) [0|7] "" XXX + +BO_ 2149728256 Charging_Sys_Trans_Shift_Lock_LS: 5 XXX + SG_ ChrgSysTrnsShftLckRq : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ChrgPrtDrStat : 2|2@0+ (1,0) [0|3] "" XXX + SG_ PrtyChrgActIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PrtyChrgAct : 4|1@0+ (1,0) [0|1] "" XXX + SG_ HghVltgPropState : 7|3@0+ (1,0) [0|7] "" XXX + SG_ ChgCdTfAlCzCrStVal : 10|3@0+ (1,0) [0|7] "" XXX + SG_ ChgCdTfAlCzStAvbl : 11|1@0+ (1,0) [0|1] "" XXX + SG_ ChgPwLsAlCzCrStVal : 14|3@0+ (1,0) [0|7] "" XXX + SG_ ChgPwLsAlCzStAvbl : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ChgSyAudInCsCrStVa : 18|3@0+ (1,0) [0|7] "" XXX + SG_ ChgSysAudInCsStAvl : 19|1@0+ (1,0) [0|1] "" XXX + SG_ HVChrgPwrLvl : 22|3@0+ (1,0) [0|7] "" XXX + SG_ EngAstHtCsCrStVal : 26|3@0+ (1,0) [0|7] "" XXX + SG_ EngAstHtCsStAvl : 27|1@0+ (1,0) [0|1] "" XXX + SG_ EngAstHtPlgInCsCrStVl : 30|3@0+ (1,0) [0|7] "" XXX + SG_ EngAstHtPlgInCsStAvl : 31|1@0+ (1,0) [0|1] "" XXX + SG_ PrtyChrgStPnt : 38|7@0+ (1,0) [0|127] "" XXX + +BO_ 2150023168 Hybrid_Information_LS: 5 XXX + SG_ HybChrgMdStat : 1|2@0+ (1,0) [0|3] "" XXX + SG_ HVInvRatVltGroup : 2|19@0+ (1,0) [0|0] "" XXX + SG_ HVInvRatVltV : 2|1@0+ (1,0) [0|1] "" XXX + SG_ HVInvRatVlt : 8|9@0+ (1,0) [0|511] "volts" XXX + SG_ OffBrdVehImmbNot : 5|3@0+ (1,0) [0|7] "" XXX + SG_ ElecPrplsnMtrTach : 28|13@0+ (1,0) [0|8191] "rpm" XXX + +BO_ 2153988096 Power_Elec_Info_LS: 7 XXX + SG_ PwrElecCoolLpTempGroup : 1|10@0+ (1,0) [0|0] "" XXX + SG_ PwrElecCoolLpTempV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ PwrElecCoolLpTempM : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PwrElecCoolLpTemp : 15|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ EngyUsgScr : 20|37@0+ (1,0) [0|0] "" XXX + SG_ EUS_TcEngyUsgScrAvVal : 20|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUS_TrEngyUsgScrAvVal : 29|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUS_OTEngyUsgScrAvVal : 38|7@0- (0.1,0) [-5|5] "" XXX + SG_ EUS_TtEngyUsgScrAvVal : 40|9@0- (0.1,0) [-20|20] "" XXX + SG_ EUS_ITEngyUsgScrAvVal : 47|7@0- (0.1,0) [-5|5] "" XXX + +BO_ 2155945984 Jump_Start_Req_LS: 1 XXX + SG_ JmpStrtReq : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TCSysCurStReq : 2|2@0+ (1,0) [0|3] "" XXX + SG_ VehStbEnhmntCurStRq : 4|2@0+ (1,0) [0|3] "" XXX + SG_ VehStbCmptvMdCurStRq : 6|2@0+ (1,0) [0|3] "" XXX + +BO_ 2155585536 MSB_Customization_Setting_Req_LS: 1 XXX + SG_ StBltTgtCSRq : 2|3@0+ (1,0) [0|7] "" XXX + +BO_ 2155569152 CPS_Customization_Setting_Req_LS: 3 XXX + SG_ ColPrSysCustReq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ ExtHlStrAssCsStRq : 5|3@0+ (1,0) [0|7] "" XXX + SG_ IntDimSeldClrTypStReq : 12|5@0+ (1,0) [0|31] "" XXX + SG_ HLOCCstSetReq : 15|3@0+ (1,0) [0|7] "" XXX + SG_ IntDimSeldAnmTypStReq : 19|4@0+ (1,0) [0|15] "" XXX + SG_ SmPhRmFunCstStReq : 22|3@0+ (1,0) [0|7] "" XXX + +BO_ 2155233280 VICM_Info_LS: 8 XXX + SG_ VehRefuelSt : 2|3@0+ (1,0) [0|7] "" XXX + SG_ FlDrOpenIndOn : 3|1@0+ (1,0) [0|1] "" XXX + SG_ UtlChrgPopUpAct : 4|1@0+ (1,0) [0|1] "" XXX + SG_ UtlChrgIntrfrIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ ShftPrkIO_3B2 : 6|1@0+ (1,0) [0|1] "" XXX + SG_ NtrlCstdwnCrtMdActvIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ RtBsChrgCmplnTmPrfRsp : 9|2@0+ (1,0) [0|3] "" XXX + SG_ EngRnngDutoVehSpdIO : 10|1@0+ (1,0) [0|1] "" XXX + SG_ NtrlGrWrngIO : 11|1@0+ (1,0) [0|1] "" XXX + SG_ LftmFuelEcon : 19|12@0+ (0.1,0) [0|409.5] "kilometers/liter" XXX + SG_ LiftimeFuelEcnEquiv : 35|12@0+ (0.1,0) [0|409.5] "km/l" XXX + SG_ ChrgCyclFuelEcn : 51|12@0+ (0.1,0) [0|409.5] "km/l" XXX + +BO_ 2152169472 Coolant_Heater_Status_LS: 3 XXX + SG_ ClntHtrSt : 1|2@0+ (1,0) [0|3] "" XXX + SG_ ClntHtrPCBOvTmpFlt : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ClntHtrHtSnkOvTmpFlt : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ClntHtrElecPwrGroup : 4|13@0+ (1,0) [0|0] "" XXX + SG_ ClntHtrElecPwrV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ClntHtrElecPwr : 15|8@0+ (0.04,0) [0|10.2] "kW" XXX + SG_ ClntHtrFlt : 7|3@0+ (1,0) [0|7] "" XXX + SG_ ClntHtrInltClntTmp : 23|8@0+ (1,-40) [-40|215] "deg C" XXX + +BO_ 2152759296 SITM_Front_Sensor_IO_LS: 1 XXX + SG_ FrtCmrBlckdIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ FrtEOCMMdlFldIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ FrtCmrFldIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ FrtRdrFldIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PedWrnIndReq : 5|2@0+ (1,0) [0|3] "" XXX + +BO_ 2152742912 SITM_Rear_Sensor_IO_LS: 1 XXX + SG_ RrEOCMMdlFldIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RrRdrBlckdIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RrRdrFldIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ShrtRngRdrOffIO : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150891520 Go_Notifier_Req_LS: 5 XXX + SG_ DgtlMapSpdCat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ FwdClnAlrtCustStngReq : 5|3@0+ (1,0) [0|7] "" XXX + SG_ GNCustStngReq : 7|2@0+ (1,0) [0|3] "" XXX + SG_ DgtlMapDrvngSd : 8|1@0+ (1,0) [0|1] "" XXX + SG_ DgtlMapPsgRstrctn : 11|3@0+ (1,0) [0|7] "" XXX + SG_ RrStRmndrCstSetReq : 14|3@0+ (1,0) [0|7] "" XXX + SG_ DgtlMapEffSpdLmt : 20|5@0+ (1,0) [0|31] "" XXX + SG_ DgtlMapEffSpdLmtTyp : 23|3@0+ (1,0) [0|7] "" XXX + SG_ DgtlMapVerYr : 29|6@0+ (1,0) [0|63] "" XXX + SG_ DgtlMapVerQtr : 31|2@0+ (1,0) [0|3] "" XXX + SG_ DgtlMapCndlSpdLmt : 36|5@0+ (1,0) [0|31] "" XXX + SG_ DgtlMapCndlSpdLmtTyp : 39|3@0+ (1,0) [0|7] "" XXX + +BO_ 2151751680 Haptic_Seat_Status_LS: 3 XXX + SG_ CrshAlrtDrvrSlctdType : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CrshAlrtStPrsnt : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HptcStVbnStat : 3|2@0+ (1,0) [0|3] "" XXX + SG_ HptcStFldIO : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155536384 Rear_Virtual_Bmper_Indication_LS: 1 XXX + SG_ RVBDsbldIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RVBEnbldIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RVBFldIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RVBUnblIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvRIMOffUnbIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ RevClnMtgnBrkReqAct : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151481344 CSV_FSRACC_Indications_LS: 1 XXX + SG_ AutoBrkRlsIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ShtToPrkBfExtngVehIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HdUpDsplyUnblIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ FSRACCFrstRsmPrssIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ FrtRdrBlckdIO : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151432192 ACC_Drv_Seat_Vib_Req_IO_LS: 1 XXX + SG_ ACCHptcStVbnRqSeqN : 1|2@0+ (1,0) [0|3] "" XXX + SG_ ACCHptcStVbnReq : 7|6@0+ (1,0) [0|63] "" XXX + +BO_ 2151415808 Ln_Dep_Wrn_Drv_Seat_Vib_Req_LS: 5 XXX + SG_ LDWLftHptcStRqSN : 1|2@0+ (1,0) [0|3] "" XXX + SG_ LDWLftHptcStRq : 7|6@0+ (1,0) [0|63] "" XXX + SG_ LDWRghtHptcStRqSN : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LDWRghtHptcStRq : 15|6@0+ (1,0) [0|63] "" XXX + SG_ LftLnChgThrtHptStRqSN : 17|2@0+ (1,0) [0|3] "" XXX + SG_ LftLnChgThrtHptStRq : 23|6@0+ (1,0) [0|63] "Pulse" XXX + SG_ RgtLnChgThrtHptStRqSN : 25|2@0+ (1,0) [0|3] "" XXX + SG_ RgtLnChgThrtHptStRq : 31|6@0+ (1,0) [0|63] "Pulse" XXX + SG_ FrPedDetCsStAvl : 32|1@0+ (1,0) [0|1] "" XXX + SG_ FrPedDetCsCrStVal : 35|3@0+ (1,0) [0|7] "" XXX + +BO_ 2151350272 Frnt_Prk_Ast_Drv_Seat_Vib_Req_LS: 3 XXX + SG_ FPAHptcStVbnRqSeqN : 1|2@0+ (1,0) [0|3] "" XXX + SG_ FPAHptcStVbnReq : 7|6@0+ (1,0) [0|63] "" XXX + SG_ APAIconDispRq : 10|3@0+ (1,0) [0|7] "" XXX + SG_ APAIconFilPctRq : 22|7@0+ (1,0) [0|127] "" XXX + +BO_ 2151333888 Rear_Prk_Ast_Drv_Seat_Vib_Req_LS: 1 XXX + SG_ RPAHptcStVbRqSeqN : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RPAHptcStVbnReq : 7|6@0+ (1,0) [0|63] "" XXX + +BO_ 2151522304 Reset_FuelLife_Request_LS: 1 XXX + SG_ FuelFltLfRstRqd : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ElEngyEconAvgRstRq : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TCSTmpDsblReqConf : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LnchCtrlRelLnLockReqd : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150629376 CV_System_Failure_LS: 1 XXX + SG_ CVSysFlrIO : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155929600 Diesel_Information_LS: 8 XXX + SG_ DslExFldTpWrngIndRq : 3|4@0+ (1,0) [0|15] "" XXX + SG_ DslExhFldDiagWrnIdRq : 6|3@0+ (1,0) [0|7] "" XXX + SG_ DslExhFldQlyWrngIReq : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DslExhFldWrngIdRqER : 15|4@0+ (1,0) [0|15] "" XXX + SG_ DslExhFluidDistTIndcmt : 22|15@0+ (2,0) [0|65534] "km" XXX + SG_ DslExNxEmWrngIndRq : 35|4@0+ (1,0) [0|15] "" XXX + SG_ DslExFldCnWrngIndRq : 39|4@0+ (1,0) [0|15] "" XXX + SG_ DslExFldWrngVSpdLmt : 47|24@0+ (1,0) [0|0] "" XXX + SG_ DEFWVSL_S1SpdLmt : 47|8@0+ (1,0) [0|255] "km / h" XXX + SG_ DEFWVSL_S2SpdLmt : 55|8@0+ (1,0) [0|255] "km / h" XXX + SG_ DEFWVSL_S3SpdLmt : 63|8@0+ (1,0) [0|255] "km / h" XXX + +BO_ 2154741760 RSA_Status_LS: 1 XXX + SG_ RSAPrsnt : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154807296 Lighting_Customization_Info_3_LS: 4 XXX + SG_ AFLGPSCstCrStVal : 2|3@0+ (1,0) [0|7] "" XXX + SG_ AFLCstCrStVal : 5|3@0+ (1,0) [0|7] "" XXX + SG_ AFLGPSCstStAvl : 6|1@0+ (1,0) [0|1] "" XXX + SG_ AFLCstStAvl : 7|1@0+ (1,0) [0|1] "" XXX + SG_ AFLGPSMnu2CstStAvl : 8|1@0+ (1,0) [0|1] "" XXX + SG_ AFLMnu2CstStAvl : 9|1@0+ (1,0) [0|1] "" XXX + SG_ AFLMnu3CstStAvl : 10|1@0+ (1,0) [0|1] "" XXX + SG_ EngAutoStpNotProb : 11|1@0+ (1,0) [0|1] "" XXX + SG_ ESCMHiEleclLdReqAct : 12|1@0+ (1,0) [0|1] "" XXX + SG_ EngAutoStrtStpInfo : 17|10@0+ (1,0) [0|0] "" XXX + SG_ EASSI_StrtStpSt : 17|2@0+ (1,0) [0|3] "" XXX + SG_ EASSI_UnsdRsrvd2 : 24|1@0+ (1,0) [0|1] "" XXX + SG_ EASSI_TorqDetdIndet : 25|1@0+ (1,0) [0|1] "" XXX + SG_ EASSI_StlDetd : 26|1@0+ (1,0) [0|1] "" XXX + SG_ EASSI_TrqDetd : 27|1@0+ (1,0) [0|1] "" XXX + SG_ EASSI_FuelReqOn : 28|1@0+ (1,0) [0|1] "" XXX + SG_ EASSI_StrtTyp : 31|3@0+ (1,0) [0|7] "" XXX + +BO_ 2151079936 PDIM_Status_LS: 1 XXX + SG_ PDIMPrsnt : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155364352 Hybrid_Information_SuperSlow_LS: 5 XXX + SG_ SvcHybridSysIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ JmpStrtStat : 3|3@0+ (1,0) [0|7] "" XXX + SG_ HybMdDisp : 7|4@0+ (1,0) [0|15] "" XXX + SG_ CstmrUsblSOCGroup : 15|15@0+ (1,0) [0|0] "" XXX + SG_ CstmrUsblSOC : 15|8@0+ (0.39216,0) [0|100.0008] "%" XXX + SG_ CstmrUsblSOCV : 17|1@0+ (1,0) [0|1] "" XXX + SG_ BattCntrlPrcssrVDA : 16|1@0+ (1,0) [0|1] "" XXX + SG_ InstDrvEff : 31|8@0- (0.78125,0) [-100|99.21875] "%" XXX + SG_ ClntCrcFlwRtEst : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + +BO_ 2154979328 Front_Seat_Heat_Cool_Req_LS: 1 XXX + SG_ FrntStVoltBstModReq : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155282432 RearSeat_HeatVent_Cool_LS: 1 XXX + SG_ RrStVoltBstModReq : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151505920 VehInfoTripComputer_LS: 7 XXX + SG_ SpdCurvAdvSysEnbld : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrBrkDsplyAct : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ACCSettingType : 3|2@0+ (1,0) [0|3] "" XXX + SG_ AutoMdSpdLmtCnfrmd : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PTExPrtclFltManRgnRqd : 5|1@0+ (1,0) [0|1] "" XXX + SG_ Trp2OdomtrGroup : 6|55@0+ (1,0) [0|0] "" XXX + SG_ Trp2OdomtrV : 6|1@0+ (1,0) [0|1] "" XXX + SG_ Trp2Odomtr : 38|23@0+ (0.015625,0) [0|131071.984375] "km" XXX + SG_ Trp1OdomtrGroup : 7|32@0+ (1,0) [0|0] "" XXX + SG_ Trp1OdomtrV : 7|1@0+ (1,0) [0|1] "" XXX + SG_ Trp1Odomtr : 14|23@0+ (0.015625,0) [0|131071.984375] "km" XXX + +BO_ 2155896832 Alternative_Fuel_Information_LS: 5 XXX + SG_ FuelMdStat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ AltFuelMdReqDndIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ FlLvlTank2PctGroup : 4|13@0+ (1,0) [0|0] "" XXX + SG_ FlLvlTank2PctV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ FlLvlTank2Pct : 15|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ AltFuelAccWrnngAct : 5|1@0+ (1,0) [0|1] "" XXX + SG_ AltFuelLvlLo : 6|1@0+ (1,0) [0|1] "" XXX + SG_ AltFuelPHeatAct : 7|1@0+ (1,0) [0|1] "" XXX + SG_ FuelTotCapTnk2 : 19|12@0+ (0.125,0) [0|511.875] "liters" XXX + SG_ FuelAlchlCompAdptnPrg : 20|1@0+ (1,0) [0|1] "" XXX + SG_ FuelAlcoholCompGroup : 21|22@0+ (1,0) [0|0] "" XXX + SG_ FuelAlcoholCompV : 21|1@0+ (1,0) [0|1] "" XXX + SG_ FuelAlcoholComp : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + +BO_ 2155552768 Exterior_Lock_Switch_Req_LS: 1 XXX + SG_ PsvEntCmftWndRq : 1|2@0+ (1,0) [0|3] "" XXX + +BO_ 2154496000 Rear_Closure_Soft_Top_Info_LS: 1 XXX + SG_ CmpSftTopMotBfrOpTrnkIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TargaTopStateGroup : 2|2@0+ (1,0) [0|0] "" XXX + SG_ TargaTopState : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TargaTopStateV : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155208704 Power_Conv_Top_Info_LS: 3 XXX + SG_ SftTpAbvWrngSpdIndOn : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpFlrIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpLtcIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpMnlLtchIndOn : 3|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpMchnOvhtIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpRmCrgCrrIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpStrIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpTmpLwIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpTneuCvrIO : 8|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpVehOvSpdIndOn : 9|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpVltLwIO : 10|1@0+ (1,0) [0|1] "" XXX + SG_ CkSoftTpIO : 11|1@0+ (1,0) [0|1] "" XXX + SG_ ClsTrnkLidIO : 12|1@0+ (1,0) [0|1] "" XXX + SG_ FTUpdWndPsLmtEnbld : 13|1@0+ (1,0) [0|1] "" XXX + SG_ VltSwAtvIndOn : 14|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpTrnLmpsRqd : 15|1@0+ (1,0) [0|1] "" XXX + SG_ FldngTpSt : 18|3@0+ (1,0) [0|7] "" XXX + SG_ FldngTpWndCmftRq : 20|2@0+ (1,0) [0|3] "" XXX + SG_ SftTpPlsDnSrtdIndOn : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SftTpPlsDnWrngIndOn : 22|1@0+ (1,0) [0|1] "" XXX + +BO_ 2153390080 Manual_Liftgate_Control_LS: 1 XXX + SG_ RrClosOpenSwAct_2D1Group : 3|3@0+ (1,0) [0|0] "" XXX + SG_ RrClosOpenSwAct_2D1 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RrClosOpenSwAct_2D1V : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155175936 CruiseControlGapSwitch_LS: 1 XXX + SG_ AdptCrsGapSwAct : 1|2@0+ (1,0) [0|3] "" XXX + SG_ AdptCrsLKALDWSwAct : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 2156806144 Cellular_Network_Date_and_Time: 6 XXX + SG_ CldrDayCmpstdVal : 4|5@0+ (1,0) [0|31] "days" XXX + SG_ HrsCmpstdValGroup : 5|30@0+ (1,0) [0|0] "" XXX + SG_ HrsCmpstdValV : 5|1@0+ (1,0) [0|1] "" XXX + SG_ HrsCmpstdVal : 28|5@0+ (1,0) [0|31] "h" XXX + SG_ MinsCmpstdValGroup : 6|39@0+ (1,0) [0|0] "" XXX + SG_ MinsCmpstdValV : 6|1@0+ (1,0) [0|1] "" XXX + SG_ MinsCmpstdVal : 37|6@0+ (1,0) [0|63] "min" XXX + SG_ SecCmpstdValGroup : 7|48@0+ (1,0) [0|0] "" XXX + SG_ SecCmpstdValV : 7|1@0+ (1,0) [0|1] "" XXX + SG_ SecCmpstdVal : 45|6@0+ (1,0) [0|63] "secs" XXX + SG_ CldrMthCmpstdVal : 11|4@0+ (1,0) [0|15] "" XXX + SG_ CellNtwrkDtTmAvl : 12|1@0+ (1,0) [0|1] "" XXX + SG_ CldrYrCmpstdVal : 23|8@0+ (1,2000) [2000|2255] "year" XXX + +BO_ 2154078208 Window_Position_Status_LS: 2 XXX + SG_ DrvWndPosStat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ LRWndPosStat : 5|3@0+ (1,0) [0|7] "" XXX + SG_ PsWndPosStat : 10|3@0+ (1,0) [0|7] "" XXX + SG_ RRWndPosStat : 13|3@0+ (1,0) [0|7] "" XXX + +BO_ 2159058944 ODIEvent_IPC_LS: 3 XXX + SG_ ODIEvntPkt_IPC : 5|22@0+ (1,0) [0|0] "" XXX + SG_ ODIEI_EvID : 5|6@0+ (1,0) [0|63] "" XXX + SG_ ODIEI_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODIEI_MultiFrRetCh : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 2159042560 ODI_DynData_IPC_LS: 8 XXX + SG_ ODIDynData_IPC : 14|55@0+ (1,0) [0|0] "" XXX + SG_ ODDI_InvldData : 8|1@0+ (1,0) [0|1] "" XXX + SG_ ODDI_DataType : 14|6@0+ (1,0) [0|63] "" XXX + SG_ ODDI_FUCID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDI_DataId : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODDI_DataVal : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2150006784 System_Power_Mode_Pushbutton_LS: 1 XXX + SG_ SysPwrMdPshbtnActGroup : 1|2@0+ (1,0) [0|0] "" XXX + SG_ SysPwrMdPshbtnAct : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SysPwrMdPshbtnActV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PEPSRunCrnkRlyDctd : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155216896 Road_Type_Information_LS: 6 XXX + SG_ MpDataAvlbl : 0|1@0+ (1,0) [0|1] "" XXX + SG_ BldUpArDet : 1|1@0+ (1,0) [0|1] "" XXX + SG_ SprtLnRd : 2|1@0+ (1,0) [0|1] "" XXX + SG_ CntrldAccRd : 3|1@0+ (1,0) [0|1] "" XXX + SG_ CurvAdvInd : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SpdLmtPstdSpdGroup : 6|23@0+ (1,0) [0|0] "" XXX + SG_ SpdLmtPstdSpdM : 6|1@0+ (1,0) [0|1] "" XXX + SG_ SpdLmtPstdSpd : 23|8@0+ (1,0) [0|255] "" XXX + SG_ DgtlMapPstdSpdLimAsrd : 7|1@0+ (1,0) [0|1] "" XXX + SG_ FncRdClass : 10|3@0+ (1,0) [0|7] "" XXX + SG_ RdSpdCatType : 12|2@0+ (1,0) [0|3] "" XXX + SG_ LnCat : 14|2@0+ (1,0) [0|3] "" XXX + SG_ SpdLmtUnits : 15|1@0+ (1,0) [0|1] "" XXX + SG_ SpdLmtRecmndSpd : 31|8@0+ (1,0) [0|255] "" XXX + SG_ IntlStdAlph2CddCntryCd : 33|10@0+ (1,0) [0|0] "" XXX + SG_ ISA2CCC_FrstCdChr : 33|5@0+ (1,0) [0|31] "" XXX + SG_ ISA2CCC_ScndCdChr : 44|5@0+ (1,0) [0|31] "" XXX + +BO_ 2156216320 TTY_Status_LS: 1 XXX + SG_ TxtTelephoneDevPr : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2158813184 ODIIndication_IPC_LS: 8 XXX + SG_ ODIInd_IPC : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ODIIIPC_FUCID : 7|8@0+ (1,0) [0|255] "" XXX + SG_ ODIIIPC_ODIInd8 : 8|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd7 : 9|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd6 : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd5 : 11|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd4 : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd3 : 13|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd2 : 14|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd1 : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd16 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd15 : 17|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd14 : 18|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd13 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd12 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd11 : 21|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd10 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd9 : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd24 : 24|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd23 : 25|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd22 : 26|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd21 : 27|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd20 : 28|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd19 : 29|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd18 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd17 : 31|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd32 : 32|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd31 : 33|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd30 : 34|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd29 : 35|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd28 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd27 : 37|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd26 : 38|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd25 : 39|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd40 : 40|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd39 : 41|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd38 : 42|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd37 : 43|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd36 : 44|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd35 : 45|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd34 : 46|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd33 : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd48 : 48|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd47 : 49|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd46 : 50|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd45 : 51|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd44 : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd43 : 53|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd42 : 54|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd41 : 55|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd56 : 56|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd55 : 57|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd54 : 58|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd53 : 59|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd52 : 60|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd51 : 61|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd50 : 62|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIIPC_ODIInd49 : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150277120 GPS_Geographical_Position_LS: 8 XXX + SG_ PsngSysLatGroup : 6|31@0+ (1,0) [0|0] "" XXX + SG_ PsngSysLat : 5|30@0- (1,0) [-536870912|536870911] "mas" XXX + SG_ PsngSysLatV : 6|1@0+ (1,0) [0|1] "" XXX + SG_ PsngSysLongGroup : 39|32@0+ (1,0) [0|0] "" XXX + SG_ PsngSysLong : 38|31@0- (1,0) [-1073741824|1073741823] "mas" XXX + SG_ PsngSysLongV : 39|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150285312 GPS_Elevation_and_Heading_LS: 8 XXX + SG_ PsngSysHdingGroup : 3|37@0+ (1,0) [0|0] "" XXX + SG_ PsngSysHding : 3|12@0+ (0.1,0) [0|409.5] "deg" XXX + SG_ PsngSysHdingV : 47|1@0+ (1,0) [0|1] "" XXX + SG_ PsngSysDilPrcsGroup : 4|29@0+ (1,0) [0|0] "" XXX + SG_ PsngSysDilPrcsV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PsngSysDilPrcs : 17|10@0+ (0.1,0) [0|102.3] "" XXX + SG_ PsngSysCalcSpdGroup : 39|10@0+ (1,0) [0|0] "" XXX + SG_ PsngSysCalcSpd : 39|8@0+ (1,0) [0|255] "km / h" XXX + SG_ PsngSysCalcSpdV : 46|1@0+ (1,0) [0|1] "" XXX + SG_ PsngSysElvtnGroup : 45|22@0+ (1,0) [0|0] "" XXX + SG_ PsngSysElvtn : 44|21@0+ (1,-100000) [-100000|1997151] "cm" XXX + SG_ PsngSysElvtnV : 45|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151890944 Telematics_Indication_Request_LS: 4 XXX + SG_ TlmtcsIndCntrlReq : 15|24@0+ (1,0) [0|0] "" XXX + SG_ TICR_Ind1Cnt : 11|4@0+ (1,0) [0|15] "" XXX + SG_ TICR_Ind1 : 13|2@0+ (1,0) [0|3] "" XXX + SG_ TICR_Ind1Req : 15|2@0+ (1,0) [0|3] "" XXX + SG_ TICR_Ind1FlshRtOff : 23|8@0+ (10,0) [0|2550] "ms" XXX + SG_ TICR_Ind1FlshRtOn : 31|8@0+ (10,0) [0|2550] "ms" XXX + +BO_ 2151251968 Telematics_Indication_Control_LS: 4 XXX + SG_ TlmtcsIndCntrlStat : 12|21@0+ (1,0) [0|0] "" XXX + SG_ TICS_Ind1V : 8|1@0+ (1,0) [0|1] "" XXX + SG_ TICS_Ind1 : 10|2@0+ (1,0) [0|3] "" XXX + SG_ TICS_Ind1Stat : 12|2@0+ (1,0) [0|3] "" XXX + SG_ TICS_Ind1FlshRtOffSt : 23|8@0+ (10,0) [0|2550] "ms" XXX + SG_ TICS_Ind1FlshRtOnSt : 31|8@0+ (10,0) [0|2550] "ms" XXX + +BO_ 2155495424 Remote_Start_Seat_Request_LS: 1 XXX + SG_ RmStrCldStEnReq : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RmStrHtdStEnRq : 1|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149990400 HS_Indications_Fast_LS: 8 XXX + SG_ ABSIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ StpOnBrkToRelPBIndOn : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrBrkngVDA : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DrvThrtlOvrdIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ TreInfMonSysRstPrfmd : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ACCHdwayStngIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ ACCDrvrSeltdSpdIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrWiringFltIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ AdvHlmpsVDA : 9|1@0+ (1,0) [0|1] "" XXX + SG_ SADmpVDA : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ScndryAxleVDA : 11|1@0+ (1,0) [0|1] "" XXX + SG_ SrvTrlrBrkngSysIO : 12|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrBrkngGainSetIO : 13|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrCnctdIO : 14|1@0+ (1,0) [0|1] "" XXX + SG_ ChkTrlrIO : 15|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrBrkngFrcOtpt : 23|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ TrlrBrkngGainSet : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ TrlrHtchSwAtv_ITBC : 32|1@0+ (1,0) [0|1] "" XXX + SG_ TransNtrlCntrlMdStat : 34|2@0+ (1,0) [0|3] "" XXX + SG_ MotStBltFldIO : 35|1@0+ (1,0) [0|1] "" XXX + SG_ MotStBltUnblIO : 36|1@0+ (1,0) [0|1] "" XXX + SG_ TrnsfrCsRngShfSpdLmt : 47|8@0+ (1,0) [0|255] "km / h" XXX + SG_ InstFuelConsmpRate : 51|12@0+ (0.025,0) [0|102.375] "liters/hr" XXX + SG_ SecAxlOperMod : 55|4@0+ (1,0) [0|15] "" XXX + +BO_ 2155380736 HS_Indications_SuperSlow_LS: 6 XXX + SG_ VehOvrLdIndOn : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SrvLevSysIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HdLtLvlFlrIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RrLevVDA : 3|1@0+ (1,0) [0|1] "" XXX + SG_ AirCndOffIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ EngOilHotIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ PTExPrtclFltrWrnIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ DslGlwPlgIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ EngHotFuelEnrchmntIO : 8|1@0+ (1,0) [0|1] "" XXX + SG_ EngOilChngIO : 9|1@0+ (1,0) [0|1] "" XXX + SG_ EngOilLvlLwIO : 10|1@0+ (1,0) [0|1] "" XXX + SG_ EngOilPrsLwIO : 11|1@0+ (1,0) [0|1] "" XXX + SG_ EngWtrInFlIO : 12|1@0+ (1,0) [0|1] "" XXX + SG_ RdcdPwrIO : 13|1@0+ (1,0) [0|1] "" XXX + SG_ CkFlFilrCapIO : 14|1@0+ (1,0) [0|1] "" XXX + SG_ EngHt_StpEngIO : 15|1@0+ (1,0) [0|1] "" XXX + SG_ StrAsstRdcdLvl2IO : 16|1@0+ (1,0) [0|1] "" XXX + SG_ PwrStrIO : 17|1@0+ (1,0) [0|1] "" XXX + SG_ PTExPrtclFltrWrn2IO : 18|1@0+ (1,0) [0|1] "" XXX + SG_ AdvFrntLghtSysIndRq : 21|3@0+ (1,0) [0|7] "" XXX + SG_ StrngAsstRdcdIO : 22|1@0+ (1,0) [0|1] "" XXX + SG_ StrAsstRdcdLvl3IO : 23|1@0+ (1,0) [0|1] "" XXX + SG_ PwrPckAirInTempFlt : 31|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ PwrPkFnSpd : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ ARSFlrIO : 40|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150498304 Analog_Values_Slow_LS: 8 XXX + SG_ EngCltTmpGroup : 0|57@0+ (1,0) [0|0] "" XXX + SG_ EngCltTmpV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ EngCltTmp : 63|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ EngIntAirTmpGroup : 1|50@0+ (1,0) [0|0] "" XXX + SG_ EngIntAirTmpV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ EngIntAirTmp : 55|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ EngOilTmpGroup : 2|43@0+ (1,0) [0|0] "" XXX + SG_ EngOilTmpV : 2|1@0+ (1,0) [0|1] "" XXX + SG_ EngOilTmp : 47|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ OAT_PT_EstGroup : 4|37@0+ (1,0) [0|0] "" XXX + SG_ OAT_PT_EstV : 3|1@0+ (1,0) [0|1] "" XXX + SG_ OAT_PT_EstM : 4|1@0+ (1,0) [0|1] "" XXX + SG_ OAT_PT_Est : 39|8@0+ (0.5,-40) [-40|87.5] "deg C" XXX + SG_ TrnOilTmpGroup : 5|30@0+ (1,0) [0|0] "" XXX + SG_ TrnOilTmpV : 5|1@0+ (1,0) [0|1] "" XXX + SG_ TrnOilTmp : 31|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ BarPrsAbsGroup : 6|23@0+ (1,0) [0|0] "" XXX + SG_ BarPrsAbsV : 6|1@0+ (1,0) [0|1] "" XXX + SG_ BarPrsAbs : 23|8@0+ (0.5,0) [0|127.5] "kPa" XXX + SG_ EngOilPrsGroup : 7|16@0+ (1,0) [0|0] "" XXX + SG_ EngOilPrsV : 7|1@0+ (1,0) [0|1] "" XXX + SG_ EngOilPrs : 15|8@0+ (4,0) [0|1020] "kPa" XXX + +BO_ 2151047168 HUD_Status_LS: 1 XXX + SG_ HUDActv : 0|1@0+ (1,0) [0|1] "" XXX + SG_ HdUpDspAnmtStat : 3|3@0+ (1,0) [0|7] "" XXX + +BO_ 2155331584 Wheel_Pulses_LS: 4 XXX + SG_ WhlPlsPerRevDrvn : 6|7@0+ (1,0) [0|127] "" XXX + SG_ WhlPlsPerRevNonDrvn : 14|7@0+ (1,0) [0|127] "" XXX + SG_ WhlRotStatTmstmpRes : 18|11@0+ (0.002,0) [0|4.094] "uSec" XXX + +BO_ 2154225664 Door_Handle_Switch_Status_LS: 1 XXX + SG_ DrvDrHndleSwAtv : 0|1@0+ (1,0) [0|1] "" XXX + SG_ PasDrHndleSwAtv : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RCHndleSwAtv : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RRDrHndleSwAtv : 3|1@0+ (1,0) [0|1] "" XXX + SG_ RLDrHndleSwAtv : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149900288 Telematics_Contol_LS: 3 XXX + SG_ EnhSrvRClsRlsRq : 1|1@0+ (1,0) [0|1] "" XXX + SG_ EnhSrvVisAlRq : 3|2@0+ (1,0) [0|3] "" XXX + SG_ EnhSrvAudAlRq : 5|2@0+ (1,0) [0|3] "" XXX + SG_ EnhSrvRmStrtRq : 7|2@0+ (1,0) [0|3] "" XXX + SG_ EnhSrvLckRq : 10|3@0+ (1,0) [0|7] "" XXX + SG_ BTTethrngPrngReq : 14|4@0+ (1,0) [0|15] "" XXX + SG_ EnhSvVehTopSpdLim : 23|8@0+ (2,0) [0|510] "km / h" XXX + +BO_ 2159001600 ODIEnumDynamicData_IPC_LS: 8 XXX + SG_ ODIEnmDynData_IPC : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODIEDDIPC_Data2Value : 2|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data1Value : 5|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data5Value : 9|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data4Value : 12|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data3Value : 15|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data8Value : 16|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data7Value : 19|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data6Value : 22|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data10Value : 26|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data9Value : 29|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data13Value : 33|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data12Value : 36|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data11Value : 39|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data16Value : 40|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data15Value : 43|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data14Value : 46|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data18Value : 50|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_Data17Value : 53|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDIPC_FUCID : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2158993408 ODIEnumDynamicData_CntrStack_LS: 8 XXX + SG_ ODIEnmDynData_CenterStack : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODIEDDCS_Data2Value : 2|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data1Value : 5|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data5Value : 9|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data4Value : 12|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data3Value : 15|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data8Value : 16|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data7Value : 19|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data6Value : 22|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data10Value : 26|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data9Value : 29|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data13Value : 33|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data12Value : 36|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data11Value : 39|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data16Value : 40|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data15Value : 43|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data14Value : 46|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data18Value : 50|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_Data17Value : 53|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDDCS_FUCID : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2154708992 Audio_Master_Source_Status_LS: 2 XXX + SG_ AudSrcStat2 : 3|12@0+ (1,0) [0|0] "" XXX + SG_ ASS2AudSrcType : 3|5@0+ (1,0) [0|31] "" XXX + SG_ ASS2AudSrcStatCode : 11|4@0+ (1,0) [0|15] "" XXX + SG_ ASS2AudSrcChType : 14|3@0+ (1,0) [0|7] "" XXX + +BO_ 2158985216 ODIDynDataMultiReq_OTIM_LS: 8 XXX + SG_ ODIDynDataMltRq_OTIM : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODDMO_DataID2Vld : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMO_DataID3Vld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMO_DataID4Vld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMO_DataID5Vld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMO_ReqType : 5|2@0+ (1,0) [0|3] "" XXX + SG_ ODDMO_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMO_DispMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMO_DataID1 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMO_DataID2 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMO_DataID3 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMO_DataID4 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMO_DataID5 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2154471424 Rear_Closure_Ajar_Switch_Status: 1 XXX + SG_ RrClosAjarSwAct : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RrClsrSnwLdIO : 1|1@0+ (1,0) [0|1] "" XXX + +BO_ 2159149056 ODI_TEL_2_CenterStack_LS: 8 XXX + SG_ ODI_TEL2CntrStck : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159116288 ODI_TEL_2_AuxIP_LS: 8 XXX + SG_ ODI_TEL2AxIP : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2158796800 ODIIndication_LS: 8 XXX + SG_ ODIInd : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ODII_FUCID : 7|8@0+ (1,0) [0|255] "" XXX + SG_ ODII_ODIInd8 : 8|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd7 : 9|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd6 : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd5 : 11|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd4 : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd3 : 13|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd2 : 14|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd1 : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd16 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd15 : 17|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd14 : 18|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd13 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd12 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd11 : 21|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd10 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd9 : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd24 : 24|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd23 : 25|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd22 : 26|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd21 : 27|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd20 : 28|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd19 : 29|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd18 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd17 : 31|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd32 : 32|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd31 : 33|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd30 : 34|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd29 : 35|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd28 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd27 : 37|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd26 : 38|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd25 : 39|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd40 : 40|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd39 : 41|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd38 : 42|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd37 : 43|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd36 : 44|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd35 : 45|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd34 : 46|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd33 : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd48 : 48|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd47 : 49|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd46 : 50|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd45 : 51|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd44 : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd43 : 53|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd42 : 54|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd41 : 55|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd56 : 56|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd55 : 57|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd54 : 58|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd53 : 59|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd52 : 60|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd51 : 61|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd50 : 62|1@0+ (1,0) [0|1] "" XXX + SG_ ODII_ODIInd49 : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 2158755840 ODIEvent_LS: 4 XXX + SG_ ODIEvntPkt : 13|22@0+ (1,0) [0|0] "" XXX + SG_ ODIE_EvID : 13|6@0+ (1,0) [0|63] "" XXX + SG_ ODIE_FUCID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODIE_MultiFrRetCh : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 2159157248 ODI_CenterStack_2_TEL_LS: 8 XXX + SG_ ODI_CntrStck2TEL : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2153955328 Infrastructure_Timer_Status_LS: 5 XXX + SG_ EngOffTmExtRngGroup : 0|33@0+ (1,0) [0|0] "" XXX + SG_ EngOffTmExtRngV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ EngOffTmExtRng : 39|8@0+ (4,0) [0|1020] "min" XXX + SG_ ElpsdTimeCntRstOcc : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ElpsdTimeCnt : 15|24@0+ (1,0) [0|16777215] "min" XXX + +BO_ 2151063552 Infotainment_Operation_LS: 7 XXX + SG_ InftnOprAlwd : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ValetMdAct : 1|1@0+ (1,0) [0|1] "" XXX + SG_ Frnt360CamSwAct : 2|1@0+ (1,0) [0|1] "" XXX + SG_ CamVideoICSDispAct : 3|1@0+ (1,0) [0|1] "" XXX + SG_ LRStStatDispAct : 4|1@0+ (1,0) [0|1] "" XXX + SG_ RRStStatDispAct : 5|1@0+ (1,0) [0|1] "" XXX + SG_ TrgdVidRecSwAct : 6|1@0+ (1,0) [0|1] "" XXX + SG_ RrPedDetCstStReq : 10|3@0+ (1,0) [0|7] "" XXX + SG_ IntrStopAlrtCsSetReq : 13|3@0+ (1,0) [0|7] "" XXX + SG_ ICSTchStat : 17|34@0+ (1,0) [0|0] "" XXX + SG_ ICSTS_TchPrxmty : 17|2@0+ (1,0) [0|3] "" XXX + SG_ ICSTS_X1TchCrdnt : 31|16@0+ (0.001526,0) [0|100] "" XXX + SG_ ICSTS_Y1TchCrdnt : 47|16@0+ (0.001526,0) [0|100] "" XXX + SG_ TrfRdsdInfCsStReq : 20|3@0+ (1,0) [0|7] "" XXX + SG_ CntdVehBrAltCsStReq : 23|3@0+ (1,0) [0|7] "" XXX + +BO_ 2157985792 Fob_Programming_Request_LS: 1 XXX + SG_ FobProgEvntRqd : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151284736 Park_Assistant_General_Status: 1 XXX + SG_ PrkAsstClnPrkAstIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAsstDisablIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstFld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstSnrsBlk : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstSnsDistrbdIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvPrkAstOffUnbIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAstOprtrDsrdStat_1D0 : 7|2@0+ (1,0) [0|3] "" XXX + +BO_ 2159099904 ODI_DAB_2_AuxIP_LS: 8 XXX + SG_ ODI_DAB2AxIP : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159067136 ODI_DAB_2_IPC_LS: 8 XXX + SG_ ODI_DAB2IPC : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159206400 ODI_AuxIP_2_IPC_LS: 8 XXX + SG_ ODI_AxIP2IPC : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159198208 ODI_IPC_2_AuxIP_LS: 8 XXX + SG_ ODI_IPC2AxIP : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159190016 ODI_AuxIP_2_CenterStack_LS: 8 XXX + SG_ ODI_AxIP2CntrStck : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159181824 ODI_CenterStack_2_AuxIP_LS: 8 XXX + SG_ ODI_CntrStck2AxIP : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159173632 ODI_IPC_2_CenterStack_LS: 8 XXX + SG_ ODI_IPC2CntrStck : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159165440 ODI_CenterStack_2_IPC_LS: 8 XXX + SG_ ODI_CntrStck2IPC : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159108096 ODI_AuxIP_2_DAB_LS: 8 XXX + SG_ ODI_AxIP2DAB : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159075328 ODI_IPC_2_DAB_LS: 8 XXX + SG_ ODI_IPC2DAB : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2151718912 Chime_Active: 1 XXX + SG_ ChmAct : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ChmVolSt : 2|2@0+ (1,0) [0|3] "" XXX + +BO_ 2155479040 Customization_Setting_Request_LS: 5 XXX + SG_ DrvlnCustStngReq : 2|3@0+ (1,0) [0|7] "" XXX + SG_ RstrCustFctrDef : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PedFrndlyAlrtCsStReq : 6|3@0+ (1,0) [0|7] "" XXX + SG_ SusCustStngReq : 10|3@0+ (1,0) [0|7] "" XXX + SG_ StrCustStngReq : 13|3@0+ (1,0) [0|7] "" XXX + SG_ ElvtdIdlCstStReq : 15|2@0+ (1,0) [0|3] "" XXX + SG_ SndPerfMdCsStRq : 18|3@0+ (1,0) [0|7] "" XXX + SG_ DispPerfMdCsStRq : 21|3@0+ (1,0) [0|7] "" XXX + SG_ ACCPerfMdCsStReq : 26|3@0+ (1,0) [0|7] "" XXX + SG_ DrvrStPerfMdCsStReq : 29|3@0+ (1,0) [0|7] "" XXX + SG_ PsngStPerfMdCsStReq : 34|3@0+ (1,0) [0|7] "" XXX + SG_ DrvStyPerfMdCsStReq : 37|3@0+ (1,0) [0|7] "" XXX + +BO_ 2151383040 Reset_TP_request_LS: 1 XXX + SG_ TreInfMonSysRstReq : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155421696 Passive_Entry_Challenge_LS: 5 XXX + SG_ PsvEntChlng : 7|32@0+ (1,0) [0|4294967295] "passwrd" XXX + SG_ ServKylsStSysIO : 32|1@0+ (1,0) [0|1] "" XXX + SG_ PsvEntApprchDtcd : 33|1@0+ (1,0) [0|1] "" XXX + SG_ PsvEntAprchDrctn : 36|3@0+ (1,0) [0|7] "" XXX + SG_ PsvEntApprchCnfgReq : 39|3@0+ (1,0) [0|7] "" XXX + +BO_ 2155413504 Drv_Dr_Key_Cyl_Status_LS: 3 XXX + SG_ DrvrDrKeyCylUlkSwActGroup : 1|2@0+ (1,0) [0|0] "" XXX + SG_ DrvrDrKeyCylUlkSwAct : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DrvrDrKeyCylUlkSwActV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PsvLckngReqd : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PsvApprchVehId : 15|16@0+ (1,0) [0|65535] "" XXX + +BO_ 2159026176 ODIDynamicData_LS: 8 XXX + SG_ ODIDynData : 14|55@0+ (1,0) [0|0] "" XXX + SG_ ODD_InvldData : 8|1@0+ (1,0) [0|1] "" XXX + SG_ ODD_DataType : 14|6@0+ (1,0) [0|63] "" XXX + SG_ ODD_FUCID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODD_DataId : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODD_DataVal : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2158936064 ODIEnumDynamicData_LS: 8 XXX + SG_ ODIEnmDynData : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODIEDD_Data2Value : 2|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data1Value : 5|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data5Value : 9|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data4Value : 12|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data3Value : 15|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data8Value : 16|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data7Value : 19|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data6Value : 22|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data10Value : 26|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data9Value : 29|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data13Value : 33|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data12Value : 36|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data11Value : 39|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data16Value : 40|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data15Value : 43|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data14Value : 46|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data18Value : 50|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_Data17Value : 53|3@0+ (1,0) [0|7] "" XXX + SG_ ODIEDD_FUCID : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2158845952 ODIAction_CntrStack_LS: 8 XXX + SG_ ODIActn_CntrStck : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODIAC_DaTy : 5|6@0+ (1,0) [0|63] "" XXX + SG_ ODIAC_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAC_ActnID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAC_DspMID : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAC_ActnVal : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2158886912 ODIDynDataListRequest_IPC_LS: 8 XXX + SG_ ODIDynDataLstRq_IPC : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ODDLI_FUCID : 7|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLI_DataId : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLI_DspMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLI_ReqDir : 24|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLI_NmEntries : 31|7@0+ (1,0) [0|127] "" XXX + SG_ ODDLI_Idx : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ODDLI_SubIdReqM : 51|12@0+ (1,0) [0|4095] "" XXX + SG_ ODDLI_WrpArnd : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLI_BckgndFlag : 53|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLI_ReqType : 55|2@0+ (1,0) [0|3] "" XXX + +BO_ 2151366656 Man_Prk_Brk_LS: 1 XXX + SG_ RrAxlLckIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ FrntAxlLckIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PrkBrkSwAtv : 2|1@0+ (1,0) [0|1] "" XXX + SG_ AxlLcksServIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ AxlLckUnavailIndReq : 6|3@0+ (1,0) [0|7] "" XXX + SG_ AxlLcksVDA : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149842944 Vehicle_Stability_LS: 8 XXX + SG_ IMUProtLonAccGroup : 2|11@0+ (1,0) [0|0] "" XXX + SG_ IMUProtLonAcc : 1|10@0- (0.03,0) [-15.36|15.33] "m/s^2" XXX + SG_ IMUProtLonAccV : 2|1@0+ (1,0) [0|1] "" XXX + SG_ TCSysAtv : 3|1@0+ (1,0) [0|1] "" XXX + SG_ BrkSysAutBrkFld : 4|1@0+ (1,0) [0|1] "" XXX + SG_ VSEAct : 5|1@0+ (1,0) [0|1] "" XXX + SG_ StrWhAngGroup : 6|47@0+ (1,0) [0|0] "" XXX + SG_ StrWhAngV : 6|1@0+ (1,0) [0|1] "" XXX + SG_ StrWhAng : 39|16@0- (0.0625,0) [-2048|2047.9375] "deg" XXX + SG_ StWhAnVDA : 7|1@0+ (1,0) [0|1] "" XXX + SG_ VehStabEnhmntStat : 18|3@0+ (1,0) [0|7] "" XXX + SG_ VehStabEnhmntMd : 21|3@0+ (1,0) [0|7] "" XXX + SG_ StrWhlAngSenCalStat : 23|2@0+ (1,0) [0|3] "" XXX + SG_ TCSysOpMd : 26|3@0+ (1,0) [0|7] "" XXX + SG_ TCSysOpStat : 29|3@0+ (1,0) [0|7] "" XXX + SG_ VSELatAccGroup : 52|13@0+ (1,0) [0|0] "" XXX + SG_ VSELatAcc : 51|12@0- (0.015625,0) [-32|31.984375] "m/s^2" XXX + SG_ VSELatAccV : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AdptDrvrSeatStng : 55|3@0+ (1,0) [0|7] "" XXX + +BO_ 2159132672 ODIAction_RearSeat_LS: 8 XXX + SG_ ODIActn_RSD : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODIAR_DaTy : 5|6@0+ (1,0) [0|63] "" XXX + SG_ ODIAR_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAR_ActnID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAR_DspMID : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAR_ActnVal : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2158968832 ODI_RearSeat_2_Centerstack_LS: 8 XXX + SG_ ODI_RSD2CntrStck : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2158960640 ODIIndication_Centerstack_LS: 8 XXX + SG_ ODIInd_CntrStck : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ODIIC_FUCID : 7|8@0+ (1,0) [0|255] "" XXX + SG_ ODIIC_ODIInd8 : 8|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd7 : 9|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd6 : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd5 : 11|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd4 : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd3 : 13|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd2 : 14|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd1 : 15|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd16 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd15 : 17|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd14 : 18|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd13 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd12 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd11 : 21|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd10 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd9 : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd24 : 24|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd23 : 25|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd22 : 26|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd21 : 27|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd20 : 28|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd19 : 29|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd18 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd17 : 31|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd32 : 32|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd31 : 33|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd30 : 34|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd29 : 35|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd28 : 36|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd27 : 37|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd26 : 38|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd25 : 39|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd40 : 40|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd39 : 41|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd38 : 42|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd37 : 43|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd36 : 44|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd35 : 45|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd34 : 46|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd33 : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd48 : 48|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd47 : 49|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd46 : 50|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd45 : 51|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd44 : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd43 : 53|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd42 : 54|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd41 : 55|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd56 : 56|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd55 : 57|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd54 : 58|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd53 : 59|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd52 : 60|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd51 : 61|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd50 : 62|1@0+ (1,0) [0|1] "" XXX + SG_ ODIIC_ODIInd49 : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 2158977024 ODIEvent_Centerstack_LS: 4 XXX + SG_ ODIEvntPkt_CntrStck : 13|22@0+ (1,0) [0|0] "" XXX + SG_ ODIEC_EvID : 13|6@0+ (1,0) [0|63] "" XXX + SG_ ODIEC_FUCID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODIEC_MultiFrRetCh : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 2158952448 ODIDynDataMultiReq_RearSeat_LS: 8 XXX + SG_ ODIDynDataMltRq_RSD : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODDMR_DataID2Vld : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMR_DataID3Vld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMR_DataID4Vld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMR_DataID5Vld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMR_ReqType : 5|2@0+ (1,0) [0|3] "" XXX + SG_ ODDMR_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMR_DispMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMR_DataID1 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMR_DataID2 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMR_DataID3 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMR_DataID4 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMR_DataID5 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2158944256 ODIDynDataListReq_RearSeat_LS: 8 XXX + SG_ ODIDynDataLstRq_RSD : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ODDLR_FUCID : 7|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLR_DataId : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLR_DspMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLR_ReqDir : 24|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLR_NmEntries : 31|7@0+ (1,0) [0|127] "" XXX + SG_ ODDLR_Idx : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ODDLR_SubIdReqM : 51|12@0+ (1,0) [0|4095] "" XXX + SG_ ODDLR_WrpArnd : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLR_BckgndFlag : 53|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLR_ReqType : 55|2@0+ (1,0) [0|3] "" XXX + +BO_ 2158927872 ODI_DynData_CenterStack_LS: 8 XXX + SG_ ODIDynData_CntrStck : 14|55@0+ (1,0) [0|0] "" XXX + SG_ ODDC_InvldData : 8|1@0+ (1,0) [0|1] "" XXX + SG_ ODDC_DataType : 14|6@0+ (1,0) [0|63] "" XXX + SG_ ODDC_FUCID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDC_DataId : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODDC_DataVal : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2158895104 ODI_CenterStack_2_RearSeat_LS: 8 XXX + SG_ ODI_CntrStck2RSD : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2152038400 Infomatics_Response_Payload_LS: 8 XXX + SG_ InfMdRspPld : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2152022016 Infomatics_Metadata_Response_LS: 7 XXX + SG_ InfMdRspCmplt : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ InfMdRspInf : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ InfMdStRsp : 35|4@0+ (1,0) [0|15] "" XXX + SG_ AudSelctdSrcReq : 44|5@0+ (1,0) [0|31] "" XXX + SG_ AudSysVolSetCtrl : 55|8@0+ (1,0) [0|0] "" XXX + SG_ ASVSC_ReqEnbld : 48|1@0+ (1,0) [0|1] "" XXX + SG_ ASVSC_VolReq : 55|7@0+ (0.787402,0) [0|100.000054] "" XXX + +BO_ 2152005632 Infomatics_Request_Payload_LS: 8 XXX + SG_ InfMdRqstPld : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2151989248 Infomatics_Metadata_Request_LS: 5 XXX + SG_ InfMdRqstCmplt : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ InfMdRqstInt : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ InfMdStReq : 35|4@0+ (1,0) [0|15] "" XXX + +BO_ 2151972864 Fuel_Level_Status_LS: 4 XXX + SG_ FuelLvlLwIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ LnchCtrlMdReq : 2|2@0+ (1,0) [0|3] "" XXX + SG_ LnchCtrlWhlSlpReq : 7|5@0+ (1,0) [0|31] "" XXX + SG_ VehFuelRngCalcGroup : 9|18@0+ (1,0) [0|0] "" XXX + SG_ VehFuelRngCalc : 8|17@0+ (0.015625,0) [0|2047.984375] "km" XXX + SG_ VehFuelRngCalcV : 9|1@0+ (1,0) [0|1] "" XXX + SG_ LnchCtrlEngRPMReq : 15|6@0+ (1,0) [0|63] "" XXX + +BO_ 2154528768 Wheel_Grnd_Velocity_LS: 8 XXX + SG_ WhlGrndVlctyLftDrvnGroup : 6|15@0+ (1,0) [0|0] "" XXX + SG_ WhlGrndVlctyLftDrvn : 5|14@0+ (0.03125,0) [0|511.96875] "km / h" XXX + SG_ WhlGrndVlctyLftDrvnV : 6|1@0+ (1,0) [0|1] "" XXX + SG_ WhlGrndVlctyLftNnDrvnGroup : 22|15@0+ (1,0) [0|0] "" XXX + SG_ WhlGrndVlctyLftNnDrvn : 21|14@0+ (0.03125,0) [0|511.96875] "km / h" XXX + SG_ WhlGrndVlctyLftNnDrvnV : 22|1@0+ (1,0) [0|1] "" XXX + SG_ WhlGrndVlctyRtDrvnGroup : 38|15@0+ (1,0) [0|0] "" XXX + SG_ WhlGrndVlctyRtDrvn : 37|14@0+ (0.03125,0) [0|511.96875] "km / h" XXX + SG_ WhlGrndVlctyRtDrvnV : 38|1@0+ (1,0) [0|1] "" XXX + SG_ WhlGrndVlctyRtNnDrvnGroup : 54|15@0+ (1,0) [0|0] "" XXX + SG_ WhlGrndVlctyRtNnDrvn : 53|14@0+ (0.03125,0) [0|511.96875] "km / h" XXX + SG_ WhlGrndVlctyRtNnDrvnV : 54|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150916096 Park_Heater_Info_LS: 4 XXX + SG_ PrkHtrAtv : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ClntCircPmpAct : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PrkHtrCoolntTempGroup : 2|11@0+ (1,0) [0|0] "" XXX + SG_ PrkHtrCoolntTempV : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PrkHtrCoolntTemp : 15|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ PrkHtrFlCsmdRlCntRsOc : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PrkHtrFlCnsmdRolCntGroup : 4|29@0+ (1,0) [0|0] "" XXX + SG_ PrkHtrFlCnsmdRolCntV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PrkHtrFlCnsmdRolCnt : 23|16@0+ (3.05176E-006,0) [0|0.1999970916] "liters" XXX + SG_ PrkHtrPrhtAch : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150367232 Immobilizer_Identifier_LS: 5 XXX + SG_ ImoId : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ LrnEnvId : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ LrnEnvIdSt : 32|1@0+ (1,0) [0|1] "" XXX + SG_ ImoIdSt : 33|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150621184 Keyless_Start_Auth_LS: 1 XXX + SG_ KylsStrAuthRslt : 7|8@0+ (1,0) [0|0] "" XXX + SG_ KSARUID8 : 0|1@0+ (1,0) [0|1] "" XXX + SG_ KSARUID7 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ KSARUID6 : 2|1@0+ (1,0) [0|1] "" XXX + SG_ KSARUID5 : 3|1@0+ (1,0) [0|1] "" XXX + SG_ KSARUID4 : 4|1@0+ (1,0) [0|1] "" XXX + SG_ KSARUID3 : 5|1@0+ (1,0) [0|1] "" XXX + SG_ KSARUID2 : 6|1@0+ (1,0) [0|1] "" XXX + SG_ KSARUID1 : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151309312 Inflatable_Restraints_Key_Id_LS: 2 XXX + SG_ InflRestId : 7|16@0+ (1,0) [0|39321] "" XXX + +BO_ 2154061824 Window_Normalized_Indication_LS: 1 XXX + SG_ PsWndNtNrmIndOn : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DrWndNtNrmIndOn : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RLWndNtNrmIndOn : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RRWndNtNrmIndOn : 3|1@0+ (1,0) [0|1] "" XXX + SG_ RmtWndMvmntAtv : 4|1@0+ (1,0) [0|1] "" XXX + SG_ WndOprAlwd : 5|1@0+ (1,0) [0|1] "" XXX + SG_ RrDrUnlckIO : 6|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154512384 Rear_Closure_Rel_Sw_Sta_LS: 1 XXX + SG_ RrClosRelSwActGroup : 1|2@0+ (1,0) [0|0] "" XXX + SG_ RrClosRelSwAct : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RrClosRelSwActV : 1|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155347968 HS_Indications_Slow_LS: 8 XXX + SG_ ActVbnCtrlMlfIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ PedtrnProtSysDpl : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TirePrsLowIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ACCUnavlbleDTWthrIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EngOilStrvtnIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ SecAxlNonEmMalfIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ BrkFldLvlLwGroup : 7|4@0+ (1,0) [0|0] "" XXX + SG_ BrkFldLvlLwV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ BrkFldLvlLw : 7|1@0+ (1,0) [0|1] "" XXX + SG_ ACCSnsClnRqdIO : 8|1@0+ (1,0) [0|1] "" XXX + SG_ ACCTmpUnavlbleIO : 9|1@0+ (1,0) [0|1] "" XXX + SG_ EngRecmndUpshftIO : 10|1@0+ (1,0) [0|1] "" XXX + SG_ ServAdpCrsCtrlIndOn : 11|1@0+ (1,0) [0|1] "" XXX + SG_ SrvSuspSysIO : 12|1@0+ (1,0) [0|1] "" XXX + SG_ BrkPadWrnIO : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BrkSysMalFuncIndOn : 15|1@0+ (1,0) [0|1] "" XXX + SG_ EngEmsRelMalfIndReq : 18|3@0+ (1,0) [0|7] "" XXX + SG_ RrAxlMalfIO : 19|1@0+ (1,0) [0|1] "" XXX + SG_ DrShftCntrlReqDndIO : 20|1@0+ (1,0) [0|1] "" XXX + SG_ CompOvrhtIndOn : 21|1@0+ (1,0) [0|1] "" XXX + SG_ TrnsSkpShftIO : 22|1@0+ (1,0) [0|1] "" XXX + SG_ RrAxlTmpInhIO : 23|1@0+ (1,0) [0|1] "" XXX + SG_ SecAxlTmpInhIO : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CPSAlrtOnlIO : 25|1@0+ (1,0) [0|1] "" XXX + SG_ EPBSysStatIndReq : 27|2@0+ (1,0) [0|3] "" XXX + SG_ EPBSysWrnIndReq : 29|2@0+ (1,0) [0|3] "" XXX + SG_ CPSFldIO : 30|1@0+ (1,0) [0|1] "" XXX + SG_ CPSOffIO : 31|1@0+ (1,0) [0|1] "" XXX + SG_ CPSUnblIO : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SrvPedtrnProtSysIO : 33|1@0+ (1,0) [0|1] "" XXX + SG_ PedtrnProtSysDisbld : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PedtrnProtVDA : 35|1@0+ (1,0) [0|1] "" XXX + SG_ AppCltchAutSrtIO : 36|1@0+ (1,0) [0|1] "" XXX + SG_ StBltTgtSetAvl : 37|1@0+ (1,0) [0|1] "" XXX + SG_ FourWhlDrvIndReq : 42|3@0+ (1,0) [0|7] "" XXX + SG_ EngRecDwnshftIO : 43|1@0+ (1,0) [0|1] "" XXX + SG_ StBltTgtCrtSetVal : 46|3@0+ (1,0) [0|7] "" XXX + SG_ HillDesCtrlRedVehSpIO : 47|1@0+ (1,0) [0|1] "" XXX + SG_ VehRollAngleGroup : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VehRollAngle : 54|7@0+ (0.703125,-45) [-45|44.296875] "deg" XXX + SG_ VehRollAngleV : 55|1@0+ (1,0) [0|1] "" XXX + SG_ ACCPerfMdCsCrStVal : 58|3@0+ (1,0) [0|7] "" XXX + SG_ ACCPerfMdCsStAvl : 59|1@0+ (1,0) [0|1] "" XXX + SG_ DrvrStPerfMdCsCrStVal : 62|3@0+ (1,0) [0|7] "" XXX + SG_ DrvrStPerfMdCsStAvl : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149777408 Non_Drvn_Whl_Rot_Status_LS: 8 XXX + SG_ WhlRotStatLftNDrvn : 7|32@0+ (1,0) [0|0] "" XXX + SG_ WRSLNDWhlDistPCntr : 1|10@0+ (1,0) [0|1023] "counts" XXX + SG_ WRSLNDWhlDistVal : 2|1@0+ (1,0) [0|1] "" XXX + SG_ WRSLNDWhlRotStRst : 3|1@0+ (1,0) [0|1] "" XXX + SG_ WRSLNDSeqNum : 5|2@0+ (1,0) [0|3] "counts" XXX + SG_ WRSLNDWhlDisTpRC : 7|2@0+ (1,0) [0|3] "counts" XXX + SG_ WRSLNDWhlDistTstm : 23|16@0+ (1,0) [0|65535] "counts" XXX + SG_ WhlRotStatRghtNDrvn : 39|32@0+ (1,0) [0|0] "" XXX + SG_ WRSRNDWhlDistPCntr : 33|10@0+ (1,0) [0|1023] "counts" XXX + SG_ WRSRNDWhlDistVal : 34|1@0+ (1,0) [0|1] "" XXX + SG_ WRSRNDWhlRotStRst : 35|1@0+ (1,0) [0|1] "" XXX + SG_ WRSRNDSeqNum : 37|2@0+ (1,0) [0|3] "counts" XXX + SG_ WRSRNDWhlDisTpRC : 39|2@0+ (1,0) [0|3] "counts" XXX + SG_ WRSRNDWhlDistTstm : 55|16@0+ (1,0) [0|65535] "counts" XXX + +BO_ 2149769216 Driven_Whl_Rotational_Stat_LS: 8 XXX + SG_ WhlRotatStatLftDrvn : 7|32@0+ (1,0) [0|0] "" XXX + SG_ WRSLDWhlDistPlsCntr : 1|10@0+ (1,0) [0|1023] "counts" XXX + SG_ WRSLDWhlDistVal : 2|1@0+ (1,0) [0|1] "" XXX + SG_ WRSLDWhlRotStatRst : 3|1@0+ (1,0) [0|1] "" XXX + SG_ WRSLDSeqNum : 5|2@0+ (1,0) [0|3] "counts" XXX + SG_ WRSLDWhlDisTpRC : 7|2@0+ (1,0) [0|3] "counts" XXX + SG_ WRSLDWhlDistTmstm : 23|16@0+ (1,0) [0|65535] "counts" XXX + SG_ WhlRotatStatRtDrvn : 39|32@0+ (1,0) [0|0] "" XXX + SG_ WRSRDWhlDistPlsCntr : 33|10@0+ (1,0) [0|1023] "counts" XXX + SG_ WRSRDWhlDistVal : 34|1@0+ (1,0) [0|1] "" XXX + SG_ WRSRDWhlRotStatRst : 35|1@0+ (1,0) [0|1] "" XXX + SG_ WRSRDSeqNum : 37|2@0+ (1,0) [0|3] "counts" XXX + SG_ WRSRDWhlDisTpRC : 39|2@0+ (1,0) [0|3] "counts" XXX + SG_ WRSRDWhlDistTmstm : 55|16@0+ (1,0) [0|65535] "counts" XXX + +BO_ 2156789760 Time_of_Day_LS: 6 XXX + SG_ CldrYr : 7|8@0+ (1,2000) [2000|2255] "year" XXX + SG_ CldrMth : 11|4@0+ (1,0) [0|15] "" XXX + SG_ FrPedDetCsStReq : 14|3@0+ (1,0) [0|7] "" XXX + SG_ CldrDay : 20|5@0+ (1,0) [0|31] "days" XXX + SG_ SmrtHgBmAstCstSetReq : 23|3@0+ (1,0) [0|7] "" XXX + SG_ TmofDay : 24|17@0+ (1,0) [0|0] "" XXX + SG_ TOD_HrofDay : 24|5@0+ (1,0) [0|31] "hr" XXX + SG_ TOD_MinofHr : 35|6@0+ (1,0) [0|63] "min" XXX + SG_ TOD_SecofMin : 45|6@0+ (1,0) [0|63] "s" XXX + SG_ TimeDispFormat : 25|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155020288 Language_Selection_LS: 1 XXX + SG_ LngSelExt : 5|6@0+ (1,0) [0|63] "" XXX + SG_ ChVolRq2 : 7|2@0+ (1,0) [0|3] "" XXX + +BO_ 2150432768 Engine_Information_4_LS: 8 XXX + SG_ TransOilTempSensPres : 0|1@0+ (1,0) [0|1] "" XXX + SG_ GenFldDutCycGroup : 1|42@0+ (1,0) [0|0] "" XXX + SG_ GenFldDutCycV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ GenFldDutCyc : 47|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ FuelFltLifRstPerf : 2|1@0+ (1,0) [0|1] "" XXX + SG_ TrnEmsMlfAtv : 3|1@0+ (1,0) [0|1] "" XXX + SG_ GrdBrkgAct : 4|1@0+ (1,0) [0|1] "" XXX + SG_ TrnsNEmsRltMalfActv : 5|1@0+ (1,0) [0|1] "" XXX + SG_ EngShtdwnPndgIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EngManfldAirTempCrtdGroup : 7|16@0+ (1,0) [0|0] "" XXX + SG_ EngManfldAirTempCrtdV : 7|1@0+ (1,0) [0|1] "" XXX + SG_ EngManfldAirTempCrtd : 15|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ FuelTotCap : 19|12@0+ (0.125,0) [0|511.875] "liters" XXX + SG_ TrnsThrmlMngmntStat : 21|2@0+ (1,0) [0|3] "" XXX + SG_ PTHiElecLdReqd : 22|1@0+ (1,0) [0|1] "" XXX + SG_ EngOilRmnLf : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ FuelFltRmnLf : 63|8@0+ (0.392157,0) [0|100.000035] "%" XXX + +BO_ 2155298816 Tire_Pressure_Sensor_Prog_Req_LS: 1 XXX + SG_ TrPrsSnsProgEvntRqd : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TrPrsMntrTrLdRstRqstd : 2|2@0+ (1,0) [0|3] "" XXX + +BO_ 2158878720 ODIDynDataListReq_CntrStack_LS: 8 XXX + SG_ ODIDynDataLstRq_CntrStck : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ODDLC_FUCID : 7|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLC_DataId : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLC_DspMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLC_ReqDir : 24|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLC_NmEntries : 31|7@0+ (1,0) [0|127] "" XXX + SG_ ODDLC_Idx : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ODDLC_SubIdReqM : 51|12@0+ (1,0) [0|4095] "" XXX + SG_ ODDLC_WrpArnd : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLC_BckgndFlag : 53|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLC_ReqType : 55|2@0+ (1,0) [0|3] "" XXX + +BO_ 2158870528 ODIDynDataListRequest_AuxIP_LS: 8 XXX + SG_ ODIDynDataLstRq_AxIP : 7|64@0+ (1,0) [0|0] "" XXX + SG_ ODDLA_FUCID : 7|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLA_DataId : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLA_DspMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDLA_ReqDir : 24|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLA_NmEntries : 31|7@0+ (1,0) [0|127] "" XXX + SG_ ODDLA_Idx : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ ODDLA_SubIdReqM : 51|12@0+ (1,0) [0|4095] "" XXX + SG_ ODDLA_WrpArnd : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLA_BckgndFlag : 53|1@0+ (1,0) [0|1] "" XXX + SG_ ODDLA_ReqType : 55|2@0+ (1,0) [0|3] "" XXX + +BO_ 2154692608 Audio_Source_Status_LS: 2 XXX + SG_ AudSrcStat : 3|12@0+ (1,0) [0|0] "" XXX + SG_ ASSAudSrcType : 3|5@0+ (1,0) [0|31] "" XXX + SG_ ASSAudSrcStatCode : 11|4@0+ (1,0) [0|15] "" XXX + SG_ ASSAudSrcChType : 14|3@0+ (1,0) [0|7] "" XXX + SG_ LgclAVChnl : 7|4@0+ (1,0) [0|15] "" XXX + +BO_ 2154627072 Audio_Master_Arbitration_Command: 2 XXX + SG_ AudMstrArbCom : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LgclAVChnl_368 : 7|4@0+ (1,0) [0|15] "" XXX + SG_ AudMstrSrcTyp : 12|5@0+ (1,0) [0|31] "" XXX + SG_ AudMstrChnnlTyp : 15|3@0+ (1,0) [0|7] "" XXX + +BO_ 2151112704 Occupant_Sensning_Status_LS: 2 XXX + SG_ FrntPassClass : 2|3@0+ (1,0) [0|7] "" XXX + SG_ FrPsSeatOccSnsOpMd : 5|3@0+ (1,0) [0|7] "N/A" XXX + SG_ FrPasSeatResCtrlOccStGroup : 7|14@0+ (1,0) [0|0] "" XXX + SG_ FrPasSeatResCtrlOccSt : 7|2@0+ (1,0) [0|3] "" XXX + SG_ FrPasSeatResCtrlOccStV : 10|1@0+ (1,0) [0|1] "" XXX + SG_ FrPsSeatOccFltSt : 9|2@0+ (1,0) [0|3] "N/A" XXX + SG_ FrPasSeatbltRemOccSt : 11|1@0+ (1,0) [0|1] "" XXX + +BO_ 2153938944 Remote_Reflash_Req_LS: 1 XXX + SG_ RmtRflshMdReqtd : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2159239168 ODI_TEL_2_OTIM_LS: 8 XXX + SG_ ODI_TEL2OTIM : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159230976 ODI_OTIM_2_TEL_LS: 8 XXX + SG_ ODI_OTIM2TEL : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159222784 ODI_PDIM_2_CenterStack_LS: 8 XXX + SG_ ODI_PDIM2CntrStck : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2159214592 ODI_CenterStack_2_PDIM_LS: 8 XXX + SG_ ODI_CntrStck2PDIM : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2158862336 ODIAction_OTIM_LS: 8 XXX + SG_ ODIActn_OTIM : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODIAOT_DaTy : 5|6@0+ (1,0) [0|63] "" XXX + SG_ ODIAOT_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAOT_ActnID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAOT_DspMID : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAOT_ActnVal : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2150662144 Environment_Id_Resp_3_LS: 3 XXX + SG_ EnvIdRsp3 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ EnvIdRspSt3 : 17|2@0+ (1,0) [0|3] "" XXX + +BO_ 2150653952 Environment_Id_Resp_2_LS: 3 XXX + SG_ EnvIdRsp2 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ EnvIdRspSt2 : 17|2@0+ (1,0) [0|3] "" XXX + +BO_ 2150850560 Seatbelt_Information_LS: 1 XXX + SG_ DrSbltAtcGroup : 1|2@0+ (1,0) [0|0] "" XXX + SG_ DrSbltAtc : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DrSbltAtcV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PsSbltAtcGroup : 3|2@0+ (1,0) [0|0] "" XXX + SG_ PsSbltAtc : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PsSbltAtcV : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154659840 Column_Lock_Status_2: 2 XXX + SG_ UnlckRtryRotIndOn : 2|1@0+ (1,0) [0|1] "" XXX + SG_ UnlockRtryPshIndOn : 3|1@0+ (1,0) [0|1] "" XXX + SG_ StrgClmnLckVisNot : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ClmnLckStatGroup : 5|6@0+ (1,0) [0|0] "" XXX + SG_ ClmnLckStat : 1|2@0+ (1,0) [0|3] "" XXX + SG_ ClmnLckStatV : 5|1@0+ (1,0) [0|1] "" XXX + SG_ ClmSysFlrIndOn : 7|1@0+ (1,0) [0|1] "" XXX + SG_ StrngClmnLckTT : 9|2@0+ (1,0) [0|3] "" XXX + +BO_ 2154938368 Fob_Programming_Mode_Status_LS: 1 XXX + SG_ FobProgMdStat : 1|2@0+ (1,0) [0|3] "" XXX + +BO_ 2155266048 Rear_Seat_Heat_Cool_Switches_LS: 1 XXX + SG_ RLHCSeatSw1Act : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSeatSw2Act : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSeatSw3Act : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSeatSw1Act : 3|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSeatSw2Act : 4|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSeatSw3Act : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155249664 Rear_Seat_Heat_Cool_Control_LS: 4 XXX + SG_ RLHCSModeIndCtrl : 4|5@0+ (1,0) [0|0] "" XXX + SG_ RLHCSMInd3 : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSMInd2 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSMInd1 : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSMIndReq : 4|2@0+ (1,0) [0|3] "" XXX + SG_ RRHCSModeIndCtrl : 12|5@0+ (1,0) [0|0] "" XXX + SG_ RRHCSMInd3 : 8|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSMInd2 : 9|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSMInd1 : 10|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSMIndReq : 12|2@0+ (1,0) [0|3] "" XXX + SG_ RLHCSeatLevIndCtrl : 22|7@0+ (1,0) [0|0] "" XXX + SG_ RLHCSLSeatLev5 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSLSeatLev4 : 17|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSLSeatLev3 : 18|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSLSeatLev2 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSLSeatLev1 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ RLHCSLIndReq : 22|2@0+ (1,0) [0|3] "" XXX + SG_ RRHCSeatLevIndCtrl : 30|7@0+ (1,0) [0|0] "" XXX + SG_ RRHCSLSeatLev5 : 24|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSLSeatLev4 : 25|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSLSeatLev3 : 26|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSLSeatLev2 : 27|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSLSeatLev1 : 28|1@0+ (1,0) [0|1] "" XXX + SG_ RRHCSLIndReq : 30|2@0+ (1,0) [0|3] "" XXX + +BO_ 2155184128 CruiseControl_LS: 3 XXX + SG_ CrsCntAtv : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CrsSpdLmtrSwStat : 4|4@0+ (1,0) [0|15] "" XXX + SG_ TrnsShftLvrLckStat : 5|1@0+ (1,0) [0|1] "" XXX + SG_ RrStRmndrIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ RrStRmndrCstSetAvail : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CrsCntrlSwStat : 15|8@0+ (1,0) [0|0] "" XXX + SG_ CrsCntrlSwStSwDataIntgty : 9|2@0+ (1,0) [0|3] "" XXX + SG_ CrsCntrlSwStSpDcSwAct : 10|1@0+ (1,0) [0|1] "" XXX + SG_ CrsCntrlSwStSpdInSwAct : 11|1@0+ (1,0) [0|1] "" XXX + SG_ CrsCntrlSwStSetSwAct : 12|1@0+ (1,0) [0|1] "" XXX + SG_ CrsCntrlSwStResSwAct : 13|1@0+ (1,0) [0|1] "" XXX + SG_ CrsCntrlSwStOnSwAct : 14|1@0+ (1,0) [0|1] "" XXX + SG_ CrsCntrlSwStCanSwAct : 15|1@0+ (1,0) [0|1] "" XXX + SG_ SmPhRmFunCstCurStVal : 18|3@0+ (1,0) [0|7] "" XXX + SG_ SmPhRmFunCstStAval : 19|1@0+ (1,0) [0|1] "" XXX + SG_ IdlRecmndToClEngIO : 20|1@0+ (1,0) [0|1] "" XXX + SG_ RrStRmndrCstCurrSetVal : 23|3@0+ (1,0) [0|7] "" XXX + +BO_ 2155167744 Power_Mode_Info_LS: 3 XXX + SG_ ShftPrkIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ShftToNtrlIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ Ky_IdDevPr : 2|1@0+ (1,0) [0|1] "" XXX + SG_ SecPwrMdPshBtnAtv : 3|1@0+ (1,0) [0|1] "" XXX + SG_ TransModActIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ TransModInactIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ KylsStrtUseTxPckIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ TrStLgMdAtv : 7|1@0+ (1,0) [0|1] "" XXX + SG_ VehMovState : 10|3@0+ (1,0) [0|7] "" XXX + SG_ AutoShtdwnDsblIO : 11|1@0+ (1,0) [0|1] "" XXX + SG_ AppPrkBrkIO : 12|1@0+ (1,0) [0|1] "" XXX + SG_ NRmtDtdPsCluRstIO : 13|1@0+ (1,0) [0|1] "" XXX + SG_ ApplyBrkPdlIO : 14|1@0+ (1,0) [0|1] "" XXX + SG_ ApplyCltPdlIO : 15|1@0+ (1,0) [0|1] "" XXX + SG_ NoReDetInOn : 16|1@0+ (1,0) [0|1] "" XXX + SG_ NRmtDtdPsBrkRstIO : 17|1@0+ (1,0) [0|1] "" XXX + SG_ PrsBtnAgnTTrnEngOffIO : 18|1@0+ (1,0) [0|1] "" XXX + SG_ TSLgMdPwrCtOWAtv : 19|1@0+ (1,0) [0|1] "" XXX + SG_ NRmtDtctdRstrtAllwd : 20|1@0+ (1,0) [0|1] "" XXX + SG_ PrsStrtAgnIO : 21|1@0+ (1,0) [0|1] "" XXX + SG_ PrsCltchPrsStrtAgnIO : 22|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154921984 Fob_Status_LS: 2 XXX + SG_ RFAFnc : 1|10@0+ (1,0) [0|0] "" XXX + SG_ RFRmtCntFobNm : 1|3@0+ (1,0) [0|7] "" XXX + SG_ RFRmtCntFobBatLw : 8|1@0+ (1,0) [0|1] "" XXX + SG_ RFRmtCntrlFobFnc : 14|6@0+ (1,0) [0|63] "" XXX + SG_ FobPogLimRchdIndOn : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151317504 Park_Assistant_Rear_Status: 4 XXX + SG_ PrkAsstRrExtdDist : 3|12@0+ (0.01,0) [0|40.95] "m" XXX + SG_ PrkAstRrSysStat : 5|2@0+ (1,0) [0|3] "" XXX + SG_ PARrRgn1ObjStat : 19|4@0+ (1,0) [0|15] "" XXX + SG_ PARrRgn2ObjStat : 23|4@0+ (1,0) [0|15] "" XXX + SG_ PARrRgn3ObjStat : 27|4@0+ (1,0) [0|15] "" XXX + SG_ PARrRgn4ObjStat : 31|4@0+ (1,0) [0|15] "" XXX + +BO_ 2151301120 Park_Assistant_Front_Status: 4 XXX + SG_ PrkAsstFrtExtdDist : 3|12@0+ (0.01,0) [0|40.95] "m" XXX + SG_ PrkAstFrSysStat : 5|2@0+ (1,0) [0|3] "" XXX + SG_ PrkAstAdvSysAct : 6|1@0+ (1,0) [0|1] "" XXX + SG_ PrkAsstRrOffIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ PAFrtRgn1ObjStat : 19|4@0+ (1,0) [0|15] "" XXX + SG_ PAFrtRgn2ObjStat : 23|4@0+ (1,0) [0|15] "" XXX + SG_ PAFrtRgn3ObjStat : 27|4@0+ (1,0) [0|15] "" XXX + SG_ PAFrtRgn4ObjStat : 31|4@0+ (1,0) [0|15] "" XXX + +BO_ 2159083520 ODI_TEL_2_IPC_LS: 8 XXX + SG_ ODI_TEL2IPC : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2153922560 Climate_Control_Voltage_LS: 3 XXX + SG_ ClimCtrlVoltBstModReq : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ClmtCtrlHtrEngRunRq : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HtrVlvRqstdPstn : 3|2@0+ (1,0) [0|3] "" XXX + SG_ ClntHtrElecPwrRatGroup : 4|13@0+ (1,0) [0|0] "" XXX + SG_ ClntHtrElecPwrRatV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ClntHtrElecPwrRat : 15|8@0+ (0.04,0) [0|10.2] "kW" XXX + SG_ ClmCtrHiVltPwrRqtd : 23|8@0+ (0.1,0) [0|25.5] "kW" XXX + +BO_ 2153807872 Door_Open_Switch_Status_LS: 1 XXX + SG_ DrDoorOpenSwActGroup : 1|2@0+ (1,0) [0|0] "" XXX + SG_ DrDoorOpenSwAct : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DrDoorOpenSwActV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ PsDoorOpenSwActGroup : 3|2@0+ (1,0) [0|0] "" XXX + SG_ PsDoorOpenSwAct : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PsDoorOpenSwActV : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ClmSysAuxFlrIndOn : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PsvStrtStrngClmnLckTT : 6|2@0+ (1,0) [0|3] "" XXX + +BO_ 2150703104 Audio_Amplifier_Status: 1 XXX + SG_ AudSysDigSigProcPres : 0|1@0+ (1,0) [0|1] "" XXX + SG_ AudSysSurSndSysPres : 1|1@0+ (1,0) [0|1] "" XXX + SG_ AudSysVNoisCompPres : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151399424 Wash_Level_LS: 1 XXX + SG_ WshFldLw : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151956480 Driver_Workload_LS: 2 XXX + SG_ DrvWrkldLvl : 3|4@0+ (1,0) [0|15] "" XXX + SG_ ClstrHMIAnmSt : 6|3@0+ (1,0) [0|7] "" XXX + SG_ ClstrHMIRdy : 7|1@0+ (1,0) [0|1] "" XXX + SG_ StrWhlThbwhlCnts : 13|6@0- (1,0) [-32|31] "counts" XXX + +BO_ 2151940096 Alarm_2_Request_LS: 7 XXX + SG_ Alrm2ExtRngReq : 1|26@0+ (1,0) [0|0] "" XXX + SG_ A2ERRAlrmReq : 1|2@0+ (1,0) [0|3] "" XXX + SG_ A2ERRAlrmTime : 15|24@0+ (1,0) [0|16777215] "min" XXX + SG_ EstBulkIntAirTmpGroup : 2|35@0+ (1,0) [0|0] "" XXX + SG_ EstBulkIntAirTmpV : 2|1@0+ (1,0) [0|1] "" XXX + SG_ EstBulkIntAirTmp : 39|8@0+ (0.5,-40) [-40|87.5] "deg C" XXX + SG_ EstIntRfSrfcTmpGroup : 3|44@0+ (1,0) [0|0] "" XXX + SG_ EstIntRfSrfcTmpV : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EstIntRfSrfcTmp : 47|8@0+ (0.5,-40) [-40|87.5] "deg C" XXX + SG_ EstIntHorzDshSrfTmpGroup : 4|53@0+ (1,0) [0|0] "" XXX + SG_ EstIntHorzDshSrfTmpM : 4|1@0+ (1,0) [0|1] "" XXX + SG_ EstIntHorzDshSrfTmp : 55|8@0+ (1,-40) [-40|215] "deg C" XXX + +BO_ 2151923712 Alarm_1_Request_LS: 5 XXX + SG_ Alrm1ExtRngReq : 1|26@0+ (1,0) [0|0] "" XXX + SG_ A1ERRAlrmReq : 1|2@0+ (1,0) [0|3] "" XXX + SG_ A1ERRAlrmTime : 15|24@0+ (1,0) [0|16777215] "min" XXX + SG_ HLOCCstCurrSetVal : 6|3@0+ (1,0) [0|7] "" XXX + SG_ HLOCCstSetAvail : 7|1@0+ (1,0) [0|1] "" XXX + SG_ HLOCCstAvail : 39|7@0+ (1,0) [0|0] "" XXX + SG_ HLOCCA_Res4Avail : 33|1@0+ (1,0) [0|1] "" XXX + SG_ HLOCCA_Res3Avail : 34|1@0+ (1,0) [0|1] "" XXX + SG_ HLOCCA_Res2Avail : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HLOCCA_Res1Avail : 36|1@0+ (1,0) [0|1] "" XXX + SG_ HLOCCA_OnOpnOnlyAvail : 37|1@0+ (1,0) [0|1] "" XXX + SG_ HLOCCA_OnAvail : 38|1@0+ (1,0) [0|1] "" XXX + SG_ HLOCCA_OffAvail : 39|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150645760 Environment_Id_Resp_1_LS: 3 XXX + SG_ EnvIdRsp1 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ EnvIdRspSt1 : 17|2@0+ (1,0) [0|3] "" XXX + +BO_ 2152464384 Lane_Departure_Warning_LS: 3 XXX + SG_ LaneDepWrnDisbldIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ LnKpAstDisbldIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ SrvcLaneDepWrnSysIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ SrvcLnKpAstSysIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ HndsOffStrWhlDtIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ TnDrvLDWOffUnbIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ LftLnDepWrnSt : 7|2@0+ (1,0) [0|3] "" XXX + SG_ LaneDepWrnIndCntrl : 13|6@0+ (1,0) [0|0] "" XXX + SG_ LDWIC_LnDepWAWLn : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LDWIC_Ind2 : 10|1@0+ (1,0) [0|1] "" XXX + SG_ LDWIC_Ind1 : 11|1@0+ (1,0) [0|1] "" XXX + SG_ LDWIC_IndReq : 13|2@0+ (1,0) [0|3] "" XXX + SG_ RtLnDepWrnSt : 15|2@0+ (1,0) [0|3] "" XXX + SG_ LnKpAstIndCntrl : 21|6@0+ (1,0) [0|0] "" XXX + SG_ LKAIC_AdbWngLn : 17|2@0+ (1,0) [0|3] "" XXX + SG_ LKAIC_Ind2 : 18|1@0+ (1,0) [0|1] "" XXX + SG_ LKAIC_Ind1 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ LKAIC_IndReq : 21|2@0+ (1,0) [0|3] "" XXX + +BO_ 2154971136 Front_Seat_Heat_Cool_Switches_LS: 1 XXX + SG_ DrvHCSeatSw1Act : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSeatSw2Act : 1|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSeatSw3Act : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSeatSw1Act : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSeatSw2Act : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSeatSw3Act : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154962944 Front_Seat_Heat_Cool_Control_LS: 4 XXX + SG_ DrvHCSModeIndCtrl : 4|5@0+ (1,0) [0|0] "" XXX + SG_ DrvHCSMInd3 : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSMInd2 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSMInd1 : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSMIndReq : 4|2@0+ (1,0) [0|3] "" XXX + SG_ PassHCSModeIndCtrl : 12|5@0+ (1,0) [0|0] "" XXX + SG_ PassHCSMInd3 : 8|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSMInd2 : 9|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSMInd1 : 10|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSMIndReq : 12|2@0+ (1,0) [0|3] "" XXX + SG_ DrvHCSLevIndCtrl : 22|7@0+ (1,0) [0|0] "" XXX + SG_ DrvHCSLSeatLev5 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSLSeatLev4 : 17|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSLSeatLev3 : 18|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSLSeatLev2 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSLSeatLev1 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ DrvHCSLIndReq : 22|2@0+ (1,0) [0|3] "" XXX + SG_ PassHCSeatLevIndCtrl : 30|7@0+ (1,0) [0|0] "" XXX + SG_ PassHCSLSeatLev5 : 24|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSLSeatLev4 : 25|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSLSeatLev3 : 26|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSLSeatLev2 : 27|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSLSeatLev1 : 28|1@0+ (1,0) [0|1] "" XXX + SG_ PassHCSLIndReq : 30|2@0+ (1,0) [0|3] "" XXX + +BO_ 2156232704 Alarm_Clock_Status_LS: 4 XXX + SG_ AlrmClkStat : 7|32@0+ (1,0) [0|0] "" XXX + SG_ ACSAlarm3 : 1|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm2 : 3|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm1 : 5|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm0 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm7 : 9|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm6 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm5 : 13|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm4 : 15|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm11 : 17|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm10 : 19|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm9 : 21|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm8 : 23|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm15 : 25|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm14 : 27|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm13 : 29|2@0+ (1,0) [0|3] "" XXX + SG_ ACSAlarm12 : 31|2@0+ (1,0) [0|3] "" XXX + +BO_ 2154987520 Hood_Status_LS: 1 XXX + SG_ HdStGroup : 2|3@0+ (1,0) [0|0] "" XXX + SG_ HdSt : 1|2@0+ (1,0) [0|3] "" XXX + SG_ HdStV : 2|1@0+ (1,0) [0|1] "" XXX + SG_ WrlsChrgSysChrgStat : 5|3@0+ (1,0) [0|7] "" XXX + +BO_ 2154840064 Compass_Status_LS: 4 XXX + SG_ CmpsOctHdingDataSrc : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CmpsModFltPrs : 1|1@0+ (1,0) [0|1] "" XXX + SG_ CmpsModManCalInPrc : 2|1@0+ (1,0) [0|1] "" XXX + SG_ CmpsZnNvrSet : 3|1@0+ (1,0) [0|1] "" XXX + SG_ CmpsDecZone : 11|4@0+ (1,0) [0|15] "" XXX + SG_ CmpsOctHding : 14|3@0+ (1,0) [0|7] "" XXX + SG_ CmpsSatrtd : 15|1@0+ (1,0) [0|1] "" XXX + SG_ CmpsCrHding : 23|16@0+ (0.0054932,0) [0|359.996862] "deg" XXX + +BO_ 2154676224 Compass_Request_LS: 1 XXX + SG_ CmpsDecZonCmndVal : 3|4@0+ (1,0) [0|15] "" XXX + SG_ CmpsDecZonSetReq : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CmpsModManCalReq : 5|1@0+ (1,0) [0|1] "" XXX + SG_ CmpsModSlfTstReq : 6|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154643456 Auxiliary_Heater_Status_LS: 3 XXX + SG_ AuxHtrAtv : 0|1@0+ (1,0) [0|1] "" XXX + SG_ HtrCoreInltClntTmpCalcGroup : 4|21@0+ (1,0) [0|0] "" XXX + SG_ HtrCoreInltClntTmpCalcV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ HtrCoreInltClntTmpCalc : 23|8@0+ (1,-40) [-40|215] "deg C" XXX + SG_ CCClntCrcFlwRtReq : 15|8@0+ (0.392157,0) [0|100.000035] "%" XXX + +BO_ 2154905600 Driver_Identifier_LS: 1 XXX + SG_ DrId : 2|3@0+ (1,0) [0|7] "" XXX + SG_ DrvSeatPrsMemID : 5|3@0+ (1,0) [0|7] "" XXX + +BO_ 2154954752 High_Volt_Climate_Pwr_Status_LS: 5 XXX + SG_ ClmtHtPwrRqd : 0|1@0+ (1,0) [0|1] "" XXX + SG_ HtdStWhlCmd : 2|2@0+ (1,0) [0|3] "" XXX + SG_ HtdStWhlInd : 4|2@0+ (1,0) [0|3] "" XXX + SG_ HtdStWhlCtrlSrc : 5|1@0+ (1,0) [0|1] "" XXX + SG_ ClntHtrElecPwrReq : 15|8@0+ (0.04,0) [0|10.2] "kW" XXX + SG_ EstACCompPwrRchCbnCmf : 23|8@0+ (0.04,0) [0|10.2] "kw" XXX + SG_ EstACCompPwrMtnCbnCmf : 31|8@0+ (0.04,0) [0|10.2] "kW" XXX + +BO_ 2153381888 Control_Power_Liftgate_LS: 4 XXX + SG_ FnshRrClsrMtnBfrDrvIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RrClsrObstclDtctd : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RrClsrInMtn : 3|1@0+ (1,0) [0|1] "" XXX + SG_ RrClosOpenSwActGroup : 4|3@0+ (1,0) [0|0] "" XXX + SG_ RrClosOpenSwAct : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RrClosOpenSwActV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ RrWprInhbRq : 5|1@0+ (1,0) [0|1] "" XXX + SG_ GrgPrgMdCmpl : 6|1@0+ (1,0) [0|1] "" XXX + SG_ PwrLftgtInclAngGroup : 7|16@0+ (1,0) [0|0] "" XXX + SG_ PwrLftgtInclAngV : 7|1@0+ (1,0) [0|1] "" XXX + SG_ PwrLftgtInclAng : 15|8@0+ (1,0) [0|255] "" XXX + SG_ VehIncAngEst : 23|8@0+ (1,0) [0|255] "deg" XXX + SG_ PwrLftgtMotStat : 26|3@0+ (1,0) [0|7] "" XXX + SG_ VltActRrAccUnavlIO : 27|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149752832 Chassis_Information_LS: 8 XXX + SG_ VehHghtStatGroup : 0|9@0+ (1,0) [0|0] "" XXX + SG_ VehHghtStatV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ VehHghtStat : 11|4@0+ (1,0) [0|15] "" XXX + SG_ IntBrkAssPreFilReq : 1|1@0+ (1,0) [0|1] "N/A" XXX + SG_ BksOvht : 2|1@0+ (1,0) [0|1] "" XXX + SG_ HalfSysFail : 3|1@0+ (1,0) [0|1] "" XXX + SG_ BrkSysRedBrkTlltlReq : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ABSAtv : 5|1@0+ (1,0) [0|1] "" XXX + SG_ DrvlnCustStngAvlbl : 6|1@0+ (1,0) [0|1] "" XXX + SG_ StrCustStngAvlbl : 7|1@0+ (1,0) [0|1] "" XXX + SG_ PrkBrkVDA : 12|1@0+ (1,0) [0|1] "" XXX + SG_ PowStVDA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ RrDrCntVDA : 14|1@0+ (1,0) [0|1] "" XXX + SG_ BrkSysVDA : 15|1@0+ (1,0) [0|1] "" XXX + SG_ SprTireSt : 18|3@0+ (1,0) [0|7] "" XXX + SG_ EPBSysAudWarnReq : 20|2@0+ (1,0) [0|3] "" XXX + SG_ EPBSysDspMsgReq : 23|3@0+ (1,0) [0|7] "" XXX + SG_ DrvlnCustCurrStngVal : 26|3@0+ (1,0) [0|7] "" XXX + SG_ StrCustCurrStngVal : 29|3@0+ (1,0) [0|7] "" XXX + SG_ SusCustStngAvlbl : 30|1@0+ (1,0) [0|1] "" XXX + SG_ EBDFailed : 31|1@0+ (1,0) [0|1] "" XXX + SG_ SusCustCurrStngVal : 34|3@0+ (1,0) [0|7] "" XXX + SG_ HillDscntCntlSysStat : 37|3@0+ (1,0) [0|7] "" XXX + SG_ ElecPrkBrkStat : 39|2@0+ (1,0) [0|3] "" XXX + SG_ HlStrAssActIO : 41|1@0+ (1,0) [0|1] "" XXX + SG_ ColPrSysStngAvl : 42|1@0+ (1,0) [0|1] "" XXX + SG_ GNCustSetngAvlbl : 44|1@0+ (1,0) [0|1] "" XXX + SG_ GNCustCrntStngVal : 47|3@0+ (1,0) [0|7] "" XXX + SG_ CPSInfotmntMtReq : 49|2@0+ (1,0) [0|3] "" XXX + SG_ ColPrSysCrntStng : 52|3@0+ (1,0) [0|7] "" XXX + SG_ SndEnhcmtPerfMdRq : 55|3@0+ (1,0) [0|7] "" XXX + SG_ DispPerfMdCsCrStVal : 58|3@0+ (1,0) [0|7] "" XXX + SG_ DispPerfMdCsStAvl : 59|1@0+ (1,0) [0|1] "" XXX + SG_ SndPerfMdCsCrStVal : 62|3@0+ (1,0) [0|7] "" XXX + SG_ SndPerfMdCsStAvl : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151514112 Reset_OilLife_Request_LS: 1 XXX + SG_ EngOilLfRstRq : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2158903296 ODIDynDataMultiRequest_AuxIP_LS: 8 XXX + SG_ ODIDynDataMltRq_AuxIP : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODDMA_DataID2Vld : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMA_DataID3Vld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMA_DataID4Vld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMA_DataID5Vld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMA_ReqType : 5|2@0+ (1,0) [0|3] "" XXX + SG_ ODDMA_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMA_DispMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMA_DataID1 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMA_DataID2 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMA_DataID3 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMA_DataID4 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMA_DataID5 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2158911488 ODIDynDataMultiReq_CntrStack_LS: 8 XXX + SG_ ODIDynDataMltRq_CntrStck : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODDMC_DataID2Vld : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMC_DataID3Vld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMC_DataID4Vld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMC_DataID5Vld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMC_ReqType : 5|2@0+ (1,0) [0|3] "" XXX + SG_ ODDMC_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMC_DispMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMC_DataID1 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMC_DataID2 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMC_DataID3 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMC_DataID4 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMC_DataID5 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2158919680 ODIDynDataMultiRequest_IPC_LS: 8 XXX + SG_ ODIDynDataMltRq_IPC : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODDMI_DataID2Vld : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMI_DataID3Vld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMI_DataID4Vld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMI_DataID5Vld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ODDMI_ReqType : 5|2@0+ (1,0) [0|3] "" XXX + SG_ ODDMI_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMI_DispMID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMI_DataID1 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMI_DataID2 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMI_DataID3 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMI_DataID4 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ ODDMI_DataID5 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2151825408 Outside_Air_Temperature_LS: 3 XXX + SG_ OtsAirTmpCrValGroup : 0|9@0+ (1,0) [0|0] "" XXX + SG_ OtsAirTmpCrValV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ OtsAirTmpCrVal : 15|8@0+ (0.5,-40) [-40|87.5] "deg C" XXX + SG_ OtsAirTmpGroup : 1|18@0+ (1,0) [0|0] "" XXX + SG_ OtsAirTmpV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ OtsAirTmp : 23|8@0+ (0.5,-40) [-40|87.5] "deg C" XXX + SG_ OtsAirTmpCrValMsk : 2|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151153664 Rear_Window_Defog_Status_LS: 1 XXX + SG_ RrWndDfgOn : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151170048 Trailer_Status_LS: 2 XXX + SG_ TrlrHtchSwAtv : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrBrkLtFld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrFgLtFld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrRvsLtFld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrTlLtFld : 4|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrFgLtPrs : 5|1@0+ (1,0) [0|1] "" XXX + SG_ TrlrRtTrInLtFld : 6|1@0+ (1,0) [0|1] "" XXX + SG_ TrlLfTrInLtFld : 7|1@0+ (1,0) [0|1] "" XXX + SG_ LftSecTrnIndFld : 8|1@0+ (1,0) [0|1] "" XXX + SG_ RtSecTrnIndFld : 9|1@0+ (1,0) [0|1] "" XXX + SG_ DisRrPrmryLmps : 10|1@0+ (1,0) [0|1] "" XXX + SG_ RLftPrkLmpFld : 11|1@0+ (1,0) [0|1] "" XXX + SG_ RRPrkLmpFld : 12|1@0+ (1,0) [0|1] "" XXX + SG_ RrEndCrrStat : 13|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151841792 Wipe_Wash_Status_LS: 1 XXX + SG_ TurnWprIntIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RnSnsActIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RnSnsOffIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ WSWprAct : 3|1@0+ (1,0) [0|1] "" XXX + SG_ HtdFrntWSSt : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154995712 Air_Conditioning_Comp_Type_LS: 1 XXX + SG_ HVHtrOvrTmpIndOn : 3|1@0+ (1,0) [0|1] "" XXX + SG_ HVHtrFldIO : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154094592 Adjustable_Pedal_Motion_Inh_LS: 8 XXX + SG_ AdjPdlMotInhbtd : 0|1@0+ (1,0) [0|1] "" XXX + SG_ IntDimSeldAnmTypStVal : 4|4@0+ (1,0) [0|15] "" XXX + SG_ IntDimSeldClrTypStVal : 12|5@0+ (1,0) [0|31] "" XXX + SG_ IntDimAnmTypAvl : 22|15@0+ (1,0) [0|0] "" XXX + SG_ IDATA_AnmTyp6Avl : 16|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp5Avl : 17|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp4Avl : 18|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp3Avl : 19|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp2Avl : 20|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp1Avl : 21|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_OffAvl : 22|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp14Avl : 24|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp13Avl : 25|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp12Avl : 26|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp11Avl : 27|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp10Avl : 28|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp9Avl : 29|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp8Avl : 30|1@0+ (1,0) [0|1] "" XXX + SG_ IDATA_AnmTyp7Avl : 31|1@0+ (1,0) [0|1] "" XXX + SG_ IntDimClrTypAvl : 38|31@0+ (1,0) [0|0] "" XXX + SG_ IDCTA_ClrTyp6Avl : 32|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp5Avl : 33|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp4Avl : 34|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp3Avl : 35|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp2Avl : 36|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp1Avl : 37|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_OffAvl : 38|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp14Avl : 40|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp13Avl : 41|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp12Avl : 42|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp11Avl : 43|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp10Avl : 44|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp9Avl : 45|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp8Avl : 46|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp7Avl : 47|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp22Avl : 48|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp21Avl : 49|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp20Avl : 50|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp19Avl : 51|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp18Avl : 52|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp17Avl : 53|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp16Avl : 54|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp15Avl : 55|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp30Avl : 56|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp29Avl : 57|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp28Avl : 58|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp27Avl : 59|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp26Avl : 60|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp25Avl : 61|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp24Avl : 62|1@0+ (1,0) [0|1] "" XXX + SG_ IDCTA_ClrTyp23Avl : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149711872 ACC_YawRate_Information_LS: 8 XXX + SG_ ACCDrvrSeltdSpd : 3|12@0+ (0.0625,0) [0|255.9375] "km / h" XXX + SG_ AdapCrsCntVDA : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ACCAct370 : 6|1@0+ (1,0) [0|1] "" XXX + SG_ CrsCntlDrSelSpdAct : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CrsSpdLmtrDrvSelSpd : 19|12@0+ (0.0625,0) [0|255.9375] "km / h" XXX + SG_ ACCHdwyStg : 22|3@0+ (1,0) [0|7] "" XXX + SG_ FwdClnAlrtPr : 23|1@0+ (1,0) [0|1] "" XXX + SG_ VehDynYawRateGroup : 36|13@0+ (1,0) [0|0] "" XXX + SG_ VehDynYawRate : 35|12@0- (0.0625,0) [-128|127.9375] "deg/sec" XXX + SG_ VehDynYawRateV : 36|1@0+ (1,0) [0|1] "" XXX + SG_ SpdLmtrSpdWrngEnbld : 37|1@0+ (1,0) [0|1] "" XXX + SG_ SpdLmtrSpdWrngAct : 38|1@0+ (1,0) [0|1] "" XXX + SG_ FwdClnAlrtOffIO : 39|1@0+ (1,0) [0|1] "" XXX + SG_ FwdObjAlrtInd : 48|9@0+ (1,0) [0|0] "" XXX + SG_ FOAI_AlrtChmIhbRq : 48|1@0+ (1,0) [0|1] "" XXX + SG_ FOAI_AlrtWrnIndRq : 59|4@0+ (1,0) [0|15] "" XXX + SG_ FOAI_VehAhdIndRq : 63|4@0+ (1,0) [0|15] "" XXX + SG_ AutoMdSpdLmtStat : 50|2@0+ (1,0) [0|3] "" XXX + SG_ ACCAutoSetSpdStat : 52|2@0+ (1,0) [0|3] "" XXX + SG_ SetSpdLmtRchd : 54|2@0+ (1,0) [0|3] "" XXX + +BO_ 2153979904 BulbOutage_LS: 2 XXX + SG_ CHMSLFld : 0|1@0+ (1,0) [0|1] "" XXX + SG_ FLTrnIndLtFld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ FRTrnIndLtFld : 2|1@0+ (1,0) [0|1] "" XXX + SG_ LftBrkLtFld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ LftLwBmFld : 4|1@0+ (1,0) [0|1] "" XXX + SG_ LftPrkLtFld : 5|1@0+ (1,0) [0|1] "" XXX + SG_ LicPltLtFld : 6|1@0+ (1,0) [0|1] "" XXX + SG_ RLTrnIndLtFld : 7|1@0+ (1,0) [0|1] "" XXX + SG_ RRTrnIndLtFld : 8|1@0+ (1,0) [0|1] "" XXX + SG_ RtBrkLtFld : 9|1@0+ (1,0) [0|1] "" XXX + SG_ RtLwBmFld : 10|1@0+ (1,0) [0|1] "" XXX + SG_ RtPrkLtFld : 11|1@0+ (1,0) [0|1] "" XXX + SG_ RFgLtFld : 12|1@0+ (1,0) [0|1] "" XXX + SG_ RvsLtFld : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LftDytmRunLmpFld : 14|1@0+ (1,0) [0|1] "" XXX + SG_ RtDytmRunLmpFld : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150154240 Passive_Entry_Reply_LS: 8 XXX + SG_ PsvEntVehIdExt : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ PsvEntChlngRply : 39|32@0+ (1,0) [0|4294967295] "passwrd" XXX + +BO_ 2155003904 Side_Blind_Zone_Alert_Status: 2 XXX + SG_ SBZASysClnIndOn : 0|1@0+ (1,0) [0|1] "" XXX + SG_ SBZASysOffIndOn : 1|1@0+ (1,0) [0|1] "" XXX + SG_ SBZASysSrvIndOn : 2|1@0+ (1,0) [0|1] "" XXX + SG_ SBZATmpUnvIndOn : 3|1@0+ (1,0) [0|1] "" XXX + SG_ LftLnChgThrt : 4|1@0+ (1,0) [0|1] "" XXX + SG_ LfLnChngThrtAprchSpd : 15|8@0- (1,0) [-128|127] "km/h" XXX + +BO_ 2150817792 Airbag_Impact_Data_5: 3 XXX + SG_ ImpMaxLateralDeltaVel : 7|8@0- (1,0) [-128|127] "" XXX + SG_ ImpMaxLongDeltaVel : 15|8@0- (1,0) [-128|127] "" XXX + SG_ ImpTimeToMaxDeltaVel : 23|8@0+ (10,0) [0|2550] "ms" XXX + +BO_ 2150227968 Phone_Speech_Rec_Status_LS: 1 XXX + SG_ PhnSpRcgnApSt : 1|2@0+ (1,0) [0|3] "" XXX + +BO_ 2162982912 VIN_Digits_10_to_17: 8 XXX + SG_ VehIdNmDig10_17 : 7|64@0+ (1,0) [0|1] "" XXX + +BO_ 2162966528 VIN_Digits_2_to_9: 8 XXX + SG_ VehIdNmDig2_9 : 7|64@0+ (1,0) [0|1] "" XXX + +BO_ 2151497728 Tire_Pressure_Sensors_LS: 6 XXX + SG_ TireLFPrsGroup : 0|17@0+ (1,0) [0|0] "" XXX + SG_ TireLFPrsV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TireLFPrs : 23|8@0+ (4,0) [0|1020] "kPaG" XXX + SG_ TireRFPrsGroup : 1|34@0+ (1,0) [0|0] "" XXX + SG_ TireRFPrsV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TireRFPrs : 39|8@0+ (4,0) [0|1020] "kPaG" XXX + SG_ TireLFPrsStat : 4|3@0+ (1,0) [0|7] "" XXX + SG_ TireRFPrsStat : 7|3@0+ (1,0) [0|7] "" XXX + SG_ TireLRPrsGroup : 8|17@0+ (1,0) [0|0] "" XXX + SG_ TireLRPrsV : 8|1@0+ (1,0) [0|1] "" XXX + SG_ TireLRPrs : 31|8@0+ (4,0) [0|1020] "kPaG" XXX + SG_ TireRRPrsGroup : 9|34@0+ (1,0) [0|0] "" XXX + SG_ TireRRPrsV : 9|1@0+ (1,0) [0|1] "" XXX + SG_ TireRRPrs : 47|8@0+ (4,0) [0|1020] "kPaG" XXX + SG_ TireLRPrsStat : 12|3@0+ (1,0) [0|7] "" XXX + SG_ TireRRPrsStat : 15|3@0+ (1,0) [0|7] "" XXX + +BO_ 2151219200 Remote_Start_Status: 1 XXX + SG_ RemStrtSt : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RmVehStrRq : 1|1@0+ (1,0) [0|1] "" XXX + +BO_ 2153775104 DTC_Triggered: 7 XXX + SG_ DTCInfo : 7|56@0+ (1,0) [0|0] "" XXX + SG_ DTCI_DTCTriggered : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DTCIUnused1 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ DTCIUnused2 : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DTCIUnused3 : 3|1@0+ (1,0) [0|1] "" XXX + SG_ DTCIUnused4 : 4|1@0+ (1,0) [0|1] "" XXX + SG_ DTCIUnused5 : 5|1@0+ (1,0) [0|1] "" XXX + SG_ DTCIUnused6 : 6|1@0+ (1,0) [0|1] "" XXX + SG_ DTCIUnused7 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_DTCSource : 15|8@0+ (1,0) [0|255] "" XXX + SG_ DTCI_DTCNumber : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ DTCI_DTCFailType : 39|8@0+ (1,0) [0|255] "" XXX + SG_ DTCI_CodeSupported : 40|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_CurrentStatus : 41|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_TstNPsdCdClrdSt : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_TstFldCdClrdStat : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_HistStat : 44|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_TstNPsdPwrUpSt : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_TstFldPwrUpSt : 46|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_WrnIndRqdSt : 47|1@0+ (1,0) [0|1] "" XXX + SG_ DTCI_DTCFaultType : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 2151235584 Vehicle_Theft_Notification_Stat: 5 XXX + SG_ DrIdDevLrnd : 0|1@0+ (1,0) [0|1] "" XXX + SG_ VehSecSysFldIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ VTDTmprDetected : 2|1@0+ (1,0) [0|1] "" XXX + SG_ EhnSrvEngImmStat : 3|1@0+ (1,0) [0|1] "" XXX + SG_ IllDrIdDevDtctd : 4|1@0+ (1,0) [0|1] "" XXX + SG_ AlcKyIIncmIndOn : 5|1@0+ (1,0) [0|1] "" XXX + SG_ VehSecStrgColLckPwdGroup : 6|31@0+ (1,0) [0|0] "" XXX + SG_ VehSecStrgColLckPwdV : 6|1@0+ (1,0) [0|1] "" XXX + SG_ VehSecStrgColLckPwd : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ VehSecAuthnSesComp : 7|1@0+ (1,0) [0|1] "" XXX + SG_ VhSecNImmoIndRq : 9|2@0+ (1,0) [0|3] "" XXX + SG_ StrgColLckCmd : 11|2@0+ (1,0) [0|3] "" XXX + SG_ NmofPrgKFbExtd : 15|4@0+ (1,0) [0|15] "" XXX + SG_ VehStatStAtv : 32|1@0+ (1,0) [0|1] "" XXX + SG_ EhnSrvImmbComRst : 33|1@0+ (1,0) [0|1] "" XXX + SG_ ClmSysBkupFlrIndOn : 34|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150809600 Airbag_Impact_Data_4: 8 XXX + SG_ ImpDltVlcSamp12 : 7|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS12_Axis1 : 7|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS12_Axis2 : 15|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp13 : 23|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS13_Axis1 : 23|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS13_Axis2 : 31|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp14 : 39|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS14_Axis1 : 39|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS14_Axis2 : 47|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp15 : 55|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS15_Axis1 : 55|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS15_Axis2 : 63|8@0- (1,0) [-128|127] "counts" XXX + +BO_ 2150793216 Airbag_Impact_Data_2: 8 XXX + SG_ ImpDltVlcSamp4 : 7|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS4_Axis1 : 7|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS4_Axis2 : 15|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp5 : 23|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS5_Axis1 : 23|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS5_Axis2 : 31|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp6 : 39|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS6_Axis1 : 39|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS6_Axis2 : 47|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp7 : 55|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS7_Axis1 : 55|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS7_Axis2 : 63|8@0- (1,0) [-128|127] "counts" XXX + +BO_ 2150801408 Airbag_Impact_Data_3: 8 XXX + SG_ ImpDltVlcSamp8 : 7|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS8_Axis1 : 7|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS8_Axis2 : 15|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp9 : 23|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS9_Axis1 : 23|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS9_Axis2 : 31|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp10 : 39|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS10_Axis1 : 39|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS10_Axis2 : 47|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp11 : 55|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS11_Axis1 : 55|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS11_Axis2 : 63|8@0- (1,0) [-128|127] "counts" XXX + +BO_ 2150785024 Airbag_Impact_Data_1: 8 XXX + SG_ ImpDltVlcScal : 7|8@0+ (0.00245,0.706) [0.706|1.33075] "kph/cnt" XXX + SG_ AirbgAccelOrien : 10|3@0+ (45,0) [0|315] "deg" XXX + SG_ ImpDltVlcSamp1 : 23|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS1_Axis1 : 23|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS1_Axis2 : 31|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp2 : 39|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS2_Axis1 : 39|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS2_Axis2 : 47|8@0- (1,0) [-128|127] "counts" XXX + SG_ ImpDltVlcSamp3 : 55|16@0+ (1,0) [0|0] "" XXX + SG_ IDVS3_Axis1 : 55|8@0- (1,0) [-128|127] "counts" XXX + SG_ IDVS3_Axis2 : 63|8@0- (1,0) [-128|127] "counts" XXX + +BO_ 2151202816 Rear_Window_Defog_Inhibit: 5 XXX + SG_ RrWndDfgInhRq : 0|1@0+ (1,0) [0|1] "" XXX + SG_ RrWndDfgSwAtv : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ILSSCommErr : 2|1@0+ (1,0) [0|1] "" XXX + SG_ IPSnsrRwSolrIntFltd : 3|1@0+ (1,0) [0|1] "" XXX + SG_ IPSnsrSolrAnglFltd : 4|1@0+ (1,0) [0|1] "" XXX + SG_ IPSnsrTpCvrTempFltd : 5|1@0+ (1,0) [0|1] "" XXX + SG_ AuxHtrAlwd : 6|1@0+ (1,0) [0|1] "" XXX + SG_ IPSnsrRwSolrInt : 15|8@0+ (3,0) [0|765] "W/m2" XXX + SG_ IPSnsrSolrAzmthAngl : 23|8@0+ (2,-180) [-180|330] "deg" XXX + SG_ IPSnsrSolrElvtnAngl : 31|8@0+ (1,0) [0|255] "deg" XXX + SG_ IPSnsrTpCvrTemp : 39|8@0+ (0.5,-40) [-40|87.5] "deg C" XXX + +BO_ 2150825984 Airbag_Indications: 6 XXX + SG_ FsnDrvStbltIC : 7|8@0+ (1,0) [0|0] "" XXX + SG_ FDSIC_IndPer : 3|4@0+ (1,0) [0|15] "" XXX + SG_ FDSIC_IndDC : 6|3@0+ (12.5,12.5) [12.5|100] "%" XXX + SG_ FDSIC_IO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ FsnPsngStbltIC : 15|8@0+ (1,0) [0|0] "" XXX + SG_ FPSIC_IndPer : 11|4@0+ (1,0) [0|15] "" XXX + SG_ FPSIC_IndDtCyc : 14|3@0+ (12.5,12.5) [12.5|100] "%" XXX + SG_ FPSIC_IO : 15|1@0+ (1,0) [0|1] "" XXX + SG_ AirbgIC : 23|8@0+ (1,0) [0|0] "" XXX + SG_ AirbgICIndPer : 19|4@0+ (1,0) [0|15] "" XXX + SG_ AirbgICDutCyc : 22|3@0+ (12.5,12.5) [12.5|100] "%" XXX + SG_ AirbgICIO : 23|1@0+ (1,0) [0|1] "" XXX + SG_ FstnSndRwLtPsStbtInR : 25|2@0+ (1,0) [0|3] "" XXX + SG_ FstnSndRwCtPsStbtInR : 27|2@0+ (1,0) [0|3] "" XXX + SG_ FstnSndRwRtPsStbtInR : 29|2@0+ (1,0) [0|3] "" XXX + SG_ FsnDrStbAuxIR : 31|2@0+ (1,0) [0|3] "" XXX + SG_ FsnPsStbAuxIR : 34|3@0+ (1,0) [0|7] "" XXX + SG_ AirbgFldIO : 35|1@0+ (1,0) [0|1] "" XXX + SG_ SndRwStbltRdIndMd : 37|2@0+ (1,0) [0|3] "" XXX + SG_ FstnThrdRwCtPsStbtInR : 39|2@0+ (1,0) [0|3] "" XXX + SG_ FstnThrdRwRtPsStbtInR : 41|2@0+ (1,0) [0|3] "" XXX + SG_ FstnThrdRwLtPsStbtInR : 43|2@0+ (1,0) [0|3] "" XXX + SG_ SrvIntdPdstProtSysIO : 44|1@0+ (1,0) [0|1] "" XXX + SG_ PdstIntdProtSysDsbld : 45|1@0+ (1,0) [0|1] "" XXX + SG_ PdstIntdProtSysDplyd : 46|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151759872 Door_Lock_Command: 4 XXX + SG_ CntrlLckRqwExtActFun : 9|18@0+ (1,0) [0|0] "" XXX + SG_ CLRAF_Unl_Lk : 9|3@0+ (1,0) [0|7] "" XXX + SG_ CLRAF_FuelD : 16|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_RrCls : 17|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_Hd : 18|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_RLD : 19|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_RRD : 20|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_PD : 21|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_DD : 22|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_ActFunc : 28|5@0+ (1,0) [0|31] "" XXX + SG_ CLRAF_UnandRsv3 : 29|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_UnandRsv2 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ CLRAF_UnandRsv1 : 31|1@0+ (1,0) [0|1] "" XXX + SG_ RrClsRelRq : 10|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149974016 Content_Theft_Sensor_Status: 3 XXX + SG_ SrvAlrmSysIO : 0|1@0+ (1,0) [0|1] "" XXX + SG_ IntrSnsDisbld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgDrvDr : 3|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgPsngDr : 4|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgRrRtDr : 5|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgRrLftDr : 6|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrigTonn : 7|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgTrnk : 8|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgTltSns : 9|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgIntMvmntSns : 10|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrggrdBattRcnctd : 11|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgGlsBrkSns : 12|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgNonOffPM : 13|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrigMidClsr : 14|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmTrgdIO : 15|1@0+ (1,0) [0|1] "" XXX + SG_ AlrmStat : 18|3@0+ (1,0) [0|7] "" XXX + SG_ AlrmTrgHd : 21|1@0+ (1,0) [0|1] "" XXX + +BO_ 2151907328 Steering_Wheel_Control_Switches: 1 XXX + SG_ StrgWhlUnit1SwStat : 3|4@0+ (1,0) [0|15] "" XXX + SG_ StrgWhlUnit2SwStat : 7|4@0+ (1,0) [0|15] "" XXX + +BO_ 2150219776 Voice_Recognition_Status: 1 XXX + SG_ PhnSpRcgnRq : 1|2@0+ (1,0) [0|3] "" XXX + SG_ VcRecVcFdbckSt : 3|2@0+ (1,0) [0|3] "" XXX + +BO_ 2152685568 Radiomarks_Response: 8 XXX + SG_ RadBrdcstSrc : 3|4@0+ (1,0) [0|15] "" XXX + SG_ RadConInfReqSrc : 7|4@0+ (1,0) [0|15] "" XXX + SG_ RadConInfCmd : 11|4@0+ (1,0) [0|15] "" XXX + SG_ RadConInfID : 31|40@0+ (1,0) [0|1099511627775] "" XXX + +BO_ 2151874560 Vehicle_Theft_Notify_Reset_Req: 8 XXX + SG_ EhnSrvEngImmbCom : 0|57@0+ (1,0) [0|0] "" XXX + SG_ ESEIC_EngImmbRq : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ESEIC_EngImRqPsw : 15|56@0+ (1,0) [0|1] "" XXX + SG_ RstVTDTmprDtctd : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RstIllDrIdDevDtctd : 2|1@0+ (1,0) [0|1] "" XXX + SG_ RstDrIdDevLrnd : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150268928 GPS_Date_and_Time_LS: 6 XXX + SG_ CldrYr_154 : 7|8@0+ (1,2000) [2000|2255] "year" XXX + SG_ CldrMth_154 : 11|4@0+ (1,0) [0|15] "" XXX + SG_ CldrDay_154 : 20|5@0+ (1,0) [0|31] "days" XXX + SG_ HrsGroup : 29|6@0+ (1,0) [0|0] "" XXX + SG_ Hrs : 28|5@0+ (1,0) [0|31] "h" XXX + SG_ HrsV : 29|1@0+ (1,0) [0|1] "" XXX + SG_ MinsGroup : 38|7@0+ (1,0) [0|0] "" XXX + SG_ Mins : 37|6@0+ (1,0) [0|63] "min" XXX + SG_ MinsV : 38|1@0+ (1,0) [0|1] "" XXX + SG_ SecGroup : 46|7@0+ (1,0) [0|0] "" XXX + SG_ Sec : 45|6@0+ (1,0) [0|63] "s" XXX + SG_ SecV : 46|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150137856 RFA_Status_LS: 3 XXX + SG_ FobPrevLrndIndOn : 0|1@0+ (1,0) [0|1] "" XXX + SG_ Ky_IdDevNotPrIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ FbProgCustActRqd : 2|1@0+ (1,0) [0|1] "" XXX + SG_ KeyInWrnIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ VehSecAtoLrnAtv : 4|1@0+ (1,0) [0|1] "" XXX + SG_ Ky_IdDevPrgmAuthReq : 5|1@0+ (1,0) [0|1] "" XXX + SG_ LMTTCPrsnOffStat : 6|1@0+ (1,0) [0|1] "" XXX + SG_ VehSecAtoLrnDlyTmr : 12|5@0+ (1,0) [0|31] "min" XXX + SG_ FldTpMotReq : 15|3@0+ (1,0) [0|7] "" XXX + SG_ RemCtrlFobNumForProgER : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 2151677952 Chime_Command: 5 XXX + SG_ SndChrs : 3|28@0+ (1,0) [0|0] "" XXX + SG_ SC_SndTne : 3|4@0+ (1,0) [0|15] "" XXX + SG_ SC_SndCdnPrd : 15|8@0+ (10,0) [0|2550] "ms" XXX + SG_ SC_NmofRp : 23|8@0+ (1,0) [0|255] "reps" XXX + SG_ SC_SndDutCyc : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ SndLoc : 7|4@0+ (1,0) [0|0] "" XXX + SG_ SndLocRtRr : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SndLocLftRr : 5|1@0+ (1,0) [0|1] "" XXX + SG_ SndLocPasFr : 6|1@0+ (1,0) [0|1] "" XXX + SG_ SndLocDrFr : 7|1@0+ (1,0) [0|1] "" XXX + SG_ SndPriority : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 2150776832 Airbag_Status: 6 XXX + SG_ ShfUlkBrToShftIndCtrl : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ShftLkdBuStbltIndCtrl : 1|1@0+ (1,0) [0|1] "" XXX + SG_ SbItlkTrnsShftLvLkRd : 2|1@0+ (1,0) [0|1] "" XXX + SG_ MmryRclImpctDisRq : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EvntEnbld : 4|1@0+ (1,0) [0|1] "" XXX + SG_ SftyMuteRd : 5|1@0+ (1,0) [0|1] "" XXX + SG_ HybVehHiVltInvDisRqd : 6|1@0+ (1,0) [0|1] "" XXX + SG_ HybImpSnsDsbld : 7|1@0+ (1,0) [0|1] "" XXX + SG_ SIREvntSychCntr : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ FrPsngrStOccSnsngPriDat : 39|16@0+ (1,0) [0|39321] "" XXX + +BO_ 2150760448 Airbag_Impact_Data: 8 XXX + SG_ SIRDpl : 1|1@0+ (1,0) [0|1] "" XXX + SG_ NotPsSeatStat : 5|2@0+ (1,0) [0|3] "" XXX + SG_ NotDrvSeatStat : 7|2@0+ (1,0) [0|3] "" XXX + SG_ NotSecRowRtSeaOccStat : 9|2@0+ (1,0) [0|3] "" XXX + SG_ NotSndRwMdlSeatStat : 11|2@0+ (1,0) [0|3] "" XXX + SG_ NotSndRwRtSeatStat : 13|2@0+ (1,0) [0|3] "" XXX + SG_ NotSndRwLtSeatStat : 15|2@0+ (1,0) [0|3] "" XXX + SG_ NotEventStat : 17|2@0+ (1,0) [0|3] "" XXX + SG_ NotSecRowLeSeaOccStat : 25|2@0+ (1,0) [0|3] "" XXX + SG_ NotSecRowCtSeaOccStat : 27|2@0+ (1,0) [0|3] "" XXX + SG_ NotiFrntPasSeatOccSta : 34|3@0+ (1,0) [0|7] "" XXX + SG_ NoEvDeLoSt : 46|7@0+ (1,0) [0|0] "" XXX + SG_ NEDLSSdCrtnArbgDpld : 40|1@0+ (1,0) [0|1] "" XXX + SG_ NEDLSRtSdArbgDld : 41|1@0+ (1,0) [0|1] "" XXX + SG_ NEDLSLtSdArbgDld : 42|1@0+ (1,0) [0|1] "" XXX + SG_ NEDLSPaFrSt2De : 43|1@0+ (1,0) [0|1] "" XXX + SG_ NEDLSPaFrSt1De : 44|1@0+ (1,0) [0|1] "" XXX + SG_ NEDLSDrFrSt2De : 45|1@0+ (1,0) [0|1] "" XXX + SG_ NEDLSDrFrSt1De : 46|1@0+ (1,0) [0|1] "" XXX + SG_ NoEvSevSt : 54|7@0+ (1,0) [0|0] "" XXX + SG_ NESSRoSevSt : 48|1@0+ (1,0) [0|1] "" XXX + SG_ NESSRiSiSevSt : 49|1@0+ (1,0) [0|1] "" XXX + SG_ NESSReImpSevSt : 50|1@0+ (1,0) [0|1] "" XXX + SG_ NESSLeSiSevSt : 51|1@0+ (1,0) [0|1] "" XXX + SG_ NESSFrImpSt2SevSt : 52|1@0+ (1,0) [0|1] "" XXX + SG_ NESSFrImpSt1SevSt : 53|1@0+ (1,0) [0|1] "" XXX + SG_ NESSFrImpPreSevSt : 54|1@0+ (1,0) [0|1] "" XXX + SG_ NotiEventCount : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 2155872256 Fuel_Information: 6 XXX + SG_ FlLvlPctGroup : 0|9@0+ (1,0) [0|0] "" XXX + SG_ FlLvlPctV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ FlLvlPct : 15|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ FlInjRlCtRstOcc : 1|1@0+ (1,0) [0|1] "" XXX + SG_ FuelFltChgNwIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DrvStyPerfMdCsCrStVal : 5|3@0+ (1,0) [0|7] "" XXX + SG_ DrvStyPerfMdCsStAvl : 6|1@0+ (1,0) [0|1] "" XXX + SG_ RdWhlAngGroup : 23|8@0+ (1,0) [0|0] "" XXX + SG_ RdWhlAng : 22|7@0+ (0.703125,-45) [-45|44.296875] "deg" XXX + SG_ RdWhlAngV : 23|1@0+ (1,0) [0|1] "" XXX + SG_ VehPitchAngleGroup : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VehPitchAngle : 30|7@0+ (0.703125,-45) [-45|44.296875] "deg" XXX + SG_ VehPitchAngleV : 31|1@0+ (1,0) [0|1] "" XXX + SG_ FlInjRlCt : 39|16@0+ (3.05176E-005,0) [0|1.999970916] "liters" XXX + +BO_ 2156175360 Display_Measurement_System_LS: 1 XXX + SG_ DispMeasSysExt : 1|2@0+ (1,0) [0|3] "" XXX + SG_ DispMeasSys : 2|1@0+ (1,0) [0|1] "" XXX + SG_ NtVsnSysEnbld : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149859328 System_Power_Mode_Backup_LS: 1 XXX + SG_ SysBkupPwrMdEn : 2|1@0+ (1,0) [0|1] "" XXX + SG_ SysBkUpPwrMdGroup : 3|4@0+ (1,0) [0|0] "" XXX + SG_ SysBkUpPwrMd : 1|2@0+ (1,0) [0|3] "" XXX + SG_ SysBkUpPwrMdV : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 2158854144 ODIAction_IPC_LS: 8 XXX + SG_ ODIActn_IPC : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODIAI_DaTy : 5|6@0+ (1,0) [0|63] "" XXX + SG_ ODIAI_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAI_ActnID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAI_DspMID : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAI_ActnVal : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2158837760 ODIAction_AuxIP_LS: 8 XXX + SG_ ODIActn_AxIP : 5|62@0+ (1,0) [0|0] "" XXX + SG_ ODIAA_DaTy : 5|6@0+ (1,0) [0|63] "" XXX + SG_ ODIAA_FUCID : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAA_ActnID : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAA_DspMID : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ODIAA_ActnVal : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2159091712 ODI_IPC_2_TEL_LS: 8 XXX + SG_ ODI_IPC2TEL : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2154561536 Vehicle_Odo_LS: 5 XXX + SG_ VehOdoGroup : 7|40@0+ (1,0) [0|0] "" XXX + SG_ VehOdo : 7|32@0+ (0.015625,0) [0|67108863.984375] "km" XXX + SG_ VehOdoV : 32|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149908480 Brake_Pedal_Status_LS: 2 XXX + SG_ BrkPedInitTrvlAchvdStat : 1|2@0+ (1,0) [0|0] "" XXX + SG_ BrkPedTrvlAchvdV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ BrkPedTrvlAchvd : 1|1@0+ (1,0) [0|1] "" XXX + SG_ BrkPdlModTrvlGroup : 3|2@0+ (1,0) [0|0] "" XXX + SG_ BrkPdlModTrvl : 2|1@0+ (1,0) [0|1] "" XXX + SG_ BrkPdlModTrvlV : 3|1@0+ (1,0) [0|1] "" XXX + SG_ BrkPdlPos : 15|8@0+ (0.392157,0) [0|100.000035] "% full" XXX + +BO_ 2151268352 Column_Lock_Status: 1 XXX + SG_ ClmnLckTT : 1|2@0+ (1,0) [0|3] "" XXX + +BO_ 2150604800 Right_Rear_Door_Status: 1 XXX + SG_ RRDoorAjarSwAct : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150588416 Passenger_Door_Status_LS: 1 XXX + SG_ PDAjrSwAtv : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150596608 Left_Rear_Door_Status: 1 XXX + SG_ RLDoorAjarSwAct : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 2155036672 Climate_Control_General_Status: 6 XXX + SG_ ACCompNormLdGroup : 0|9@0+ (1,0) [0|0] "" XXX + SG_ ACCompNormLdV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ACCompNormLd : 15|8@0+ (0.1,0) [0|25.5] "l/min" XXX + SG_ ACCmEngRunReq : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ACCmpsrFldOn : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ACCompModReq : 5|2@0+ (1,0) [0|3] "" XXX + SG_ ClmtCtrlTrgtTemp : 17|10@0+ (0.1,-10) [-10|92.3] "deg C" XXX + +BO_ 2150424576 Engine_Information_3_LS: 8 XXX + SG_ TrnsEngdStateGroup : 2|3@0+ (1,0) [0|0] "" XXX + SG_ TrnsEngdState : 1|2@0+ (1,0) [0|3] "" XXX + SG_ TrnsEngdStateV : 2|1@0+ (1,0) [0|1] "" XXX + SG_ ACRfHiSdFldPrsGroup : 3|20@0+ (1,0) [0|0] "" XXX + SG_ ACRfHiSdFldPrsV : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ACRfHiSdFldPrs : 23|8@0+ (14,0) [0|3570] "kPaG" XXX + SG_ ACCompCmnd : 4|1@0+ (1,0) [0|1] "" XXX + SG_ RrAxlELSDCplLwResGroup : 5|46@0+ (1,0) [0|0] "" XXX + SG_ RrAxlELSDCplLwResV : 5|1@0+ (1,0) [0|1] "" XXX + SG_ RrAxlELSDCplLwRes : 47|8@0+ (10,0) [0|2550] "Nm" XXX + SG_ EngAirIntBstPrGroup : 6|39@0+ (1,0) [0|0] "" XXX + SG_ EngAirIntBstPrV : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EngAirIntBstPr : 39|8@0- (1,0) [-128|127] "kPaG" XXX + SG_ ExtHlStrAssCsStAvl : 7|1@0+ (1,0) [0|1] "" XXX + SG_ TrnsRngInhbtStat : 10|3@0+ (1,0) [0|7] "" XXX + SG_ DrvtShftCntrlTrgtGear : 14|4@0+ (1,0) [0|15] "" XXX + SG_ ACCmpNrmLdGrdAld : 31|8@0+ (0.1,0) [0|25.5] "dm3/m/s" XXX + SG_ EngTrqDrRqdExtRngGroup : 52|13@0+ (1,0) [0|0] "" XXX + SG_ EngTrqDrRqdExtRng : 51|12@0+ (0.5,-848) [-848|1199.5] "Nm" XXX + SG_ EngTrqDrRqdExtRngV : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ExtHlStrAssCsCrStVal : 55|3@0+ (1,0) [0|7] "" XXX + +BO_ 2150416384 Engine_Information_2_LS: 8 XXX + SG_ EngBstPrsIndGroup : 0|33@0+ (1,0) [0|0] "" XXX + SG_ EngBstPrsIndV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ EngBstPrsInd : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ VaccBoostFailure : 2|1@0+ (1,0) [0|1] "" XXX + SG_ GenFld : 3|1@0+ (1,0) [0|1] "" XXX + SG_ EngSpdLmtnMdAct : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PTWrmgWtToShftIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ EngNEmsnsRelMalfAct : 6|1@0+ (1,0) [0|1] "" XXX + SG_ EngCstFlCutAct : 7|1@0+ (1,0) [0|1] "" XXX + SG_ EngRunAtv : 8|1@0+ (1,0) [0|1] "" XXX + SG_ EngIdlAtv : 11|1@0+ (1,0) [0|1] "" XXX + SG_ VehTopSpdLmtMdAct : 13|1@0+ (1,0) [0|1] "" XXX + SG_ EngCylDeactMd : 15|2@0+ (1,0) [0|3] "" XXX + SG_ TransEstGearGroup : 20|5@0+ (1,0) [0|0] "" XXX + SG_ TransEstGear : 19|4@0+ (1,0) [0|15] "" XXX + SG_ TransEstGearV : 20|1@0+ (1,0) [0|1] "" XXX + SG_ EngTrqActExtRngGroup : 21|46@0+ (1,0) [0|0] "" XXX + SG_ EngTrqActExtRngV : 21|1@0+ (1,0) [0|1] "" XXX + SG_ EngTrqActExtRng : 51|12@0+ (0.5,-848) [-848|1199.5] "Nm" XXX + SG_ EngVDA : 22|1@0+ (1,0) [0|1] "" XXX + SG_ TrnsVDA : 23|1@0+ (1,0) [0|1] "" XXX + SG_ EngCoolFanSpd : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ VehTopSpdLmtArbVal : 47|8@0+ (2,0) [0|510] "km / h" XXX + SG_ EngSpdStat : 53|2@0+ (1,0) [0|3] "" XXX + SG_ RmVhStrtEngRng : 54|1@0+ (1,0) [0|1] "" XXX + SG_ TrnCrpMdAtv : 55|1@0+ (1,0) [0|1] "" XXX + +BO_ 2150408192 Engine_Information_1_LS: 8 XXX + SG_ TrnsSftMdStat : 2|3@0+ (1,0) [0|7] "" XXX + SG_ ThrPosGroup : 3|36@0+ (1,0) [0|0] "" XXX + SG_ ThrPosV : 3|1@0+ (1,0) [0|1] "" XXX + SG_ ThrPos : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ AccActPosGroup : 4|45@0+ (1,0) [0|0] "" XXX + SG_ AccActPosV : 4|1@0+ (1,0) [0|1] "" XXX + SG_ AccActPos : 47|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ ElcRngSelDrvAct : 5|1@0+ (1,0) [0|1] "" XXX + SG_ TmpDrvrShftCtlAct : 6|1@0+ (1,0) [0|1] "" XXX + SG_ AccPdlOvrrdAtv : 7|1@0+ (1,0) [0|1] "" XXX + SG_ TrnShftPtrnActStat : 10|3@0+ (1,0) [0|7] "" XXX + SG_ TransTUDMdStat : 12|2@0+ (1,0) [0|3] "" XXX + SG_ Eng12vStrtrMtrCmmdOn : 13|1@0+ (1,0) [0|1] "" XXX + SG_ EngRunng : 14|1@0+ (1,0) [0|1] "" XXX + SG_ TrnsShftLvrPosGroup : 15|48@0+ (1,0) [0|0] "" XXX + SG_ TrnsShftLvrPosV : 15|1@0+ (1,0) [0|1] "" XXX + SG_ TrnsShftLvrPos : 51|4@0+ (1,0) [0|15] "" XXX + SG_ EngSpd : 23|16@0+ (0.25,0) [0|16383.75] "rpm" XXX + SG_ AutoTransComndGear : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CrsCntEnbld : 56|1@0+ (1,0) [0|1] "" XXX + SG_ CltStartSwAtvGroup : 58|2@0+ (1,0) [0|0] "" XXX + SG_ CltStartSwAtv : 57|1@0+ (1,0) [0|1] "" XXX + SG_ CltStartSwAtvV : 58|1@0+ (1,0) [0|1] "" XXX + SG_ TopTrvlCltchSwActGroup : 60|2@0+ (1,0) [0|0] "" XXX + SG_ TopTrvlCltchSwAct : 59|1@0+ (1,0) [0|1] "" XXX + SG_ TopTrvlCltchSwActV : 60|1@0+ (1,0) [0|1] "" XXX + SG_ AdptPsngrSeatStng : 63|3@0+ (1,0) [0|7] "" XXX + +BO_ 2155954176 Climate_Control_Basic_Status_LS: 4 XXX + SG_ ACHtIdleBstLevReq : 1|2@0+ (1,0) [0|3] "" XXX + SG_ ClimCtrlAftBlowModActv : 2|1@0+ (1,0) [0|1] "" XXX + SG_ AirCndActIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ ClmCntlExtDefActIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ClntCircPmpRq : 7|1@0+ (1,0) [0|1] "" XXX + SG_ ClmCntFrBlwFnSp : 15|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ AirCndCmptLdEst : 23|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ ClmCntRrBlwFnSp : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + +BO_ 2153971712 Driver_Door_Status: 1 XXX + SG_ LftglsAjrSwAct : 1|1@0+ (1,0) [0|1] "" XXX + SG_ LftglsRelSwAct : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DDAjrSwAtvGroup : 7|8@0+ (1,0) [0|0] "" XXX + SG_ DDAjrSwAtv : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DDAjrSwAtvM : 7|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149875712 Battery_Voltage: 7 XXX + SG_ BatVltGroup : 0|17@0+ (1,0) [0|0] "" XXX + SG_ BatVltV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ BatVlt : 23|8@0+ (0.1,3) [3|28.5] "volts" XXX + SG_ BatSaverIO : 1|1@0+ (1,0) [0|1] "" XXX + SG_ SrvBattChrgSysIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ BatSOCGroup : 3|28@0+ (1,0) [0|0] "" XXX + SG_ BatSOCV : 3|1@0+ (1,0) [0|1] "" XXX + SG_ BatSOC : 31|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ BattStOfChrgCrtyLow : 4|1@0+ (1,0) [0|1] "" XXX + SG_ IntlgntBattSnsFldIO : 5|1@0+ (1,0) [0|1] "" XXX + SG_ BattStOfChrgLowIO : 6|1@0+ (1,0) [0|1] "" XXX + SG_ DCCnvStblznErrIO : 7|1@0+ (1,0) [0|1] "" XXX + SG_ EnrgMgtLdShdRq : 11|4@0+ (1,0) [0|15] "" XXX + SG_ BattVltIRq : 13|2@0+ (1,0) [0|3] "" XXX + SG_ PwrMdOffBattSOC : 39|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ BattCrntFltrd : 47|8@0- (0.5,0) [-64|63.5] "A" XXX + SG_ BatSvrMdSevLvl : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 2151186432 Auto_High_Beam_Status: 1 XXX + SG_ AutoBmSlctStat : 1|2@0+ (1,0) [0|3] "" XXX + SG_ CtLghtDet : 2|1@0+ (1,0) [0|1] "" XXX + SG_ AutoHgBmCtrlInOn : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 2149629952 Lighting_Status_LS: 5 XXX + SG_ OtsdAmbtLtLvlStatGroup : 0|23@0+ (1,0) [0|0] "" XXX + SG_ OtsdAmbtLtLvlStatV : 0|1@0+ (1,0) [0|1] "" XXX + SG_ OtsdAmbtLtLvlStat : 27|2@0+ (1,0) [0|3] "" XXX + SG_ DRLAct : 1|1@0+ (1,0) [0|1] "" XXX + SG_ HazSwAtv : 2|1@0+ (1,0) [0|1] "" XXX + SG_ PrkLtLeftIO : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PrkLtRightIO : 4|1@0+ (1,0) [0|1] "" XXX + SG_ TrnSwAct : 6|2@0+ (1,0) [0|3] "" XXX + SG_ FrFogLmpsAct : 7|1@0+ (1,0) [0|1] "" XXX + SG_ PrkLtLeftOn : 8|1@0+ (1,0) [0|1] "" XXX + SG_ FrFgLtIO : 9|1@0+ (1,0) [0|1] "" XXX + SG_ AutoLtsInactIO : 10|1@0+ (1,0) [0|1] "" XXX + SG_ AutoLtsActIO : 11|1@0+ (1,0) [0|1] "" XXX + SG_ RrFgLtIO : 12|1@0+ (1,0) [0|1] "" XXX + SG_ HiBmIO : 13|1@0+ (1,0) [0|1] "" XXX + SG_ PrkLtIO : 14|1@0+ (1,0) [0|1] "" XXX + SG_ BrkLtsAtv : 15|1@0+ (1,0) [0|1] "" XXX + SG_ FlToPsSwAtv : 16|1@0+ (1,0) [0|1] "" XXX + SG_ RevLmpAtv : 17|1@0+ (1,0) [0|1] "N/A" XXX + SG_ PrkngLtsAct : 18|1@0+ (1,0) [0|1] "" XXX + SG_ RrFogLmpsAct : 19|1@0+ (1,0) [0|1] "" XXX + SG_ HiBmReqd : 20|1@0+ (1,0) [0|1] "" XXX + SG_ AutoBmSlctAllwd : 21|1@0+ (1,0) [0|1] "" XXX + SG_ PrkLtRightOn : 22|1@0+ (1,0) [0|1] "" XXX + SG_ SrvlnceMdAct : 23|1@0+ (1,0) [0|1] "" XXX + SG_ RtTrnLmpAtv : 25|2@0+ (1,0) [0|3] "" XXX + SG_ LftTrnLmpAtv : 29|2@0+ (1,0) [0|3] "" XXX + SG_ MainLghtSw : 31|2@0+ (1,0) [0|3] "N/A" XXX + SG_ HdlmpBmSelectStat : 33|2@0+ (1,0) [0|3] "" XXX + +BO_ 2149646336 Vehicle_Speed_Information: 8 XXX + SG_ VehSpdAvgDrvnGroup : 7|16@0+ (1,0) [0|0] "" XXX + SG_ VehSpdAvgDrvn : 6|15@0+ (0.015625,0) [0|511.984375] "km / h" XXX + SG_ VehSpdAvgDrvnV : 7|1@0+ (1,0) [0|1] "" XXX + SG_ DstRolCntAvgDrnRstOc : 21|1@0+ (1,0) [0|1] "" XXX + SG_ DistRollCntAvgDrvnGroup : 22|15@0+ (1,0) [0|0] "" XXX + SG_ DistRollCntAvgDrvn : 20|13@0+ (0.125,0) [0|1023.875] "m" XXX + SG_ DistRollCntAvgDrvnV : 22|1@0+ (1,0) [0|1] "" XXX + SG_ VehSpdAvgDrvnSrc : 23|1@0+ (1,0) [0|1] "" XXX + SG_ VehSpdAvgNDrvnGroup : 38|17@0+ (1,0) [0|0] "" XXX + SG_ VehSpdAvgNDrvn : 38|15@0+ (0.015625,0) [0|511.984375] "km / h" XXX + SG_ VehSpdAvgNDrvnV : 54|1@0+ (1,0) [0|1] "" XXX + SG_ DstRolCntAvgNonDrvnGroup : 39|32@0+ (1,0) [0|0] "" XXX + SG_ DstRolCntAvgNonDrvnV : 39|1@0+ (1,0) [0|1] "" XXX + SG_ DstRolCntAvgNonDrvn : 52|13@0+ (0.125,0) [0|1023.875] "m" XXX + SG_ DstRolCntAvNDrRstOc : 53|1@0+ (1,0) [0|1] "" XXX + SG_ DistRollCntAvgDrvnSrc : 55|1@0+ (1,0) [0|1] "" XXX + +BO_ 2154053632 Dimming_Information_LS: 3 XXX + SG_ IntDimNtPnlAtv : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DispNtSchmAtv : 1|1@0+ (1,0) [0|1] "" XXX + SG_ CargoLmpActIO : 2|1@0+ (1,0) [0|1] "" XXX + SG_ IntDimLvl : 15|8@0+ (0.392157,0) [0|100.000035] "%" XXX + SG_ IntDimDspLvl : 23|8@0+ (0.392157,0) [0|100.000035] "%" XXX + +BO_ 2149851136 System_Power_Mode_LS: 1 XXX + SG_ SysPwrMdGroup : 2|3@0+ (1,0) [0|0] "" XXX + SG_ SysPwrMd : 1|2@0+ (1,0) [0|3] "" XXX + SG_ SysPwrMdV : 2|1@0+ (1,0) [0|1] "" XXX + SG_ KylsStrtAuthRq : 3|1@0+ (1,0) [0|1] "" XXX + +BO_ 2159124480 ODI_AuxIP_2_TEL_LS: 8 XXX + SG_ ODI_AxIP2TEL : 7|64@0+ (1,0) [0|1.84467440737096E+019] "" XXX + +BO_ 2151530496 TPM_Display_Commands: 6 XXX + SG_ TPMTrLrnMdCmplt : 0|1@0+ (1,0) [0|1] "" XXX + SG_ TrPrsMntrAtLocFld : 1|1@0+ (1,0) [0|1] "" XXX + SG_ TrPrsMntrTrLdStat : 3|2@0+ (1,0) [0|3] "" XXX + SG_ TireTrdTmpStat : 6|3@0+ (1,0) [0|7] "" XXX + SG_ TrFrntAxlPresStat : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TrRrAxlPresStat : 11|2@0+ (1,0) [0|3] "" XXX + SG_ WintTrRecIndOn : 12|1@0+ (1,0) [0|1] "" XXX + SG_ TrPrsMntrFld : 13|1@0+ (1,0) [0|1] "" XXX + SG_ TireLocatnWarnEn : 15|1@0+ (1,0) [0|1] "" XXX + SG_ HVChgSyChgLvPfStRmt1 : 18|3@0+ (1,0) [0|7] "" XXX + SG_ StTODChrgTmpOvrdRmt1 : 20|2@0+ (1,0) [0|3] "" XXX + SG_ PrtyChrgRqRmt1 : 22|2@0+ (1,0) [0|3] "" XXX + SG_ OfBrdHVCVhCsChRqRmt1 : 23|1@0+ (1,0) [0|1] "" XXX + SG_ HVBatTmBsDlChStRqRmt1 : 28|21@0+ (1,0) [0|0] "" XXX + SG_ HVBTBDCSRR1_DChHStRq : 28|5@0+ (1,0) [0|31] "hr" XXX + SG_ HVBTBDCSRR1_DChSlSRq : 35|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBDCSRR1_DChDStRq : 39|4@0+ (1,0) [0|15] "" XXX + SG_ HVBTBDCSRR1_DChMHSRq : 45|6@0+ (1,0) [0|63] "min" XXX + SG_ HVBTBDCSRR1_DChSnSRq : 47|2@0+ (1,0) [0|3] "" XXX + SG_ HVBatTmBsChgMdRqRmt1 : 31|3@0+ (1,0) [0|7] "" XXX + + + +BA_DEF_ "UseGMParameterIDs" INT 0 0; +BA_DEF_ "ProtocolType" STRING ; +BA_DEF_ "BusType" STRING ; +BA_DEF_DEF_ "UseGMParameterIDs" 1; +BA_DEF_DEF_ "ProtocolType" "GMLAN"; +BA_DEF_DEF_ "BusType" ""; +BA_ "ProtocolType" "GMLAN"; +BA_ "BusType" "CAN"; + diff --git a/opendbc/gm_global_a_object.dbc b/opendbc_repo/opendbc/dbc/gm_global_a_object.dbc similarity index 100% rename from opendbc/gm_global_a_object.dbc rename to opendbc_repo/opendbc/dbc/gm_global_a_object.dbc diff --git a/opendbc_repo/opendbc/dbc/gm_global_a_powertrain_expansion.dbc b/opendbc_repo/opendbc/dbc/gm_global_a_powertrain_expansion.dbc new file mode 100644 index 000000000000000..b18ac6974da42f9 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/gm_global_a_powertrain_expansion.dbc @@ -0,0 +1,56 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: +BU_: K1_APM +BO_ 470 APM_Stats: 7 K1_APM + SG_ APM_Low_Voltage_Sensed : 16|8@1+ (0.0787402,0) [0|0] "V" Vector__XXX + SG_ APM_Temperature_1 : 24|8@1+ (1,-40) [0|0] "C" Vector__XXX + SG_ APM_Temperature_2 : 32|8@1+ (1,-40) [0|0] "C" Vector__XXX + SG_ APM_Low_Voltage_Current_Output : 40|8@1- (1,0) [0|0] "A" Vector__XXX + SG_ APM_Status : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ APM_High_Voltage_Input_Current : 8|8@1- (0.15,-7) [0|0] "A" Vector__XXX + SG_ APM_Counter : 48|8@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 468 APM_Command: 2 K1_APM + SG_ APM_Status : 0|8@1+ (1,0) [0|0] "" Vector__XXX + SG_ APM_Voltage_Requested : 8|8@1+ (0.0787402,0) [0|0] "V" Vector__XXX + +BA_DEF_ BO_ "GenMsgBackgroundColor" STRING ; +BA_DEF_ BO_ "GenMsgForegroundColor" STRING ; +BA_DEF_ BO_ "isj1939dbc" INT 0 0; +BA_DEF_DEF_ "GenMsgBackgroundColor" "#ffffff"; +BA_DEF_DEF_ "GenMsgForegroundColor" "#000000"; +BA_DEF_DEF_ "isj1939dbc" 0; +CM_ BU_ K1_APM "14V Power Module"; +VAL_ 468 APM_Status 0 "Off" 160 "On"; diff --git a/opendbc/gm_global_a_powertrain_generated.dbc b/opendbc_repo/opendbc/dbc/gm_global_a_powertrain_generated.dbc similarity index 94% rename from opendbc/gm_global_a_powertrain_generated.dbc rename to opendbc_repo/opendbc/dbc/gm_global_a_powertrain_generated.dbc index 1c78dd7b07fbc13..429665ccb9b32ab 100644 --- a/opendbc/gm_global_a_powertrain_generated.dbc +++ b/opendbc_repo/opendbc/dbc/gm_global_a_powertrain_generated.dbc @@ -1,23 +1,5 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 NEO - SG_ GAS_COMMAND : 7|16@0+ (0.125677,-75.909) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.251976,-76.601) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.125677,-75.909) [0|1] "" NEO - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.251976,-76.601) [0|1] "" NEO - SG_ STATE : 39|4@0+ (1,0) [0|15] "" NEO - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" NEO - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" NEO - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - CM_ "gm_global_a_powertrain.dbc starts here"; VERSION "" @@ -189,6 +171,7 @@ BO_ 497 BCMGeneralPlatformStatus: 8 K9_BCM SG_ ParkBrakeSwActive : 36|1@0+ (1,0) [0|3] "" XXX BO_ 500 SportMode: 6 XXX + SG_ SnowIceMode : 9|1@0+ (1,0) [0|1] "" XXX SG_ SportMode : 15|1@0+ (1,0) [0|1] "" XXX BO_ 501 ECMPRDNL2: 8 K20_ECM diff --git a/opendbc/honda_accord_2018_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_accord_2018_can_generated.dbc similarity index 97% rename from opendbc/honda_accord_2018_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_accord_2018_can_generated.dbc index 85947333d52d928..ea9d30f3c889275 100644 --- a/opendbc/honda_accord_2018_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_accord_2018_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX BO_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; 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_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/honda_civic_ex_2022_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_civic_ex_2022_can_generated.dbc similarity index 95% rename from opendbc/honda_civic_ex_2022_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_civic_ex_2022_can_generated.dbc index 8433001dcfbf3b9..7ec5b1327859d72 100644 --- a/opendbc/honda_civic_ex_2022_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_civic_ex_2022_can_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON @@ -340,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX BO_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -414,7 +398,8 @@ CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; 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_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _steering_sensors_a.dbc starts here"; BO_ 330 STEERING_SENSORS: 8 EPS @@ -476,6 +461,16 @@ BO_ 467 CRUISE_FAULT_STATUS: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX +BO_ 477 GEARBOX_ALT_2: 8 XXX + SG_ GEAR_MT : 39|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 495 SPEED_LIMIT_DASH_DISPLAY: 8 ADAS + SG_ SPEED_LIMIT : 47|8@0+ (1,0) [0|255] "mph" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + BO_ 829 LKAS_HUD: 8 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY @@ -516,7 +511,9 @@ BO_ 254913108 LKAS_HUD_2: 8 ADAS CM_ 446 "If exists, describes cruise faults and what the PCM uses for brake press detection."; CM_ SG_ 456 IDLESTOP_ALLOW "allows car to turn off engine at a standstill"; CM_ SG_ 456 STANDSTILL "set to 1 when camera requests -4.0 m/s^2"; +CM_ SG_ 495 SPEED_LIMIT "Defaults to 0xFF if no speed limit found"; 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_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P" 0 "B" ; +VAL_ 477 GEAR_MT 14 "reverse" 6 "6th" 5 "5th" 4 "4th" 3 "3rd" 2 "2nd" 1 "1st" 0 "Clutch"; diff --git a/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc similarity index 97% rename from opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc index 75ba176a8f51e01..60000d88f65bb2e 100644 --- a/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX BO_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; 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_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/honda_civic_touring_2016_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_civic_touring_2016_can_generated.dbc similarity index 95% rename from opendbc/honda_civic_touring_2016_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_civic_touring_2016_can_generated.dbc index db6b21423f8a78b..e7b02285e831999 100644 --- a/opendbc/honda_civic_touring_2016_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_civic_touring_2016_can_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc_repo/opendbc/dbc/honda_clarity_hybrid_2018_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_clarity_hybrid_2018_can_generated.dbc new file mode 100644 index 000000000000000..8353038ba3fac7a --- /dev/null +++ b/opendbc_repo/opendbc/dbc/honda_clarity_hybrid_2018_can_generated.dbc @@ -0,0 +1,387 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + + +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + SG_ CAR_SPEED : 7|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "mph" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ IMPERIAL_UNIT : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "kph" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF_2 : 36|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01_2 : 55|1@0+ (1,0) [0|1] "" BDY + SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" BDY + SG_ CHIME : 51|3@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY + SG_ ICONS : 63|2@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 780 PCM_SPEED "Used by Nidec"; +CM_ SG_ 780 PCM_GAS "Used by Nidec"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; + +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _nidec_common.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST_ALT : 11|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_X00 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_X00_2 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_1 : 31|1@0+ (1,0) [0|1] "" EBCM + SG_ AEB_REQ_1 : 29|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_REQ_2 : 26|3@0+ (1,0) [0|7] "" XXX + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ SET_ME_X00_3 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ AEB_STATUS : 41|2@0+ (1,0) [0|3] "" XXX + SG_ COMPUTER_BRAKE_ALT : 55|10@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; +CM_ SG_ 506 COMPUTER_BRAKE_ALT "Used by dual-can Nidec"; +CM_ SG_ 506 BRAKE_PUMP_REQUEST_ALT "Used by dual-can Nidec"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; + + +CM_ "Imported file _steering_sensors_a.dbc starts here"; +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ "honda_clarity_hybrid_2018_can.dbc starts here"; + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 388 BRAKE_ERROR: 8 XXX + SG_ BRAKE_ERROR_1 : 32|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 34|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 545 ECON_STATUS: 6 XXX + SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 768 VEHICLE_STATE: 8 ADAS + SG_ SET_ME_XF9 : 7|8@0+ (1,0) [0|255] "" Vector__XXX + SG_ VEHICLE_SPEED : 15|8@0+ (1,0) [0|255] "kph" Vector__XXX + SG_ SET_ME_X8A : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_XD0 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SALTED_WITH_IDX : 39|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 769 VEHICLE_STATE2: 8 ADAS + SG_ SET_ME_X5D : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X02 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X5F : 39|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ CMBS_BUTTON : 22|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ REVERSE_LIGHT : 18|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +BO_ 1302 XXX_27: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; +CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; + +VAL_ 399 STEER_STATUS 5 "tmp_fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ; +VAL_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; +VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; +VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; diff --git a/opendbc/honda_crv_ex_2017_body_generated.dbc b/opendbc_repo/opendbc/dbc/honda_crv_ex_2017_body_generated.dbc similarity index 100% rename from opendbc/honda_crv_ex_2017_body_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_crv_ex_2017_body_generated.dbc diff --git a/opendbc/honda_crv_ex_2017_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_crv_ex_2017_can_generated.dbc similarity index 97% rename from opendbc/honda_crv_ex_2017_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_crv_ex_2017_can_generated.dbc index 9f3dc0fba9dbb92..06ec21b248064b7 100644 --- a/opendbc/honda_crv_ex_2017_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_crv_ex_2017_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX BO_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; 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_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/honda_crv_executive_2016_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_crv_executive_2016_can_generated.dbc similarity index 94% rename from opendbc/honda_crv_executive_2016_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_crv_executive_2016_can_generated.dbc index c218b19ed586486..f62a28bcd3d6b96 100644 --- a/opendbc/honda_crv_executive_2016_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_crv_executive_2016_can_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc/honda_crv_touring_2016_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_crv_touring_2016_can_generated.dbc similarity index 94% rename from opendbc/honda_crv_touring_2016_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_crv_touring_2016_can_generated.dbc index 8b3f1b208bb5f0f..66ce03d57461df7 100644 --- a/opendbc/honda_crv_touring_2016_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_crv_touring_2016_can_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc/honda_fit_ex_2018_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_fit_ex_2018_can_generated.dbc similarity index 94% rename from opendbc/honda_fit_ex_2018_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_fit_ex_2018_can_generated.dbc index 05cd391c781580b..8f3803387951e09 100644 --- a/opendbc/honda_fit_ex_2018_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_fit_ex_2018_can_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc_repo/opendbc/dbc/honda_fit_hybrid_2018_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_fit_hybrid_2018_can_generated.dbc new file mode 100644 index 000000000000000..c1247b270891c7e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/honda_fit_hybrid_2018_can_generated.dbc @@ -0,0 +1,343 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + + +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + SG_ CAR_SPEED : 7|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "mph" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ IMPERIAL_UNIT : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "kph" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF_2 : 36|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01_2 : 55|1@0+ (1,0) [0|1] "" BDY + SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" BDY + SG_ CHIME : 51|3@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY + SG_ ICONS : 63|2@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 780 PCM_SPEED "Used by Nidec"; +CM_ SG_ 780 PCM_GAS "Used by Nidec"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; + +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _nidec_common.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + +BO_ 506 BRAKE_COMMAND: 8 ADAS + SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM + SG_ BRAKE_PUMP_REQUEST_ALT : 11|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_X00 : 23|3@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_X00_2 : 19|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM + SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM + SG_ SET_ME_1 : 31|1@0+ (1,0) [0|1] "" EBCM + SG_ AEB_REQ_1 : 29|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_REQ_2 : 26|3@0+ (1,0) [0|7] "" XXX + SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM + SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM + SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM + SG_ SET_ME_X00_3 : 44|1@0+ (1,0) [0|1] "" EBCM + SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM + SG_ AEB_STATUS : 41|2@0+ (1,0) [0|3] "" XXX + SG_ COMPUTER_BRAKE_ALT : 55|10@0+ (1,0) [0|0] "" EBCM + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; +CM_ SG_ 506 COMPUTER_BRAKE_ALT "Used by dual-can Nidec"; +CM_ SG_ 506 BRAKE_PUMP_REQUEST_ALT "Used by dual-can Nidec"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; + +CM_ "honda_fit_hybrid_2018_can.dbc starts here"; + +BO_ 228 STEERING_CONTROL: 5 ADAS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 419 GEARBOX: 8 PCM + SG_ GEAR : 7|8@0+ (1,0) [0|256] "" EON + SG_ GEAR_SHIFTER : 35|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 422 SCM_BUTTONS: 8 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON + SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON + SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 545 ECON_STATUS: 5 XXX + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON + SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EON + +BO_ 660 SCM_FEEDBACK: 8 SCM + SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON + SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 862 HIGHBEAM_CONTROL: 8 ADAS + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 ADAS + SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY + SG_ ZEROS_BOH2 : 31|8@0+ (1,0) [0|127] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|15] "" BDY + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|15] "" BDY + SG_ LEAD_SPEED : 39|9@0+ (1,0) [0|127] "" BDY + SG_ LEAD_STATE : 46|3@0+ (1,0) [0|127] "" BDY + SG_ LEAD_DISTANCE : 43|5@0+ (1,0) [0|31] "" BDY + SG_ ZEROS_BOH3 : 54|7@0+ (1,0) [0|127] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; + +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_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; +VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; +VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; +VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; diff --git a/opendbc/honda_insight_ex_2019_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_insight_ex_2019_can_generated.dbc similarity index 97% rename from opendbc/honda_insight_ex_2019_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_insight_ex_2019_can_generated.dbc index ccbf25bfc740727..cbb3d568d406d13 100644 --- a/opendbc/honda_insight_ex_2019_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_insight_ex_2019_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX BO_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; 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_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/honda_odyssey_exl_2018_generated.dbc b/opendbc_repo/opendbc/dbc/honda_odyssey_exl_2018_generated.dbc similarity index 95% rename from opendbc/honda_odyssey_exl_2018_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_odyssey_exl_2018_generated.dbc index 1dd222ed970193f..dcad96db25e0769 100644 --- a/opendbc/honda_odyssey_exl_2018_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_odyssey_exl_2018_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc similarity index 94% rename from opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc rename to opendbc_repo/opendbc/dbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc index b109a70b6274536..7d17803d0945916 100644 --- a/opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc +++ b/opendbc_repo/opendbc/dbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc @@ -1,24 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _honda_common.dbc starts here"; BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc_repo/opendbc/dbc/honda_pilot_2023_can_generated.dbc b/opendbc_repo/opendbc/dbc/honda_pilot_2023_can_generated.dbc new file mode 100644 index 000000000000000..84cc64f01ab62d9 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/honda_pilot_2023_can_generated.dbc @@ -0,0 +1,498 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + + +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + SG_ CAR_SPEED : 7|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "mph" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ IMPERIAL_UNIT : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "kph" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF_2 : 36|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01_2 : 55|1@0+ (1,0) [0|1] "" BDY + SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" BDY + SG_ CHIME : 51|3@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY + SG_ ICONS : 63|2@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 780 PCM_SPEED "Used by Nidec"; +CM_ SG_ 780 PCM_GAS "Used by Nidec"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; + +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _bosch_2018.dbc starts here"; +BO_ 148 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 228 STEERING_CONTROL: 5 EON + SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ STEER_DOWN_TO_ZERO : 38|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 229 BOSCH_SUPPLEMENTAL_1: 8 XXX + SG_ SET_ME_X04 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 8|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X80 : 16|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X10 : 24|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 232 BRAKE_HOLD: 7 XXX + SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX + SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX + SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 545 XXX_16: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 576 LEFT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 577 LEFT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 579 RIGHT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 580 RIGHT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 582 ADJACENT_LEFT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 583 ADJACENT_LEFT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 585 ADJACENT_RIGHT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 586 ADJACENT_RIGHT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ HUD_LEAD : 40|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_64 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH3 : 47|7@0+ (1,0) [0|127] "" XXX + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 576 LINE_DISTANCE_VISIBLE "Length of line visible, undecoded"; +CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, indicates location of the portion of the line furthest from the car, undecoded"; +CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; +CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; +CM_ SG_ 577 LINE_SOLID "1 = line is solid"; + +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_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; + +CM_ "Imported file _steering_sensors_a.dbc starts here"; +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ "honda_pilot_2023_can.dbc starts here"; + +BO_ 419 GEARBOX: 8 XXX + SG_ GEAR_SHIFTER : 24|8@1+ (1,0) [0|255] "" XXX + SG_ GEAR : 32|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ GAS_COMMAND : 7|16@0- (1,0) [0|0] "" XXX + SG_ ACCEL_COMMAND : 31|11@0- (0.01,0) [0|0] "m/s2" XXX + SG_ BRAKE_LIGHTS : 62|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_REQUEST : 34|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL : 35|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_RELEASE : 36|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_STATUS : 33|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_BRAKING : 47|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_PREPARE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 829 LKAS_HUD: 8 XXX + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" XXX + SG_ BOH : 6|7@0+ (1,0) [0|127] "" XXX + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" XXX + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" XXX + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DTC : 13|1@0+ (1,0) [0|1] "" XXX + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" XXX + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" XXX + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" XXX + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LANE_LINES : 36|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; +CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; +CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; +CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; +CM_ SG_ 829 LANE_LINES "related to lane lines on cluster, left/right white/green"; + +VAL_ 419 GEAR_SHIFTER 2 "S" 32 "D" 16 "N" 8 "R" 4 "P"; +VAL_ 419 GEAR 26 "S" 20 "D" 19 "N" 18 "R" 17 "P"; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 829 LANE_LINES 7 "both_lines_green" 6 "both_lines_white" 2 "left_line_white" 0 "no_lines"; diff --git a/opendbc_repo/opendbc/dbc/hongqi_hs5.dbc b/opendbc_repo/opendbc/dbc/hongqi_hs5.dbc new file mode 100644 index 000000000000000..76b41d873cce9aa --- /dev/null +++ b/opendbc_repo/opendbc/dbc/hongqi_hs5.dbc @@ -0,0 +1,160 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 146 ECM_1: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ THROTTLE_1 : 8|12@1+ (1,0) [0|255] "" XXX + SG_ THROTTLE_2 : 24|8@1+ (1,0) [0|255] "" XXX + SG_ THROTTLE_3 : 32|8@1+ (1,0) [0|255] "" XXX + SG_ DRIVER_THROTTLE : 40|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 192 ABS_1: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|15] "" XXX + SG_ FRONT_LEFT : 8|16@1+ (0.01,0) [0|65535] "km/h" XXX + SG_ FRONT_RIGHT : 24|16@1+ (0.01,0) [0|65535] "km/h" XXX + SG_ VEHICLE_SPEED : 40|16@1+ (0.01,0) [0|65535] "km/h" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 194 ABS_2: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|15] "" XXX + SG_ REAR_LEFT : 8|16@1+ (0.01,0) [0|65535] "km/h" XXX + SG_ REAR_RIGHT : 24|16@1+ (0.01,0) [0|65535] "km/h" XXX + SG_ BRAKE_PRESSURE : 40|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 208 EPS_1: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|15] "" XXX + SG_ STEER_ANGLE : 8|15@1+ (0.0225,0) [0|65535] "" XXX + SG_ STEER_ANGLE_DIRECTION : 23|1@1+ (1,0) [0|1] "direction" XXX + SG_ STEER_RATE : 24|15@1+ (0.0225,0) [0|65535] "" XXX + SG_ STEER_RATE_DIRECTION : 39|1@1+ (1,0) [0|1] "direction" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 336 EPS_2: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ EPS_TORQUE : 8|10@1- (1,0) [0|255] "" XXX + SG_ EPS_TORQUE_DIRECTION : 18|1@1+ (1,0) [0|1] "direction" XXX + SG_ UNKNOWN : 22|2@1+ (1,0) [0|3] "" XXX + SG_ LKAS_STATUS : 24|4@1+ (1,0) [0|15] "" XXX + SG_ DRIVER_INPUT_TORQUE : 32|8@1+ (1,0) [0|255] "" XXX + SG_ LKAS_TORQUE : 40|10@1+ (1,0) [0|1023] "" XXX + SG_ LKAS_TORQUE_DIRECTION : 50|1@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 272 ACC: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_1 : 8|12@1+ (1,0) [0|4095] "" XXX + SG_ UNKNOWN_2 : 20|4@1+ (1,0) [0|15] "" XXX + SG_ ACCELERATION : 24|12@1+ (1,-300) [0|255] "" XXX + SG_ STATUS : 36|4@1+ (1,0) [0|31] "x" XXX + SG_ UNKNOWN_3 : 46|1@1+ (1,0) [0|1] "" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 274 LKAS: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ LKAS_TORQUE : 8|10@1+ (1,0) [0|2047] "x" XXX + SG_ LKAS_TORQUE_DIRECTION : 18|1@1+ (1,0) [0|1] "" XXX + SG_ LKAS_TORQUE_ACTIVE : 19|1@1+ (1,0) [0|1] "" XXX + SG_ UNKNOWN_ACTIVE_STATE : 26|1@1+ (1,0) [0|1] "" XXX + SG_ MAYBE_HUD_LANE_STATES : 28|2@1+ (1,0) [0|3] "" XXX + SG_ LKAS_ACTIVE : 32|1@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 148 MAYBE_ABS: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ UNKNOWN_1 : 8|16@1+ (1,0) [0|15] "x" XXX + SG_ UNKNOWN_2 : 24|8@1+ (1,0) [0|255] "" XXX + SG_ BRAKE_PRESSED : 35|1@1+ (1,0) [0|1] "x" XXX + SG_ UNKNOWN_3 : 46|2@1+ (1,0) [0|3] "" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 304 ABS_3: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_1 : 15|8@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 23|8@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 31|8@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 39|8@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_5 : 47|8@1+ (1,0) [0|255] "" XXX + SG_ DRIVER_BRAKE_PRESSURE : 48|12@1+ (1,0) [0|65535] "" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 144 MAYBE_ENGINE: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 8|12@1+ (1,0) [0|255] "" XXX + SG_ MAYBE_RPM : 20|12@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_1 : 32|8@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 46|14@1+ (1,0) [0|4095] "" XXX + SG_ COUNTER : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 422 MAYBE_ACC_BUTTONS: 8 XXX + SG_ NEW_SIGNAL_1 : 18|1@0+ (1,0) [0|1] "" XXX + +BO_ 560 TURN_SIGNALS: 8 XXX + SG_ RIGHT_TURN_SIGNALING : 45|1@1+ (1,0) [0|1] "" XXX + SG_ LEFT_TURN_SIGNALING : 44|1@1+ (1,0) [0|1] "" XXX + SG_ RIGHT_TURN_BULB_3 : 21|1@1+ (1,0) [0|1] "" XXX + SG_ LEFT_TURN_BULB_3 : 20|1@1+ (1,0) [0|1] "" XXX + SG_ RIGHT_TURN_BULB_2 : 19|1@1+ (1,0) [0|1] "" XXX + SG_ LEFT_TURN_BULB_2 : 18|1@1+ (1,0) [0|1] "" XXX + SG_ LEFT_TURN_BULB_1 : 16|1@1+ (1,0) [0|1] "" XXX + SG_ RIGHT_TURN_BULB_1 : 17|1@1+ (1,0) [0|1] "" XXX + +BO_ 586 DOOR_FL: 8 XXX + SG_ OPEN : 2|1@1+ (1,0) [0|1] "" XXX + +BO_ 588 DOOR_FR: 8 XXX + SG_ OPEN : 2|1@1+ (1,0) [0|1] "" XXX + +BO_ 590 DOOR_RL: 8 XXX + SG_ OPEN : 2|1@1+ (1,0) [0|1] "" XXX + +BO_ 591 DOOR_RR: 8 XXX + SG_ OPEN : 2|1@1+ (1,0) [0|1] "" XXX + + + + +CM_ SG_ 274 UNKNOWN_ACTIVE_STATE "Triggers changes from 8 to 9 in EPS_2.LKAS_STATUS"; +CM_ SG_ 560 RIGHT_TURN_SIGNALING "Includes 2.5 second convenience lane change interval"; +CM_ SG_ 560 LEFT_TURN_SIGNALING "Includes 2.5 second convenience lane change interval"; +VAL_ 336 LKAS_STATUS 1 "INITIALIZING" 5 "READY" 8 "ACTIVE_1" 9 "ACTIVE_2" 13 "FAULT" ; +VAL_ 586 OPEN 0 "CLOSED" 1 "OPEN" ; +VAL_ 588 OPEN 0 "CLOSED" 1 "OPEN" ; +VAL_ 590 OPEN 0 "CLOSED" 1 "OPEN" ; +VAL_ 591 OPEN 0 "CLOSED" 1 "OPEN" ; diff --git a/opendbc_repo/opendbc/dbc/hyundai_2015_ccan.dbc b/opendbc_repo/opendbc/dbc/hyundai_2015_ccan.dbc new file mode 100644 index 000000000000000..fc1e1739071f592 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/hyundai_2015_ccan.dbc @@ -0,0 +1,1416 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: IAP ODS _4WD BCM HUD DATC MDPS AAF_Tester AEMC SMK _4WD EPB CUBIS MTS TMU EVP CGW TPMS LPI DI_BOX SPAS EMS LCA TCU IBOX FATC AFLS FPCM SCC AHLS AVM ABS SNV OPI PGS SAS AAF Dummy LDWS_LKAS LVR ESC PSB CLU ECS ACU REA + +BO_ 1532 ODS13: 5 ODS + SG_ CR_Ods_ID : 0|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_Chksum_H : 8|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_Chksum_L : 16|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_RomID_H : 24|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + SG_ CR_Ods_RomID_L : 32|8@1+ (1.0,0.0) [0.0|255.0] "" Dummy + +BO_ 1531 ODS12: 8 ODS + SG_ CR_Ods_SerNum0 : 0|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum3 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum4 : 32|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum5 : 40|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum6 : 48|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + SG_ CR_Ods_SerNum7 : 56|8@1+ (1.0,0.0) [0.0|255.0] "" ACU + +BO_ 1530 ODS11: 8 ODS + SG_ CF_Ods_PrcCmd : 1|1@1+ (1.0,0.0) [0.0|1.0] "" Dummy + SG_ CF_Ods_BtsFail : 3|1@1+ (1.0,0.0) [0.0|1.0] "" Dummy + SG_ CF_Ods_AcuRcvSN : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_EolCal : 5|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_PsFail : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_EcuFail : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_WgtStat : 8|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CF_Ods_OccStat : 16|1@1+ (1.0,0.0) [0.0|1.0] "" ACU + SG_ CR_Wcs_ErrStat : 32|8@1+ (1.0,0.0) [0.0|63.0] "" ACU + SG_ CR_Wcs_ClassStat : 40|8@1+ (1.0,0.0) [0.0|4.0] "" ACU,BCM + +BO_ 1017 ECS12: 4 ECS + SG_ Height_FL : 0|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_FR : 8|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_RL : 16|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + SG_ Height_RR : 24|8@1+ (1.0,-128.0) [-128.0|127.0] "mm" AFLS + +BO_ 1268 SPAS12: 8 SPAS + SG_ CF_Spas_HMI_Stat : 0|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Spas_Disp : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS + SG_ CF_Spas_FIL_Ind : 10|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FIR_Ind : 13|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FOL_Ind : 16|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FOR_Ind : 19|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_VolDown : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RIL_Ind : 24|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_RIR_Ind : 27|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FLS_Alarm : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_ROL_Ind : 32|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_ROR_Ind : 35|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FCS_Alarm : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_FI_Ind : 40|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_RI_Ind : 43|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU + SG_ CF_Spas_FRS_Alarm : 46|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_FR_Alarm : 48|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Spas_RR_Alarm : 50|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Spas_BEEP_Alarm : 52|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Spas_StatAlarm : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Spas_RLS_Alarm : 57|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RCS_Alarm : 59|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_RRS_Alarm : 61|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1265 CLU11: 4 CLU + SG_ CF_Clu_CruiseSwState : 0|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,LDWS_LKAS,SCC + SG_ CF_Clu_CruiseSwMain : 3|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,LDWS_LKAS,SCC + SG_ CF_Clu_SldMainSW : 4|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Clu_ParityBit1 : 5|1@1+ (1.0,0.0) [0.0|1.0] "pulse count" EMS + SG_ CF_Clu_VanzDecimal : 6|2@1+ (0.125,0.0) [0.0|0.375] "" EMS + SG_ CF_Clu_Vanz : 8|9@1+ (0.5,0.0) [0.0|255.5] "km/h or MPH" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Clu_SPEED_UNIT : 17|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CUBIS,EMS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Clu_DetentOut : 18|1@1+ (1.0,0.0) [0.0|1.0] "" AVM,BCM,LCA,PGS,SPAS + SG_ CF_Clu_RheostatLevel : 19|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,BCM,LCA,PGS,SPAS + SG_ CF_Clu_CluInfo : 24|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + 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_ 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 + +BO_ 1491 HU_DATC_PE_00: 8 CLU + SG_ HU_VRActivity : 0|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ HU_PhoneActivity : 2|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ BlowerNoiseControl : 4|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + +BO_ 1490 HU_DATC_E_02: 8 CLU + SG_ HU_DATC_RearOnOffSet : 6|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ HU_DATC_ADSOnOffSet : 8|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + +BO_ 1479 EMS21: 8 EMS + SG_ SCR_LEVEL_WARN_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ SCR_LEVEL_WARN : 1|3@1+ (1.0,0.0) [0.0|4.0] "" CLU + SG_ SCR_SYS_ERROR_WARN : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ SCR_SYSTEM_WARN_LAMP : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ SCR_INDUCEMENT_EXIT_COND : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ SCR_UREA_LEVEL : 16|8@1+ (0.5,0.0) [0.0|100.0] "%" CLU + SG_ SCR_NO_REMAINING_RESTARTS : 24|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ SCR_REMAINING_DISTANCE : 32|16@1+ (1.0,0.0) [0.0|25000.0] "km" CLU + +BO_ 1472 GW_Warning_PE: 8 BCM + SG_ Audio_VolumeDown : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Flh_Alarm : 48|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Fcnt_Alarm : 50|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Frh_Alarm : 52|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Rlh_Alarm : 56|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,PGS + SG_ Pas_Spkr_Rcnt_Alarm : 58|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Pas_Spkr_Rrh_Alarm : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,PGS + +BO_ 1984 CAL_SAS11: 2 ESC + SG_ CCW : 0|4@1+ (1.0,0.0) [0.0|15.0] "" SAS + SG_ SAS_CID : 4|11@1+ (1.0,0.0) [0.0|2047.0] "" SAS + +BO_ 1456 CLU12: 4 CLU + SG_ CF_Clu_Odometer : 0|24@1+ (0.1,0.0) [0.0|1677721.4] "km" _4WD,AAF,BCM,CUBIS,EMS,EPB,IBOX,LDWS_LKAS,SCC,TPMS + +BO_ 688 SAS11: 5 MDPS + SG_ SAS_Angle : 0|16@1- (0.1,0.0) [-3276.8|3276.7] "Deg" _4WD,ACU,AFLS,AVM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU,_4WD,ACU,AFLS,AVM,BCM,CLU,ECS,EMS,ESC,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SPAS,TCU + SG_ SAS_Speed : 16|8@1+ (4.0,0.0) [0.0|1016.0] "" AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU,AFLS,ECS,ESC,IBOX,LDWS_LKAS,SCC,SPAS,TCU + SG_ SAS_Stat : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ MsgCount : 32|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS + SG_ CheckSum : 36|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS,ECS,EMS,ESC,IBOX,LDWS_LKAS,PSB,SCC,SPAS + +BO_ 1441 ACU12: 8 ACU + SG_ CR_Acu_SN : 0|64@1+ (1.0,0.0) [0.0|0.0] "" ODS + +BO_ 1440 ACU11: 8 ACU + SG_ CF_Ods_SNRcv : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Ods_IDRcv : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Ods_RZReq : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Abg_DepInhEnt : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_Abg_DepEnt : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ODS + SG_ CF_PasBkl_FltStat : 28|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_DriBkl_FltStat : 29|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_PasBkl_Stat : 30|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,ODS,PSB,TMU + SG_ CF_DriBkl_Stat : 31|1@1+ (1.0,0.0) [0.0|1.0] "" ODS,PSB + SG_ CF_SWL_Ind : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CUBIS,IBOX + SG_ CF_Acu_FltStat : 34|2@1+ (1.0,0.0) [0.0|3.0] "" CUBIS,IBOX + SG_ CF_Acu_ExtOfSab : 36|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,CUBIS,IBOX + SG_ CF_Acu_Dtc : 40|16@1+ (1.0,0.0) [0.0|65535.0] "" CUBIS,IBOX + SG_ CF_Acu_NumOfFlt : 56|8@1+ (1.0,0.0) [0.0|255.0] "" CUBIS,IBOX + +BO_ 1437 AHLS11: 8 AHLS + SG_ CF_Ahls_WarnLamp : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Ahls_WarnMsg : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1434 PSB11: 2 PSB + SG_ PSB_LH_FAIL : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PSB_LH_TGL : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ PSB_LH_ACT : 3|4@1+ (1.0,0.0) [0.0|4.0] "" Dummy + SG_ PSB_RH_FAIL : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PSB_RH_TGL : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ PSB_RH_ACT : 11|4@1+ (1.0,0.0) [0.0|4.0] "" Dummy + +BO_ 916 TCS13: 8 ESC + SG_ aBasis : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC + SG_ BrakeLight : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,SCC + SG_ DCEnable : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ AliveCounterTCS : 13|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,SCC + SG_ ACCReqLim : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ TQI_ACC : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS + SG_ ACCEL_REF_ACC : 32|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,SCC + SG_ ACCEnable : 43|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ DriverOverride : 45|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,SCC + SG_ StandStill : 47|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ CheckSum_TCS3 : 48|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,SCC + SG_ ACC_EQUIP : 52|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ PBRAKE_ACT : 53|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ ACC_REQ : 54|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ DriverBraking : 55|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,SCC + SG_ CF_VSM_Coded : 56|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_VSM_Avail : 57|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,SCC + SG_ CF_VSM_Handshake : 59|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_DriBkeStat : 60|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + SG_ CF_VSM_ConfSwi : 61|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ AEB_EQUIP : 63|1@1+ (1.0,0.0) [0.0|1.0] "" SCC + +BO_ 1427 TPMS11: 6 BCM + SG_ TPMS_W_LAMP : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX + SG_ TREAD_W_LAMP : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,HUD,IBOX,CLU,CUBIS,HUD,IBOX + SG_ POS_FL_W_LAMP : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_FR_W_LAMP : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_RL_W_LAMP : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ POS_RR_W_LAMP : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,HUD,IBOX + SG_ STATUS_TPMS : 8|3@1+ (1.0,0.0) [0.0|0.0] "" CLU + SG_ UNIT : 11|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ PRESSURE_FL : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_FR : 24|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_RL : 32|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ PRESSURE_RR : 40|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + +BO_ 915 TCS12: 4 ESC + SG_ SA_COUNT : 0|16@1+ (2.0,-32768.0) [-32768.0|98302.0] "" _4WD,ACU,MDPS + SG_ SA_Z_COUNT : 16|15@1+ (2.0,-32768.0) [-32768.0|32766.0] "" _4WD,ACU,MDPS + SG_ SA_Z_FLAG : 31|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,MDPS + +BO_ 1170 EMS19: 8 EMS + SG_ CF_Ems_BrkReq : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX,TCU + SG_ CF_Ems_DnShftReq : 1|4@1+ (1.0,0.0) [0.0|14.0] "" IBOX,TCU + SG_ CF_Ems_RepModChk : 5|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ CF_Ems_AAFOpenReq : 7|1@1+ (1.0,0.0) [0.0|1.0] "" AAF,IBOX + SG_ CF_Ems_DecelReq : 8|12@1+ (0.0010,-4.094) [-4.094|0.0] "m/s^2" ESC,IBOX,TCU + SG_ CR_Ems_BstPre : 20|12@1+ (1.322,0.0) [0.0|4094.0] "hPa" CLU,IBOX + SG_ CR_Ems_EngOilTemp : 32|8@1+ (0.75,-40.0) [0.0|254.0] "deg" CLU,IBOX + SG_ DPF_LAMP_STAT : 40|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ BAT_LAMP_STAT : 42|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_ModeledAmbTemp : 48|8@1+ (0.5,-41.0) [-41.0|85.5] "deg" AAF,IBOX + SG_ CF_Ems_OPSFail : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_AliveCounterEMS9 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU + SG_ CF_Ems_ChecksumEMS9 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AAF,ABS,CUBIS,ECS,EPB,IBOX,MDPS,REA,SCC,SMK,TCU + +BO_ 1425 AFLS11: 2 AFLS + SG_ AFLS_STAT : 1|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Afls_TrfChgStat : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Afls_LedHLStat : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 912 SPAS11: 7 SPAS + SG_ CF_Spas_Stat : 0|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,MDPS + SG_ CF_Spas_TestMode : 4|2@1+ (1.0,0.0) [0.0|3.0] "" MDPS + SG_ CR_Spas_StrAngCmd : 8|16@1- (0.1,0.0) [-3276.8|3276.7] "" MDPS + SG_ CF_Spas_BeepAlarm : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Spas_Mode_Seq : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Spas_AliveCnt : 32|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Spas_Chksum : 40|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Spas_PasVol : 48|3@1+ (1.0,0.0) [0.0|7.0] "" CGW,CLU + +BO_ 1168 EPB11: 7 EPB + SG_ EPB_I_LAMP : 0|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU,CUBIS,ESC,IBOX + SG_ EPB_F_LAMP : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,ESC,IBOX + SG_ EPB_ALARM : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ EPB_CLU : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,ESC + SG_ EPB_SWITCH : 16|2@1+ (1.0,0.0) [0.0|3.0] "" ESC,SCC + SG_ EPB_RBL : 18|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,ESC + SG_ EPB_STATUS : 19|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,ESC,SCC,TCU + SG_ EPB_FRC_ERR : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,SCC,TCU + SG_ EPB_DBF_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ ESP_ACK : 25|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ EPB_DBF_REQ : 26|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ EPB_FAIL : 29|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,SCC + SG_ EPB_FORCE : 32|12@1+ (1.0,-1000.0) [-1000.0|3000.0] "" ESC + SG_ EPB_DBF_DECEL : 48|8@1+ (0.01,0.0) [0.0|2.54] "g" ESC + +BO_ 399 EMS_H12: 8 EMS + SG_ R_TqAcnApvC : 0|8@1+ (0.2,0.0) [0.0|51.0] "Nm" DATC,IBOX + SG_ R_PAcnC : 8|8@1+ (125.0,0.0) [0.0|31875.0] "hPa" DATC,IBOX + SG_ TQI_B : 16|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ABS,ESC,IBOX + SG_ SLD_VS : 24|8@1+ (1.0,0.0) [0.0|255.0] "km/h" CLU,IBOX + SG_ CF_CdaStat : 32|3@1+ (1.0,0.0) [0.0|7.0] "" AEMC,IBOX,TCU + SG_ CF_Ems_IsgStat : 35|3@1+ (1.0,0.0) [0.0|7.0] "" ABS,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,MDPS,SMK,TCU + SG_ CF_Ems_OilChg : 38|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_EtcLimpMod : 39|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ R_NEngIdlTgC : 40|8@1+ (10.0,0.0) [0.0|2550.0] "rpm" DATC,IBOX,TCU + SG_ CF_Ems_UpTarGr : 48|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_DownTarGr : 49|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_DesCurGr : 50|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX + SG_ CF_Ems_SldAct : 54|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_SldPosAct : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_HPresStat : 56|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ CF_Ems_IsgBuz : 57|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_IdlStpFCO : 58|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_FCopen : 59|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Ems_ActEcoAct : 60|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ CF_Ems_EngRunNorm : 61|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,IBOX,TCU + SG_ CF_Ems_IsgStat2 : 62|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX,TCU + +BO_ 1419 LCA11: 8 LCA + SG_ CF_Lca_Stat : 0|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Rcta_Stat : 4|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Lca_IndLeft : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Rcw_Stat : 10|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_RCW_Warning : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Lca_IndRight : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_Lca_SndWan_Stat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_FR_SndWan : 20|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_FL_SndWan : 21|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_RR_SndWan : 22|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_RL_SndWan : 23|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU + SG_ CF_Lca_IndBriLeft : 24|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_Lca_IndBriRight : 32|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndBriLeft : 40|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndBriRight : 48|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_RCTA_IndLeft : 56|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_RCTA_IndRight : 58|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + SG_ CF_SndWarnForClu : 60|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 906 ABS11: 8 ABS + SG_ ABS_DEF : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,EMS,SPAS,TCU + SG_ EBD_DEF : 1|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,SPAS,TCU + SG_ ABS_ACT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,EPB,SPAS,TCU + SG_ ABS_W_LAMP : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,CUBIS,MTS,TMU + SG_ EBD_W_LAMP : 4|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ ABS_DIAG : 5|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ ESS_STAT : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,BCM,CLU,EMS + +BO_ 903 WHL_PUL11: 6 ABS + SG_ WHL_PUL_FL : 0|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_FR : 8|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_RL : 16|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_PUL_RR : 24|8@1+ (0.5,0.0) [0.0|127.5] "pulse count" CUBIS,EPB,IBOX,SPAS,TMU,TPMS,CUBIS,EPB,IBOX,LDWS_LKAS,SPAS,TMU,TPMS + SG_ WHL_DIR_FL : 32|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_FR : 34|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_RL : 36|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_DIR_RR : 38|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,SPAS,TPMS,EPB,LCA,SPAS,TPMS + SG_ WHL_PUL_Chksum : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EPB,SPAS,TPMS,EPB,LCA,LDWS_LKAS,SPAS,TPMS + +BO_ 1415 TMU11: 8 IBOX + SG_ CF_Tmu_VehSld : 0|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Tmu_VehImmo : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Tmu_ReqRepCnd : 2|2@1+ (1.0,0.0) [0.0|3.0] "" EMS + SG_ CF_Tmu_AirconCtr : 4|1@1+ (1.0,0.0) [0.0|1.0] "" DATC + SG_ CF_Tmu_TempMd : 5|1@1+ (1.0,0.0) [0.0|1.0] "" DATC + SG_ CF_Tmu_TempSet : 6|16@1+ (1.0,0.0) [0.0|20.0] "" DATC + SG_ CF_Tmu_DefrostCtr : 22|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,FATC + SG_ CF_Tmu_AliveCnt1 : 56|4@1+ (1.0,0.0) [0.0|15.0] "" EMS + +BO_ 902 WHL_SPD11: 8 ABS + SG_ WHL_SPD_FL : 0|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_FR : 16|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,ACU,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_RL : 32|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,BCM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,BCM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_RR : 48|14@1+ (0.03125,0.0) [0.0|511.96875] "km/h" _4WD,AFLS,AHLS,AVM,CLU,CUBIS,ECS,EMS,EPB,IBOX,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS,_4WD,ACU,AFLS,AHLS,AVM,CLU,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PGS,PSB,SCC,SMK,SPAS,TCU,TPMS + SG_ WHL_SPD_AliveCounter_LSB : 14|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_AliveCounter_MSB : 30|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_Checksum_LSB : 46|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ WHL_SPD_Checksum_MSB : 62|2@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + +BO_ 1414 EVP11: 3 EVP + SG_ CF_Evp_Stat : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1412 AAF11: 8 AAF + SG_ CF_Aaf_ActFlapStatus : 0|2@1+ (1.0,0.0) [0.0|3.0] "" AAF_Tester + SG_ CF_Aaf_ModeStatus : 2|3@1+ (1.0,0.0) [0.0|7.0] "" AAF_Tester + SG_ CF_Aaf_WrnLamp : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Aaf_ErrStatus : 6|10@1+ (1.0,0.0) [0.0|1023.0] "" AAF_Tester,EMS + SG_ CF_Aaf_OpenRqSysAct : 16|8@1+ (1.0,0.0) [0.0|255.0] "" AAF_Tester + SG_ CF_Aaf_PStatus : 24|8@1+ (1.0,0.0) [0.0|100.0] "%" AAF_Tester + SG_ CF_Aaf_OpenRqSysSol : 32|8@1+ (1.0,0.0) [0.0|255.0] "" AAF_Tester + SG_ CF_Aaf_SolFlapStatus : 40|2@1+ (1.0,0.0) [0.0|3.0] "" AAF_Tester + SG_ CF_Aaf_MilOnReq : 42|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 900 EMS17: 8 EMS + SG_ CF_Ems_PkpCurMSV : 0|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_HolCurMSV : 8|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_InjVBnkAct : 16|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_InjVActSet : 24|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_DiagFulHDEV : 32|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_SwiOffIC1 : 33|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_SwiOffIC2 : 34|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CF_Ems_DiagReqHDEV : 38|1@1+ (1.0,0.0) [0.0|1.0] "" DI_BOX + SG_ CR_Ems_DutyCycMSV : 40|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" DI_BOX + SG_ CR_Ems_BatVolRly : 48|8@1+ (0.1,0.0) [0.0|25.5] "V" DI_BOX + +BO_ 387 REA11: 8 REA + SG_ CF_EndBst_PwmDuH : 0|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PwmDuL : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PwmFqOutRng : 2|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_HbriOverCur : 3|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_HbriOverTemp : 4|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PosSnsKOR : 6|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_PosSnsOSOR : 7|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_EepFlt : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_RomFlt : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_RamFlt : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_CanFlt : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_AgH : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_AgL : 13|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_EndBst_ORVol : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CR_EndBst_ActPos : 16|16@1+ (0.117,0.0) [1.989|118.053] "" EMS + SG_ CR_EndBst_DemPos : 32|16@1+ (0.117,0.0) [0.0|119.691] "" EMS + SG_ CR_EndBst_HbriPwr : 48|16@1+ (0.045,0.0) [0.0|99.99] "%" EMS + +BO_ 1411 CUBIS11: 8 CUBIS + SG_ CF_Cubis_HUDisp : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + +BO_ 899 FATC11: 8 DATC + SG_ CR_Fatc_TqAcnOut : 0|8@1+ (0.2,0.0) [0.0|50.8] "Nm" EMS,IBOX + SG_ CF_Fatc_AcnRqSwi : 8|1@1+ (1.0,0.0) [0.0|1.0] "" AAF,EMS,IBOX + SG_ CF_Fatc_AcnCltEnRq : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_EcvFlt : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_BlwrOn : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_FATC_Iden : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Fatc_BlwrMax : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX + SG_ CF_Fatc_EngStartReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_IsgStopReq : 16|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_CtrInf : 17|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,IBOX + SG_ CF_Fatc_MsgCnt : 20|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + SG_ CR_Fatc_OutTemp : 24|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" BCM,CLU,EMS,IBOX,SPAS,TCU,TPMS + SG_ CR_Fatc_OutTempSns : 32|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" AAF,AHLS,CLU,EMS,IBOX,SPAS,TCU + SG_ CF_Fatc_Compload : 40|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,IBOX + SG_ CF_Fatc_ActiveEco : 43|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Fatc_AutoActivation : 44|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX + SG_ CF_Fatc_DefSw : 45|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,IBOX + SG_ CF_Fatc_PtcRlyStat : 46|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Fatc_ChkSum : 56|8@1+ (1.0,0.0) [0.0|255.0] "" EMS,IBOX,SPAS + +BO_ 129 EMS_DCT12: 8 EMS + SG_ CR_Ems_SoakTimeExt : 0|6@1+ (5.0,0.0) [0.0|315.0] "Min" TCU + SG_ BRAKE_ACT : 6|2@1+ (1.0,0.0) [0.0|3.0] "" TCU + SG_ CF_Ems_EngOperStat : 8|8@1+ (1.0,0.0) [0.0|255.0] "" TCU + SG_ CR_Ems_IndAirTemp : 16|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" TCU + SG_ CF_Ems_Alive2 : 56|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Ems_ChkSum2 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 897 MDPS11: 8 MDPS + SG_ CF_Mdps_WLmp : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,EMS,IBOX,SPAS + SG_ CF_Mdps_Flex : 2|3@1+ (1.0,0.0) [0.0|3.0] "" CLU,LDWS_LKAS + SG_ CF_Mdps_FlexDisp : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Mdps_Stat : 7|4@1+ (1.0,0.0) [0.0|15.0] "" SPAS + SG_ CR_Mdps_DrvTq : 11|12@1+ (0.01,-20.48) [-20.48|20.46] "" SPAS + SG_ CF_Mdps_ALTRequest : 23|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CR_Mdps_StrAng : 24|16@1- (0.1,0.0) [-3276.8|3276.7] "Deg" SPAS + SG_ CF_Mdps_AliveCnt : 40|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,SPAS + SG_ CF_Mdps_Chksum : 48|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,SPAS + SG_ CF_Mdps_SPAS_FUNC : 57|1@1+ (1.0,0.0) [0.0|1.0] "flag" SPAS + SG_ CF_Mdps_LKAS_FUNC : 58|1@1+ (1.0,0.0) [0.0|1.0] "flag" LDWS_LKAS + SG_ CF_Mdps_CurrMode : 59|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Mdps_Type : 61|2@1+ (1.0,0.0) [0.0|2.0] "" LDWS_LKAS,SPAS + +BO_ 896 DI_BOX13: 8 DI_BOX + SG_ CF_DiBox_HPreInjVConfStat : 0|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVStat1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVStat2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVPkp : 24|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_HPreInjVBpt : 32|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_ErrRegFrtMSV : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_ErrRegSedMSV : 48|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SPIErrSedMSV : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_SPIErrFrtMSV : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IDErrSedMSV : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IDErrFrtMSV : 59|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_IniStatMSV : 60|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 640 EMS13: 8 EMS + SG_ LV_FUEL_TYPE_ECU : 0|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,LPI,SMK + SG_ LV_BFS_CFIRM : 1|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_CRASH : 2|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_VB_OFF_ACT : 3|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_GSL_MAP M : 4|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ LV_ENG_TURN : 5|1@1+ (1.0,0.0) [0.0|1.0] "" LPI + SG_ ERR_FUEL : 8|8@1+ (1.0,0.0) [0.0|255.0] "" LPI + SG_ EOS : 16|8@1+ (1.0,0.0) [0.0|255.0] "" LPI + SG_ TCO : 24|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" LPI + SG_ N_32 : 32|8@1+ (32.0,0.0) [0.0|8160.0] "rpm" LPI + SG_ MAF : 40|8@1+ (5.447,0.0) [0.0|1388.985] "mg/TDC" LPI + SG_ TIA : 48|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" LPI + SG_ MAP m1 : 56|8@1+ (0.47058,0.0) [0.0|119.9979] "kPa" LPI + SG_ AMP m0 : 56|8@1+ (21.22,0.0) [0.0|5411.1] "hPa" LPI + +BO_ 128 EMS_DCT11: 8 EMS + SG_ PV_AV_CAN : 0|8@1+ (0.3906,0.0) [0.0|99.603] "%" TCU + SG_ TQ_STND : 8|6@1+ (10.0,0.0) [0.0|630.0] "Nm" TCU + SG_ F_N_ENG : 14|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ F_SUB_TQI : 15|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ N : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" TCU + SG_ TQI_ACOR : 32|8@1+ (0.390625,0.0) [0.0|99.6094] "%" IBOX,TCU + SG_ TQFR : 40|8@1+ (0.390625,0.0) [0.0|99.6094] "%" TCU + SG_ TQI : 48|8@1+ (0.390625,0.0) [0.0|99.609375] "%" TCU + SG_ CF_Ems_Alive : 56|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Ems_ChkSum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 1407 HU_MON_PE_01: 8 CLU + SG_ HU_Type : 0|8@1+ (1.0,0.0) [0.0|255.0] "" AVM,PGS + +BO_ 127 CGW5: 8 BCM + SG_ C_StopLampLhOpenSts : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_StopLampRhOpenSts : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HMSLOpenSts : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampLowLhOpenSts : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampLowRhOpenSts : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampHighLhOpenSts : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_HLampHighRhOpenSts : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_DRLLampLhOpenSts : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_DRLLampRhOpenSts : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearFOGLhOpenSts : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearFOGRhOpenSts : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontFOGLhOpenSts : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontFOGRhOpenSts : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearEXTTailLhOpenSts : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearEXTTailRhOpenSts : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontEXTTailLhOpenSts : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontEXTTailRhOpenSts : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearTSIGLhOpenSts : 17|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_RearTSIGRhOpenSts : 18|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontTSIGLhOpenSts : 19|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_FrontTSIGRhOpenSts : 20|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SBendingLhOpenSts : 21|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SBendingRhOpenSts : 22|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_LicensePlateLhOpenSts : 23|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_LicensePlateRhOpenSts : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1151 ESP11: 6 ESC + SG_ AVH_STAT : 0|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,TCU + SG_ LDM_STAT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" EPB,TCU + SG_ REQ_EPB_ACT : 3|2@1+ (1.0,0.0) [0.0|3.0] "" EPB,TCU + SG_ REQ_EPB_STAT : 5|1@1+ (1.0,0.0) [0.0|1.0] "" EPB + SG_ ECD_ACT : 6|1@1+ (1.0,0.0) [0.0|1.0] "" EPB + SG_ _4WD_LIM_REQ : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS + SG_ ROL_CNT_ESP : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EPB,TCU + SG_ _4WD_TQC_LIM : 16|16@1+ (1.0,0.0) [0.0|65535.0] "Nm" _4WD,EMS + SG_ _4WD_CLU_LIM : 32|8@1+ (0.390625,0.0) [0.0|99.609375] "%" _4WD,EMS + SG_ _4WD_OPEN : 40|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,EMS + SG_ _4WD_LIM_MODE : 42|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD + +BO_ 1397 HU_AVM_E_00: 8 CLU + SG_ HU_AVM_Cal_Cmd : 0|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_Cal_Method : 4|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_Save_Controlpoint : 6|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_PT_X : 8|12@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_RearViewPointOpt : 20|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_PT_Y : 24|12@1+ (1.0,0.0) [0.0|4095.0] "" AVM,PGS + SG_ HU_AVM_FrontViewPointOpt : 36|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_SelectedMenu : 40|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,PGS + SG_ HU_AVM_CameraOff : 45|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + SG_ HU_AVM_Option : 48|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_CrossLineMove_Cmd : 52|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_RearView_Option : 56|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_FrontView_Option : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + +BO_ 1395 HU_AVM_E_01: 8 CLU + SG_ HU_PGSSelectedMenu : 0|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_PGSOption : 8|5@1+ (1.0,0.0) [0.0|31.0] "" AVM,PGS + SG_ HU_AVM_ParkingAssistMenu : 56|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + SG_ HU_AVM_ParkingAssistSB : 60|4@1+ (1.0,0.0) [0.0|15.0] "" AVM,PGS + +BO_ 1393 OPI11: 5 OPI + SG_ CR_Opi_Spd_Rpm : 0|8@1+ (20.0,0.0) [0.0|3500.0] "rpm" TCU + SG_ CF_Opi_Over_Temp : 8|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Over_Cur : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Over_Vol : 10|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Hall_Fail : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Flt : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,TCU + SG_ CF_Opi_Motor_Dir : 15|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Opi_Romver : 16|8@1+ (1.0,0.0) [0.0|255.0] "" TCU + SG_ CF_Opi_PWM_Rate : 24|12@1+ (1.0,0.0) [0.0|100.0] "%" TCU + +BO_ 625 LPI11: 8 LPI + SG_ FUP_LPG_MMV : 0|8@1+ (128.0,0.0) [0.0|32640.0] "hPa" EMS + SG_ LV_FUEL_TYPE_BOX : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_BFS_IN_PROGRESS : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_GAS_OK : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_FUP_ENA_THD : 11|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,EMS,SMK + SG_ LPI_OBD : 12|4@1+ (1.0,0.0) [0.0|15.0] "" EMS + SG_ ERR_GAS : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ FAC_TI_GAS_COR : 24|16@1+ (3.05E-5,0.0) [0.0|1.9988175] "" EMS + SG_ FTL_AFU : 40|8@1+ (0.392,0.0) [0.0|99.96] "%" EMS + SG_ BFS_CYL : 48|8@1+ (1.0,0.0) [0.0|6.0] "Cyl Nr." EMS + SG_ LV_PRE_CDN_LEAK : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_CONF_INJECTION_DELAY : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ LV_LPG_SW_DRIVER_REQ : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 356 VSM11: 4 ESC + SG_ CR_Esc_StrTqReq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" MDPS + SG_ CF_Esc_Act : 12|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,MDPS + SG_ CF_Esc_CtrMode : 13|3@1+ (1.0,0.0) [0.0|7.0] "" MDPS + SG_ CF_Esc_Def : 16|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Esc_AliveCnt : 17|4@1+ (1.0,0.0) [0.0|15.0] "" LDWS_LKAS,MDPS + SG_ CF_Esc_Chksum : 24|8@1+ (1.0,0.0) [0.0|255.0] "" LDWS_LKAS,MDPS + +BO_ 1379 PGS_HU_PE_01: 8 PGS + SG_ PGS_State : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ PGS_ParkGuideState : 8|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ PGS_Option : 16|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ PGS_Version : 32|16@1+ (1.0,0.0) [0.0|65535.0] "" CLU + +BO_ 354 TCU_DCT13: 3 TCU + SG_ Clutch_Driving_Tq : 0|10@1+ (1.0,-512.0) [0.0|0.0] "Nm" ESC + SG_ Cluster_Engine_RPM : 10|13@1+ (0.9766,0.0) [0.0|0.0] "" CLU + SG_ Cluster_Engine_RPM_Flag : 23|1@1+ (1.0,0.0) [0.0|0.0] "" CLU + +BO_ 1378 HUD11: 4 HUD + SG_ CF_Hud_HeightStaus : 0|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ CF_Hud_PBackStatus : 6|2@1+ (1.0,0.0) [0.0|0.0] "" BCM,CLU + SG_ CF_Hud_Brightness : 8|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + +BO_ 608 EMS16: 8 EMS + SG_ TQI_MIN : 0|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ TQI : 8|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ TQI_TARGET : 16|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EPB,ESC,IBOX,TCU + SG_ GLOW_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,IBOX,SMK + SG_ CRUISE_LAMP_M : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ CRUISE_LAMP_S : 26|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,TCU + SG_ PRE_FUEL_CUT_IN : 27|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ENG_STAT : 28|3@1+ (1.0,0.0) [0.0|7.0] "" ABS,AHLS,AVM,BCM,CLU,EPB,ESC,EVP,FPCM,IBOX,LCA,LDWS_LKAS,MDPS,SCC,SMK,TCU + SG_ SOAK_TIME_ERROR : 31|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,EPB,IBOX,TCU + SG_ SOAK_TIME : 32|8@1+ (1.0,0.0) [0.0|255.0] "Min" _4WD,DATC,EPB,IBOX,TCU + SG_ TQI_MAX : 40|8@1+ (0.390625,0.0) [0.0|99.609375] "%" ESC,IBOX,TCU + SG_ SPK_TIME_CUR : 48|8@1+ (0.375,-35.625) [-35.625|60.0] "" IBOX,TCU + SG_ Checksum : 56|4@1+ (1.0,0.0) [0.0|15.0] "" ECS,IBOX,LDWS_LKAS,MDPS,SCC + SG_ AliveCounter : 60|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,LDWS_LKAS,MDPS,SCC + SG_ CF_Ems_AclAct : 62|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,SCC + +BO_ 1371 AVM_HU_PE_00: 8 AVM + SG_ AVM_View : 0|5@1+ (1.0,0.0) [0.0|31.0] "" CLU + SG_ AVM_ParkingAssist_BtnSts : 5|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ AVM_Display_Message : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ AVM_Popup_Msg : 16|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Ready : 20|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_ParkingAssist_Step : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_FrontBtn_Type : 28|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Option : 32|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_FrontViewPointOpt : 36|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_RearView_Option : 40|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_HU_FrontView_Option : 44|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ AVM_Version : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" CLU + +BO_ 1370 HU_AVM_PE_00: 8 CLU + SG_ HU_AVM_Status : 0|2@1+ (1.0,0.0) [0.0|3.0] "" AVM,PGS + +BO_ 1369 CGW4: 8 BCM + SG_ CF_Gway_MemoryP1Cmd : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_MemoryP2Cmd : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackP1Cmd : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackP2Cmd : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_StrgWhlHeatedState : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBackStopCmd : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,HUD + SG_ CF_Gway_StaticBendLhAct : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_StaticBendRhAct : 7|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_DrvWdwStat : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RLWdwState : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RRWdwState : 10|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_AstWdwStat : 11|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_MemoryEnable : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBACKStopCmd : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_PBACKStop : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,HUD + SG_ CF_Gway_IMSBuzzer : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_DrvSeatBeltInd : 36|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_AstSeatBeltInd : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RCSeatBeltInd : 40|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RLSeatBeltInd : 42|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RRSeatBeltInd : 44|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_RrWiperHighSw : 46|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_RrWiperLowSw : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 1367 EngFrzFrm12: 8 EMS + SG_ PID_06h : 0|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_07h : 8|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_08h : 16|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_09h : 24|8@1+ (0.78125,-100.0) [-100.0|99.22] "%" AAF,IBOX,TCU + SG_ PID_0Bh : 32|8@1+ (1.0,0.0) [0.0|255.0] "kPa" AAF,IBOX,TCU + SG_ PID_23h : 40|16@1+ (10.0,0.0) [0.0|655350.0] "kPa" AAF,IBOX,TCU + +BO_ 1366 EngFrzFrm11: 8 EMS + SG_ PID_04h : 0|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" AAF,TCU + SG_ PID_05h : 8|8@1+ (1.0,-40.0) [-40.0|215.0] "deg" AAF,TCU + SG_ PID_0Ch : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" AAF,TCU + SG_ PID_0Dh : 32|8@1+ (1.0,0.0) [0.0|255.0] "km/h" AAF,TCU + SG_ PID_11h : 40|8@1+ (0.3921568627,0.0) [0.0|100.0] "%" AAF,TCU + SG_ PID_03h : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" AAF,TCU + +BO_ 1365 FPCM11: 8 FPCM + SG_ CR_Fpcm_LPActPre : 0|8@1+ (3.137254902,0.0) [0.0|800.0] "kPa" EMS + SG_ CF_Fpcm_LPPumpOverCur : 8|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrHi : 9|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrDisc : 10|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrShort : 11|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LPPumpDiscShort : 12|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LP_System_Error : 13|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_PreSnrSigErr : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Fpcm_LPCtrCirFlt : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 852 LVR11: 7 LVR + SG_ CF_Lvr_GearInf : 0|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,TCU + SG_ CF_Lvr_PRelStat : 4|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,SMK,TCU + SG_ CF_Lvr_BkeAct : 5|1@1+ (1.0,0.0) [0.0|1.0] "" TCU + SG_ CF_Lvr_NFnStat : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Lvr_PosInf : 8|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_PosCpl : 12|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_UlkButStat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" TCU + SG_ CF_Lvr_PNStat : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lvr_ShtLkStat : 24|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_ShfErrInf : 28|20@1+ (1.0,0.0) [0.0|8191.0] "" CLU,TCU + SG_ CF_Lvr_AC : 48|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + SG_ CF_Lvr_CS : 52|4@1+ (1.0,0.0) [0.0|15.0] "" TCU + +BO_ 1363 CGW2: 8 BCM + SG_ CF_Gway_GwayDiagState : 0|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_DDMDiagState : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SCMDiagState : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_PSMDiagState : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SJBDiagState : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IPMDiagState : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_LDMFail : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,LDWS_LKAS,LDWS_LKAS + SG_ CF_Gway_CLUSwGuiCtrl : 10|3@1+ (1.0,0.0) [0.0|63.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwGroup : 13|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwMode : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CLUSwEnter : 15|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_AutoLightValue : 16|1@1+ (1.0,0.0) [0.0|1.0] "" LCA,LCA + SG_ CF_Gway_BrakeFluidSw : 17|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_DrvSeatBeltInd : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_AvTail : 20|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,SNV,SNV + SG_ CF_Gway_RearFogAct : 21|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ExtTailAct : 22|1@1+ (1.0,0.0) [0.0|1.0] "" AVM,CLU,LCA,PGS,SPAS,AVM,LCA,PGS,SPAS + SG_ CF_Gway_RRDrSw : 23|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_RLDrSw : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IntTailAct : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_CountryCfg : 26|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,Dummy + SG_ CF_Gway_WiperParkPosition : 32|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,EMS,LDWS_LKAS,AFLS,EMS,LDWS_LKAS + SG_ CF_Gway_HLLowLHFail : 33|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV + SG_ CF_Gway_HLLowRHFail : 34|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS,SNV,LDWS_LKAS,SNV + SG_ CF_Gway_ESCLFailWarn : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ESCLNotLockedWarn : 36|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ESCLNotUnlockWarn : 37|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_IDoutWarn : 38|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_ImmoLp : 40|1@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_BCMRKEID : 41|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_VehicleNotPWarn : 44|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_DeactivationWarn : 45|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_KeyBATDischargeWarn : 46|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SSBWarn : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SMKFobID : 48|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_SMKRKECmd : 51|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + SG_ CF_Gway_AutoLightOption : 54|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_SJBDeliveryMode : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_KeyoutLp : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,Dummy + SG_ CF_Gway_SMKDispWarn : 57|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,Dummy + SG_ CF_Gway_WngBuz : 61|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,Dummy + +BO_ 339 TCS11: 8 ESC + SG_ TCS_REQ : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,TCU + SG_ MSR_C_REQ : 1|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,EPB,SCC,TCU + SG_ TCS_PAS : 2|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,SCC,SPAS,TCU + SG_ TCS_GSC : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,TCU + SG_ CF_Esc_LimoInfo : 4|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,SCC + SG_ ABS_DIAG : 6|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB + SG_ ABS_DEF : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,SCC,SPAS,TCU + SG_ TCS_DEF : 8|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SCC,SPAS,TCU + SG_ TCS_CTL : 9|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SCC,SPAS,TCU + SG_ ABS_ACT : 10|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU + SG_ EBD_DEF : 11|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,SPAS,TCU + SG_ ESP_PAS : 12|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,CLU,EMS,EPB,LDWS_LKAS,SCC,TCU + SG_ ESP_DEF : 13|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,TCU + SG_ ESP_CTL : 14|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,ECS,EMS,EPB,LDWS_LKAS,SCC,SPAS,TCU + SG_ TCS_MFRN : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,EPB,TCU + SG_ DBC_CTL : 16|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ DBC_PAS : 17|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ DBC_DEF : 18|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB + SG_ HAC_CTL : 19|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ HAC_PAS : 20|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ HAC_DEF : 21|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,EMS,EPB,TCU + SG_ ESS_STAT : 22|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,BCM,CLU,EMS,EPB + SG_ TQI_TCS : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ TQI_MSR : 32|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ TQI_SLW_TCS : 40|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,EPB,TCU + SG_ CF_Esc_BrkCtl : 48|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ BLA_CTL : 49|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CGW,CLU + SG_ AliveCounter_TCS1 : 52|4@1+ (1.0,0.0) [0.0|14.0] "" EMS,EPB,LDWS_LKAS + SG_ CheckSum_TCS1 : 56|8@1+ (1.0,0.0) [0.0|255.0] "" EMS,EPB,LDWS_LKAS + +BO_ 1362 SNV11: 4 SNV + SG_ CF_SNV_DisplayControl : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,HUD + SG_ CF_Snv_BeepWarning : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,HUD + SG_ CF_Snv_WarningMessage : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,HUD + SG_ CF_Snv_DetectionEnable : 7|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CLU,HUD + SG_ CF_Snv_PedestrianDetect : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,HUD + SG_ CF_Snv_IRLampControl : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,HUD + +BO_ 593 MDPS12: 8 MDPS + SG_ CR_Mdps_StrColTq : 0|11@1+ (0.0078125,-8.0) [-8.0|7.9921875] "Nm" LDWS_LKAS + SG_ CF_Mdps_Def : 11|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_Mdps_ToiUnavail : 12|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_ToiActive : 13|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_ToiFlt : 14|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_FailStat : 15|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Mdps_MsgCount2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" ESC,LDWS_LKAS + SG_ CF_Mdps_Chksum2 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" ESC,LDWS_LKAS + SG_ CF_Mdps_SErr : 37|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CR_Mdps_StrTq : 40|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" ESC + SG_ CR_Mdps_OutTq : 52|12@1+ (0.1,-204.8) [-204.8|204.7] "" ESC,LDWS_LKAS + +BO_ 1360 IAP11: 3 IAP + SG_ CF_Iap_EcoPmodSwi : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Iap_EcoPmodAct : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Iap_ReqWarn : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1356 TCU_DCT14: 8 TCU + SG_ Vehicle_Stop_Time : 0|5@1+ (1.0,0.0) [0.0|0.0] "" CLU + SG_ HILL_HOLD_WARNING : 5|1@1+ (1.0,0.0) [0.0|0.0] "" CLU + +BO_ 1353 BAT11: 8 EMS + SG_ BAT_SNSR_I : 0|16@1+ (0.01,-327.0) [-327.0|328.0] "A" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOC : 16|8@1+ (1.0,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_V : 24|14@1+ (0.0010,6.0) [6.0|18.0] "V" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Temp : 38|9@1- (0.5,-40.0) [-40.0|125.0] "deg" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_State : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOH : 48|7@1+ (1.0,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Invalid : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + SG_ BAT_SOF : 56|7@1+ (0.1,0.0) [0.0|12.0] "V" CGW,CUBIS,IBOX,TMU + SG_ BAT_SNSR_Error : 63|1@1+ (1.0,0.0) [0.0|1.0] "" CGW,CUBIS,IBOX,TMU + +BO_ 1351 EMS15: 8 EMS + SG_ ECGPOvrd : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX,SCC + SG_ QECACC : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ ECFail : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ SwitchOffCondExt : 3|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ BLECFail : 4|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ CF_Ems_IsaAct : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ FA_PV_CAN : 8|8@1+ (0.3906,0.0) [0.0|99.2] "%" IBOX,LDWS_LKAS,TCU + SG_ IntAirTemp : 16|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" _4WD,ECS,EPB,IBOX,TCU + SG_ STATE_DC_OBD : 24|7@1+ (1.0,0.0) [0.0|127.0] "" IBOX,TCU + SG_ INH_DC_OBD : 31|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ CTR_IG_CYC_OBD : 32|16@1+ (1.0,0.0) [0.0|65535.0] "" ACU,IBOX,TCU + SG_ CTR_CDN_OBD : 48|16@1+ (1.0,0.0) [0.0|65535.0] "" IBOX,TCU + +BO_ 1350 DI_BOX12: 8 DI_BOX + SG_ CF_DiBox_FrtInjVDiagReg0 : 0|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_FrtInjVDiagReg1 : 8|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_FrtInjVDiagReg2 : 16|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg0 : 24|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg1 : 32|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CF_DiBox_SedInjVDiagReg2 : 40|8@1+ (1.0,0.0) [0.0|255.0] "" EMS + SG_ CR_DiBox_BatVol : 48|8@1+ (0.1,0.0) [0.0|25.5] "V" EMS + SG_ CF_DiBox_SedInjVChg : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_FrtInjVChg : 57|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_SedInjVErrSPI : 58|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_DiBox_FrtInjVErrSPI : 59|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + +BO_ 1349 EMS14: 8 EMS + SG_ IMMO_LAMP_STAT : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ L_MIL : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,IBOX + SG_ IM_STAT : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ AMP_CAN : 3|5@1+ (10.731613,458.98) [458.98|791.660003] "mmHg" CLU,IBOX,TCU,TPMS + SG_ BAT_Alt_FR_Duty : 8|8@1+ (0.4,0.0) [0.0|100.0] "%" CGW,CUBIS,IBOX,TMU + SG_ VB : 24|8@1+ (0.1015625,0.0) [0.0|25.8984375] "V" CLU,CUBIS,DATC,EPB,FPCM,IBOX + SG_ EMS_VS : 32|12@1+ (0.0625,0.0) [0.0|255.875] "km/h" CLU + SG_ TEMP_FUEL : 56|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" FPCM + +BO_ 68 DATC11: 8 DATC + SG_ CF_Datc_Type : 0|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Datc_VerMaj : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_Datc_VerMin : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CR_Datc_OutTempC : 24|8@1+ (0.5,-41.0) [-41.0|86.5] "deg" CLU,FPCM + SG_ CR_Datc_OutTempF : 32|8@1+ (1.0,-42.0) [-42.0|213.0] "deg" CLU + SG_ CF_Datc_IncarTemp : 40|8@1+ (0.5,-40.0) [-40.0|60.0] "deg" BCM,CLU + +BO_ 67 DATC13: 8 DATC + SG_ CF_Datc_TempDispUnit : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ CF_Datc_ModDisp : 2|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_IonClean : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_ChgReqDisp : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_IntakeDisp : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AutoDisp : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_FrDefLed : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,IBOX + SG_ CF_Datc_AutoDefogBlink : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_ClmScanDisp : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AqsDisp : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_AcDisp : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_OpSts : 25|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Mtc_MaxAcDisp : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_DualDisp : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_PwrInf : 32|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_RearManual : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearAutoDisp : 40|2@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Datc_RearOffDisp : 42|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearClimateScnDisp : 44|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearChgReqDisp : 46|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_RearModDisp : 48|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_RearBlwDisp : 52|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_PSModDisp : 56|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ CF_Datc_FrontBlwDisp : 60|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX + +BO_ 66 DATC12: 8 DATC + SG_ CR_Datc_DrTempDispC : 0|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU,IBOX + SG_ CR_Datc_DrTempDispF : 8|8@1+ (1.0,56.0) [58.0|90.0] "" CLU,IBOX + SG_ CR_Datc_PsTempDispC : 16|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU,IBOX + SG_ CR_Datc_PsTempDispF : 24|8@1+ (1.0,56.0) [58.0|90.0] "" CLU,IBOX + SG_ CR_Datc_RearDrTempDispC : 40|8@1+ (0.5,14.0) [15.0|32.0] "deg" CLU + SG_ CR_Datc_RearDrTempDispF : 48|8@1+ (1.0,58.0) [58.0|90.0] "" CLU + SG_ CF_Datc_CO2_Warning : 56|8@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1345 CGW1: 8 BCM + SG_ CF_Gway_IGNSw : 0|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC,ECS,EMS,EPB,ESC,IBOX,LVR,MDPS,SAS,SCC + SG_ CF_Gway_RKECmd : 3|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvKeyLockSw : 6|1@1+ (1.0,0.0) [0.0|1.0] "" ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvKeyUnlockSw : 7|1@1+ (1.0,0.0) [0.0|1.0] "" ECS,EMS,IBOX,ECS,EMS,IBOX + SG_ CF_Gway_DrvDrSw : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU,ECS,EMS,EPB,ESC,IBOX,SCC,TCU + SG_ CF_Gway_DrvSeatBeltSw : 10|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,ESC,IBOX,PSB,TCU,EMS,EPB,ESC,IBOX,PSB,TCU + SG_ CF_Gway_TrunkTgSw : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ECS,EMS,EPB,ESC,IBOX,ECS,EMS,EPB,ESC,IBOX + SG_ CF_Gway_AstSeatBeltSw : 14|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX,PSB,IBOX,PSB + SG_ CF_Gway_SMKOption : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,EMS,IBOX,SMK + SG_ CF_Gway_HoodSw : 17|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,EPB,ESC,IBOX,EMS,EPB,ESC,IBOX + SG_ CF_Gway_TurnSigLh : 19|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC + SG_ CF_Gway_WiperIntT : 21|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperIntSw : 24|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperLowSw : 25|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperHighSw : 26|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_WiperAutoSw : 27|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_RainSnsState : 28|3@1+ (1.0,0.0) [0.0|7.0] "" AFLS,EMS,IBOX,LDWS_LKAS,AFLS,EMS,ESC,IBOX,LDWS_LKAS + SG_ CF_Gway_HeadLampLow : 31|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,SNV,AFLS,EMS,IBOX,LDWS_LKAS,SNV + SG_ CF_Gway_HeadLampHigh : 32|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,EMS,IBOX,LDWS_LKAS,AFLS,EMS,IBOX,LDWS_LKAS + SG_ CF_Gway_HazardSw : 33|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS,ABS,EMS,ESC,IBOX,LCA,LDWS_LKAS + SG_ CF_Gway_AstDrSw : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,IBOX + SG_ CF_Gway_DefoggerRly : 36|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX,EMS,IBOX + SG_ CF_Gway_ALightStat : 37|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_LightSwState : 38|2@1+ (1.0,0.0) [0.0|3.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_Frt_Fog_Act : 40|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,CLU,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_TSigRHSw : 41|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_TSigLHSw : 42|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_DriveTypeOption : 43|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_StarterRlyState : 44|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX,EMS,IBOX,SMK + SG_ CF_Gway_PassiveAccessLock : 45|2@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK + SG_ CF_Gway_WiperMistSw : 47|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,IBOX,LDWS_LKAS + SG_ CF_Gway_PassiveAccessUnlock : 48|2@1+ (1.0,0.0) [0.0|7.0] "" CLU,ECS,EMS,IBOX,ECS,EMS,IBOX,SMK + SG_ CF_Gway_RrSunRoofOpenState : 50|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,DATC,IBOX + SG_ CF_Gway_PassingSW : 51|1@1+ (1.0,0.0) [0.0|1.0] "" AFLS,IBOX,LDWS_LKAS,AFLS,IBOX,LDWS_LKAS + SG_ CF_Gway_HBAControlMode : 52|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_HLpHighSw : 53|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LDWS_LKAS,IBOX,LDWS_LKAS + SG_ CF_Gway_InhibitRMT : 54|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,MDPS,PGS,SCC,SPAS,TPMS,EPB,ESC,IBOX,LCA,LDWS_LKAS,PGS,SCC,SPAS,TPMS + SG_ CF_Gway_RainSnsOption : 56|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ C_SunRoofOpenState : 57|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,DATC,IBOX,DATC,IBOX + SG_ CF_Gway_Ign1 : 58|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_Ign2 : 59|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Gway_ParkBrakeSw : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IBOX,SCC,ESC,IBOX,SCC + SG_ CF_Gway_TurnSigRh : 62|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,IBOX,LCA,LDWS_LKAS,SCC,EMS,IBOX,LCA,LDWS_LKAS,SCC + +BO_ 64 DATC14: 8 DATC + SG_ CF_Datc_AqsLevelOut : 0|4@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Datc_DiagMode : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CR_Datc_SelfDiagCode : 8|8@1+ (1.0,-1.0) [0.0|254.0] "" CLU + SG_ DATC_SyncDisp : 16|4@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_OffDisp : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_SmartVentDisp : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_SmartVentOnOffStatus : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_AutoDefogSysOff_Disp : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ DATC_ADSDisp : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 832 LKAS11: 8 LDWS_LKAS + SG_ CF_Lkas_LdwsSysState : 2|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,IBOX,PSB + SG_ CF_Lkas_SysWarning : 6|4@1+ (1.0,0.0) [0.0|15.0] "" BCM,CLU + SG_ CF_Lkas_LdwsLHWarning : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,PSB + SG_ CF_Lkas_LdwsRHWarning : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU,PSB + SG_ CF_Lkas_HbaLamp : 14|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Lkas_FcwBasReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC + SG_ CR_Lkas_StrToqReq : 16|11@1+ (0.0078125,-8.0) [-8.0|8.0] "Nm" MDPS + SG_ CF_Lkas_ActToi : 27|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Lkas_ToiFlt : 28|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Lkas_HbaSysState : 29|3@1+ (1.0,0.0) [0.0|7.0] "" BCM,CLU + SG_ CF_Lkas_FcwOpt : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_HbaOpt : 34|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,CGW + SG_ CF_Lkas_MsgCount : 36|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,MDPS + SG_ CF_Lkas_FcwSysState : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Lkas_FcwCollisionWarning : 43|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_FusionState : 45|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Lkas_Chksum : 48|8@1+ (1.0,0.0) [0.0|255.0] "" MDPS + SG_ CF_Lkas_FcwOpt_USM : 56|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Lkas_LdwsOpt_USM : 59|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,MDPS + +BO_ 1342 LKAS12: 6 LDWS_LKAS + SG_ CF_Lkas_TsrSlifOpt : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_LkasTsrStatus : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Lkas_TsrSpeed_Display_Clu : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU + SG_ CF_LkasTsrSpeed_Display_Navi : 24|8@1+ (1.0,0.0) [0.0|255.0] "" BCM,CLU + SG_ CF_Lkas_TsrAddinfo_Display : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1338 TMU_GW_E_01: 8 CLU + SG_ CF_Gway_TeleReqDrLock : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqDrUnlock : 2|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqHazard : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqHorn : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Gway_TeleReqEngineOperate : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1078 PAS11: 4 BCM + SG_ CF_Gway_PASDisplayFLH : 0|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASDisplayFRH : 3|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASRsound : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASDisplayFCTR : 8|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,AVM + SG_ CF_Gway_PASDisplayRCTR : 11|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASFsound : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASDisplayRLH : 16|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASDisplayRRH : 19|3@1+ (1.0,0.0) [0.0|7.0] "" AVM,CLU,PGS,AVM + SG_ CF_Gway_PASCheckSound : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASSystemOn : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,Dummy + SG_ CF_Gway_PASOption : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PASDistance : 28|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + +BO_ 48 EMS18: 6 EMS + SG_ CF_Ems_DC1NumPerMSV : 0|8@1+ (1.0,0.0) [0.0|255.0] "" DI_BOX + SG_ CF_Ems_DC2NumPerMSV : 8|16@1+ (1.0,0.0) [0.0|65535.0] "" DI_BOX + SG_ CR_Ems_DutyCyc1MSV : 24|8@1+ (0.1953,0.0) [0.0|49.8] "%" DI_BOX + SG_ CR_Ems_DutyCyc2MSV : 32|8@1+ (0.13725,0.0) [0.0|35.0] "%" DI_BOX + SG_ CR_Ems_DutyCyc3MSV : 40|8@1+ (0.392,0.0) [0.0|100.0] "%" DI_BOX + +BO_ 1322 CLU15: 8 CLU + SG_ CF_Clu_VehicleSpeed : 0|8@1+ (1.0,0.0) [0.0|255.0] "" BCM + SG_ CF_Clu_InhibitP : 9|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_InhibitR : 10|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_InhibitN : 11|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_InhibitD : 12|1@1+ (1.0,0.0) [0.0|1.0] "" BCM + SG_ CF_Clu_HudInfoSet : 13|7@1+ (1.0,0.0) [0.0|127.0] "" HUD + SG_ CF_Clu_HudFontColorSet : 20|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudBrightUpSW : 22|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudBrightDnSW : 24|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudHeightUpSW : 26|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudHeightDnSW : 28|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_HudSet : 30|1@1+ (1.0,0.0) [0.0|1.0] "" HUD + SG_ CF_Clu_HudFontSizeSet : 31|2@1+ (1.0,0.0) [0.0|3.0] "" HUD + SG_ CF_Clu_LanguageInfo : 33|5@1+ (1.0,0.0) [0.0|31.0] "" BCM,PGS + SG_ CF_Clu_ClusterSound : 38|1@1- (1.0,0.0) [0.0|0.0] "" BCM,CGW,FATC + +BO_ 1066 _4WD13: 6 _4WD + SG_ _4WD_CURRENT : 0|8@1+ (0.390625,0.0) [-50.0|50.0] "A" TCU + SG_ _4WD_POSITION : 8|16@1+ (0.015625,0.0) [-180.0|180.0] "Deg" TCU + SG_ _4WD_CLU_THERM_STR : 24|8@1+ (1.0,0.0) [0.0|100.0] "%" TCU + SG_ _4WD_STATUS : 32|8@1+ (1.0,0.0) [0.0|15.0] "" ESC,TCU + +BO_ 1065 _4WD12: 8 _4WD + SG_ Ster_Pos : 0|16@1+ (1.0,-600.0) [-600.0|600.0] "Deg" ESC + SG_ FRSS : 16|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ FLSS : 24|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ RRSS : 32|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ RLSS : 40|8@1+ (1.0,0.0) [0.0|254.0] "km/h" ESC + SG_ CLU_PRES : 48|16@1+ (0.0625,-50.0) [-50.0|50.0] "Bar" ESC + +BO_ 809 EMS12: 8 EMS + SG_ CONF_TCU m1 : 0|6@1+ (1.0,0.0) [0.0|63.0] "" _4WD,ACU,BCM,CLU,DATC,EPB,ESC,IBOX,LCA,SMK + SG_ CAN_VERS m0 : 0|6@1+ (1.0,0.0) [0.0|7.7] "" _4WD,ABS,ESC,IBOX + SG_ TQ_STND m3 : 0|6@1+ (10.0,0.0) [0.0|630.0] "Nm" _4WD,DATC,ECS,EPB,ESC,FATC,IBOX + SG_ OBD_FRF_ACK m2 : 0|6@1+ (1.0,0.0) [0.0|63.0] "" _4WD,ESC,IBOX + SG_ MUL_CODE M : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ABS,ACU,BCM,CLU,DATC,ECS,EPB,ESC,IBOX,LCA,SMK,TCU + SG_ TEMP_ENG : 8|8@1+ (0.75,-48.0) [-48.0|143.25] "deg" _4WD,BCM,CLU,DATC,EPB,ESC,IBOX,SMK,TCU + SG_ MAF_FAC_ALTI_MMV : 16|8@1+ (0.00781,0.0) [0.0|1.99155] "" IBOX,TCU + SG_ VB_OFF_ACT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ACK_ES : 25|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,IBOX + SG_ CONF_MIL_FMY : 26|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,IBOX,TCU + SG_ OD_OFF_REQ : 29|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,TCU + SG_ ACC_ACT : 30|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ABS,CLU,ESC,IAP,IBOX,SCC,TCU + SG_ CLU_ACK : 31|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EPB,ESC,IBOX + SG_ BRAKE_ACT : 32|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ABS,ACU,AFLS,CLU,DATC,ECS,EPB,ESC,IBOX,LDWS_LKAS,TCU + SG_ ENG_CHR : 34|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,ABS,ACU,CLU,DATC,EPB,ESC,FATC,IBOX,SCC,SMK,TCU + SG_ GP_CTL : 38|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ TPS : 40|8@1+ (0.4694836,-15.0234742) [-15.0234742|104.6948357] "%" _4WD,ABS,ACU,CLU,DATC,ECS,EPB,ESC,IBOX,TCU + SG_ PV_AV_CAN : 48|8@1+ (0.3906,0.0) [0.0|99.603] "%" _4WD,AAF,ABS,ACU,AFLS,CLU,DATC,EPB,ESC,IAP,IBOX,LDWS_LKAS,SCC,TCU + SG_ ENG_VOL : 56|8@1+ (0.1,0.0) [0.0|25.5] "liter" _4WD,ABS,ACU,BCM,CLU,DATC,EPB,ESC,IBOX,LDWS_LKAS,SCC,SMK + +BO_ 1064 _4WD11: 8 _4WD + SG_ _4WD_TYPE : 0|2@1+ (1.0,0.0) [0.0|3.0] "" ACU,ESC,TPMS + SG_ _4WD_SUPPORT : 2|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,ESC,TPMS + SG_ _4WD_ERR : 8|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,ESC + SG_ CLU_DUTY : 16|8@1+ (1.0,0.0) [0.0|64.0] "%" ABS,ESC + SG_ R_TIRE : 24|8@1+ (1.0,200.0) [200.0|455.0] "mm" ABS,ESC,TPMS + SG_ _4WD_SW : 32|8@1+ (1.0,0.0) [0.0|9.9] "" ESC + SG_ _2H_ACT : 40|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC + SG_ _4H_ACT : 41|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,CLU,ESC,TPMS + SG_ LOW_ACT : 42|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,TCU,TPMS + SG_ AUTO_ACT : 43|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,ESC,TPMS + SG_ LOCK_ACT : 44|1@1+ (1.0,0.0) [0.0|1.0] "" ABS,CLU,ESC,TPMS + SG_ _4WD_TQC_CUR : 48|16@1+ (1.0,0.0) [0.0|65535.0] "Nm" ABS,ESC + +BO_ 1319 HU_GW_E_01: 8 CLU + SG_ C_ADrLNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ C_ADrUNValueSet : 4|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ C_TwUnNValueSet : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_ABuzzerNValueSet : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_ArmWKeyNValueSet : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_PSMNValueSet : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SCMNValueSet : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_HLEscortNValueSet : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_WELNValueSet : 20|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TriTurnLNValueSet : 22|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SNVWarnNValueSet : 24|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_LkasWarnNValueSet : 26|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1318 HU_GW_E_00: 8 CLU + SG_ C_ADrLURValueReq : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TwUnRValueReq : 2|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_AlarmRValueReq : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_IMSRValueReq : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_HLEscortRValueReq : 8|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_WELRValueReq : 10|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_TriTurnLRValueReq : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_SNVWarnRValueReq : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ C_LkasWarnRValueReq : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 1317 GW_HU_E_01: 8 BCM + SG_ C_ADrLRValue : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_ADrURValue : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_TwUnRValue : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ABuzzerRValue : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ArmWKeyRValue : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_PSMRValue : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SCMRValue : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_HLEscortRValue : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_WELRValue : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TriTurnLRValue : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1316 GW_HU_E_00: 8 BCM + SG_ C_ADrLUNValueConf : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TwUnNValueConf : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_AlarmNValueConf : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_PSMNValueConf : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SCMNValueConf : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_HLEscortNValueConf : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_WELNValueConf : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TriTurnLNValueConf : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1315 GW_SWRC_PE: 8 BCM + SG_ C_ModeSW : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_MuteSW : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SeekDnSW : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SeekUpSW : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_BTPhoneCallSW : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_BTPhoneHangUpSW : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_DISCDownSW : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_DISCUpSW : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SdsSW : 18|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_MTSSW : 20|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_VolDnSW : 22|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_VolUpSW : 24|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1314 GW_IPM_PE_1: 8 BCM + SG_ C_AV_Tail : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ParkingBrakeSW : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_RKECMD : 4|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ C_BAState : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_IGNSW : 12|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_CountryCfg : 16|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ C_TailLampActivity : 26|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ RearSW_RSELockOnOff : 28|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SMKTeleCrankingState : 32|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_SMKTeleCrankingFailRes : 34|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1057 SCC12: 8 SCC + SG_ CF_VSM_Prefill : 0|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_VSM_DecCmdAct : 1|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ CF_VSM_HBACmd : 2|2@1+ (1.0,0.0) [0.0|3.0] "" ESC + SG_ CF_VSM_Warn : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IAP + SG_ CF_VSM_Stat : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,PSB + SG_ CF_VSM_BeltCmd : 8|3@1+ (1.0,0.0) [0.0|7.0] "" ESC,PSB + SG_ ACCFailInfo : 11|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,ESC,IBOX + SG_ ACCMode : 13|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC,IBOX,TCU + SG_ StopReq : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EPB,ESC + SG_ CR_VSM_DecCmd : 16|8@1+ (0.01,0.0) [0.0|2.55] "g" ESC + SG_ aReqMax : 24|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU + SG_ TakeOverReq : 35|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC,TCU + SG_ PreFill : 36|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,TCU + SG_ aReqMin : 37|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" EMS,ESC,TCU + SG_ CF_VSM_ConfMode : 48|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_Failinfo : 50|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_Status : 52|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ AEB_CmdAct : 54|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ AEB_StopReq : 55|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC + SG_ CR_VSM_Alive : 56|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,PSB + SG_ CR_VSM_ChkSum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" ESC,PSB + +BO_ 1313 GW_DDM_PE: 8 BCM + SG_ C_DRVDoorStatus : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_ASTDoorStatus : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_RLDoorStatus : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_RRDoorStatus : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_TrunkStatus : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ C_OSMirrorStatus : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1056 SCC11: 8 SCC + SG_ MainMode_ACC : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,ESC + SG_ SCCInfoDisplay : 1|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC + SG_ AliveCounterACC : 4|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,EMS,ESC,TCU + SG_ VSetDis : 8|8@1+ (1.0,0.0) [0.0|255.0] "km/h or MPH" CLU,ESC,TCU + SG_ ObjValid : 16|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,ESC,TCU + SG_ DriverAlertDisplay : 17|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,ESC + SG_ TauGapSet : 19|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC,TCU + SG_ ACC_ObjStatus : 22|2@1+ (1.0,0.0) [0.0|3.0] "" ABS,ESC + SG_ ACC_ObjLatPos : 24|9@1+ (0.1,-20.0) [-20.0|31.1] "m" ABS,ESC + SG_ ACC_ObjDist : 33|11@1+ (0.1,0.0) [0.0|204.7] "m" ABS,ESC + SG_ ACC_ObjRelSpd : 44|12@1+ (0.1,-170.0) [-170.0|239.5] "m/s" ABS,ESC + SG_ Navi_SCC_Curve_Status : 56|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Curve_Act : 58|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Camera_Act : 60|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ Navi_SCC_Camera_Status : 62|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + +BO_ 1312 CGW3: 8 BCM + SG_ CR_Photosensor_LH : 0|8@1+ (78.125,0.0) [0.0|20000.0] "" DATC,DATC + SG_ CR_Photosensor_RH : 10|8@1+ (78.125,0.0) [0.0|20000.0] "" DATC,DATC + SG_ CF_Hoodsw_memory : 22|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,EMS + SG_ C_MirOutTempSns : 24|8@1+ (0.5,-40.5) [-40.0|60.0] "deg" AAF,CLU,DATC,EMS,SPAS,AAF,DATC,EMS,SPAS + +BO_ 544 ESP12: 8 ESC + SG_ LAT_ACCEL : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LAT_ACCEL_STAT : 11|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LAT_ACCEL_DIAG : 12|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,IBOX,LDWS_LKAS,MDPS,PSB,SCC,TCU + SG_ LONG_ACCEL : 13|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" _4WD,ECS,EMS,EPB,IBOX,LCA,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ LONG_ACCEL_STAT : 24|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ LONG_ACCEL_DIAG : 25|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,SPAS,TCU + SG_ CYL_PRES : 26|12@1+ (0.1,0.0) [0.0|409.5] "Bar" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU + SG_ CYL_PRES_STAT : 38|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EMS,EPB,IBOX,LDWS_LKAS,PSB,SCC,TCU + SG_ CYL_PRESS_DIAG : 39|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EMS,EPB,IBOX,PSB,SCC,TCU + SG_ YAW_RATE : 40|13@1+ (0.01,-40.95) [-40.95|40.96] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ YAW_RATE_STAT : 53|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ YAW_RATE_DIAG : 54|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,AFLS,IBOX,LCA,LDWS_LKAS,MDPS,PSB,SCC,SPAS,TCU + SG_ ESP12_AliveCounter : 56|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + SG_ ESP12_Checksum : 60|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,LPI,TCU,TMU + +BO_ 1307 CLU16: 8 CLU + SG_ CF_Clu_TirePressUnitNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" TPMS + SG_ CF_Clu_SlifNValueSet : 3|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_RearWiperNValueSet : 12|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + +BO_ 790 EMS11: 8 EMS + SG_ SWI_IGK : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ABS,ACU,AHLS,CUBIS,DI_BOX,ECS,EPB,ESC,IBOX,LDWS_LKAS,MDPS,REA,SAS,SCC,TCU + SG_ F_N_ENG : 1|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,IBOX,MDPS,SCC,TCU + SG_ ACK_TCS : 2|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,IBOX + SG_ PUC_STAT : 3|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,DATC,IBOX,TCU + SG_ TQ_COR_STAT : 4|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ESC,IBOX,TCU + SG_ RLY_AC : 6|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,IBOX,TCU + SG_ F_SUB_TQI : 7|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ECS,EPB,ESC,IBOX,TCU + SG_ TQI_ACOR : 8|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU + SG_ N : 16|16@1+ (0.25,0.0) [0.0|16383.75] "rpm" _4WD,ACU,AFLS,CLU,CUBIS,DATC,ECS,EPB,ESC,FPCM,IBOX,MDPS,SCC,TCU + SG_ TQI : 32|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,ECS,EPB,ESC,IBOX,TCU + SG_ TQFR : 40|8@1+ (0.390625,0.0) [0.0|99.6094] "%" _4WD,EPB,ESC,IBOX,TCU + SG_ VS : 48|8@1+ (1.0,0.0) [0.0|254.0] "km/h" _4WD,AAF,ACU,AHLS,BCM,CLU,DATC,ECS,EPB,IBOX,LCA,LDWS_LKAS,LVR,MDPS,ODS,SCC,SMK,SPAS,TCU,TPMS + SG_ RATIO_TQI_BAS_MAX_STND : 56|8@1+ (0.0078,0.0) [0.0|2.0] "" _4WD,IBOX,TCU + +BO_ 1301 CLU14: 8 CLU + SG_ CF_Clu_ADrUNValueSet : 0|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_ADrLNValueSet : 3|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_EscortHLNValueSet : 6|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_DoorLSNValueSet : 8|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_PSMNValueSet : 11|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_TTUnlockNValueSet : 14|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_PTGMNValueSet : 16|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_SCMNValueSet : 18|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_WlightNValueSet : 20|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_TempUnitNValueSet : 22|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,DATC + SG_ CF_Clu_MoodLpNValueSet : 24|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_TrfChgSet : 27|2@1+ (1.0,0.0) [0.0|3.0] "" AFLS + SG_ CF_Clu_OTTurnNValueSet : 29|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_LcaNValueSet : 32|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_RctaNValueSet : 34|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_RcwNValueSet : 36|2@1+ (1.0,0.0) [0.0|3.0] "" LCA + SG_ CF_Clu_EscOffNValueSet : 38|3@1+ (1.0,0.0) [0.0|7.0] "" ESC + SG_ CF_Clu_SccNaviCrvNValueSet : 41|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_SccNaviCamNValueSet : 43|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_SccAebNValueSet : 45|2@1+ (1.0,0.0) [0.0|3.0] "" SCC + SG_ CF_Clu_LkasModeNValueSet : 47|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_FcwNValueSet : 51|2@1+ (1.0,0.0) [0.0|3.0] "" LDWS_LKAS + SG_ CF_Clu_PasSpkrLvNValueSet : 53|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + SG_ CF_Clu_SccDrvModeNValueSet : 56|3@1+ (1.0,0.0) [0.0|7.0] "" SCC + SG_ CF_Clu_HAnBNValueSet : 59|2@1+ (1.0,0.0) [0.0|3.0] "" BCM + SG_ CF_Clu_HfreeTrunkTgNValueSet : 61|3@1+ (1.0,0.0) [0.0|7.0] "" BCM + +BO_ 275 TCU13: 8 TCU + SG_ N_TGT_LUP : 0|8@1+ (10.0,500.0) [500.0|3040.0] "rpm" EMS,IBOX + SG_ SLOPE_TCU : 8|6@1+ (0.5,-16.0) [-16.0|15.5] "%" CLU,CUBIS,EMS,IBOX + SG_ CF_Tcu_InhCda : 14|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_IsgInhib : 15|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_BkeOnReq : 16|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_NCStat : 18|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_TarGr : 20|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,CLU,DATC,EMS,EPB,ESC,IBOX,SCC + SG_ CF_Tcu_ShfPatt : 24|4@1+ (1.0,0.0) [0.0|15.0] "" CLU,CUBIS,EMS,IBOX + SG_ CF_Tcu_InhVis : 28|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_PRelReq : 29|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX,LVR + SG_ CF_Tcu_ITPhase : 30|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_ActEcoRdy : 31|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_TqGrdLim : 32|8@1+ (10.0,0.0) [0.0|2540.0] "Nm/s" EMS,IBOX + SG_ CR_Tcu_IsgTgtRPM : 40|8@1+ (20.0,0.0) [0.0|3500.0] "rpm" EMS,IBOX + SG_ CF_Tcu_SptRdy : 48|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,IBOX + SG_ CF_Tcu_SbwPInfo : 56|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ CF_Tcu_Alive3 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_ChkSum3 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + +BO_ 274 TCU12: 8 TCU + SG_ ETL_TCU : 0|8@1+ (2.0,0.0) [0.0|508.0] "Nm" EMS,IBOX + SG_ CUR_GR : 8|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,EMS,ESC,IBOX,SCC,TPMS + SG_ CF_Tcu_Alive : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX,SCC + SG_ CF_Tcu_ChkSum : 14|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX,SCC + SG_ VS_TCU : 16|8@1+ (1.0,0.0) [0.0|254.0] "km/h" BCM,CLU,DATC,EMS,IBOX,LCA,LVR,PGS,SMK,SNV + SG_ FUEL_CUT_TCU : 28|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ INH_FUEL_CUT : 29|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ IDLE_UP_TCU : 30|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ N_INC_TCU : 31|1@1+ (1.0,0.0) [0.0|1.0] "" EMS,IBOX + SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15.0|15.0] "" EMS,IBOX + SG_ N_TC_RAW : 40|16@1+ (0.25,0.0) [0.0|16383.5] "rpm" EMS,IBOX + SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0.0) [0.0|0.9921875] "km/h" CLU,EMS,IBOX,LCA + +BO_ 273 TCU11: 8 TCU + SG_ TQI_TCU_INC : 0|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,ESC,IBOX + SG_ G_SEL_DISP : 8|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,AFLS,AVM,BCM,CGW,CLU,CUBIS,ECS,EMS,EPB,ESC,IAP,IBOX,LCA,LDWS_LKAS,LVR,MDPS,PGS,SCC,SMK,SNV,SPAS,TPMS + SG_ F_TCU : 12|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,ESC,IBOX + SG_ TCU_TYPE : 14|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,EMS,ESC,IBOX + SG_ TCU_OBD : 16|3@1+ (1.0,0.0) [0.0|7.0] "" EMS,ESC,IBOX + SG_ SWI_GS : 19|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,EMS,EPB,ESC,IBOX,SCC + SG_ GEAR_TYPE : 20|4@1+ (1.0,0.0) [0.0|15.0] "" _4WD,CLU,EMS,ESC,IBOX,SCC + SG_ TQI_TCU : 24|8@1+ (0.390625,0.0) [0.0|99.609375] "%" EMS,ESC,IBOX + SG_ TEMP_AT : 32|8@1+ (1.0,-40.0) [-40.0|214.0] "deg" AAF,CLU,CUBIS,EMS,ESC,IBOX + SG_ N_TC : 40|16@1+ (0.25,0.0) [0.0|16383.5] "rpm" _4WD,EMS,EPB,ESC,IBOX + SG_ SWI_CC : 56|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,CLU,EMS,ESC,IBOX + SG_ CF_Tcu_Alive1 : 58|2@1+ (1.0,0.0) [0.0|3.0] "" EMS,IBOX + SG_ CF_Tcu_ChkSum1 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,IBOX + +BO_ 16 ACU13: 8 ACU + SG_ CF_Acu_CshAct : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CUBIS,IBOX,ODS + +BO_ 1040 CGW_USM1: 8 BCM + SG_ CF_Gway_ATTurnRValue : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PTGMRValue : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_EscortHLRValue : 4|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_TTUnlockRValue : 6|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_ADrLRValue : 8|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_ADrURValue : 11|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_SCMRValue : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_WlightRValue : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PSMRValue : 18|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_OTTurnRValue : 21|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_DrLockSoundRValue : 24|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_HAnBRValue : 27|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_MoodLpRValue : 30|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_HfreeTrunkRValue : 32|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_AutoLightRValue : 35|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_Gway_RearWiperRValue : 38|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_Gway_PasSpkrLvRValue : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + +BO_ 1292 CLU13: 8 CLU + SG_ CF_Clu_LowfuelWarn : 0|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,FPCM,IBOX + SG_ CF_Clu_RefDetMod : 2|1@1+ (1.0,0.0) [0.0|1.0] "" IBOX + SG_ CF_Clu_AvgFCU : 3|2@1+ (1.0,0.0) [0.0|3.0] "" IBOX + SG_ CF_Clu_AvsmCur : 5|1@1+ (1.0,0.0) [0.0|1.0] "" ESC,SCC + SG_ CF_Clu_AvgFCI : 6|10@1+ (0.1,0.0) [0.0|102.2] "" IBOX + SG_ CF_Clu_DrivingModeSwi : 16|2@1+ (1.0,0.0) [0.0|3.0] "" DATC,ECS,EMS,ESC,IAP,MDPS,TCU + SG_ CF_Clu_FuelDispLvl : 18|5@1+ (1.0,0.0) [0.0|31.0] "" CGW,IBOX + SG_ CF_Clu_FlexSteerSW : 23|1@1+ (1.0,0.0) [0.0|1.0] "" MDPS + SG_ CF_Clu_DTE : 24|10@1+ (1.0,0.0) [0.0|1023.0] "" DATC + SG_ CF_Clu_TripUnit : 34|2@1+ (1.0,0.0) [0.0|3.0] "" DATC + SG_ CF_Clu_SWL_Stat : 36|3@1+ (1.0,0.0) [0.0|7.0] "" ACU,EMS + SG_ CF_Clu_ActiveEcoSW : 39|1@1+ (1.0,0.0) [0.0|1.0] "" DATC,EMS,TCU + SG_ CF_Clu_EcoDriveInf : 40|3@1+ (1.0,0.0) [0.0|7.0] "" CUBIS,EMS,IAP,IBOX + SG_ CF_Clu_IsaMainSW : 43|1@1+ (1.0,0.0) [0.0|1.0] "" EMS + SG_ CF_Clu_LdwsLkasSW : 56|1@1+ (1.0,0.0) [0.0|1.0] "" LDWS_LKAS + SG_ CF_Clu_AltLStatus : 59|1@1+ (1.0,0.0) [0.0|1.0] "" BCM,DATC,EMS + SG_ CF_Clu_AliveCnt2 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" EMS,LDWS_LKAS + +BO_ 1290 SCC13: 8 SCC + SG_ SCCDrvModeRValue : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ SCC_Equip : 3|1@1+ (1.0,0.0) [0.0|1.0] "" ESC + SG_ AebDrvSetStatus : 4|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,ESC + +BO_ 1287 TCS15: 4 ESC + SG_ ABS_W_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU,CUBIS,IBOX + SG_ TCS_OFF_LAMP : 1|2@1+ (1.0,0.0) [0.0|1.0] "" _4WD,ACU,CLU + SG_ TCS_LAMP : 3|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,ACU,CLU,CUBIS,IBOX,SCC + SG_ DBC_W_LAMP : 5|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ DBC_F_LAMP : 6|2@1+ (1.0,0.0) [0.0|3.0] "" _4WD,CLU + SG_ ESC_Off_Step : 8|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ AVH_CLU : 16|8@1+ (1.0,0.0) [0.0|255.0] "" CLU,EPB + SG_ AVH_I_LAMP : 24|2@1+ (1.0,0.0) [0.0|3.0] "" EPB + SG_ EBD_W_LAMP : 26|1@1+ (1.0,0.0) [0.0|1.0] "" _4WD,CLU + SG_ AVH_ALARM : 27|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ AVH_LAMP : 29|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EPB,SPAS + +BO_ 1282 TCU14: 4 TCU + SG_ CF_TCU_WarnMsg : 0|3@1+ (1.0,0.0) [0.0|7.0] "" CLU + SG_ CF_TCU_WarnImg : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_TCU_WarnSnd : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ CF_Tcu_GSel_BlinkReq : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,LVR + SG_ CF_Tcu_StRelStat : 12|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,EMS,ESC + SG_ CF_Tcu_DriWarn1 : 13|3@1+ (1.0,0.0) [0.0|7.0] "" CLU,EMS,ESC + SG_ CF_Tcu_DriWarn2 : 16|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,EMS,ESC + +BO_ 1281 ECS11: 3 ECS + SG_ ECS_W_LAMP : 0|1@1+ (1.0,0.0) [0.0|1.0] "" CLU,CUBIS,IBOX + SG_ SYS_NA : 1|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ ECS_DEF : 2|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ ECS_DIAG : 3|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ L_CHG_NA : 4|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Leveling_Off : 5|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ LC_overheat : 6|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Lifting : 8|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Lowering : 9|1@1+ (1.0,0.0) [0.0|1.0] "" CLU + SG_ Damping_Mode : 10|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_Damping : 12|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_Height : 14|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ REQ_level : 16|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + SG_ ACT_Height : 20|4@1+ (1.0,0.0) [0.0|15.0] "" CLU + +BO_ 1024 CLU_CFG11: 2 CLU + SG_ Vehicle_Type : 0|16@1+ (1.0,0.0) [0.0|65536.0] "" _4WD + +BO_ 1280 ACU14: 1 ACU + SG_ CF_SWL_Ind : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_TTL_Ind : 2|2@1+ (1.0,0.0) [0.0|3.0] "" CLU + SG_ CF_SBR_Ind : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU + +BO_ 512 EMS20: 6 EMS + SG_ FCO : 0|16@1+ (0.128,0.0) [0.0|8388.48] "ul" CLU,CUBIS,FPCM,IBOX + SG_ CF_Ems_PumpTPres : 16|8@1+ (3.137254902,0.0) [0.0|800.0] "kPa" FPCM,IBOX + SG_ Split_Stat : 32|1@1+ (1.0,0.0) [0.0|1.0] "" FPCM diff --git a/opendbc_repo/opendbc/dbc/hyundai_2015_mcan.dbc b/opendbc_repo/opendbc/dbc/hyundai_2015_mcan.dbc new file mode 100644 index 000000000000000..6bcd771e5112050 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/hyundai_2015_mcan.dbc @@ -0,0 +1,1564 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: CLOCK HUD H_U DATC CCP KMA_TMU CUBIS TMU IPM RSE_R RRC CGW RSE_L AMP EDT SWRC IBOX CLU FHCU ASD MON AVM KBD + + +BO_ 3221225472 VECTOR__INDEPENDENT_SIG_MSG: 0 Vector__XXX + SG_ C_WHEEL_FL : 0|12@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_WHEEL_FR : 0|12@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_WHEEL_RL : 0|12@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_WHEEL_RR : 0|12@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 2046 TP_EDT_AMP: 8 EDT + SG_ Byte0_TCP_7FE : 7|8@0+ (1,0) [0|0] "" AMP + SG_ Byte1_Data_7FE : 15|8@0+ (1,0) [0|0] "" AMP + SG_ Byte2_Data_7FE : 23|8@0+ (1,0) [0|0] "" AMP + SG_ Byte3_Data_7FE : 31|8@0+ (1,0) [0|0] "" AMP + SG_ Byte4_Data_7FE : 39|8@0+ (1,0) [0|0] "" AMP + SG_ Byte5_Data_7FE : 47|8@0+ (1,0) [0|0] "" AMP + SG_ Byte6_Data_7FE : 55|8@0+ (1,0) [0|0] "" AMP + SG_ Byte7_Data_7FE : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 251 HU_TMU_E_02: 8 H_U + SG_ HU_GPS_Year : 7|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Month : 15|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Day : 23|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Hour : 31|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Minute : 39|8@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ HU_GPS_Second : 47|8@0+ (1,0) [0|0] "" CUBIS,TMU + +BO_ 250 HU_TMU_E_01: 8 H_U + SG_ HU_VoiceRecCom : 2|3@0+ (1,0) [0|0] "" TMU + SG_ HU_LangChgCom : 5|3@0+ (1,0) [0|0] "" TMU + SG_ HU_CallEndCmd : 9|2@0+ (1,0) [0|0] "" TMU + SG_ HU_ServiceReqtID : 13|4@0+ (1,0) [0|0] "" TMU + SG_ HU_MicReqCmd : 15|2@0+ (1,0) [0|0] "" TMU + SG_ HU_SeviceAction : 18|3@0+ (1,0) [0|0] "" TMU + SG_ HU_eCallStatus : 20|2@0+ (1,0) [0|0] "" TMU + +BO_ 1269 TP_CLU_ANDAUTO_HU: 8 CLU + SG_ Byte0_TCP_4F5 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4F5 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4F5 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4F5 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4F5 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4F5 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4F5 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4F5 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1268 TP_HU_ANDAUTO_CLU: 8 H_U + SG_ Byte0_TCP_4F4 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4F4 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4F4 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4F4 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4F4 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4F4 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4F4 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4F4 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1267 TP_CLU_CARPLAY_HU: 8 CLU + SG_ Byte0_TCP_4F3 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4F3 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4F3 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4F3 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4F3 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4F3 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4F3 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4F3 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1266 TP_HU_CARPLAY_CLU: 8 H_U + SG_ Byte0_TCP_4F2 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4F2 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4F2 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4F2 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4F2 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4F2 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4F2 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4F2 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1263 TP_CLU_IBOX_HU: 8 CLU + SG_ Byte0_TCP_4EF : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4EF : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4EF : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4EF : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4EF : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4EF : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4EF : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4EF : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1262 TP_HU_IBOX_CLU: 8 H_U + SG_ Byte0_TCP_4EE : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4EE : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4EE : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4EE : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4EE : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4EE : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4EE : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4EE : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1261 TP_CLU_DLNA_HU: 8 CLU + SG_ Byte0_TCP_4ED : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4ED : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4ED : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4ED : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4ED : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4ED : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4ED : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4ED : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1260 TP_HU_DLNA_CLU: 8 H_U + SG_ Byte0_TCP_4EC : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4EC : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4EC : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4EC : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4EC : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4EC : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4EC : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4EC : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 491 GW_DDM_PE: 8 CLU + SG_ C_DRVDoorStatus : 1|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_ASTDoorStatus : 3|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_RLDoorStatus : 5|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_RRDoorStatus : 7|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_TrunkStatus : 9|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ C_OSMirrorStatus : 11|2@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CUBIS,DATC,EDT,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + +BO_ 1259 TP_CLU_MP_HU: 8 CLU + SG_ Byte0_TCP_4EB : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4EB : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4EB : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4EB : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4EB : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4EB : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4EB : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4EB : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1258 TP_HU_MP_CLU: 8 H_U + SG_ Byte0_TCP_4EA : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4EA : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4EA : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4EA : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4EA : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4EA : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4EA : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4EA : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1257 TP_CLU_FM_HU: 8 CLU + SG_ Byte0_TCP_4E9 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E9 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E9 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E9 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E9 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E9 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E9 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E9 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1256 TP_HU_FM_CLU: 8 H_U + SG_ Byte0_TCP_4E8 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4E8 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4E8 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4E8 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4E8 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4E8 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4E8 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4E8 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1255 TP_CLU_MLT_HU: 8 CLU + SG_ Byte0_TCP_4E7 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E7 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E7 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E7 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E7 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E7 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E7 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E7 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 487 HU_CLU_PE_13: 8 H_U + SG_ Navi_DistToPoint1_F : 11|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint1_I : 7|12@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint1_U : 23|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint2_I : 19|12@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint2_F : 35|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint2_U : 39|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint3_F : 51|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint3_I : 47|12@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToPoint3_U : 63|4@0+ (1,0) [0|0] "" CLU,HUD + +BO_ 1254 TP_HU_MLT_CLU: 8 H_U + SG_ Byte0_TCP_4E6 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4E6 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4E6 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4E6 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4E6 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4E6 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4E6 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4E6 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 486 HU_CLU_PE_12: 8 H_U + SG_ Navi_DistToDest_I : 7|16@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToDest_F : 19|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_DistToDest_U : 23|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_EstimHour : 31|8@0+ (1,0) [0|254] "hh" CLU,HUD + SG_ Navi_EstimMin : 37|6@0+ (1,0) [0|59] "mm" CLU,HUD + SG_ Navi_EstimTimeType : 39|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_Compass : 45|6@0+ (7.5,-7.5) [0|352.5] "Degree" CLU,HUD + +BO_ 229 HU_SYS_E_00: 8 H_U + SG_ SYS_SW_Ver_Req : 1|2@0+ (1,0) [0|0] "" AMP,CCP,CGW,CLOCK,CLU,HUD,IBOX,RRC,RSE_L + SG_ SYS_CAN_Ver_Req : 3|2@0+ (1,0) [0|0] "" AMP,CCP,CGW,CLOCK,CLU,HUD,IBOX,RRC,RSE_L + SG_ SYS_HW_Ver_Req : 5|2@0+ (1,0) [0|0] "" AMP,CCP,CGW,CLOCK,CLU,IBOX,RRC + SG_ SYS_RBD_Req : 9|2@0+ (1,0) [0|0] "" AMP,IBOX + SG_ SYS_MOSTErrorDiag_Req : 11|2@0+ (1,0) [0|0] "" AMP,IBOX + SG_ SYS_Reset_Req : 17|2@0+ (1,0) [0|0] "" AMP,IBOX + +BO_ 1253 TP_CLU_VCDC_HU: 8 CLU + SG_ Byte0_TCP_4E5 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E5 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E5 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E5 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E5 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E5 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E5 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E5 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 485 HU_CLU_PE_11: 8 H_U + SG_ Navi_FixedSpdTrap : 3|4@0+ (10,0) [10|110] "Km/h" CLU,HUD + SG_ Navi_MobileSpdTrap : 7|4@0+ (10,0) [10|110] "Km/h" CLU,HUD + SG_ Navi_OverSpdAlarm : 11|2@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ Navi_SpdRedlightTrap : 15|4@0+ (10,0) [10|110] "Km/h" CLU,HUD + SG_ Navi_NonSpdTrap : 20|5@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_WarningZone : 27|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_MergeWarning : 33|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_CurveWarning : 39|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_BusSpdTrap : 43|4@0+ (10,0) [10|110] "Km/h" CLU,HUD + SG_ Navi_SpdLimit_Type : 49|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_SpdLimit_Unit : 51|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_SpdInfo_Type : 55|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ Navi_SpdLimit : 63|8@0+ (1,0) [1|254] "" CLU,HUD + +BO_ 1252 TP_HU_VCDC_CLU: 8 H_U + SG_ Byte0_TCP_4E4 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4E4 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4E4 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4E4 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4E4 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4E4 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4E4 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4E4 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1251 TP_CLU_JB_HU: 8 CLU + SG_ Byte0_TCP_4E3 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E3 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E3 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E3 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E3 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E3 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E3 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E3 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1250 TP_HU_JB_CLU: 8 H_U + SG_ Byte0_TCP_4E2 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4E2 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4E2 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4E2 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4E2 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4E2 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4E2 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4E2 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1248 TP_TMU_HU: 8 TMU + SG_ Byte0_TCP_4E0 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4E0 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4E0 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4E0 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4E0 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4E0 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4E0 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4E0 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 479 CLU_HU_PE_01: 8 CLU + SG_ CLU_Type : 7|8@0+ (1,0) [0|0] "" H_U + SG_ CLU_Region : 15|8@0+ (1,0) [0|0] "" H_U + SG_ CLU_VersionMinor : 23|8@0+ (1,0) [0|0] "" H_U + SG_ CLU_VersionMajor : 31|8@0+ (1,0) [0|0] "" H_U + SG_ CLU_CurrentDispState : 39|8@0+ (1,0) [0|0] "" H_U + SG_ C_DRVDRSW : 41|2@0+ (1,0) [0|0] "" H_U + SG_ CF_Clu_LowfuelWarning : 44|2@0+ (1,0) [0|0] "" H_U + SG_ CLU_PowerInfo : 46|2@0+ (1,0) [0|0] "" H_U + SG_ C_DrivingModeState : 50|3@0+ (1,0) [0|0] "" H_U + SG_ Clu_RheostatLvl : 55|5@0+ (1,0) [0|0] "" H_U,MON,SWRC + SG_ C_Clu_ActiveEcoSW : 57|2@0+ (1,0) [0|0] "" H_U + SG_ C_Detent : 59|2@0+ (1,0) [0|0] "" CCP,CLOCK,H_U,KBD,MON,RRC,RSE_L,RSE_R + SG_ C_DrivingModeOn : 61|2@0+ (1,0) [0|0] "" H_U + +BO_ 2015 TP_EDT_All_Req: 8 EDT + SG_ Byte0_TCP_7DF : 7|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte1_Data_7DF : 15|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte2_Data_7DF : 23|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte3_Data_7DF : 31|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte4_Data_7DF : 39|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte5_Data_7DF : 47|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte6_Data_7DF : 55|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + SG_ Byte7_Data_7DF : 63|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,FHCU,HUD,H_U,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + +BO_ 474 CLU_HU_PE_02: 8 CLU + SG_ CF_Clu_AvgFCU : 1|2@0+ (1,0) [0|0] "" H_U + SG_ CF_Clu_AvgFCL : 9|10@0+ (1,0) [0|0] "" H_U + SG_ CF_Clu_TermAvgSync : 25|2@0+ (1,0) [0|0] "" H_U + SG_ CF_Clu_EcoDriveInf : 36|3@0+ (1,0) [0|0] "" H_U + SG_ CR_Clu_TermAvgFCI : 33|10@0+ (1,0) [0|0] "" H_U + SG_ CF_CLU_EcoScore : 55|16@0+ (1,0) [0|0] "" H_U + +BO_ 1495 CLU_HU_P_05: 8 CLU + SG_ Clu_TripUnit : 9|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ Clu_DTEWarn : 11|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ Clu_DTE : 7|12@0+ (1,0) [0|1500] "km" H_U,IBOX + SG_ Clu_AFC : 23|10@0+ (0.1,0) [0|99.9] "" H_U,IBOX + SG_ Clu_IFC : 29|10@0+ (0.1,0) [0|99.9] "" H_U,IBOX + SG_ Clu_Odometer : 47|24@0+ (1,0) [0|999999] "" H_U,IBOX + +BO_ 1494 CLU_HU_P_01: 8 CLU + SG_ CF_TripUnit : 13|2@0+ (1,0) [0|0] "" H_U + SG_ CF_DTE : 7|10@0+ (1,0) [0|0] "" H_U + +BO_ 214 AMP_HU_E_SYS: 8 AMP + SG_ AMP_SWVerMajor : 7|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_SWVerMinor : 15|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_CANVerMajor : 23|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_CANVerMinor : 31|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_RBDResult : 34|3@0+ (1,0) [0|0] "" H_U + SG_ AMP_MOSTErrorDiagResult : 38|3@0+ (1,0) [0|0] "" H_U + SG_ AMP_HWVerMajor : 55|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ AMP_HWVerMinor : 63|8@0+ (1,0) [0|254] "" H_U,IBOX + +BO_ 1492 CLU_HU_P_04: 8 CLU + SG_ MM_CR_Fatc_AcnComCst_W : 7|10@0+ (10,0) [0|8000] "W" H_U + SG_ MM_CR_Ldc_PwrMon_W : 12|8@0+ (10,0) [0|2550] "W" H_U + SG_ MM_CR_Fatc_PTCPwrCon_W : 17|10@0+ (10,0) [0|10000] "W" H_U + SG_ MM_CR_BmsChgExp_T_Fast : 39|16@0+ (1,0) [0|0] "minute" H_U + SG_ MM_CR_BmsChgExp_T_Slow : 55|16@0+ (1,0) [0|0] "minute" H_U + +BO_ 1491 CLU_HU_P_03: 8 CLU + SG_ MM_CF_Vcu_EvMod : 3|4@0+ (1,0) [0|0] "" H_U + SG_ MM_CF_Vcu_GarSelDisp : 7|4@0+ (999,0) [0|0] "" H_U + SG_ MM_CF_Vcu_ThiBatTir : 8|1@0+ (1,0) [0|0] "" H_U + SG_ CR_Mcu_MotEstTqPc : 23|10@0+ (0.2,-100) [-100|99.8] "%" H_U + SG_ CR_Mcu_MotActRotSpd_rpm : 39|16@0+ (1,-32768) [-32768|32767] "rpm" H_U + +BO_ 1490 CLU_HU_P_02: 8 CLU + SG_ MM_CR_Vcu_EcoSco : 3|4@0+ (1,0) [0|0] "" H_U + SG_ MM_CF_Vcu_PgmRun5 : 5|2@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Clu_Odometer_kph : 15|24@0+ (0.1,0) [0|0] "km" H_U + +BO_ 1489 DATC_P_B_01: 8 CLU + SG_ C_InhibitR_DATC : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_InhibitP_DATC : 50|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_InhibitN_DATC : 49|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_InhibitD_DATC : 48|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 465 CLU_HU_PE_03: 8 CLU + SG_ CF_Clu_EVDTEDisp : 0|9@0+ (1,0) [0|0] "" H_U,IBOX + SG_ CF_Clu_GasDTEDisp : 17|10@0+ (1,0) [0|0] "" H_U,IBOX + SG_ MM_CR_Clu_TotalDTEDisp : 34|11@0+ (1,0) [0|0] "" H_U,IBOX + SG_ CF_Clu_TripUnit : 49|2@0+ (1,0) [0|0] "" H_U,IBOX + +BO_ 1232 TP_HU_TMU: 8 H_U + SG_ Byte0_TCP_4D0 : 7|8@0+ (1,0) [0|0] "" TMU + SG_ Byte1_Data_4D0 : 15|8@0+ (1,0) [0|0] "" TMU + SG_ Byte2_Data_4D0 : 23|8@0+ (1,0) [0|0] "" TMU + SG_ Byte3_Data_4D0 : 31|8@0+ (1,0) [0|0] "" TMU + SG_ Byte4_Data_4D0 : 39|8@0+ (1,0) [0|0] "" TMU + SG_ Byte5_Data_4D0 : 47|8@0+ (1,0) [0|0] "" TMU + SG_ Byte6_Data_4D0 : 55|8@0+ (1,0) [0|0] "" TMU + SG_ Byte7_Data_4D0 : 63|8@0+ (1,0) [0|0] "" TMU + +BO_ 1488 CLU_HU_P_00: 8 CLU + SG_ MM_CR_Mcu_VehSpd_Kph : 7|8@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Mcu_VehSpdDec_Kph : 15|8@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Bms_Soc_Pc : 23|8@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Vcu_TqMotClu_Pc : 31|8@0+ (1,-127) [0|0] "" H_U + SG_ MM_CR_Bms_DrvEnaDist : 39|8@0+ (1,0) [0|0] "" H_U + SG_ MM_CR_Clu_Soc_Seg : 44|5@0+ (1,0) [0|0] "" H_U,IBOX + +BO_ 208 CLU_HU_E_SYS: 8 CLU + SG_ CLU_SWVerMajor : 7|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_SWVerMinor : 15|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_CANVerMajor : 23|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_CANVerMinor : 31|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_HWVerMajor : 55|8@0+ (1,0) [0|254] "" H_U + SG_ CLU_HWVerMinor : 63|8@0+ (1,0) [0|254] "" H_U + +BO_ 448 HU_DATC_PE_00: 8 H_U + SG_ DATC_AqsLevelChg : 3|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ RSELockOnOff : 7|2@0+ (1,0) [0|0] "" CGW,DATC,IPM,RRC + SG_ DATC_AqsMode : 9|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_Graphreset_Info : 17|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_VRActivity : 33|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_PhoneActivity : 35|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ BlowerNoiseControl : 37|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + +BO_ 1211 TP_HU_TBT_CLU: 8 H_U + SG_ Byte0_TCP_4BB : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4BB : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4BB : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4BB : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4BB : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4BB : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4BB : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4BB : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1207 TP_HU_DAB_CLU: 8 H_U + SG_ Byte0_TCP_4B7 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4B7 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4B7 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4B7 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4B7 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4B7 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4B7 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4B7 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1206 TP_HU_XM_CLU: 8 H_U + SG_ Byte0_TCP_4B6 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4B6 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4B6 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4B6 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4B6 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4B6 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4B6 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4B6 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1204 TP_HU_DMB_CLU: 8 H_U + SG_ Byte0_TCP_4B4 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_4B4 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_4B4 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_4B4 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_4B4 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_4B4 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_4B4 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_4B4 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 432 TMU_GW_PE_01: 8 TMU + SG_ C_DATCOnOffReq : 1|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ C_DATCTempUnit : 3|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ C_DATCTempSet : 15|8@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ TMU_IVRActivity : 33|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ TMU_PhoneActivity : 35|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + +BO_ 1195 TP_CLU_TBT_HU: 8 CLU + SG_ Byte0_TCP_4AB : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4AB : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4AB : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4AB : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4AB : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4AB : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4AB : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4AB : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1191 TP_CLU_DAB_HU: 8 CLU + SG_ Byte0_TCP_4A7 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4A7 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4A7 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4A7 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4A7 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4A7 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4A7 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4A7 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1190 TP_CLU_XM_HU: 8 CLU + SG_ Byte0_TCP_4A6 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4A6 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4A6 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4A6 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4A6 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4A6 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4A6 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4A6 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1188 TP_CLU_DMB_HU: 8 CLU + SG_ Byte0_TCP_4A4 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_4A4 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_4A4 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_4A4 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_4A4 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_4A4 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_4A4 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_4A4 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1179 TP_HU_NAVI_CLU: 8 H_U + SG_ Byte0_TCP_49B : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_49B : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_49B : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_49B : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_49B : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_49B : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_49B : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_49B : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1178 TP_CLU_Ipod_HU: 8 CLU + SG_ Byte0_TCP_49A : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_49A : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_49A : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_49A : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_49A : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_49A : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_49A : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_49A : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 410 HU_CLU_PE_08: 8 H_U + SG_ VCDC_SelDiscNo : 11|4@0+ (1,0) [0|0] "" CLU + SG_ VCDC_TrackChapterNo : 7|10@0+ (1,0) [0|0] "" CLU + SG_ VCDC_PlayTime : 23|24@0+ (1,0) [0|0] "" CLU + SG_ MLT_PlayTime : 47|24@0+ (1,0) [0|0] "" CLU + +BO_ 1176 TP_CLU_DVD_HU: 8 CLU + SG_ Byte0_TCP_498 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_498 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_498 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_498 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_498 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_498 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_498 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_498 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 1175 TP_CLU_USB_HU: 8 CLU + SG_ Byte0_TCP_497 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_497 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_497 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_497 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_497 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_497 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_497 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_497 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 407 HU_CLU_PE_05: 8 H_U + SG_ HU_LanguageInfo : 7|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_MuteStatus : 9|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_VolumeStatus : 15|6@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_NaviDisp : 17|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_NaviStatus : 19|2@0+ (1,0) [0|0] "" CGW,CLU,HUD,IPM + SG_ HU_DistanceUnit : 21|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_Navigation_On_Off : 23|2@0+ (1,0) [0|0] "" AVM,CGW,CLU,DATC,HUD,IPM + +BO_ 1942 TP_AMP_HU_DiagRes: 8 AMP + SG_ Byte0_TCP_796 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_796 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_796 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_796 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_796 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_796 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_796 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_796 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 406 HU_CLU_PE_04: 8 H_U + SG_ C_SDARS_ChannelNo : 7|8@0+ (1,0) [0|0] "" CLU + SG_ C_NaviRouteGuidance : 11|2@0+ (1,0) [0|0] "" CLU + SG_ HD_SPS_ChannelNo : 15|4@0+ (1,0) [0|0] "" CLU + SG_ C_SDARS_PresetNo : 19|4@0+ (1,0) [0|0] "" CLU + SG_ DAB_ServiceFollowing : 21|2@0+ (1,0) [0|0] "" CLU + SG_ SXM_ChannelNo : 25|10@0+ (1,0) [0|999] "" AMP,CLU,HUD + +BO_ 1941 TP_HU_AMP_DiagReq: 8 H_U + SG_ Byte0_TCP_795 : 7|8@0+ (1,0) [0|0] "" AMP + SG_ Byte1_Data_795 : 15|8@0+ (1,0) [0|0] "" AMP + SG_ Byte2_Data_795 : 23|8@0+ (1,0) [0|0] "" AMP + SG_ Byte3_Data_795 : 31|8@0+ (1,0) [0|0] "" AMP + SG_ Byte4_Data_795 : 39|8@0+ (1,0) [0|0] "" AMP + SG_ Byte5_Data_795 : 47|8@0+ (1,0) [0|0] "" AMP + SG_ Byte6_Data_795 : 55|8@0+ (1,0) [0|0] "" AMP + SG_ Byte7_Data_795 : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 1173 TP_CLU_CD_HU: 8 CLU + SG_ Byte0_TCP_495 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_495 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_495 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_495 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_495 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_495 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_495 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_495 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 405 HU_CLU_PE_03: 8 H_U + SG_ HU_IntegPresetNum : 7|8@0+ (1,0) [0|0] "" AMP,CLU,HUD + SG_ Radio_Area : 10|8@0+ (1,0) [0|0] "" CLU + SG_ DMB_PresetNo : 29|5@0+ (1,0) [0|0] "" CLU + SG_ RADIO_PresetNo : 18|5@0+ (1,0) [0|0] "" CLU + SG_ HU_Opstate_DIS2 : 38|7@0+ (1,0) [0|0] "" AMP,CLU,HUD + +BO_ 1168 TP_HU_USB_CLU: 8 H_U + SG_ Byte0_TCP_490 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_490 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_490 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_490 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_490 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_490 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_490 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_490 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1936 TP_HU_All_Req: 8 H_U + SG_ Byte0_TCP_790 : 7|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte1_Data_790 : 15|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte2_Data_790 : 23|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte3_Data_790 : 31|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte4_Data_790 : 39|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte5_Data_790 : 47|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte6_Data_790 : 55|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + SG_ Byte7_Data_790 : 63|8@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CGW,CLOCK,CLU,CUBIS,DATC,EDT,FHCU,HUD,IBOX,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,SWRC,TMU + +BO_ 1167 TP_HU_Ipod_CLU: 8 H_U + SG_ Byte0_TCP_48F : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_48F : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_48F : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_48F : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_48F : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_48F : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_48F : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_48F : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1166 TP_HU_DVD_CLU: 8 H_U + SG_ Byte0_TCP_48E : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_48E : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_48E : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_48E : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_48E : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_48E : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_48E : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_48E : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1165 TP_HU_CD_CLU: 8 H_U + SG_ Byte0_TCP_48D : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_48D : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_48D : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_48D : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_48D : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_48D : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_48D : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_48D : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 1164 TP_CLU_NAVI_HU: 8 CLU + SG_ Byte0_TCP_48C : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_48C : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_48C : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_48C : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_48C : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_48C : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_48C : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_48C : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 139 AMP_HU_E_12: 8 AMP + SG_ AMP_Beep2VolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2FrequencyState : 15|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2OutputMaskState : 31|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2DOnState : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2DOffState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2NOfCycleState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 138 AMP_HU_E_11: 8 AMP + SG_ AMP_Beep1VolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1FrequencyState : 15|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1OutputMaskState : 31|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1DOnState : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1DOffState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1NOfCycleState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 137 AMP_HU_E_10: 8 AMP + SG_ AMP_MTSOutputMaskSupport : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_MTSMuteMaskSupport : 5|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFOutputMaskSupport : 9|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFMuteMaskSupport : 13|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviOutputMaskSupport : 17|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviMuteMaskSupport : 21|2@0+ (1,0) [0|0] "" H_U + +BO_ 1928 TP_HU_PhyRes: 8 H_U + SG_ Byte0_TCP_788 : 7|8@0+ (1,0) [0|0] "" EDT + SG_ Byte1_Data_788 : 15|8@0+ (1,0) [0|0] "" EDT + SG_ Byte2_Data_788 : 23|8@0+ (1,0) [0|0] "" EDT + SG_ Byte3_Data_788 : 31|8@0+ (1,0) [0|0] "" EDT + SG_ Byte4_Data_788 : 39|8@0+ (1,0) [0|0] "" EDT + SG_ Byte5_Data_788 : 47|8@0+ (1,0) [0|0] "" EDT + SG_ Byte6_Data_788 : 55|8@0+ (1,0) [0|0] "" EDT + SG_ Byte7_Data_788 : 63|8@0+ (1,0) [0|0] "" EDT + +BO_ 136 AMP_HU_E_09: 8 AMP + SG_ AMP_MaxBeep2VolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep2Freq_State : 15|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep2OutputMaskSup : 33|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep2DOnState : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep2DOffState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep2NOfCycleState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 135 AMP_HU_E_08: 8 AMP + SG_ AMP_MaxBeep1VolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep1Freq_State : 15|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_Beep1OutputMaskSup : 33|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep1DOnState : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep1DOffState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBeep1NOfCycleState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 134 AMP_HU_E_07: 8 AMP + SG_ ASD_SetValue : 2|3@0+ (1,0) [0|0] "" H_U,IBOX + SG_ ASD_Version : 15|8@0+ (1,0) [0|0] "" H_U,IBOX + +BO_ 1157 TP_HU_CLU_HF: 8 H_U + SG_ Byte0_TCP_485 : 7|8@0+ (1,0) [0|0] "" CLU + SG_ Byte1_Data_485 : 15|8@0+ (1,0) [0|0] "" CLU + SG_ Byte2_Data_485 : 23|8@0+ (1,0) [0|0] "" CLU + SG_ Byte3_Data_485 : 31|8@0+ (1,0) [0|0] "" CLU + SG_ Byte4_Data_485 : 39|8@0+ (1,0) [0|0] "" CLU + SG_ Byte5_Data_485 : 47|8@0+ (1,0) [0|0] "" CLU + SG_ Byte6_Data_485 : 55|8@0+ (1,0) [0|0] "" CLU + SG_ Byte7_Data_485 : 63|8@0+ (1,0) [0|0] "" CLU + +BO_ 133 AMP_HU_E_06: 8 AMP + SG_ AMP_MaxVolumeStep : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBalanceStep : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxFadeStep : 23|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxBassStep : 31|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxMidStep : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxTrebleStep : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_ASDMajorVer : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_ASDMinorVer : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 389 AMP_HU_PE_05: 8 AMP + SG_ AMP_EngOrderC2Setting : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_EngOrderC4Setting : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_EngOrderC6Setting : 23|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand0Setting : 31|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand1Setting : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand2Setting : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand3Setting : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_APSBand4Setting : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 132 AMP_HU_E_05: 8 AMP + SG_ AMP_HFVolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFAudioCutState : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFOutputMaskState : 23|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_HFMuteMaskState : 39|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxHFVolumeState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxHFAudioCutState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 388 AMP_HU_PE_04: 8 AMP + SG_ AMP_PESSModeState : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_PESSDesignSetting : 4|3@0+ (1,0) [0|0] "" H_U + SG_ AMP_PESSAPSSetting : 7|3@0+ (1,0) [0|0] "" H_U + SG_ AMP_PESSVolumeSetting : 15|8@0+ (1,0) [0|0] "" H_U + +BO_ 1156 TP_CLU_HF_HU: 8 CLU + SG_ Byte0_TCP_484 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_484 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_484 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_484 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_484 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_484 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_484 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_484 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 131 AMP_HU_E_04: 8 AMP + SG_ AMP_MTSVolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MTSAudioCutState : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MTSOutputMaskState : 23|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_MTSMuteMaskState : 39|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxMTSVolumeState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxMTSAudioCutState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 387 AMP_HU_PE_03: 8 AMP + SG_ AMP_MainVolumeSetting : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_BalanceSetting : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_FadeSetting : 23|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_BassSetting : 31|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MidSetting : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_TrebleSetting : 47|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_VehicleSpeedamp : 55|8@0+ (1,0) [0|0] "" H_U + +BO_ 130 AMP_HU_E_03: 8 AMP + SG_ AMP_NaviVolumeState : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviAudioCutState : 15|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviOutputMaskState : 23|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_NaviMuteMaskState : 39|16@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxNaviVolumeState : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_MaxNaviAudioCutState : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 129 AMP_HU_E_02: 8 AMP + SG_ AMP_DriveState : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_ConvertibleTopState : 5|2@0+ (1,0) [0|0] "" H_U + +BO_ 385 AMP_HU_PE_02: 8 AMP + SG_ AMP_MuteState : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_RearSpMuteState : 3|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SurroundModeState : 9|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_EQState : 13|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SPDIFMuteSt : 17|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_BeatsModeState : 21|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_DefaultBeep1St : 25|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_DefaultBeep2St : 29|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_AudioSource : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_VIPModeState : 41|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_QLSModeState : 43|2@0+ (1,0) [0|0] "" H_U + +BO_ 128 AMP_HU_E_01: 8 AMP + SG_ AMP_CurrentVehicleID : 7|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_SPDIFModeState : 11|4@0+ (1,0) [0|0] "" H_U + SG_ AMP_MajorVer : 23|8@0+ (1,0) [0|0] "" H_U,MON + SG_ AMP_MinorVer : 31|8@0+ (1,0) [0|0] "" H_U,MON + SG_ AMP_UpdateStartResp : 33|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_UpdateEndResp : 41|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_TuningMajorVer : 55|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_TuningMinorVer : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 384 AMP_HU_PE_01: 8 AMP + SG_ AMP_HFModeState : 1|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ HU_InitInfo : 3|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_ASDModeState : 6|3@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_NaviModeState : 9|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_SPDIFInfo : 12|3@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_MTSModeState : 17|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_VSCModeState : 25|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_SDVCStepState : 29|3@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_Beep1ModeState : 33|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_Beep2ModeState : 41|2@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_DistrInfoState : 55|8@0+ (1,0) [0|0] "" CLU,H_U + SG_ AMP_INFORM_TO_IPM : 57|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,H_U,IPM + SG_ AMP_SignalDoctorState : 59|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_AutoVolumeState : 61|2@0+ (1,0) [0|0] "" H_U + +BO_ 1408 AMP_HU_P_01: 8 AMP + SG_ AMP_SupportMute : 1|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportHFMode : 3|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportCfgBeep1 : 5|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportCfgBeep2 : 7|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportSpeedAdjust : 9|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportSurroundMode : 11|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportNaviMode : 13|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportMTSMode : 15|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportTopState : 17|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportBothLHDandRHD : 19|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportEQState : 21|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportVehicleID : 23|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportAudioSource : 25|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportSPDIFModeState : 27|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportRearSpMute : 29|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportVEQMode : 31|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_MakerID : 39|8@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportASDMode : 41|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportBeatsMode : 43|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportVIPMode : 45|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportQLS : 47|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportSignalDoctor : 49|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportAutoVolume : 51|2@0+ (1,0) [0|0] "" H_U + SG_ AMP_SupportPESSMode : 53|2@0+ (1,0) [0|0] "" H_U + +BO_ 1920 TP_HU_PhyReq: 8 EDT + SG_ Byte0_TCP_780 : 7|8@0+ (1,0) [0|0] "" H_U + SG_ Byte1_Data_780 : 15|8@0+ (1,0) [0|0] "" H_U + SG_ Byte2_Data_780 : 23|8@0+ (1,0) [0|0] "" H_U + SG_ Byte3_Data_780 : 31|8@0+ (1,0) [0|0] "" H_U + SG_ Byte4_Data_780 : 39|8@0+ (1,0) [0|0] "" H_U + SG_ Byte5_Data_780 : 47|8@0+ (1,0) [0|0] "" H_U + SG_ Byte6_Data_780 : 55|8@0+ (1,0) [0|0] "" H_U + SG_ Byte7_Data_780 : 63|8@0+ (1,0) [0|0] "" H_U + +BO_ 371 HU_TMU_PE_01: 8 H_U + SG_ HU_AliveStatus : 1|2@0+ (1,0) [0|0] "" CLU,CGW,TMU + SG_ HU_DeviceType : 5|4@0+ (1,0) [0|0] "" TMU + SG_ HU_DistanceUnit : 7|2@0+ (1,0) [0|0] "" TMU + SG_ HU_AudAllocStatus : 9|2@0+ (1,0) [0|0] "" TMU + SG_ HU_PowerStatus : 12|3@0+ (1,0) [0|0] "" TMU + SG_ HU_BTCallStatus : 15|3@0+ (1,0) [0|0] "" TMU + SG_ HU_VoiceRecStatus : 17|2@0+ (1,0) [0|0] "" TMU + SG_ HU_LangStatus : 20|3@0+ (1,0) [0|0] "" TMU + +BO_ 369 HU_Car_PE_01: 8 H_U + SG_ HU_VehiclePwr : 3|4@0+ (1,0) [0|0] "" AMP,ASD,AVM,CCP,CLOCK,CLU,CUBIS,DATC,FHCU,IPM,KBD,KMA_TMU,MON,RRC,RSE_L,RSE_R,TMU + +BO_ 1392 HU_TMU_P_01: 8 H_U + SG_ HU_GPS_Signal : 7|64@0+ (1,0) [0|0] "" TMU + +BO_ 112 HU_AMP_E_09: 8 H_U + SG_ AMP_Beep1VolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1Frequency : 15|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1Ch_OutputMask : 31|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1DurationOn : 47|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1DurationOff : 55|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1NumberOfCycles : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 1390 GW_CLU_P: 8 CLU + SG_ C_VehicleSpeed : 7|8@0+ (1,0) [0|254] "" H_U,IBOX + SG_ C_Odometer : 15|24@0+ (1,0) [0|999999] "" H_U,IBOX + +BO_ 363 GW_IPM_PE_2: 8 CLU + SG_ C_DRVUnlockState : 1|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_ASTUnlockState : 3|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_RLUnlockstate : 5|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_RRUnlockState : 7|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_VehicleInfoTMU : 9|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_Engine_Status : 11|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_TMULockFeedBack : 23|2@0+ (1,0) [0|0] "" CUBIS,TMU + +BO_ 362 GW_IPM_PE_1: 8 CLU + SG_ C_AV_Tail : 1|2@0+ (1,0) [0|0] "" AMP,CCP,CLOCK,CLU,HUD,H_U,IBOX,RRC,RSE_L + SG_ C_ParkingBrakeSW : 3|2@0+ (1,0) [0|0] "" H_U + SG_ C_RKECMD : 7|4@0+ (1,0) [0|0] "" H_U + SG_ C_BAState : 9|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_IGNSW : 14|3@0+ (1,0) [0|0] "" AMP,AVM,CUBIS,EDT,H_U,MON,RRC,SWRC + SG_ C_CountryCfg : 18|3@0+ (1,0) [0|0] "" AVM,H_U + SG_ C_AltL : 25|2@0+ (1,0) [0|0] "" H_U + SG_ C_TailLampActivity : 27|2@0+ (1,0) [0|0] "" AMP,CCP,CLOCK,HUD,H_U,IBOX,RRC,RSE_L,SWRC + SG_ RearSW_RSELockOnOff : 29|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_TMULockFeedBack : 31|2@0+ (1,0) [0|0] "" CUBIS,TMU + SG_ C_SMKTeleCrankingState : 33|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_SMKTeleCrankingFailRes : 35|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_RKECMD_GEN2 : 39|3@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_Acu_CshAct : 41|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_IntTailAct : 43|2@0+ (1,0) [0|0] "" AMP,CCP,CLOCK,CLU,HUD,H_U,IBOX,RRC,RSE_L + SG_ C_PassiveAccessUnlock : 47|3@0+ (1,0) [0|0] "" H_U,IBOX + SG_ Lca_IndLeft : 49|2@0+ (1,0) [0|0] "" H_U + SG_ FL_SndWarn : 51|2@0+ (1,0) [0|0] "" AMP + SG_ FR_SndWarn : 53|2@0+ (1,0) [0|0] "" AMP + SG_ Lca_IndRight : 55|2@0+ (1,0) [0|0] "" H_U + SG_ RCTA_IndLeft : 57|2@0+ (1,0) [0|0] "" H_U + SG_ RL_SndWarn : 59|2@0+ (1,0) [0|0] "" AMP + SG_ RR_SndWarn : 61|2@0+ (1,0) [0|0] "" AMP + SG_ RCTA_IndRight : 63|2@0+ (1,0) [0|0] "" H_U + +BO_ 361 GW_CHASSIS_PE_1: 8 CLU + SG_ C_Inhibit_State : 3|4@0+ (1,0) [0|0] "" AVM,H_U + SG_ C_P_BrakeStatus : 5|2@0+ (1,0) [0|0] "" AVM,H_U + SG_ C_Clu_AltLStatus : 7|2@0+ (1,0) [0|0] "" AVM,H_U + +BO_ 359 GW_WARNING_PE_01: 8 CLU + SG_ Spas_BEEP_Alarm : 3|4@0+ (1,0) [0|0] "" AMP + SG_ Spas_Audio_VolumeDown : 5|2@0+ (1,0) [0|0] "" AMP + SG_ Spas_Spkr_Flh_Alarm : 9|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Fcnt_Alarm : 11|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Frh_Alarm : 13|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Rlh_Alarm : 17|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Rcnt_Alarm : 19|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Rrh_Alarm : 21|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Lkas_SysStatus : 27|4@0+ (1,0) [0|0] "" AMP,H_U + SG_ Lkas_LH_Warning : 29|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Lkas_RH_Warning : 31|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Spas_Spkr_Level : 35|3@0+ (1,0) [0|0] "" AMP + SG_ Lkas_Audio_VolumeDown : 37|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Audio_VolumeDown : 39|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_BEEP_Alarm : 43|4@0+ (1,0) [0|0] "" AMP + SG_ Pas_Audio_VolumeDown : 45|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Level : 32|3@0+ (1,0) [0|0] "" AMP + SG_ Pas_Spkr_Flh_Alarm : 49|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Fcnt_Alarm : 51|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Frh_Alarm : 53|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Rlh_Alarm : 57|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Rcnt_Alarm : 59|2@0+ (1,0) [0|0] "" AMP,H_U + SG_ Pas_Spkr_Rrh_Alarm : 61|2@0+ (1,0) [0|0] "" AMP,H_U + +BO_ 1376 HU_TMU_P_02: 8 H_U + SG_ HU_GPS_Signal2 : 7|8@0+ (2,0) [0|0] "Degree" TMU + SG_ HU_GPS_Signal3 : 9|2@0+ (1,0) [0|0] "" TMU + SG_ HU_GPS_Signal4 : 12|3@0+ (1,0) [0|0] "" TMU + +BO_ 93 DATC_HU_E_SYS: 8 CLU + SG_ DATC_SWVerMajor : 7|8@0+ (1,0) [0|254] "" H_U + SG_ DATC_SWVerMinor : 15|8@0+ (1,0) [0|254] "" H_U + SG_ DATC_CANVerMajor : 23|8@0+ (1,0) [0|254] "" H_U + SG_ DATC_CANVerMinor : 31|8@0+ (1,0) [0|254] "" H_U + +BO_ 344 GW_CLU_PE: 8 CLU + SG_ C_InhibitP : 1|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_InhibitR : 3|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_InhibitN : 5|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_InhibitD : 7|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_P_BrakeStatus : 9|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_Clu_AltLStatus : 11|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ CF_Clu_LowfuelWarning : 13|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ C_InhibitRMT : 15|2@0+ (1,0) [0|0] "" H_U + SG_ CF_SMKRKECmd : 18|3@0+ (1,0) [0|0] "" H_U + +BO_ 87 HU_E_02: 8 H_U + SG_ NaviValidity : 1|2@0+ (1,0) [0|0] "" CGW,CLU + +BO_ 343 GW_WARNING_PE_02: 8 CLU + SG_ CF_Lkas_TsrSlifOpt : 1|2@0+ (1,0) [0|3] "" H_U + SG_ CF_Lkas_TsrStatus : 3|2@0+ (1,0) [0|3] "" H_U + SG_ CF_Lkas_TsrAddinfo_Disp : 7|2@0+ (1,0) [0|3] "" H_U + SG_ CF_Lkas_TsrSpeed_Display : 15|8@0+ (1,0) [0|255] "" H_U + +BO_ 75 HU_AMP_E_12: 8 H_U + SG_ AMP_EngOrderC2GainSet : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_EngOrderC4GainSet : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_EngOrderC6GainSet : 23|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand0GainSet : 31|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand1GainSet : 39|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand2GainSet : 47|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand3GainSet : 55|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_APSBand4GainSet : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 74 HU_AMP_E_11: 8 H_U + SG_ AMP_PESSMode : 1|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_PESSDesignSet : 4|3@0+ (1,0) [0|0] "" AMP + SG_ AMP_PESSAPSSet : 7|3@0+ (1,0) [0|0] "" AMP + SG_ AMP_PESSVolumeSet : 15|8@0+ (1,0) [0|0] "" AMP + +BO_ 1864 TP_AMP_EDT: 8 AMP + SG_ Byte0_TCP_748 : 7|8@0+ (1,0) [0|0] "" EDT + SG_ Byte1_Data_748 : 15|8@0+ (1,0) [0|0] "" EDT + SG_ Byte2_Data_748 : 23|8@0+ (1,0) [0|0] "" EDT + SG_ Byte3_Data_748 : 31|8@0+ (1,0) [0|0] "" EDT + SG_ Byte4_Data_748 : 39|8@0+ (1,0) [0|0] "" EDT + SG_ Byte5_Data_748 : 47|8@0+ (1,0) [0|0] "" EDT + SG_ Byte6_Data_748 : 55|8@0+ (1,0) [0|0] "" EDT + SG_ Byte7_Data_748 : 63|8@0+ (1,0) [0|0] "" EDT + +BO_ 327 TMU_HU_PE_03: 8 TMU + SG_ TMU_TbT_TurnIcon : 7|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_CountDownBar : 11|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_Distance_Unit : 13|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DestDistance_Unit : 15|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DistanceLo : 27|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DistanceHi : 23|12@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DestDistanceLo : 43|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_DestDistanceHi : 39|12@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_ExpectRemainHour : 55|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_TbT_ExpectRemainMin : 61|6@0+ (1,0) [0|0] "" H_U + +BO_ 326 TMU_HU_PE_02: 8 TMU + SG_ TMU_CallStatus : 3|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_CallType : 6|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_CDMA_Streng : 11|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_PacketStatus : 13|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_TalkTimeHour : 20|5@0+ (1,0) [0|0] "" H_U + SG_ TMU_TalkTimeMinute : 29|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_TalkTimeSecond : 37|6@0+ (1,0) [0|0] "" H_U + +BO_ 325 TMU_HU_PE_01: 8 TMU + SG_ TMU_AliveStatus : 2|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_AudioStatus : 4|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_UpdateStatus : 7|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_LangStatus : 10|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_VoiceRecStatus : 12|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_MicStatus : 14|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_ServCommuStatus : 19|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_PowerStatus : 21|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_EngineStatus : 23|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_DownProgress : 31|8@0+ (1,0) [0|0] "" H_U + +BO_ 69 TMU_HU_E_04: 8 TMU + SG_ TMU_eCall : 1|2@0+ (1,0) [0|0] "" H_U + +BO_ 67 TMU_GW_E_01: 8 TMU + SG_ C_ReqDrLock : 1|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ C_ReqDrUnlock : 3|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ C_ReqHazard : 5|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ C_ReqHorn : 7|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ C_ReqEngineOperate : 9|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + +BO_ 66 TMU_HU_E_03: 8 TMU + SG_ CDMA_SelfDiag : 1|2@0+ (1,0) [0|0] "" H_U + SG_ CDMA_Antena_SelfDiag : 3|2@0+ (1,0) [0|0] "" H_U + +BO_ 1345 TMU_HU_P_02: 8 TMU + SG_ TMU_SupVoiceTextService : 1|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_SupEcoCoachService : 3|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_SupSongTagService : 5|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_SupContentService : 7|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_MajorVersion : 15|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_MinorVersion : 23|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_DistributeInfo : 27|4@0+ (1,0) [0|0] "" H_U + +BO_ 65 TMU_HU_E_02: 8 TMU + SG_ TMU_BarLevel1 : 7|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel2 : 1|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel4 : 21|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel3 : 11|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel5 : 31|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel6 : 25|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel8 : 45|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel7 : 35|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel9 : 55|6@0+ (1,0) [0|0] "" H_U + SG_ TMU_BarLevel10 : 63|6@0+ (1,0) [0|0] "" H_U + +BO_ 1344 TMU_HU_P_01: 8 TMU + SG_ TMU_Arrow : 3|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_ReFill_Info : 5|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_AverageMPG : 1|10@0+ (1,0) [0|0] "" H_U + SG_ TMU_TotalMPG : 23|10@0+ (1,0) [0|0] "" H_U + SG_ TMU_RewardStar : 37|14@0+ (1,0) [0|0] "" H_U + +BO_ 64 TMU_HU_E_01: 8 TMU + SG_ TMU_DisMode : 3|4@0+ (1,0) [0|0] "" H_U + SG_ TMU_AudSrcType : 7|4@0+ (1,0) [0|0] "" CLU,DATC,H_U + SG_ TMU_AudReqCmd : 9|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_LangCmd : 12|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_ServReq : 15|3@0+ (1,0) [0|0] "" H_U + SG_ TMU_ErrorEvent : 23|8@0+ (1,0) [0|0] "" H_U + SG_ TMU_BeepCmd : 25|2@0+ (1,0) [0|0] "" H_U + SG_ TMU_eCall : 28|3@0+ (1,0) [0|0] "" H_U + +BO_ 62 HU_Navi_E_00: 8 H_U + SG_ Navi_SLIF_SpdUnit : 1|2@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ Navi_SLIF_Frwinfo : 4|3@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ Navi_SLIF_LinkClass : 7|3@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ Navi_SLIF_SpdLimit : 15|8@0+ (1,0) [1|254] "" CGW,CLU,HUD + SG_ Navi_SLIFMapSource : 29|4@0+ (1,0) [0|8] "" CGW,CLU,HUD + SG_ Navi_SLIF_CountryCode : 23|10@0+ (1,0) [0|0] "" CGW,CLU,HUD + +BO_ 52 HU_DATC_E_02: 8 H_U + SG_ HU_DATC_DrTempUpDn : 1|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_PsTempUpDn : 3|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RlTempUpDn : 5|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RrTempUpDn : 7|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_MainBlower : 11|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_SubBlower : 15|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RearBlower : 19|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATCRearPsModeSet : 23|4@0+ (1,0) [0|0] "" CGW,CLU + SG_ HU_DATC_FrontModeSet : 27|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RearModeSet : 31|4@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_AutoSet : 33|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_OffReq : 35|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_IntakeSet : 37|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RearOnOffSet : 39|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_AcSet : 41|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_AqsSet : 43|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_FrontDefog : 45|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_RearDefog : 47|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_ZoneControl : 49|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ HU_DATC_CO2Set : 51|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ DATC_SmartVentOnOffSet : 53|2@0+ (1,0) [0|0] "" CGW,CLU,DATC,IPM + SG_ DATC_ADSOnOffSet : 55|2@0+ (1,0) [0|0] "" CGW,CLU + SG_ HU_DATC_RearAutoDisp : 57|2@0+ (1,0) [0|0] "" CGW,CLU + SG_ HU_DATC_RearOffDisp : 59|2@0+ (1,0) [0|0] "" CGW,CLU + +BO_ 308 DATC_PE_05: 8 CLU + SG_ DATC_PwrInfo : 3|4@0+ (1,0) [0|0] "" AMP,AVM,CUBIS,H_U,MON + SG_ DATC_AltL : 5|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_CarInfo : 7|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_ParkingBrake : 9|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_LowFuelWarn : 11|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_Rear_Off_Disp : 13|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_Rear_AutoDisp : 15|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_Rear_BlowerDisp : 19|4@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_DrSeatWarmerDisp : 22|3@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_SyncDisp : 27|4@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_RearDispCtrl : 31|4@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_RearDrModeDisp : 35|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_PsSeatWarmerDisp : 38|3@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_DrVentSeatDisp : 42|3@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_PSVentSeatDisp : 46|3@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_RrDefLed : 49|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_SmartVentOnOffStatus : 51|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_ADSOnOffStatus : 53|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_AcDisp_OSD : 55|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_PsModeDisp_OSD : 59|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_ModeDisp_OSD : 63|4@0+ (1,0) [0|0] "" H_U + +BO_ 307 DATC_PE_04: 8 CLU + SG_ DATC_DiagMode : 1|2@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_Rear_ChangeReqDisp : 3|2@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_Rear_ClimateScnDisp : 5|2@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_CO2OnOffStatus : 7|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_SelfDiagDisp : 15|8@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_RearBlwDisp_OSD : 19|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_AqsLevelOut : 23|4@0+ (1,0) [0|0] "" H_U,IBOX,MON + SG_ DATC_RearModeDisp : 27|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_RearPsModeDisp : 31|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_FrontBlwDisp_Ps : 35|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_AutoDisp_Ps : 39|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_RearModeDisp_OSD : 43|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_RearPSModeDisp_OSD : 47|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_FrontBlwDisp_OSD : 51|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_FrontBlwDispPs_OSD : 55|4@0+ (1,0) [0|0] "" H_U + SG_ DATC_Variant : 63|8@0+ (1,0) [0|0] "" H_U,IBOX,MON + +BO_ 306 DATC_PE_03: 8 CLU + SG_ DATC_ModeDisp : 3|4@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_TempUnit : 5|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_AutoDisp : 9|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_IntakeDisp : 11|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_ChangeReqDisp : 13|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_AcDisp : 17|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_AqsDisp : 19|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_ClimateScnDisp : 21|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_DualDisp : 25|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_OffDisp : 27|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_OpSts : 30|3@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_RearManual : 33|2@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_FrDefLed : 37|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_SmartVentDisp : 39|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_AutoDefogBlink : 41|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_ADSDisp : 43|2@0+ (1,0) [0|0] "" H_U + SG_ DATC_IonClean : 45|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_CO2Warning : 47|2@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_SubBlowerDisp : 51|4@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_BeepReq : 55|4@0+ (1,0) [0|0] "" H_U,KBD,MON + SG_ DATC_MainBlowerDisp : 59|4@0+ (1,0) [0|0] "" H_U,IBOX + SG_ DATC_PsModeDisp : 63|4@0+ (1,0) [0|0] "" H_U,IBOX + +BO_ 1329 DATC_P_02: 8 CLU + SG_ DATC_AmbientTemp_C : 7|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_AmbientTemp_F : 23|8@0+ (1,0) [0|0] "" H_U,MON + +BO_ 305 DATC_PE_02: 8 CLU + SG_ DATC_DrTempDispC : 7|8@0+ (0.5,14) [15|32] "C" H_U,IBOX,MON + SG_ DATC_Rear_DrTempDispC : 15|8@0+ (0.5,14) [15|32] "C" H_U,IBOX,MON + SG_ DATC_DrTempDispF : 23|8@0+ (1,56) [58|90] "F" H_U,IBOX,MON + SG_ DATC_Rear_DrTempDispF : 31|8@0+ (1,56) [58|90] "F" H_U,IBOX,MON + SG_ DATC_PsTempDispC : 39|8@0+ (0.5,14) [15|32] "C" H_U,IBOX,MON + SG_ Datc_RearPsTempDispC : 47|8@0+ (0.5,14) [15|32] "C" H_U,IBOX,MON + SG_ DATC_PsTempDispF : 55|8@0+ (1,56) [58|90] "F" H_U,IBOX,MON + SG_ DATC_RearPsTempDispF : 63|8@0+ (1,56) [58|90] "F" H_U,IBOX,MON + +BO_ 304 DATC_PE_01: 8 CLU + SG_ DATC_Type : 7|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerMMMajor : 15|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerMMMinor : 23|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerBDFMajor : 31|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerBDMinor : 39|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerCSMajor : 47|8@0+ (1,0) [0|0] "" H_U,MON + SG_ DATC_VerCSMinor : 55|8@0+ (1,0) [0|0] "" H_U,MON + +BO_ 291 HU_CLU_PE_07: 8 H_U + SG_ NV_DS_Curve : 3|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_Merge : 7|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_RailCross : 9|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_FallingRocks : 11|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_SchoolZone : 13|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_AccidentBlack : 15|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_SpeedBump : 17|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_RoadKill : 19|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_Downhill : 21|2@0+ (1,0) [0|0] "" CLU + SG_ NV_DS_Fog : 23|2@0+ (1,0) [0|0] "" CLU + SG_ NV_Display_TG : 31|2@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_Charge : 39|16@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_Charge_Unit : 55|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_BarGraph100Level : 63|8@0+ (1,0) [0|100] "%" CLU,HUD + +BO_ 290 HU_CLU_PE_06: 8 H_U + SG_ NV_SD_SpdLimit2 : 3|4@0+ (10,0) [0|0] "km/h" CLU + SG_ NV_SD_SpdLimit1 : 7|4@0+ (10,0) [0|0] "km/h" CLU + SG_ NV_SD_EtcCam : 11|4@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_SpdLimit3 : 15|4@0+ (10,0) [0|0] "km/h" CLU + SG_ NV_SD_SignCam : 17|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_SignOverCam : 19|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_MobileCam : 21|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_FixedCam : 23|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_OverLoadCam : 25|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_ParkCam : 27|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_CutInCam : 29|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_BusOnlyCam : 31|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_ShoulderCam : 35|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_TrafficCam : 37|2@0+ (1,0) [0|0] "" CLU + SG_ NV_SD_PlateRcgCam : 39|2@0+ (1,0) [0|0] "" CLU + +BO_ 286 HU_CLU_PE_10: 8 H_U + SG_ Navi_TBTInfo : 63|8@0+ (1,0) [0|0] "" CGW,CLU + +BO_ 29 CLU_HU_E_00: 8 CLU + SG_ SYS_CLUVer : 7|16@0+ (1,0) [0|0] "" CUBIS,H_U + SG_ CLU_ClockInfoReq : 17|2@0+ (1,0) [0|0] "" H_U + SG_ CLU_DateInfoReq : 19|2@0+ (1,0) [0|0] "" H_U + +BO_ 27 AMP_HU_E_00: 8 AMP + SG_ SYS_AMPVer : 7|16@0+ (1,0) [0|0] "" H_U + +BO_ 23 HU_IPM_E_00: 8 H_U + SG_ C_ADrLNValueSet : 2|3@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ADrUNValueSet : 5|3@0+ (1,0) [0|0] "" DATC,IPM + SG_ SYS_Ver_Req : 7|2@0+ (1,0) [0|0] "" AMP,AVM,CLU,CUBIS,DATC,IPM + SG_ C_IMSRValueReq : 9|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_PSMNValueSet : 11|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_SCMNValueSet : 13|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ADrLURValueReq : 15|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ABuzzerNValueSet : 17|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_AlarmRValueReq : 19|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ArmWKeyNValueSet : 21|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_TwUnRValueReq : 23|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_TwUnNValueSet : 25|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_AutoMRFoldRValueReq : 27|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_AutoMRFoldNValueSet : 29|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ADrLRValueReq : 31|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ArmWKeyRValueReq : 33|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ABuzzerRValueReq : 35|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_ADrURValueReq : 37|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_PSMRValueReq : 39|2@0+ (1,0) [0|0] "" DATC,IPM + SG_ C_SCMRValueReq : 47|2@0+ (1,0) [0|0] "" DATC,IPM + +BO_ 277 HU_CLU_PE_02: 8 H_U + SG_ TBT_Display_Type : 7|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_Side_Street : 15|16@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_Direction : 31|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_Distance_Turn_Point : 39|16@0+ (1,0) [0|0] "m" CLU,HUD + SG_ TBT_Combined_Side_Street : 51|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_Scale : 55|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ TBT_DistancetoTurnPoint : 59|4@0+ (1,0) [0|0] "times" CLU,HUD + SG_ TBT_Bar_Graph_Level : 63|4@0+ (10,0) [0|100] "" CLU,HUD + +BO_ 276 HU_CLU_PE_01: 8 H_U + SG_ HU_OpState : 6|7@0+ (1,0) [0|0] "" AMP,CLU + SG_ HU_Navi_On_Off : 7|1@0+ (1,0) [0|0] "" CLU,HUD + SG_ HU_Preset_Number : 12|5@0+ (1,1) [1|30] "" AMP,CLU + SG_ HU_Tuner_Area : 15|3@0+ (1,0) [0|0] "" AMP,CLU + SG_ HU_Track_Number : 23|16@0+ (1,0) [0|0] "" CLU + SG_ HU_Play_time_Sec : 39|6@0+ (1,0) [0|0] "" CLU + SG_ HU_Play_time_Min : 33|7@0+ (1,0) [0|0] "" CLU + SG_ HU_Play_time_Hour : 42|6@0+ (1,0) [0|0] "" CLU + SG_ HU_Disc_select_No : 59|4@0+ (1,0) [0|0] "" CLU + SG_ HU_Frequency : 52|9@0+ (1,0) [0|0] "" AMP,CLU + +BO_ 17 HU_AMP_E_10: 8 H_U + SG_ AMP_Beep2VolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2Frequency : 15|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2Ch_OutputMask : 31|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2DurationOn : 47|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2DurationOff : 55|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2NumberOfCycles : 63|8@0+ (1,0) [0|0] "" AMP + +BO_ 15 HU_AMP_E_08: 8 H_U + SG_ AMP_MainVolumeSet : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_BalanceSet : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_FadeSet : 23|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_BassSet : 31|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_MidSet : 39|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_TrebleSet : 47|8@0+ (1,0) [0|0] "" AMP + +BO_ 14 HU_AMP_E_07: 8 H_U + SG_ AMP_HFVolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_HFMainAudioCut : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_HFChannelOutputMask : 23|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_HFChannelMuteMask : 39|16@0+ (1,0) [0|0] "" AMP + +BO_ 13 HU_AMP_E_06: 8 H_U + SG_ AMP_MTSVolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_MTSMainAudioCut : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_MTSChannelOutputMask : 23|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_MTSChannelMuteMask : 39|16@0+ (1,0) [0|0] "" AMP + +BO_ 12 HU_AMP_E_05: 8 H_U + SG_ AMP_NaviVolumeStep : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_NaviMainAudioCut : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_NaviChannelOutputMask : 23|16@0+ (1,0) [0|0] "" AMP + SG_ AMP_NaviChannelMuteMask : 39|16@0+ (1,0) [0|0] "" AMP + +BO_ 11 HU_AMP_E_04: 8 H_U + SG_ AMP_Drive : 1|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_ConvertibleTop : 5|2@0+ (1,0) [0|0] "" AMP + +BO_ 10 HU_AMP_E_03: 8 H_U + SG_ AMP_CrtVehicleID : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_SPDIFMode : 11|4@0+ (1,0) [0|0] "" AMP + SG_ AMP_VersionReq : 17|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_UpdateStart : 25|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_UpdateEnd : 33|2@0+ (1,0) [0|0] "" AMP + +BO_ 9 HU_AMP_E_02: 8 H_U + SG_ AMP_Mute : 1|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_RearSpMute : 3|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_SurroundMode : 5|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_VEQMode : 7|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_AudioMode : 15|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_EQ : 17|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_Reset : 19|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_SPDIFMute : 21|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_DefaultBeep1 : 25|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_DefaultBeep2 : 29|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_BeatsMode : 33|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_VIPMode : 35|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_QLSMode : 37|2@0+ (1,0) [0|0] "" AMP + +BO_ 1288 HU_CLU_P_02: 8 H_U + SG_ NV_TIME_TYPE : 3|4@0+ (1,0) [0|0] "" CLU + SG_ NV_Hour : 15|8@0+ (1,0) [0|0] "" CLU + SG_ NV_Min : 23|8@0+ (1,0) [0|0] "" CLU + +BO_ 8 HU_AMP_E_01: 8 H_U + SG_ AMP_HFMode : 1|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_NaviMode : 3|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_MTSMode : 5|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_VSCMode : 7|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep1Mode : 9|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_Beep2Mode : 11|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_SDVCStep : 14|3@0+ (1,0) [0|0] "" AMP + SG_ AMP_ASDMode : 18|3@0+ (1,0) [0|0] "" AMP + SG_ AMP_SignalDoctor : 20|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_AutoVolume : 22|2@0+ (1,0) [0|0] "" AMP + +BO_ 1287 HU_CLU_P_01: 8 H_U + SG_ NV_DistToTurn_F1 : 3|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_Unit : 7|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_F3 : 11|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_F2 : 15|4@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_I1 : 23|16@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_I2 : 39|16@0+ (1,0) [0|0] "" CLU + SG_ NV_DistToTurn_I3 : 55|16@0+ (1,0) [0|0] "" CLU + +BO_ 1286 HU_CLU_P_00: 8 H_U + SG_ NV_EstDist_F : 3|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstDist_Unit : 7|4@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstHour : 15|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstMin : 23|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_Azimuth : 31|8@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstDist_I : 39|16@0+ (1,0) [0|0] "" CLU,HUD + SG_ NV_EstimTimeType : 49|2@0+ (1,0) [0|0] "" CGW,CLU,HUD + SG_ NV_EstimTimeFormat : 51|2@0+ (1,0) [0|0] "" CGW,CLU,HUD + +BO_ 1284 HU_AMP_P_01: 8 H_U + SG_ HU_VehicleSpeed : 7|8@0+ (1,0) [0|0] "" AMP + SG_ AMP_SetMaxMainVolStep : 9|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_LKASWarningOn : 21|2@0+ (1,0) [0|0] "" AMP + SG_ AMP_BSDWarningOn : 23|2@0+ (1,0) [0|0] "" AMP + +BO_ 256 HU_MON_PE_01: 8 H_U + SG_ HU_Type : 7|8@0+ (1,0) [0|0] "" AMP,CGW,CLU,HUD,KMA_TMU + SG_ HU_VerMajor : 15|8@0+ (1,0) [0|0] "" AMP,CLU,KMA_TMU,MON + SG_ HU_VerMinor : 23|8@0+ (1,0) [0|0] "" AMP,CLU,KMA_TMU,MON + SG_ HU_DistributeInfo : 31|8@0+ (1,0) [0|0] "" AMP,CGW,CLU,KMA_TMU,MON,RRC + SG_ HU_SubVerMajor : 39|8@0+ (1,0) [0|0] "" AMP,MON + SG_ HU_SubVerMinor : 47|8@0+ (1,0) [0|0] "" AMP,MON + SG_ HU_SDARSVersion : 55|8@0+ (1,0) [0|0] "" AMP,MON + SG_ HU_AdasSupport : 58|3@0+ (1,0) [0|0] "" CGW,CLU + +BO_ 1092 NM_CLOCK: 8 CLOCK + SG_ Destination_CLOCK : 7|8@0+ (1,0) [0|0] "" HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CLOCK : 13|2@0+ (1,0) [0|0] "" HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CLOCK : 10|3@0+ (1,0) [0|0] "" HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1108 NM_HUD: 8 HUD + SG_ Destination_HUD : 7|8@0+ (1,0) [0|0] "" CLOCK,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_HUD : 13|2@0+ (1,0) [0|0] "" CLOCK,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_HUD : 10|3@0+ (1,0) [0|0] "" CLOCK,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1088 NM_H_U: 8 H_U + SG_ Destination_H_U : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_H_U : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_H_U : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1091 NM_DATC: 8 DATC + SG_ Destination_DATC : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_DATC : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_DATC : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1105 NM_CCP: 8 CCP + SG_ Destination_CCP : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CCP : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CCP : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1100 NM_KMA_TMU: 8 KMA_TMU + SG_ Destination_KMA_TMU : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_KMA_TMU : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_KMA_TMU : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1098 NM_CUBIS: 8 CUBIS + SG_ Destination_CUBIS : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CUBIS : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CUBIS : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1099 NM_TMU: 8 TMU + SG_ Destination_TMU : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_TMU : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_TMU : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1095 NM_IPM: 8 IPM + SG_ Destination_IPM : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_IPM : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_IPM : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1107 NM_RSE_R: 8 RSE_R + SG_ Destination_RSE_R : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_RSE_R : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_RSE_R : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1093 NM_RRC: 8 RRC + SG_ Destination_RRC : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_RRC : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_RRC : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1109 NM_CGW: 8 CGW + SG_ Destination_CGW : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CGW : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CGW : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1106 NM_RSE_L: 8 RSE_L + SG_ Destination_RSE_L : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_RSE_L : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_RSE_L : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1096 NM_AMP: 8 AMP + SG_ Destination_AMP : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_AMP : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_AMP : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1103 NM_EDT: 8 EDT + SG_ Destination_EDT : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_EDT : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_EDT : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1110 NM_SWRC: 8 SWRC + SG_ Destination_SWRC : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_SWRC : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_SWRC : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,IBOX,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1102 NM_IBOX: 8 IBOX + SG_ Destination_IBOX : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_IBOX : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,CLU,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_IBOX : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,CLU,FHCU,ASD,MON,AVM,KBD + +BO_ 1101 NM_CLU: 8 CLU + SG_ Destination_CLU : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,FHCU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_CLU : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,FHCU,ASD,MON,AVM,KBD + SG_ NMCommandCode_CLU : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,FHCU,ASD,MON,AVM,KBD + +BO_ 1097 NM_FHCU: 8 FHCU + SG_ Destination_FHCU : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,ASD,MON,AVM,KBD + SG_ NMSleepFlag_FHCU : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,ASD,MON,AVM,KBD + SG_ NMCommandCode_FHCU : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,ASD,MON,AVM,KBD + +BO_ 1094 NM_ASD: 8 ASD + SG_ Destination_ASD : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,MON,AVM,KBD + SG_ NMSleepFlag_ASD : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,MON,AVM,KBD + SG_ NMCommandCode_ASD : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,MON,AVM,KBD + +BO_ 1089 NM_MON: 8 MON + SG_ Destination_MON : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,AVM,KBD + SG_ NMSleepFlag_MON : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,AVM,KBD + SG_ NMCommandCode_MON : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,AVM,KBD + +BO_ 1104 NM_AVM: 8 AVM + SG_ Destination_AVM : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,KBD + SG_ NMSleepFlag_AVM : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,KBD + SG_ NMCommandCode_AVM : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,KBD + +BO_ 1090 NM_KBD: 8 KBD + SG_ Destination_KBD : 7|8@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM + SG_ NMSleepFlag_KBD : 13|2@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM + SG_ NMCommandCode_KBD : 10|3@0+ (1,0) [0|0] "" CLOCK,HUD,H_U,DATC,CCP,KMA_TMU,CUBIS,TMU,IPM,RSE_R,RRC,CGW,RSE_L,AMP,EDT,SWRC,IBOX,CLU,FHCU,ASD,MON,AVM + diff --git a/opendbc/hyundai_canfd.dbc b/opendbc_repo/opendbc/dbc/hyundai_canfd.dbc similarity index 100% rename from opendbc/hyundai_canfd.dbc rename to opendbc_repo/opendbc/dbc/hyundai_canfd.dbc diff --git a/opendbc_repo/opendbc/dbc/hyundai_i30_2014.dbc b/opendbc_repo/opendbc/dbc/hyundai_i30_2014.dbc new file mode 100644 index 000000000000000..3524f9b21a893c7 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/hyundai_i30_2014.dbc @@ -0,0 +1,549 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 128 EMS_DCT1: 8 XXX + SG_ PV_AV_CAN : 0|8@1+ (0.3906,0) [0|99.603] "%" XXX + SG_ TQ_STND : 8|6@1+ (10,0) [0|630] "Nm" XXX + SG_ F_N_ENG : 14|1@1+ (1,0) [0|1] "" XXX + SG_ F_SUB_TQI : 15|1@1+ (1,0) [0|1] "" XXX + SG_ N : 16|16@1+ (0.25,0) [0|16383.8] "rpm" XXX + SG_ TQI_ACOR : 32|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ TQFR : 40|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ TQI : 48|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ CF_Ems_Alive : 56|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Ems_ChkSum : 60|4@1+ (1,0) [0|15] "" XXX + + +BO_ 129 EMS_DCT2: 8 XXX + SG_ CR_Ems_SoakTimeExt : 0|6@1+ (5,0) [0|315] "Min" XXX + SG_ BRAKE_ACT : 6|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Ems_EngOperStat : 8|8@1+ (1,0) [0|255] "" XXX + SG_ CR_Ems_IndAirTemp : 16|8@1+ (0.75,-48) [-48|143.25] "" XXX + SG_ CF_Ems_Alive2 : 56|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Ems_ChkSum2 : 60|4@1+ (1,0) [0|15] "" XXX + + +BO_ 160 EngFrzFrm1: 8 XXX + SG_ PID_04h : 0|8@1+ (0.392157,0) [0|100] "%" XXX + SG_ PID_05h : 8|8@1+ (1,-40) [-40|215] "" XXX + SG_ PID_0Ch : 16|16@1+ (0.25,0) [0|16383.8] "rpm" XXX + SG_ PID_0Dh : 32|8@1+ (1,0) [0|255] "km/h" XXX + SG_ PID_11h : 40|8@1+ (0.392157,0) [0|100] "%" XXX + SG_ PID_03h : 48|16@1+ (1,0) [0|65535] "" XXX + + +BO_ 161 EngFrzFrm2: 8 XXX + SG_ PID_06h : 0|8@1+ (0.78125,-100) [-100|99.22] "%" XXX + SG_ PID_07h : 8|8@1+ (0.78125,-100) [-100|99.22] "%" XXX + SG_ PID_08h : 16|8@1+ (0.78125,-100) [-100|99.22] "%" XXX + SG_ PID_09h : 24|8@1+ (0.78125,-100) [-100|99.22] "%" XXX + SG_ PID_0Bh : 32|8@1+ (1,0) [0|255] "kPa" XXX + SG_ PID_23h : 40|16@1+ (10,0) [0|655350] "kPa" XXX + + +BO_ 304 YRS1: 8 XXX + SG_ CR_Yrs_Yr : 0|16@1+ (0.005,-163.84) [-163.84|163.83] "" XXX + SG_ CF_Yrs_SnsStat1 : 16|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Yrs_YrStat : 20|4@1+ (1,0) [0|15] "" XXX + SG_ CR_Yrs_LatAc : 32|16@1+ (0.000127465,-4.17677) [-4.17677|4.17652] "g" XXX + SG_ CR_Yrs_MsgCnt1 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Yrs_LatAcStat1 : 52|4@1+ (1,0) [0|15] "" XXX + SG_ CR_Yrs_Crc1 : 56|8@1+ (1,0) [0|255] "" XXX + + +BO_ 305 YRS3: 8 XXX + SG_ CR_Yrs_YawAcc : 0|16@1+ (0.125,-4096) [-4096|4095.75] "" XXX + SG_ CF_Yrs_YawAccStat : 20|4@1+ (1,0) [0|15] "" XXX + SG_ CR_Yrs_Ax : 32|16@1+ (0.000127465,-4.17677) [-4.17677|4.17652] "g" XXX + SG_ CR_Yrs_MsgCnt3 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Yrs_AxStat : 52|4@1+ (1,0) [0|15] "" XXX + SG_ CR_Yrs_Crc3 : 56|8@1+ (1,0) [0|255] "" XXX + + +BO_ 320 YRS2: 8 XXX + SG_ CF_Yrs_McuStat : 0|8@1+ (1,0) [0|255] "" XXX + SG_ CF_Yrs_SnsStat2 : 8|8@1+ (1,0) [0|255] "" XXX + SG_ CF_Yrs_ExtSysStat : 32|8@1+ (1,0) [0|255] "" XXX + SG_ CR_Yrs_Diag : 40|8@1+ (1,0) [0|255] "" XXX + SG_ CR_Yrs_MsgCnt2 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Yrs_Type : 52|4@1+ (1,0) [0|15] "" XXX + SG_ CR_Yrs_Crc2 : 56|8@1+ (1,0) [0|255] "" XXX + + +BO_ 339 TCS1: 8 XXX + SG_ TCS_REQ : 0|1@1+ (1,0) [0|1] "" XXX + SG_ MSR_C_REQ : 1|1@1+ (1,0) [0|1] "" XXX + SG_ TCS_PAS : 2|1@1+ (1,0) [0|1] "" XXX + SG_ TCS_GSC : 3|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Esc_LimoInfo : 4|2@1+ (1,0) [0|3] "" XXX + SG_ ABS_DIAG : 6|1@1+ (1,0) [0|1] "" XXX + SG_ ABS_DEF : 7|1@1+ (1,0) [0|1] "" XXX + SG_ TCS_DEF : 8|1@1+ (1,0) [0|1] "" XXX + SG_ TCS_CTL : 9|1@1+ (1,0) [0|1] "" XXX + SG_ ABS_ACT : 10|1@1+ (1,0) [0|1] "" XXX + SG_ EBD_DEF : 11|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_PAS : 12|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_DEF : 13|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_CTL : 14|1@1+ (1,0) [0|1] "" XXX + SG_ TCS_MFRN : 15|1@1+ (1,0) [0|1] "" XXX + SG_ DBC_CTL : 16|1@1+ (1,0) [0|1] "" XXX + SG_ DBC_PAS : 17|1@1+ (1,0) [0|1] "" XXX + SG_ DBC_DEF : 18|1@1+ (1,0) [0|1] "" XXX + SG_ HAC_CTL : 19|1@1+ (1,0) [0|1] "" XXX + SG_ HAC_PAS : 20|1@1+ (1,0) [0|1] "" XXX + SG_ HAC_DEF : 21|1@1+ (1,0) [0|1] "" XXX + SG_ ESS_STAT : 22|2@1+ (1,0) [0|3] "" XXX + SG_ TQI_TCS : 24|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ TQI_MSR : 32|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ TQI_SLW_TCS : 40|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ CF_Esc_BrkCtl : 48|1@1+ (1,0) [0|1] "" XXX + SG_ ESC_OFF_STEP : 49|2@1+ (1,0) [0|3] "" XXX + SG_ _4WD_Status : 51|1@1+ (1,0) [0|1] "" XXX + SG_ AliveCounter_TCS1 : 52|4@1+ (1,0) [0|1] "" XXX + SG_ CheckSum_TCS1 : 56|8@1+ (1,0) [0|1] "" XXX + + +BO_ 356 VSM1: 8 XXX + SG_ CR_Esc_StrTqReq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" XXX + SG_ CF_Esc_Act : 12|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Esc_CtrMode : 13|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Esc_Def : 16|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Esc_AliveCnt : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Esc_Chksum : 56|8@1+ (1,0) [0|255] "" XXX + + +BO_ 357 VSM2: 8 XXX + SG_ CR_Mdps_StrTq : 0|12@1+ (0.01,-20.48) [-20.48|20.47] "Nm" XXX + SG_ CR_Mdps_OutTq : 12|12@1+ (0.1,-204.8) [-204.8|204.7] "" XXX + SG_ CF_Mdps_Def : 24|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Mdps_SErr : 25|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Mdps_AliveCnt : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Mdps_Chksum : 56|8@1+ (1,0) [0|255] "" XXX + + +BO_ 399 EMS_H2: 8 XXX + SG_ R_TqAcnApvC : 0|8@1+ (0.2,0) [0|51] "Nm" XXX + SG_ R_PAcnC : 8|8@1+ (125,0) [0|31875] "hPa" XXX + SG_ TQI_B : 16|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ SLD_VS : 24|8@1+ (1,0) [0|255] "km/h" XXX + SG_ CF_CdaStat : 32|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Ems_IsgStat : 35|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Ems_OilChg : 38|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_EtcLimpMod : 39|1@1+ (1,0) [0|1] "" XXX + SG_ R_NEngIdlTgC : 40|8@1+ (10,0) [0|2550] "rpm" XXX + SG_ CF_Ems_UpTarGr : 48|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_DownTarGr : 49|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_DesCurGr : 50|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Ems_SldAct : 54|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_SldPosAct : 55|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_HPresStat : 56|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_IsgBuz : 57|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_IdlStpFCO : 58|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_FCopen : 59|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_ActEcoAct : 60|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_EngRunNorm : 61|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_IsgStat2 : 62|2@1+ (2,0) [0|3] "" XXX + + +BO_ 497 TCS5: 8 XXX + SG_ ABS_W_LAMP : 0|1@1+ (1,0) [0|1] "" XXX + SG_ EBD_W_LAMP : 1|1@1+ (1,0) [0|1] "" XXX + SG_ TCS_OFF_LAMP : 2|1@1+ (1,0) [0|1] "" XXX + SG_ TCS_LAMP : 3|2@1+ (1,0) [0|3] "" XXX + SG_ DBC_W_LAMP : 5|1@1+ (1,0) [0|1] "" XXX + SG_ DBC_F_LAMP : 6|2@1+ (1,0) [0|3] "" XXX + SG_ ODOMETER_LEFT : 8|4@1+ (1,0) [0|15] "m" XXX + SG_ ODOMETER_RIGHT : 12|4@1+ (1,0) [0|15] "m" XXX + SG_ WHEEL_FL : 16|12@1+ (0.125,0) [0|511.875] "km/h" XXX + SG_ WHEEL_FR : 28|12@1+ (0.125,0) [0|511.875] "km/h" XXX + SG_ WHEEL_RL : 40|12@1+ (0.125,0) [0|511.875] "km/h" XXX + SG_ WHEEL_RR : 52|12@1+ (0.125,0) [0|511.875] "km/h" XXX + + +BO_ 544 ESP2: 8 XXX + SG_ LAT_ACCEL : 0|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" XXX + SG_ ESP2_AliveCounter_LSB : 11|3@1+ (1,0) [0|7] "" XXX + SG_ LAT_ACCEL_STAT : 14|1@1+ (1,0) [0|1] "" XXX + SG_ LAT_ACCEL_DIAG : 15|1@1+ (1,0) [0|1] "" XXX + SG_ LONG_ACCEL : 16|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" XXX + SG_ ESP2_AliveCounter_MSB : 27|1@1+ (1,0) [0|1] "" XXX + SG_ ESP2_Checksum_LSB : 28|2@1+ (1,0) [0|3] "" XXX + SG_ LONG_ACCEL_STAT : 30|1@1+ (1,0) [0|1] "" XXX + SG_ LONG_ACCEL_DIAG : 31|1@1+ (1,0) [0|1] "" XXX + SG_ CYL_PRES : 32|12@1+ (0.1,0) [0|409.5] "Bar" XXX + SG_ ESP12_Checksum_MSB : 44|2@1+ (1,0) [0|3] "" XXX + SG_ CYL_PRES_STAT : 46|1@1+ (1,0) [0|1] "" XXX + SG_ CYL_PRESS_DIAG : 47|1@1+ (1,0) [0|1] "" XXX + SG_ YAW_RATE : 48|13@1+ (0.01,-40.95) [-40.95|40.96] "" XXX + SG_ CYL_PRES_FLAG : 61|1@1+ (1,0) [0|1] "" XXX + SG_ YAW_RATE_STAT : 62|1@1+ (1,0) [0|1] "" XXX + SG_ YAW_RATE_DIAG : 63|1@1+ (1,0) [0|1] "" XXX + + +BO_ 608 EMS6: 8 XXX + SG_ TQI_MIN : 0|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ TQI : 8|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ TQI_TARGET : 16|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ GLOW_STAT : 24|1@1+ (1,0) [0|1] "" XXX + SG_ CRUISE_LAMP_M : 25|1@1+ (1,0) [0|1] "" XXX + SG_ CRUISE_LAMP_S : 26|1@1+ (1,0) [0|1] "" XXX + SG_ PRE_FUEL_CUT_IN : 27|1@1+ (1,0) [0|1] "" XXX + SG_ ENG_STAT : 28|3@1+ (1,0) [0|7] "" XXX + SG_ SOAK_TIME_ERROR : 31|1@1+ (1,0) [0|1] "" XXX + SG_ SOAK_TIME : 32|8@1+ (1,0) [0|255] "Min" XXX + SG_ TQI_MAX : 40|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ SPK_TIME_CUR : 48|8@1+ (0.375,-35.625) [-35.625|60] "" XXX + SG_ Checksum : 56|4@1+ (1,0) [0|15] "" XXX + SG_ AliveCounter : 60|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Ems_AclAct : 62|2@1+ (1,0) [0|3] "" XXX + + +BO_ 672 EMS5: 8 XXX + SG_ ECGPOvrd : 0|1@1+ (1,0) [0|1] "" XXX + SG_ QECACC : 1|1@1+ (1,0) [0|1] "" XXX + SG_ ECFail : 2|1@1+ (1,0) [0|1] "" XXX + SG_ SwitchOffCondExt : 3|1@1+ (1,0) [0|1] "" XXX + SG_ BLECFail : 4|1@1+ (1,0) [0|1] "" XXX + SG_ AliveCounter : 5|2@1+ (1,0) [0|3] "" XXX + SG_ Byte0Parity : 7|1@1+ (1,0) [0|1] "" XXX + SG_ FA_PV_CAN : 8|8@1+ (0.3906,0) [0|99.2] "%" XXX + SG_ IntAirTemp : 16|8@1+ (0.75,-48) [-48|143.25] "" XXX + SG_ STATE_DC_OBD : 24|7@1+ (1,0) [0|127] "" XXX + SG_ INH_DC_OBD : 31|1@1+ (1,0) [0|1] "" XXX + SG_ CTR_IG_CYC_OBD : 32|16@1+ (1,0) [0|65535] "" XXX + SG_ CTR_CDN_OBD : 48|16@1+ (1,0) [0|65535] "" XXX + + +BO_ 688 SAS1: 8 XXX + SG_ SAS_Angle : 0|16@1+ (0.1,0) [-3276.8|3276.7] "Deg" XXX + SG_ SAS_Speed : 16|8@1+ (4,0) [0|1016] "" XXX + SG_ SAS_Stat : 24|8@1+ (1,0) [0|255] "" XXX + SG_ MsgCount : 32|4@1+ (1,0) [0|15] "" XXX + SG_ CheckSum : 36|4@1+ (1,0) [0|15] "" XXX + + +BO_ 790 EMS1: 8 XXX + SG_ SWI_IGK : 0|1@1+ (1,0) [0|1] "" XXX + SG_ F_N_ENG : 1|1@1+ (1,0) [0|1] "" XXX + SG_ ACK_TCS : 2|1@1+ (1,0) [0|1] "" XXX + SG_ PUC_STAT : 3|1@1+ (1,0) [0|1] "" XXX + SG_ TQ_COR_STAT : 4|2@1+ (1,0) [0|3] "" XXX + SG_ RLY_AC : 6|1@1+ (1,0) [0|1] "" XXX + SG_ F_SUB_TQI : 7|1@1+ (1,0) [0|1] "" XXX + SG_ TQI_ACOR : 8|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ N : 16|16@1+ (0.25,0) [0|16383.8] "rpm" XXX + SG_ TQI : 32|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ TQFR : 40|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ VS : 48|8@1+ (1,0) [0|254] "km/h" XXX + SG_ RATIO_TQI_BAS_MAX_STND : 56|8@1+ (0.0078,0) [0|2] "" XXX + + +BO_ 809 EMS2: 8 XXX + SG_ TQ_STND : 0|6@1+ (10,0) [0|630] "Nm" XXX + SG_ CAN_VERS : 0|6@1+ (1,0) [0|7.7] "" XXX + SG_ CONF_TCU : 0|6@1+ (1,0) [0|63] "" XXX + SG_ OBD_FRF_ACK : 0|6@1+ (1,0) [0|63] "" XXX + SG_ MUL_CODE : 6|2@1+ (1,0) [0|3] "" XXX + SG_ TEMP_ENG : 8|8@1+ (0.75,-48) [-48|143.25] "" XXX + SG_ MAF_FAC_ALTI_MMV : 16|8@1+ (0.00781,0) [0|1.99155] "" XXX + SG_ VB_OFF_ACT : 24|1@1+ (1,0) [0|1] "" XXX + SG_ ACK_ES : 25|1@1+ (1,0) [0|1] "" XXX + SG_ CONF_MIL_FMY : 26|3@1+ (1,0) [0|7] "" XXX + SG_ OD_OFF_REQ : 29|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_ACT : 30|1@1+ (1,0) [0|1] "" XXX + SG_ CLU_ACK : 31|1@1+ (1,0) [0|1] "" XXX + SG_ BRAKE_ACT : 32|2@1+ (1,0) [0|3] "" XXX + SG_ ENG_CHR : 34|4@1+ (1,0) [0|15] "" XXX + SG_ GP_CTL : 38|2@1+ (1,0) [0|3] "" XXX + SG_ TPS : 40|8@1+ (0.469484,-15.0235) [-15.0235|104.695] "%" XXX + SG_ PV_AV_CAN : 48|8@1+ (0.3906,0) [0|99.603] "%" XXX + SG_ ENG_VOL : 56|8@1+ (0.1,0) [0|25.5] "liter" XXX + + +BO_ 848 FATC: 8 XXX + SG_ CR_Fatc_TqAcnOut : 0|8@1+ (0.2,0) [0|50.8] "Nm" XXX + SG_ CF_Fatc_AcnRqSwi : 8|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_AcnCltEnRq : 9|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_EcvFlt : 10|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_BlwrOn : 11|1@1+ (1,0) [0|1] "" XXX + SG_ CF_FATC_Iden : 12|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Fatc_BlwrMax : 14|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_EngStartReq : 15|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_IsgStopReq : 16|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_CtrInf : 17|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Fatc_MsgCnt : 20|4@1+ (1,0) [0|15] "" XXX + SG_ CR_Fatc_OutTemp : 24|8@1+ (0.5,-40) [-40|60] "" XXX + SG_ CR_Fatc_OutTempSns : 32|8@1+ (0.5,-40) [-40|60] "" XXX + SG_ CF_Fatc_Compload : 40|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Fatc_ActiveEco : 43|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_AutoActivation : 44|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_DefSw : 45|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_PtcRlyStat : 46|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Fatc_ChkSum : 56|8@1+ (1,0) [0|255] "" XXX + + +BO_ 880 TCU3: 8 XXX + SG_ N_TGT_LUP : 0|8@1+ (10,500) [500|3040] "rpm" XXX + SG_ SLOPE_TCU : 8|6@1+ (0.5,-16) [-16|15.5] "%" XXX + SG_ CF_Tcu_InhCda : 14|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_IsgInhib : 15|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_BkeOnReq : 16|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Tcu_NCStat : 18|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Tcu_TarGr : 20|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Tcu_ShfPatt : 24|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Tcu_InhVis : 28|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_PRelReq : 29|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_ITPhase : 30|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_ActEcoRdy : 31|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_TqGrdLim : 32|8@1+ (10,0) [0|2540] "Nm/s" XXX + SG_ CR_Tcu_IsgTgtRPM : 40|8@1+ (20,0) [0|3500] "rpm" XXX + SG_ TQI_TCU_INC : 48|8@1+ (0.390625,0) [0|99.6094] "%" XXX + SG_ CF_Tcu_SbwPInfo : 56|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_SptRdy : 57|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_Alive3 : 58|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Tcu_ChkSum3 : 60|4@1+ (1,0) [0|15] "" XXX + + +BO_ 898 EMS9: 8 XXX + SG_ CF_Ems_BrkReq : 0|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_DnShftReq : 1|4@1+ (1,0) [0|14] "" XXX + SG_ CF_Ems_RepModChk : 5|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Ems_AAFOpenReq : 7|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_DecelReq : 8|12@1+ (0.001,-4.094) [-4.094|0] "m/s^2" XXX + SG_ CR_Ems_BstPre : 20|12@1+ (1.322,0) [0|4094] "hPa" XXX + SG_ CR_Ems_EngOilTemp : 32|8@1+ (0.75,-40) [0|254] "" XXX + SG_ CF_Ems_PumpTPres : 40|8@1+ (3.13725,0) [0|800] "kPa" XXX + SG_ CF_Ems_ModeledAmbTemp : 48|8@1+ (0.5,-41) [-40|60] "" XXX + SG_ CF_Ems_OPSFail : 56|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_ECTTRQLIM : 57|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_AliveCounterEMS9 : 58|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Ems_ChecksumEMS9 : 60|4@1+ (1,0) [0|15] "" XXX + + +BO_ 1075 EPB1: 8 XXX + SG_ EPB_I_LAMP : 0|4@1+ (1,0) [0|15] "" XXX + SG_ EPB_F_LAMP : 4|2@1+ (1,0) [0|3] "" XXX + SG_ EPB_ALARM : 6|2@1+ (1,0) [0|3] "" XXX + SG_ EPB_CLU : 8|8@1+ (1,0) [0|255] "" XXX + SG_ EPB_SWITCH : 16|2@1+ (1,0) [0|3] "" XXX + SG_ EPB_RBL : 18|1@1+ (1,0) [0|1] "" XXX + SG_ EPB_STATUS : 19|3@1+ (1,0) [0|7] "" XXX + SG_ EPB_FRC_ERR : 22|2@1+ (1,0) [0|3] "" XXX + SG_ EPB_DBF_STAT : 24|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_ACK : 25|1@1+ (1,0) [0|1] "" XXX + SG_ EPB_DBF_REQ : 26|1@1+ (1,0) [0|1] "" XXX + SG_ EPB_FAIL : 29|3@1+ (1,0) [0|7] "" XXX + SG_ EPB_FORCE : 32|12@1+ (1,-1000) [-1000|3000] "" XXX + SG_ EPB_DBF_DECEL : 48|8@1+ (0.01,0) [0|2.54] "g" XXX + + +BO_ 1087 TCU1: 8 XXX + SG_ ETL_TCU : 0|8@1+ (2,0) [0|508] "Nm" XXX + SG_ CUR_GR : 8|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Tcu_Alive : 12|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Tcu_ChkSum : 14|2@1+ (1,0) [0|3] "" XXX + SG_ VS_TCU : 16|8@1+ (1,0) [0|254] "km/h" XXX + SG_ FAN_CTRL_TCU : 24|2@1+ (1,0) [0|3] "" XXX + SG_ BRAKE_ACT_TCU : 26|2@1+ (1,0) [0|3] "" XXX + SG_ FUEL_CUT_TCU : 28|1@1+ (1,0) [0|1] "" XXX + SG_ INH_FUEL_CUT : 29|1@1+ (1,0) [0|1] "" XXX + SG_ IDLE_UP_TCU : 30|1@1+ (1,0) [0|1] "" XXX + SG_ N_INC_TCU : 31|1@1+ (1,0) [0|1] "" XXX + SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15|15] "" XXX + SG_ N_TC_RAW : 40|16@1+ (0.25,0) [0|16383.5] "rpm" XXX + SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0) [0|0.992188] "km/h" XXX + + +BO_ 1088 TCU2: 8 XXX + SG_ ETL_TCU : 0|8@1+ (2,0) [0|508] "Nm" XXX + SG_ CUR_GR : 8|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Tcu_Alive : 12|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Tcu_ChkSum : 14|2@1+ (1,0) [0|3] "" XXX + SG_ VS_TCU : 16|8@1+ (1,0) [0|254] "km/h" XXX + SG_ FAN_CTRL_TCU : 24|2@1+ (1,0) [0|3] "" XXX + SG_ BRAKE_ACT_TCU : 26|2@1+ (1,0) [0|3] "" XXX + SG_ FUEL_CUT_TCU : 28|1@1+ (1,0) [0|1] "" XXX + SG_ INH_FUEL_CUT : 29|1@1+ (1,0) [0|1] "" XXX + SG_ IDLE_UP_TCU : 30|1@1+ (1,0) [0|1] "" XXX + SG_ N_INC_TCU : 31|1@1+ (1,0) [0|1] "" XXX + SG_ SPK_RTD_TCU : 32|8@1+ (0.375,-23.625) [-15|15] "" XXX + SG_ N_TC_RAW : 40|16@1+ (0.25,0) [0|16383.5] "rpm" XXX + SG_ VS_TCU_DECIMAL : 56|8@1+ (0.0078125,0) [0|0.992188] "km/h" XXX + + +BO_ 1200 WHL_SPD: 8 XXX + SG_ WHL_SPD_FL : 0|14@1+ (0.03125,0) [0|511.969] "km/h" XXX + SG_ WHL_SPD_FR : 16|14@1+ (0.03125,0) [0|511.969] "km/h" XXX + SG_ WHL_SPD_RL : 32|14@1+ (0.03125,0) [0|511.969] "km/h" XXX + SG_ WHL_SPD_RR : 48|14@1+ (0.03125,0) [0|511.969] "km/h" XXX + + +BO_ 1201 WHL_PUL: 8 XXX + SG_ WHL_PUL_FL : 0|8@1+ (0.5,0) [0|127.5] "pulse count" XXX + SG_ WHL_PUL_FR : 8|8@1+ (0.5,0) [0|127.5] "pulse count" XXX + SG_ WHL_PUL_RL : 16|8@1+ (0.5,0) [0|127.5] "pulse count" XXX + SG_ WHL_PUL_RR : 24|8@1+ (0.5,0) [0|127.5] "pulse count" XXX + SG_ WHL_DIR_FL : 32|2@1+ (1,0) [0|3] "" XXX + SG_ WHL_DIR_FR : 34|2@1+ (1,0) [0|3] "" XXX + SG_ WHL_DIR_RL : 36|2@1+ (1,0) [0|3] "" XXX + SG_ WHL_DIR_RR : 38|2@1+ (1,0) [0|3] "" XXX + SG_ WHL_PUL_Chksum : 56|8@1+ (1,0) [0|255] "" XXX + + +BO_ 1264 CLU1: 8 XXX + SG_ CF_Clu_CruiseSwState : 0|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Blr_MaxStat : 3|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_SldMainSW : 4|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_ParityBit1 : 5|1@1+ (1,0) [0|1] "pulse count" XXX + SG_ CF_Clu_SPEED_UNIT : 6|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_ParkBrakeSw : 7|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_Vanz : 8|9@1+ (0.5,0) [0|255.5] "km/h or MPH" XXX + SG_ CF_Clu_AliveCounter : 17|7@1+ (1,0) [0|127] "" XXX + SG_ CF_Clu_CruiseSwMain : 24|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_VanzDecimal : 25|2@1+ (1,0) [0|0.375] "" XXX + SG_ VEHICLE_INFO : 27|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Clu_StrRlyState : 30|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_SMKOption : 31|1@1+ (1,0) [0|1] "" XXX + SG_ R_TqAcnOutC : 32|8@1+ (1,0) [0|51] "Nm" XXX + SG_ CF_Clu_Odometer : 40|24@1+ (0.1,0) [0|1.67772e+006] "km" XXX + + +BO_ 1265 CLU3: 8 XXX + SG_ CF_Clu_AcnRqSwi : 0|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_AcnCltEnRq : 1|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_RefDetMod : 2|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_DefoggerRly : 5|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_LowfuelWarn : 16|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_SportsModeSwi : 18|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_ALightStat : 20|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_FrtFog : 21|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_DetentOut : 22|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HeadLampTail : 23|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_TrailerMode : 24|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_DTE : 25|10@1+ (1,0) [0|1023] "" XXX + SG_ CF_Clu_TripUnit : 35|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_IsaMainSW : 37|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_FlexSteerSW : 40|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_AvsmCur : 41|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HudSpeedset : 42|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HudTbtSet : 43|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HudSccSet : 44|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HudLdwsSet : 45|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HudDisSet : 46|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HudFontSizeSet : 47|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_HudFontColorSet : 49|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_HudBrightSet : 51|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_HudHeightSet : 53|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_CluInfo : 55|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_RheostatLevel : 56|5@1+ (1,0) [0|31] "" XXX + SG_ CF_Clu_DrivinglampStat : 61|3@1+ (1,0) [0|7] "" XXX + + +BO_ 1349 EMS4: 8 XXX + SG_ IMMO_LAMP_STAT : 0|1@1+ (1,0) [0|1] "" XXX + SG_ L_MIL : 1|1@1+ (1,0) [0|1] "" XXX + SG_ IM_STAT : 2|1@1+ (1,0) [0|1] "" XXX + SG_ AMP_CAN : 3|5@1+ (10.7316,458.98) [458.98|791.66] "mmHg" XXX + SG_ FCO : 8|16@1+ (0.128,0) [0|8388.48] "ul" XXX + SG_ VB : 24|8@1+ (0.101563,0) [0|25.8984] "V" XXX + SG_ TEMP_FUEL : 48|8@1+ (0.75,-48) [-48|143.25] "" XXX + SG_ Split_Stat : 56|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Ems_IsaAct : 57|1@1+ (1,0) [0|1] "" XXX + + +BO_ 1435 TCU4: 8 XXX + SG_ CF_TCU_WarnMsg : 0|3@1+ (1,0) [0|7] "" XXX + SG_ CF_TCU_WarnImg : 3|1@1+ (1,0) [0|1] "" XXX + SG_ CF_TCU_WarnSnd : 4|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_EolStat : 5|1@1+ (1,0) [0|1] "" XXX + SG_ CR_Tcu_GearSelDisp2 : 8|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Tcu_StRelStat : 12|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_DriWarn1 : 13|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Tcu_DriWarn2 : 16|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Tcu_DrivingModeReq : 18|4@1+ (1,0) [0|0] "" XXX + SG_ CF_Tcu_DrivingModeDisp : 22|4@1+ (1,0) [0|0] "" XXX + SG_ CF_Tcu_SiCluster : 26|5@1+ (1,0) [0|0] "" XXX + SG_ CF_Tcu_DSmode_Inf : 31|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Tcu_Alive4 : 58|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Tcu_ChkSum4 : 60|4@1+ (1,0) [0|15] "" XXX + + +BO_ 1508 MDPS1: 8 XXX + SG_ CF_Mdps_WLmp : 1|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Mdps_ALTRequest : 5|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Mdps_Flex : 8|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Mdps_FlexDisp : 11|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Mdps_CurrMode : 12|2@1+ (1,0) [0|3] "" XXX + + +BO_ 1680 CLU2: 8 XXX + SG_ CF_Clu_IGNSw : 0|3@1+ (1,0) [0|7] "" XXX + SG_ RKE_CMD : 3|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Clu_DrvDrSw : 6|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_DrvKeyLockSw : 8|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_DrvKeyUnlockSw : 9|1@1+ (1,0) [0|1] "" XXX + SG_ PIC_Lock : 10|3@1+ (1,0) [0|7] "" XXX + SG_ PIC_Unlock : 13|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Clu_DrvSeatBeltSw : 16|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_TrunkTgSw : 18|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_AstSeatBeltSw : 20|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_HoodSw : 22|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_TurnSigLh : 24|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_TurnSigRh : 25|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_LdwsLkasSW : 26|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_WiperIntT : 27|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Clu_WiperIntSW : 30|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_WiperLow : 31|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_WiperHigh : 32|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_WiperAuto : 33|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_RainSnsStat : 34|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Clu_HeadLampLow : 37|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HeadLampHigh : 38|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_AltLStatus : 39|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_EcoDriveInf : 40|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Clu_SwiGearR : 43|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_SWL_Stat : 45|3@1+ (1,0) [0|7] "" XXX + SG_ CF_Clu_ActiveEcoSW : 48|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_HazardSW : 49|1@1+ (1,0) [0|1] "" XXX + SG_ CF_Clu_AliveCnt2 : 50|4@1+ (1,0) [0|15] "" XXX + SG_ CF_Clu_AstDrSw : 54|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_LkasDispMode : 56|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_AutoLightLevel : 58|2@1+ (1,0) [0|3] "" XXX + SG_ CF_Clu_SunRoofOpenState : 60|1@1+ (1,0) [0|1] "" XXX + + diff --git a/opendbc/hyundai_kia_generic.dbc b/opendbc_repo/opendbc/dbc/hyundai_kia_generic.dbc similarity index 99% rename from opendbc/hyundai_kia_generic.dbc rename to opendbc_repo/opendbc/dbc/hyundai_kia_generic.dbc index fc4d14f4fe9b3e1..c828d33c2f0ca9b 100644 --- a/opendbc/hyundai_kia_generic.dbc +++ b/opendbc_repo/opendbc/dbc/hyundai_kia_generic.dbc @@ -442,6 +442,9 @@ BO_ 129 EMS_DCT12: 8 EMS SG_ CF_Ems_Alive2 : 56|4@1+ (1.0,0.0) [0.0|15.0] "" TCU SG_ CF_Ems_ChkSum2 : 60|4@1+ (1.0,0.0) [0.0|15.0] "" TCU +BO_ 145 FCEV_ACCELERATOR: 8 XXX + SG_ ACCELERATOR_PEDAL : 48|8@1+ (1,0) [0|255] "" XXX + BO_ 897 MDPS11: 8 MDPS SG_ CF_Mdps_WLmp : 0|2@1+ (1.0,0.0) [0.0|3.0] "" CLU,CUBIS,EMS,IBOX,SPAS SG_ CF_Mdps_Flex : 2|3@1+ (1.0,0.0) [0.0|3.0] "" CLU,LDWS_LKAS @@ -1429,7 +1432,7 @@ BO_ 1280 ACU14: 1 ACU SG_ CF_SBR_Ind : 4|2@1+ (1.0,0.0) [0.0|3.0] "" BCM,CLU BO_ 512 EMS20: 6 EMS - SG_ FCO : 0|16@1+ (0.128,0.0) [0.0|8388.48] "ul" CLU,CUBIS,FPCM,IBOX + SG_ HYDROGEN_GEAR_SHIFTER : 11|3@1+ (1,0) [0|7] "" XXX SG_ CF_Ems_PumpTPres : 16|8@1+ (3.137254902,0.0) [0.0|800.0] "kPa" FPCM,IBOX SG_ Split_Stat : 32|1@1+ (1.0,0.0) [0.0|1.0] "" FPCM @@ -1648,11 +1651,14 @@ BO_ 1348 Navi_HU: 8 XXX SG_ SpeedLim_Nav_Cam : 30|1@0+ (1,0) [0|1] "" XXX CM_ "BO_ E_EMS11: All (plug-in) hybrids use this gas signal: CR_Vcu_AccPedDep_Pos, and all EVs use the Accel_Pedal_Pos signal. See hyundai/values.py for a specific car list"; +CM_ 145 "Contains signal with accelerator pedal press. Used by fuel cell hydrogen-powered (FCEV) cars such as the 2021 Hyundai Nexo."; +CM_ 512 "Contains signal with gear shifter. Used by fuel cell hydrogen-powered (FCEV) cars such as the 2021 Hyundai Nexo."; CM_ SG_ 871 CF_Lvr_IsgState "Idle Stop and Go"; CM_ SG_ 1056 SCCInfoDisplay "Goes to 1 for a second while transitioning from Cruise Control to No Message"; CM_ SG_ 1348 SpeedLim_Nav_Clu "Speed limit displayed on Nav, Cluster and HUD"; VAL_ 274 CUR_GR 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 7 "D" 8 "D" 14 "R" 0 "P"; +VAL_ 512 HYDROGEN_GEAR_SHIFTER 5 "D" 8 "S" 6 "N" 7 "R" 0 "P"; VAL_ 871 CF_Lvr_IsgState 0 "enabled" 1 "activated" 2 "unknown" 3 "disabled"; VAL_ 871 CF_Lvr_Gear 12 "T" 5 "D" 8 "S" 6 "N" 7 "R" 0 "P"; VAL_ 882 Elect_Gear_Shifter 5 "D" 8 "S" 6 "N" 7 "R" 0 "P"; diff --git a/opendbc_repo/opendbc/dbc/hyundai_kia_mando_corner_radar_generated.dbc b/opendbc_repo/opendbc/dbc/hyundai_kia_mando_corner_radar_generated.dbc new file mode 100644 index 000000000000000..80627f9aebae7e5 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/hyundai_kia_mando_corner_radar_generated.dbc @@ -0,0 +1,374 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + +CM_ "hyundai_kia_mando_corner_radar.dbc starts here"; + +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + +BO_ 256 RADAR_POINTS_METADATA_0x100: 64 RADAR + SG_ SIGNAL_1 : 0|32@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_2 : 32|32@1+ (1,0) [0|65535] "" XXX + SG_ SIGNAL_3 : 64|4@1+ (1,0) [0|15] "" XXX + SG_ SIGNAL_4 : 68|4@1+ (1,0) [0|15] "" XXX + SG_ RADAR_POINT_COUNT : 72|8@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_6 : 80|7@1+ (0.015625,0) [0|3] "" XXX + SG_ SIGNAL_7 : 87|1@1+ (1,0) [0|1] "" XXX + SG_ SIGNAL_8 : 88|3@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_9 : 91|5@1+ (0.0625,0) [0|31] "" XXX + SG_ SIGNAL_10 : 96|8@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_11 : 104|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_12 : 111|2@1+ (1,0) [0|65535] "" XXX + SG_ SIGNAL_13 : 113|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_14 : 120|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_15 : 127|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_16 : 130|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_17 : 133|2@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_18 : 134|1@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_19 : 135|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_20 : 138|8@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_21 : 146|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_22 : 148|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_23 : 149|4@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_24 : 153|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_25 : 154|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_26 : 157|2@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_27 : 158|7@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_28 : 165|7@1+ (0.015625,0) [0|31] "" XXX + SG_ SIGNAL_29 : 172|7@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_30 : 179|7@1+ (0.015625,0) [0|1] "" XXX + SG_ SIGNAL_31 : 186|4@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_32 : 190|14@1+ (0.015625,0) [0|15] "" XXX + SG_ SIGNAL_33 : 204|11@1+ (0.03125,0) [0|8191] "" XXX + SG_ SIGNAL_34 : 215|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_35 : 217|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_36 : 224|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_37 : 230|6@1+ (0.2,0) [0|31] "" XXX + SG_ SIGNAL_38 : 236|6@1+ (0.2,0) [0|7] "" XXX + SG_ SIGNAL_39 : 242|8@1+ (1,-90) [0|255] "" XXX + SG_ SIGNAL_40 : 250|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_41 : 256|8@1+ (0.25,0) [0|255] "" XXX + SG_ SIGNAL_42 : 264|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_43 : 267|12@1+ (0.01,0) [0|31] "" XXX + SG_ SIGNAL_44 : 279|32@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_45 : 311|1@1+ (1,0) [0|1] "" XXX + SG_ SIGNAL_46 : 312|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_47 : 314|32@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_48 : 346|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_49 : 352|7@1+ (0.25,0) [0|127] "" XXX + SG_ SIGNAL_50 : 359|6@1+ (0.03125,0) [0|31] "" XXX + SG_ SIGNAL_51 : 365|10@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_52 : 375|10@1+ (0.125,0) [0|63] "" XXX + SG_ SIGNAL_53 : 385|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_54 : 392|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_55 : 399|8@1+ (0.00390625,0) [0|31] "" XXX + SG_ SIGNAL_56 : 407|10@1+ (0.125,0) [0|63] "" XXX + SG_ SIGNAL_57 : 417|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_58 : 418|1@1+ (1,0) [0|3] "" XXX + +BO_ 512 RADAR_POINTS_METADATA_0x200: 64 RADAR + SG_ SIGNAL_1 : 0|32@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_2 : 32|32@1+ (1,0) [0|65535] "" XXX + SG_ SIGNAL_3 : 64|4@1+ (1,0) [0|15] "" XXX + SG_ SIGNAL_4 : 68|4@1+ (1,0) [0|15] "" XXX + SG_ RADAR_POINT_COUNT : 72|8@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_6 : 80|7@1+ (0.015625,0) [0|3] "" XXX + SG_ SIGNAL_7 : 87|1@1+ (1,0) [0|1] "" XXX + SG_ SIGNAL_8 : 88|3@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_9 : 91|5@1+ (0.0625,0) [0|31] "" XXX + SG_ SIGNAL_10 : 96|8@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_11 : 104|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_12 : 111|2@1+ (1,0) [0|65535] "" XXX + SG_ SIGNAL_13 : 113|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_14 : 120|7@1+ (0.015625,0) [0|127] "" XXX + SG_ SIGNAL_15 : 127|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_16 : 130|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_17 : 133|2@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_18 : 134|1@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_19 : 135|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_20 : 138|8@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_21 : 146|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_22 : 148|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_23 : 149|4@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_24 : 153|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_25 : 154|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_26 : 157|2@0+ (1,0) [0|3] "" XXX + SG_ SIGNAL_27 : 158|7@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_28 : 165|7@1+ (0.015625,0) [0|31] "" XXX + SG_ SIGNAL_29 : 172|7@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_30 : 179|7@1+ (0.015625,0) [0|1] "" XXX + SG_ SIGNAL_31 : 186|4@1+ (1,0) [0|7] "" XXX + SG_ SIGNAL_32 : 190|14@1+ (0.015625,0) [0|15] "" XXX + SG_ SIGNAL_33 : 204|11@1+ (0.03125,0) [0|8191] "" XXX + SG_ SIGNAL_34 : 215|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_35 : 217|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_36 : 224|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_37 : 230|6@1+ (0.2,0) [0|31] "" XXX + SG_ SIGNAL_38 : 236|6@1+ (0.2,0) [0|7] "" XXX + SG_ SIGNAL_39 : 242|8@1+ (1,-90) [0|255] "" XXX + SG_ SIGNAL_40 : 250|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_41 : 256|8@1+ (0.25,0) [0|255] "" XXX + SG_ SIGNAL_42 : 264|3@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_43 : 267|12@1+ (0.01,0) [0|31] "" XXX + SG_ SIGNAL_44 : 279|32@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_45 : 311|1@1+ (1,0) [0|1] "" XXX + SG_ SIGNAL_46 : 312|2@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_47 : 314|32@1+ (1,0) [0|255] "" XXX + SG_ SIGNAL_48 : 346|6@1+ (1,0) [0|63] "" XXX + SG_ SIGNAL_49 : 352|7@1+ (0.25,0) [0|127] "" XXX + SG_ SIGNAL_50 : 359|6@1+ (0.03125,0) [0|31] "" XXX + SG_ SIGNAL_51 : 365|10@1+ (0.125,0) [0|3] "" XXX + SG_ SIGNAL_52 : 375|10@1+ (0.125,0) [0|63] "" XXX + SG_ SIGNAL_53 : 385|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_54 : 392|7@1+ (1,0) [0|127] "" XXX + SG_ SIGNAL_55 : 399|8@1+ (0.00390625,0) [0|31] "" XXX + SG_ SIGNAL_56 : 407|10@1+ (0.125,0) [0|63] "" XXX + SG_ SIGNAL_57 : 417|1@1+ (1,0) [0|3] "" XXX + SG_ SIGNAL_58 : 418|1@1+ (1,0) [0|3] "" XXX + +BO_ 257 RADAR_POINTS_0x101: 64 RADAR + SG_ MESSAGE_ID : 0|5@1+ (1,0) [0|31] "" XXX + SG_ LAYOUT_ID : 5|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_DISTANCE : 7|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_1_SIGNAL_2 : 21|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_3 : 23|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_1_REL_VELOCITY : 31|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_1_SIGNAL_5 : 44|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_6 : 46|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_AZIMUTH : 48|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_1_SIGNAL_8 : 60|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_9 : 62|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_1_SIGNAL_10 : 63|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_1_SIGNAL_11 : 70|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_1_SIGNAL_12 : 71|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_1_SIGNAL_13 : 77|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_14 : 79|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_1_SIGNAL_15 : 87|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_1_SIGNAL_16 : 88|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_17 : 90|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_1_SIGNAL_18 : 93|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_1_SIGNAL_19 : 99|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_1_SIGNAL_20 : 107|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_2_DISTANCE : 108|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_2_SIGNAL_2 : 122|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_3 : 124|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_2_REL_VELOCITY : 132|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_2_SIGNAL_5 : 145|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_6 : 147|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_AZIMUTH : 149|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_2_SIGNAL_8 : 161|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_9 : 163|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_2_SIGNAL_10 : 164|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_2_SIGNAL_11 : 171|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_2_SIGNAL_12 : 172|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_2_SIGNAL_13 : 178|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_14 : 180|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_2_SIGNAL_15 : 188|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_2_SIGNAL_16 : 189|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_17 : 191|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_2_SIGNAL_18 : 194|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_2_SIGNAL_19 : 200|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_2_SIGNAL_20 : 208|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_3_DISTANCE : 209|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_3_SIGNAL_2 : 223|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_3 : 225|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_3_REL_VELOCITY : 233|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_3_SIGNAL_5 : 246|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_6 : 248|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_AZIMUTH : 250|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_3_SIGNAL_8 : 262|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_9 : 264|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_3_SIGNAL_10 : 265|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_3_SIGNAL_11 : 272|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_3_SIGNAL_12 : 273|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_3_SIGNAL_13 : 279|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_14 : 281|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_3_SIGNAL_15 : 289|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_3_SIGNAL_16 : 290|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_17 : 292|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_3_SIGNAL_18 : 295|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_3_SIGNAL_19 : 301|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_3_SIGNAL_20 : 309|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_4_DISTANCE : 310|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_4_SIGNAL_2 : 324|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_3 : 326|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_4_REL_VELOCITY : 334|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_4_SIGNAL_5 : 347|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_6 : 349|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_AZIMUTH : 351|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_4_SIGNAL_8 : 363|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_9 : 365|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_4_SIGNAL_10 : 366|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_4_SIGNAL_11 : 373|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_4_SIGNAL_12 : 374|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_4_SIGNAL_13 : 380|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_14 : 382|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_4_SIGNAL_15 : 390|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_4_SIGNAL_16 : 391|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_17 : 393|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_4_SIGNAL_18 : 396|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_4_SIGNAL_19 : 402|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_4_SIGNAL_20 : 410|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_5_DISTANCE : 411|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_5_SIGNAL_2 : 425|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_3 : 427|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_5_REL_VELOCITY : 435|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_5_SIGNAL_5 : 448|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_6 : 450|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_AZIMUTH : 452|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_5_SIGNAL_8 : 464|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_9 : 466|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_5_SIGNAL_10 : 467|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_5_SIGNAL_11 : 474|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_5_SIGNAL_12 : 475|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_5_SIGNAL_13 : 481|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_14 : 483|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_5_SIGNAL_15 : 491|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_5_SIGNAL_16 : 492|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_17 : 494|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_5_SIGNAL_18 : 497|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_5_SIGNAL_19 : 503|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_5_SIGNAL_20 : 511|1@1+ (1,0) [0|1] "" XXX + +BO_ 513 RADAR_POINTS_0x201: 64 RADAR + SG_ MESSAGE_ID : 0|5@1+ (1,0) [0|31] "" XXX + SG_ LAYOUT_ID : 5|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_DISTANCE : 7|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_1_SIGNAL_2 : 21|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_3 : 23|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_1_REL_VELOCITY : 31|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_1_SIGNAL_5 : 44|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_6 : 46|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_AZIMUTH : 48|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_1_SIGNAL_8 : 60|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_9 : 62|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_1_SIGNAL_10 : 63|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_1_SIGNAL_11 : 70|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_1_SIGNAL_12 : 71|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_1_SIGNAL_13 : 77|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_14 : 79|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_1_SIGNAL_15 : 87|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_1_SIGNAL_16 : 88|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_1_SIGNAL_17 : 90|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_1_SIGNAL_18 : 93|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_1_SIGNAL_19 : 99|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_1_SIGNAL_20 : 107|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_2_DISTANCE : 108|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_2_SIGNAL_2 : 122|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_3 : 124|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_2_REL_VELOCITY : 132|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_2_SIGNAL_5 : 145|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_6 : 147|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_AZIMUTH : 149|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_2_SIGNAL_8 : 161|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_9 : 163|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_2_SIGNAL_10 : 164|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_2_SIGNAL_11 : 171|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_2_SIGNAL_12 : 172|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_2_SIGNAL_13 : 178|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_14 : 180|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_2_SIGNAL_15 : 188|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_2_SIGNAL_16 : 189|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_2_SIGNAL_17 : 191|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_2_SIGNAL_18 : 194|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_2_SIGNAL_19 : 200|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_2_SIGNAL_20 : 208|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_3_DISTANCE : 209|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_3_SIGNAL_2 : 223|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_3 : 225|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_3_REL_VELOCITY : 233|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_3_SIGNAL_5 : 246|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_6 : 248|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_AZIMUTH : 250|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_3_SIGNAL_8 : 262|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_9 : 264|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_3_SIGNAL_10 : 265|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_3_SIGNAL_11 : 272|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_3_SIGNAL_12 : 273|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_3_SIGNAL_13 : 279|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_14 : 281|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_3_SIGNAL_15 : 289|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_3_SIGNAL_16 : 290|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_3_SIGNAL_17 : 292|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_3_SIGNAL_18 : 295|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_3_SIGNAL_19 : 301|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_3_SIGNAL_20 : 309|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_4_DISTANCE : 310|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_4_SIGNAL_2 : 324|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_3 : 326|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_4_REL_VELOCITY : 334|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_4_SIGNAL_5 : 347|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_6 : 349|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_AZIMUTH : 351|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_4_SIGNAL_8 : 363|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_9 : 365|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_4_SIGNAL_10 : 366|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_4_SIGNAL_11 : 373|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_4_SIGNAL_12 : 374|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_4_SIGNAL_13 : 380|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_14 : 382|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_4_SIGNAL_15 : 390|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_4_SIGNAL_16 : 391|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_4_SIGNAL_17 : 393|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_4_SIGNAL_18 : 396|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_4_SIGNAL_19 : 402|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_4_SIGNAL_20 : 410|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_5_DISTANCE : 411|14@1+ (0.015625,0) [0|255.984375] "" XXX + SG_ POINT_5_SIGNAL_2 : 425|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_3 : 427|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_5_REL_VELOCITY : 435|13@1+ (0.03125,-66) [-66|189.96875] "" XXX + SG_ POINT_5_SIGNAL_5 : 448|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_6 : 450|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_AZIMUTH : 452|12@1+ (0.001953125,-3.998046875) [-3.998046875|4.0] "" XXX + SG_ POINT_5_SIGNAL_8 : 464|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_9 : 466|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_5_SIGNAL_10 : 467|7@1+ (1,0) [0|127] "" XXX + SG_ POINT_5_SIGNAL_11 : 474|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_5_SIGNAL_12 : 475|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_5_SIGNAL_13 : 481|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_14 : 483|8@1+ (0.001953125,-0.248046875) [-0.248046875|0.25] "" XXX + SG_ POINT_5_SIGNAL_15 : 491|1@1+ (1,0) [0|1] "" XXX + SG_ POINT_5_SIGNAL_16 : 492|2@1+ (1,0) [0|3] "" XXX + SG_ POINT_5_SIGNAL_17 : 494|3@1+ (1,0) [0|7] "" XXX + SG_ POINT_5_SIGNAL_18 : 497|6@1+ (1,0) [0|63] "" XXX + SG_ POINT_5_SIGNAL_19 : 503|8@1+ (1,0) [0|255] "" XXX + SG_ POINT_5_SIGNAL_20 : 511|1@1+ (1,0) [0|1] "" XXX + +BO_ 260 RADAR_POINTS_CHECKSUM_0x104: 3 RADAR + SG_ CRC16 : 0|16@1+ (1,0) [0|65535] "" XXX + +BO_ 516 RADAR_POINTS_CHECKSUM_0x204: 3 RADAR + SG_ CRC16 : 0|16@1+ (1,0) [0|65535] "" XXX diff --git a/opendbc/hyundai_kia_mando_front_radar_generated.dbc b/opendbc_repo/opendbc/dbc/hyundai_kia_mando_front_radar_generated.dbc similarity index 100% rename from opendbc/hyundai_kia_mando_front_radar_generated.dbc rename to opendbc_repo/opendbc/dbc/hyundai_kia_mando_front_radar_generated.dbc diff --git a/opendbc_repo/opendbc/dbc/hyundai_santafe_2007.dbc b/opendbc_repo/opendbc/dbc/hyundai_santafe_2007.dbc new file mode 100644 index 000000000000000..c0f4f7e180ae25b --- /dev/null +++ b/opendbc_repo/opendbc/dbc/hyundai_santafe_2007.dbc @@ -0,0 +1,118 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: AWD ECU TCU ESP SAS ABS + + +BO_ 339 ESP_Flags: 8 ESP + SG_ ABD_Active : 3|1@1+ (1,0) [0|1] "yes/no" AWD,ECU,TCU + SG_ TCS_Active : 9|1@1+ (1,0) [0|1] "yes/no" AWD,ECU,TCU + SG_ ABS_Active : 10|1@1+ (1,0) [0|1] "yes/no" AWD,ECU,TCU + SG_ ESP_Off : 12|1@1+ (1,0) [0|1] "yes/no" AWD,ECU,TCU + SG_ ESP_Active : 14|1@1+ (1,0) [0|1] "yes/no" AWD,ECU,TCU + SG_ VehicleSpeed : 16|8@1+ (1,0) [0|254] "km/h" AWD,ECU,TCU + SG_ TorqueRequestFast : 24|8@1+ (0.390625,0) [0|99.609375] "%" ECU,TCU + SG_ TorqueRequestSlow : 40|8@1+ (0.390625,0) [0|99.609375] "%" ECU,TCU + +BO_ 497 ESP_WheelSpeed: 8 ESP + SG_ FrontRightWheelSpeed : 16|12@1+ (0.125,0) [0|511.875] "km/h" AWD + SG_ FrontLeftWheelSpeed : 28|12@1+ (0.125,0) [0|511.875] "km/h" AWD + SG_ RearRightWheelSpeed : 40|12@1+ (0.125,0) [0|511.875] "km/h" AWD + SG_ RearLeftWheelSpeed : 52|12@1+ (0.125,0) [0|511.875] "km/h" AWD + +BO_ 608 ECU_Data1: 8 ECU + SG_ TorqueMin : 0|8@1+ (0.390625,0) [0|99.609375] "%" ESP,TCU + SG_ Torque : 8|8@1+ (0.390625,0) [0|99.609375] "%" ESP,TCU + SG_ TorqueTarget : 16|8@1+ (0.390625,0) [0|99.609375] "%" ESP,TCU + SG_ CruiseEnabled : 25|1@1+ (1,0) [0|1] "yes/no" TCU + SG_ CruiseActive : 26|1@1+ (1,0) [0|1] "yes/no" TCU + SG_ TorqueMax : 40|8@1+ (0.390625,0) [0|99.609375] "%" ESP,TCU + +BO_ 640 ECU_Data2: 8 ECU + SG_ RPM : 32|8@1+ (32,0) [0|8160] "rpm" TCU + SG_ MAF : 40|8@1+ (5.447,0) [0|1388.985] "mg/TDC" TCU + SG_ IAT : 48|8@1- (0.75,-48) [-48|143.25] "C" TCU + SG_ MAP : 56|8@1+ (0.47058,0) [0|119.9979] "KPa" TCU + +BO_ 688 SAS_Data: 5 SAS + SG_ SAS_Angle : 0|16@1- (0.1,0) [-3276.8|3276.7] "deg" AWD,ECU,ESP,TCU + SG_ SAS_Speed : 16|8@1+ (4,0) [0|1016] "deg/s" ESP,TCU + SG_ SAS_Status : 24|8@1+ (1,0) [0|255] "" ESP,TCU + SG_ Msg_Count : 32|4@1+ (1,0) [0|15] "" ESP + SG_ Check_Sum : 36|4@1+ (1,0) [0|15] "" ECU,ESP + +BO_ 809 ECU_Data5: 8 ECU + SG_ ECT : 8|8@1- (0.75,-48) [-48|143.25] "C" AWD,ABS,ESP,TCU + SG_ BrakeActive : 32|2@1+ (1,0) [0|3] "yes/no" AWD,ABS,ESP,TCU + SG_ TPS : 40|8@1+ (0.47265625,-15) [-15|105.52734375] "%" AWD,ABS,ESP,TCU + +BO_ 1064 AWD_Data1: 8 AWD + SG_ ClutchDuty : 16|8@1+ (1,0) [0|100] "%" ABS,ESP + SG_ ClutchLocked : 44|1@1+ (1,0) [0|1] "yes/no" ABS,ESP + +BO_ 1065 AWD_Data2: 8 AWD + SG_ SteeringWheelPosition : 0|16@1+ (1,-600) [-600|600] "deg" ABS + SG_ FrontRightWheelSpeed : 16|8@1+ (1,0) [0|254] "km/h" ABS + SG_ FrontLeftWheelSpeed : 24|8@1+ (1,0) [0|254] "km/h" ABS + SG_ RearRightWheelSpeed : 32|8@1+ (1,0) [0|254] "km/h" ABS + SG_ RearLeftWheelSpeed : 40|8@1+ (1,0) [0|254] "km/h" ABS + +BO_ 1087 TCU_Data: 8 TCU + SG_ CurrentGear : 0|3@1+ (1,0) [0|7] "" ECU + SG_ GearSwitch : 3|1@1+ (1,0) [0|1] "yes/no" ECU + SG_ SelectorPosition : 8|4@1+ (1,0) [0|15] "" ECU + SG_ InputShaftSpeed : 40|16@1+ (0.25,0) [0|16383.5] "rpm" ECU + +BO_ 1349 ECU_Data6: 8 ECU + SG_ BatteryVoltage : 24|8@1+ (0.1015625,0) [0|25.8984375] "V" ABS,ESP + +BO_ 1408 ABS_WheelSpeed: 8 ABS + SG_ FrontRightWheelSpeed : 16|12@1+ (0.125,0) [0|511.875] "km/h" AWD + SG_ FrontLeftWheelSpeed : 28|12@1+ (0.125,0) [0|511.875] "km/h" AWD + SG_ RearRightWheelSpeed : 40|12@1+ (0.125,0) [0|511.875] "km/h" AWD + SG_ RearLeftWheelSpeed : 52|12@1+ (0.125,0) [0|511.875] "km/h" AWD + +BO_ 1695 ECU_Data7: 8 ECU + SG_ ECU_Temperature : 8|8@1- (1,-28) [-28|227] "C" TCU + +BO_ 1984 SAS_Calibration: 2 ESP + SG_ CCW : 0|4@1+ (1,0) [0|15] "" SAS + SG_ CID : 4|11@1+ (1,0) [0|2047] "" SAS + + + +VAL_ 1087 CurrentGear 7 "R" 0 "N" 1 "1" 2 "2" 3 "3" 4 "4" ; +VAL_ 1087 SelectorPosition 7 "R" 6 "N" 5 "D" 8 "M" 15 "P" ; + diff --git a/opendbc_repo/opendbc/dbc/luxgen_s5_2015.dbc b/opendbc_repo/opendbc/dbc/luxgen_s5_2015.dbc new file mode 100644 index 000000000000000..34fe6b64605ba57 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/luxgen_s5_2015.dbc @@ -0,0 +1,153 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 928 EPB_STATUS: 8 XXX + SG_ EPB_BRAKE : 16|1@1+ (1,0) [0|3] "" XXX + +BO_ 1104 SEATBELT_STATUS: 8 XXX + SG_ DRIVER_SEAT_BELT_ONOFF : 21|1@0+ (1,0) [0|3] "" XXX + +BO_ 1056 BODY_ECU_STATUS: 8 XXX + SG_ DOOR_RL_STATUS : 18|1@0+ (1,0) [0|255] "" XXX + SG_ DOOR_FL_STATUS : 13|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_FR_STATUS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_RR_STATUS : 19|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_BACK_DOOR_STATUS : 22|1@0+ (1,0) [0|1] "" XXX + SG_ LEFT_SIGNAL_STATUS : 10|1@0+ (1,0) [0|1] "" XXX + SG_ RIGHT_SIGNAL_STATUS : 9|1@0+ (1,0) [0|1] "" XXX + +BO_ 832 GEAR_RPM_SPEED_STATUS: 8 XXX + SG_ TRANS_MODE : 7|5@1+ (1,0) [0|0] "" XXX + SG_ TRANS_GEAR_POS : 2|3@0+ (1,0) [0|1] "" XXX + SG_ ENGINE_RPM1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ ENGINE_TEMP : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 821 THROTTLE_STATUS: 8 XXX + SG_ CRUSE_ONOFF : 2|1@0+ (1,0) [0|1] "on/off" XXX + SG_ CRUSE_ENABLED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ THROTTLE_PEDAL_POS : 32|8@1+ (1,0) [0|255] "" XXX + SG_ THROTTLE_POS : 24|8@1+ (1,0) [0|255] "" XXX + SG_ RPM : 48|8@1- (1,0) [0|65535] "" XXX + +BO_ 922 STEERING_ANGLE_STATUS: 8 XXX + SG_ STEER_ANGLE_9000 : 7|16@0- (1,0) [0|65535] "" XXX + +BO_ 906 WHEEL_SPEEDS: 8 XXX + SG_ SPEED_FR : 24|8@1+ (1,0) [0|255] "" XXX + SG_ ABS_UNDEF1 : 32|8@1+ (1,0) [0|255] "" XXX + SG_ SPEED_FL : 0|8@1+ (1,0) [0|255] "" XXX + +BO_ 848 ABS_WHEELS_STATUS: 8 XXX + SG_ NEW_SIGNAL_1 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 15|8@0+ (1,0) [0|255] "" XXX + +BO_ 1402 DASH_STATUS: 8 XXX + SG_ CAR_SPEED : 32|8@1+ (1,0) [0|255] "" XXX + SG_ DASH_INFO2 : 16|8@1+ (1,0) [0|255] "" XXX + SG_ DASH_INFO0 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ DASH_INFO_2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ DASH_INFO_3 : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 1306 _SPEEDX: 8 XXX + SG_ DASH_CAR_SPEED : 7|9@0+ (1,0) [0|255] "" XXX + +BO_ 1296 undefined: 8 XXX + +BO_ 790 ENGINE_DATA: 8 XXX + SG_ _X2 : 6|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_5 : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 1313 undefined_2: 8 XXX + +BO_ 1312 __trigger_every_range: 8 XXX + SG_ __SIGNAL_every_interval : 4|1@0+ (1,0) [0|1] "" XXX + +BO_ 896 undefined_3: 8 XXX + SG_ NEW_SIGNAL_1 : 32|4@1+ (1,0) [0|15] "" XXX + +BO_ 809 undefined_4: 8 XXX + +BO_ 864 BREAK_TCS_STATUS: 8 XXX + SG_ SPEED3 : 24|8@1+ (1,0) [0|255] "" XXX + SG_ TCS_ON_FF : 45|1@0+ (1,0) [0|1] "" XXX + SG_ XXXX1 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PRSSED : 42|1@0+ (1,0) [0|1] "" XXX + +BO_ 842 undefined_5: 8 XXX + +BO_ 880 WHEEL_RPM_STATUS: 8 XXX + SG_ WHEEL_RL_SPEED : 23|16@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_FR_SPEED : 39|16@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_FL_SPEED : 55|16@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_RR_SPEED : 7|16@0- (1,0) [0|255] "" XXX + +BO_ 1040 CONSOLE_STATUS: 8 XXX + SG_ LEFT_SIGNAL_SWITCH : 1|1@0+ (1,0) [0|1] "" XXX + SG_ RIGHT_SIGNAL_SWITCH : 2|1@0+ (1,0) [0|1] "" XXX + SG_ HEAD_LIGHT_HANDLE_SWITCH : 3|1@0+ (1,0) [0|1] "" XXX + SG_ HID_LIGHT_SWITCH : 4|1@0+ (1,0) [0|1] "" XXX + SG_ YELLOW_WARN_TEMP_TRIGGER : 5|1@0+ (1,0) [0|1] "" XXX + SG_ HID_LIGHT_HANDLE_SWITCH : 6|1@0+ (1,0) [0|1] "" XXX + SG_ MIX_MODE : 7|1@0+ (1,0) [0|1] "" XXX + SG_ slider_rain_bar : 13|1@0+ (1,0) [0|1] "" XXX + SG_ temp_slider_rain_bar : 15|1@0+ (1,0) [0|1] "" XXX + SG_ temp_water_push : 11|1@0+ (1,0) [0|1] "" XXX + +BO_ 1120 HAVC_STATUS: 8 XXX + SG_ HAVC_TEMP : 32|8@1+ (1,0) [0|255] "" XXX + + +CM_ SG_ 1104 DRIVER_SEAT_BELT_ONOFF "0 - on , 1 = off"; +CM_ SG_ 1056 DOOR_RL_STATUS "04 - RL - open"; +CM_ SG_ 1056 DOOR_FL_STATUS "28 - FL open , 38 - FR"; +CM_ SG_ 1056 RIGHT_SIGNAL_STATUS "R,L shows at same time means hazard"; +CM_ SG_ 832 TRANS_MODE "AT - 85 / MT - 8D"; +CM_ SG_ 832 TRANS_GEAR_POS "R-7 , 0 - N"; +CM_ SG_ 821 CRUSE_ONOFF "Cruse Switch"; +CM_ SG_ 821 CRUSE_ENABLED "Cruse enabled"; +CM_ SG_ 821 THROTTLE_PEDAL_POS "Real Pedal Pos"; +CM_ SG_ 821 THROTTLE_POS "Throttle Pos for Cruse Mode"; +CM_ SG_ 906 ABS_UNDEF1 "ABS force"; +CM_ SG_ 906 SPEED_FL "used for car speed in dash board"; +CM_ SG_ 864 TCS_ON_FF "ON = 1, OFF =0"; diff --git a/opendbc/mazda_2017.dbc b/opendbc_repo/opendbc/dbc/mazda_2017.dbc similarity index 100% rename from opendbc/mazda_2017.dbc rename to opendbc_repo/opendbc/dbc/mazda_2017.dbc diff --git a/opendbc_repo/opendbc/dbc/mazda_3_2019.dbc b/opendbc_repo/opendbc/dbc/mazda_3_2019.dbc new file mode 100644 index 000000000000000..b23e7196bf7a27b --- /dev/null +++ b/opendbc_repo/opendbc/dbc/mazda_3_2019.dbc @@ -0,0 +1,408 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 256 CAM_Start: 8 XXX + SG_ NEW_SIGNAL_7 : 56|4@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_8 : 61|2@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_10 : 44|12@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_2 : 63|2@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_5 : 24|12@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 2|2@0+ (1,0) [0|1] "" XXX + SG_ ACTIVE_TARGET : 4|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 20|12@0+ (1,0) [0|7] "" XXX + SG_ DISTANCE_LEAD_CAR : 0|12@0+ (1,0) [0|255] "" XXX + +BO_ 358 CAM_End: 8 XXX + SG_ NEW_SIGNAL_2 : 61|2@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_3 : 59|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_1 : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 1216 CAM_69: 8 XXX + SG_ NEW_SIGNAL_1 : 56|4@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_2 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_3 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_5 : 55|12@0+ (1,0) [0|7] "" XXX + +BO_ 1120 CAM_KEEP_ALIVE_2: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_2 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 1436 CAM_71: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 18 STEER: 8 XXX + SG_ NEW_SIGNAL_3 : 55|2@0+ (1,0) [0|15] "" XXX + SG_ CTR : 41|2@0+ (1,0) [0|3] "" XXX + SG_ STEER_LEFT_BIT : 26|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_ANGLE : 25|14@0- (1,375) [0|65536] "" XXX + SG_ ENGINE_OFF : 43|2@0+ (1,0) [0|63] "" XXX + SG_ NEW_SIGNAL_2 : 53|6@0+ (1,0) [0|15] "" XXX + +BO_ 257 LKAS: 8 XXX + SG_ CTR : 59|4@0+ (1,0) [0|255] "" XXX + SG_ CTR_ACT : 61|2@0+ (1,0) [0|3] "" XXX + SG_ SET_0 : 48|1@1+ (1,0) [0|3] "" XXX + SG_ SET_0_1 : 63|2@0+ (1,0) [0|3] "" XXX + SG_ SET_19 : 2|2@0+ (1,0) [0|255] "" XXX + SG_ LEAD_DIST : 0|12@0+ (1,0) [0|255] "" XXX + SG_ ANGLE_TARGET : 20|12@0+ (1,0) [0|4095] "" XXX + SG_ UNKNOWN : 24|12@0+ (1,0) [0|4095] "" XXX + SG_ MAX_TORQUE__ : 44|12@0- (1,0) [0|4095] "" XXX + +BO_ 258 NEW_MSG_3: 8 XXX + SG_ NEW_SIGNAL_3 : 59|4@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_5 : 44|10@0- (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_6 : 1|2@1+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_4 : 39|10@0- (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 13|10@0- (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 18|10@0- (1,0) [0|255] "" XXX + +BO_ 28 WHEEL_SPEEDS: 8 XXX + SG_ RR : 55|16@0+ (0.01,-100) [0|65535] "" XXX + SG_ RL : 39|16@0+ (0.01,-102) [0|65535] "" XXX + SG_ FL : 7|16@0+ (0.01,-100) [0|65535] "" XXX + SG_ FR : 23|16@0+ (0.01,-100) [0|65535] "" XXX + +BO_ 259 NEW_MSG_5: 8 XXX + SG_ NEW_SIGNAL_3 : 39|10@0- (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_4 : 44|10@0- (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 0|12@0- (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 19|11@0- (1,0) [0|10000000] "" XXX + +BO_ 260 NEW_MSG_6: 8 XXX + SG_ NEW_SIGNAL_1 : 0|12@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 24|12@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 20|12@0- (1,0) [0|1] "" XXX + +BO_ 261 NEW_MSG_7: 8 XXX + SG_ NEW_SIGNAL_1 : 15|8@0+ (1,0) [0|255] "" XXX + +BO_ 262 NEW_MSG_8: 8 XXX + SG_ NEW_SIGNAL_1 : 15|8@0- (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 7|8@0+ (1,0) [0|255] "" XXX + +BO_ 263 NEW_MSG_9: 8 XXX + SG_ NEW_SIGNAL_1 : 15|8@0+ (1,0) [0|255] "" XXX + +BO_ 310 NEW_MSG_10: 8 XXX + SG_ NEW_SIGNAL_1 : 56|4@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 308 ACC_POSSIBLY: 8 XXX + SG_ NEW_SIGNAL_1 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_6 : 4|1@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 54|7@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_2 : 0|7@0+ (1,0) [0|63] "" XXX + SG_ NEW_SIGNAL_7 : 37|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_4 : 18|7@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_5 : 36|7@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_8 : 55|1@0+ (1,0) [0|1] "" XXX + +BO_ 304 CAM_LANES: 8 XXX + SG_ NEW_SIGNAL_3 : 59|4@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 61|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LANE_DETECTED : 7|1@0+ (1,0) [0|1] "" XXX + SG_ RIGHT_LANE_DETECTED : 4|1@0+ (1,0) [0|255] "" XXX + SG_ DISTANCE_TO_LEFT_LANE_LOW_RES : 29|8@0+ (1,0) [0|4095] "" XXX + SG_ DISTANCE_TO_RIGHT_LANE_LOW_RES : 37|8@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_TO_RIGHT_LANE : 23|10@0- (1,0) [0|2047] "" XXX + SG_ DISTANCE_TO_LEFT_LANE : 1|10@0- (1,0) [0|1] "" XXX + +BO_ 305 CAM_LANES_2_MAYBE: 8 XXX + SG_ NEW_SIGNAL_1 : 1|10@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 37|8@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_5 : 56|4@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_6 : 61|2@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_4 : 29|8@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_7 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_8 : 4|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 23|10@0+ (1,0) [0|4095] "" XXX + +BO_ 352 NEW_MSG_14: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 355 NEW_MSG_15: 8 XXX + SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|127] "" XXX + +BO_ 356 NEW_MSG_16: 8 XXX + SG_ NEW_SIGNAL_1 : 56|4@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_2 : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 357 NEW_MSG_17: 8 XXX + SG_ NEW_SIGNAL_1 : 61|2@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_2 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ NEW_SIGNAL_3 : 56|4@1+ (1,0) [0|15] "" XXX + +BO_ 59 STEER_RATE: 8 XXX + SG_ NEW_SIGNAL_2 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ STEER_ANGLE_RATE : 55|8@0+ (0.05,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_1 : 43|4@0+ (1,0) [0|15] "" XXX + SG_ STEER_ANGLE : 23|16@0+ (0.05,-1600) [-500|500] "" XXX + SG_ CHKSUM : 39|8@0+ (1,0) [0|15] "" XXX + +BO_ 24 BRAKE_PEDAL: 8 XXX + SG_ BRAKE_PEDAL_PRESSED_AND_ENGINE_ON : 0|1@0+ (1,0) [0|3] "" XXX + SG_ NOT_BRAKE_PEDAL_PRESSED : 6|1@0+ (1,0) [0|3] "" XXX + SG_ BRAKE_PEDAL_PRESSED : 7|1@0+ (1,0) [0|65535] "" XXX + SG_ NOT_BRAKE_PEDAL_PRESSED_AND_ENGINE_ON : 15|1@0+ (1,0) [0|7] "" XXX + +BO_ 26 ENGINE_DATA: 8 XXX + SG_ PEDAL_GAS : 39|10@0+ (1,0) [0|15] "" XXX + SG_ CHKSUM : 63|8@0- (1,0) [0|15] "" XXX + SG_ RPM : 7|13@0+ (1,0) [0|15] "" XXX + SG_ ENGINE_ON : 52|1@0+ (1,0) [0|15] "" XXX + +BO_ 145 BLINK_INFO: 8 XXX + SG_ RIGHT_BLINK : 12|1@0+ (1,0) [0|3] "" XXX + SG_ LEFT_BLINK : 13|1@0+ (1,0) [0|3] "" XXX + SG_ Speed : 27|12@0+ (1,0) [0|255] "" XXX + SG_ CTR : 51|4@0+ (1,0) [0|15] "" XXX + SG_ CHKSUM : 63|8@0+ (1,0) [0|15] "" XXX + +BO_ 16 STEER_TORQUE: 8 XXX + SG_ NEW_SIGNAL_12 : 7|2@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_1 : 43|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_5 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_3 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_4 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ STEER_TORQUE_SENSOR : 5|13@0+ (1,-4000) [0|15] "" XXX + SG_ CHKSUM : 63|8@0- (1,0) [0|15] "" XXX + SG_ STEER_TORQUE_MOTOR : 8|13@0+ (0.05,-205) [0|15] "" XXX + SG_ BRAKE_PREASURE : 27|12@0+ (1,0) [0|15] "" XXX + +BO_ 17 STEER_TORQUE_2: 8 XXX + SG_ CTR : 51|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_5 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_TORQUE_MOTOR : 7|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 27|14@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 45|6@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_3 : 23|12@0+ (1,0) [0|255] "" XXX + +BO_ 29 WHEEL: 8 XXX + SG_ STANDSTILL : 52|1@0+ (1,0) [0|15] "" XXX + SG_ SPEED : 39|16@0+ (1,0) [0|127] "" XXX + SG_ ENCODER_1 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ ENCODER_2 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_6 : 55|3@0+ (1,0) [0|7] "" XXX + SG_ NEW_SIGNAL_1 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 31 GEAR: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_2 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 55|16@0+ (1,0) [0|65535] "" XXX + SG_ GEAR : 36|4@0+ (1,0) [0|65535] "" XXX + +BO_ 96 STEER2: 8 XXX + SG_ NEW_SIGNAL_5 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ CTR : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ TURN_ON : 34|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_OFF : 32|1@0+ (1,0) [0|1] "" XXX + SG_ ENGINE_ON : 33|1@0+ (1,0) [0|1] "" XXX + SG_ CAR_MOVING_FORWARD : 21|1@0+ (1,0) [0|15] "" XXX + SG_ CAR_REVERSING : 22|1@0+ (1,0) [0|1] "" XXX + SG_ ENGINE_OFF : 23|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_4 : 45|1@0+ (1,0) [0|15] "" XXX + SG_ SPEED : 18|16@0- (0.00621371,-62.1371) [-65635|65635] "MPH" XXX + SG_ STEER__ : 7|16@0+ (1,0) [0|65535] "" XXX + +BO_ 1209 KEEP_ALIVE_1: 8 XXX + SG_ NEW_SIGNAL_1 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_5 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_6 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_7 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_8 : 4|5@0+ (1,0) [0|127] "" XXX + +BO_ 37 BLANK_1: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_2 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 44 BLANK_2: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|16777215] "" XXX + SG_ NEW_SIGNAL_3 : 55|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_2 : 39|16@0+ (1,0) [0|16777215] "" XXX + +BO_ 128 RADARS: 8 XXX + SG_ NEW_SIGNAL_1 : 59|4@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 15|1@0+ (1,0) [0|255] "" XXX + SG_ FRONT_LEFT : 19|1@0+ (1,0) [0|255] "" XXX + SG_ FRONT : 21|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_RIGHT : 18|1@0+ (1,0) [0|1] "" XXX + SG_ REAR_RIGHT : 20|1@0+ (1,0) [0|15] "" XXX + SG_ REAR_LEFT : 17|1@0+ (1,0) [0|1] "" XXX + +BO_ 129 NEW_MSG_19: 8 XXX + SG_ NEW_SIGNAL_2 : 15|1@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_3 : 31|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 47|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_5 : 56|8@1+ (1,0) [0|15] "" XXX + +BO_ 1034 KEEP_ALIVE_2: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 23|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 39|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_5 : 55|16@0+ (1,0) [0|255] "" XXX + +BO_ 1200 KEEP_ALIVE_3: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 55|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 39|16@0+ (1,0) [0|65535] "" XXX + +BO_ 354 CAM_KEEP_ALIVE_1: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_2 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_3 : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 55|30@0+ (1,0) [0|65535] "" XXX + +BO_ 336 NEW_MSG_20: 8 XXX + SG_ NEW_SIGNAL_2 : 7|8@0+ (1,0) [0|4095] "" XXX + SG_ NEW_SIGNAL_1 : 11|12@0+ (1,0) [0|127] "" XXX + SG_ NEW_SIGNAL_3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_5 : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 342 NEW_MSG_21: 8 XXX + SG_ NEW_SIGNAL_1 : 56|4@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_2 : 63|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_4 : 55|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_5 : 39|16@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_3 : 48|4@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_7 : 7|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_8 : 23|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_6 : 40|4@1+ (1,0) [0|15] "" XXX + +BO_ 264 NEW_MSG_2: 8 XXX + SG_ NEW_SIGNAL_1 : 56|8@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_2 : 49|3@1+ (1,0) [0|7] "" XXX + SG_ CRZ_CTRL_PRESSED : 48|1@0+ (1,0) [0|1] "" XXX + +BO_ 22 CRZ_CTRL_BTNS: 8 XXX + SG_ CRZ_CTRL_BTN_PRESSED : 48|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 51|3@0+ (1,0) [0|7] "" XXX + SG_ SIGNAL : 45|1@0+ (1,0) [0|15] "" XXX + SG_ NOT_SIGNAL : 46|1@0+ (1,0) [0|3] "" XXX + +BO_ 306 CAM_LANE_3_MAYBE: 8 XXX + SG_ NEW_SIGNAL_1 : 19|10@0+ (1,0) [0|63] "" XXX + SG_ NEW_SIGNAL_2 : 13|10@0+ (1,0) [0|255] "" XXX + SG_ LANE_DETECTED_1 : 44|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_DETECTED_2 : 45|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_4 : 25|10@0+ (1,0) [0|1] "" XXX + SG_ STEER : 7|10@0+ (1,0) [0|1] "" XXX + +BO_ 307 NEW_MSG_1: 8 XXX + SG_ NEW_SIGNAL_2 : 13|10@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_5 : 61|6@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 25|10@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_4 : 7|10@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 19|10@0+ (1,0) [0|1] "" XXX + +BO_ 320 NEW_MSG_4: 8 XXX + SG_ NEW_SIGNAL_4 : 16|1@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 43|6@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 36|9@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 27|7@0+ (1,0) [0|1] "" XXX + +BO_ 321 NEW_MSG_11: 8 XXX + SG_ NEW_SIGNAL_1 : 5|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 32|1@0+ (1,0) [0|1] "" XXX + +BO_ 293 NEW_MSG_12: 8 XXX + SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 39|16@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 19|4@0+ (1,0) [0|1] "" XXX + +BO_ 294 NEW_MSG_13: 8 XXX + SG_ NEW_SIGNAL_1 : 59|4@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 61|2@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 7|16@0+ (1,0) [0|1] "" XXX + +BO_ 292 NEW_MSG_18: 8 XXX + SG_ NEW_SIGNAL_1 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 291 NEW_MSG_22: 8 XXX + SG_ NEW_SIGNAL_1 : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 290 NEW_MSG_23: 8 XXX + SG_ NEW_SIGNAL_1 : 31|5@0+ (1,0) [0|255] "" XXX + +BO_ 277 NEW_MSG_24: 8 XXX + SG_ NEW_SIGNAL_1 : 47|8@0+ (1,0) [0|1] "" XXX + +BO_ 278 NEW_MSG_25: 8 XXX + +BO_ 273 NEW_MSG_26: 8 XXX + SG_ NEW_SIGNAL_1 : 23|4@0+ (1,0) [0|3] "" XXX + +BO_ 274 NEW_MSG_27: 8 XXX + SG_ NEW_SIGNAL_1 : 39|8@0+ (1,0) [0|1] "" XXX + +BO_ 289 NEW_MSG_28: 8 XXX + SG_ NEW_SIGNAL_1 : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 20 NEW_MSG_29: 8 XXX + SG_ RIGHT_BLINK_CLOCK : 23|8@0+ (1,0) [0|1] "" XXX + +BO_ 288 NEW_MSG_30: 8 XXX + + + + +CM_ SG_ 31 GEAR "13-P, 12-R, 11-N, 1-6-D"; +CM_ SG_ 96 SPEED ""; +VAL_ 31 GEAR 13 "P" 12 "R" 11 "N" 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D"; diff --git a/opendbc_repo/opendbc/dbc/mazda_radar.dbc b/opendbc_repo/opendbc/dbc/mazda_radar.dbc new file mode 100644 index 000000000000000..a4fe3b4b9e867fc --- /dev/null +++ b/opendbc_repo/opendbc/dbc/mazda_radar.dbc @@ -0,0 +1,73 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 540 CRZ_CTRL: 8 XXX + +BO_ 539 CRZ_INFO: 8 XXX + +BO_ 865 RADAR_TRACK_361: 8 XXX + SG_ DIST_OBJ : 7|12@0+ (1,0) [0|4095] "" XXX + SG_ ANG_OBJ : 11|12@0- (1,0) [-2047|2047] "" XXX + SG_ RELV_OBJ : 31|11@0- (1,0) [-1023|1023] "" XXX + +BO_ 866 RADAR_TRACK_362: 8 XXX + SG_ DIST_OBJ : 7|12@0+ (1,0) [0|4095] "" XXX + SG_ ANG_OBJ : 11|12@0- (1,0) [-2047|2047] "" XXX + SG_ RELV_OBJ : 31|11@0- (1,0) [-1023|1023] "" XXX + +BO_ 867 RADAR_TRACK_363: 8 XXX + SG_ DIST_OBJ : 7|12@0+ (1,0) [0|4095] "" XXX + SG_ ANG_OBJ : 11|12@0- (1,0) [-2047|2047] "" XXX + SG_ RELV_OBJ : 31|11@0- (1,0) [-1023|1023] "" XXX + +BO_ 868 RADAR_TRACK_364: 8 XXX + SG_ DIST_OBJ : 7|12@0+ (1,0) [0|4095] "" XXX + SG_ ANG_OBJ : 11|12@0- (1,0) [-2047|2047] "" XXX + SG_ RELV_OBJ : 31|11@0- (1,0) [-1023|1023] "" XXX + +BO_ 869 RADAR_TRACK_365: 8 XXX + SG_ DIST_OBJ : 7|12@0+ (1,0) [0|4095] "" XXX + SG_ ANG_OBJ : 11|12@0- (1,0) [-2047|2047] "" XXX + SG_ RELV_OBJ : 31|11@0- (1,0) [-1023|1023] "" XXX + +BO_ 870 RADAR_TRACK_366: 8 XXX + SG_ DIST_OBJ : 7|12@0+ (1,0) [0|4095] "" XXX + SG_ ANG_OBJ : 11|12@0- (1,0) [-2047|2047] "" XXX + SG_ RELV_OBJ : 31|11@0- (1,0) [-1023|1023] "" XXX + +BO_ 1177 RADAR_499: 8 XXX \ No newline at end of file diff --git a/opendbc_repo/opendbc/dbc/mazda_rx8.dbc b/opendbc_repo/opendbc/dbc/mazda_rx8.dbc new file mode 100644 index 000000000000000..f491a9698fd630e --- /dev/null +++ b/opendbc_repo/opendbc/dbc/mazda_rx8.dbc @@ -0,0 +1,77 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: PowertrainControlModule InstrumentCluster ElectricPowerSteering AntilockBrakeSystem + + +BO_ 129 steering: 8 ElectricPowerSteering + SG_ SteeringAngle : 23|16@0- (1,0) [0|0] "deg" Vector__XXX + +BO_ 513 speed: 8 PowertrainControlModule + SG_ EngineRPM : 7|16@0+ (0.25,0) [0|0] "rpm" Vector__XXX + SG_ VehicleSpeed : 39|16@0+ (0.01,-100) [0|0] "kph" Vector__XXX + SG_ AcceleratorPos : 55|8@0+ (0.5,0) [0|0] "%" Vector__XXX + +BO_ 592 throttle_body: 8 PowertrainControlModule + SG_ IntakeAirTemperature : 31|8@0+ (1,-40) [0|0] "Cel" Vector__XXX + SG_ AcceleratorPedalSensorRaw : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ AcceleratorPedalSensorFiltered : 55|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 658 brake_controls: 8 PowertrainControlModule + SG_ BrakePedalSwitch : 43|1@1+ (1,0) [0|0] "" Vector__XXX + SG_ ParkingBrakeSwitch : 38|1@1+ (1,0) [0|0] "" Vector__XXX + +BO_ 1056 coolant: 8 PowertrainControlModule + SG_ CoolantTemperature : 7|8@0+ (1,-40) [0|0] "Cel" Vector__XXX + +BO_ 1072 instrument_cluster: 8 InstrumentCluster + SG_ FuelLevel : 7|8@0+ (0.392156,0) [0|0] "%" Vector__XXX + SG_ FuelTankSensorLeft : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ FuelTankSensorRight : 23|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1200 wheel_speed: 8 AntilockBrakeSystem + SG_ WheelSpeedFL : 7|16@0+ (0.01,-100) [0|0] "kph" Vector__XXX + SG_ WheelSpeedFR : 23|16@0+ (0.01,-100) [0|0] "kph" Vector__XXX + SG_ WheelSpeedRL : 39|16@0+ (0.01,-100) [0|0] "kph" Vector__XXX + SG_ WheelSpeedRR : 55|16@0+ (0.01,-100) [0|0] "kph" Vector__XXX + +CM_ SG_ 129 SteeringAngle "Steering wheel angle: positive is right and negative is left"; +CM_ SG_ 513 AcceleratorPos "processed interpretation of AcceleratorPedalSensor values"; +CM_ SG_ 1072 FuelTankSensorLeft "lower sensor values indicate a more full tank"; +CM_ SG_ 1072 FuelTankSensorRight "lower sensor values indicate a more full tank"; + + + + diff --git a/opendbc_repo/opendbc/dbc/mercedes_benz_e350_2010.dbc b/opendbc_repo/opendbc/dbc/mercedes_benz_e350_2010.dbc new file mode 100644 index 000000000000000..da6ae4c15ee66bd --- /dev/null +++ b/opendbc_repo/opendbc/dbc/mercedes_benz_e350_2010.dbc @@ -0,0 +1,176 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + + +BO_ 3 STEER_SENSOR: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_RATE : 19|12@0- (0.5,0) [0|255] "" XXX + SG_ STEER_DIRECTION : 4|1@0+ (1,2) [0|1] "" XXX + SG_ STEER_ANGLE : 3|12@0- (-0.5,0) [-500|500] "degrees" XXX + +BO_ 5 BRAKE_MODULE: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_HOLD : 2|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_POSITION : 17|10@0+ (1,0) [0|65535] "" XXX + SG_ DRIVER_BRAKE : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COMPUTER_BRAKE : 10|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_PRESSED : 0|1@1+ (1,0) [0|1] "" XXX + +BO_ 69 DRIVER_CONTROLS: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ STEERING_WHEEL_BUTTONS : 32|16@1+ (1,0) [0|255] "4 directional, 2 volume control & 2 phone buttons" XXX + SG_ LEFT_BLINKER : 16|1@0+ (1,0) [0|1] "" XXX + SG_ RIGHT_BLINKER : 17|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAM_TOGGLE : 18|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAM_MOMENTARY : 19|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_CANCEL : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_RESUME : 1|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_ACCEL_HIGH : 2|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_DECEL_HIGH : 3|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_ACCEL_LOW : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_DECEL_LOW : 5|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_XFF : 15|8@0+ (1,0) [0|255] "" XXX + +BO_ 513 WHEEL_ENCODERS: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ WHEEL_ENCODER_2 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_ENCODER_3 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ WHEEL_ENCODER_4 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 56|8@1+ (1,0) [0|255] "" XXX + SG_ WHEEL_ENCODER_1 : 7|8@0+ (1,0) [0|255] "" XXX + +BO_ 261 GAS_PEDAL: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ ENGINE_RPM : 4|5@0+ (1,0) [0|255] "" XXX + SG_ GAS_PEDAL : 39|8@0+ (1,0) [0|255] "" XXX + SG_ COMBINED_GAS : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 DOOR_SENSORS: 8 XXX + SG_ BRAKE_PRESSED : 27|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 3|1@1+ (1,0) [0|3] "" XXX + SG_ DOOR_OPEN_RL : 5|1@0+ (1,0) [0|3] "" XXX + SG_ DOOR_OPEN_RR : 7|1@0+ (1,0) [0|3] "" XXX + SG_ DOOR_OPEN_FL : 1|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_FL : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_FR : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_RL : 4|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_CLOSED_RR : 6|1@0+ (1,0) [0|1] "" XXX + +BO_ 885 SEATBELT_SENSORS: 8 XXX + SG_ SEATBELT_DRIVER_LATCHED : 16|1@0+ (1,0) [0|1] "" XXX + SG_ SEATBELT_PASSENGER_LATCHED : 18|1@0+ (1,0) [0|1] "" XXX + +BO_ 257 CRUISE_CONTROL: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 6|1@0+ (1,0) [0|255] "" XXX + SG_ CRUISE_DISABLED : 23|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X002 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X003 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_1 : 5|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ACCELERATING : 22|1@0+ (1,0) [0|1] "" XXX + SG_ LONGITUDINAL_ACCEL_REQUEST : 15|8@0- (1,0) [0|127] "" XXX + +BO_ 260 CRUISE_CONTROL2: 8 XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_XFF : 31|8@0+ (1,0) [0|65535] "" XXX + SG_ SET_ME_X02 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_XFF2 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 7|4@0+ (1,0) [0|255] "" XXX + +BO_ 14 STEER_TORQUE: 8 XXX + SG_ STEER_TORQUE : 15|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 888 CRUISE_CONTROL3: 8 XXX + SG_ NEW_SIGNAL_2 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 38|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_5 : 32|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_DISABLED : 36|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_ENABLED : 34|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X003 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X004 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X002 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ CRUISE_SET_SPEED : 15|8@0+ (1,0) [0|63] "mph" XXX + SG_ CRUISE_SPEED_CHANGE : 55|1@0+ (1,0) [0|1] "" XXX + +BO_ 307 POWER_SEATS: 8 XXX + SG_ DRIVER_FORWARD : 0|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVER_BACK : 1|1@0+ (1,0) [0|1] "" XXX + +BO_ 109 GEAR_LEVER: 8 XXX + SG_ PARK_BUTTON : 12|1@0+ (1,0) [0|1] "" XXX + SG_ NEUTRAL_UP : 9|1@0+ (1,0) [0|1] "" XXX + SG_ NEUTRAL_DOWN : 10|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE : 11|1@0+ (1,0) [0|1] "" XXX + SG_ REVERSE : 8|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 23|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 115 GEAR_PACKET: 8 XXX + SG_ GEAR : 0|4@1+ (1,0) [0|15] "" XXX + +BO_ 581 IGNITION: 8 XXX + +BO_ 515 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_MOVING_FR : 22|1@1+ (1,0) [0|15] "" XXX + SG_ WHEEL_MOVING_RL : 38|1@0+ (1,0) [0|1] "" XXX + SG_ WHEEL_MOVING_FL : 6|1@0+ (1,0) [0|1] "" XXX + SG_ WHEEL_MOVING_RR : 54|1@0+ (1,0) [0|1] "" XXX + SG_ WHEEL_SPEED_FL : 2|11@0+ (0.0375,0) [0|255] "mph" XXX + SG_ WHEEL_SPEED_FR : 18|11@0+ (0.0375,0) [0|255] "mph" XXX + SG_ WHEEL_SPEED_RL : 34|11@0+ (0.0375,0) [0|255] "mph" XXX + SG_ WHEEL_SPEED_RR : 50|11@0+ (0.0375,0) [0|255] "mph" XXX + + + + +CM_ SG_ 3 STEER_DIRECTION "0 = left, 1 = right"; +CM_ SG_ 5 BRAKE_POSITION "computer and driver"; +CM_ SG_ 5 BRAKE_PRESSED "computer and driver"; +CM_ SG_ 261 GAS_PEDAL "user gas input"; +CM_ SG_ 261 COMBINED_GAS "computer and driver gas"; +CM_ SG_ 257 CRUISE_ACCELERATING ""; \ No newline at end of file diff --git a/opendbc/nissan_leaf_2018_generated.dbc b/opendbc_repo/opendbc/dbc/nissan_leaf_2018_generated.dbc similarity index 100% rename from opendbc/nissan_leaf_2018_generated.dbc rename to opendbc_repo/opendbc/dbc/nissan_leaf_2018_generated.dbc diff --git a/opendbc/nissan_x_trail_2017_generated.dbc b/opendbc_repo/opendbc/dbc/nissan_x_trail_2017_generated.dbc similarity index 100% rename from opendbc/nissan_x_trail_2017_generated.dbc rename to opendbc_repo/opendbc/dbc/nissan_x_trail_2017_generated.dbc diff --git a/opendbc_repo/opendbc/dbc/nissan_xterra_2011.dbc b/opendbc_repo/opendbc/dbc/nissan_xterra_2011.dbc new file mode 100644 index 000000000000000..1e7bd4c4ae12cfa --- /dev/null +++ b/opendbc_repo/opendbc/dbc/nissan_xterra_2011.dbc @@ -0,0 +1,96 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + +BO_ 2 STEERING: 5 XXX + SG_ COUNTER : 35|4@0+ (1,0) [0|255] "" XXX + SG_ STEERING_ANGLE : 0|16@1- (0.1,0) [0|65535] "deg" XXX + SG_ POWER_STEER_RATE : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 505 ENGINE_1: 8 XXX + SG_ RPM : 16|16@1+ (0.125,0) [0|45000] "R/min" XXX + SG_ FAN_REQ : 6|2@1+ (1,0) [0|3] "" XXX + SG_ AC_REQ : 3|1@1+ (1,0) [0|1] "" XXX + +BO_ 561 ENGINE_2: 8 XXX + SG_ Pedal_position : 16|8@1+ (0.5,0) [0|200] "%" XXX + +BO_ 563 ENGINE_7: 8 XXX + SG_ CLT : 0|8@1+ (0.366666,0) [0|255] "C" XXX + SG_ RPMlow : 32|8@1+ (3.15,0) [0|45000] "R/min" XXX + SG_ RPMhi : 56|8@1+ (3.15,0) [0|45000] "R/min" XXX + +BO_ 573 ENGINE_3: 8 XXX + SG_ Pedal_position : 8|8@1+ (0.392,0) [0|255] "%" XXX + SG_ Throttle_position_capped : 16|8@1+ (0.392,0) [0|255] "%" XXX + SG_ RPM : 24|16@1+ (3.15,0) [0|45000] "R/min" XXX + SG_ CLT : 56|8@1+ (0.366666,0) [0|255] "C" XXX + +BO_ 574 ENGINE_4: 8 XXX + SG_ Throttle_position_inverted : 16|8@1+ (0.392,0) [0|255] "%" XXX + SG_ EstimatedTorque : 24|16@1+ (0.1,0) [0|45000] "nM" XXX + SG_ Throttle_position : 48|8@1+ (0.392,0) [0|255] "%" XXX + +BO_ 595 TCU_1: 8 XXX + SG_ SHAFT_1_SPEED : 32|16@1+ (1,0) [0|45000] "r/min" XXX + SG_ SHAFT_2_SPEED : 48|16@1+ (1,0) [0|45000] "r/min" XXX + +BO_ 640 SPEED: 8 XXX + SG_ SPEED : 32|16@1+ (0.01,0) [0|45000] "km/h" XXX + +BO_ 644 ABS_1: 8 XXX + SG_ WHEEL_1 : 0|16@1+ (0.01,0) [0|45000] "km/h" XXX + SG_ WHEEL_2 : 15|16@1+ (0.01,0) [0|45000] "km/h" XXX + +BO_ 645 ABS_2: 8 XXX + SG_ WHEEL_3 : 0|16@1+ (0.01,0) [0|45000] "km/h" XXX + SG_ WHEEL_4 : 15|16@1+ (0.01,0) [0|45000] "km/h" XXX + +BO_ 852 SPEED_BREAK: 8 XXX + SG_ BREAK_LIGHT : 52|1@0+ (1,0) [0|3] "" XXX + SG_ SPEED_MPH : 7|16@0+ (0.0066,0) [0|65535] "mph" XXX + SG_ TCS_OFF : 38|1@0+ (1,0) [0|255] "" XXX + +BO_ 861 BCM: 8 XXX + +BO_ 1361 ENGINE_5: 8 XXX + SG_ CLT : 0|8@1+ (1,-45) [-45|150] "" XXX + +BO_ 1408 ENGINE_6: 8 XXX + SG_ RPM : 7|16@0+ (1.5,0) [0|65535] "" XXX + SG_ OIL_TEMP : 32|8@1+ (1,-40) [-40|150] "" XXX + +BO_ 1477 MILEAGE: 8 XXX \ No newline at end of file diff --git a/opendbc_repo/opendbc/dbc/opel_omega_2001.dbc b/opendbc_repo/opendbc/dbc/opel_omega_2001.dbc new file mode 100644 index 000000000000000..8f8e0cfdea17314 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/opel_omega_2001.dbc @@ -0,0 +1,104 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: ABS ESP ECU TCU SAS + + +BO_ 272 TCU_Data1: 8 TCU + SG_ TorqueRequest1 : 15|8@0+ (1,0) [0|255] "" ABS,ESP,ECU + SG_ TorqueRequest2 : 31|8@0+ (1,0) [0|255] "" ABS,ESP,ECU + SG_ OutputShaftSpeed : 55|16@0+ (1,0) [0|65535] "rpm" ABS,ESP,ECU + +BO_ 288 ESP_Data1: 8 ESP + SG_ ABD_Active : 4|1@0+ (1,0) [0|1] "yes/no" ECU,TCU + SG_ TorqueRequestFast : 15|8@0+ (1,0) [0|255] "" ECU,TCU + SG_ TorqueRequestSlow : 31|8@0+ (1,0) [0|255] "" ECU,TCU + +BO_ 384 SAS_Data: 8 SAS + SG_ SteeringAngle : 0|16@1- (0.1,0) [-3276.8|3276.7] "yes/no" ECU,TCU + SG_ SteeringSpeed : 16|8@1+ (1,0) [0|255] "" ECU,TCU + +BO_ 416 ECU_Data1: 8 ECU + SG_ RPM : 15|16@0+ (1,0) [0|65535] "rpm" ABS,ESP,TCU + SG_ TorqueResponse : 31|8@0+ (1,0) [0|255] "" ABS,ESP,TCU + SG_ TorqueLost : 39|8@0+ (1,0) [0|255] "" ABS,ESP,TCU + SG_ APP : 47|8@0+ (1,0) [0|102] "" ABS,ESP,TCU + SG_ TorqueRequest : 63|8@0+ (1,0) [0|255] "" ABS,ESP,TCU + +BO_ 448 ECU_Data2: 8 ECU + SG_ TPS : 23|8@0+ (1,0) [0|100] "" ABS,ESP,TCU + +BO_ 640 ECU_Data3: 8 ECU + SG_ BrakeActive : 18|1@0+ (1,0) [0|1] "yes/no" ABS,ESP,TCU + SG_ KickdownActive : 20|1@0+ (1,0) [0|1] "yes/no" ABS,ESP,TCU + SG_ CruiseActive : 22|1@0+ (1,0) [0|1] "yes/no" ABS,ESP,TCU + +BO_ 736 TCU_Data2: 8 TCU + SG_ TOT : 31|8@0- (1,-40) [-40|215] "" ECU + SG_ InputShaftSpeed : 47|16@0+ (1,0) [0|65535] "rpm" ECU + +BO_ 768 ABS_WheelSpeed: 8 ABS + SG_ FrontLeftWheelSpeed : 5|14@0+ (0.112,0) [0|255] "km/h" ECU,TCU + SG_ FrontLeftWheelErrorFlag : 7|1@0+ (1,0) [0|1] "" ECU,TCU + SG_ FrontRightWheelSpeed : 21|14@0+ (0.112,0) [0|255] "km/h" ECU,TCU + SG_ FrontRightWheelErrorFlag : 23|1@0+ (1,0) [0|1] "" ECU,TCU + SG_ RearLeftWheelSpeed : 37|14@0+ (0.112,0) [0|255] "km/h" ECU,TCU + SG_ RearLeftWheelErrorFlag : 39|1@0+ (1,0) [0|1] "" ECU,TCU + SG_ RearRightWheelSpeed : 53|14@0+ (0.112,0) [0|255] "km/h" ECU,TCU + SG_ RearRightWheelErrorFlag : 55|1@0+ (1,0) [0|1] "" ECU,TCU + +BO_ 792 ESP_Data2: 8 ESP + SG_ ABS_Active : 12|1@0+ (1,0) [0|1] "yes/no" ECU,TCU + SG_ ESP_Off : 20|1@0+ (1,0) [0|1] "yes/no" ECU,TCU + SG_ ESP_Active : 21|1@0+ (1,0) [0|1] "yes/no" ECU,TCU + +BO_ 992 TCU_Data3: 8 TCU + SG_ CurrentGear : 11|4@0+ (1,0) [0|15] "" ECU + SG_ SelectorPosition : 18|3@0+ (1,0) [0|7] "" ECU + SG_ AutoNeutralActive : 26|1@0+ (1,0) [0|1] "yes/no" ECU + SG_ WinterModeActive : 29|1@0+ (1,0) [0|1] "yes/no" ECU + SG_ SportModeActive : 30|1@0+ (1,0) [0|1] "yes/no" ECU + SG_ TCC_State : 37|2@0+ (1,0) [0|2] "" ECU + +BO_ 1472 ECU_Data4: 8 ECU + SG_ ECT : 15|8@0- (1,-40) [-40|215] "" TCU + SG_ IAT : 47|8@0- (1,-40) [-40|215] "" TCU + + + +VAL_ 992 CurrentGear 5 "1" 6 "2" 7 "3" 8 "4" ; +VAL_ 992 SelectorPosition 1 "P" 2 "R" 3 "N" 4 "D" 7 "3" 6 "2" 5 "1" ; +VAL_ 992 TCC_State 0 "Off" 1 "Partially Locked" 2 "Locked" ; + diff --git a/opendbc/subaru_forester_2017_generated.dbc b/opendbc_repo/opendbc/dbc/subaru_forester_2017_generated.dbc similarity index 100% rename from opendbc/subaru_forester_2017_generated.dbc rename to opendbc_repo/opendbc/dbc/subaru_forester_2017_generated.dbc diff --git a/opendbc/subaru_global_2017_generated.dbc b/opendbc_repo/opendbc/dbc/subaru_global_2017_generated.dbc similarity index 100% rename from opendbc/subaru_global_2017_generated.dbc rename to opendbc_repo/opendbc/dbc/subaru_global_2017_generated.dbc diff --git a/opendbc/subaru_global_2020_hybrid_generated.dbc b/opendbc_repo/opendbc/dbc/subaru_global_2020_hybrid_generated.dbc similarity index 100% rename from opendbc/subaru_global_2020_hybrid_generated.dbc rename to opendbc_repo/opendbc/dbc/subaru_global_2020_hybrid_generated.dbc diff --git a/opendbc/subaru_outback_2015_generated.dbc b/opendbc_repo/opendbc/dbc/subaru_outback_2015_generated.dbc similarity index 100% rename from opendbc/subaru_outback_2015_generated.dbc rename to opendbc_repo/opendbc/dbc/subaru_outback_2015_generated.dbc diff --git a/opendbc/subaru_outback_2019_generated.dbc b/opendbc_repo/opendbc/dbc/subaru_outback_2019_generated.dbc similarity index 100% rename from opendbc/subaru_outback_2019_generated.dbc rename to opendbc_repo/opendbc/dbc/subaru_outback_2019_generated.dbc diff --git a/opendbc/tesla_can.dbc b/opendbc_repo/opendbc/dbc/tesla_can.dbc similarity index 100% rename from opendbc/tesla_can.dbc rename to opendbc_repo/opendbc/dbc/tesla_can.dbc diff --git a/opendbc_repo/opendbc/dbc/tesla_model3_party.dbc b/opendbc_repo/opendbc/dbc/tesla_model3_party.dbc new file mode 100644 index 000000000000000..8fa1658691a97cb --- /dev/null +++ b/opendbc_repo/opendbc/dbc/tesla_model3_party.dbc @@ -0,0 +1,339 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: CH DIPF DIPR ETH FC HVI HVS PARTY SDCV VEH VIRT + + +BO_ 905 DAS_status2: 8 PARTY + SG_ DAS_status2Checksum : 56|8@1+ (1,0) [0|255] "" aps + SG_ DAS_status2Counter : 52|4@1+ (1,0) [0|15] "" aps + SG_ DAS_longCollisionWarning : 48|4@1+ (1,0) [0|15] "" aps + SG_ DAS_ppOffsetDesiredRamp : 40|8@1+ (0.01,-1.28) [-1.28|1.27] "m" aps + SG_ DAS_driverInteractionLevel : 38|2@1+ (1,0) [0|2] "" aps + SG_ DAS_robState : 36|2@1+ (1,0) [0|3] "" aps + SG_ DAS_radarTelemetry : 34|2@1+ (1,0) [0|2] "" aps + SG_ DAS_lssState : 31|3@1+ (1,0) [0|7] "" aps + SG_ DAS_ACC_report : 26|5@1+ (1,0) [0|24] "" aps + SG_ DAS_pmmCameraFaultReason : 24|2@1+ (1,0) [0|2] "" aps + SG_ DAS_pmmSysFaultReason : 21|3@1+ (1,0) [0|7] "" aps + SG_ DAS_pmmRadarFaultReason : 19|2@1+ (1,0) [0|2] "" aps + SG_ DAS_pmmUltrasonicsFaultReason : 16|3@1+ (1,0) [0|4] "" aps + SG_ DAS_activationFailureStatus : 14|2@1+ (1,0) [0|2] "" aps + SG_ DAS_pmmLoggingRequest : 13|1@1+ (1,0) [0|1] "" aps + SG_ DAS_pmmObstacleSeverity : 10|3@1+ (1,0) [0|7] "" aps + SG_ DAS_accSpeedLimit : 0|10@1+ (0.4,0) [0|204.6] "mph" aps + +BO_ 264 DI_torque: 8 PARTY + SG_ DI_axleSpeed : 40|16@1- (0.1,0.0) [-2750|2750] "RPM" epas3s + SG_ DI_torqueActual : 27|13@1- (2,0) [-7500|7500] "Nm" X + SG_ DI_torqueCommand : 12|13@1- (2,0) [-7500|7500] "Nm" X + SG_ DI_torqueCounter : 8|4@1+ (1,0) [0|15] "" epas3s + SG_ DI_torqueChecksum : 0|8@1+ (1,0) [0|255] "" epas3s + +BO_ 585 SCCM_leftStalk: 3 PARTY + SG_ SCCM_leftStalkReserved1 : 19|5@1+ (1,0) [0|31] "" X + SG_ SCCM_turnIndicatorStalkStatus : 16|3@1+ (1,0) [0|5] "" park + SG_ SCCM_washWipeButtonStatus : 14|2@1+ (1,0) [0|3] "" X + SG_ SCCM_highBeamStalkStatus : 12|2@1+ (1,0) [0|3] "" X + SG_ SCCM_leftStalkCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ SCCM_leftStalkCrc : 0|8@1+ (1,0) [0|255] "" X + +BO_ 280 DI_systemStatus: 8 PARTY + SG_ DI_trackModeState : 48|2@1+ (1,0) [0|2] "" X + SG_ DI_keepAliveRequest : 47|1@1+ (1,0) [0|1] "" X + SG_ DI_proximity : 46|1@1+ (1,0) [0|1] "" X + SG_ DI_epbRequest : 44|2@1+ (1,0) [0|2] "" X + SG_ DI_tractionControlMode : 40|3@1+ (1,0) [0|5] "" X + SG_ DI_accelPedalPos : 32|8@1+ (0.4,0) [0|100] "%" X + SG_ DI_immobilizerState : 27|3@1+ (1,0) [0|6] "" X + SG_ DI_regenLight : 26|1@1+ (1,0) [0|1] "" X + SG_ DI_gear : 21|3@1+ (1,0) [0|7] "" park + SG_ DI_brakePedalState : 19|2@1+ (1,0) [0|2] "" X + SG_ DI_systemState : 16|3@1+ (1,0) [0|5] "" X + SG_ DI_systemStatusCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ DI_systemStatusChecksum : 0|8@1+ (1,0) [0|255] "" X + +BO_ 697 DAS_control: 8 PARTY + SG_ DAS_controlChecksum : 56|8@1+ (1,0) [0|255] "" aps + SG_ DAS_controlCounter : 53|3@1+ (1,0) [0|7] "" aps + SG_ DAS_accelMax : 44|9@1+ (0.04,-15) [-15|5.44] "m/s^2" aps + SG_ DAS_accelMin : 35|9@1+ (0.04,-15) [-15|5.44] "m/s^2" aps + SG_ DAS_jerkMax : 27|8@1+ (0.034,0) [0|8.67] "m/s^3" aps + SG_ DAS_jerkMin : 18|9@1+ (0.018,-9.1) [-9.1|0.097999999999999] "m/s^3" aps + SG_ DAS_aebEvent : 16|2@1+ (1,0) [0|3] "" aps + SG_ DAS_accState : 12|4@1+ (1,0) [0|15] "" aps + SG_ DAS_setSpeed : 0|12@1+ (0.1,0) [0|409.4] "kph" aps + +BO_ 341 ESP_B: 8 PARTY + SG_ ESP_wheelRotationChecksum : 56|8@1+ (1,0) [0|255] "" app + SG_ ESP_wheelRotationCounter : 52|4@1+ (1,0) [0|15] "" app + SG_ ESP_vehicleSpeed : 42|10@1+ (0.5,0) [0|511] "kph" app + SG_ ESP_vehicleStandstillSts : 41|1@1+ (1,0) [0|1] "" park + SG_ ESP_wheelSpeedsQF : 40|1@1+ (1,0) [0|1] "" epas3s + SG_ ESP_WheelRotationFrL : 38|2@1+ (1,0) [0|3] "" aps + SG_ ESP_WheelRotationFrR : 36|2@1+ (1,0) [0|3] "" aps + SG_ ESP_WheelRotationReL : 34|2@1+ (1,0) [0|3] "" aps + SG_ ESP_WheelRotationReR : 32|2@1+ (1,0) [0|3] "" aps + SG_ ESP_wheelPulseCountReR : 24|8@1+ (1,0) [0|254] "1" das + SG_ ESP_wheelPulseCountReL : 16|8@1+ (1,0) [0|254] "1" das + SG_ ESP_wheelPulseCountFrR : 8|8@1+ (1,0) [0|254] "1" app + SG_ ESP_wheelPulseCountFrL : 0|8@1+ (1,0) [0|254] "1" app + +BO_ 969 APS_status: 4 PARTY + SG_ APS_statusCounter : 22|4@1+ (1,0) [0|15] "" X + SG_ APS_apbGpioState : 20|2@1+ (1,0) [0|3] "" gtw + SG_ APS_apbStatusMonitorState : 16|3@1+ (1,0) [0|7] "" gtw + SG_ APS_switchState : 15|1@1+ (1,0) [0|1] "" X + SG_ APS_eacInternalState : 12|3@1+ (1,0) [0|7] "" gtw + SG_ APS_appGpioState : 10|2@1+ (1,0) [0|3] "" gtw + SG_ APS_canMaster : 8|2@1+ (1,0) [0|3] "" gtw + SG_ APS_vehBehaviorState : 4|3@1+ (1,0) [0|7] "" gtw + SG_ APS_appStatusMonitorState : 0|3@1+ (1,0) [0|7] "" gtw + +BO_ 925 IBST_status: 5 PARTY + SG_ IBST_sInputRodDriver : 21|12@1+ (0.015625,-5) [-5|47] "mm" gtw + SG_ IBST_internalState : 18|3@1+ (1,0) [0|6] "" gtw + SG_ IBST_driverBrakeApply : 16|2@1+ (1,0) [0|3] "" gtw + SG_ IBST_iBoosterStatus : 12|3@1+ (1,0) [0|6] "" gtw + SG_ IBST_statusCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ IBST_statusChecksum : 0|8@1+ (1,0) [0|255] "" X + +BO_ 880 EPAS3S_sysStatus: 8 PARTY + SG_ EPAS3S_sysStatusChecksum : 63|8@0+ (1,0) [0|255] "" park + SG_ EPAS3S_sysStatusCounter : 51|4@0+ (1,0) [0|15] "" gtw + SG_ EPAS3S_eacStatus : 55|3@0+ (1,0) [0|7] "" das + SG_ EPAS3S_internalSAS : 37|14@0+ (0.1,-819.2) [-819.2|819] "deg" das + SG_ EPAS3S_handsOnLevel : 39|2@0+ (1,0) [0|3] "" das + SG_ EPAS3S_torsionBarTorque : 19|12@0+ (0.01,-20.5) [-20.5|20.45] "Nm" das + SG_ EPAS3S_eacErrorCode : 23|4@0+ (1,0) [0|15] "" das + SG_ EPAS3S_steeringRackForce : 1|10@0+ (50,-25575) [-25575|25575] "N" gtw + SG_ EPAS3S_steeringFault : 2|1@0+ (1,0) [0|1] "" das + SG_ EPAS3S_steeringReduced : 3|1@0+ (1,0) [0|1] "" das + SG_ EPAS3S_internalSASQF : 4|1@0+ (1,0) [0|1] "" gtw + SG_ EPAS3S_currentTuneMode : 7|3@0+ (1,0) [0|5] "" gtw + +BO_ 637 APS_eacMonitor: 3 PARTY + SG_ APS_eacAllow : 0|2@1+ (1,0) [0|0] "" X + SG_ APS_eacMonitorChecksum : 16|8@1+ (1,0) [0|0] "" X + SG_ APS_eacMonitorCounter : 8|4@1+ (1,0) [0|0] "" X + +BO_ 599 DI_speed: 8 PARTY + SG_ DI_uiSpeedUnits : 32|1@1+ (1,0) [0|1] "" das + SG_ DI_uiSpeed : 24|8@1+ (1,0) [0|254] "" das + SG_ DI_vehicleSpeed : 12|12@1+ (0.08,-40) [-40|285] "kph" park + SG_ DI_speedCounter : 8|4@1+ (1,0) [0|15] "" park + SG_ DI_speedChecksum : 0|8@1+ (1,0) [0|255] "" park + +BO_ 1160 DAS_steeringControl: 4 PARTY + SG_ DAS_steeringControlChecksum : 31|8@0+ (1,0) [0|255] "" aps + SG_ DAS_steeringControlCounter : 19|4@0+ (1,0) [0|15] "" aps + SG_ DAS_steeringControlType : 23|2@0+ (1,0) [0|3] "" aps + SG_ DAS_steeringAngleRequest : 6|15@0+ (0.1,-1638.35) [-1638.35|1638.35] "deg" aps + SG_ DAS_steeringHapticRequest : 7|1@0+ (1,0) [0|1] "" aps + +BO_ 297 SCCM_steeringAngleSensor: 8 PARTY + SG_ SCCM_steeringAngleSensorReservd3 : 56|8@1+ (1,0) [0|255] "" X + SG_ SCCM_steeringAngleSensorReservd2 : 48|8@1+ (1,0) [0|255] "" X + SG_ SCCM_steeringAngleSensorReservd1 : 46|2@1+ (1,0) [0|3] "" X + SG_ SCCM_steeringAngleSpeed : 32|14@1+ (0.5,-4096) [-4096|4095.5] "deg/s" park + SG_ SCCM_steeringAngleValidity : 30|2@1+ (1,0) [0|3] "" park + SG_ SCCM_steeringAngle : 16|14@1+ (0.1,-819.2) [-819.2|819] "deg" epas3s + SG_ SCCM_steeringAngleSensorStatus : 14|2@1+ (1,0) [0|3] "" epas3s + SG_ SCCM_supplierID : 12|2@1+ (1,0) [0|3] "" park + SG_ SCCM_steeringAngleCounter : 8|4@1+ (1,0) [0|15] "" epas3s + SG_ SCCM_steeringAngleCrc : 0|8@1+ (1,0) [0|255] "" epas3s + +BO_ 646 DI_state: 7 ETH + SG_ DI_summonInPanic : 48|1@1+ (1,0) [0|0] "" X + SG_ DI_rollPreventionState : 45|3@1+ (1,0) [0|0] "" X + SG_ DI_vehicleHoldState : 42|3@1+ (1,0) [0|0] "" X + SG_ DI_pmmStatus : 40|2@1+ (1,0) [0|0] "" X + SG_ DI_aebState : 37|3@1+ (1,0) [0|0] "" X + SG_ DI_autopilotRequest : 36|1@1+ (1,0) [0|0] "" X + SG_ DI_parkBrakeState : 32|4@1+ (1,0) [0|0] "" X + SG_ DI_autoparkState : 25|4@1+ (1,0) [0|0] "" X + SG_ DI_speedUnits : 24|1@1+ (1,0) [0|0] "" X + SG_ DI_digitalSpeed : 15|9@1+ (0.5,0) [0|0] "speed" X + SG_ DI_cruiseState : 12|3@1+ (1,0) [0|0] "" X + SG_ DI_locStatusCounter : 8|4@1+ (1,0) [0|0] "" X + SG_ DI_locStatusChecksum : 0|8@1+ (1,0) [0|0] "" X + +BO_ 785 UI_warning: 7 XXX + SG_ buckleStatus : 13|1@0+ (1,0) [0|1] "" XXX + SG_ leftBlinkerOn : 22|1@0+ (1,0) [0|1] "" XXX + SG_ rightBlinkerOn : 23|1@0+ (1,0) [0|1] "" XXX + SG_ anyDoorOpen : 28|1@0+ (1,0) [0|1] "" XXX + +BO_ 923 DAS_status: 8 PARTY + SG_ DAS_statusChecksum : 56|8@1+ (1,0) [0|255] "" aps + SG_ DAS_statusCounter : 52|4@1+ (1,0) [0|15] "" aps + SG_ DAS_summonAvailable : 51|1@1+ (1,0) [0|1] "" aps + SG_ DAS_autoLaneChangeState : 46|5@1+ (1,0) [0|31] "" aps + SG_ DAS_autopilotHandsOnState : 42|4@1+ (1,0) [0|15] "" aps + SG_ DAS_fleetSpeedState : 40|2@1+ (1,0) [0|3] "" aps + SG_ DAS_laneDepartureWarning : 37|3@1+ (1,0) [0|5] "" aps + SG_ DAS_csaState : 35|2@1+ (1,0) [0|3] "" aps + SG_ DAS_sideCollisionInhibit : 34|1@1+ (1,0) [0|1] "" aps + SG_ DAS_sideCollisionWarning : 32|2@1+ (1,0) [0|3] "" aps + SG_ DAS_sideCollisionAvoid : 30|2@1+ (1,0) [0|3] "" aps + SG_ DAS_summonRvsLeashReached : 29|1@1+ (1,0) [0|1] "" aps + SG_ DAS_summonFwdLeashReached : 28|1@1+ (1,0) [0|1] "" aps + SG_ DAS_autoparkWaitingForBrake : 26|1@1+ (1,0) [0|1] "" gtw + SG_ DAS_autoParked : 25|1@1+ (1,0) [0|1] "" aps + SG_ DAS_autoparkReady : 24|1@1+ (1,0) [0|1] "" aps + SG_ DAS_forwardCollisionWarning : 22|2@1+ (1,0) [0|3] "" aps + SG_ DAS_heaterState : 21|1@1+ (1,0) [0|1] "" gtw + SG_ DAS_visionOnlySpeedLimit : 16|5@1+ (5,0) [0|150] "kph/mph" aps + SG_ DAS_summonClearedGate : 15|1@1+ (1,0) [0|1] "" aps + SG_ DAS_summonObstacle : 14|1@1+ (1,0) [0|1] "" aps + SG_ DAS_suppressSpeedWarning : 13|1@1+ (1,0) [0|1] "" aps + SG_ DAS_fusedSpeedLimit : 8|5@1+ (5,0) [0|150] "kph/mph" aps + SG_ DAS_blindSpotRearRight : 6|2@1+ (1,0) [0|3] "" aps + SG_ DAS_blindSpotRearLeft : 4|2@1+ (1,0) [0|3] "" aps + SG_ DAS_autopilotState : 0|4@1+ (1,0) [0|15] "" aps + + + + + + + + +VAL_ 905 DAS_longCollisionWarning 7 "FCM_LONG_COLLISION_WARNING_VEHICLE_CUTIN" 0 "FCM_LONG_COLLISION_WARNING_NONE" 4 "FCM_LONG_COLLISION_WARNING_STOPSIGN_STOPLINE" 9 "FCM_LONG_COLLISION_WARNING_VEHICLE_MCVL2" 15 "FCM_LONG_COLLISION_WARNING_SNA" 8 "FCM_LONG_COLLISION_WARNING_VEHICLE_MCVL" 5 "FCM_LONG_COLLISION_WARNING_TFL_STOPLINE" 2 "FCM_LONG_COLLISION_WARNING_PEDESTRIAN" 12 "FCM_LONG_COLLISION_WARNING_VEHICLE_CIPV2" 6 "FCM_LONG_COLLISION_WARNING_VEHICLE_CIPV" 10 "FCM_LONG_COLLISION_WARNING_VEHICLE_MCVR" 3 "FCM_LONG_COLLISION_WARNING_IPSO" 1 "FCM_LONG_COLLISION_WARNING_VEHICLE_UNKNOWN" 11 "FCM_LONG_COLLISION_WARNING_VEHICLE_MCVR2" ; +VAL_ 905 DAS_ppOffsetDesiredRamp 128 "PP_NO_OFFSET" ; +VAL_ 905 DAS_driverInteractionLevel 0 "DRIVER_INTERACTING" 1 "DRIVER_NOT_INTERACTING" 2 "CONTINUED_DRIVER_NOT_INTERACTING" ; +VAL_ 905 DAS_robState 0 "ROB_STATE_INHIBITED" 2 "ROB_STATE_ACTIVE" 3 "ROB_STATE_MAPLESS" 1 "ROB_STATE_MEASURE" ; +VAL_ 905 DAS_radarTelemetry 0 "RADAR_TELEMETRY_IDLE" 1 "RADAR_TELEMETRY_NORMAL" 2 "RADAR_TELEMETRY_URGENT" ; +VAL_ 905 DAS_lssState 7 "LSS_STATE_OFF" 1 "LSS_STATE_LDW" 4 "LSS_STATE_MONITOR" 2 "LSS_STATE_LKA" 3 "LSS_STATE_ELK" 0 "LSS_STATE_FAULT" 5 "LSS_STATE_BLINDSPOT" 6 "LSS_STATE_ABORT" ; +VAL_ 905 DAS_ACC_report 12 "ACC_REPORT_LC_EXTERNAL_STATE_ABORTING" 17 "ACC_REPORT_TARGET_MCP" 11 "ACC_REPORT_LC_HANDS_ON_REQD_STRUCK_OUT" 19 "ACC_REPORT_MCVLR_DPP" 1 "ACC_REPORT_TARGET_CIPV" 15 "ACC_REPORT_RADAR_OBJ_ONE" 16 "ACC_REPORT_RADAR_OBJ_TWO" 14 "ACC_REPORT_LC_EXTERNAL_STATE_ACTIVE_RESTRICTED" 4 "ACC_REPORT_TARGET_MCVR" 20 "ACC_REPORT_MCVLR_IN_PATH" 10 "ACC_REPORT_CSA" 5 "ACC_REPORT_TARGET_CUTIN" 9 "ACC_REPORT_TARGET_TYPE_FAULT" 7 "ACC_REPORT_TARGET_TYPE_TRAFFIC_LIGHT" 6 "ACC_REPORT_TARGET_TYPE_STOP_SIGN" 24 "ACC_REPORT_BEHAVIOR_REPORT" 18 "ACC_REPORT_FLEET_SPEEDS" 2 "ACC_REPORT_TARGET_IN_FRONT_OF_CIPV" 23 "ACC_REPORT_CAMERA_ONLY" 3 "ACC_REPORT_TARGET_MCVL" 22 "ACC_REPORT_RADAR_OBJ_FIVE" 0 "ACC_REPORT_TARGET_NONE" 8 "ACC_REPORT_TARGET_TYPE_IPSO" 21 "ACC_REPORT_CIPV_CUTTING_OUT" 13 "ACC_REPORT_LC_EXTERNAL_STATE_ABORTED" ; +VAL_ 905 DAS_pmmCameraFaultReason 1 "PMM_CAMERA_BLOCKED_FRONT" 2 "PMM_CAMERA_INVALID_MIA" 0 "PMM_CAMERA_NO_FAULT" ; +VAL_ 905 DAS_pmmSysFaultReason 4 "PMM_FAULT_STEERING_ANGLE_RATE" 6 "PMM_FAULT_ROAD_TYPE" 5 "PMM_FAULT_DISABLED_BY_USER" 0 "PMM_FAULT_NONE" 1 "PMM_FAULT_DAS_DISABLED" 3 "PMM_FAULT_DI_FAULT" 2 "PMM_FAULT_SPEED" 7 "PMM_FAULT_BRAKE_PEDAL_INHIBIT" ; +VAL_ 905 DAS_pmmRadarFaultReason 2 "PMM_RADAR_INVALID_MIA" 1 "PMM_RADAR_BLOCKED_FRONT" 0 "PMM_RADAR_NO_FAULT" ; +VAL_ 905 DAS_pmmUltrasonicsFaultReason 2 "PMM_ULTRASONICS_BLOCKED_REAR" 0 "PMM_ULTRASONICS_NO_FAULT" 1 "PMM_ULTRASONICS_BLOCKED_FRONT" 3 "PMM_ULTRASONICS_BLOCKED_BOTH" 4 "PMM_ULTRASONICS_INVALID_MIA" ; +VAL_ 905 DAS_activationFailureStatus 0 "LC_ACTIVATION_IDLE" 2 "LC_ACTIVATION_FAILED_2" 1 "LC_ACTIVATION_FAILED_1" ; +VAL_ 905 DAS_pmmLoggingRequest 0 "FALSE" 1 "TRUE" ; +VAL_ 905 DAS_pmmObstacleSeverity 5 "PMM_CRASH_FRONT" 0 "PMM_NONE" 2 "PMM_IMMINENT_FRONT" 4 "PMM_CRASH_REAR" 1 "PMM_IMMINENT_REAR" 6 "PMM_ACCEL_LIMIT" 7 "PMM_SNA" 3 "PMM_BRAKE_REQUEST" ; +VAL_ 905 DAS_accSpeedLimit 1023 "SNA" 0 "NONE" ; +VAL_ 264 DI_axleSpeed -32768 "SNA" ; +VAL_ 264 DI_torqueActual -4096 "SNA" ; +VAL_ 264 DI_torqueCommand -4096 "SNA" ; +VAL_ 585 SCCM_turnIndicatorStalkStatus 3 "DOWN_1" 5 "SNA" 0 "IDLE" 1 "UP_1" 4 "DOWN_2" 2 "UP_2" ; +VAL_ 585 SCCM_washWipeButtonStatus 3 "SNA" 0 "NOT_PRESSED" 2 "2ND_DETENT" 1 "1ST_DETENT" ; +VAL_ 585 SCCM_highBeamStalkStatus 3 "SNA" 0 "IDLE" 1 "PULL" 2 "PUSH" ; +VAL_ 280 DI_trackModeState 0 "TRACK_MODE_UNAVAILABLE" 1 "TRACK_MODE_AVAILABLE" 2 "TRACK_MODE_ON" ; +VAL_ 280 DI_keepAliveRequest 1 "KEEP_ALIVE" 0 "NO_REQUEST" ; +VAL_ 280 DI_epbRequest 0 "DI_EPBREQUEST_NO_REQUEST" 1 "DI_EPBREQUEST_PARK" 2 "DI_EPBREQUEST_UNPARK" ; +VAL_ 280 DI_tractionControlMode 0 "TC_NORMAL" 1 "TC_SLIP_START" 4 "TC_ROLLS_MODE" 2 "TC_DEV_MODE_1" 5 "TC_DYNO_MODE" 3 "TC_DEV_MODE_2" ; +VAL_ 280 DI_accelPedalPos 255 "SNA" ; +VAL_ 280 DI_immobilizerState 2 "DI_IMM_STATE_AUTHENTICATING" 0 "DI_IMM_STATE_INIT_SNA" 3 "DI_IMM_STATE_DISARMED" 4 "DI_IMM_STATE_IDLE" 6 "DI_IMM_STATE_FAULT" 1 "DI_IMM_STATE_REQUEST" 5 "DI_IMM_STATE_RESET" ; +VAL_ 280 DI_gear 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" 7 "DI_GEAR_SNA" 2 "DI_GEAR_R" 3 "DI_GEAR_N" 4 "DI_GEAR_D" ; +VAL_ 280 DI_brakePedalState 2 "INVALID" 0 "OFF" 1 "ON" ; +VAL_ 280 DI_systemState 5 "DI_SYS_ENABLE" 1 "DI_SYS_IDLE" 2 "DI_SYS_STANDBY" 0 "DI_SYS_UNAVAILABLE" 3 "DI_SYS_FAULT" 4 "DI_SYS_ABORT" ; +VAL_ 697 DAS_accelMax 511 "SNA" ; +VAL_ 697 DAS_accelMin 511 "SNA" ; +VAL_ 697 DAS_jerkMax 255 "SNA" ; +VAL_ 697 DAS_jerkMin 511 "SNA" ; +VAL_ 697 DAS_aebEvent 2 "AEB_FAULT" 0 "AEB_NOT_ACTIVE" 3 "AEB_SNA" 1 "AEB_ACTIVE" ; +VAL_ 697 DAS_accState 4 "ACC_ON" 9 "APC_PAUSE" 14 "ACC_CANCEL_OUT_OF_CALIBRATION" 10 "APC_UNPARK_COMPLETE" 6 "APC_FORWARD" 3 "ACC_HOLD" 2 "ACC_CANCEL_RADAR_BLIND" 7 "APC_COMPLETE" 1 "ACC_CANCEL_CAMERA_BLIND" 8 "APC_ABORT" 13 "ACC_CANCEL_GENERIC_SILENT" 5 "APC_BACKWARD" 11 "APC_SELFPARK_START" 0 "ACC_CANCEL_GENERIC" 12 "ACC_CANCEL_PATH_NOT_CLEAR" 15 "FAULT_SNA" ; +VAL_ 697 DAS_setSpeed 4095 "SNA" ; +VAL_ 341 ESP_vehicleSpeed 1023 "ESP_VEHICLE_SPEED_SNA" ; +VAL_ 341 ESP_vehicleStandstillSts 1 "STANDSTILL" 0 "NOT_STANDSTILL" ; +VAL_ 341 ESP_wheelSpeedsQF 0 "ONE_OR_MORE_WSS_INVALID" 1 "ALL_WSS_VALID" ; +VAL_ 341 ESP_WheelRotationFrL 1 "WR_BACKWARD" 0 "WR_FORWARD" 3 "WR_NOT_DEFINABLE" 2 "WR_STANDSTILL" ; +VAL_ 341 ESP_WheelRotationFrR 1 "WR_BACKWARD" 0 "WR_FORWARD" 3 "WR_NOT_DEFINABLE" 2 "WR_STANDSTILL" ; +VAL_ 341 ESP_WheelRotationReL 1 "WR_BACKWARD" 0 "WR_FORWARD" 3 "WR_NOT_DEFINABLE" 2 "WR_STANDSTILL" ; +VAL_ 341 ESP_WheelRotationReR 1 "WR_BACKWARD" 0 "WR_FORWARD" 3 "WR_NOT_DEFINABLE" 2 "WR_STANDSTILL" ; +VAL_ 341 ESP_wheelPulseCountReR 255 "SNA" ; +VAL_ 341 ESP_wheelPulseCountReL 255 "SNA" ; +VAL_ 341 ESP_wheelPulseCountFrR 255 "SNA" ; +VAL_ 341 ESP_wheelPulseCountFrL 255 "SNA" ; +VAL_ 969 APS_apbGpioState 0 "AP_GPIO_STATE_PWR_DOWN_REBOOT" 3 "AP_GPIO_STATE_HEALTHY" 1 "AP_GPIO_STATE_DISABLED" 2 "AP_GPIO_STATE_CRITICAL" ; +VAL_ 969 APS_apbStatusMonitorState 1 "STATUS_MONITOR_STATE_PWR_OFF" 2 "STATUS_MONITOR_STATE_INIT" 7 "STATUS_MONITOR_NUM_STATES" 0 "STATUS_MONITOR_STATE_UNKNOWN" 4 "STATUS_MONITOR_STATE_CRITICAL" 6 "STATUS_MONITOR_STATE_RECOVERY" 5 "STATUS_MONITOR_STATE_SHUTTING_DOWN" 3 "STATUS_MONITOR_STATE_NOMINAL" ; +VAL_ 969 APS_eacInternalState 1 "APS_EAC_STATE_MOMENTARY" 3 "APS_EAC_STATE_AUTOPARK" 5 "APS_EAC_STATE_OVERRIDE" 4 "APS_EAC_STATE_INHIBIT" 0 "APS_EAC_STATE_INIT" 2 "APS_EAC_STATE_CONTINUOUS" 7 "APS_EAC_NUM_STATES" 6 "APS_EAC_STATE_LSS" ; +VAL_ 969 APS_appGpioState 0 "AP_GPIO_STATE_PWR_DOWN_REBOOT" 3 "AP_GPIO_STATE_HEALTHY" 1 "AP_GPIO_STATE_DISABLED" 2 "AP_GPIO_STATE_CRITICAL" ; +VAL_ 969 APS_canMaster 0 "CAN_MASTER_APS" 2 "CAN_MASTER_APB" 3 "CAN_MASTER_SNA" 1 "CAN_MASTER_APP" ; +VAL_ 969 APS_vehBehaviorState 0 "VEH_BEHAVIOR_STATE_UNKNOWN" 3 "VEH_BEHAVIOR_STATE_APS_BRIDGE_APP" 1 "VEH_BEHAVIOR_STATE_APS_AVAILABLE" 5 "VEH_BEHAVIOR_STATE_APS_FAIL_SAFE" 7 "VEH_BEHAVIOR_NUM_STATES" 2 "VEH_BEHAVIOR_STATE_APS_CONTROL" 6 "VEH_BEHAVIOR_STATE_APS_OVERRIDE" 4 "VEH_BEHAVIOR_STATE_APS_BRIDGE_APB" ; +VAL_ 969 APS_appStatusMonitorState 1 "STATUS_MONITOR_STATE_PWR_OFF" 2 "STATUS_MONITOR_STATE_INIT" 7 "STATUS_MONITOR_NUM_STATES" 0 "STATUS_MONITOR_STATE_UNKNOWN" 4 "STATUS_MONITOR_STATE_CRITICAL" 6 "STATUS_MONITOR_STATE_RECOVERY" 5 "STATUS_MONITOR_STATE_SHUTTING_DOWN" 3 "STATUS_MONITOR_STATE_NOMINAL" ; +VAL_ 925 IBST_internalState 5 "TRANSITION_TO_IDLE" 0 "NO_MODE_ACTIVE" 4 "DIAGNOSTIC" 6 "POST_DRIVE_CHECK" 1 "PRE_DRIVE_CHECK" 3 "EXTERNAL_BRAKE_REQUEST" 2 "LOCAL_BRAKE_REQUEST" ; +VAL_ 925 IBST_driverBrakeApply 1 "BRAKES_NOT_APPLIED" 2 "DRIVER_APPLYING_BRAKES" 3 "FAULT" 0 "NOT_INIT_OR_OFF" ; +VAL_ 925 IBST_iBoosterStatus 6 "IBOOSTER_ACTUATION" 4 "IBOOSTER_ACTIVE_GOOD_CHECK" 2 "IBOOSTER_FAILURE" 5 "IBOOSTER_READY" 3 "IBOOSTER_DIAGNOSTIC" 0 "IBOOSTER_OFF" 1 "IBOOSTER_INIT" ; +VAL_ 880 EPAS3S_eacStatus 7 "SNA" 2 "EAC_ACTIVE" 4 "LANE_KEEP_ASSIST" 3 "EAC_FAULT" 1 "EAC_AVAILABLE" 5 "EMERGENCY_LANE_KEEP" 0 "EAC_INHIBITED" ; +VAL_ 880 EPAS3S_handsOnLevel 1 "LEVEL_1" 0 "LEVEL_0" 3 "LEVEL_3" 2 "LEVEL_2" ; +VAL_ 880 EPAS3S_torsionBarTorque 4095 "SNA" 4094 "UNDEFINABLE_DATA" ; +VAL_ 880 EPAS3S_eacErrorCode 15 "SNA" 11 "EAC_ERROR_HIGH_TORSION_SAFETY" 4 "EAC_ERROR_TMP_FAULT" 2 "EAC_ERROR_MAX_SPEED" 7 "EAC_ERROR_HIGH_ANGLE_RATE_REQ" 0 "EAC_ERROR_IDLE" 10 "EAC_ERROR_HIGH_MMOT_SAFETY" 6 "EAC_ERROR_HIGH_ANGLE_REQ" 8 "EAC_ERROR_HIGH_ANGLE_SAFETY" 5 "EAR_ERROR_MAX_STEER_DELTA" 13 "EAC_ERROR_PINION_VEL_DIFF" 1 "EAC_ERROR_MIN_SPEED" 14 "EAC_EXTERNAL_MONITOR_INHIBIT" 12 "EAC_ERROR_LOW_ASSIST" 9 "EAC_ERROR_HIGH_ANGLE_RATE_SAFETY" 3 "EAC_ERROR_HANDS_ON" ; +VAL_ 880 EPAS3S_steeringRackForce 1023 "SNA" 1022 "NOT_IN_SPEC" ; +VAL_ 880 EPAS3S_steeringFault 0 "NO_FAULT" 1 "FAULT" ; +VAL_ 880 EPAS3S_steeringReduced 0 "NORMAL_ASSIST" 1 "REDUCED_ASSIST" ; +VAL_ 880 EPAS3S_internalSASQF 1 "IN_SPEC" 0 "UNDEFINABLE_ACCURACY" ; +VAL_ 880 EPAS3S_currentTuneMode 3 "STEERING_TUNE_RWD_COMFORT" 1 "STEERING_TUNE_DM_STANDARD" 5 "STEERING_TUNE_RWD_SPORT" 0 "STEERING_TUNE_DM_COMFORT" 4 "STEERING_TUNE_RWD_STANDARD" 2 "STEERING_TUNE_DM_SPORT" ; +VAL_ 599 DI_uiSpeedUnits 0 "DI_SPEED_MPH" 1 "DI_SPEED_KPH" ; +VAL_ 599 DI_uiSpeed 255 "DI_UI_SPEED_SNA" ; +VAL_ 599 DI_vehicleSpeed 4095 "SNA" ; +VAL_ 637 APS_eacAllow 0 "INHIBIT" 1 "ALLOW" 2 "RESERVED" 3 "SNA"; +VAL_ 1160 DAS_steeringControlType 2 "LANE_KEEP_ASSIST" 0 "NONE" 1 "ANGLE_CONTROL" 3 "EMERGENCY_LANE_KEEP" ; +VAL_ 1160 DAS_steeringAngleRequest 16384 "ZERO_ANGLE" ; +VAL_ 297 SCCM_steeringAngleValidity 3 "SNA" 2 "INIT" 0 "INVALID" 1 "VALID" ; +VAL_ 297 SCCM_steeringAngleSensorStatus 0 "OK" 1 "INIT" 2 "ERROR" 3 "ERROR_INIT" ; +VAL_ 646 DI_rollPreventionState 0 "UNAVAILABLE" 1 "STANDBY" 2 "READY" 3 "BUILD" 4 "HOLD" 5 "PARK" 6 "FAULT" 7 "INIT" ; +VAL_ 646 DI_vehicleHoldState 0 "UNAVAILABLE" 1 "STANDBY" 2 "BLEND_IN" 3 "STANDSTILL" 4 "BLEND_OUT" 5 "PARK" 6 "FAULT" 7 "INIT" ; +VAL_ 646 DI_pmmStatus 0 "INACTIVE" 1 "ACTIVE" 2 "LOGGING_ACTIVE" 3 "SNA" ; +VAL_ 646 DI_aebState 0 "UNAVAILABLE" 1 "STANDBY" 2 "ENABLED" 3 "STANDSTILL" 4 "FAULT" 7 "SNA" ; +VAL_ 646 DI_autopilotRequest 0 "IDLE" 1 "ACTIVATE" ; +VAL_ 646 DI_parkBrakeState 0 "UNAVAILABLE" 1 "RELEASED" 2 "REQUESTED" 3 "APPLIED" 4 "FAULTED" 5 "PANIC_EPB" 6 "PANIC_SKID" 7 "RELEASING" 15 "SNA" ; +VAL_ 646 DI_autoparkState 0 "UNAVAILABLE" 1 "STANDBY" 2 "STARTED" 3 "ACTIVE" 4 "COMPLETE" 5 "PAUSED" 6 "ABORTED" 7 "RESUMED" 8 "UNPARK_COMPLETE" 9 "SELFPARK_STARTED" 15 "SNA" ; +VAL_ 646 DI_speedUnits 0 "MPH" 1 "KPH" ; +VAL_ 646 DI_cruiseState 0 "UNAVAILABLE" 1 "STANDBY" 2 "ENABLED" 3 "STANDSTILL" 4 "OVERRIDE" 5 "FAULT" 6 "PRE_FAULT" 7 "PRE_CANCEL" ; +VAL_ 785 buckleStatus 1 "LATCHED" 0 "UNLATCHED" ; +VAL_ 785 anyDoorOpen 1 "OPEN" 0 "CLOSED" ; +VAL_ 923 DAS_autoLaneChangeState 5 "ALC_UNAVAILABLE_VEHICLE_SPEED" 17 "ALC_ABORT_POOR_VIEW_RANGE" 23 "ALC_BLOCKED_VEH_TTC_AND_USS_L" 0 "ALC_UNAVAILABLE_DISABLED" 26 "ALC_BLOCKED_LANE_TYPE_L" 29 "ALC_ABORT_TIMEOUT" 9 "ALC_IN_PROGRESS_L" 4 "ALC_UNAVAILABLE_EXITING_HIGHWAY" 22 "ALC_BLOCKED_VEH_TTC_L" 12 "ALC_WAITING_FOR_SIDE_OBST_TO_PASS_R" 18 "ALC_ABORT_LC_HEALTH_BAD" 28 "ALC_WAITING_HANDS_ON" 8 "ALC_AVAILABLE_BOTH" 11 "ALC_WAITING_FOR_SIDE_OBST_TO_PASS_L" 3 "ALC_UNAVAILABLE_TP_FOLLOW" 2 "ALC_UNAVAILABLE_SONICS_INVALID" 21 "ALC_UNAVAILABLE_SOLID_LANE_LINE" 24 "ALC_BLOCKED_VEH_TTC_R" 1 "ALC_UNAVAILABLE_NO_LANES" 25 "ALC_BLOCKED_VEH_TTC_AND_USS_R" 30 "ALC_ABORT_MISSION_PLAN_INVALID" 27 "ALC_BLOCKED_LANE_TYPE_R" 19 "ALC_ABORT_BLINKER_TURNED_OFF" 31 "ALC_SNA" 13 "ALC_WAITING_FOR_FWD_OBST_TO_PASS_L" 16 "ALC_ABORT_SIDE_OBSTACLE_PRESENT_R" 6 "ALC_AVAILABLE_ONLY_L" 20 "ALC_ABORT_OTHER_REASON" 15 "ALC_ABORT_SIDE_OBSTACLE_PRESENT_L" 7 "ALC_AVAILABLE_ONLY_R" 14 "ALC_WAITING_FOR_FWD_OBST_TO_PASS_R" 10 "ALC_IN_PROGRESS_R" ; +VAL_ 923 DAS_autopilotHandsOnState 8 "LC_HANDS_ON_SUSPENDED" 15 "LC_HANDS_ON_SNA" 7 "LC_HANDS_ON_REQD_STRUCK_OUT" 3 "LC_HANDS_ON_REQD_VISUAL" 4 "LC_HANDS_ON_REQD_CHIME_1" 6 "LC_HANDS_ON_REQD_SLOWING" 1 "LC_HANDS_ON_REQD_DETECTED" 2 "LC_HANDS_ON_REQD_NOT_DETECTED" 5 "LC_HANDS_ON_REQD_CHIME_2" 0 "LC_HANDS_ON_NOT_REQD" ; +VAL_ 923 DAS_fleetSpeedState 0 "FLEETSPEED_UNAVAILABLE" 1 "FLEETSPEED_AVAILABLE" 2 "FLEETSPEED_ACTIVE" 3 "FLEETSPEED_HOLD" ; +VAL_ 923 DAS_laneDepartureWarning 5 "SNA" 0 "NONE" 2 "RIGHT_WARNING" 4 "RIGHT_WARNING_SEVERE" 3 "LEFT_WARNING_SEVERE" 1 "LEFT_WARNING" ; +VAL_ 923 DAS_csaState 1 "CSA_EXTERNAL_STATE_AVAILABLE" 3 "CSA_EXTERNAL_STATE_HOLD" 2 "CSA_EXTERNAL_STATE_ENABLE" 0 "CSA_EXTERNAL_STATE_UNAVAILABLE" ; +VAL_ 923 DAS_sideCollisionInhibit 0 "NO_INHIBIT" 1 "INHIBIT" ; +VAL_ 923 DAS_sideCollisionWarning 0 "NONE" 2 "WARN_RIGHT" 1 "WARN_LEFT" 3 "WARN_LEFT_RIGHT" ; +VAL_ 923 DAS_sideCollisionAvoid 3 "SNA" 0 "NONE" 1 "AVOID_LEFT" 2 "AVOID_RIGHT" ; +VAL_ 923 DAS_autoparkReady 0 "AUTOPARK_UNAVAILABLE" 1 "AUTOPARK_READY" ; +VAL_ 923 DAS_forwardCollisionWarning 3 "SNA" 0 "NONE" 1 "FORWARD_COLLISION_WARNING" ; +VAL_ 923 DAS_heaterState 0 "HEATER_OFF_SNA" 1 "HEATER_ON" ; +VAL_ 923 DAS_visionOnlySpeedLimit 31 "NONE" 0 "UNKNOWN_SNA" ; +VAL_ 923 DAS_suppressSpeedWarning 1 "Suppress_Speed_Warning" 0 "Do_Not_Suppress" ; +VAL_ 923 DAS_fusedSpeedLimit 31 "NONE" 0 "UNKNOWN_SNA" ; +VAL_ 923 DAS_blindSpotRearRight 3 "SNA" 0 "NO_WARNING" 1 "WARNING_LEVEL_1" 2 "WARNING_LEVEL_2" ; +VAL_ 923 DAS_blindSpotRearLeft 3 "SNA" 0 "NO_WARNING" 1 "WARNING_LEVEL_1" 2 "WARNING_LEVEL_2" ; +VAL_ 923 DAS_autopilotState 15 "SNA" 8 "ABORTING" 3 "ACTIVE_NOMINAL" 0 "DISABLED" 4 "ACTIVE_RESTRICTED" 5 "ACTIVE_NAV" 14 "FAULT" 1 "UNAVAILABLE" 9 "ABORTED" 2 "AVAILABLE" ; + + + diff --git a/opendbc_repo/opendbc/dbc/tesla_model3_vehicle.dbc b/opendbc_repo/opendbc/dbc/tesla_model3_vehicle.dbc new file mode 100644 index 000000000000000..604db8fe27c277c --- /dev/null +++ b/opendbc_repo/opendbc/dbc/tesla_model3_vehicle.dbc @@ -0,0 +1,339 @@ +VERSION "" + + +BU_: CH DIPF DIPR ETH FC HVI HVS PARTY SDCV VEH VIRT + + +BO_ 962 VCLEFT_switchStatus: 8 VEH + SG_ VCLEFT_frontBuckleSwitch m0: 48|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackUpLF m0: 32|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontSeatTrackBack m0: 8|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoDownLF m0: 35|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackDownRR m0: 46|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoUpRR m0: 45|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoDownRR m0: 47|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_rightMirrorTilt m0: 5|3@1+ (1,0) [0|4] "" vcright + SG_ VCLEFT_btnWindowSwPackUpRR m0: 44|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontOccupancySwitch m0: 50|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_swcRightTiltLeft m1: 8|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_rearRightOccupancySwitch m0: 58|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackDownLF m0: 34|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoUpLF m0: 33|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_swcLeftTiltRight m1: 3|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_frontSeatBackrestForward m0: 22|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_swcRightTiltRight m1: 10|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_swcLeftScrollTicks m1: 16|6@1- (1,0) [-32|31] "" das + SG_ VCLEFT_btnWindowUpLR m1: 32|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowAutoDownLR m1: 35|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackDownRF m0: 42|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoUpRF m0: 41|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontSeatLumbarIn m0: 28|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatLiftUp m0: 18|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackDownLR m0: 38|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoUpLR m0: 37|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontSeatLumbarDown m0: 24|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_driverPresent m0: 4|1@1+ (1,0) [0|1] "" das + SG_ VCLEFT_frontSeatTiltDown m0: 12|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatTrackForward m0: 10|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_rearLeftBuckleSwitch m0: 52|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_hazardButtonPressed m0: 3|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_swcRightScrollTicks m1: 24|6@1- (1,0) [-32|31] "" das + SG_ VCLEFT_swcRightPressed m1: 12|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_frontSeatLumbarOut m0: 30|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_brakePressed m0: 60|1@1+ (1,0) [0|1] "" di + SG_ VCLEFT_swcLeftTiltLeft m1: 14|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_swcLeftPressed m1: 5|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_btnWindowSwPackUpLR m0: 36|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontSeatTiltUp m0: 14|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_rearLeftOccupancySwitch m0: 56|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatBackrestBack m0: 20|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoDownLR m0: 39|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_rearCenterOccupancySwitch m0: 54|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatLumbarUp m0: 26|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatLiftDown m0: 16|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_hornSwitchPressed m0: 2|1@1+ (1,0) [0|1] "" app + SG_ VCLEFT_btnWindowSwPackUpRF m0: 40|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowAutoUpLR m1: 33|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoDownRF m0: 43|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_switchStatusIndex M: 0|2@1+ (1,0) [0|2] "" X + SG_ VCLEFT_btnWindowDownLR m1: 34|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_rearHVACButtonPressed m0: 61|1@1+ (1,0) [0|1] "" gtw + +BO_ 259 VCRIGHT_doorStatus: 8 VEH + SG_ VCRIGHT_reservedForBackCompat : 28|2@1+ (1,0) [0|3] "" X + SG_ VCRIGHT_trunkLatchStatus : 56|4@1+ (1,0) [0|8] "" di + SG_ VCRIGHT_mirrorFoldState : 52|3@1+ (1,0) [0|4] "" gtw + SG_ VCRIGHT_rearLatchStatus : 4|4@1+ (1,0) [0|8] "" aps + SG_ VCRIGHT_mirrorTiltYPosition : 41|8@1+ (0.02,0) [0|5] "V" gtw + SG_ VCRIGHT_frontRelActuatorSwitch : 12|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_mirrorRecallState : 60|3@1+ (1,0) [0|5] "" gtw + SG_ VCRIGHT_frontIntSwitchPressed : 31|1@1+ (1,0) [0|1] "" aps + SG_ VCRIGHT_mirrorState : 49|3@1+ (1,0) [0|4] "" gtw + SG_ VCRIGHT_rearRelActuatorSwitch : 13|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_frontHandlePulledPersist : 30|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_mirrorTiltXPosition : 33|8@1+ (0.02,0) [0|5] "V" gtw + SG_ VCRIGHT_mirrorDipped : 63|1@1+ (1,0) [0|1] "" X + SG_ VCRIGHT_frontHandlePulled : 10|1@1+ (1,0) [0|1] "" aps + SG_ VCRIGHT_frontLatchStatus : 0|4@1+ (1,0) [0|8] "" aps + SG_ VCRIGHT_rearHandlePulled : 11|1@1+ (1,0) [0|1] "" aps + SG_ VCRIGHT_frontHandlePWM : 14|7@1+ (1,0) [0|100] "%" X + SG_ VCRIGHT_frontLatchSwitch : 8|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_rearLatchSwitch : 9|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_rearHandlePWM : 21|7@1+ (1,0) [0|100] "%" X + SG_ VCRIGHT_rearIntSwitchPressed : 32|1@1+ (1,0) [0|1] "" aps + +BO_ 585 SCCM_leftStalk: 3 VEH + SG_ SCCM_leftStalkCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ SCCM_washWipeButtonStatus : 14|2@1+ (1,0) [0|3] "" das + SG_ SCCM_turnIndicatorStalkStatus : 16|3@1+ (1,0) [0|5] "" das + SG_ SCCM_leftStalkCrc : 0|8@1+ (1,0) [0|255] "" X + SG_ SCCM_leftStalkReserved1 : 19|5@1+ (1,0) [0|31] "" X + SG_ SCCM_highBeamStalkStatus : 12|2@1+ (1,0) [0|3] "" das + +BO_ 280 DI_systemStatus: 8 VEH + SG_ DI_epbRequest : 44|2@1+ (1,0) [0|2] "" epbl + SG_ DI_systemStatusCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ DI_proximity : 46|1@1+ (1,0) [0|1] "" bms + SG_ DI_keepAliveRequest : 47|1@1+ (1,0) [0|1] "" bms + SG_ DI_accelPedalPos : 32|8@1+ (0.4,0) [0|100] "%" vcfront + SG_ DI_gear : 21|3@1+ (1,0) [0|7] "" gtw + SG_ DI_tractionControlMode : 40|3@1+ (1,0) [0|5] "" X + SG_ DI_trackModeState : 48|2@1+ (1,0) [0|2] "" gtw + SG_ DI_regenLight : 26|1@1+ (1,0) [0|1] "" vcleft + SG_ DI_systemState : 16|3@1+ (1,0) [0|5] "" epbl + SG_ DI_immobilizerState : 27|3@1+ (1,0) [0|6] "" X + SG_ DI_systemStatusChecksum : 0|8@1+ (1,0) [0|255] "" X + SG_ DI_brakePedalState : 19|2@1+ (1,0) [0|2] "" vcleft + +BO_ 835 VCRIGHT_status: 8 VEH + SG_ VCRIGHT_5AVoltage : 18|10@1+ (0.005443676098,0) [0|5.56888] "V" gtw + SG_ VCRIGHT_loadShedPriority : 0|8@1+ (1,0) [0|255] "" X + SG_ VCRIGHT_rearDefrostState : 11|3@1+ (1,0) [0|4] "" gtw + SG_ VCRIGHT_vbatProt : 28|12@1+ (0.005443676098,0) [0|22.29185] "V" gtw + SG_ VCRIGHT_vehiclePowerStateDBG : 8|2@1+ (1,0) [0|3] "" gtw + SG_ VCRIGHT_swEnStatus : 10|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_mirrorHeatState : 14|3@1+ (1,0) [0|4] "" X + SG_ VCRIGHT_OTAState : 17|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_footwellLightCurrent : 40|12@1- (0.1,0) [-204.8|204.7] "mA" X + SG_ VCRIGHT_pcbaTemperature : 52|11@1+ (0.125,-40) [-40|150] "degC" gtw + +BO_ 553 SCCM_rightStalk: 3 VEH + SG_ SCCM_rightStalkCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ SCCM_rightStalkCrc : 0|8@1+ (1,0) [0|255] "" X + SG_ SCCM_rightStalkReserved1 : 15|1@1+ (1,0) [0|1] "" X + SG_ SCCM_parkButtonStatus : 16|2@1+ (1,0) [0|3] "" das + SG_ SCCM_rightStalkReserved2 : 18|6@1+ (1,0) [0|63] "" X + SG_ SCCM_rightStalkStatus : 12|3@1+ (1,0) [0|6] "" das + +BO_ 297 SCCM_steeringAngleSensor: 8 VEH + SG_ SCCM_steeringAngleValidity : 30|2@1+ (1,0) [0|3] "" gtw + SG_ SCCM_supplierID : 12|2@1+ (1,0) [0|3] "" gtw + SG_ SCCM_steeringAngleSensorReservd1 : 46|2@1+ (1,0) [0|3] "" X + SG_ SCCM_steeringAngleCrc : 0|8@1+ (1,0) [0|255] "" gtw + SG_ SCCM_steeringAngleSensorStatus : 14|2@1+ (1,0) [0|3] "" aps + SG_ SCCM_steeringAngleSpeed : 32|14@1+ (0.5,-4096) [-4096|4095.5] "deg/s" das + SG_ SCCM_steeringAngle : 16|14@1+ (0.1,-819.2) [-819.2|819] "deg" aps + SG_ SCCM_steeringAngleSensorReservd2 : 48|8@1+ (1,0) [0|255] "" X + SG_ SCCM_steeringAngleCounter : 8|4@1+ (1,0) [0|15] "" gtw + SG_ SCCM_steeringAngleSensorReservd3 : 56|8@1+ (1,0) [0|255] "" X + +BO_ 258 VCLEFT_doorStatus: 8 VEH + SG_ VCLEFT_mirrorDipped : 61|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_frontHandlePulledPersist : 62|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_mirrorRecallState : 55|3@1+ (1,0) [0|5] "" gtw + SG_ VCLEFT_rearIntSwitchPressed : 32|1@1+ (1,0) [0|1] "" aps + SG_ VCLEFT_rearLatchSwitch : 9|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_rearHandlePWM : 24|7@1+ (1,0) [0|100] "%" X + SG_ VCLEFT_frontLatchSwitch : 8|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontHandlePWM : 16|7@1+ (1,0) [0|100] "%" X + SG_ VCLEFT_rearHandlePulled : 11|1@1+ (1,0) [0|1] "" aps + SG_ VCLEFT_rearLatchStatus : 4|4@1+ (1,0) [0|8] "" aps + SG_ VCLEFT_frontHandlePulled : 10|1@1+ (1,0) [0|1] "" aps + SG_ VCLEFT_mirrorTiltXPosition : 33|8@1+ (0.02,0) [0|5] "V" gtw + SG_ VCLEFT_mirrorState : 49|3@1+ (1,0) [0|4] "" gtw + SG_ VCLEFT_frontIntSwitchPressed : 31|1@1+ (1,0) [0|1] "" aps + SG_ VCLEFT_rearRelActuatorSwitch : 13|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_mirrorHeatState : 58|3@1+ (1,0) [0|4] "" X + SG_ VCLEFT_frontRelActuatorSwitch : 12|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_mirrorTiltYPosition : 41|8@1+ (0.02,0) [0|5] "V" gtw + SG_ VCLEFT_frontLatchStatus : 0|4@1+ (1,0) [0|8] "" aps + SG_ VCLEFT_mirrorFoldState : 52|3@1+ (1,0) [0|4] "" gtw + + +BO_ 568 STW_ACTN_RQ: 8 STW + SG_ SpdCtrlLvr_Stat : 0|6@1+ (1,0) [0|0] "" NEO + SG_ VSL_Enbl_Rq : 6|1@1+ (1,0) [0|0] "" NEO + SG_ SpdCtrlLvrStat_Inv : 7|1@1+ (1,0) [0|0] "" NEO + SG_ DTR_Dist_Rq : 8|8@1+ (1,0) [0|200] "" NEO + SG_ TurnIndLvr_Stat : 16|2@1+ (1,0) [0|0] "" NEO + SG_ HiBmLvr_Stat : 18|2@1+ (1,0) [0|0] "" NEO + SG_ WprWashSw_Psd : 20|2@1+ (1,0) [0|0] "" NEO + SG_ WprWash_R_Sw_Posn_V2 : 22|2@1+ (1,0) [0|0] "" NEO + SG_ StW_Lvr_Stat : 24|3@1+ (1,0) [0|0] "" NEO + SG_ StW_Cond_Flt : 27|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Cond_Psd : 28|2@1+ (1,0) [0|0] "" NEO + SG_ HrnSw_Psd : 30|2@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw00_Psd : 32|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw01_Psd : 33|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw02_Psd : 34|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw03_Psd : 35|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw04_Psd : 36|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw05_Psd : 37|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw06_Psd : 38|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw07_Psd : 39|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw08_Psd : 40|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw09_Psd : 41|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw10_Psd : 42|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw11_Psd : 43|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw12_Psd : 44|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw13_Psd : 45|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw14_Psd : 46|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw15_Psd : 47|1@1+ (1,0) [0|0] "" NEO + SG_ WprSw6Posn : 48|3@1+ (1,0) [0|0] "" NEO + SG_ MC_STW_ACTN_RQ : 52|4@1+ (1,0) [0|15] "" NEO + SG_ CRC_STW_ACTN_RQ : 56|8@1+ (1,0) [0|0] "" NEO + +BO_ 1001 DAS_bodyControls: 8 VEH + SG_ DAS_headlightRequest : 0|2@1+ (1,0) [0|3] "" aps + SG_ DAS_hazardLightRequest : 2|2@1+ (1,0) [0|3] "" aps + SG_ DAS_wiperSpeed : 4|4@1+ (1,0) [0|15] "" aps + SG_ DAS_turnIndicatorRequest : 8|2@1+ (1,0) [0|3] "" aps + SG_ DAS_highLowBeamDecision : 10|2@1+ (1,0) [0|3] "" aps + SG_ DAS_heaterRequest : 12|2@1+ (1,0) [0|2] "" aps + SG_ DAS_turnIndicatorRequestReason : 17|4@1+ (1,0) [0|8] "" aps + SG_ DAS_autopilotActive : 24|1@1+ (1,0) [0|1] "" XXX + SG_ DAS_accActive : 29|1@1+ (1,0) [0|1] "" XXX + SG_ DAS_bodyControlsCounter : 52|4@1+ (1,0) [0|15] "" aps + SG_ DAS_bodyControlsChecksum : 56|8@1+ (1,0) [0|255] "" aps + +BO_ 1013 ID3F5VCFRONT_lighting: 8 VEH + SG_ VCFRONT_lowBeamsCalibrated : 62|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_lowBeamsOnForDRL : 61|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_simLatchingStalk : 59|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_highBeamSwitchActive : 58|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_parkRightStatus : 56|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_parkLeftStatus : 54|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_turnSignalRightStatus : 52|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_turnSignalLeftStatus : 50|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_sideRepeaterRightStatus : 48|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_sideRepeaterLeftStatus : 46|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_sideMarkersStatus : 44|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_fogRightStatus : 42|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_fogLeftStatus : 40|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_DRLRightStatus : 38|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_DRLLeftStatus : 36|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_highBeamRightStatus : 34|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_highBeamLeftStatus : 32|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_lowBeamRightStatus : 30|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_lowBeamLeftStatus : 28|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_hazardSwitchBacklight : 27|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_seeYouHomeLightingReq : 26|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_approachLightingRequest : 25|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_courtesyLightingRequest : 24|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_switchLightingBrightness : 16|8@1+ (0.5,0) [0|127] "%" Receiver + SG_ VCFRONT_ambientLightingBrightnes : 8|8@1+ (0.5,0) [0|127] "%" Receiver + SG_ VCFRONT_hazardLightRequest : 4|4@1+ (1,0) [0|8] "" Receiver + SG_ VCFRONT_indicatorRightRequest : 2|2@1+ (1,0) [0|2] "" Receiver + SG_ VCFRONT_indicatorLeftRequest : 0|2@1+ (1,0) [0|2] "" Receiver + +VAL_ 568 SpdCtrlLvr_Stat 32 "DN_1ST" 16 "UP_1ST" 8 "DN_2ND" 4 "UP_2ND" 2 "RWD" 1 "FWD" 0 "IDLE" ; +VAL_ 568 DTR_Dist_Rq 255 "SNA" 200 "ACC_DIST_7" 166 "ACC_DIST_6" 133 "ACC_DIST_5" 100 "ACC_DIST_4" 66 "ACC_DIST_3" 33 "ACC_DIST_2" 0 "ACC_DIST_1" ; +VAL_ 568 TurnIndLvr_Stat 3 "SNA" 2 "RIGHT" 1 "LEFT" 0 "IDLE" ; +VAL_ 568 HiBmLvr_Stat 3 "SNA" 2 "HIBM_FLSH_ON_PSD" 1 "HIBM_ON_PSD" 0 "IDLE" ; +VAL_ 568 WprWashSw_Psd 3 "SNA" 2 "WASH" 1 "TIPWIPE" 0 "NPSD" ; +VAL_ 568 WprWash_R_Sw_Posn_V2 3 "SNA" 2 "WASH" 1 "INTERVAL" 0 "OFF" ; +VAL_ 568 StW_Lvr_Stat 4 "STW_BACK" 3 "STW_FWD" 2 "STW_DOWN" 1 "STW_UP" 0 "NPSD" ; +VAL_ 568 StW_Cond_Psd 3 "SNA" 2 "DOWN" 1 "UP" 0 "NPSD" ; +VAL_ 568 HrnSw_Psd 3 "SNA" 2 "NDEF2" 1 "PSD" 0 "NPSD" ; +VAL_ 568 StW_Sw00_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 568 StW_Sw01_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 568 StW_Sw03_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 568 StW_Sw04_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 568 WprSw6Posn 7 "SNA" 6 "STAGE2" 5 "STAGE1" 4 "INTERVAL4" 3 "INTERVAL3" 2 "INTERVAL2" 1 "INTERVAL1" 0 "OFF" ; + +VAL_ 1001 DAS_headlightRequest 3 "DAS_HEADLIGHT_REQUEST_INVALID" 1 "DAS_HEADLIGHT_REQUEST_ON" 0 "DAS_HEADLIGHT_REQUEST_OFF"; +VAL_ 1001 DAS_hazardLightRequest 3 "DAS_REQUEST_HAZARDS_SNA" 2 "DAS_REQUEST_HAZARDS_UNUSED" 0 "DAS_REQUEST_HAZARDS_OFF" 1 "DAS_REQUEST_HAZARDS_ON"; +VAL_ 1001 DAS_wiperSpeed 3 "DAS_WIPER_SPEED_3" 12 "DAS_WIPER_SPEED_12" 8 "DAS_WIPER_SPEED_8" 14 "DAS_WIPER_SPEED_14" 5 "DAS_WIPER_SPEED_5" 13 "DAS_WIPER_SPEED_13" 2 "DAS_WIPER_SPEED_2" 0 "DAS_WIPER_SPEED_OFF" 4 "DAS_WIPER_SPEED_4" 1 "DAS_WIPER_SPEED_1" 15 "DAS_WIPER_SPEED_INVALID" 10 "DAS_WIPER_SPEED_10" 11 "DAS_WIPER_SPEED_11" 7 "DAS_WIPER_SPEED_7" 9 "DAS_WIPER_SPEED_9" 6 "DAS_WIPER_SPEED_6"; +VAL_ 1001 DAS_turnIndicatorRequest 0 "DAS_TURN_INDICATOR_NONE" 2 "DAS_TURN_INDICATOR_RIGHT" 3 "DAS_TURN_INDICATOR_CANCEL" 1 "DAS_TURN_INDICATOR_LEFT"; +VAL_ 1001 DAS_highLowBeamDecision 2 "DAS_HIGH_BEAM_ON" 1 "DAS_HIGH_BEAM_OFF" 3 "DAS_HIGH_BEAM_SNA" 0 "DAS_HIGH_BEAM_UNDECIDED"; +VAL_ 1001 DAS_heaterRequest 0 "DAS_HEATER_SNA" 2 "DAS_HEATER_ON" 1 "DAS_HEATER_OFF"; +VAL_ 1001 DAS_turnIndicatorRequestReason 8 "DAS_ACTIVE_COMMANDED_LANE_CHANGE" 4 "DAS_CANCEL_LANE_CHANGE" 6 "DAS_ACTIVE_MERGE" 2 "DAS_ACTIVE_SPEED_LANE_CHANGE" 5 "DAS_CANCEL_FORK" 0 "DAS_NONE" 3 "DAS_ACTIVE_FORK" 7 "DAS_CANCEL_MERGE" 1 "DAS_ACTIVE_NAV_LANE_CHANGE"; + +VAL_ 1013 VCFRONT_DRLLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_DRLRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_ambientLightingBrightnes 255 "SNA" ; +VAL_ 1013 VCFRONT_fogLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_fogRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_hazardLightRequest 1 "HAZARD_REQUEST_BUTTON" 6 "HAZARD_REQUEST_CAR_ALARM" 5 "HAZARD_REQUEST_CRASH" 7 "HAZARD_REQUEST_DAS" 2 "HAZARD_REQUEST_LOCK" 4 "HAZARD_REQUEST_MISLOCK" 0 "HAZARD_REQUEST_NONE" 8 "HAZARD_REQUEST_UDS" 3 "HAZARD_REQUEST_UNLOCK" ; +VAL_ 1013 VCFRONT_highBeamLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_highBeamRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_indicatorLeftRequest 2 "TURN_SIGNAL_ACTIVE_HIGH" 1 "TURN_SIGNAL_ACTIVE_LOW" 0 "TURN_SIGNAL_OFF" ; +VAL_ 1013 VCFRONT_indicatorRightRequest 2 "TURN_SIGNAL_ACTIVE_HIGH" 1 "TURN_SIGNAL_ACTIVE_LOW" 0 "TURN_SIGNAL_OFF" ; +VAL_ 1013 VCFRONT_lowBeamLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_lowBeamRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_parkLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_parkRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_sideMarkersStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_sideRepeaterLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_sideRepeaterRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_simLatchingStalk 0 "SIMULATED_LATCHING_STALK_IDLE" 1 "SIMULATED_LATCHING_STALK_LEFT" 2 "SIMULATED_LATCHING_STALK_RIGHT" 3 "SIMULATED_LATCHING_STALK_SNA" ; +VAL_ 1013 VCFRONT_switchLightingBrightness 255 "SNA" ; +VAL_ 1013 VCFRONT_turnSignalLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_turnSignalRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 962 VCLEFT_frontBuckleSwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatTrackBack 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rightMirrorTilt 4 "MIRROR_TILT_LEFT" 2 "MIRROR_TILT_UP" 3 "MIRROR_TILT_RIGHT" 0 "MIRROR_TILT_STOP" 1 "MIRROR_TILT_DOWN"; +VAL_ 962 VCLEFT_frontOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcRightTiltLeft 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rearRightOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcLeftTiltRight 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatBackrestForward 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcRightTiltRight 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLumbarIn 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLiftUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLumbarDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatTiltDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatTrackForward 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rearLeftBuckleSwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcRightPressed 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLumbarOut 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcLeftTiltLeft 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcLeftPressed 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatTiltUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rearLeftOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatBackrestBack 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rearCenterOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLumbarUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLiftDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_switchStatusIndex 1 "VCLEFT_SWITCH_STATUS_INDEX_1" 2 "VCLEFT_SWITCH_STATUS_INDEX_INVALID" 0 "VCLEFT_SWITCH_STATUS_INDEX_0"; +VAL_ 259 VCRIGHT_trunkLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 259 VCRIGHT_mirrorFoldState 4 "MIRROR_FOLD_STATE_UNFOLDING" 1 "MIRROR_FOLD_STATE_FOLDED" 3 "MIRROR_FOLD_STATE_FOLDING" 0 "MIRROR_FOLD_STATE_UNKNOWN" 2 "MIRROR_FOLD_STATE_UNFOLDED"; +VAL_ 259 VCRIGHT_rearLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 259 VCRIGHT_mirrorRecallState 5 "MIRROR_RECALL_STATE_RECALLING_STOPPED" 2 "MIRROR_RECALL_STATE_RECALLING_AXIS_2" 0 "MIRROR_RECALL_STATE_INIT" 3 "MIRROR_RECALL_STATE_RECALLING_COMPLETE" 4 "MIRROR_RECALL_STATE_RECALLING_FAILED" 1 "MIRROR_RECALL_STATE_RECALLING_AXIS_1"; +VAL_ 259 VCRIGHT_mirrorState 3 "MIRROR_STATE_FOLD_UNFOLD" 1 "MIRROR_STATE_TILT_X" 0 "MIRROR_STATE_IDLE" 2 "MIRROR_STATE_TILT_Y" 4 "MIRROR_STATE_RECALL"; +VAL_ 259 VCRIGHT_frontLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 585 SCCM_washWipeButtonStatus 3 "SNA" 0 "NOT_PRESSED" 2 "2ND_DETENT" 1 "1ST_DETENT"; +VAL_ 585 SCCM_turnIndicatorStalkStatus 3 "DOWN_1" 5 "SNA" 0 "IDLE" 1 "UP_1" 4 "DOWN_2" 2 "UP_2"; +VAL_ 585 SCCM_highBeamStalkStatus 3 "SNA" 0 "IDLE" 1 "PULL" 2 "PUSH"; +VAL_ 280 DI_epbRequest 0 "DI_EPBREQUEST_NO_REQUEST" 1 "DI_EPBREQUEST_PARK" 2 "DI_EPBREQUEST_UNPARK"; +VAL_ 280 DI_keepAliveRequest 1 "KEEP_ALIVE" 0 "NO_REQUEST"; +VAL_ 280 DI_accelPedalPos 255 "SNA"; +VAL_ 280 DI_gear 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" 7 "DI_GEAR_SNA" 2 "DI_GEAR_R" 3 "DI_GEAR_N" 4 "DI_GEAR_D"; +VAL_ 280 DI_tractionControlMode 0 "TC_NORMAL" 1 "TC_SLIP_START" 4 "TC_ROLLS_MODE" 2 "TC_DEV_MODE_1" 5 "TC_DYNO_MODE" 3 "TC_DEV_MODE_2"; +VAL_ 280 DI_trackModeState 0 "TRACK_MODE_UNAVAILABLE" 1 "TRACK_MODE_AVAILABLE" 2 "TRACK_MODE_ON"; +VAL_ 280 DI_systemState 5 "DI_SYS_ENABLE" 1 "DI_SYS_IDLE" 2 "DI_SYS_STANDBY" 0 "DI_SYS_UNAVAILABLE" 3 "DI_SYS_FAULT" 4 "DI_SYS_ABORT"; +VAL_ 280 DI_immobilizerState 2 "DI_IMM_STATE_AUTHENTICATING" 0 "DI_IMM_STATE_INIT_SNA" 3 "DI_IMM_STATE_DISARMED" 4 "DI_IMM_STATE_IDLE" 6 "DI_IMM_STATE_FAULT" 1 "DI_IMM_STATE_REQUEST" 5 "DI_IMM_STATE_RESET"; +VAL_ 280 DI_brakePedalState 2 "INVALID" 0 "OFF" 1 "ON"; +VAL_ 835 VCRIGHT_rearDefrostState 2 "HEATER_STATE_OFF" 4 "HEATER_STATE_FAULT" 1 "HEATER_STATE_ON" 0 "HEATER_STATE_SNA" 3 "HEATER_STATE_OFF_UNAVAILABLE"; +VAL_ 835 VCRIGHT_vehiclePowerStateDBG 3 "VEHICLE_POWER_STATE_DRIVE" 1 "VEHICLE_POWER_STATE_CONDITIONING" 2 "VEHICLE_POWER_STATE_ACCESSORY" 0 "VEHICLE_POWER_STATE_OFF"; +VAL_ 835 VCRIGHT_mirrorHeatState 2 "HEATER_STATE_OFF" 4 "HEATER_STATE_FAULT" 1 "HEATER_STATE_ON" 0 "HEATER_STATE_SNA" 3 "HEATER_STATE_OFF_UNAVAILABLE"; +VAL_ 553 SCCM_parkButtonStatus 3 "SNA" 0 "NOT_PRESSED" 2 "INIT" 1 "PRESSED"; +VAL_ 553 SCCM_rightStalkStatus 3 "DOWN_1" 6 "SNA" 0 "IDLE" 5 "INIT" 1 "UP_1" 4 "DOWN_2" 2 "UP_2"; +VAL_ 297 SCCM_steeringAngleValidity 3 "SNA" 2 "INIT" 0 "INVALID" 1 "VALID"; +VAL_ 297 SCCM_steeringAngleSensorStatus 0 "OK" 1 "INIT" 2 "ERROR" 3 "ERROR_INIT"; +VAL_ 258 VCLEFT_mirrorRecallState 5 "MIRROR_RECALL_STATE_RECALLING_STOPPED" 2 "MIRROR_RECALL_STATE_RECALLING_AXIS_2" 0 "MIRROR_RECALL_STATE_INIT" 3 "MIRROR_RECALL_STATE_RECALLING_COMPLETE" 4 "MIRROR_RECALL_STATE_RECALLING_FAILED" 1 "MIRROR_RECALL_STATE_RECALLING_AXIS_1"; +VAL_ 258 VCLEFT_rearLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 258 VCLEFT_mirrorState 3 "MIRROR_STATE_FOLD_UNFOLD" 1 "MIRROR_STATE_TILT_X" 0 "MIRROR_STATE_IDLE" 2 "MIRROR_STATE_TILT_Y" 4 "MIRROR_STATE_RECALL"; +VAL_ 258 VCLEFT_mirrorHeatState 2 "HEATER_STATE_OFF" 4 "HEATER_STATE_FAULT" 1 "HEATER_STATE_ON" 0 "HEATER_STATE_SNA" 3 "HEATER_STATE_OFF_UNAVAILABLE"; +VAL_ 258 VCLEFT_frontLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 258 VCLEFT_mirrorFoldState 4 "MIRROR_FOLD_STATE_UNFOLDING" 1 "MIRROR_FOLD_STATE_FOLDED" 3 "MIRROR_FOLD_STATE_FOLDING" 0 "MIRROR_FOLD_STATE_UNKNOWN" 2 "MIRROR_FOLD_STATE_UNFOLDED"; diff --git a/opendbc/tesla_powertrain.dbc b/opendbc_repo/opendbc/dbc/tesla_powertrain.dbc similarity index 100% rename from opendbc/tesla_powertrain.dbc rename to opendbc_repo/opendbc/dbc/tesla_powertrain.dbc diff --git a/opendbc/tesla_radar_bosch_generated.dbc b/opendbc_repo/opendbc/dbc/tesla_radar_bosch_generated.dbc similarity index 100% rename from opendbc/tesla_radar_bosch_generated.dbc rename to opendbc_repo/opendbc/dbc/tesla_radar_bosch_generated.dbc diff --git a/opendbc/tesla_radar_continental_generated.dbc b/opendbc_repo/opendbc/dbc/tesla_radar_continental_generated.dbc similarity index 100% rename from opendbc/tesla_radar_continental_generated.dbc rename to opendbc_repo/opendbc/dbc/tesla_radar_continental_generated.dbc diff --git a/opendbc_repo/opendbc/dbc/toyota_2017_ref_pt.dbc b/opendbc_repo/opendbc/dbc/toyota_2017_ref_pt.dbc new file mode 100644 index 000000000000000..17cd8f1b36900ec --- /dev/null +++ b/opendbc_repo/opendbc/dbc/toyota_2017_ref_pt.dbc @@ -0,0 +1,1638 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: AFS BSR CGW CSR DS1 FCM FRD KSS MAV SCS Vector__XXX + + +BO_ 1196 ABG1D50: 8 CGW + SG_ DRABG01 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG02 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG03 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG04 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG05 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG06 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG07 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG08 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1212 ABG1D51: 8 CGW + SG_ DRABG09 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG10 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG11 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG12 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG13 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG14 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG15 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRABG16 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 945 ABG1S01: 8 CGW + SG_ CDT : 22|3@0+ (1,0) [0|0] "" DS1 + SG_ AB : 19|2@0+ (1,0) [0|0] "" DS1 + SG_ DBKLAB : 17|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PODT : 27|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PBKLAB : 25|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ EDRTRG : 44|2@0+ (1,0) [0|0] "" DS1 + +BO_ 836 ACC1F01: 8 DS1 + SG_ DSS1GDRV : 7|10@0- (0.1,0) [0|0] "m/s^2" Vector__XXX + SG_ DS1STAT2 : 13|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ DS1STBK2 : 10|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSWAR : 18|1@0+ (1,0) [0|0] "" FCM + SG_ PCSALM : 17|1@0+ (1,0) [0|0] "" FCM + SG_ PCSOPR : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSABK : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PBATRGR : 30|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PPTRGR : 28|1@0+ (1,0) [0|0] "" FCM + SG_ IBTRGR : 27|1@0+ (1,0) [0|0] "" FCM + SG_ CLEXTRGR : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ IRLT_REQ : 25|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKHLD : 37|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVSTRGR : 36|1@0+ (1,0) [0|0] "" SCS + SG_ VGRSTRGR : 35|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PREFILL : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PBRTRGR : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSDIS : 43|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PBPREPMP : 40|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCF01SM : 63|8@0+ (1,0) [0|0] "" FCM + +BO_ 1227 ACC1N01: 8 DS1 + SG_ ACCNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ ACCSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ ACCSPF : 23|16@0+ (1,0) [0|0] "" CGW + SG_ ACCREV : 39|32@0+ (1,0) [0|0] "" CGW + +BO_ 835 ACC1S03: 8 DS1 + SG_ ATACC2 : 7|16@0- (0.001,0) [0|0] "m/s^2" Vector__XXX + SG_ ACCTYPE : 23|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ XTRGT2 : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XLTMD2 : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LCDT2 : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LCNG : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SMC : 17|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ STOKJD : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PMTBRKG : 30|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LVSTP : 29|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LCCWOK : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LCBW2 : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CACC : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ AT_RAW : 47|8@0- (0.05,0) [0|0] "m/s^2" Vector__XXX + SG_ ACC03SUM : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 896 ACN1S01: 8 CGW + SG_ R_AC2 : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_HTR : 5|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ECOSW : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_EGON : 1|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ BLWON : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SCAC : 13|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CGIH : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FAN_AC : 22|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACHI : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACMAX : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_VSCUS : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_SHTR : 30|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_PTC : 29|2@0+ (1,0) [0|0] "piece" Vector__XXX + SG_ GNRTIH : 27|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_COL_TM : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_HET_TM : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TAMOUT : 55|8@0- (0.625,0) [0|0] "" Vector__XXX + +BO_ 897 ACN1S04: 8 CGW + SG_ R_ACCALL : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_AC_WNG : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_SW_CON : 5|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_BEEP : 4|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_RA_AUT : 3|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_RA_AC : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_RA_LO : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_RA_HI : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_AUTO_D : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_AUTO_P : 14|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_DEF : 13|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_RRDEF : 12|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_RFAUT : 11|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_REC : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_FRS : 9|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_AC : 8|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_MHTR : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_WIPD : 22|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_DUSY : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_SWNG : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_BLW_F : 19|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_OAUT_D : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_OLET_D : 30|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_OAUT_P : 27|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_OLET_P : 26|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ ST_BMN_F : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_AIRPR : 47|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_O2 : 46|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_PLSM : 45|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_KAFUN : 43|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_SAFS : 42|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_ACOFF : 41|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_ONSCRN : 40|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 944 ACN1S07: 6 CGW + SG_ RDEF : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MHTR : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TR_TEMP : 15|8@0+ (0.25,-6.5) [0|0] "" Vector__XXX + SG_ ACN_AMB : 31|8@0+ (1,0) [0|0] "" CSR,DS1,FCM + SG_ AC_AMB05 : 44|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AC_MODE : 43|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1250 AFS1N01: 8 AFS + SG_ AFSNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ AFSSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ AFSSPF : 23|16@0+ (1,0) [0|0] "" CGW + SG_ AFSREV : 39|32@0+ (1,0) [0|0] "" CGW + +BO_ 913 AFS1S01: 8 AFS + SG_ HLLI : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AZB_ADV : 5|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ HEDH_AZB : 3|1@0+ (1,0) [0|0] "" FCM + SG_ AZB_IND : 13|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ AZB_HIND : 11|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AZB_PRE : 10|1@0+ (1,0) [0|0] "" FCM + SG_ LED_HLI : 9|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LPECU_PR : 24|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 845 AFS1S02: 5 AFS + SG_ AHRR : 17|10@0+ (0.0048828125,0) [0|0] "V" Vector__XXX + SG_ AHVLD : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AHFAIL : 38|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1044 AHB1S01: 8 FCM + SG_ AHB_DUTY : 47|8@0+ (0.5,0) [0|0] "%" Vector__XXX + SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 900 AVN1S01: 6 CGW + SG_ RDC : 7|4@0+ (1,0) [0|0] "" SCS + SG_ CONFID01 : 3|2@0+ (1,0) [0|0] "" SCS + SG_ CONF : 1|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LYT : 15|4@0+ (1,0) [0|0] "" SCS + SG_ DRVW : 9|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MWMP : 8|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GRAD : 23|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ HARSHID : 19|4@0+ (1,0) [0|0] "" SCS + SG_ BRANCH : 27|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ HARSH : 35|2@0+ (1,0) [0|0] "" SCS + SG_ TOLLGATE : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TUNL : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LEAVEOUT : 47|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MRGLANE : 46|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LVLANE : 45|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 902 AVN1S03: 6 CGW + SG_ ANS : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CRS1 : 15|1@0+ (1,0) [0|0] "" SCS + SG_ RQAC : 14|7@0+ (0.02,0) [0|0] "G" Vector__XXX + SG_ GUID : 23|1@0+ (1,0) [0|0] "" SCS + SG_ GYRO : 22|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ NCRN : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CRN6 : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CRN5 : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CRN3 : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CRN2 : 17|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CRN1 : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CONFID03 : 31|2@0+ (1,0) [0|0] "" SCS + SG_ CURV : 29|2@0+ (1,0) [0|0] "" SCS + SG_ CVST : 27|1@0+ (1,0) [0|0] "" SCS + SG_ NAVI_STR : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MIND : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ONOFF : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ HWPB : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RAD : 38|7@0+ (5,0) [0|0] "m" SCS + SG_ AFS_SW : 41|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVS_SW : 40|1@0+ (1,0) [0|0] "" SCS + +BO_ 911 AVN1S07: 8 CGW + SG_ TOFC_RST : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SL_CSTM : 3|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SL_RMDG : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ST_RTCOM : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVN07VLD : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ST_UCST : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RSCOM51 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ RSCOM52 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ RSCOM53 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ RSCOM54 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ RSCOM55 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ RSCOM56 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 905 AVN1S08: 8 CGW + SG_ VVSW : 7|3@0+ (1,0) [0|0] "" CSR + SG_ BZV : 4|3@0+ (1,0) [0|0] "" CSR + SG_ DFS : 1|2@0+ (1,0) [0|0] "" CSR + SG_ BZ_M_SW : 15|1@0+ (1,0) [0|0] "" CSR + SG_ VOL_SW : 14|1@0+ (1,0) [0|0] "" CSR + SG_ BM : 13|1@0+ (1,0) [0|0] "" CSR + SG_ DOFR : 12|1@0+ (1,0) [0|0] "" CSR + SG_ RDSW : 11|1@0+ (1,0) [0|0] "" CSR + SG_ FDSW : 10|1@0+ (1,0) [0|0] "" CSR + SG_ RBSW : 9|1@0+ (1,0) [0|0] "" CSR + SG_ FBSW : 8|1@0+ (1,0) [0|0] "" CSR + SG_ NVDP_OK : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DEVICE : 22|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ DISPSIZE : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ HPTCSW_L : 30|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ HPTCSW_R : 29|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ HPTCSW_E : 28|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_MODE : 27|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VARBGM : 26|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ WBGM : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ X_LL : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ Y_LL : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ X_RH : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ Y_RH : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 998 AVN1S11: 5 CGW + SG_ SENSPFM : 7|3@0+ (1,0) [0|0] "" SCS + SG_ SENSFAIL : 4|3@0+ (1,0) [0|0] "" SCS + SG_ CONFID11 : 1|2@0+ (1,0) [0|0] "" SCS + SG_ CONFMMC : 15|8@0+ (1,0) [0|0] "" SCS + SG_ DISTERR : 23|8@0+ (1,0) [0|0] "" SCS + SG_ CONFLANE : 31|8@0+ (1,0) [0|0] "" SCS + SG_ CONFDIR : 39|8@0+ (1,0) [0|0] "" SCS + +BO_ 933 AVN1S13: 8 CGW + SG_ HUD_DISP : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRVSIDE : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DT_GP : 5|6@0+ (1,0) [0|0] "" Vector__XXX + SG_ DT_UNIT : 15|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ DIR_TURN : 12|5@0+ (11.25,0) [0|0] "degree" Vector__XXX + SG_ ROTARY : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ROAD_TP1 : 22|15@0+ (1,0) [0|0] "" Vector__XXX + SG_ ROAD_TP2 : 39|16@0+ (1,0) [0|0] "" Vector__XXX + SG_ N_H_UP : 55|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ COMPASS : 54|6@0+ (11.25,0) [0|0] "degree" Vector__XXX + SG_ DIR : 63|6@0+ (11.25,0) [0|0] "degree" Vector__XXX + +BO_ 936 AVN1S16: 5 CGW + SG_ NDADVSRY : 7|5@0+ (1,0) [0|0] "" Vector__XXX + SG_ NDCAUTON : 15|5@0+ (1,0) [0|0] "" Vector__XXX + SG_ NDSSLCT : 23|5@0+ (1,0) [0|0] "" Vector__XXX + SG_ NDCNFDID : 18|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ NDINDST : 25|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVN16SUM : 39|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 999 AVN1S17: 7 CGW + SG_ AVN17VLD : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANEID17 : 6|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRVLANE : 3|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRV_SIDE : 12|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE_NS : 11|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE1FLG : 23|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE2FLG : 19|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE1DIR : 31|16@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE2DIR : 47|16@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1000 AVN1S18: 8 CGW + SG_ AVN18VLD : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANEID18 : 6|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE3FLG : 3|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE4FLG : 15|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE5FLG : 11|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE3DIR : 23|16@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE4DIR : 39|16@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE5DIR : 55|16@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1001 AVN1S19: 8 CGW + SG_ AVN19VLD : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANEID19 : 6|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE6FLG : 3|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE7FLG : 15|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE8FLG : 11|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE6DIR : 23|16@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE7DIR : 39|16@0+ (1,0) [0|0] "" Vector__XXX + SG_ LANE8DIR : 55|16@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1076 AVN1S20: 8 CGW + SG_ A_LNG_ST : 7|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LANG : 5|6@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LNGDB1 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LNGDB2 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LNGDB3 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LNGDB4 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LNGDB5 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LNGDB6 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LNGDB7 : 63|7@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_LNGCHG : 56|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1077 AVN1S21: 8 CGW + SG_ A_OPEN_S : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ OPENCHG : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CAPSW_S : 5|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_CLR_S : 3|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ DISP_BRT : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DISP_CNT : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MM_CLOCK : 31|11@0+ (1,0) [0|0] "" Vector__XXX + SG_ CLK_OFST : 36|4@0- (5,0) [0|0] "min" Vector__XXX + SG_ DST : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CLK_TYP : 47|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_UNTTMP : 45|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_UNTSP : 43|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_UNTDST : 41|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_UNTCSP : 55|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_CLRCHG : 52|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_TMPCHG : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_SPCHG : 50|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_DSTCHG : 49|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_CSPCHG : 48|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ A_SPLM : 63|6@0+ (5,0) [0|0] "" Vector__XXX + SG_ A_UTSPLM : 57|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1043 AVN1S31: 8 CGW + SG_ GPSTM_Y : 7|8@0+ (1,0) [0|0] "year" Vector__XXX + SG_ GPSTM_MO : 15|8@0+ (1,0) [0|0] "month" Vector__XXX + SG_ GPSTM_D : 23|8@0+ (1,0) [0|0] "day" Vector__XXX + SG_ GPSTM_H : 31|8@0+ (1,0) [0|0] "hour" Vector__XXX + SG_ GPSTM_MI : 39|8@0+ (1,0) [0|0] "minute" Vector__XXX + SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GMTDIF_H : 54|4@0+ (1,0) [0|0] "hour" Vector__XXX + SG_ GMTDIF_M : 50|6@0+ (1,0) [0|0] "minute" Vector__XXX + SG_ SUMMERTM : 60|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075054137 BDB1F01_14: 8 CGW + SG_ BDBF01ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDBF01IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ SALR : 23|6@0+ (1,0) [0|0] "" Vector__XXX + SG_ HDCY_BDB : 17|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AARE_B : 31|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ I_SEN_B : 27|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ INTSET_B : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ INCSET_B : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ISSD_BDB : 39|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SEID : 37|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ WS_ID : 44|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ WS_SWON : 41|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ WS_DATA : 55|16@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075185211 BDB1F03_16: 8 CGW + SG_ BDBF03ID : 7|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ BDBF03IF : 15|8@0+ (1,0) [0|0] "" DS1,FCM + SG_ TRIP_CNT : 23|16@0+ (1,0) [0|0] "trip" AFS,BSR,CSR,DS1,FCM,MAV + SG_ TIME_CNT : 39|32@0+ (100,0) [0|0] "ms" AFS,BSR,CSR,DS1,FCM,MAV + +BO_ 1074791968 BDB1S01_10: 8 CGW + SG_ BDB01_ID : 7|8@0+ (1,0) [0|0] "" FCM,MAV + SG_ BDB01_IF : 15|8@0+ (1,0) [0|0] "" FCM + SG_ LX : 23|16@0+ (0.2,0) [0|0] "ms" FCM + SG_ ADIM : 39|2@0+ (1,0) [0|0] "" AFS,BSR,CSR + SG_ IG_BDB : 37|1@0+ (1,0) [0|0] "" AFS,MAV + SG_ ACC_BDB : 36|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SKSW : 46|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DCTY : 45|1@0+ (1,0) [0|0] "" FCM,MAV,SCS + SG_ PCTY : 44|1@0+ (1,0) [0|0] "" MAV,SCS + SG_ RRCY : 43|1@0+ (1,0) [0|0] "" MAV,SCS + SG_ RLCY : 42|1@0+ (1,0) [0|0] "" MAV,SCS + SG_ BCTY : 41|1@0+ (1,0) [0|0] "" MAV,SCS + SG_ PSW : 51|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SRBZ : 49|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DBKL : 63|2@0+ (1,0) [0|0] "" FCM + SG_ PKB_BDB : 60|1@0+ (1,0) [0|0] "" CSR + SG_ SREXIST : 59|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SRPOS : 58|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1074857505 BDB1S02_11: 8 CGW + SG_ BDB02_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB02_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ LUD : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TRNKOPN : 45|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1074923042 BDB1S03_12: 8 CGW + SG_ BDB03_ID : 7|8@0+ (1,0) [0|0] "" DS1,FCM + SG_ BDB03_IF : 15|8@0+ (1,0) [0|0] "" DS1,FCM + SG_ LTS : 23|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ PANL : 19|1@0+ (1,0) [0|0] "" BSR,CSR + SG_ UDRL : 31|1@0+ (1,0) [0|0] "" AFS + SG_ HEDH : 30|1@0+ (1,0) [0|0] "" AFS,DS1,FCM + SG_ HEDL : 29|1@0+ (1,0) [0|0] "" AFS,DS1 + SG_ TAIL : 28|1@0+ (1,0) [0|0] "" AFS,BSR,CSR,DS1 + SG_ FFOG : 27|1@0+ (1,0) [0|0] "" DS1 + SG_ RFOG : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SB_IND : 39|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SB_OK : 37|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RTRRQ : 35|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SRWARN : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PWWARN : 50|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ WEL_REQ : 48|1@0+ (1,0) [0|0] "" AFS + SG_ DRPBZ_R : 62|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075381795 BDB1S04_19: 8 CGW + SG_ BDB04_ID : 7|8@0+ (1,0) [0|0] "" MAV + SG_ BDB04_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MRMV_R : 23|2@0+ (1,0) [0|0] "" MAV + SG_ RSEL : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LSEL : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MHR : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MHL : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MVU : 17|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MVD : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GHSW : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GCTY : 30|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GHOPN : 42|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ ABIF : 55|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ FLSHRQ : 63|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ SB_ADV : 60|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1074988600 BDB1S05_13: 8 CGW + SG_ BDB05_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB05_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ PARK : 23|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSWB : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LSWD : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LSWP : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LSWR : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LSWL : 17|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LSWB : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRVKS_R : 31|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ PWDRD : 39|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PWDRP : 37|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PWDRR : 35|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PWDRL : 33|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ DKLS : 43|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ BKLS : 54|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ KIDSCN_R : 51|7@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075250736 BDB1S06_17: 8 CGW + SG_ BDB06_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB06_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TBSW : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ WBZF : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ WVOL : 42|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075316273 BDB1S07_18: 8 CGW + SG_ BDB07_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB07_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ WCD : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ W1D : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ W2D : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ W3D : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB7SUM1 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB7SUM2 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075447332 BDB1S08_1A: 8 CGW + SG_ BDB08_ID : 7|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ BDB08_IF : 15|8@0+ (1,0) [0|0] "" DS1,FCM + SG_ DEST_BDB : 23|8@0+ (1,0) [0|0] "" AFS,BSR,CSR,DS1,FCM,MAV + SG_ DS_PACK1 : 31|8@0+ (1,0) [0|0] "" AFS,BSR,DS1,FCM,MAV + SG_ DS_PACK2 : 39|8@0+ (1,0) [0|0] "" AFS,BSR,DS1,FCM,MAV + SG_ STRG_WHL : 47|2@0+ (1,0) [0|0] "" AFS,CSR,DS1,FCM,MAV + SG_ DEICER : 40|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ KEYPLATE : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DBLLCK : 62|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ U2OP_CST : 61|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ U2OP_DFT : 60|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075643943 BDB1S11_1D: 8 CGW + SG_ BDB11_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB11_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDBREQ11 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDBREQ12 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1083704892 BDB1S17_98: 8 CGW + SG_ BDB17_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB17_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ CHABASE1 : 23|8@0+ (1,0) [0|0] "" AFS + SG_ CHABASE2 : 31|8@0+ (1,0) [0|0] "" AFS + SG_ CHABASE3 : 39|8@0+ (1,0) [0|0] "" AFS + SG_ CHA_NO1 : 47|4@0+ (1,0) [0|0] "" AFS + SG_ CHA_NO2 : 43|4@0+ (1,0) [0|0] "" AFS + SG_ CHA_NO3 : 55|4@0+ (1,0) [0|0] "" AFS + SG_ SP_BODY : 63|5@0+ (1,0) [0|0] "" AFS + +BO_ 1083770429 BDB1S18_99: 8 CGW + SG_ BDB18_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB18_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ POP_NAME : 23|8@0+ (1,0) [0|0] "" AFS + SG_ BODY : 31|8@0+ (1,0) [0|0] "" AFS + SG_ GEAR : 39|8@0+ (1,0) [0|0] "" AFS + SG_ GRADE : 47|8@0+ (1,0) [0|0] "" AFS + SG_ ENGINE : 55|8@0+ (1,0) [0|0] "" AFS + +BO_ 1020 BDB1S19: 8 CGW + SG_ SOLAR_R : 23|9@0+ (100,0) [0|0] "" Vector__XXX + SG_ SOLAR_L : 39|9@0+ (100,0) [0|0] "" Vector__XXX + SG_ N_LX : 55|13@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1083835966 BDB1S20_9A: 8 CGW + SG_ BDB20_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB20_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ RNBDYC : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ RNBDYD : 39|32@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1083901503 BDB1S21_9B: 8 CGW + SG_ BDB21_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BDB21_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ RFOG_SW : 22|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FFOG_SW : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ HF_SW : 20|1@0+ (1,0) [0|0] "" AFS + SG_ HU_SW : 19|1@0+ (1,0) [0|0] "" AFS + SG_ AUTO_SW : 18|1@0+ (1,0) [0|0] "" AFS + SG_ HEAD_SW : 17|1@0+ (1,0) [0|0] "" AFS + SG_ TAIL_SW : 16|1@0+ (1,0) [0|0] "" AFS + SG_ DRL_OFF : 24|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1005 BGM1S01: 2 CGW + SG_ WCAA : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ R_DISP : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BGM_BEEP : 11|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ BGM_MODE : 9|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1237 BSR1N01: 8 BSR + SG_ BSRNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ BSRSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ BSRSPF : 23|16@0+ (1,0) [0|0] "" CGW + SG_ BSRREV : 39|32@0+ (1,0) [0|0] "" CGW + +BO_ 1014 BSR1S01: 8 BSR + SG_ BSD_STAT : 7|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ BSD_SW : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BSD_BUZ : 23|1@0+ (1,0) [0|0] "" CSR + +BO_ 1114 CGW1N02: 8 CGW + SG_ CGW2REV : 7|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1228 CSR1N01: 8 CSR + SG_ CSRNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ CSRSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ CSRSPF : 23|16@0+ (1,0) [0|0] "" CGW + SG_ CSRREV : 39|32@0+ (1,0) [0|0] "" CGW + +BO_ 918 CSR1S01: 7 CSR + SG_ CSV : 7|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ CSSR : 4|2@0+ (1,0) [0|0] "" MAV + SG_ CSD : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CSME : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CSIN : 0|1@0+ (1,0) [0|0] "" MAV + SG_ FL_INFO : 15|4@0+ (1,0) [0|0] "" MAV + SG_ FR_INFO : 11|4@0+ (1,0) [0|0] "" MAV + SG_ RB_INFO : 23|4@0+ (1,0) [0|0] "" MAV + SG_ FC_INFO : 19|4@0+ (1,0) [0|0] "" MAV + SG_ RL_INFO : 31|4@0+ (1,0) [0|0] "" MAV + SG_ RR_INFO : 27|4@0+ (1,0) [0|0] "" MAV + SG_ CZV : 39|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ VOT : 47|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ FCZD : 43|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RCZD : 42|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FCDD : 41|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RCDD : 40|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VOL : 55|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ CDG : 52|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ MUTE : 49|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BZ_OFF : 48|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1087768273 DMS1S02_D6: 8 CGW + SG_ SS_MODE : 25|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 869 DS11D70: 7 DS1 + SG_ D_TRGJDG : 7|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_RESSW : 3|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_SETSW : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_CANSW : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_MAINSW : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_VMCC : 15|8@0+ (1,0) [0|0] "km/h" Vector__XXX + SG_ D_VNCC : 23|8@0+ (1,0) [0|0] "km/h" Vector__XXX + SG_ D_CCREQ : 31|8@0+ (100,-12800) [0|0] "N" Vector__XXX + SG_ D_TGTDST : 39|8@0+ (1,0) [0|0] "m" Vector__XXX + SG_ D_VRCC : 47|8@0- (1,0) [0|0] "km/h" Vector__XXX + SG_ D_WSTL : 55|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_DSW : 54|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_FDJDG : 52|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ D_DSSJDG : 51|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 870 DS11D71: 7 DS1 + SG_ XREQALM : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XREQABK : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TGT_DIST : 5|14@0+ (0.01,0) [0|0] "m" Vector__XXX + SG_ XREQPBA : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XREQFPB : 22|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XREQPB : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XREQEXT : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XREQPSB : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TGT_VGAP : 18|11@0+ (0.025,-51.175) [0|0] "m/s" Vector__XXX + SG_ PCSDISP : 39|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ XPCSRDY : 35|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TGT_NUMB : 34|3@0+ (1,1) [0|0] "" Vector__XXX + SG_ TGT_POSX : 47|8@0- (0.04,0) [0|0] "m" Vector__XXX + +BO_ 871 DS11D72: 2 FCM + SG_ LKADRTRG : 7|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKADRSHR : 5|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKADRSLK : 4|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKADRSLD : 3|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKADRCC : 2|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKADRTUR : 15|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKADRINV : 13|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 643 DS11F01: 7 DS1 + SG_ DSCOUNT : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DSLCCW1 : 15|1@0+ (1,0) [0|0] "" FCM + SG_ DSSTPBZ : 14|1@0+ (1,0) [0|0] "" FCM + SG_ PBRTRGR2 : 12|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DSSFTRQD : 11|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ DSS1FDRV : 23|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ DSS1STBK : 39|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ DSS1STAT : 36|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ DSBHOK : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PPTRGR2 : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DSRQBH : 47|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ IBTRGR2 : 45|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSABK2 : 44|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSNOCHG : 41|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ DS1F01SM : 55|8@0+ (1,0) [0|0] "" FCM + +BO_ 1041 DS12F02: 8 DS1 + SG_ PCSINDI : 7|2@0+ (1,0) [0|0] "" FCM + SG_ PCSWM : 5|2@0+ (1,0) [0|0] "" FCM + SG_ PCSFCT : 3|1@0+ (1,0) [0|0] "" FCM + SG_ PCSTUCT : 2|1@0+ (1,0) [0|0] "" FCM + SG_ DS1LCCK : 1|2@0+ (1,0) [0|0] "" FCM + SG_ PBTUCT : 14|1@0+ (1,0) [0|0] "" FCM + SG_ PCSEXIST : 13|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSWDUCT : 11|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSWD : 9|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSDW : 39|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSDSRF : 36|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSTEMP : 35|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSDUST : 34|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSLCCK : 33|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSPEDW : 47|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSPVSN : 44|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCTEMP2 : 42|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSDUST2 : 41|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSOFFS : 40|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSWDS : 55|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ FRDADJ : 53|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1042 DS12F03: 8 FCM + SG_ LKAINDI : 7|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKAWLSL : 5|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKAWLSR : 3|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKAFCT : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKATUCT : 14|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKACAMT : 13|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LDWEXIST : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKASPCND : 23|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKAWTCS : 18|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKASAUT : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LDWBZ : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LDAFCVB : 47|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LDARDA : 46|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SWSSENSD : 45|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SWSSWD : 43|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SWSRAD : 55|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SWSFLD : 53|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ SWSBUZ : 50|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1207 ECO1D50: 8 CGW + SG_ DRECO01 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECO02 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECO03 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECO04 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECO05 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECO06 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECO07 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECO08 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 355 ECO1S01: 5 CGW + SG_ ECOSTAON : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ECOMODE : 18|3@0+ (1,0) [0|0] "" KSS,SCS + SG_ FCREQ : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SSVMREQ : 27|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ E2MRXMK : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BPHLDRQ : 36|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BPHLDRQ2 : 35|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ ECOEGSTP : 33|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 922 ECO1S90: 8 CGW + SG_ ECOBZR : 23|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ ECOLMP : 21|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ TESTECO : 30|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ OPLMPMSK : 29|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MSTART : 28|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ECOMODE3 : 27|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ INFSSCOP : 39|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ INFSSSTL : 36|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ ECLMP : 34|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ AUTOSTA : 47|1@0+ (1,0) [0|0] "" SCS + SG_ INFSSFAL : 46|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ INFSSINH : 45|6@0+ (1,0) [0|0] "" Vector__XXX + SG_ SSACMODE : 52|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ INFSSADV : 50|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1182 ECT1D50: 8 CGW + SG_ DRECT01 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT02 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT03 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT04 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT05 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT06 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT07 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT08 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1183 ECT1D51: 8 CGW + SG_ DRECT11 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT12 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT13 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT14 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT15 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT16 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT17 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT18 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1200 ECT1D52: 8 CGW + SG_ DRECT21 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT22 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT23 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT24 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT25 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT26 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT27 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT28 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1201 ECT1D53: 8 CGW + SG_ DRECT31 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT32 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT33 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT34 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT35 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT36 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT37 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT38 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1202 ECT1D54: 8 CGW + SG_ DRECT41 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT42 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT43 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT44 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT45 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT46 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT47 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT48 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1203 ECT1D55: 8 CGW + SG_ DRECT51 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT52 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT53 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT54 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT55 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT56 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT57 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRECT58 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 464 ECT1F03: 8 CGW + SG_ NT : 7|16@0- (0.390625,0) [0|0] "rpm" Vector__XXX + SG_ ACT : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XDMET : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XNTSW : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XNMET : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XRMET : 17|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XPMET : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SFTOUT_S : 29|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ X3MET : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ X2MET : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XLOMET : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ L4SW : 38|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SNOW : 36|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XFSFT : 35|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SFTOUT : 34|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ HSSLWN : 55|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ HSINH : 54|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CLTMODBK : 53|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ LUOUT : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LUKG : 50|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ FBCOA : 48|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ECTF03SM : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 725 ECT1S10: 2 CGW + SG_ VTORATIO : 7|16@0+ (0.0009765625,0) [0|0] "" Vector__XXX + +BO_ 956 ECT1S92: 8 CGW + SG_ B_OILW : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_OILMD : 5|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_ISNW : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_RJTB : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_WNDL : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_LMULRJ : 14|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_P : 13|1@0+ (1,0) [0|0] "" AFS,CSR,MAV + SG_ B_R : 12|1@0+ (1,0) [0|0] "" AFS,BSR,CSR,DS1,FCM,MAV + SG_ B_N : 11|1@0+ (1,0) [0|0] "" AFS,CSR,MAV + SG_ B_ISPTM : 10|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ BV_THOCL : 23|16@0+ (0.625,-50) [0|0] "" Vector__XXX + SG_ B_GEAR : 39|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_SMDE : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_D : 47|1@0+ (1,0) [0|0] "" AFS,CSR,DS1,MAV + SG_ B_ECOMI : 40|1@0+ (1,0) [0|0] "" DS1 + SG_ B_SPTMI : 55|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_PWRM : 54|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_OILWM : 51|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_SPTMS : 49|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_DMODE : 61|3@0+ (1,0) [0|0] "" SCS + +BO_ 1176 ENG1D50: 8 CGW + SG_ DRENG01 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG02 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG03 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG04 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG05 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG06 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG07 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG08 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1177 ENG1D51: 8 CGW + SG_ DRENG11 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG12 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG13 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG14 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG15 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG16 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG17 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG18 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1178 ENG1D52: 8 CGW + SG_ DRENG21 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG22 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG23 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG24 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG25 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG26 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG27 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG28 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1179 ENG1D53: 8 CGW + SG_ DRENG31 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG32 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG33 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG34 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG35 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG36 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG37 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG38 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1180 ENG1D54: 8 CGW + SG_ DRENG41 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG42 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG43 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG44 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG45 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG46 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG47 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG48 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1181 ENG1D55: 8 CGW + SG_ DRENG51 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG52 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG53 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG54 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG55 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG56 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG57 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG58 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1192 ENG1D56: 8 CGW + SG_ DRENG61 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG62 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG63 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG64 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG65 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG66 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG67 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG68 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1191 ENG1D57: 8 CGW + SG_ DRENG71 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG72 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG73 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG74 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG75 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG76 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG77 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG78 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1197 ENG1D58: 8 CGW + SG_ DRENG81 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG82 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG83 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG84 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG85 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG86 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG87 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG88 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1198 ENG1D59: 8 CGW + SG_ DRENG91 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG92 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG93 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG94 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG95 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG96 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG97 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG98 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1199 ENG1D60: 8 CGW + SG_ DRENG101 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG102 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG103 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG104 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG105 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG106 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG107 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRENG108 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1017 ENG1F03: 8 CGW + SG_ VARENG1 : 7|4@0+ (1,0) [0|0] "" AFS,SCS + SG_ VARENG2 : 3|4@0+ (1,0) [0|0] "" AFS,SCS + SG_ VARENG3 : 15|4@0+ (1,0) [0|0] "" AFS,SCS + SG_ VARENG4 : 11|1@0+ (1,0) [0|0] "" AFS,SCS + SG_ HVFLAG : 10|1@0+ (1,0) [0|0] "" AFS,BSR,FCM,SCS + SG_ VARTRM1 : 23|4@0+ (1,0) [0|0] "" AFS,CSR,FCM,MAV,SCS + SG_ GEARINF : 19|4@0+ (1,0) [0|0] "" SCS + SG_ DVINF : 31|2@0+ (1,0) [0|0] "" AFS,DS1,FCM,SCS + SG_ OBDINF : 27|4@0+ (1,0) [0|0] "" BSR,DS1,FCM,SCS + SG_ ECOFLAG : 39|1@0+ (1,0) [0|0] "" FCM + SG_ CDYMD : 38|2@0+ (1,0) [0|0] "" DS1,FCM + SG_ ENGF03SM : 63|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + +BO_ 452 ENG1F07: 8 CGW + SG_ NE1 : 7|16@0- (0.78125,0) [0|0] "rpm" SCS + SG_ THA1 : 23|8@0+ (2.5,-40) [0|0] "" Vector__XXX + SG_ THWX : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ EGF : 30|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ T2ERXF : 29|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ T2ERXMK : 28|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ASTEFI : 27|1@0+ (1,0) [0|0] "" AFS + SG_ B2ERXMK : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PDLF : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENTCAL2 : 39|8@0+ (12.5,0) [0|0] "rpm" Vector__XXX + SG_ EGFB : 46|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ PTFB : 45|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MILREQ : 43|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_ECOL : 55|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_IECOCR : 53|6@0+ (2,0) [0|0] "" Vector__XXX + SG_ ENGF07SM : 63|8@0+ (1,0) [0|0] "" AFS,DS1,FCM + +BO_ 114 ENG1F43: 5 CGW + SG_ FAVLMCHL : 7|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ FAVLMONL : 23|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ ENGF43SM : 39|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 705 ENG1S01: 8 CGW + SG_ ETCSFB : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ETCSF : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VSCTH : 5|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ THF : 4|1@0+ (1,0) [0|0] "" DS1 + SG_ IDL1 : 3|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XCCACT2 : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ STPSWF : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ WTC : 0|1@0+ (1,0) [0|0] "" KSS,SCS + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" Vector__XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" Vector__XXX + SG_ EACCP : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ ENG01SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM + +BO_ 961 ENG1S23: 3 CGW + SG_ EKLSM : 7|8@0+ (0.625,0) [0|0] "%" Vector__XXX + SG_ GATHW : 15|16@0- (0.625,0) [0|0] "" Vector__XXX + +BO_ 979 ENG1S28: 2 CGW + SG_ B_FC : 7|16@0+ (0.0005,0) [0|0] "ml" Vector__XXX + +BO_ 1408 ENG1S51: 8 CGW + SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1409 ENG1S52: 8 CGW + SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1410 ENG1S54: 8 CGW + SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ VC : 52|5@0+ (1,0) [0|0] "" Vector__XXX + SG_ TES : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 955 ENG1S92: 8 CGW + SG_ B_ST : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_TC : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_GLOW : 3|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_STPE : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_OMWI : 15|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_SILUP : 13|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_SILDN : 12|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_WSTP : 11|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_LOUT : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_OILPL : 9|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_TMP : 23|8@0+ (0.5,0) [0|0] "" Vector__XXX + SG_ OGENETCS : 30|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_DPFW : 28|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ BOSLAMP : 37|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ BOSMINF : 34|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ GOSLAMP : 45|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ GOSMINF : 42|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 921 ENG1S95: 8 CGW + SG_ B_LLSP2 : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TLSTBZ : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_ASLBZ2 : 5|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_SPU2 : 4|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACASID1 : 3|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACASID2 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_LSP2 : 31|8@0+ (1,0) [0|0] "km/h Emph" Vector__XXX + SG_ B_ASLSP2 : 39|8@0+ (1,0) [0|0] "km/h Emph" Vector__XXX + SG_ CACCTRN : 47|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CACCINF : 46|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CACCFR2 : 45|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CACCFR1 : 44|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CACCFLD : 43|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CACCCM3 : 42|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CACCCM2 : 41|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CACCCM1 : 40|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 238 ENG2F01: 4 CGW + SG_ STOFOK : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GROWIND : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_TMP3 : 15|8@0+ (0.5,0) [0|0] "" Vector__XXX + SG_ IMMINJST : 23|16@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 466 ENG2F04: 8 CGW + SG_ XLDR : 7|1@0+ (1,0) [0|0] "" DS1 + SG_ XACCACTV : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XACCACT : 5|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ XPAIDLV : 4|1@0+ (1,0) [0|0] "" DS1 + SG_ XPAIDL : 3|1@0+ (1,0) [0|0] "" DS1 + SG_ BHOK : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RQBH : 1|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCSTAT : 15|3@0+ (1,0) [0|0] "" DS1 + SG_ ACCSTBK : 12|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ STPBZ : 9|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ PLOCKF : 8|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ACCREQ : 23|16@0- (0.0009765625,0) [0|0] "m/s^2" DS1 + SG_ ACCAVL : 39|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ SPDSTAT : 55|4@0+ (1,0) [0|0] "" DS1 + SG_ SSTOK : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CANREQ : 49|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FCACT : 48|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SM1D2 : 63|8@0+ (1,0) [0|0] "" DS1,FCM + +BO_ 467 ENG2F05: 8 CGW + SG_ LCCW2 : 4|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ WSTL2 : 3|1@0+ (1,0) [0|0] "" DS1 + SG_ LCCHK : 2|3@0+ (1,0) [0|0] "" DS1 + SG_ XCCOK2 : 15|1@0+ (1,0) [0|0] "" DS1 + SG_ SLTACC : 14|2@0+ (1,0) [0|0] "" DS1 + SG_ LTME2 : 12|2@0+ (1,0) [0|0] "" DS1 + SG_ STPSWF2 : 10|1@0+ (1,0) [0|0] "" DS1 + SG_ CCSF : 9|1@0+ (1,0) [0|0] "" DS1 + SG_ CCSNG : 8|1@0+ (1,0) [0|0] "" DS1 + SG_ VM : 23|16@0+ (0.00390625,0) [0|0] "km/h" DS1 + SG_ INTG : 39|8@0- (0.04,0) [0|0] "m/s^2" DS1 + SG_ D2PRXMK : 47|1@0+ (1,0) [0|0] "" DS1 + SG_ SM1D3 : 63|8@0+ (1,0) [0|0] "" DS1,FCM + +BO_ 119 ENG2F41: 6 CGW + SG_ FDRV : 7|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ FDRVREAL : 23|13@0- (10,0) [0|0] "N" Vector__XXX + SG_ XAECT : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XFDRVCOL : 38|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVSELP : 34|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F41S : 47|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 120 ENG2F42: 4 CGW + SG_ FAVLMCHH : 7|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ CCRNG : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVTYPD : 22|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ GEARHD : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F42S : 31|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 916 EPS1S90: 1 CGW + SG_ B_WPS0 : 1|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1235 FCM1N01: 8 FCM + SG_ FCMNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ FCMSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ FCMSPF : 23|16@0+ (1,0) [0|0] "" CGW + SG_ FCMREV : 39|32@0+ (1,0) [0|0] "" CGW + +BO_ 1161 FCM1S10: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1162 FCM1S11: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1163 FCM1S12: 8 FCM + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" Vector__XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" Vector__XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" Vector__XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1279 FRD1N01: 8 FRD + SG_ FRDNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ FRDSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ FRDSPF : 23|16@0+ (1,0) [0|0] "" CGW + SG_ FRDREV : 39|32@0+ (1,0) [0|0] "" CGW + +BO_ 737 FWM1S01: 2 CGW + SG_ ACTHLF : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MOT4WD : 6|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CCANCEL : 5|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AI4WD : 4|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LOW4 : 3|1@0+ (1,0) [0|0] "" MAV,SCS + SG_ DLOCK : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RDLOCK : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ HLN : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ F_SP4WD : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RQ_SP4WD : 14|7@0+ (1,73) [0|0] "km/h" Vector__XXX + +BO_ 1082263092 IDT1S03_82: 8 CGW + SG_ IDT03_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ IDT03_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ CO_IDT : 23|16@0+ (1,0) [0|0] "" Vector__XXX + SG_ UACK : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ WRT : 38|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RSTP : 37|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1082328629 IDT1S04_83: 8 CGW + SG_ IDT04_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ IDT04_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ OSID : 47|16@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1257 KSS1N01: 8 KSS + SG_ KSSNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ KSSSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ KSSSPF : 23|16@0+ (1,0) [0|0] "" CGW + SG_ KSSREV : 39|32@0+ (1,0) [0|0] "" CGW + +BO_ 927 KSS1S90: 1 KSS + SG_ LKSS0 : 1|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1263 MAV1N01: 8 MAV + SG_ MAVNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ MAVSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ MAVSPF : 23|16@0+ (1,0) [0|0] "" CGW + +BO_ 1075840528 MET1S01_20: 8 CGW + SG_ MET01_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET01_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET_SPD : 23|8@0+ (1,0) [0|0] "km/h" CSR + SG_ RHEOSTAT : 30|7@0+ (1,0) [0|0] "%" Vector__XXX + SG_ TAIL_CN : 39|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ ILL_OF : 37|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ UNIT_TMP : 33|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ IN_FC : 47|16@0+ (0.1,0) [0|0] "Note" Vector__XXX + SG_ UNIT_0 : 63|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ SP_TL : 60|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET_TC : 56|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075906065 MET1S02_21: 8 CGW + SG_ MET02_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET02_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET_DEST : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ ODO_UNIT : 29|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ OMRS : 27|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ UNIT_CH : 26|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ ODO : 39|32@0+ (1,0) [0|0] "km/mile" Vector__XXX + +BO_ 1076037145 MET1S04_23: 8 CGW + SG_ MET04_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET04_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ AF_FC : 23|16@0+ (0.1,0) [0|0] "Note" Vector__XXX + SG_ UNIT_3 : 39|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ RANGE : 47|16@0+ (1,0) [0|0] "Note" Vector__XXX + SG_ UNIT_4 : 63|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1076102682 MET1S05_24: 8 CGW + SG_ MET05_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET05_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TO_SP : 23|16@0+ (0.1,0) [0|0] "km/h,MPH" Vector__XXX + SG_ UNIT_5 : 39|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ TO_FC : 47|16@0+ (0.1,0) [0|0] "MPG Ekm/l El/100km Ekm/gallon" Vector__XXX + SG_ UNIT_6 : 63|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1076299282 MET1S08_27: 8 CGW + SG_ MET08_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET08_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ TO_DT : 23|16@0+ (1,0) [0|0] "km,mile" Vector__XXX + SG_ UNIT_10 : 39|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1076364819 MET1S09_28: 8 CGW + SG_ MET09_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET09_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ WASH : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BLVW : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_CW : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENGW : 29|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ABSW : 28|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VSCW : 27|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ OPW : 37|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ OLW : 36|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LW : 35|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FSRS : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ HALW : 46|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRW : 43|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TIRW : 42|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FWW : 40|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SUSW : 53|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LKAW : 61|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET_PCSW : 59|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ WTPW : 57|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1076430356 MET1S10_29: 8 CGW + SG_ MET10_ID : 7|8@0+ (1,0) [0|0] "" DS1,FCM + SG_ MET10_IF : 15|8@0+ (1,0) [0|0] "" DS1,FCM + SG_ OM_MLG : 23|7@0+ (100,0) [0|0] "miles" Vector__XXX + SG_ PR_OM_FL : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TNS : 29|2@0+ (1,0) [0|0] "" AFS,BSR,DS1,FCM + SG_ HZS : 27|1@0+ (1,0) [0|0] "" AFS,FCM + +BO_ 1076495893 MET1S11_2A: 8 CGW + SG_ MET11_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET11_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ UNIT_CH2 : 23|2@0+ (1,0) [0|0] "" FCM + SG_ TOLER_A : 21|6@0+ (0.002,0.94) [0|0] "" FCM + SG_ CDISP_EX : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TOLER_B : 29|6@0- (0.2,0) [0|0] "km/h" FCM + SG_ TRIP_B : 39|32@0+ (0.1,0) [0|0] "km/MILE" Vector__XXX + +BO_ 1076561430 MET1S12_2B: 8 CGW + SG_ MET12_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ MET12_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ ESLW : 19|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CSOW : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LHLW : 37|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SMBW : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ KDSW : 32|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ OMRW : 46|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BSDW : 54|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ MTSW : 48|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ATSW : 63|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 992 MET1S18: 8 CGW + SG_ M_LANG : 7|6@0+ (1,0) [0|0] "" Vector__XXX + SG_ M_LNG_ST : 1|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ M_LNGDB1 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ M_LNGDB2 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ M_LNGDB3 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ M_LNGDB4 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ M_LNGDB5 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ M_LNGDB6 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ M_LNGDB7 : 63|7@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1075840755 MET1S22_20: 8 CGW + SG_ ID6F320 : 7|8@0+ (1,0) [0|0] "" DS1,FCM + SG_ IF6F320 : 15|8@0+ (1,0) [0|0] "" DS1,FCM + SG_ TSR_OSM : 22|2@0+ (1,0) [0|0] "" FCM + SG_ TSR_OSL : 20|2@0+ (1,0) [0|0] "" FCM + SG_ TSR_SNM : 18|2@0+ (1,0) [0|0] "" FCM + SG_ TSR_MAIN : 16|1@0+ (1,0) [0|0] "" FCM + SG_ LDAMCUS : 31|2@0+ (1,0) [0|0] "" FCM + SG_ LDAMSW : 29|2@0+ (1,0) [0|0] "" FCM + SG_ FCMUSER : 27|1@0+ (1,0) [0|0] "" FCM + SG_ FCMMCUS : 26|2@0+ (1,0) [0|0] "" FCM + SG_ FCMMSW : 24|1@0+ (1,0) [0|0] "" FCM + SG_ BSMMSW : 37|1@0+ (1,0) [0|0] "" BSR + SG_ CSRMSW : 34|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSMCUS : 41|1@0+ (1,0) [0|0] "" DS1 + SG_ PCSMSW : 40|1@0+ (1,0) [0|0] "" DS1 + SG_ LKACTCSW : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ LDA_SFB : 50|3@0+ (1,0) [0|0] "" FCM + +BO_ 1088685760 PMN1F03_E4: 8 CGW + SG_ PMNF03ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ PMNF03IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ PSSW_PMN : 17|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PSW_PMN : 31|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ KCC_PMN : 29|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PMOD_PMN : 27|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ MOD_EIG : 39|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ SWBZ_EIG : 36|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1193 SCS1D50: 8 SCS + SG_ DRSCS01 : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRSCS02 : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRSCS03 : 23|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRSCS04 : 31|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRSCS05 : 39|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRSCS06 : 47|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRSCS07 : 55|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ DRSCS08 : 63|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1226 SCS1N01: 8 SCS + SG_ SCSNID : 7|8@0+ (1,0) [0|0] "" CGW + SG_ SCSSNG : 15|1@0+ (1,0) [0|0] "" CGW + SG_ SCSSPF : 23|16@0+ (1,0) [0|0] "" CGW + SG_ SCSREV : 39|32@0+ (1,0) [0|0] "" CGW + +BO_ 744 SCS1S01: 8 SCS + SG_ SELECTOR : 3|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVS_MD : 63|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 815 SCS1S06: 5 SCS + SG_ RRVH : 23|8@0- (1,0) [0|0] "mm" AFS + SG_ RLVH : 31|8@0- (1,0) [0|0] "mm" AFS + SG_ SCECOINH : 35|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 917 SCS1S90: 4 SCS + SG_ B_LSUS6 : 7|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_LSUS4 : 5|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_LSUS2 : 3|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_LSUS8 : 9|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ DLR_HSID : 23|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LAR_HS : 18|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVSNI : 16|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 37 STR1S01: 8 CGW + SG_ STS3 : 7|1@0+ (1,0) [0|0] "" AFS,BSR,DS1,FCM,MAV + SG_ STS2 : 6|1@0+ (1,0) [0|0] "" AFS,DS1,FCM,KSS,MAV,SCS + SG_ STS1 : 5|1@0+ (1,0) [0|0] "" AFS,BSR,DS1,FCM,KSS,MAV,SCS + SG_ STS0 : 4|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ SSA : 3|12@0- (1.5,0) [0|0] "deg" AFS,BSR,DS1,FCM,KSS,MAV,SCS + SG_ SAZS : 23|1@0+ (1,0) [0|0] "" AFS,BSR,DS1,FCM + SG_ SFRZ : 22|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ SSAZ : 19|12@0- (1.5,0) [0|0] "deg" AFS,BSR,DS1,FCM + SG_ SSAS : 39|4@0- (0.1,0) [0|0] "deg" FCM,KSS,SCS + SG_ SSAV : 35|12@0- (1,0) [0|0] "deg/s" FCM,KSS,SCS + SG_ STDID : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ STR01SUM : 63|8@0+ (1,0) [0|0] "" AFS,DS1,FCM,MAV + +BO_ 1059 STR1S02: 1 CGW + SG_ SFR : 5|1@0+ (1,0) [0|0] "" MAV + SG_ STRWVG : 4|1@0+ (1,0) [0|0] "" AFS,BSR,DS1,FCM + +BO_ 170 VSC1F01: 8 CGW + SG_ VXFREF : 7|1@0+ (1,0) [0|0] "" AFS,FCM,MAV + SG_ VXFR : 6|15@0+ (0.01,-67.67) [0|0] "km/h" AFS,BSR,DS1,FCM,KSS,MAV,SCS + SG_ VXFLEF : 23|1@0+ (1,0) [0|0] "" AFS,FCM,MAV + SG_ VXFL : 22|15@0+ (0.01,-67.67) [0|0] "km/h" AFS,BSR,DS1,FCM,KSS,MAV,SCS + SG_ VXRREF : 39|1@0+ (1,0) [0|0] "" AFS,FCM,MAV + SG_ VXRR : 38|15@0+ (0.01,-67.67) [0|0] "km/h" AFS,BSR,DS1,FCM,KSS,MAV,SCS + SG_ VXRLEF : 55|1@0+ (1,0) [0|0] "" AFS,FCM,MAV + SG_ VXRL : 54|15@0+ (0.01,-67.67) [0|0] "km/h" AFS,BSR,DS1,FCM,KSS,MAV,SCS + +BO_ 426 VSC1F02: 6 CGW + SG_ VXFRF : 7|1@0+ (1,0) [0|0] "" AFS,BSR,FCM,MAV + SG_ VXFRIGS : 6|1@0+ (1,0) [0|0] "" BSR,DS1,FCM,MAV + SG_ VXFRHDS : 5|1@0+ (1,0) [0|0] "" FCM,KSS,MAV,SCS + SG_ VXFLF : 2|1@0+ (1,0) [0|0] "" AFS,BSR,FCM,MAV + SG_ VXFLIGS : 1|1@0+ (1,0) [0|0] "" BSR,DS1,FCM,MAV + SG_ VXFLHDS : 0|1@0+ (1,0) [0|0] "" FCM,KSS,MAV,SCS + SG_ VXRRF : 13|1@0+ (1,0) [0|0] "" AFS,BSR,FCM,MAV + SG_ VXRRIGS : 12|1@0+ (1,0) [0|0] "" BSR,DS1,FCM,MAV + SG_ VXRRHDS : 11|1@0+ (1,0) [0|0] "" FCM,KSS,MAV,SCS + SG_ VXRLF : 8|1@0+ (1,0) [0|0] "" AFS,BSR,FCM,MAV + SG_ VXRLIGS : 23|1@0+ (1,0) [0|0] "" BSR,DS1,FCM,MAV + SG_ VXRLHDS : 22|1@0+ (1,0) [0|0] "" FCM,KSS,MAV,SCS + SG_ VSCF02SM : 47|8@0+ (1,0) [0|0] "" AFS,DS1,FCM,MAV + +BO_ 550 VSC1F06: 8 CGW + SG_ VSCF01FG : 7|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ AHCURQ : 4|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PMCF : 3|1@0+ (1,0) [0|0] "" DS1 + SG_ PMCS : 2|1@0+ (1,0) [0|0] "" DS1 + SG_ PMC : 1|10@0+ (0.02,0) [0|0] "Mpa" DS1 + SG_ ECOEN : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ CCS : 22|1@0+ (1,0) [0|0] "" DS1 + SG_ FBA : 21|1@0+ (1,0) [0|0] "" DS1 + SG_ TRBRKSYS : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TS : 38|1@0+ (1,0) [0|0] "" KSS,SCS + SG_ WSTP : 37|1@0+ (1,0) [0|0] "" DS1,KSS,SCS + SG_ VSCACT : 36|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ BAEX : 35|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TEM : 34|3@0+ (1,0) [0|0] "" SCS + SG_ FSTP : 60|1@0+ (1,0) [0|0] "" DS1 + SG_ ABSACT : 59|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + +BO_ 180 VSC1S03: 8 CGW + SG_ SP1P : 39|6@0+ (1,0) [0|0] "" DS1,FCM + SG_ SP1S : 33|1@0+ (1,0) [0|0] "" BSR,DS1,FCM,MAV + SG_ SP1 : 47|16@0- (0.01,0) [0|0] "km/h" BSR,DS1,FCM,MAV + SG_ VSC03SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + +BO_ 800 VSC1S07: 8 CGW + SG_ FBKRLY : 6|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCM : 4|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCSFT : 3|1@0+ (1,0) [0|0] "" DS1 + SG_ FABS : 2|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ TSVSC : 1|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCL : 0|1@0+ (1,0) [0|0] "" DS1 + SG_ RQCSTBKB : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PSBSTBY : 14|1@0+ (1,0) [0|0] "" DS1 + SG_ P2BRXMK : 13|1@0+ (1,0) [0|0] "" DS1 + SG_ MCC : 11|1@0+ (1,0) [0|0] "" DS1 + SG_ RQBKB : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRSTOP : 9|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ BRKON : 8|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ ASLP : 23|8@0- (1,0) [0|0] "deg" DS1 + SG_ BRTYPACC : 31|2@0+ (1,0) [0|0] "" DS1 + SG_ BRKABT3 : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT2 : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT1 : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GVC : 39|8@0- (0.04,0) [0|0] "m/s^2" DS1 + SG_ XGVCINV : 43|1@0+ (1,0) [0|0] "" DS1 + SG_ S07CNT : 52|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSBRSTA : 50|2@0+ (1,0) [0|0] "" DS1 + SG_ VSC07SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM + +BO_ 1056 VSC1S08: 8 CGW + SG_ YR1Z : 7|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ YR2Z : 23|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ GL1Z : 39|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ GL2Z : 47|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ YRGSDIR : 55|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,SCS + SG_ GLZS : 51|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ YRZF : 50|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZS : 49|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZKS : 48|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ VSC08SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + +BO_ 186 VSC1S12: 4 CGW + SG_ HAC2ESRQ : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FHACHOLD : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VSC12SUM : 31|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 562 VSC1S14: 6 CGW + SG_ VWPSUMFR : 7|8@0+ (1,0) [0|0] "" MAV + SG_ VWPSUMFL : 15|8@0+ (1,0) [0|0] "" MAV + SG_ VWPFRPM : 23|1@0+ (1,0) [0|0] "" MAV + SG_ VWPFLPM : 22|1@0+ (1,0) [0|0] "" MAV + SG_ S14CNT : 21|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ VWPFRPMS : 18|1@0+ (1,0) [0|0] "" MAV + SG_ VWPFLPMS : 17|1@0+ (1,0) [0|0] "" MAV + SG_ VWPSUMRR : 31|8@0+ (1,0) [0|0] "" MAV + SG_ VWPSUMRL : 39|8@0+ (1,0) [0|0] "" MAV + SG_ VSC14SUM : 47|8@0+ (1,0) [0|0] "" MAV + +BO_ 552 VSC1S29: 4 CGW + SG_ ICBACT : 7|1@0+ (1,0) [0|0] "" DS1 + SG_ DVS0PCS : 6|15@0- (0.001,0) [0|0] "m/s^2" DS1 + SG_ SM228 : 31|8@0+ (1,0) [0|0] "" DS1 + +BO_ 1168 VSC1S92: 1 CGW + SG_ C_DCMOD1 : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_DCMOD2 : 6|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ C_DCMOD3 : 3|4@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 951 VSC1S95: 8 CGW + SG_ B_BRKW : 7|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_ABS : 5|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_BRLV : 14|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TRCOFF : 13|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ VSCOFF : 12|2@0+ (1,0) [0|0] "" DS1,FCM + SG_ SLP_WL : 10|3@0+ (1,0) [0|0] "" MAV + SG_ B_MCST : 19|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_BUZZER : 31|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_ALSD : 27|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_DACIND : 25|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ OGENVSC : 37|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_ATRC : 47|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_STRC : 46|3@0+ (1,0) [0|0] "" MAV + SG_ B_HZD : 43|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VSCSWIH : 51|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ STRCDISP : 50|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ STRCDSP2 : 60|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VSCEXIST : 59|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1063 VSC1S96: 8 CGW + SG_ MTS_DISP : 5|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ B_MTS : 1|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ TRCCONRL : 11|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TRCCONRR : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TRCCONFL : 9|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TRCCONFR : 8|1@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 545 VSC2F05: 5 CGW + SG_ TQER : 7|16@0- (0.03125,0) [0|0] "Nm" Vector__XXX + SG_ REQC : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ REQ2 : 22|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ REQ1 : 21|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AIDWI : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ RTD : 19|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ LOMUSFT : 31|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VSC2F05S : 39|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 544 VSC2F07: 4 CGW + SG_ FSROT : 7|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRK2 : 4|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRK1 : 3|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FCNG : 1|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TSLP : 0|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ TRCACT : 15|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ ABSSLP : 14|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ VDMACT : 13|1@0+ (1,0) [0|0] "" FCM + SG_ DAC_CND : 9|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ VSC2F07S : 31|8@0+ (1,0) [0|0] "" DS1,FCM + +BO_ 36 YGS1S03: 8 CGW + SG_ YRS11S : 7|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRS14S : 6|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRS21S : 5|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRS24S : 4|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YGS1 : 3|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ YGS0 : 2|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ YR : 1|10@0+ (0.244,-125) [0|0] "deg/sec" DS1,FCM,MAV + SG_ YR_CPUMN : 23|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ GS4S : 19|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ GS1S : 18|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ GL1X : 17|10@0+ (0.03589,-18.375) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ YG_ID : 39|4@0+ (1,0) [0|0] "" DS1,FCM,KSS,SCS + SG_ GS5S : 35|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ GS2S : 34|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ GL2Y : 33|10@0+ (0.03589,-18.375) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ YR_DIF : 55|8@0+ (0.244,-31) [0|0] "deg/sec" DS1,FCM,MAV + SG_ YGS03SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + +BO_ 1073743490 YGW1S01_0: 8 CGW + SG_ YGW01_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ YGW01_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ YR_STSW : 22|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ YR_EGST : 20|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ YR_DRLK : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ YR_KLEG : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ YR_HZRD : 26|3@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1073743491 YGW1S02_0: 8 CGW + SG_ YGW02_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ YGW02_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ YR_DEFOG : 19|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ YR_ARCON : 17|2@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1073743494 YGW1S05_0: 8 CGW + SG_ YGW05_ID : 7|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ YGW05_IF : 15|8@0+ (1,0) [0|0] "" Vector__XXX + SG_ YI_IMO_E : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ YI_UREQ : 16|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ YI_RE : 47|16@0+ (1,0) [0|0] "" Vector__XXX diff --git a/opendbc/toyota_adas.dbc b/opendbc_repo/opendbc/dbc/toyota_adas.dbc similarity index 100% rename from opendbc/toyota_adas.dbc rename to opendbc_repo/opendbc/dbc/toyota_adas.dbc diff --git a/opendbc_repo/opendbc/dbc/toyota_iQ_2009_can.dbc b/opendbc_repo/opendbc/dbc/toyota_iQ_2009_can.dbc new file mode 100644 index 000000000000000..2213e1ade23f316 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/toyota_iQ_2009_can.dbc @@ -0,0 +1,196 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX + +BO_ 1552 CONTAINS_LRES_SPEED: 8 XXX + SG_ SPEED_LOWRES : 16|8@1+ (1,0) [0|255] "km/h?" XXX + SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX + +BO_ 452 ENGINE: 8 XXX + SG_ ENGINE_RPM : 7|16@0+ (1,0) [0|65535] "rpm" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ DIFFERENT_EACH_RIDE : 23|8@0+ (1,0) [0|255] "" XXX + SG_ A_DECREASING_VALUE : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 37 STEERING: 8 XXX + SG_ STEER_DIRECTION : 3|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 42|2@0- (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_2 : 44|2@0- (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 46|2@0- (1,0) [0|3] "" XXX + SG_ STEER_ANGLE : 2|11@0- (1,0) [-350|350] "" XXX + +BO_ 36 ACCELERATIONS: 8 XXX + SG_ ACC_LAT_CLEAN : 2|11@0- (1,0) [0|255] "" XXX + SG_ ACC_LATERAL : 63|8@0- (1,0) [0|255] "" XXX + SG_ ACC_FRONT_BACK_1 : 31|8@0- (1,0) [0|255] "" XXX + SG_ ACC_FRONT_BACK_2 : 47|8@0- (1,0) [0|255] "" XXX + +BO_ 947 LOW_RES_INDICATORS: 8 XXX + SG_ LOW_RES_ACC_PEDAL : 23|7@0+ (1,0) [0|63] "" XXX + SG_ LOW_RES_RPM : 7|16@0+ (1,0) [0|255] "rpm" XXX + +BO_ 955 BRAKING_PLUS_OTHER: 8 XXX + SG_ IS_BRAKING_2 : 0|1@0+ (1,0) [0|1] "" XXX + SG_ ENGINE_TEMPERATURE : 23|8@0+ (1,0) [0|255] "" XXX + SG_ MAYBE_CLUTCH : 13|1@0+ (1,0) [0|1] "" XXX + +BO_ 1595 CONTAINS_TIME: 8 XXX + SG_ TIME_ON : 55|16@0+ (0.1,0) [0|65535] "s" XXX + SG_ BETWEEN_RIDES : 7|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 170 WHEELS_SPEEDS: 8 XXX + SG_ FRONT_LEFT_WHEEL_SPEED : 23|16@0+ (0.01,-67.67) [0|65535] "km/h" XXX + SG_ REAR_RIGHT_WHEEL_SPEED : 39|16@0+ (0.01,-67.67) [0|65535] "km/h" XXX + SG_ REAR_LEFT_WHEEL_SPEED : 55|16@0+ (0.01,-67.67) [0|65535] "km/h" XXX + SG_ FRONT_RIGHT_WHEEL_SPEED : 7|16@0+ (0.01,-67.67) [0|65535] "km/h" XXX + +BO_ 180 VEHICLE_DYNAMICS: 8 XXX + SG_ WIERD_STUFF : 8|2@1+ (1,0) [0|3] "" XXX + SG_ VEHICLE_SPEED : 47|16@0+ (0.01,0) [0|255] "km/h" XXX + SG_ SPEED_MOD_256 : 63|8@0- (1,0) [0|255] "" XXX + SG_ MAYBE_DISTANCE_MOD_256 : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 186 NEW_MSG_9: 8 XXX + SG_ NEW_SIGNAL_2 : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 426 NEW_MSG_5: 8 XXX + SG_ CONSTANT : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 906 BOOLS: 8 XXX + SG_ MAY_CONTAIN_LIGHTS : 7|4@0+ (1,0) [0|127] "" XXX + SG_ NEW_SIGNAL_1 : 3|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 2|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 1|1@0+ (1,0) [0|1] "" XXX + SG_ MOVEMENT_START_TRIGGER : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 979 LOW_RES_ACCELERATOR: 8 XXX + SG_ VERY_LRES_ACC : 7|16@0+ (1,0) [0|65535] "" XXX + +BO_ 1600 SLOW_VARIABLE_INFOS: 8 XXX + SG_ CHANGES_EACH_RIDE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ INCREASING_VALUE_FUEL : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 1568 DOORS: 8 XXX + SG_ KEY_ACC : 36|1@0+ (1,0) [0|1] "" XXX + SG_ KEY_ON : 37|1@0+ (1,0) [0|1] "" XXX + SG_ KEY_INSERT : 46|1@0+ (1,0) [0|1] "" XXX + SG_ NOT_ON : 63|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_RIGHT : 44|1@0+ (1,0) [0|3] "" XXX + SG_ DOOR_TRUNK : 41|1@1+ (1,0) [0|3] "" XXX + SG_ DOOR_LEFT : 45|1@0+ (1,0) [0|255] "" XXX + SG_ HANDBRAKE : 60|1@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_1 : 4|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVER_SEATBELT : 62|1@0+ (1,0) [0|1] "" XXX + SG_ TRIGGER_BOOL : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 705 COMMAND: 8 XXX + SG_ NOT_ACCELERATING_PEDAL : 3|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_PEDAL_SENSOR : 55|16@0+ (1,0) [0|65535] "" XXX + SG_ ACC_COMMAND : 31|16@0- (1,0) [0|7] "" XXX + SG_ ACC_PEDAL_MEAN : 15|16@0- (1,0) [0|255] "" XXX + SG_ NEGATIVE_COMMAND_OFFSET : 47|8@0- (1,0) [0|255] "" XXX + +BO_ 928 STEER2_MAYBE: 8 XXX + SG_ NEW_SIGNAL_1 : 13|6@0+ (1,0) [0|63] "" XXX + SG_ NEW_SIGNAL_2 : 60|5@0+ (1,0) [0|31] "" XXX + SG_ NEW_SIGNAL_4 : 5|6@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 46|7@0+ (1,0) [0|15] "" XXX + +BO_ 896 LONG_TERM_2: 8 XXX + SG_ NEW_SIGNAL_1 : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 944 LONG_TERM_MSG: 8 XXX + SG_ LONG_TERM_SIGN : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 1553 TOTAL_DIST: 8 XXX + SG_ TOTAL_DISTANCE : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 1572 WHY_THESE_VALUES: 8 XXX + +BO_ 1555 BETWEEN_RIDES_CHANGE_1: 8 XXX + SG_ BETWEEN_RIDES : 23|1@0+ (1,0) [0|1] "" XXX + +BO_ 1090 ASYNC_MSG_ACK: 8 XXX + SG_ NEW_SIGNAL_1 : 13|2@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 23|1@0+ (1,0) [0|1] "" XXX + +BO_ 1592 NEW_MSG_14: 8 XXX + SG_ DOORS_LOCKED2 : 20|1@0+ (1,0) [0|1] "" XXX + SG_ DOORS_LOCKED1 : 16|1@0+ (1,0) [0|1] "" XXX + +BO_ 608 NEW_MSG_6: 8 XXX + SG_ VERY_SMALL_SIGNAL2 : 56|1@0+ (1,0) [0|255] "" XXX + SG_ VERY_SMALL_SIGNAL1 : 0|1@0+ (1,0) [0|1] "" XXX + +BO_ 945 BETWEEN_RIDES_CHANGES_2: 8 XXX + SG_ BETWEEN_RIDES : 24|1@0+ (1,0) [0|65535] "" XXX + + + + +CM_ SG_ 1552 SPEED_LOWRES "Negative values to check"; +CM_ SG_ 452 CHECKSUM "Follows path of RPMs but more precise & 1 byte only"; +CM_ SG_ 452 A_DECREASING_VALUE "stabilizes to 62 after ~10 mins"; +CM_ SG_ 37 STEER_DIRECTION "Could be intended as 12 bit steering angle"; +CM_ SG_ 37 STEER_ANGLE "can convert to degrees (imprecise) or percentage of max amplitude"; +CM_ SG_ 36 ACC_FRONT_BACK_1 "more likely up-down"; +CM_ SG_ 36 ACC_FRONT_BACK_2 "more likely front-back"; +CM_ SG_ 947 LOW_RES_ACC_PEDAL "Follows rather closely other acceleration commands"; +CM_ SG_ 947 LOW_RES_RPM "Maybe used for onboard display?"; +CM_ SG_ 955 MAYBE_CLUTCH "might be related to shifting gears"; +CM_ SG_ 1595 TIME_ON "Time since last ignition, tenth of seconds"; +CM_ SG_ 1595 BETWEEN_RIDES "the fourth byte (at least) changes between rides"; +CM_ SG_ 180 WIERD_STUFF "Might be a signed value on the whole two bytes (sometimes all set)"; +CM_ SG_ 180 VEHICLE_SPEED "Roughly 2 seconds before wheel speeds"; +CM_ SG_ 180 SPEED_MOD_256 "One byte speed, a bit before vehicle speed"; +CM_ SG_ 180 MAYBE_DISTANCE_MOD_256 "Looks like measure for distance or wheel angle"; +CM_ SG_ 906 MOVEMENT_START_TRIGGER "trigger of when speed becomes != 0"; +CM_ SG_ 979 VERY_LRES_ACC "Power used by engine? moves alongside speed, very low res, goes from 0 to 9 max?"; +CM_ SG_ 1600 CHANGES_EACH_RIDE "Small decrementation during some rides, possibly long term fuel"; +CM_ SG_ 1600 INCREASING_VALUE_FUEL "Fuel/distance? Average fuel consumption?"; +CM_ SG_ 705 NOT_ACCELERATING_PEDAL "Looks like opposite of accelerating bit"; +CM_ SG_ 705 ACC_PEDAL_SENSOR "similar to pedal sensor maybe checksum."; +CM_ SG_ 705 ACC_COMMAND "Similar to other pedal indicator., cleaner, must be sent back to engine"; +CM_ SG_ 705 ACC_PEDAL_MEAN "Actual sensor for pedal (works when engine off)"; +CM_ SG_ 705 NEGATIVE_COMMAND_OFFSET "Mysterious for now"; +CM_ SG_ 928 NEW_SIGNAL_1 "Very slow changing noisy value, 45-49 in 10 min"; +CM_ SG_ 928 NEW_SIGNAL_2 "Other very slow changing 24-26 in 10 min"; +CM_ SG_ 928 NEW_SIGNAL_4 "Inconsistent across rides"; +CM_ SG_ 896 NEW_SIGNAL_1 "there is a difference at the beginning of 2017-10-31--12-04-05"; +CM_ SG_ 1553 TOTAL_DISTANCE "Probably also contains the previous/two previous bytes but can't confirm"; +CM_ SG_ 945 BETWEEN_RIDES "Might be others in the same message. at least this one"; + diff --git a/opendbc/toyota_new_mc_pt_generated.dbc b/opendbc_repo/opendbc/dbc/toyota_new_mc_pt_generated.dbc similarity index 84% rename from opendbc/toyota_new_mc_pt_generated.dbc rename to opendbc_repo/opendbc/dbc/toyota_new_mc_pt_generated.dbc index dfb69df492fd4bb..c7de833c368cfc1 100644 --- a/opendbc/toyota_new_mc_pt_generated.dbc +++ b/opendbc_repo/opendbc/dbc/toyota_new_mc_pt_generated.dbc @@ -1,50 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STATE : 23|4@0+ (1,0) [0|15] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS-P Toyotas. Learn more: https://github.com/RetroPilot/ocelot/tree/main/firmware/smart_dsu"; -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -VAL_ 767 STATE 7 "STATE_AEB_CTRL" 6 "FAULT_INVALID" 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -93,9 +49,24 @@ BO_ 37 STEER_ANGLE_SENSOR: 8 XXX SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX +BO_ 119 ENG2F41: 6 CGW + SG_ FDRV : 7|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ FDRVREAL : 23|13@0- (10,0) [0|0] "N" Vector__XXX + SG_ XAECT : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XFDRVCOL : 38|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVSELP : 34|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F41S : 47|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 120 ENG2F42: 4 CGW + SG_ FAVLMCHH : 7|16@0- (2,0) [0|0] "N" Vector__XX228X + SG_ CCRNG : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVTYPD : 22|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ GEARHD : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F42S : 31|8@0+ (1,0) [0|0] "" Vector__XXX + BO_ 166 BRAKE: 8 XXX SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_FORCE : 23|8@0+ (40,0) [0|10200] "N" XXX BO_ 170 WHEEL_SPEEDS: 8 XXX SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX @@ -109,8 +80,8 @@ BO_ 180 SPEED: 8 XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 295 GEAR_PACKET_HYBRID: 8 XXX - SG_ CAR_MOVEMENT : 25|10@0- (1,0) [0|255] "" XXX - SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ FDRVREAL : 26|11@0- (25,0) [-25600|25575] "N" XXX + SG_ UNKNOWN : 55|8@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX @@ -119,6 +90,7 @@ BO_ 353 DSU_SPEED: 7 XXX BO_ 452 ENGINE_RPM: 8 CGW SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS + SG_ ENGINE_RUNNING : 27|1@0+ (1,0) [0|1] "" XXX BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX @@ -139,9 +111,10 @@ BO_ 467 PCM_CRUISE_2: 8 XXX SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "m/s^2" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s^2" XXX +BO_ 552 VSC1S29: 4 CGW + SG_ ICBACT : 7|1@0+ (1,0) [0|0] "" DS1 + SG_ DVS0PCS : 6|15@0- (0.001,0) [0|0] "m/s^2" DS1 + SG_ SM228 : 31|8@0+ (1,0) [0|0] "" DS1 BO_ 560 BRAKE_2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX @@ -180,7 +153,11 @@ BO_ 643 PRE_COLLISION: 7 DSU BO_ 705 GAS_PEDAL: 8 XXX SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX @@ -195,6 +172,31 @@ BO_ 742 LEAD_INFO: 8 DSU SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU +BO_ 800 VSC1S07: 8 CGW + SG_ FBKRLY : 6|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCM : 4|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCSFT : 3|1@0+ (1,0) [0|0] "" DS1 + SG_ FABS : 2|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ TSVSC : 1|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCL : 0|1@0+ (1,0) [0|0] "" DS1 + SG_ RQCSTBKB : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PSBSTBY : 14|1@0+ (1,0) [0|0] "" DS1 + SG_ P2BRXMK : 13|1@0+ (1,0) [0|0] "" DS1 + SG_ MCC : 11|1@0+ (1,0) [0|0] "" DS1 + SG_ RQBKB : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRSTOP : 9|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ BRKON : 8|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ ASLP : 23|8@0- (1,0) [0|0] "deg" DS1 + SG_ BRTYPACC : 31|2@0+ (1,0) [0|0] "" DS1 + SG_ BRKABT3 : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT2 : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT1 : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GVC : 39|8@0- (0.04,0) [0|0] "m/s^2" DS1 + SG_ XGVCINV : 43|1@0+ (1,0) [0|0] "" DS1 + SG_ S07CNT : 52|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSBRSTA : 50|2@0+ (1,0) [0|0] "" DS1 + SG_ VSC07SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM + BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX @@ -213,12 +215,19 @@ BO_ 835 ACC_CONTROL: 8 DSU SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 836 PRE_COLLISION_2: 8 DSU + SG_ DSS1GDRV : 7|10@0- (0.1,0) [0|0] "m/s^2" Vector__XXX + SG_ PCSALM : 17|1@0+ (1,0) [0|0] "" FCM + SG_ IBTRGR : 27|1@0+ (1,0) [0|0] "" FCM + SG_ PBATRGR : 30|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PREFILL : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVSTRGR : 36|1@0+ (1,0) [0|0] "" SCS SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX BO_ 865 CLUTCH: 8 XXX SG_ ACC_FAULTED : 32|1@0+ (1,0) [0|1] "" XXX SG_ GAS_PEDAL_ALT : 23|8@0+ (0.005,0) [0|1] "" XXX SG_ CLUTCH_RELEASED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 48|16@1+ (0.0002,-6.5536) [-6.5536|6.5534] "" XXX BO_ 869 DSU_CRUISE : 7 DSU SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX @@ -320,6 +329,18 @@ BO_ 1044 AUTO_HIGH_BEAM: 8 FCM SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX +BO_ 1056 VSC1S08: 8 CGW + SG_ YR1Z : 7|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ YR2Z : 23|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ GL1Z : 39|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ GL2Z : 47|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ YRGSDIR : 55|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,SCS + SG_ GLZS : 51|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ YRZF : 50|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZS : 49|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZKS : 48|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ VSC08SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + BO_ 1083 AUTOPARK_STATUS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX @@ -398,9 +419,11 @@ BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX BO_ 1553 UI_SETTING: 8 XXX SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX SG_ ODOMETER : 39|32@0+ (1,0) [0|1048575] "" XXX + BO_ 1556 BLINKERS_STATE: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + SG_ BLINKER_BUTTON_PRESSED : 15|1@0+ (1,0) [0|1] "" XXX SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX BO_ 1568 BODY_CONTROL_STATE: 8 XXX SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX @@ -429,13 +452,30 @@ BO_ 1592 DOOR_LOCKS: 8 XXX SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX +BO_ 1779 ADAS_TOGGLE_STATE: 8 XXX + SG_ OK_BUTTON_PRESSED : 15|1@0+ (1,0) [0|1] "" BCM + SG_ SWS_TOGGLE_CMD : 24|1@0+ (1,0) [0|1] "" XXX + SG_ SWS_SENSITIVITY_CMD : 26|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_ON_CMD : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_OFF_CMD : 29|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY_HI_CMD : 30|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY_STD_CMD : 31|1@0+ (1,0) [0|1] "" XXX + SG_ IPAS_TOGGLE : 34|1@0+ (1,0) [0|1] "" XXX + SG_ BSM_TOGGLE_CMD : 37|1@0+ (1,0) [0|1] "" XXX + SG_ IPAS_SONAR_TOGGLE : 38|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_TOGGLE_CMD : 40|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_SENSITIVITY_CMD : 41|1@0+ (1,0) [0|1] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 ACCEL_X "x-axis accel"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 119 FDRVREAL "ICE only: force applied by wheels from the engine. includes creeping force, regen, and engine braking"; +CM_ SG_ 166 BRAKE_FORCE "hybrid only: force applied by friction brakes from user or ACC command"; +CM_ SG_ 295 FDRVREAL "hybrid only: force applied by wheels from the engine and/or electric motors. includes creeping force, regen, and engine braking"; CM_ SG_ 466 NEUTRAL_FORCE "force in newtons the engine/electric motors are applying without any acceleration commands or user input"; CM_ SG_ 466 ACC_BRAKING "whether brakes are being actuated from ACC command"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 466 ACCEL_NET "net negative acceleration (braking) applied by the system if on flat ground"; CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; CM_ SG_ 467 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement"; CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; @@ -448,6 +488,8 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 _COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 800 SLOPE_ANGLE "potentially used by the PCM to compensate for road pitch"; +CM_ SG_ 800 ACCEL "filtered ego acceleration"; CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; @@ -460,6 +502,7 @@ CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 865 GAS_PEDAL_ALT "copy of main GAS_PEDAL. Both use 8 bits. Might indicate that this message is for pedals."; CM_ SG_ 865 CLUTCH_RELEASED "boolean of clutch for 6MT."; +CM_ SG_ 865 ACCEL_NET "net positive acceleration (gas) applied by the system if on flat ground, may not include creeping force"; CM_ SG_ 865 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement. Also describes a lockout when the ACC_CONTROL->ACC_MALFUNCTION bit is set."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in the vehicle's UI with the vehicle's unit"; CM_ SG_ 921 TEMP_ACC_FAULTED "1 when the UI is displaying or playing fault-related alerts or sounds. Also 1 when pressing main on."; @@ -560,6 +603,7 @@ VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; VAL_ 1552 UNITS 1 "km (km/L)" 2 "km (L/100km)" 3 "miles (MPG US)" 4 "miles (MPG Imperial)"; VAL_ 1553 UNITS 1 "km" 2 "miles"; VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1556 BLINKER_BUTTON_PRESSED 1 "button pressed" 0 "not pressed"; VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; CM_ "toyota_new_mc_pt.dbc starts here"; diff --git a/opendbc/toyota_nodsu_pt_generated.dbc b/opendbc_repo/opendbc/dbc/toyota_nodsu_pt_generated.dbc similarity index 86% rename from opendbc/toyota_nodsu_pt_generated.dbc rename to opendbc_repo/opendbc/dbc/toyota_nodsu_pt_generated.dbc index efbcccc86090b36..f392713b6ad188a 100644 --- a/opendbc/toyota_nodsu_pt_generated.dbc +++ b/opendbc_repo/opendbc/dbc/toyota_nodsu_pt_generated.dbc @@ -1,50 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STATE : 23|4@0+ (1,0) [0|15] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS-P Toyotas. Learn more: https://github.com/RetroPilot/ocelot/tree/main/firmware/smart_dsu"; -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -VAL_ 767 STATE 7 "STATE_AEB_CTRL" 6 "FAULT_INVALID" 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -93,9 +49,24 @@ BO_ 37 STEER_ANGLE_SENSOR: 8 XXX SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX +BO_ 119 ENG2F41: 6 CGW + SG_ FDRV : 7|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ FDRVREAL : 23|13@0- (10,0) [0|0] "N" Vector__XXX + SG_ XAECT : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XFDRVCOL : 38|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVSELP : 34|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F41S : 47|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 120 ENG2F42: 4 CGW + SG_ FAVLMCHH : 7|16@0- (2,0) [0|0] "N" Vector__XX228X + SG_ CCRNG : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVTYPD : 22|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ GEARHD : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F42S : 31|8@0+ (1,0) [0|0] "" Vector__XXX + BO_ 166 BRAKE: 8 XXX SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_FORCE : 23|8@0+ (40,0) [0|10200] "N" XXX BO_ 170 WHEEL_SPEEDS: 8 XXX SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX @@ -109,8 +80,8 @@ BO_ 180 SPEED: 8 XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 295 GEAR_PACKET_HYBRID: 8 XXX - SG_ CAR_MOVEMENT : 25|10@0- (1,0) [0|255] "" XXX - SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ FDRVREAL : 26|11@0- (25,0) [-25600|25575] "N" XXX + SG_ UNKNOWN : 55|8@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX @@ -119,6 +90,7 @@ BO_ 353 DSU_SPEED: 7 XXX BO_ 452 ENGINE_RPM: 8 CGW SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS + SG_ ENGINE_RUNNING : 27|1@0+ (1,0) [0|1] "" XXX BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX @@ -139,9 +111,10 @@ BO_ 467 PCM_CRUISE_2: 8 XXX SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "m/s^2" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s^2" XXX +BO_ 552 VSC1S29: 4 CGW + SG_ ICBACT : 7|1@0+ (1,0) [0|0] "" DS1 + SG_ DVS0PCS : 6|15@0- (0.001,0) [0|0] "m/s^2" DS1 + SG_ SM228 : 31|8@0+ (1,0) [0|0] "" DS1 BO_ 560 BRAKE_2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX @@ -180,7 +153,11 @@ BO_ 643 PRE_COLLISION: 7 DSU BO_ 705 GAS_PEDAL: 8 XXX SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX @@ -195,6 +172,31 @@ BO_ 742 LEAD_INFO: 8 DSU SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU +BO_ 800 VSC1S07: 8 CGW + SG_ FBKRLY : 6|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCM : 4|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCSFT : 3|1@0+ (1,0) [0|0] "" DS1 + SG_ FABS : 2|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ TSVSC : 1|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCL : 0|1@0+ (1,0) [0|0] "" DS1 + SG_ RQCSTBKB : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PSBSTBY : 14|1@0+ (1,0) [0|0] "" DS1 + SG_ P2BRXMK : 13|1@0+ (1,0) [0|0] "" DS1 + SG_ MCC : 11|1@0+ (1,0) [0|0] "" DS1 + SG_ RQBKB : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRSTOP : 9|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ BRKON : 8|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ ASLP : 23|8@0- (1,0) [0|0] "deg" DS1 + SG_ BRTYPACC : 31|2@0+ (1,0) [0|0] "" DS1 + SG_ BRKABT3 : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT2 : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT1 : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GVC : 39|8@0- (0.04,0) [0|0] "m/s^2" DS1 + SG_ XGVCINV : 43|1@0+ (1,0) [0|0] "" DS1 + SG_ S07CNT : 52|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSBRSTA : 50|2@0+ (1,0) [0|0] "" DS1 + SG_ VSC07SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM + BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX @@ -213,12 +215,19 @@ BO_ 835 ACC_CONTROL: 8 DSU SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 836 PRE_COLLISION_2: 8 DSU + SG_ DSS1GDRV : 7|10@0- (0.1,0) [0|0] "m/s^2" Vector__XXX + SG_ PCSALM : 17|1@0+ (1,0) [0|0] "" FCM + SG_ IBTRGR : 27|1@0+ (1,0) [0|0] "" FCM + SG_ PBATRGR : 30|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PREFILL : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVSTRGR : 36|1@0+ (1,0) [0|0] "" SCS SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX BO_ 865 CLUTCH: 8 XXX SG_ ACC_FAULTED : 32|1@0+ (1,0) [0|1] "" XXX SG_ GAS_PEDAL_ALT : 23|8@0+ (0.005,0) [0|1] "" XXX SG_ CLUTCH_RELEASED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 48|16@1+ (0.0002,-6.5536) [-6.5536|6.5534] "" XXX BO_ 869 DSU_CRUISE : 7 DSU SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX @@ -320,6 +329,18 @@ BO_ 1044 AUTO_HIGH_BEAM: 8 FCM SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX +BO_ 1056 VSC1S08: 8 CGW + SG_ YR1Z : 7|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ YR2Z : 23|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ GL1Z : 39|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ GL2Z : 47|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ YRGSDIR : 55|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,SCS + SG_ GLZS : 51|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ YRZF : 50|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZS : 49|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZKS : 48|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ VSC08SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + BO_ 1083 AUTOPARK_STATUS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX @@ -398,9 +419,11 @@ BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX BO_ 1553 UI_SETTING: 8 XXX SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX SG_ ODOMETER : 39|32@0+ (1,0) [0|1048575] "" XXX + BO_ 1556 BLINKERS_STATE: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + SG_ BLINKER_BUTTON_PRESSED : 15|1@0+ (1,0) [0|1] "" XXX SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX BO_ 1568 BODY_CONTROL_STATE: 8 XXX SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX @@ -429,13 +452,30 @@ BO_ 1592 DOOR_LOCKS: 8 XXX SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX +BO_ 1779 ADAS_TOGGLE_STATE: 8 XXX + SG_ OK_BUTTON_PRESSED : 15|1@0+ (1,0) [0|1] "" BCM + SG_ SWS_TOGGLE_CMD : 24|1@0+ (1,0) [0|1] "" XXX + SG_ SWS_SENSITIVITY_CMD : 26|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_ON_CMD : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_OFF_CMD : 29|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY_HI_CMD : 30|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY_STD_CMD : 31|1@0+ (1,0) [0|1] "" XXX + SG_ IPAS_TOGGLE : 34|1@0+ (1,0) [0|1] "" XXX + SG_ BSM_TOGGLE_CMD : 37|1@0+ (1,0) [0|1] "" XXX + SG_ IPAS_SONAR_TOGGLE : 38|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_TOGGLE_CMD : 40|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_SENSITIVITY_CMD : 41|1@0+ (1,0) [0|1] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 ACCEL_X "x-axis accel"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 119 FDRVREAL "ICE only: force applied by wheels from the engine. includes creeping force, regen, and engine braking"; +CM_ SG_ 166 BRAKE_FORCE "hybrid only: force applied by friction brakes from user or ACC command"; +CM_ SG_ 295 FDRVREAL "hybrid only: force applied by wheels from the engine and/or electric motors. includes creeping force, regen, and engine braking"; CM_ SG_ 466 NEUTRAL_FORCE "force in newtons the engine/electric motors are applying without any acceleration commands or user input"; CM_ SG_ 466 ACC_BRAKING "whether brakes are being actuated from ACC command"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 466 ACCEL_NET "net negative acceleration (braking) applied by the system if on flat ground"; CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; CM_ SG_ 467 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement"; CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; @@ -448,6 +488,8 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 _COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 800 SLOPE_ANGLE "potentially used by the PCM to compensate for road pitch"; +CM_ SG_ 800 ACCEL "filtered ego acceleration"; CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; @@ -460,6 +502,7 @@ CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 865 GAS_PEDAL_ALT "copy of main GAS_PEDAL. Both use 8 bits. Might indicate that this message is for pedals."; CM_ SG_ 865 CLUTCH_RELEASED "boolean of clutch for 6MT."; +CM_ SG_ 865 ACCEL_NET "net positive acceleration (gas) applied by the system if on flat ground, may not include creeping force"; CM_ SG_ 865 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement. Also describes a lockout when the ACC_CONTROL->ACC_MALFUNCTION bit is set."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in the vehicle's UI with the vehicle's unit"; CM_ SG_ 921 TEMP_ACC_FAULTED "1 when the UI is displaying or playing fault-related alerts or sounds. Also 1 when pressing main on."; @@ -560,6 +603,7 @@ VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; VAL_ 1552 UNITS 1 "km (km/L)" 2 "km (L/100km)" 3 "miles (MPG US)" 4 "miles (MPG Imperial)"; VAL_ 1553 UNITS 1 "km" 2 "miles"; VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1556 BLINKER_BUTTON_PRESSED 1 "button pressed" 0 "not pressed"; VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; CM_ "toyota_nodsu_pt.dbc starts here"; diff --git a/opendbc_repo/opendbc/dbc/toyota_prius_2010_pt.dbc b/opendbc_repo/opendbc/dbc/toyota_prius_2010_pt.dbc new file mode 100644 index 000000000000000..5c7df7d18b3ea7f --- /dev/null +++ b/opendbc_repo/opendbc/dbc/toyota_prius_2010_pt.dbc @@ -0,0 +1,203 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX DSU HCU EPS IPAS + + +BO_ 36 KINEMATICS: 8 XXX + SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX + SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX + SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX + +BO_ 166 BRAKE: 8 XXX + SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.0062,-67.67) [0|250] "mph" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.0062,-67.67) [0|250] "mph" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.0062,-67.67) [0|250] "mph" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.0062,-67.67) [0|250] "mph" XXX + +BO_ 180 SPEED: 8 XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SPEED : 47|16@0+ (0.0062,0) [0|115] "mph" XXX + SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 295 GEAR_PACKET: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + +BO_ 466 PCM_CRUISE: 8 XXX + SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 552 ACCELEROMETER: 8 XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + +BO_ 560 BRAKE_MODULE2: 8 XXX + SG_ BRAKE_LIGHTS : 26|1@0+ (1,0) [0|1] "" XXX + +BO_ 581 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 5 EPS + SG_ STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 614 STEERING_IPAS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1,0) [0|16777215] "" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 XXX + +BO_ 740 STEERING_LKA: 8 XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + +BO_ 1556 STEERING_LEVERS: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 XXX + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_1 : 7|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SEETING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 SEATS_DOORS: 8 XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 452 POWERTRAIN: 8 XXX + SG_ ENGINE_RPM : 7|16@0+ (1,0) [0|65535] "rpm" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + + + + +CM_ SG_ 36 ACCEL_Y "unit is tbd"; +CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; +CM_ SG_ 36 YAW_RATE "verify"; +CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 560 BRAKE_LIGHTS "double check"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; +CM_ SG_ 1042 SET_ME_1 "unclear what this is, nut it's always 1 in drive traces"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B" ; +VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "setspeeddown" 9 "setspeedup" 8 "active" 7 "standstill" 1 "off" 0 "off"; +VAL_ 610 STATE 5 "override" 3 "enabled" 1 "disabled" ; +VAL_ 610 LKA_STATE 50 "temporary_fault" ; +VAL_ 614 STATE 3 "enabled" 1 "disabled" ; +VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left" ; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ; +VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ; +VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted" ; +VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none" ; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none" ; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none" ; +VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none" ; +VAL_ 1553 UNITS 1 "km" 2 "miles" ; diff --git a/opendbc_repo/opendbc/dbc/toyota_radar_dsu_tssp.dbc b/opendbc_repo/opendbc/dbc/toyota_radar_dsu_tssp.dbc new file mode 100644 index 000000000000000..168e589136b8c6d --- /dev/null +++ b/opendbc_repo/opendbc/dbc/toyota_radar_dsu_tssp.dbc @@ -0,0 +1,194 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX RADAR + +BO_ 768 BUTTONS: 8 RADAR + SG_ LKAS_PRESS : 2|1@0+ (1,0) [0|1] "" XXX + SG_ DISTANCE_PRESS : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 769 OBJECT_0: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 771 OBJECT_1: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 773 OBJECT_2: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 775 OBJECT_3: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 777 OBJECT_4: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 779 OBJECT_5: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 781 OBJECT_6: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 783 OBJECT_7: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 785 OBJECT_8: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 787 OBJECT_9: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 789 OBJECT_10: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 791 OBJECT_11: 8 RADAR + SG_ ID : 5|6@0+ (1,0) [0|255] "" XXX + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|65535] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.018,0) [0|15] "" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "Front target" +BO_ 1664 CLUSTER_F: 8 RADAR + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|255] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.015,0) [-20|20] "m" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ ID : 0|6@1+ (1,0) [0|63] "" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "Front target ahead" +BO_ 1665 CLUSTER_F_A: 8 RADAR + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|255] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.015,0) [-20|20] "m" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ ID : 0|6@1+ (1,0) [0|63] "" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "Left target" +BO_ 1666 CLUSTER_L: 8 RADAR + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|255] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.015,0) [-20|20] "m" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ VALID : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ID : 0|6@1+ (1,0) [0|63] "" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "Right target" +BO_ 1667 CLUSTER_R: 8 RADAR + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|255] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.015,0) [-20|20] "m" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ VALID : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ID : 0|6@1+ (1,0) [0|63] "" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "Left target ahead" +BO_ 1668 CLUSTER_L_A: 8 RADAR + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|255] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.015,0) [-20|20] "m" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ VALID : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ID : 0|6@1+ (1,0) [0|63] "" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "Right target ahead" +BO_ 1669 CLUSTER_R_A: 8 RADAR + SG_ LONG_DIST : 7|13@1+ (0.03,0) [0|255] "m" XXX + SG_ LAT_DIST : 20|11@1- (0.015,0) [-20|20] "m" XXX + SG_ SPEED : 31|10@1- (0.06944444444,0) [0|71] "m/s" XXX + SG_ VALID : 6|1@0+ (1,0) [0|1] "" XXX + SG_ ID : 0|6@1+ (1,0) [0|63] "" XXX + SG_ LAT_SPEED : 48|7@1- (0.1,0) [0|127] "m/s" XXX + SG_ RCS : 63|8@0+ (1,0) [0|255] "" XXX diff --git a/opendbc_repo/opendbc/dbc/toyota_rav4_prime_generated.dbc b/opendbc_repo/opendbc/dbc/toyota_rav4_prime_generated.dbc new file mode 100644 index 000000000000000..fb269f2430956bd --- /dev/null +++ b/opendbc_repo/opendbc/dbc/toyota_rav4_prime_generated.dbc @@ -0,0 +1,481 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + +CM_ "toyota_rav4_prime.dbc starts here"; +VERSION "" + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX DSU HCU EPS IPAS CGW BGM + +BO_ 15 SECOC_SYNCHRONIZATION: 8 XXX + SG_ TRIP_CNT : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ RESET_CNT : 23|20@0+ (1,0) [0|65535] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + +BO_ 37 STEER_ANGLE_SENSOR: 8 XXX + SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX + SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX + SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX + +BO_ 170 WHEEL_SPEEDS: 8 XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + +BO_ 257 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_PRESSURE_1 : 31|8@0+ (1,0) [0|15] "" XXX + SG_ BRAKE_PRESSURE_2 : 61|6@0+ (1,0) [0|63] "" XXX + +BO_ 278 GAS_PEDAL: 8 XXX + SG_ GAS_PEDAL_ACC : 7|8@0+ (0.005,0) [0|255] "" XXX + SG_ GAS_PEDAL_USER : 15|8@0+ (0.005,0) [0|255] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 295 GEAR_PACKET_HYBRID: 8 XXX + SG_ CAR_MOVEMENT : 25|10@0- (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 305 STEERING_LTA_2: 8 XXX + SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_REQUEST : 3|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 13|6@0+ (1,0) [0|63] "" XXX + SG_ STEER_ANGLE_CMD : 23|16@0- (0.0573,0) [0|65535] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 353 DSU_SPEED: 7 XXX + SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "km/h" XXX + +BO_ 374 PCM_CRUISE: 8 XXX + SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_STATE : 31|4@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 375 PCM_CRUISE_3: 8 XXX + SG_ NEW_SIGNAL_1 : 7|16@0- (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_4 : 16|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_6 : 19|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_7 : 21|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_5 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ GAS_RELEASED : 30|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_2 : 31|1@0+ (1,0) [0|1] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 387 ACC_CONTROL_2: 8 XXX + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 401 STEERING_LTA: 8 XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX + SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" 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 + SG_ LKA_ACTIVE : 26|1@0+ (1,0) [0|1] "" XXX + SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX + SG_ CLEAR_HOLD_STEERING_ALERT : 30|1@0+ (1,0) [0|1] "" XXX + SG_ PERCENTAGE : 39|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_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 418 CRUISE_RELATED: 8 XXX + SG_ CRUISE_ACTIVE : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 467 PCM_CRUISE_2: 8 XXX + SG_ BRAKE_PRESSED : 3|1@0+ (1,0) [0|1] "" XXX + SG_ PCM_FOLLOW_DISTANCE : 12|2@0+ (1,0) [0|3] "" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "" XXX + SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "km/h" XXX + SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_ANGLE_INITIALIZING : 3|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1,0) [-32768|32767] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LTA_STATE : 15|5@0+ (1,0) [0|31] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 643 PRE_COLLISION: 8 DSU + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 740 STEERING_LKA: 8 XXX + SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX + SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX + SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 742 LEAD_INFO: 8 DSU + SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU + SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU + +BO_ 835 ACC_CONTROL: 8 DSU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU + SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX + SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX + SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX + SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX + SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU + SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU + SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX + SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU + SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU + SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX + SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 836 PRE_COLLISION_2: 8 DSU + SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX + SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX + SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 881 LTA_RELATED: 8 FCM + SG_ GAS_PEDAL : 15|8@0+ (0.005,0) [0|1] "" XXX + SG_ STEER_ANGLE : 23|16@0- (0.0573,0) [-500|500] "" XXX + SG_ TURN_SIGNALS : 35|2@0+ (1,0) [0|3] "" XXX + SG_ UNKNOWN_2 : 58|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SA_TOGGLE : 59|1@0+ (1,0) [0|1] "" XXX + SG_ LTA_STEER_REQUEST : 60|1@0+ (1,0) [0|1] "" XXX + SG_ UNKNOWN : 61|1@0+ (1,0) [0|1] "" XXX + SG_ STEERING_PRESSED : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 921 PCM_CRUISE_SM: 8 XXX + SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX + SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX + SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX + SG_ TEMP_ACC_FAULTED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX + +BO_ 951 ESP_CONTROL: 8 ESP + SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX + SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX + +BO_ 1014 BSM: 8 XXX + SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX + SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX + SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX + SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX + SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX + SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX + +BO_ 1020 SOLAR_SENSOR: 8 XXX + SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX + +BO_ 1041 PCS_HUD: 8 DSU + SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX + SG_ PCS_DUST : 34|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_TEMP : 35|1@0+ (1,0) [0|0] "" XXX + SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX + SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_DUST2 : 41|1@0+ (1,0) [0|0] "" XXX + SG_ PCS_TEMP2 : 42|1@0+ (1,0) [0|0] "" XXX + SG_ FRD_ADJ : 53|3@0+ (1,0) [0|0] "" XXX + SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX + +BO_ 1042 LKAS_HUD: 8 DSU + SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX + SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX + SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_STATUS : 7|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LDW_EXIST : 10|1@0+ (1,0) [0|1] "" XXX + SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX + SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE_QUIET : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE : 16|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY : 18|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SA_TOGGLE : 20|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_MESSAGES : 23|3@0+ (1,0) [0|1] "" XXX + SG_ LDA_ON_MESSAGE : 31|2@0+ (1,0) [0|3] "" XXX + SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X01 : 42|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_TOGGLE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_SENSITIVITY : 45|2@0+ (1,0) [0|3] "" XXX + SG_ TAKE_CONTROL : 46|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_FRONT_CAMERA_BLOCKED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_BUZZER : 50|2@0+ (1,0) [0|0] "" XXX + SG_ LANE_SWAY_FLD : 53|3@0+ (1,0) [0|7] "" XXX + SG_ LANE_SWAY_WARNING : 55|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX + +BO_ 1044 AUTO_HIGH_BEAM: 8 FCM + SG_ AHB_DUTY : 47|8@0+ (0.5,0) [0|0] "%" Vector__XXX + SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX + SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 1161 RSA1: 8 FCM + SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "km/h" XXX + SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX + SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX + +BO_ 1162 RSA2: 8 FCM + SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX + SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX + SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX + SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX + SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX + SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX + SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX + SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX + SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX + +BO_ 1163 RSA3: 8 FCM + SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX + SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX + SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX + SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX + SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX + SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX + SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX + SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX + +BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX + SG_ UI_SPEED : 23|8@0+ (1,0) [0|255] "" XXX + SG_ METER_SLIDER_BRIGHTNESS_PCT : 30|7@0+ (1,0) [12|100] "%" XXX + SG_ METER_SLIDER_LOW_BRIGHTNESS : 37|1@0+ (1,0) [0|1] "" XXX + SG_ METER_SLIDER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ UNITS : 63|3@0+ (1,0) [1|4] "" XXX + +BO_ 1553 UI_SETTING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + SG_ ODOMETER : 39|32@0+ (1,0) [0|1048575] "" XXX + +BO_ 1556 BLINKERS_STATE: 8 XXX + SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + +BO_ 1568 BODY_CONTROL_STATE: 8 XXX + SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX + SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 1571 CERTIFICATION_ECU: 8 CGW + SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX + SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX + SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX + +BO_ 1592 DOOR_LOCKS: 8 XXX + SG_ LOCK_STATUS_CHANGED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX + SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX + +CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; +CM_ SG_ 305 STEER_ANGLE_CMD "Used in place of STEERING_LTA.STEER_ANGLE_CMD on SecOC cars"; +CM_ SG_ 387 ACCEL_CMD "Used in place of ACC_CONTROL.ACCEL_CMD on SecOC cars"; +CM_ SG_ 401 STEER_REQUEST "enable bit for steering, 1 to steer, 0 to not"; +CM_ SG_ 401 SETME_X1 "usually 1, seen at 0 on some South American Corollas indicating lack of stock Lane Tracing Assist"; +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 STEER_REQUEST_2 "enable bit for steering, 1 to steer, 0 to not"; +CM_ SG_ 401 LKA_ACTIVE "1 when using LTA for LKA"; +CM_ SG_ 401 SETME_X3 "almost completely correlates with Toyota Safety Sense version, but may instead describe max torque when using LTA. if TSS 2.5 or 2022 RAV4, this is always 1. if TSS 2.0 this is always 3 (or 0 on Alphard, Highlander, NX)"; +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"; +CM_ SG_ 401 PERCENTAGE "driver override percentage (0-100), very close to steeringPressed in OP"; +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_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; +CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; +CM_ SG_ 467 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement"; +CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; +CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; +CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; +CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; +CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; +CM_ SG_ 835 DISTANCE "Cycle through ACC following distance from long, mid, short when set to 1"; +CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; +CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; +CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; +CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; +CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; +CM_ SG_ 881 GAS_PEDAL "not set on all cars, only seen on TSS 2.5 Camry Hybrid so far"; +CM_ SG_ 881 STEER_ANGLE "matches STEER_TORQUE_SENSOR->STEER_ANGLE"; +CM_ SG_ 881 TURN_SIGNALS "flipped on some cars"; +CM_ SG_ 881 LDA_SA_TOGGLE "not applicable for all cars"; +CM_ SG_ 881 LTA_STEER_REQUEST "only applicable for TSS 2.5: matches STEERING_LTA->STEER_REQUEST"; +CM_ SG_ 881 UNKNOWN "related to steering wheel angle"; +CM_ SG_ 881 STEERING_PRESSED "only applicable for TSS 2.5: low sensitivity steering wheel pressed by driver signal"; +CM_ SG_ 921 TEMP_ACC_FAULTED "1 when the UI is displaying or playing fault-related alerts or sounds. Also 1 when pressing main on."; +CM_ SG_ 921 UI_SET_SPEED "set speed shown in the vehicle's UI with the vehicle's unit"; +CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility"; +CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; +CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility"; +CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; +CM_ SG_ 1041 PCS_DUST "alert: Front Camera Low Visibility Unavailable See Owner's Manual"; +CM_ SG_ 1041 PCS_TEMP "alert: Front Camera Out of Temperature Range Unavailable Wait until Normal Temperature"; +CM_ SG_ 1041 PCS_DUST2 "alert: Pre-Collision System Radar Sensor Blocked Unavailable Clean Radar Sensor"; +CM_ SG_ 1041 PCS_TEMP2 "alert: Pre-Collision System Out of Temperature Range Unavailable See Owner's Manual"; +CM_ SG_ 1041 FRD_ADJ "alert: ERROR ADJUSTING FRONT RADAR BEAM"; +CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; +CM_ SG_ 1042 LDW_EXIST "Unclear what this is, it's usually set to 0"; +CM_ SG_ 1042 LDA_UNAVAILABLE_QUIET "LDA toggles and sensitivity settings are greyed out if set to 1"; +CM_ SG_ 1042 LDA_SENSITIVITY "LDA Sensitivity"; +CM_ SG_ 1042 LDA_SA_TOGGLE "LDA Steering Assist Toggle"; +CM_ SG_ 1042 LDA_MESSAGES "Various LDA Messages"; +CM_ SG_ 1042 LDA_ON_MESSAGE "Display LDA Turned ON message"; +CM_ SG_ 1042 REPEATED_BEEPS "LDA audible warning"; +CM_ SG_ 1042 SET_ME_X01 "empty bit on leaked dbc, always set to 1 during normal operations"; +CM_ SG_ 1042 LANE_SWAY_TOGGLE "Lane Sway Warning System SWS Switch"; +CM_ SG_ 1042 TAKE_CONTROL "Please Control Steering Wheel warning"; +CM_ SG_ 1042 LDA_FRONT_CAMERA_BLOCKED "originally LDAFCVB, LDA related settings are greyed out if set to 1"; +CM_ SG_ 1042 LANE_SWAY_BUZZER "Similar to TWO_BEEPS"; +CM_ SG_ 1042 LANE_SWAY_FLD "Unknown signal for Lane Sway Warning System, set to 7 on stock system when SWS is enabled, 0 when SWS is disabled"; +CM_ SG_ 1042 LANE_SWAY_WARNING "Lane Sway Warning System Triggered"; +CM_ SG_ 1042 SET_ME_X02 "empty bit on leaked dbc, always set to 2 during normal operations"; +CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; +CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; +CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; +CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; +CM_ SG_ 1163 OVSPNTM "always 3"; +CM_ SG_ 1163 NTLVLSPD "always 3"; +CM_ SG_ 1163 OTSGNNTM "always 3"; +CM_ SG_ 1163 TSRMSW "always 1"; +CM_ SG_ 1163 TSREQPD "always 1"; +CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; +CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; +CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; +CM_ SG_ 1163 TSRSPU "always 1"; +CM_ SG_ 1552 UI_SPEED "Does not appear to match dash"; +CM_ SG_ 1552 METER_SLIDER_BRIGHTNESS_PCT "Combination display brightness setting, scales from 12 per cent to 100 per cent, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1552 METER_SLIDER_LOW_BRIGHTNESS "Combination display low brightness mode, also controls footwell lighting"; +CM_ SG_ 1552 METER_SLIDER_DIMMED "Combination display slider not at max, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; +CM_ SG_ 1592 LOCK_STATUS_CHANGED "1 on rising edge of lock/unlocking"; +CM_ SG_ 1592 LOCK_STATUS "The next 3 bits always seem to follow this signal."; +CM_ SG_ 1592 LOCKED_VIA_KEYFOB "1 for as long as car is locked with key fob or door handle touch"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; +VAL_ 401 SETME_X3 3 "TSS 2.0" 1 "TSS 2.5 or 2022 RAV4" 0 "TSS 2.0 on Alphard, Highlander, NX"; +VAL_ 467 PCM_FOLLOW_DISTANCE 1 "far" 2 "medium" 3 "close"; +VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; +VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; +VAL_ 610 LTA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 3 "lta_missing_unavailable" 1 "standby"; +VAL_ 610 LKA_STATE 25 "temporary_fault" 17 "permanent_fault" 11 "lka_missing_unavailable2" 9 "temporary_fault2" 5 "active" 3 "lka_missing_unavailable" 1 "standby"; +VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; +VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; +VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; +VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; +VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; +VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; +VAL_ 1042 BARRIERS 3 "left" 2 "right" 1 "both" 0 "none"; +VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LKAS_STATUS 1 "on" 0 "off"; +VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; +VAL_ 1042 LDA_SENSITIVITY 2 "standard" 1 "high" 0 "undefined"; +VAL_ 1042 LDA_SA_TOGGLE 2 "steering assist off" 1 "steering assist on"; +VAL_ 1042 LDA_MESSAGES 4 "lda unavailable at this speed" 1 "lda unavailable below approx 50km/h" 0 "ok"; +VAL_ 1042 LDA_ON_MESSAGE 2 "Lane Departure Alert Turned ON, Steering Assist Inactive" 1 "Lane Departure Alert Turned ON, Steering Assist Active" 0 "clear"; +VAL_ 1042 TAKE_CONTROL 1 "take control" 0 "ok"; +VAL_ 1042 LDA_FRONT_CAMERA_BLOCKED 1 "lda unavailable" 0 "ok"; +VAL_ 1042 LANE_SWAY_BUZZER 3 "ok" 2 "beep twice" 1 "beep twice" 0 "ok"; +VAL_ 1042 LANE_SWAY_WARNING 3 "ok" 2 "orange please take a break" 1 "prompt would you like to take a break" 0 "ok"; +VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; +VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; +VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; +VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1552 METER_SLIDER_LOW_BRIGHTNESS 1 "Low brightness mode, footwell lights off" 0 "Normal mode, footwell lights on"; +VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; +VAL_ 1552 UNITS 1 "km (km/L)" 2 "km (L/100km)" 3 "miles (MPG US)" 4 "miles (MPG Imperial)"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; diff --git a/opendbc/toyota_tnga_k_pt_generated.dbc b/opendbc_repo/opendbc/dbc/toyota_tnga_k_pt_generated.dbc similarity index 84% rename from opendbc/toyota_tnga_k_pt_generated.dbc rename to opendbc_repo/opendbc/dbc/toyota_tnga_k_pt_generated.dbc index d95cfbe69a2a955..7b348acff56a1e4 100644 --- a/opendbc/toyota_tnga_k_pt_generated.dbc +++ b/opendbc_repo/opendbc/dbc/toyota_tnga_k_pt_generated.dbc @@ -1,50 +1,6 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _community.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (1,0) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (1,0) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STATE : 23|4@0+ (1,0) [0|15] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS-P Toyotas. Learn more: https://github.com/RetroPilot/ocelot/tree/main/firmware/smart_dsu"; -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -VAL_ 767 STATE 7 "STATE_AEB_CTRL" 6 "FAULT_INVALID" 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - - CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -93,9 +49,24 @@ BO_ 37 STEER_ANGLE_SENSOR: 8 XXX SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX +BO_ 119 ENG2F41: 6 CGW + SG_ FDRV : 7|16@0- (2,0) [0|0] "N" Vector__XXX + SG_ FDRVREAL : 23|13@0- (10,0) [0|0] "N" Vector__XXX + SG_ XAECT : 39|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ XFDRVCOL : 38|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVSELP : 34|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F41S : 47|8@0+ (1,0) [0|0] "" Vector__XXX + +BO_ 120 ENG2F42: 4 CGW + SG_ FAVLMCHH : 7|16@0- (2,0) [0|0] "N" Vector__XX228X + SG_ CCRNG : 23|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ FDRVTYPD : 22|3@0+ (1,0) [0|0] "" Vector__XXX + SG_ GEARHD : 18|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ ENG2F42S : 31|8@0+ (1,0) [0|0] "" Vector__XXX + BO_ 166 BRAKE: 8 XXX SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX + SG_ BRAKE_FORCE : 23|8@0+ (40,0) [0|10200] "N" XXX BO_ 170 WHEEL_SPEEDS: 8 XXX SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX @@ -109,8 +80,8 @@ BO_ 180 SPEED: 8 XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 295 GEAR_PACKET_HYBRID: 8 XXX - SG_ CAR_MOVEMENT : 25|10@0- (1,0) [0|255] "" XXX - SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ FDRVREAL : 26|11@0- (25,0) [-25600|25575] "N" XXX + SG_ UNKNOWN : 55|8@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX @@ -119,6 +90,7 @@ BO_ 353 DSU_SPEED: 7 XXX BO_ 452 ENGINE_RPM: 8 CGW SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS + SG_ ENGINE_RUNNING : 27|1@0+ (1,0) [0|1] "" XXX BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX @@ -139,9 +111,10 @@ BO_ 467 PCM_CRUISE_2: 8 XXX SG_ ACC_FAULTED : 47|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "m/s^2" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s^2" XXX +BO_ 552 VSC1S29: 4 CGW + SG_ ICBACT : 7|1@0+ (1,0) [0|0] "" DS1 + SG_ DVS0PCS : 6|15@0- (0.001,0) [0|0] "m/s^2" DS1 + SG_ SM228 : 31|8@0+ (1,0) [0|0] "" DS1 BO_ 560 BRAKE_2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX @@ -180,7 +153,11 @@ BO_ 643 PRE_COLLISION: 7 DSU BO_ 705 GAS_PEDAL: 8 XXX SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX @@ -195,6 +172,31 @@ BO_ 742 LEAD_INFO: 8 DSU SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU +BO_ 800 VSC1S07: 8 CGW + SG_ FBKRLY : 6|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCM : 4|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCSFT : 3|1@0+ (1,0) [0|0] "" DS1 + SG_ FABS : 2|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ TSVSC : 1|1@0+ (1,0) [0|0] "" DS1 + SG_ FVSCL : 0|1@0+ (1,0) [0|0] "" DS1 + SG_ RQCSTBKB : 15|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PSBSTBY : 14|1@0+ (1,0) [0|0] "" DS1 + SG_ P2BRXMK : 13|1@0+ (1,0) [0|0] "" DS1 + SG_ MCC : 11|1@0+ (1,0) [0|0] "" DS1 + SG_ RQBKB : 10|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRSTOP : 9|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ BRKON : 8|1@0+ (1,0) [0|0] "" DS1,FCM + SG_ ASLP : 23|8@0- (1,0) [0|0] "deg" DS1 + SG_ BRTYPACC : 31|2@0+ (1,0) [0|0] "" DS1 + SG_ BRKABT3 : 26|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT2 : 25|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ BRKABT1 : 24|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ GVC : 39|8@0- (0.04,0) [0|0] "m/s^2" DS1 + SG_ XGVCINV : 43|1@0+ (1,0) [0|0] "" DS1 + SG_ S07CNT : 52|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ PCSBRSTA : 50|2@0+ (1,0) [0|0] "" DS1 + SG_ VSC07SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM + BO_ 835 ACC_CONTROL: 8 DSU SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX @@ -213,12 +215,19 @@ BO_ 835 ACC_CONTROL: 8 DSU SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 836 PRE_COLLISION_2: 8 DSU + SG_ DSS1GDRV : 7|10@0- (0.1,0) [0|0] "m/s^2" Vector__XXX + SG_ PCSALM : 17|1@0+ (1,0) [0|0] "" FCM + SG_ IBTRGR : 27|1@0+ (1,0) [0|0] "" FCM + SG_ PBATRGR : 30|2@0+ (1,0) [0|0] "" Vector__XXX + SG_ PREFILL : 33|1@0+ (1,0) [0|0] "" Vector__XXX + SG_ AVSTRGR : 36|1@0+ (1,0) [0|0] "" SCS SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX BO_ 865 CLUTCH: 8 XXX SG_ ACC_FAULTED : 32|1@0+ (1,0) [0|1] "" XXX SG_ GAS_PEDAL_ALT : 23|8@0+ (0.005,0) [0|1] "" XXX SG_ CLUTCH_RELEASED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ ACCEL_NET : 48|16@1+ (0.0002,-6.5536) [-6.5536|6.5534] "" XXX BO_ 869 DSU_CRUISE : 7 DSU SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX @@ -320,6 +329,18 @@ BO_ 1044 AUTO_HIGH_BEAM: 8 FCM SG_ F_AHB : 55|4@0+ (1,0) [0|0] "" Vector__XXX SG_ C_AHB : 51|4@0+ (1,0) [0|0] "" Vector__XXX +BO_ 1056 VSC1S08: 8 CGW + SG_ YR1Z : 7|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ YR2Z : 23|16@0- (1,0) [0|0] "rad/s" DS1,FCM,MAV + SG_ GL1Z : 39|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ GL2Z : 47|8@0- (0.0359,0) [0|0] "m/s^2" DS1,FCM,KSS,MAV,SCS + SG_ YRGSDIR : 55|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,SCS + SG_ GLZS : 51|1@0+ (1,0) [0|0] "" DS1,FCM,KSS,MAV,SCS + SG_ YRZF : 50|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZS : 49|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ YRZKS : 48|1@0+ (1,0) [0|0] "" DS1,FCM,MAV + SG_ VSC08SUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM,MAV + BO_ 1083 AUTOPARK_STATUS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX @@ -398,9 +419,11 @@ BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX BO_ 1553 UI_SETTING: 8 XXX SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX SG_ ODOMETER : 39|32@0+ (1,0) [0|1048575] "" XXX + BO_ 1556 BLINKERS_STATE: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + SG_ BLINKER_BUTTON_PRESSED : 15|1@0+ (1,0) [0|1] "" XXX SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX BO_ 1568 BODY_CONTROL_STATE: 8 XXX SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX @@ -429,13 +452,30 @@ BO_ 1592 DOOR_LOCKS: 8 XXX SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX +BO_ 1779 ADAS_TOGGLE_STATE: 8 XXX + SG_ OK_BUTTON_PRESSED : 15|1@0+ (1,0) [0|1] "" BCM + SG_ SWS_TOGGLE_CMD : 24|1@0+ (1,0) [0|1] "" XXX + SG_ SWS_SENSITIVITY_CMD : 26|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_ON_CMD : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_OFF_CMD : 29|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY_HI_CMD : 30|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY_STD_CMD : 31|1@0+ (1,0) [0|1] "" XXX + SG_ IPAS_TOGGLE : 34|1@0+ (1,0) [0|1] "" XXX + SG_ BSM_TOGGLE_CMD : 37|1@0+ (1,0) [0|1] "" XXX + SG_ IPAS_SONAR_TOGGLE : 38|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_TOGGLE_CMD : 40|1@0+ (1,0) [0|1] "" XXX + SG_ PCS_SENSITIVITY_CMD : 41|1@0+ (1,0) [0|1] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 ACCEL_X "x-axis accel"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; +CM_ SG_ 119 FDRVREAL "ICE only: force applied by wheels from the engine. includes creeping force, regen, and engine braking"; +CM_ SG_ 166 BRAKE_FORCE "hybrid only: force applied by friction brakes from user or ACC command"; +CM_ SG_ 295 FDRVREAL "hybrid only: force applied by wheels from the engine and/or electric motors. includes creeping force, regen, and engine braking"; CM_ SG_ 466 NEUTRAL_FORCE "force in newtons the engine/electric motors are applying without any acceleration commands or user input"; CM_ SG_ 466 ACC_BRAKING "whether brakes are being actuated from ACC command"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; +CM_ SG_ 466 ACCEL_NET "net negative acceleration (braking) applied by the system if on flat ground"; CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; CM_ SG_ 467 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement"; CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; @@ -448,6 +488,8 @@ CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; CM_ SG_ 643 _COUNTER "only used on cars that use this msg for cruise control"; CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; +CM_ SG_ 800 SLOPE_ANGLE "potentially used by the PCM to compensate for road pitch"; +CM_ SG_ 800 ACCEL "filtered ego acceleration"; CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; @@ -460,6 +502,7 @@ CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 865 GAS_PEDAL_ALT "copy of main GAS_PEDAL. Both use 8 bits. Might indicate that this message is for pedals."; CM_ SG_ 865 CLUTCH_RELEASED "boolean of clutch for 6MT."; +CM_ SG_ 865 ACCEL_NET "net positive acceleration (gas) applied by the system if on flat ground, may not include creeping force"; CM_ SG_ 865 ACC_FAULTED "1 when ACC is faulted and the PCM disallows engagement. Also describes a lockout when the ACC_CONTROL->ACC_MALFUNCTION bit is set."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in the vehicle's UI with the vehicle's unit"; CM_ SG_ 921 TEMP_ACC_FAULTED "1 when the UI is displaying or playing fault-related alerts or sounds. Also 1 when pressing main on."; @@ -560,6 +603,7 @@ VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; VAL_ 1552 UNITS 1 "km (km/L)" 2 "km (L/100km)" 3 "miles (MPG US)" 4 "miles (MPG Imperial)"; VAL_ 1553 UNITS 1 "km" 2 "miles"; VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1556 BLINKER_BUTTON_PRESSED 1 "button pressed" 0 "not pressed"; VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; CM_ "toyota_tnga_k_pt.dbc starts here"; diff --git a/opendbc/toyota_tss2_adas.dbc b/opendbc_repo/opendbc/dbc/toyota_tss2_adas.dbc similarity index 100% rename from opendbc/toyota_tss2_adas.dbc rename to opendbc_repo/opendbc/dbc/toyota_tss2_adas.dbc diff --git a/opendbc_repo/opendbc/dbc/volvo_v40_2017_pt.dbc b/opendbc_repo/opendbc/dbc/volvo_v40_2017_pt.dbc new file mode 100644 index 000000000000000..3c04331649b6a40 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/volvo_v40_2017_pt.dbc @@ -0,0 +1,363 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX BCM CEM CVM DIM ECM FSM PSCM SAS SRS TCM + +BO_ 8 SAS0: 8 SAS + SG_ SteeringDirection : 42|1@0+ (1,0) [0|1] "" XXX + SG_ RelativeTurnDirection : 43|1@0+ (1,0) [0|1] "" XXX + SG_ SteeringAngle : 53|14@0+ (0.04395,0) [0|65535] "degrees" XXX + SG_ NEW_SIGNAL_1 : 47|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_2 : 39|4@0+ (1,0) [0|15] "" XXX + SG_ AngleRate : 21|14@0+ (0.075,0) [0|1500] "deg/S" XXX + +BO_ 16 CCButtons: 8 CEM + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|5@0+ (1,0) [0|31] "" XXX + SG_ B7b0 : 56|1@0+ (1,0) [0|1] "" XXX + SG_ B7b1 : 57|1@0+ (1,0) [0|1] "" XXX + SG_ B7b6 : 62|1@0+ (1,0) [0|1] "" XXX + SG_ ACCOnOffBtn : 58|1@0+ (1,0) [0|1] "" XXX + SG_ ACCSetBtn : 63|1@0+ (1,0) [0|1] "" XXX + SG_ ACCStopBtn : 60|1@0+ (1,0) [0|1] "" XXX + SG_ ACCResumeBtn : 61|1@0+ (1,0) [0|1] "" XXX + SG_ ACCMinusBtn : 48|1@0+ (1,0) [0|1] "" XXX + SG_ TimeGapIncreaseBtn : 49|1@0+ (1,0) [0|1] "" XXX + SG_ TimeGapDecreaseBtn : 50|1@0+ (1,0) [0|1] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ B7b3 : 59|1@0+ (1,0) [0|1] "" XXX + +BO_ 48 FSM0: 8 FSM + SG_ ACCStatusTracking : 56|1@0+ (1,0) [0|1] "" XXX + SG_ ACCStatusOnOff : 57|1@0+ (1,0) [0|1] "" XXX + SG_ ACCStatusActive : 58|1@0+ (1,0) [0|1] "" XXX + SG_ FCWSomething : 25|3@0+ (1,0) [0|3] "" XXX + SG_ StatusSomething : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 64 TCM0: 8 TCM + SG_ RPMSomething : 42|11@0+ (1,0) [0|2047] "" XXX + SG_ GearShifter : 46|2@0+ (1,0) [0|3] "" XXX + +BO_ 85 PedalandBrake: 8 ECM + SG_ AccPedal : 9|10@0+ (0.1,0) [0|1023] "%" XXX + SG_ BrakePedalActive2 : 24|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 35|12@0+ (1,0) [0|4095] "" XXX + SG_ BrakePedalActive : 38|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 101 EngineInfo: 8 XXX + SG_ NEW_SIGNAL_1 : 17|10@0+ (1,-512) [0|1023] "" XXX + SG_ EngineSpeed : 52|13@0+ (1,0) [0|1023] "" XXX + +BO_ 112 NEW_MSG_4: 8 XXX + SG_ NEW_SIGNAL_1 : 39|8@0+ (1,0) [0|255] "" XXX + +BO_ 114 ECM1: 8 ECM1 + SG_ NEW_SIGNAL_1 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ECM_ACC_ONOFF_INV : 43|1@0+ (1,0) [0|1] "" XXX + SG_ ECM_ACC_RESUME_INV : 45|1@0+ (1,0) [0|1] "" XXX + SG_ ECM_ACC_SET_INV : 47|1@0+ (1,0) [0|1] "" XXX + SG_ ECM_ACC_TIMEGAP_INC_INV : 33|1@0+ (1,0) [0|1] "" XXX + SG_ ECM_ACC_DEC_INV : 32|1@0+ (1,0) [0|1] "" XXX + SG_ ECM_ACC_TIMEGAP_DEC_INV : 34|1@0+ (1,0) [0|1] "" XXX + +BO_ 117 ECM1_2: 8 ECM + +BO_ 128 NEW_MSG_5: 8 XXX + SG_ NEW_SIGNAL_2 : 26|11@0+ (1,0) [0|2047] "" XXX + SG_ NEW_SIGNAL_1 : 52|13@0+ (1,0) [0|8191] "" XXX + +BO_ 176 ECM2: 8 ECM + SG_ NEW_SIGNAL_1 : 50|11@0+ (1,0) [0|2047] "" XXX + SG_ NEW_SIGNAL_2 : 47|8@0+ (1,0) [0|63] "" XXX + +BO_ 192 Gear: 8 XXX + SG_ TransmissionGear : 36|3@0+ (1,1) [0|7] "" XXX + +BO_ 208 FSM1: 8 FSM + SG_ SET_X_E3 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ SET_X_B4 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_X_08 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ TrqLim : 31|8@0+ (1,-128) [0|255] "" XXX + SG_ Checksum : 55|8@0+ (1,0) [0|255] "" XXX + SG_ LKASteerDirection : 57|2@0+ (1,0) [0|2] "" XXX + SG_ SET_X_25 : 63|6@0+ (1,0) [0|63] "" XXX + SG_ LKAAngleReq : 37|14@0+ (0.04395,-360.0384) [-360.0384|359.99445] "degrees" XXX + SG_ SET_X_02 : 39|2@0+ (1,0) [0|3] "" XXX + +BO_ 224 PSCM0: 8 PSCM + SG_ NEW_SIGNAL_2 : 12|5@0+ (1,0) [0|31] "" XXX + SG_ counter_07 : 15|3@0+ (1,0) [0|7] "" XXX + SG_ counter2_07 : 37|3@0+ (1,0) [0|16383] "" XXX + SG_ rate_of_something : 46|7@0+ (1,0) [0|62] "" XXX + SG_ OneDuringDriving : 49|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_1 : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 245 wheelspeed0: 8 BCM + SG_ counter1 : 21|6@0+ (1,0) [0|65535] "" XXX + SG_ counter0 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ WhlSpdLF : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ WhlSpdRF : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 272 SpeedSignal0: 8 XXX + SG_ VehicleSpeedSignal : 55|16@0+ (0.01,0) [0|65535] "" XXX + +BO_ 288 wheel_speed1: 8 BCM + SG_ WhlSpdLR : 39|16@0+ (1,0) [0|65535] "" XXX + SG_ WhlSpdRR : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 293 PSCM1: 8 PSCM + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ LKATorque : 11|12@0+ (1,-2000) [0|4095] "" XXX + SG_ SteeringAngleServo : 47|16@0+ (0.04395,-1440.1536) [0|65535] "deg" XXX + SG_ LKAActive : 15|4@0+ (1,0) [0|15] "" XXX + +BO_ 304 VehicleSpeed0: 8 BCM + SG_ NEW_SIGNAL_2 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ VehicleSpeed : 31|16@0+ (0.01,0) [0|65535] "km/h" XXX + SG_ NEW_SIGNAL_1 : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 325 ECM3: 8 ECM + +BO_ 336 VehicleSpeed1: 8 BCM + SG_ NEW_SIGNAL_2 : 31|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_1 : 15|16@0+ (1,0) [0|65535] "" XXX + SG_ VehicleSpeed : 55|16@0+ (0.01,0) [0|65535] "" XXX + +BO_ 352 FSM2: 8 FSM + SG_ LkaDimLine : 51|2@1+ (1,0) [0|127] "" XXX + SG_ NEW_SIGNAL_2 : 56|7@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 55|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_3 : 7|24@0+ (1,0) [0|16777215] "" XXX + SG_ NEW_SIGNAL_4 : 36|5@0+ (1,0) [0|31] "" XXX + +BO_ 432 BrakeMessages: 8 BCM + SG_ BrakePress0 : 1|10@0+ (1,0) [0|1023] "" XXX + SG_ BrakePress1 : 33|10@0+ (1,0) [0|1023] "" XXX + SG_ BrakeStatus : 18|3@0+ (1,0) [0|7] "" XXX + +BO_ 464 DIM0: 8 DIM + +BO_ 480 BCM0: 8 BCM + +BO_ 528 CEM0: 8 CEM + +BO_ 608 CVM0: 8 CVM + SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 15|5@0+ (1,0) [0|32] "" XXX + SG_ Distance : 10|11@0+ (1,0) [0|2048] "" XXX + +BO_ 624 FSM3: 8 FSM + SG_ NEW_SIGNAL_1 : 23|8@0+ (1,0) [0|255] "" XXX + +BO_ 640 FSM4: 8 FSM + SG_ SpeedTarget : 47|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 49|10@0+ (1,0) [0|255] "" XXX + +BO_ 648 SRS0: 8 SRS + +BO_ 652 ECM4: 8 ECM + +BO_ 656 ECM5: 8 ECM + +BO_ 657 ECM6: 8 ECM + +BO_ 681 MiscCarInfo: 8 CEM + SG_ TurnSignal : 1|2@0+ (1,0) [0|3] "" XXX + SG_ HighBeamOn : 52|1@0+ (1,0) [0|1] "" XX + +BO_ 693 ECM7: 8 ECM + +BO_ 709 ACC: 8 ECM + SG_ SpeedTargetACC : 0|9@0+ (0.5,0) [0|511] "" XXX + +BO_ 853 FSM5: 8 FSM + SG_ TargetSpeedOdo : 23|8@0+ (1,0) [0|63] "kph" XXX + SG_ SpeedSign : 36|5@0+ (5,0) [0|32] "" XXX + SG_ TextUnderSign : 37|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_6 : 39|3@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LaneMarkingsOdo : 15|4@0+ (1,0) [0|7] "" XXX + SG_ NEW_SIGNAL_2 : 11|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 55|16@0+ (1,0) [0|65535] "" XXX + +BO_ 864 CEM1: 8 CEM + +BO_ 912 DIM1: 8 DIM + +BO_ 968 SRS1: 8 SRS + SG_ PassengerSeatBelt : 22|1@0+ (1,0) [0|1] "" XXX + SG_ DriverSeatBelt : 19|1@0+ (1,0) [0|1] "" XXX + +BO_ 1029 CEMBCM0: 8 CEM + +BO_ 1344 NEW_MSG_1: 8 XXX + SG_ NEW_SIGNAL_1 : 4|13@0+ (1,0) [0|8191] "" XXX + +BO_ 1830 diagCEMReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1838 diagCEMResp: 8 XXX + SG_ byte03 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ byte47 : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 1840 diagPSCMReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1848 diagPSCMResp: 8 XXX + SG_ byte03 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ byte47 : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 1892 diagFSMReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1900 diagFSMResp: 8 XXX + SG_ byte03 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ byte47 : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 1939 diagCVMReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1947 diagCVMResp: 8 XXX + SG_ byte03 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ byte47 : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2015 diagGlobalReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + + + + +CM_ SG_ 85 BrakePedalActive2 "Active during braking"; +CM_ SG_ 85 NEW_SIGNAL_1 "Not yet figured out."; +CM_ SG_ 85 BrakePedalActive "Brake pedal pushed"; +CM_ SG_ 8 SteeringDirection "1=Right turn, 0=Left turn. Steering wheel pointing left or right from center (0 deg)."; +CM_ SG_ 8 RelativeTurnDirection "1=Right turn, 0=Left turn. Steering wheel currently turning the way."; +CM_ SG_ 101 NEW_SIGNAL_1 "Rate of something?"; +CM_ SG_ 192 TransmissionGear "0 = 1st gear, 1= 2nd gear..."; +CM_ SG_ 681 TurnSignal "0 = Nothing, 1= Left, 3=Right"; +CM_ SG_ 681 HighBeamOn "1=HighBeam On, 0=HighBeam Off"; +CM_ SG_ 48 ACCStatusTracking "ACC Tracking vehicle, distance control."; +CM_ SG_ 48 ACCStatusOnOff "Turns one after pressing on/off button on steering wheeel"; +CM_ SG_ 48 ACCStatusActive "ACC Active"; +CM_ SG_ 48 FCWSomething "All bit set during fcw"; +CM_ SG_ 48 StatusSomething "Some status changes when zeroing DTCs"; +CM_ SG_ 208 TrqLim "Used in checksum calculation, Limit directional torque based on the number."; +CM_ SG_ 208 Checksum "Checksum calculated as a one-complement addition of LKAAngleRequest+LKADirection+Unkown, Zeros used to pad missing bits."; +CM_ SG_ 208 SET_X_02 "Bit 0 = Vibrate steering wheel., Bit 1 = Heartbeat"; +CM_ SG_ 352 LkaDimLine "Not true, but follows lka steer direction."; +CM_ SG_ 352 NEW_SIGNAL_1 "Turned one. Got LKA service needed can this be the one?"; +CM_ SG_ 640 SpeedTarget "SpeedTarget ACC (noisy bf starting acc Jumps from 0->252->0)"; +CM_ SG_ 853 TargetSpeedOdo "Probably target speed odo"; +CM_ SG_ 853 LaneMarkingsOdo "Bit 3=Left lane, Bit 2=Right lane, Bit 1=LKA on?, Bit 0=?"; +CM_ SG_ 709 SpeedTargetACC "SpeedTargetACC"; +CM_ SG_ 224 rate_of_something "Seems to be some kind of torque rather than rate."; +CM_ SG_ 224 OneDuringDriving "Set to 1 when vehicle is rolling."; +CM_ SG_ 293 byte7 "Bit0=0 when gearshift in park, else 1"; +CM_ SG_ 293 LKAActive "Bit0=0 when gear in park otherwise =1, Bit1=1 when LKA Active, 0 when not active. Bit2=? Bit3=?"; +CM_ SG_ 16 ACCOnOffBtn "Cruise control on/off button pressed"; +CM_ SG_ 16 ACCSetBtn "Acc Set button (+) pressed"; +CM_ SG_ 16 ACCStopBtn "ACC Stop button pressed"; +CM_ SG_ 16 ACCResumeBtn "ACC Resume button pressed"; +CM_ SG_ 16 ACCMinusBtn "ACC Minus (-) button pressed"; +CM_ SG_ 16 TimeGapIncreaseBtn "Increase the time gap on ACC"; +CM_ SG_ 16 TimeGapDecreaseBtn "Decrease the time gap on ACC"; +CM_ SG_ 245 counter0 "Speed based counter"; +CM_ SG_ 245 WhlSpdLF "Wheel speed left front"; +CM_ SG_ 245 WhlSpdRF "Wheel speed right front"; +CM_ SG_ 288 WhlSpdLR "Wheel speed left rear"; +CM_ SG_ 288 WhlSpdRR "Wheel speed right rear"; +CM_ SG_ 64 RPMSomething "TransmissionOutput?"; +CM_ SG_ 64 GearShifter "P=0, R=1, N=2, D=3"; +CM_ SG_ 272 VehicleSpeedSignal "km/h"; +CM_ SG_ 432 BrakePress0 "Brake being pressed"; +CM_ SG_ 432 BrakePress1 "Brake being pressed"; +CM_ SG_ 432 BrakeStatus "ACC brake?"; +CM_ SG_ 437 Counter0 "Related to braking? Maybe one per wheel?"; +CM_ SG_ 437 Counter1 "Related to braking? Maybe one per wheel?"; +CM_ SG_ 437 Counter2 "Related to braking? Maybe one per wheel?"; +CM_ SG_ 437 Counter3 "Related to braking? Maybe one per wheel?"; +CM_ SG_ 114 NEW_SIGNAL_1 "Jumped from 0 -> 120 during start. Makes triangle from time to time"; +CM_ SG_ 608 NEW_SIGNAL_1 "Status?"; +CM_ SG_ 608 NEW_SIGNAL_2 "Classification of object?"; +CM_ SG_ 608 Distance "Distance to object in front."; +CM_ SG_ 968 PassengerSeatBelt "1 = Seatbalt latched"; +CM_ SG_ 968 DriverSeatBelt "1=Seatbelt latched"; +VAL_ 64 GearShifter 0 "P" 1 "R" 2 "N" 3 "D" ; diff --git a/opendbc_repo/opendbc/dbc/volvo_v60_2015_pt.dbc b/opendbc_repo/opendbc/dbc/volvo_v60_2015_pt.dbc new file mode 100644 index 000000000000000..f95eff00cc3c7ec --- /dev/null +++ b/opendbc_repo/opendbc/dbc/volvo_v60_2015_pt.dbc @@ -0,0 +1,230 @@ +VERSION "" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + SG_MUL_VAL_ + +BS_: + +BU_: XXX BCM CEM FSM PSCM SAS + +BO_ 16 SAS0: 8 SAS + SG_ Counter0 : 3|8@0+ (1,0) [0|511] "" XXX + SG_ RateOfChangeOrTorque : 39|16@0+ (1,-32768) [0|65535] "" XXX + SG_ NEW_SIGNAL_1 : 22|15@0+ (1,0) [0|65535] "" XXX + SG_ SteeringDirection : 6|1@0+ (1,0) [0|1] "" XXX + SG_ SteeringAngle : 53|14@0+ (0.0445,0) [0|65535] "degrees" XXX + +BO_ 32 AccPedal: 8 XXX + SG_ AccPedal : 17|10@0+ (0.1,0) [0|1023] "%" XXX + +BO_ 81 FSM0: 8 FSM + SG_ ACCStatus : 18|3@0+ (1,0) [0|7] "" XXX + +BO_ 277 NEW_MSG_7: 8 XXX + SG_ NEW_SIGNAL_1 : 39|16@0+ (1,0) [0|65535] "" XXX + +BO_ 295 CCButtons: 8 CEM + SG_ ACCMinusBtn : 48|1@0+ (1,0) [0|1] "" XXX + SG_ ACCSetBtn : 63|1@0+ (1,0) [0|1] "" XXX + SG_ ACCOnOffBtn : 59|1@0+ (1,0) [0|1] "" XXX + SG_ ACCResumeBtn : 61|1@0+ (1,0) [0|1] "" XXX + SG_ TimeGapDecreaseBtnInv : 34|1@0+ (1,0) [0|1] "" XXX + SG_ ACCOnOffBtnInv : 43|1@0+ (1,0) [0|1] "" XXX + SG_ ACCResumeBtnInv : 45|1@0+ (1,0) [0|1] "" XXX + SG_ ACCSetBtnInv : 47|1@0+ (1,0) [0|1] "" XXX + SG_ TimeGapIncreaseBtn : 49|1@0+ (1,0) [0|1] "" XXX + SG_ TimeGapDecreaseBtn : 50|1@0+ (1,0) [0|1] "" XXX + SG_ ACCMinusBtnInv : 32|1@0+ (1,0) [0|1] "" XXX + SG_ TimeGapIncreaseBtnInv : 33|1@0+ (1,0) [0|1] "" XXX + +BO_ 298 NEW_MSG_5: 8 XXX + SG_ EngineRpm : 52|13@0+ (1,0) [0|8000] "" XXX + +BO_ 336 NEW_MSG_8: 8 XXX + +BO_ 328 VehicleSpeed1: 8 XXX + SG_ VehicleSpeed : 55|16@0+ (0.01,0) [0|65535] "" XXX + +BO_ 465 NEW_MSG_4: 8 XXX + SG_ NEW_SIGNAL_1 : 55|16@0+ (1,0) [0|4095] "" XXX + +BO_ 544 wheelspeed1: 8 BCM + SG_ WhlSpdRR : 39|16@0+ (0.01,-327.68) [0|65535] "" XXX + SG_ WhlSpdLR : 55|16@0+ (0.01,-327.68) [0|65535] "" XXX + +BO_ 565 wheelspeed0: 8 BCM + SG_ WhlSpdLF : 55|16@0+ (0.01,-327.68) [0|65535] "" XXX + SG_ WhlSpdRF : 39|16@0+ (0.01,-327.68) [0|65535] "" XXX + +BO_ 582 PSCM1: 8 PSCM + SG_ byte4 : 39|4@0+ (1,0) [0|15] "" XXX + SG_ LKATorque : 35|12@0+ (1,-2000) [0|65535] "" XXX + SG_ SteeringAngleServo : 23|16@0+ (0.0447,-1468) [0|65535] "deg" XXX + SG_ SteeringWheelRateOfChange : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ LKAActive : 55|8@0+ (1,0) [0|255] "" XXX + +BO_ 608 FSM1: 8 FSM + SG_ ACC_Tracking : 7|8@0+ (1,0) [0|255] "" XXX + +BO_ 609 fromWhere: 8 XXX + SG_ SteeringAngle : 21|14@0+ (0.1,-1021) [0|65535] "deg" XXX + +BO_ 610 FSM2: 8 FSM + SG_ TrqLim : 23|8@0+ (1,-128) [0|255] "" PSCM + SG_ Checksum : 55|8@0+ (1,0) [0|255] "" PSCM + SG_ LKAAngleReq : 29|14@0+ (0.04,-327.68) [0|16383] "" PSCM + SG_ SET_X_02 : 31|2@0+ (1,0) [0|3] "" XXX + SG_ SET_X_10 : 47|6@0+ (1,0) [0|63] "" XXX + SG_ SET_X_A4 : 63|8@0+ (1,0) [0|255] "" XXX + SG_ SET_X_22 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ LKASteerDirection : 41|2@0+ (1,0) [0|3] "" PSCM + +BO_ 624 FSM3: 8 FSM + SG_ ACC_SOMETHING : 15|8@0+ (1,0) [0|255] "" XXX + SG_ ACC_Some : 17|10@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 47|8@0+ (1,0) [0|255] "" XXX + +BO_ 648 BrakePedal: 8 XXX + SG_ Counter : 0|3@1+ (1,0) [0|7] "" XXX + SG_ BrakePedal : 24|8@1+ (1,4) [0|255] "" XXX + +BO_ 794 FSM4: 8 FSM + SG_ NEW_SIGNAL_1 : 47|16@0+ (1,-46090) [0|16383] "" XXX + SG_ NEW_SIGNAL_2 : 32|4@1+ (1,0) [0|15] "" XXX + +BO_ 819 PSCM0: 8 PSCM + +BO_ 923 NEW_MSG_1: 8 XXX + SG_ NEW_SIGNAL_1 : 15|16@0+ (1,0) [0|65535] "" XXX + +BO_ 1021 FSM5: 8 FSM + +BO_ 1039 MiscCarInfo: 8 XXX + SG_ TurnSignal : 33|2@0+ (1,0) [0|3] "" XXX + +BO_ 1279 PSCM3: 8 PSCM + +BO_ 1830 diagCEMReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1838 diagCEMResp: 8 XXX + SG_ byte03 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ byte47 : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 1840 diagPSCMReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1848 diagPSCMResp: 8 XXX + SG_ byte03 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ byte47 : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 1892 diagFSMReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1900 diagFSMResp: 8 XXX + SG_ byte03 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ byte47 : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 1939 diagCVMReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + +BO_ 1947 diagCVMResp: 8 XXX + SG_ byte03 : 7|32@0+ (1,0) [0|4294967295] "" XXX + SG_ byte47 : 39|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 2015 diagGlobalReq: 8 XXX + SG_ byte0 : 7|8@0+ (1,0) [0|255] "" XXX + SG_ byte1 : 15|8@0+ (1,0) [0|255] "" XXX + SG_ byte2 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ byte3 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ byte4 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ byte5 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ byte6 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ byte7 : 63|8@0+ (1,0) [0|255] "" XXX + + + + +CM_ SG_ 16 RateOfChangeOrTorque "Rate of change? Torque?"; +CM_ SG_ 16 SteeringDirection "0 = CCW, 1=CW (turning left or right of center)"; +CM_ SG_ 298 EngineRpm "Might be engine rpm. But behaves abit weird."; +CM_ SG_ 582 byte4 "High nibble"; +CM_ SG_ 582 SteeringWheelRateOfChange "Some rate of change for steering wheel? Torque?"; +CM_ SG_ 582 byte0 "0=CCW, 1=CW, bit 2,"; +CM_ SG_ 582 LKAActive "Bit 1, 1 When LKA Active, Bit 3, 1 When denying?"; +CM_ SG_ 81 ACCStatus "0=Acc Unavailable, 1=???, 2=Acc Ready, 3,4=???, 6= Acc Active, 7=Acc active tracking object (probably) "; +CM_ SG_ 608 ACC_Tracking "Seems to track distance, or speed of vehicle in front."; +CM_ SG_ 610 SET_X_22 "0x20 Heartbeat, VEgo <58kph = 0x03, VEgo >65kph = 0x04, 0x05"; +CM_ SG_ 624 ACC_SOMETHING "Might be some acc speed, moved abit after activating acc"; +CM_ SG_ 624 ACC_Some "Jumps to life after activating ACC, 0 when not active"; +CM_ SG_ 295 ACCMinusBtn "ACC Minus (-) button pressed"; +CM_ SG_ 295 ACCSetBtn "Acc Set button (+) pressed"; +CM_ SG_ 295 ACCOnOffBtn "Cruise control on/off button pressed"; +CM_ SG_ 295 ACCResumeBtn "ACC Resume button pressed"; +CM_ SG_ 295 TimeGapDecreaseBtnInv "Active zero when button pressed."; +CM_ SG_ 295 ACCOnOffBtnInv "Active zero when button pressed."; +CM_ SG_ 295 ACCResumeBtnInv "Active zero when button pressed."; +CM_ SG_ 295 ACCSetBtnInv "Active zero when button pressed."; +CM_ SG_ 295 TimeGapIncreaseBtn "Increase the time gap on ACC"; +CM_ SG_ 295 TimeGapDecreaseBtn "Decrease the time gap on ACC"; +CM_ SG_ 295 ACCMinusBtnInv "Active zero when button pressed."; +CM_ SG_ 295 TimeGapIncreaseBtnInv "Active zero when button pressed."; +CM_ SG_ 1039 TurnSignal "0 = Nothing, 1= Left, 3=Right"; diff --git a/opendbc/vw_golf_mk4.dbc b/opendbc_repo/opendbc/dbc/vw_golf_mk4.dbc similarity index 100% rename from opendbc/vw_golf_mk4.dbc rename to opendbc_repo/opendbc/dbc/vw_golf_mk4.dbc diff --git a/opendbc/vw_mqb_2010.dbc b/opendbc_repo/opendbc/dbc/vw_mqb_2010.dbc similarity index 89% rename from opendbc/vw_mqb_2010.dbc rename to opendbc_repo/opendbc/dbc/vw_mqb_2010.dbc index 44ec0cd3e01623b..cb6ea038897cbe1 100644 --- a/opendbc/vw_mqb_2010.dbc +++ b/opendbc_repo/opendbc/dbc/vw_mqb_2010.dbc @@ -102,8 +102,8 @@ BO_ 681 ACC_15: 8 XXX SG_ AWV_Warnlevel : 58|6@1+ (1,0) [0|63] "" XXX BO_ 64 Airbag_01: 8 Airbag_MQB - SG_ Airbag_01_CRC : 0|8@1+ (1,0) [0|255] "" BMS_MQB,Gateway_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ Airbag_01_BZ : 8|4@1+ (1,0) [0|15] "" BMS_MQB,Gateway_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" BMS_MQB,Gateway_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" BMS_MQB,Gateway_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB SG_ AB_RGS_Anst : 12|4@1+ (1,0) [0|15] "" Gateway_MQB SG_ AB_Front_Crash : 16|1@1+ (1,0) [0|1] "" Gateway_MQB SG_ AB_Heck_Crash : 17|1@1+ (1,0) [0|1] "" Gateway_MQB @@ -126,6 +126,12 @@ BO_ 64 Airbag_01: 8 Airbag_MQB SG_ AB_MKB_gueltig : 39|1@1+ (1,0) [0|1] "" Gateway_MQB SG_ AB_MKB_Anforderung : 40|1@1+ (1,0) [0|1] "" Gateway_MQB SG_ AB_Versorgungsspannung : 41|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Deaktivierung_HV : 42|3@1+ (1.0,0.0) [0.0|7] "" BMS,Gateway_MQB,LEH_MQB,Motor_Hybrid_MQB + SG_ AB_EDR_Trigger : 45|2@1+ (1.0,0.0) [0.0|3] "" Gateway_MQB + SG_ AB_Gurtwarn_HFS : 47|1@1+ (1.0,0.0) [0.0|1] "" Gateway_MQB + SG_ AB_Gurtwarn_HBFS : 48|1@1+ (1.0,0.0) [0.0|1] "" Gateway_MQB + SG_ SC_Masterzeit_Offset : 53|2@1+ (5.08,0) [0.00|15.24] "Unit_Secon" Gateway_MQB + SG_ SC_Masterzeit : 57|7@1+ (0.04,0) [0.00|5.04] "Unit_Secon" Gateway_MQB BO_ 1312 Airbag_02: 8 Airbag_MQB SG_ AB_Belegung_VB : 26|2@1+ (1,0) [0|3] "" Gateway_MQB @@ -294,8 +300,8 @@ BO_ 260 EPB_01: 8 Gateway_MQB SG_ EPB_Status : 61|2@1+ (1,0) [0|3] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB BO_ 257 ESP_02: 8 Gateway_MQB - SG_ ESP_02_CRC : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_02_BZ : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB SG_ ESP_QBit_Gierrate : 12|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB SG_ ESP_QBit_Laengsbeschl : 13|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB SG_ ESP_QBit_Querb : 14|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB @@ -369,8 +375,8 @@ BO_ 914 ESP_07: 8 Gateway_MQB SG_ ESP_OBD_Status : 61|1@1+ (1,0) [0|1] "" Vector__XXX BO_ 278 ESP_10: 8 Gateway_MQB - SG_ ESP_10_CRC : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_10_BZ : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB SG_ ESP_QBit_Wegimpuls_VL : 12|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB SG_ ESP_QBit_Wegimpuls_VR : 13|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB SG_ ESP_QBit_Wegimpuls_HL : 14|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB @@ -391,34 +397,60 @@ BO_ 178 ESP_19: 8 Gateway_MQB SG_ ESP_VR_Radgeschw_02 : 48|16@1+ (0.0075,0) [0|491.49] "Unit_KiloMeterPerHour" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB BO_ 1629 ESP_20: 8 Gateway_MQB - SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Vector__XXX - SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Vector__XXX - SG_ BR_Systemart : 12|2@1+ (1,0) [0|3] "" Vector__XXX - SG_ ESP_Zaehnezahl : 16|8@1+ (1,0) [0|255] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB - SG_ ESP_Charisma_FahrPr : 24|4@1+ (1,0) [0|15] "" Vector__XXX - SG_ ESP_Charisma_Status : 28|2@1+ (1,0) [0|3] "" Vector__XXX - SG_ BR_QBit_Reifenumfang : 51|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB - SG_ BR_Reifenumfang : 52|12@1+ (1,0) [0|4095] "Unit_MilliMeter" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ BR_Systemart : 12|2@1+ (1,0) [0|3] "" XXX + SG_ ESP_SpannungsAnf_02 : 14|2@1+ (1,0) [0|3] "" XXX + SG_ ESP_Zaehnezahl : 16|8@1+ (1,0) [0|255] "" XXX + SG_ ESP_Charisma_FahrPr : 24|4@1+ (1,0) [0|15] "" XXX + SG_ ESP_Charisma_Status : 28|2@1+ (1,0) [0|3] "" XXX + SG_ ESP_Wiederstart_Anz_01 : 30|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Wiederstart_Anz_02 : 31|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Wiederstart_Anz_03 : 32|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Wiederstart_Anz_04 : 33|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Stoppverbot_Anz_01 : 34|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Stoppverbot_Anz_02 : 35|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Stoppverbot_Anz_03 : 36|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Stoppverbot_Anz_04 : 37|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Stoppverbot_Anz_05 : 38|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Stoppverbot_Anz_06 : 39|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Stoppverbot_Anz_07 : 40|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Stoppverbot_Anz_Std : 41|1@1+ (1,0) [0|1] "" XXX + SG_ ESP_Dachrelingsensor : 42|2@1+ (1,0) [0|3] "" XXX + SG_ ESP_Stoppverbot_Anz_08 : 44|1@1+ (1,0) [0|1] "" XXX + SG_ HDC_Charisma_FahrPr : 45|4@1+ (1,0) [0|15] "" XXX + SG_ HDC_Charisma_Status : 49|2@1+ (1,0) [0|3] "" XXX + SG_ BR_QBit_Reifenumfang : 51|1@1+ (1,0) [0|1] "" XXX + SG_ BR_Reifenumfang : 52|12@1+ (1,0) [0|4095] "Unit_MilliMeter" XXX BO_ 253 ESP_21: 8 Gateway_MQB - SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ BR_Eingriffsmoment : 12|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_v_Signal : 32|16@1+ (0.01,0) [0|655.32] "Unit_KiloMeterPerHour" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB - SG_ ASR_Tastung_passiv : 48|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_Tastung_passiv : 49|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_Systemstatus : 50|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ASR_Schalteingriff : 51|2@1+ (1,0) [0|3] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB - SG_ ESP_Haltebestaetigung : 53|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_QBit_v_Signal : 55|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ABS_Bremsung : 56|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ASR_Anf : 57|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ MSR_Anf : 58|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ EBV_Eingriff : 59|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ EDS_Eingriff : 60|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_Eingriff : 61|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_ASP : 62|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ ESP_Anhaltevorgang_ACC_aktiv : 63|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ BR_Eingriffsmoment : 12|10@1+ (1,-509) [-509|509] "" XXX + SG_ ESP_PLA_Bremseingriff : 22|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Diagnose : 23|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESC_Reku_Freigabe : 24|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESC_v_Signal_Qualifier_High_Low : 25|3@1+ (1.0,0.0) [0.0|7] "" XXX + SG_ ESP_Vorsteuerung : 28|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_AWV3_Brems_aktiv : 29|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ OBD_Schlechtweg : 30|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ OBD_QBit_Schlechtweg : 31|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_v_Signal : 32|16@1+ (0.01,0) [0.00|655.32] "Unit_KiloMeterPerHour" XXX + SG_ ASR_Tastung_passiv : 48|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Tastung_passiv : 49|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Systemstatus : 50|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ASR_Schalteingriff : 51|2@1+ (1.0,0.0) [0.0|3] "" XXX + SG_ ESP_Haltebestaetigung : 53|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_MKB_Abbruch_Geschw : 54|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_QBit_v_Signal : 55|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ABS_Bremsung : 56|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ASR_Anf : 57|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MSR_Anf : 58|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ EBV_Eingriff : 59|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ EDS_Eingriff : 60|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Eingriff : 61|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_ASP : 62|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Anhaltevorgang_ACC_aktiv : 63|1@1+ (1.0,0.0) [0.0|1] "" XXX BO_ 987 Gateway_72: 8 Gateway_MQB SG_ BCM_01_alt : 0|1@1+ (1,0) [0|1] "" Airbag_MQB @@ -482,18 +514,21 @@ BO_ 296 Getriebe_06: 3 Getriebe_DQ_Hybrid_MQB SG_ GE_Testparameter_2 : 16|8@1+ (1,0) [0|255] "" Waehlhebel_MQB BO_ 173 Getriebe_11: 8 Getriebe_DQ_Hybrid_MQB - SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ COUNTERXX : 8|4@1+ (1,0) [0|15] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_MMom_Soll_02 : 12|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_MMom_Vorhalt_02 : 22|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_Uefkt : 32|10@1+ (0.1,0) [0|102.2] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_Fahrstufe : 42|5@1+ (1,0) [0|31] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_Schaltvorgang : 47|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_Status_Kupplung : 54|2@1+ (1,0) [0|3] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_MMom_Status : 56|2@1+ (1,0) [0|3] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_Freig_MMom_Vorhalt : 58|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_Verbot_Ausblendung : 59|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB - SG_ GE_Zielgang : 60|4@1+ (1,0) [0|15] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER_DISABLED : 8|4@1+ (1,0) [0|15] "" XXX + SG_ GE_MMom_Soll_02 : 12|10@1+ (1,-509) [-509|509] "" XXX + SG_ GE_MMom_Vorhalt_02 : 22|10@1+ (1,-509) [-509|509] "" XXX + SG_ GE_Uefkt : 32|10@1+ (0.1,0) [0|102.2] "" XXX + SG_ GE_Fahrstufe : 42|4@1+ (1,0) [0|15] "" XXX + SG_ GE_reserv_Fahrstufe : 46|1@1+ (1,0) [0|1] "" XXX + SG_ GE_Schaltablauf : 47|2@1+ (1,0) [0|3] "" XXX + SG_ GE_Uefkt_unplausibel : 49|1@1+ (1,0) [0|1] "" XXX + SG_ GE_MMom_Status_02 : 50|3@1+ (1,0) [0|7] "" XXX + SG_ GE_Status_Kraftschluss : 53|3@1+ (1,0) [0|7] "" XXX + SG_ GE_MMom_Status : 56|2@1+ (1,0) [0|3] "" XXX + SG_ GE_Freig_MMom_Vorhalt : 58|1@1+ (1,0) [0|1] "" XXX + SG_ GE_Verbot_Ausblendung : 59|1@1+ (1,0) [0|1] "" XXX + SG_ GE_Zielgang : 60|4@1+ (1,0) [0|15] "" XXX BO_ 174 Getriebe_12: 8 Getriebe_DQ_Hybrid_MQB SG_ Getriebe_12_CRC : 0|8@1+ (1,0) [0|255] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB @@ -858,15 +893,19 @@ BO_ 1648 Motor_18: 8 Motor_Diesel_MQB BO_ 289 Motor_20: 8 Motor_Diesel_MQB SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ COUNTER : 8|4@1+ (1,0) [0|255] "" XXX - SG_ MO_Fahrpedalrohwert_01 : 12|8@1+ (0.4,0) [0|101.6] "Unit_PerCent" Airbag_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB - SG_ MO_QBit_Fahrpedalwerte_01 : 20|1@1+ (1,0) [0|1] "" Airbag_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB - SG_ MO_Fahrpedalgradient : 21|8@1+ (25,0) [0|6350] "Unit_PerCentPerSecon" Airbag_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB - SG_ MO_Sig_Fahrpedalgradient : 29|1@1+ (1,0) [0|1] "" Airbag_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB - SG_ MO_rel_Saugrohrdruck : 30|6@1+ (18,0) [0|1116] "Unit_MilliBar" Gateway_MQB - SG_ MO_rel_Saugrohrdruck_gem_err : 36|1@1+ (1,0) [0|1] "" Gateway_MQB - SG_ MO_Moment_im_Leerlauf : 37|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB - SG_ MO_Schubabschaltung : 38|1@1+ (1,0) [0|1] "" Gateway_MQB - SG_ MO_Solldrehz_Leerlauf : 40|8@1+ (10,0) [0|2540] "Unit_MinutInver" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Fahrpedalrohwert_01 : 12|8@1+ (0.4,0) [0.0|101.6] "Unit_PerCent" XXX + SG_ MO_QBit_Fahrpedalwerte_01 : 20|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_Fahrpedalgradient : 21|8@1+ (25,0) [0|6350] "Unit_PerCentPerSecon" XXX + SG_ MO_Sig_Fahrpedalgradient : 29|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_rel_Saugrohrdruck : 30|6@1+ (18,0) [0|1116] "Unit_MilliBar" XXX + SG_ MO_rel_Saugrohrdruck_gem_err : 36|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_Moment_im_Leerlauf : 37|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_Schubabschaltung : 38|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_StartStopp_StoppVorbereitung : 39|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_Solldrehz_Leerlauf : 40|8@1+ (10,0) [0|2540] "Unit_MinutInver" XXX + SG_ MO_Entkopplung_Sollschlupf : 48|7@1+ (20,0) [0|2480] "Unit_MinutInver" XXX + SG_ MO_temporaere_Fahrerabwesenheit : 55|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ TSK_a_Soll_gradientenbegrenzt : 57|7@1+ (0.1,-7.2) [-7.2|5.4] "Unit_MeterPerSeconSquar" XXX BO_ 967 Motor_26: 8 Motor_Diesel_MQB SG_ MO_HYB_Status_HV_Ladung : 8|3@1+ (1,0) [0|7] "" Gateway_MQB @@ -1263,10 +1302,20 @@ BO_ 159 LH_EPS_03: 8 XXX SG_ EPS_VZ_Lenkmoment : 55|1@1+ (1,0) [0|1] "" XXX SG_ EPS_Lenkungstyp : 60|4@1+ (1,0) [0|15] "" XXX -BO_ 286 VehicleSpeed: 8 XXX - SG_ VehicleSpeed_CRC : 0|8@1+ (1,0) [0|255] "" XXX - SG_ VehicleSpeed_BZ : 8|4@1+ (1,0) [0|15] "" XXX - SG_ Speed : 52|12@1+ (0.125,0) [0|1] "" XXX +BO_ 286 ESP_08: 8 Gateway_MQB + SG_ ESP_08_CRC : 0|8@1+ (1,0) [0|255] "" XXX + SG_ ESP_08_BZ : 8|4@1+ (1,0) [0|15] "" XXX + SG_ ESP_ANB_CM_Rueckk_Umsetz : 12|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Konsistenz_ACC_Botschaft : 13|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Stillstandsphase_erschoepft : 14|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_ZT_Rueckk_Umsetz : 15|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Tuerkontakt_Fahrertuer : 16|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Abrutschen_Stillstand : 18|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_Fahrer_tritt_ZBR_Schw : 19|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_QBit_v_ref : 41|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ ESP_v_ref_Fahrtrichtung : 42|2@1+ (1.0,0.0) [0.0|3] "" XXX + SG_ ESC_Bremsdruckgradient : 44|8@1+ (10,0) [0|2500] "Unit_BarPerSecon" XXX + SG_ ESP_v_ref : 52|12@1+ (0.125,0) [0.000|511.500] "Unit_KiloMeterPerHour" XXX BO_ 919 LDW_02: 8 XXX SG_ LDW_Gong : 12|2@1+ (1,0) [0|3] "" XXX @@ -1332,25 +1381,32 @@ BO_ 695 RCTA_01: 8 XXX SG_ RCTA_01_CRC : 0|8@1+ (1,0) [0|255] "" XXX BO_ 783 SWA_01: 8 Gateway_MQB - SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Vector__XXX - SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Vector__XXX - SG_ SWA_Anzeigen : 12|4@1+ (1,0) [0|15] "" Kombi_D4 - SG_ SWA_Blindheit_erkannt : 16|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_rel_Nichtverf : 17|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_rel_Fehler : 18|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Sta_aktiv : 19|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Sta_passiv : 20|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Standziele_li : 24|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Kolonne_li : 25|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Infostufe_SWA_li : 26|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Warnung_SWA_li : 27|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Kolonne_mi : 33|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Standziele_re : 40|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Kolonne_re : 41|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Infostufe_SWA_re : 42|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Warnung_SWA_re : 43|1@1+ (1,0) [0|1] "" Vector__XXX - SG_ SWA_Gischtzaehler : 48|7@1+ (1,0) [0|100] "Unit_PerCent" Vector__XXX - SG_ SWA_KD_Fehler : 59|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ SWA_Anzeigen : 12|4@1+ (1,0) [0|15] "" XXX + SG_ SWA_Blindheit_erkannt : 16|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_rel_Nichtverf : 17|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_rel_Fehler : 18|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Sta_aktiv : 19|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Sta_passiv : 20|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_FT_RueckLED : 21|1@1+ (1,0) [0|1] "" XXX + SG_ ASW_Status : 22|2@1+ (1,0) [0|3] "" XXX + SG_ SWA_Standziele_li : 24|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Kolonne_li : 25|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Infostufe_SWA_li : 26|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Warnung_SWA_li : 27|1@1+ (1,0) [0|1] "" XXX + SG_ ASW_Warnung_FS : 28|1@1+ (1,0) [0|1] "" XXX + SG_ ASW_Warnung_BFS : 29|1@1+ (1,0) [0|1] "" XXX + SG_ ASW_Kombitexte : 30|3@1+ (1,0) [0|7] "" XXX + SG_ SWA_Kolonne_mi : 33|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Standziele_re : 40|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Kolonne_re : 41|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Infostufe_SWA_re : 42|1@1+ (1,0) [0|1] "" XXX + SG_ SWA_Warnung_SWA_re : 43|1@1+ (1,0) [0|1] "" XXX + SG_ HRE_Anzeigetexte : 44|4@1+ (1,0) [0|15] "" XXX + SG_ SWA_Gischtzaehler : 48|7@1+ (1,0) [0|100] "Unit_PerCent" XXX + SG_ Heckradar_Kombitexte : 56|5@1+ (1,0) [0|31] "" XXX + SG_ RCTA_Kombitexte : 61|3@1+ (1,0) [0|7] "" XXX BO_ 804 ACC_04: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX @@ -1378,9 +1434,48 @@ BO_ 997 TSG_FT_02: 8 XXX BO_ 1175 Parkhilfe_01: 8 XXX -BO_ 427 ESP_33: 8 XXX - SG_ ESP_33_BZ : 8|4@1+ (1,0) [0|15] "" XXX - SG_ ESP_33_CRC : 0|8@1+ (1,0) [0|255] "" XXX +BO_ 427 ESP_33: 8 Gateway_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_AHW_aktiv : 12|3@1+ (1,0) [0|7] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_AHW_nicht_verfuegbar : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_ANB_CM_aktiv : 16|2@1+ (1,0) [0|3] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_ANB_CM_nicht_verfuegbar : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Warnruck_aktiv : 19|4@1+ (1,0) [0|15] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_Warnruck_nicht_verfuegbar : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Prefill_aktiv : 24|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Prefill_nicht_verfuegbar : 25|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_HBA_aktiv : 26|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ ESC_HBA_nicht_verfuegbar : 27|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ ESC_TSK_SRBM_Anf : 28|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_TSK_SRBM_nicht_verfuegbar : 29|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_Verz_Reg_aktiv : 30|4@1+ (1,0) [0|15] "" Airbag_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_Verz_Reg_nicht_verfuegbar : 34|1@1+ (1,0) [0|1] "" Airbag_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_Verz_Reg_TB_nicht_verfuegbar : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Verz_Reg_ZB_nicht_verfuegbar : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Bremslicht_unplausibel : 37|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_Konsistenz_ACC : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_AWV : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_ARA : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_IPA : 41|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_FCW : 42|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_NV : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_RCTA : 44|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_TSK : 45|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_Konsistenz_vFGS : 46|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_STA : 47|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Fahrer_Bremsdruck_bestimmend : 48|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_Konsistenz_EA : 49|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_BFF : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_MKB : 51|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ ESC_Verz_ASIL_Verfuegbarkeit : 52|3@1+ (1,0) [0|7] "" Airbag_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESC_Pumpenanlauf_aktiv : 55|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_AGW : 56|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_KAS : 57|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_PCF : 58|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_FAS_VK : 59|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Verz_Begrenzung : 60|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESC_Konsistenz_AWA : 61|1@1+ (1,0) [0|1] "" Vector__XXX BO_ 418 ESP_15: 8 XXX SG_ ESP_15_CRC : 0|8@1+ (1,0) [0|255] "" XXX @@ -1399,7 +1494,34 @@ BO_ 988 Gateway_73: 8 XXX BO_ 792 Kamera_Status: 8 XXX -BO_ 981 Licht_Anf_01: 8 XXX +BO_ 981 Licht_Anf_01: 8 Vector__XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ BCM1_Kurvenlicht_links_Anf : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Kurvenlicht_rechts_Anf : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Standlicht_Anf : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Abblendlicht_Anf : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Fernlicht_Anf : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Nebellicht_Anf : 17|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Parklicht_li_Anf : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Parklicht_re_Anf : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Nebelschluss_Ahg_Anf : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Nebelschluss_Fzg_Anf : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Schlusslicht_Anf : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM_Rueckfahrlicht_Anf : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Signaturlicht_Anf : 24|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Umfeldleuchten_Anf : 25|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Tagfahrlicht_Anf : 26|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Regenlicht_Anf : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Autobahnlicht_Anf : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Touristen_Licht_Anf : 29|1@1+ (1,0) [0|1] "" Frontradar + SG_ BCM1_CH_aktiv : 30|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_LH_aktiv : 31|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Gleitende_Leuchtw_Anf : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_GLW_Fernlicht_Anf : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Adaptive_Lichtvert_Anf : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_CH_LH_aktiv : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Allwetterlicht_Anf : 41|1@1+ (1,0) [0|1] "" Frontradar BO_ 1440 RLS_01: 8 XXX @@ -1433,11 +1555,22 @@ BO_ 1720 Kombi_03: 8 XXX SG_ KBI_Max_Tankinhalt : 40|8@1+ (0.5,0) [0.0|126.5] "" XXX SG_ KBI_Reifenumfang_Sekundaer : 48|12@1+ (1,0) [0|4095] "Unit_MilliMeter" XXX -BO_ 391 EV_Gearshift: 8 XXX - SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX - SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX - SG_ GearPosition : 16|4@1+ (1,0) [0|255] "" XXX - SG_ RegenBrakingMode : 12|2@1+ (1,0) [0|3] "" XXX +BO_ 391 Motor_EV_01: 8 Motor_MQB_BEV + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ EV_Rekuperationsstufe : 12|3@1+ (1.0,0.0) [0.0|7] "" XXX + SG_ HV_Bordnetz_aktiv : 15|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_Waehlpos : 16|3@1+ (1.0,0.0) [0.0|7] "" XXX + SG_ MO_Fehler_NTKreis : 19|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_Fehler_Notabschaltung_Klima : 20|2@1+ (1.0,0.0) [0.0|3] "" XXX + SG_ MO_KLE_FStatus : 22|2@1+ (1.0,0.0) [0.0|3] "" XXX + SG_ MO_WH_Texte : 24|3@1+ (1.0,0.0) [0.0|7] "" XXX + SG_ MO_Drehzahl_VM : 32|16@1+ (0.25,0) [0.00|16383.00] "Unit_MinutInver" XXX + SG_ HV_Bordnetz_Fehler : 48|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_Tankbereitschaft_Status : 49|3@1+ (1.0,0.0) [0.0|7] "" XXX + SG_ MO_Tankklappensteuerung : 52|2@1+ (1.0,0.0) [0.0|3] "" XXX + SG_ MO_HVEM_Eskalation : 54|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ MO_HVEM_MaxLeistung : 55|9@1+ (50,0) [0|25450] "Unit_Watt" XXX CM_ SG_ 134 LWI_Lenkradwinkel "Steering angle WITH variable ratio effect included"; CM_ SG_ 159 EPS_HCA_Status "Status of Heading Control Assist feature"; @@ -1445,7 +1578,7 @@ CM_ SG_ 159 EPS_Lenkmoment "Steering input by driver, torque"; CM_ SG_ 159 EPS_VZ_Lenkmoment "Steering input by driver, direction"; CM_ SG_ 159 EPS_Berechneter_LW "Raw steering angle, degrees"; CM_ SG_ 159 EPS_VZ_BLW "Raw steering angle, direction"; -CM_ SG_ 173 COUNTERXX "Message not renamed to COUNTER because J533 rate-limiting makes it look like messages are being lost"; +CM_ SG_ 173 COUNTER_DISABLED "Message not renamed to COUNTER because J533 rate-limiting makes it look like messages are being lost"; CM_ SG_ 294 HCA_01_Vib_Freq "Frequenz der Lenkradvibration"; CM_ SG_ 294 HCA_01_LM_Offset "Von HCA angefordertes Lenkmoment (Betrag)"; CM_ SG_ 294 EA_ACC_Sollstatus "Status-Anforderung ACC von Emergency Alert. Statuswechsel bei Flanke. Solange Wert=1, wird EA_ACC_Wunschgeschwindigkeit übernommen. Wert=2 führt zu Zustand ¿ACC_GRA_passiv¿"; @@ -1483,7 +1616,7 @@ CM_ SG_ 780 Folgefahrt "Following another vehicle"; CM_ SG_ 780 SetAbstand "Set following distance"; CM_ SG_ 780 Abstand "Following distance"; CM_ SG_ 780 SetSpeed "ACC set speed"; -CM_ SG_ 391 GearPosition "Traditional PRND plus B-mode aggressive regen, B-mode mapped to Drive"; +CM_ SG_ 391 MO_Waehlpos "Traditional PRND plus B-mode aggressive regen, B-mode mapped to Drive"; CM_ SG_ 679 ACC_ADAPTIVE "TSK_06.TSK_Limiter_ausgewaehlt seems to take precedence"; CM_ SG_ 960 ZAS_Kl_15 "Indicates ignition on"; CM_ SG_ 1720 KBI_BCmE_aktiv "Anzeige BCmE aktiv (BCmE-Screen oder Einsparhinweis in der Anzeige)"; @@ -1621,8 +1754,8 @@ VAL_ 681 AWV_Status_Anzeige 0 "Init" 1 "verfuegbar" 2 "nicht_verfuegbar" ; VAL_ 681 AWV_Einstellung_System_FSG 0 "deaktiviert" 1 "aktiviert" ; VAL_ 681 AWV_Einstellung_Warnung_FSG 0 "Aus" 1 "Setting_2" 2 "Setting_3" 3 "Setting_4" 4 "Setting_5" 5 "Ein" ; VAL_ 681 AWV_Warnlevel 0 "keine_Gefaehrdung" 63 "max_Gefaehrdung" ; -VAL_ 391 GearPosition 2 "P" 3 "R" 4 "N" 5 "D" 6 "D" ; -VAL_ 391 RegenBrakingMode 0 "default" 1 "B1" 2 "B2" 3 "B3" ; +VAL_ 391 MO_Waehlpos 2 "P" 3 "R" 4 "N" 5 "D" 6 "D" ; +VAL_ 391 EV_Rekuperationsstufe 0 "default" 1 "B1" 2 "B2" 3 "B3" ; VAL_ 870 Fast_Send_Rate_Active 0 "1 Hz" 1 "50 Hz" ; VAL_ 1720 KBI_Variante_USA 0 "keine USA-Variante" 1 "USA-Variante" ; VAL_ 1720 KBI_Variante 0 "Zeiger Kombiinstrument" 1 "Volldisplay Kombiinstrument" ; diff --git a/opendbc_repo/opendbc/dbc/vw_mqbevo.dbc b/opendbc_repo/opendbc/dbc/vw_mqbevo.dbc new file mode 100644 index 000000000000000..91be4a246504272 --- /dev/null +++ b/opendbc_repo/opendbc/dbc/vw_mqbevo.dbc @@ -0,0 +1,1612 @@ +BO_ 64 Airbag_01: 8 Airbag_MQB + SG_ Airbag_01_CRC : 0|8@1+ (1,0) [0|255] "" BMS_MQB,Gateway_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ Airbag_01_BZ : 8|4@1+ (1,0) [0|15] "" BMS_MQB,Gateway_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ AB_RGS_Anst : 12|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ AB_Front_Crash : 16|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Heck_Crash : 17|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_SF_Crash : 18|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_SB_Crash : 19|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Rollover_Crash : 20|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Crash_Int : 21|3@1+ (1,0) [0|7] "" BMS_MQB,Gateway_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ AB_Lampe : 24|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Deaktiviert : 25|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_VB_deaktiviert : 26|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Systemfehler : 27|1@1+ (1,0) [0|1] "" BMS_MQB,Gateway_MQB,LEH_MQB + SG_ AB_Diagnose : 28|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Stellgliedtest : 29|1@1+ (1,0) [0|1] "" BMS_MQB,Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ AB_Erh_Auf_VB : 30|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Gurtwarn_VF : 32|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Gurtwarn_VB : 33|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Anzeige_Fussg : 34|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Texte_AKS : 36|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_PAO_Leuchte_Anf : 38|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_MKB_gueltig : 39|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_MKB_Anforderung : 40|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ AB_Versorgungsspannung : 41|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 65 Airbag_03: 8 Airbag_MQB + SG_ Airbag_03_CRC : 0|8@1+ (1,0) [0|255] "" Gateway_MQB + SG_ Airbag_03_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ AB_MKB_Safing : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 134 LWI_01: 8 Gateway_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ LWI_Sensorstatus : 12|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ LWI_QBit_Sub_Daten : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LWI_QBit_Lenkradwinkel : 15|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ LWI_Lenkradwinkel : 16|13@1+ (0.1,0) [0|800] "Unit_DegreOfArc" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ LWI_VZ_Lenkradwinkel : 29|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ LWI_VZ_Lenkradw_Geschw : 30|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LWI_Lenkradw_Geschw : 31|9@1+ (5,0) [0|2500] "Unit_DegreOfArcPerSecon" Vector__XXX + SG_ LWI_Sub_Daten : 40|16@1+ (1,0) [0|65535] "" Vector__XXX + +BO_ 157 Motor_Hybrid_01: 8 Motor_Hybrid_MQB + SG_ Motor_Hybrid_01_CRC : 0|8@1+ (1,0) [0|255] "" Getriebe_DQ_Hybrid_MQB + SG_ Motor_Hybrid_01_BZ : 8|4@1+ (1,0) [0|15] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_IstStatusK0 : 12|2@1+ (1,0) [0|3] "" Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_max_ind_VM_Mom : 16|10@1+ (1,0) [0|1021] "Unit_NewtoMeter" Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_Zielzustand : 26|3@1+ (1,0) [0|7] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_Startmodus : 29|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ MO_HYB_Startmodus_PQ3x : 32|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_Stoppmodus : 33|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_VM_Mom_oE : 40|10@1+ (1,-100) [-100|922] "Unit_NewtoMeter" Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_VM_aktiv : 50|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_Schaltverhinderung : 51|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB + +BO_ 158 Getriebe_Hybrid_01: 8 Getriebe_DQ_Hybrid_MQB + SG_ Getriebe_Hybrid_01_CRC : 0|8@1+ (1,0) [0|255] "" Motor_Hybrid_MQB + SG_ Getriebe_Hybrid_01_BZ : 8|4@1+ (1,0) [0|15] "" Motor_Hybrid_MQB + SG_ GE_HYB_Fehlerstatus : 12|2@1+ (1,0) [0|3] "" Motor_Hybrid_MQB + SG_ GE_HYB_Freigabe_K0 : 16|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB + SG_ GE_HYB_Freigabe_LL_Reg : 17|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB + SG_ GE_HYB_Freig_sSchl_K0 : 18|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB + SG_ GE_HYB_Freig_VM_EM_Stop : 19|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB + SG_ GE_HYB_Wiederstart : 20|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB + SG_ GE_HYB_Filt_MomAufbau : 21|3@1+ (1,0) [0|7] "" Motor_Hybrid_MQB + SG_ GE_HYB_nK0 : 24|8@1+ (25,0) [0|6350] "Unit_MinutInver" Vector__XXX + SG_ GE_HYB_MomEingriff_EM : 32|6@1+ (0.5,0) [0|31.5] "Unit_NewtoMeter" LEH_MQB + SG_ GE_HYB_VZ_MomEingriff_EM : 38|1@1+ (1,0) [0|1] "" LEH_MQB + SG_ GE_HYB_Sportfaktor : 56|4@1+ (1,0) [0|15] "" Motor_Hybrid_MQB + SG_ GE_HYB_VM_akt_halten : 61|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB + SG_ GE_HYB_StartAnf : 62|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB + SG_ GE_HYB_VM_Startkontr : 63|1@1+ (1,0) [0|1] "" Motor_Hybrid_MQB + +BO_ 159 LH_EPS_03: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ EPS_DSR_Status : 12|4@1+ (1,0) [0|15] "" XXX + SG_ EPS_Berechneter_LW : 16|12@1+ (0.15,0) [0|613.95] "Unit_DegreOfArc" XXX + SG_ EPS_BLW_QBit : 30|1@1+ (1,0) [0|1] "" XXX + SG_ EPS_VZ_BLW : 31|1@1+ (1,0) [0|1] "" XXX + SG_ EPS_HCA_Status : 32|4@1+ (1,0) [0|15] "" XXX + SG_ EPS_Lenkmoment : 40|10@1+ (1,0) [0|8] "Unit_centiNewtoMeter" XXX + SG_ EPS_Lenkmoment_QBit : 54|1@1+ (1,0) [0|1] "" XXX + SG_ EPS_VZ_Lenkmoment : 55|1@1+ (1,0) [0|1] "" XXX + SG_ EPS_Lenkungstyp : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 167 Motor_11: 8 Motor_Diesel_MQB + SG_ Motor_11_CRC : 0|8@1+ (1,0) [0|255] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ Motor_11_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Mom_Soll_Roh : 12|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Mom_Ist_Summe : 22|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,SAK_MQB + SG_ MO_Mom_Traegheit_Summe : 32|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Mom_Soll_gefiltert : 42|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Mom_Schub : 52|9@1+ (1,-509) [-509|0] "Unit_NewtoMeter" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Status_Normalbetrieb_01 : 61|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_erste_Ungenauschwelle : 62|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_QBit_Motormomente : 63|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 168 Motor_12: 8 Motor_Diesel_MQB + SG_ Motor_12_CRC : 0|8@1+ (1,0) [0|255] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ Motor_12_BZ : 8|4@1+ (1,0) [0|15] "" BMS_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ MO_Mom_neg_verfuegbar : 12|9@1+ (1,-509) [-509|0] "Unit_NewtoMeter" Gateway_MQB + SG_ MO_Mom_Begr_stat : 21|9@1+ (1,0) [0|509] "Unit_NewtoMeter" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Mom_Begr_dyn : 30|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB + SG_ MO_Momentenintegral_02 : 40|7@1+ (1,0) [0|100] "Unit_PerCent" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_QBit_Drehzahl_01 : 47|1@1+ (1,0) [0|1] "" BMS_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ MO_Drehzahl_01 : 48|16@1+ (0.25,0) [0|16383] "Unit_MinutInver" BMS_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,SAK_MQB + +BO_ 173 Getriebe_11: 8 Getriebe_DQ_Hybrid_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTERXX : 8|4@1+ (1,0) [0|15] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_MMom_Soll_02 : 12|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_MMom_Vorhalt_02 : 22|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Uefkt : 32|10@1+ (0.1,0) [0|102.2] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Fahrstufe : 42|5@1+ (1,0) [0|31] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Schaltvorgang : 47|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Status_Kupplung : 54|2@1+ (1,0) [0|3] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_MMom_Status : 56|2@1+ (1,0) [0|3] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Freig_MMom_Vorhalt : 58|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Verbot_Ausblendung : 59|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Zielgang : 60|4@1+ (1,0) [0|15] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 174 Getriebe_12: 8 Getriebe_DQ_Hybrid_MQB + SG_ Getriebe_12_CRC : 0|8@1+ (1,0) [0|255] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ Getriebe_12_BZ : 8|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Drehzahlmesser_Daempfung : 12|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Schubabschalt_Unt : 13|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Freigabe_Synchro : 14|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Synchro_Wunschdrehz : 15|9@1+ (25,0) [0|12750] "Unit_MinutInver" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Synchro_Zeit : 24|8@1+ (20,0) [0|5080] "Unit_MilliSecon" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Mom_Begr_Gradient : 32|8@1+ (10,0) [0|2540] "Unit_NewtoMeterPerSecon" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Anheb_Solldrehz_Leerlauf : 40|8@1+ (10,0) [0|2540] "Unit_MinutInver" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Aufnahmemoment : 48|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Anf_Zylabsch : 58|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ GE_HYB_DZ_Eingriff : 62|2@1+ (1,0) [0|3] "" Motor_Hybrid_MQB + +BO_ 175 Waehlhebel_03: 4 Waehlhebel_MQB + SG_ WH_Status_Sperre : 0|3@1+ (1,0) [0|7] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ WH_Initialisierung : 3|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ WH_SensorPos_roh : 4|4@1+ (1,0) [0|15] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ WH_03_BZ : 8|4@1+ (1,0) [0|15] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ WH_SensorPos_roh_inv : 12|4@1+ (1,0) [0|15] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ WH_Testergebnis : 16|8@1+ (1,0) [0|255] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ WH_Test_Aktiv : 24|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ WH_Status : 25|7@1+ (1,0) [0|127] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 178 ESP_19: 8 Gateway_MQB + SG_ ESP_HL_Radgeschw_02 : 0|16@1+ (0.0075,0) [0|491.49] "Unit_KiloMeterPerHour" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_HR_Radgeschw_02 : 16|16@1+ (0.0075,0) [0|491.49] "Unit_KiloMeterPerHour" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_VL_Radgeschw_02 : 32|16@1+ (0.0075,0) [0|491.49] "Unit_KiloMeterPerHour" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_VR_Radgeschw_02 : 48|16@1+ (0.0075,0) [0|491.49] "Unit_KiloMeterPerHour" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 252 ESP_NEW_1: 48 XXX + SG_ XCHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ WHEEL_SPEED_RL : 64|16@1+ (0.0075,0) [0|65535] "" XXX + SG_ WHEEL_SPEED_RR : 80|16@1+ (0.0075,0) [0|65535] "" XXX + SG_ WHEEL_SPEED_FL : 96|16@1+ (0.0075,0) [0|65535] "" XXX + SG_ WHEEL_SPEED_FR : 112|16@1+ (0.0075,0) [0|65535] "" XXX + +BO_ 253 ESP_21: 8 Gateway_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BR_Eingriffsmoment : 12|10@1+ (1,-509) [-509|509] "Unit_NewtoMeter" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_v_Signal : 32|16@1+ (0.01,0) [0|655.32] "Unit_KiloMeterPerHour" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ ASR_Tastung_passiv : 48|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Tastung_passiv : 49|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Systemstatus : 50|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ASR_Schalteingriff : 51|2@1+ (1,0) [0|3] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ ESP_Haltebestaetigung : 53|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_v_Signal : 55|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ABS_Bremsung : 56|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ASR_Anf : 57|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ MSR_Anf : 58|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ EBV_Eingriff : 59|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ EDS_Eingriff : 60|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Eingriff : 61|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_ASP : 62|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Anhaltevorgang_ACC_aktiv : 63|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 257 ESP_02: 8 Gateway_MQB + SG_ ESP_02_CRC : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_02_BZ : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_Gierrate : 12|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ ESP_QBit_Laengsbeschl : 13|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_Querb : 14|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Stillstandsflag : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Querbeschleunigung : 16|8@1+ (0.01,-1.27) [-1.27|1.27] "Unit_ForceOfGravi" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Laengsbeschl : 24|10@1+ (0.03125,-16) [-16|15.90625] "Unit_MeterPerSeconSquar" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Verteil_Wankmom : 34|5@1+ (0.1,-1) [-1|1] "" Vector__XXX + SG_ ESP_QBit_Anf_Vert_Wank : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Gierrate : 40|14@1+ (0.01,0) [0|163.82] "Unit_DegreOfArcPerSecon" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ ESP_VZ_Gierrate : 54|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ ESP_Notbremsanzeige : 55|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ ESP_SpannungsAnf : 56|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_PLA_Abbruch : 57|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ ESP_Status_ESP_PLA : 60|4@1+ (1,0) [0|15] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 258 ESP_NEW_2: 48 XXX + SG_ LATERAL_ACCEL : 16|8@1+ (1,0) [0|255] "" XXX + SG_ LONGITUDINAL_ACCEL : 24|8@1- (1,0) [0|255] "" XXX + SG_ YAW_RATE : 40|14@1+ (1,0) [0|16383] "" XXX + SG_ YAW_RATE_SIGN : 54|1@1+ (1,0) [0|1] "" XXX + +BO_ 260 EPB_01: 8 Gateway_MQB + SG_ EPB_01_CRC : 0|8@1+ (1,0) [0|255] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ EPB_01_BZ : 8|4@1+ (1,0) [0|15] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ EPB_QBit_Laengsbeschleunigung : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EPB_QBit_Pedalweg_Kuppl : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EPB_BCM2_Motor_Wakeup : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EPB_Freig_Verzoeg_Anf : 15|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ EPB_Verzoeg_Anf : 16|8@1+ (0.048,-7.968) [-7.968|4.224] "Unit_MeterPerSeconSquar" Vector__XXX + SG_ EPB_Laengsbeschleunigung : 24|8@1+ (1,-128) [-128|126] "Unit_PerCentOfForceOfGravi" Vector__XXX + SG_ EPB_Pedalweg_Kuppl : 32|8@1+ (0.4,0) [8|92] "Unit_PerCent" Vector__XXX + SG_ EPB_Anfahrwunsch_erkannt : 48|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EPB_DAA_Randbed_erf : 49|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ EPB_Fehlerstatus : 50|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ EPB_Schalterposition : 52|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ EPB_QBit_Schalterpos : 54|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ EPB_Konsistenz_ACC : 55|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EPB_Spannkraft : 56|5@1+ (1,0) [0|29] "Unit_KiloNewto" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ EPB_Status : 61|2@1+ (1,0) [0|3] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 262 ESP_05: 8 Gateway_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_Bremsdruck : 12|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_Fahrer_bremst : 13|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Schwelle_Unterdruck : 14|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Bremsdruck : 16|10@1+ (0.3,-30) [-30|276.6] "Unit_Bar" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Fahrer_bremst : 26|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Verz_TSK_aktiv : 27|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Lenkeingriff_ADS : 28|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Konsistenz_TSK : 29|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Bremsruck_AWV2 : 30|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Konsistenz_AWV2 : 31|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ECD_Fehler : 32|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ECD_nicht_verfuegbar : 33|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Status_Bremsentemp : 34|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Autohold_Standby : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_HDC_Standby : 36|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ ESP_HBA_aktiv : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Prefill_ausgeloest : 38|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Rueckwaertsfahrt_erkannt : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Status_Anfahrhilfe : 40|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_HDC_aktiv : 41|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ ESP_StartStopp_Info : 42|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ ESP_Eingr_HL : 44|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Eingr_HR : 45|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Eingr_VL : 46|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Eingr_VR : 47|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_BKV_Unterdruck : 48|8@1+ (4,0) [0|1012] "Unit_MilliBar" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Autohold_aktiv : 56|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_FStatus_Anfahrhilfe : 57|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ ESP_Verz_EPB_aktiv : 58|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ECD_Bremslicht : 59|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Verzoeg_EPB_verf : 60|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Status_Bremsdruck : 61|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Anforderung_EPB : 62|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 263 Motor_04: 8 Motor_Diesel_MQB + SG_ MO_Istgang : 8|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ MO_Sollgang : 12|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ MO_Oeldruck : 16|8@1+ (0.04,0) [0|10] "Unit_Bar" Gateway_MQB + SG_ MO_Anzeigedrehz : 24|12@1+ (3,0) [0|12282] "Unit_MinutInver" Gateway_MQB + SG_ MO_Schaltempf_verfbar : 38|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Ladedruck : 39|9@1+ (0.01,0) [0|5.1] "Unit_Bar" Gateway_MQB + SG_ MO_KVS : 48|15@1+ (1,0) [0|32767] "Unit_MicroLiter" Gateway_MQB + SG_ MO_KVS_Ueberlauf : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 264 Fahrwerk_01: 8 XXX + SG_ Fahrwerk_01_CRC : 0|8@1+ (1,0) [0|255] "" XXX + SG_ Fahrwerk_01_BZ : 8|4@1+ (1,0) [0|15] "" XXX + +BO_ 267 MOTOR_NEW_1: 32 XXX + SG_ XCHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ ACCEL_PEDAL : 12|8@1+ (0.4,0) [0|255] "" XXX + SG_ TSK_STATUS : 88|3@1+ (1,0) [0|7] "" XXX + +BO_ 278 ESP_10: 8 Gateway_MQB + SG_ ESP_10_CRC : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_10_BZ : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_Wegimpuls_VL : 12|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_Wegimpuls_VR : 13|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_Wegimpuls_HL : 14|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_QBit_Wegimpuls_HR : 15|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Wegimpuls_VL : 16|10@1+ (1,0) [0|1000] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Wegimpuls_VR : 26|10@1+ (1,0) [0|1000] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Wegimpuls_HL : 36|10@1+ (1,0) [0|1000] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Wegimpuls_HR : 46|10@1+ (1,0) [0|1000] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_VL_Fahrtrichtung : 56|2@1+ (1,0) [0|3] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_VR_Fahrtrichtung : 58|2@1+ (1,0) [0|3] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_HL_Fahrtrichtung : 60|2@1+ (1,0) [0|3] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_HR_Fahrtrichtung : 62|2@1+ (1,0) [0|3] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 279 ACC_10: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ AWV1_Anf_Prefill : 16|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_CM_Info : 17|1@1+ (1,0) [0|1] "" XXX + SG_ AWV2_Freigabe : 18|1@1+ (1,0) [0|1] "" XXX + SG_ AWV1_HBA_Param : 19|2@1+ (1,0) [0|3] "" XXX + SG_ AWV2_Ruckprofil : 21|3@1+ (1,0) [0|7] "" XXX + SG_ AWV2_Priowarnung : 24|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_CM_Anforderung : 25|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_Info_Teilbremsung : 26|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_Notfallblinken : 27|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_Teilbremsung_Freigabe : 28|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_Zielbrems_Teilbrems_Verz_Anf : 29|10@1+ (0.024,-20.016) [-20.016|4.536] "Unit_MeterPerSeconSquar" XXX + SG_ ANB_Zielbremsung_Freigabe : 39|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_Vorstufe : 40|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_Halten : 41|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_CityANB_Auspraegung : 42|1@1+ (1,0) [0|1] "" XXX + SG_ PCF_Freigabe : 43|1@1+ (1,0) [0|1] "" XXX + SG_ AWV1_ECD_Anlauf : 44|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_AWA_VZ_Anf_Lenkmomoffset : 46|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_AWA_Anf_Lenkmomoffset : 47|9@1+ (0.01,0) [0|5.11] "Unit_NewtoMeter" XXX + SG_ PCF_Time_to_collision : 56|8@1+ (0.01,0) [0|2.5] "Unit_Secon" XXX + +BO_ 286 VehicleSpeed: 8 XXX + SG_ VehicleSpeed_CRC : 0|8@1+ (1,0) [0|255] "" XXX + SG_ VehicleSpeed_BZ : 8|4@1+ (1,0) [0|15] "" XXX + SG_ Speed : 52|12@1+ (0.125,0) [0|1] "" XXX + +BO_ 288 TSK_06: 8 Motor_Diesel_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_Radbremsmom : 12|12@1+ (8,0) [0|32760] "Unit_NewtoMeter" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_Status : 24|3@1+ (1,0) [0|7] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_v_Begrenzung_aktiv : 27|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_Standby_Anf_ESP : 28|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ TSK_Freig_Verzoeg_Anf : 30|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_Limiter_ausgewaehlt : 31|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_ax_Getriebe_02 : 48|9@1+ (0.024,-2.016) [-2.016|10.224] "Unit_MeterPerSeconSquar" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_Zwangszusch_ESP : 57|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ TSK_zul_Regelabw : 58|6@1+ (0.024,0) [0|1.512] "Unit_MeterPerSeconSquar" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 289 Motor_20: 8 Motor_Diesel_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|255] "" XXX + SG_ MO_Fahrpedalrohwert_01 : 12|8@1+ (0.4,0) [0|101.6] "Unit_PerCent" Airbag_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_QBit_Fahrpedalwerte_01 : 20|1@1+ (1,0) [0|1] "" Airbag_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Fahrpedalgradient : 21|8@1+ (25,0) [0|6350] "Unit_PerCentPerSecon" Airbag_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Sig_Fahrpedalgradient : 29|1@1+ (1,0) [0|1] "" Airbag_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_rel_Saugrohrdruck : 30|6@1+ (18,0) [0|1116] "Unit_MilliBar" Gateway_MQB + SG_ MO_rel_Saugrohrdruck_gem_err : 36|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Moment_im_Leerlauf : 37|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Schubabschaltung : 38|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Solldrehz_Leerlauf : 40|8@1+ (10,0) [0|2540] "Unit_MinutInver" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 290 ACC_06: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ ACC_limitierte_Anfahrdyn : 12|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_nachtr_Stopp_Anf : 13|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_DynErhoehung : 14|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Freilaufstrategie_TSK : 15|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_zul_Regelabw_unten : 16|6@1+ (0.024,0) [0|1.512] "Unit_MeterPerSeconSquar" XXX + SG_ ACC_StartStopp_Info : 22|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Sollbeschleunigung_02 : 24|11@1+ (0.005,-7.22) [-7.22|3.005] "Unit_MeterPerSeconSquar" XXX + SG_ ACC_zul_Regelabw_oben : 35|5@1+ (0.0625,0) [0|1.9375] "Unit_MeterPerSeconSquar" XXX + SG_ ACC_neg_Sollbeschl_Grad_02 : 40|8@1+ (0.05,0) [0|12.75] "Unit_MeterPerCubicSecon" XXX + SG_ ACC_pos_Sollbeschl_Grad_02 : 48|8@1+ (0.05,0) [0|12.75] "Unit_MeterPerCubicSecon" XXX + SG_ ACC_Anfahren : 56|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Anhalten : 57|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Typ : 58|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Status_ACC : 60|3@1+ (1,0) [0|7] "" XXX + SG_ ACC_Minimale_Bremsung : 63|1@1+ (1,0) [0|1] "" XXX + +BO_ 294 HCA_01: 8 Frontsensorik + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ HCA_01_Vib_Freq : 12|4@1+ (1,15) [15|30] "Unit_Hertz" Vector__XXX + SG_ HCA_01_LM_Offset : 16|9@1+ (1,0) [0|511] "Unit_centiNewtoMeter" Vector__XXX + SG_ EA_ACC_Sollstatus : 25|2@1+ (1,0) [0|3] "" Frontradar + SG_ EA_Ruckprofil : 27|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ HCA_01_Sendestatus : 30|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ HCA_01_LM_OffSign : 31|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ HCA_01_Status_HCA : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ HCA_01_Vib_Amp : 36|4@1+ (0.2,0) [0|3] "Unit_NewtoMeter" Vector__XXX + SG_ EA_Ruckfreigabe : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EA_ACC_Wunschgeschwindigkeit : 41|10@1+ (0.32,0) [0|327.04] "Unit_KiloMeterPerHour" Frontradar + +BO_ 296 Getriebe_06: 3 Getriebe_DQ_Hybrid_MQB + SG_ GE_WH_Sperre : 0|1@1+ (1,0) [0|1] "" Waehlhebel_MQB + SG_ GE_Ausleuchtungsmode : 1|1@1+ (1,0) [0|1] "" Waehlhebel_MQB + SG_ GE_Test_Freigabe : 2|1@1+ (1,0) [0|1] "" Waehlhebel_MQB + SG_ GE_Ist_Fahrstufe : 4|4@1+ (1,0) [0|15] "" Waehlhebel_MQB + SG_ GE_Testparameter_1 : 8|8@1+ (1,0) [0|255] "" Waehlhebel_MQB + SG_ GE_Testparameter_2 : 16|8@1+ (1,0) [0|255] "" Waehlhebel_MQB + +BO_ 299 GRA_ACC_01: 8 Gateway_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Hauptschalter : 12|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Abbrechen : 13|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Typ_Hauptschalter : 14|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Limiter : 15|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Tip_Setzen : 16|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Tip_Hoch : 17|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Tip_Runter : 18|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Tip_Wiederaufnahme : 19|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Verstellung_Zeitluecke : 20|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Codierung : 22|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Fehler : 24|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Typ468 : 25|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_Tip_Stufe_2 : 27|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GRA_ButtonTypeInfo : 28|2@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ MAYBE_TRAVEL_ASSIST : 30|1@1+ (1,0) [0|1] "" XXX + +BO_ 301 Getriebe_13: 8 Getriebe_DQ_Hybrid_MQB + SG_ Getriebe_13_CRC : 0|8@1+ (1,0) [0|255] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ Getriebe_13_BZ : 8|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_StartStopp_Info : 12|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ GE_Langfr_Schutzmom_02 : 14|9@1+ (1,0) [0|509] "Unit_NewtoMeter" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Eingangsdrehz : 48|14@1+ (1,0) [0|16381] "Unit_MinutInver" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Notlauf : 62|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Freig_Langfr_Schutzmom : 63|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 302 ACC_07: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ ACC_Anhalteweg : 12|11@1+ (0.01,0) [0|20.45] "Unit_Meter" XXX + SG_ ACC_Anhalten : 23|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Boost_Anf : 24|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Freilauf_Anf : 25|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Freilauf_Info : 26|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Anforderung_HMS : 28|3@1+ (1,0) [0|7] "" XXX + SG_ ACC_Anfahren : 31|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Folgebeschl : 32|8@1+ (0.03,-4.6) [-4.6|2.99] "Unit_MeterPerSeconSquar" XXX + SG_ ACC_Sollbeschleunigung_02 : 53|11@1+ (0.005,-7.22) [-7.22|3.005] "Unit_MeterPerSeconSquar" XXX + +BO_ 313 ESP_NEW_3: 32 XXX + SG_ XCHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ BRAKE_PRESSED_1 : 16|1@1+ (1,0) [0|1] "" XXX + SG_ BRAKE_PRESSED_2 : 27|1@1+ (1,0) [0|1] "" XXX + SG_ BRAKE_PRESSED_3 : 48|1@1+ (1,0) [0|1] "" XXX + SG_ BRAKE_PRESSURE : 76|10@1+ (1,0) [0|1023] "" XXX + +BO_ 317 MOTOR_NEW_2: 32 XXX + SG_ XCHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_1 : 36|1@1+ (1,0) [0|1] "" XXX + SG_ UNKNOWN : 76|10@1+ (1,0) [0|1023] "" XXX + +BO_ 333 ACC_NEW_1: 32 XXX + SG_ NEW_SIGNAL_1 : 24|12@1+ (1,0) [0|4095] "" XXX + SG_ NEW_SIGNAL_2 : 48|8@1+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_3 : 248|8@1+ (1,0) [0|255] "" XXX + +BO_ 387 CAMERA_NEW_3_HF: 64 XXX + SG_ NEW_SIGNAL_1 : 28|12@1+ (1,0) [0|15] "" XXX + +BO_ 391 EV_Gearshift: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ RegenBrakingMode : 12|2@1+ (1,0) [0|3] "" XXX + SG_ GearPosition : 16|4@1+ (1,0) [0|255] "" XXX + +BO_ 418 ESP_15: 8 XXX + SG_ ESP_15_CRC : 0|8@1+ (1,0) [0|255] "" XXX + SG_ ESP_15_BZ : 8|4@1+ (1,0) [0|15] "" XXX + +BO_ 420 CAMERA_NEW_11: 8 XXX + +BO_ 427 ESP_33: 8 XXX + SG_ ESP_33_CRC : 0|8@1+ (1,0) [0|255] "" XXX + SG_ ESP_33_BZ : 8|4@1+ (1,0) [0|15] "" XXX + +BO_ 496 CAMERA_NEW_10: 8 XXX + +BO_ 519 CAMERA_NEW_1_HF: 64 XXX + SG_ NEW_SIGNAL_2 : 36|11@1+ (1,0) [0|2047] "" XXX + SG_ NEW_SIGNAL_1 : 48|12@1+ (1,0) [0|4095] "" XXX + +BO_ 564 CAMERA_NEW_2_HF: 64 XXX + +BO_ 589 NEW_MSG_24D: 64 XXX + SG_ NEW_SIGNAL_1 : 24|12@1+ (1,0) [0|4095] "" XXX + +BO_ 619 CAMERA_NEW_5: 8 XXX + +BO_ 679 ACC_13: 8 XXX + SG_ ACC_Regelgeschw : 12|10@1+ (0.32,0) [0|327.04] "Unit_KiloMeterPerHour" XXX + SG_ ACC_Einheit_maxSetzgeschw : 22|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_maxSetzgeschw : 23|9@1+ (1,0) [0|510] "" XXX + SG_ ACC_minRegelgeschw : 32|8@1+ (0.32,0) [0|81.28] "Unit_KiloMeterPerHour" XXX + SG_ ACC_maxRegelgeschw : 40|8@1+ (0.32,0) [0|81.28] "Unit_KiloMeterPerHour" XXX + SG_ ACC_Tempolimitassistent : 48|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Kurvenassistent : 52|3@1+ (1,0) [0|7] "" XXX + SG_ ACC_RUV : 56|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Tachokranz : 58|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Typ_Tachokranz_unten : 59|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_ENG_Texte : 60|2@1+ (1,0) [0|3] "" XXX + +BO_ 681 ACC_15: 8 XXX + SG_ AWV_Warnung : 16|3@1+ (1,0) [0|7] "" XXX + SG_ AWV_Texte : 24|3@1+ (1,0) [0|7] "" XXX + SG_ AWV_Status_Anzeige : 32|2@1+ (1,0) [0|3] "" XXX + SG_ AWV_Einstellung_System_FSG : 34|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_Einstellung_Warnung_FSG : 36|3@1+ (1,0) [0|7] "" XXX + SG_ AWV_Warnlevel : 58|6@1+ (1,0) [0|63] "" XXX + +BO_ 695 RCTA_01: 8 XXX + SG_ RCTA_01_CRC : 0|8@1+ (1,0) [0|255] "" XXX + SG_ RCTA_01_BZ : 8|4@1+ (1,0) [0|15] "" XXX + +BO_ 768 ACC_NEW_2: 48 XXX + SG_ SET_SPEED : 76|10@1+ (0.32,0) [0|163.51] "kmh" XXX + SG_ NEW_SIGNAL_2 : 86|10@1+ (1,0) [0|1023] "" XXX + SG_ NEW_SIGNAL_3 : 96|8@1+ (1,0) [0|255] "" XXX + +BO_ 771 HCA_NEW: 24 XXX + SG_ ENABLED_1 : 13|2@1+ (1,0) [0|3] "" XXX + SG_ SET_ME_0X54 : 16|7@1+ (1,0) [0|127] "" XXX + SG_ ASSIST_TORQUE : 24|10@1+ (1,0) [0|1023] "" XXX + SG_ ASSIST_DIRECTION : 39|1@1+ (1,0) [0|1] "" XXX + SG_ ENABLED_2 : 66|1@1+ (1,0) [0|1] "" XXX + +BO_ 779 Kombi_01: 8 Gateway_MQB + SG_ KBI_ABS_Lampe : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_ESP_Lampe : 1|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_BKL_Lampe : 2|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Airbag_Lampe : 3|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ KBI_SILA_gueltig : 4|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ KBI_Lenkung_Lampe : 5|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Vorglueh_System_Lampe : 6|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB + SG_ KBI_NV_in_Anzeige : 7|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ Kombi_01_BZ : 8|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_Anzeigestatus_ACC : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Anzeigestatus_GRA : 13|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_Oeldruck_Schalter : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Tankwarnung : 16|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_MFA_v_Einheit_01 : 17|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_im_Stellgliedtest : 18|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ KBI_Anzeigefehler_LDW : 19|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ KBI_Variante_USA : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Oeldruckwarnung : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Handbremse : 23|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ KBI_V_Digital : 24|9@1+ (1,0) [0|511] "" Vector__XXX + SG_ KBI_PLA_in_Anzeige : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Anzeigefehler_NV : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Anzeigestatus_LIM : 35|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_angez_Geschw : 48|10@1+ (0.32,0) [0|325.12] "Unit_KiloMeterPerHour" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_Einheit_Tacho : 58|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_Konsistenz_ACC : 59|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Fehler_Anzeige_ACC : 60|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Anzeigefehler_SWA : 61|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 780 ACC_02: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ ACC_Wunschgeschw_02 : 12|10@1+ (0.32,0) [0|327.04] "Unit_KiloMeterPerHour" XXX + SG_ ACC_Status_Prim_Anz : 22|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Abstandsindex : 24|10@1+ (1,0) [1|1021] "" XXX + SG_ ACC_Akustik_02 : 34|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Warnung_Verkehrszeichen_1 : 36|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Gesetzte_Zeitluecke : 37|3@1+ (1,0) [0|7] "" XXX + SG_ ACC_Optischer_Fahrerhinweis : 40|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Typ_Tachokranz : 41|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Anzeige_Zeitluecke : 42|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Tachokranz : 43|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Display_Prio : 44|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Relevantes_Objekt : 46|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Texte_Primaeranz : 48|7@1+ (1,0) [0|127] "" XXX + SG_ ACC_Wunschgeschw_erreicht : 55|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Typ_Tachokranz_unten : 60|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Status_Anzeige : 61|3@1+ (1,0) [0|7] "" XXX + +BO_ 783 SWA_01: 8 Gateway_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ SWA_Anzeigen : 12|4@1+ (1,0) [0|15] "" Kombi_D4 + SG_ SWA_Blindheit_erkannt : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_rel_Nichtverf : 17|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_rel_Fehler : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Sta_aktiv : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Sta_passiv : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Standziele_li : 24|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Kolonne_li : 25|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Infostufe_SWA_li : 26|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Warnung_SWA_li : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Kolonne_mi : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Standziele_re : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Kolonne_re : 41|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Infostufe_SWA_re : 42|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Warnung_SWA_re : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SWA_Gischtzaehler : 48|7@1+ (1,0) [0|100] "Unit_PerCent" Vector__XXX + SG_ SWA_KD_Fehler : 59|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 792 Kamera_Status: 8 XXX + +BO_ 798 TSK_07: 8 Motor_Diesel_MQB + SG_ TSK_07_CRC : 0|8@1+ (1,0) [0|255] "" Gateway_MQB + SG_ TSK_07_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ TSK_Wunschgeschw : 12|10@1+ (0.32,0) [0|326.72] "Unit_KiloMeterPerHour" Gateway_MQB + SG_ TSK_Texte_Primaeranz : 48|5@1+ (1,0) [0|31] "" Gateway_MQB + SG_ TSK_Limiter_Anzeige : 55|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ TSK_Status_Anzeige : 61|3@1+ (1,0) [0|7] "" Gateway_MQB + +BO_ 804 ACC_04: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ ACC_Texte_Sekundaeranz : 12|4@1+ (1,0) [0|15] "" XXX + SG_ ACC_Texte_Zusatzanz : 16|6@1+ (1,0) [0|63] "" XXX + SG_ ACC_Status_Zusatzanz : 22|5@1+ (1,0) [0|31] "" XXX + SG_ ACC_Texte : 27|5@1+ (1,0) [0|31] "" XXX + SG_ ACC_Texte_braking_guard : 32|3@1+ (1,0) [0|7] "" XXX + SG_ ACC_Warnhinweis : 35|1@1+ (1,0) [0|1] "" XXX + SG_ ACC_Zeitluecke_Abstandswarner : 36|6@1+ (0.1,0) [0|6] "Unit_Secon" XXX + SG_ ACC_Abstand_Abstandswarner : 42|9@1+ (1,0) [0|508] "" XXX + SG_ ACC_Tempolimit : 51|5@1+ (1,0) [0|31] "" XXX + SG_ ACC_Charisma_FahrPr : 56|4@1+ (1,0) [0|15] "" XXX + SG_ ACC_Charisma_Status : 60|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_Texte_Abstandswarner : 62|2@1+ (1,0) [0|3] "" XXX + +BO_ 811 Motor_Hybrid_02: 8 Motor_Hybrid_MQB + SG_ MO_HYB_E_Faktor : 12|4@1+ (1,0) [0|15] "" Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_Drehzahl_VM : 16|16@1+ (0.25,0) [0|16256] "Unit_MinutInver" Getriebe_DQ_Hybrid_MQB + SG_ MO_HYB_LowSpeedModus : 32|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB + +BO_ 812 Motor_17: 8 Motor_Diesel_MQB + SG_ MO_Prio_MAX_Wunschdrehzahl : 12|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Prio_MIN_Wunschdrehzahl : 13|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Luftpfad_aktiv : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ MO_v_Begrenz_Aktivierbar : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ MO_Drehzahlbeeinflussung : 16|8@1+ (0.39,0) [0|99.45] "Unit_PerCent" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_MIN_Wunschdrehzahl : 24|8@1+ (25,0) [0|6350] "Unit_MinutInver" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_MAX_Wunschdrehzahl : 32|9@1+ (25,0) [0|12750] "Unit_MinutInver" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Charisma_FahrPr : 41|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ MO_Charisma_Status : 45|2@1+ (1,0) [0|3] "" Gateway_MQB + +BO_ 869 BEM_05: 8 Gateway_MQB + SG_ BEM_P_Generator : 16|8@1+ (50,0) [0|12700] "Unit_Watt" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BEM_n_LLA : 24|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BEM_01_Abschaltstufen : 26|3@1+ (1,0) [0|7] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BEM_Anf_KL : 29|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BEM_StartStopp_Info : 30|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ BEM_DFM : 32|5@1+ (3.225,0.025) [0.025|100] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BEM_EMLIN_ungueltig : 37|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BEM_Batt_Ab : 38|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BEM_Segel_Info : 48|2@1+ (1,0) [0|3] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BEM_HYB_DC_uSollLV : 50|6@1+ (0.1,10.6) [10.6|16] "Unit_Volt" LEH_MQB + SG_ BEM_HYB_DC_uMinLV : 56|8@1+ (0.1,0) [0|25.3] "Unit_Volt" LEH_MQB + +BO_ 870 Blinkmodi_02: 8 XXX + SG_ Hazard_Switch : 20|1@1+ (1,0) [0|1] "" XXX + SG_ Comfort_Signal_Left : 23|1@1+ (1,0) [0|1] "" XXX + SG_ Comfort_Signal_Right : 24|1@1+ (1,0) [0|1] "" XXX + SG_ Left_Turn_Exterior_Bulb_1 : 25|1@1+ (1,0) [0|1] "" XXX + SG_ Right_Turn_Exterior_Bulb_1 : 26|1@1+ (1,0) [0|1] "" XXX + SG_ Left_Turn_Exterior_Bulb_2 : 27|1@1+ (1,0) [0|1] "" XXX + SG_ Right_Turn_Exterior_Bulb_2 : 28|1@1+ (1,0) [0|1] "" XXX + SG_ Fast_Send_Rate_Active : 37|1@1+ (1,0) [0|1] "" XXX + +BO_ 873 CAMERA_NEW_4: 8 XXX + +BO_ 901 Charisma_01: 8 Gateway_MQB + SG_ CHA_Ziel_FahrPr_ALR : 0|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_ESP : 4|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_FL : 8|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Fahrer_Umschaltung : 14|1@1+ (1,0) [0|1] "" Airbag_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ CHA_Ziel_FahrPr_MO : 16|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ CHA_Ziel_FahrPr_GE : 20|4@1+ (1,0) [0|15] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ CHA_Ziel_FahrPr_ST : 24|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_SCU : 28|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_DR : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_QS : 36|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_AFS : 40|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_RGS : 44|4@1+ (1,0) [0|15] "" Airbag_MQB + SG_ CHA_Ziel_FahrPr_EPS : 48|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_ACC : 52|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_SAK : 56|4@1+ (1,0) [0|15] "" SAK_MQB + SG_ CHA_Ziel_FahrPr_MStSt : 60|4@1+ (1,0) [0|15] "" Vector__XXX + +BO_ 913 OBD_01: 8 Motor_Diesel_MQB + SG_ OBD_Calc_Load_Val : 0|8@1+ (0.39215686275,0) [0|100] "Unit_PerCent" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ OBD_Eng_Cool_Temp : 8|8@1+ (1,-40) [-40|215] "Unit_DegreCelsi" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ OBD_Abs_Throttle_Pos : 16|8@1+ (0.39215686275,0) [0|100] "Unit_PerCent" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ OBD_Abs_Load_Val : 24|16@1+ (0.39215686275,0) [0|25700] "Unit_PerCent" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ OBD_Abs_Pedal_Pos : 40|8@1+ (0.39215686275,0) [0|100] "Unit_PerCent" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ OBD_Kaltstart_Denominator : 59|1@1+ (1,0) [0|1] "" BMS_MQB,LEH_MQB + SG_ OBD_Minimum_Trip : 60|1@1+ (1,0) [0|1] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ OBD_Driving_Cycle : 61|1@1+ (1,0) [0|1] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ OBD_Warm_Up_Cycle : 62|1@1+ (1,0) [0|1] "" BMS_MQB,Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ OBD_Normed_Trip : 63|1@1+ (1,0) [0|1] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + +BO_ 914 ESP_07: 8 Gateway_MQB + SG_ ESP_07_CRC : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_07_BZ : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_ACC_LDE : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Quattro_Antrieb : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Codierung_ADS : 14|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ ESP_RTA_HL : 16|8@1+ (0.048828125,-6.20117) [-6.20117|6.152345625] "Unit_PerCent" Vector__XXX + SG_ ESP_RTA_HR : 24|8@1+ (0.048828125,-6.20117) [-6.20117|6.152345625] "Unit_PerCent" Vector__XXX + SG_ ESP_RTA_VR : 32|8@1+ (0.048828125,-6.20117) [-6.20117|6.152345625] "Unit_PerCent" Vector__XXX + SG_ OBD_Fehler_Radsensor_HL : 40|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_Fehler_Radsensor_HR : 44|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_Fehler_Radsensor_VL : 48|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_Fehler_Radsensor_VR : 52|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ESP_Qualifizierung_Antriebsart : 56|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Offroad_Modus : 57|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_MKB_ausloesbar : 58|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ ESP_MKB_Status : 59|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ ESP_CM_Variante : 60|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_OBD_Status : 61|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 916 WBA_03: 8 Getriebe_DQ_Hybrid_MQB + SG_ WBA_03_CRC : 0|8@1+ (1,0) [0|255] "" Gateway_MQB + SG_ WBA_03_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ WBA_Fahrstufe_02 : 12|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ WBA_ZielFahrstufe : 16|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ WBA_GE_Warnung_02 : 20|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ WBA_eing_Gang_02 : 24|4@1+ (1,0) [0|15] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Otto_MQB + SG_ WBA_GE_Texte : 28|3@1+ (1,0) [0|7] "" Gateway_MQB + SG_ WBA_Segeln_aktiv : 31|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WBA_Schaltschema : 32|5@1+ (1,0) [0|31] "" Gateway_MQB + +BO_ 917 LWR_AFS_01: 8 XXX + +BO_ 919 LDW_02: 8 XXX + SG_ LDW_Gong : 12|2@1+ (1,0) [0|3] "" XXX + SG_ LDW_SW_Warnung_links : 14|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_SW_Warnung_rechts : 15|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_Texte : 16|4@1+ (1,0) [0|15] "" XXX + SG_ LDW_Seite_DLCTLC : 20|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_Lernmodus : 21|3@1+ (1,0) [0|7] "" XXX + SG_ LDW_Anlaufsp_VLR : 24|4@1+ (1,0) [0|15] "" XXX + SG_ LDW_Vib_Amp_VLR : 28|4@1+ (1,0) [0|15] "" XXX + SG_ LDW_Anlaufzeit_VLR : 32|4@1+ (1,0) [0|15] "" XXX + SG_ LDW_Lernmodus_rechts : 36|2@1+ (1,0) [0|3] "" XXX + SG_ LDW_Lernmodus_links : 38|2@1+ (1,0) [0|3] "" XXX + SG_ LDW_DLC : 40|8@1+ (0.01,-1.25) [-1.25|1.25] "Unit_Meter" XXX + SG_ LDW_TLC : 48|5@1+ (0.1,0) [0|3] "Unit_Secon" XXX + SG_ LDW_Warnung_links : 56|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_Warnung_rechts : 57|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_Codierinfo_fuer_VLR : 58|2@1+ (1,0) [0|3] "" XXX + SG_ LDW_Frontscheibenheizung_aktiv : 60|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_Status_LED_gelb : 61|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_Status_LED_gruen : 62|1@1+ (1,0) [0|1] "" XXX + SG_ LDW_KD_Fehler : 63|1@1+ (1,0) [0|1] "" XXX + +BO_ 945 DC_Hybrid_01: 8 LEH_MQB + SG_ DC_HYB_iAktLV : 12|10@1+ (1,-511) [-511|510] "Unit_Amper" Gateway_MQB + SG_ DC_HYB_iAktReserveLV : 22|10@1+ (1,-511) [-511|510] "Unit_Amper" Gateway_MQB + SG_ DC_HYB_uAktLV : 32|8@1+ (0.1,0) [0|25.3] "Unit_Volt" Gateway_MQB + SG_ DC_HYB_LangsRegelung : 40|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ DC_HYB_Abregelung_Temperatur : 41|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ DC_HYB_Fehler_RedLeistung : 42|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ DC_HYB_Fehler_intern : 43|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ DC_HYB_Fehler_Spannung : 44|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ DC_HYB_Auslastungsgrad : 56|8@1+ (0.4,0) [0|100] "Unit_PerCent" Gateway_MQB + +BO_ 949 Klima_11: 8 Gateway_MQB + SG_ KL_Drehz_Anh : 0|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KL_Vorwarn_Komp_ein : 1|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KL_AC_Schalter : 2|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KL_Komp_Moment_alt : 3|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KL_Zonen : 4|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KL_Vorwarn_Zuheizer_ein : 6|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KL_Zustand : 7|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KL_Comp_rev_rq : 8|8@1+ (50,0) [0|8600] "Unit_MinutInver" Vector__XXX + SG_ KL_Charisma_FahrPr : 16|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ KL_Charisma_Status : 20|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ KL_Comp_enable : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KL_Last_Kompr : 24|8@1+ (0.25,0) [0|63.5] "Unit_NewtoMeter" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KL_Spannungs_Anf : 32|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ KL_Thermomanagement : 34|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KL_StartStopp_Info : 36|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ KL_Anf_KL : 40|8@1+ (0.4,0) [0|101.6] "Unit_PerCent" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KL_el_Zuheizer_Stufe : 48|3@1+ (1,0) [0|7] "" Motor_Diesel_MQB + +BO_ 958 Motor_14: 8 Motor_Diesel_MQB + SG_ MO_StartStopp_Status : 12|2@1+ (1,0) [0|3] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_StartStopp_Wiederstart : 14|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_StartStopp_Motorstopp : 15|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Freig_Reku : 16|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_Kl_75 : 18|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Kl_50 : 19|1@1+ (1,0) [0|1] "" Gateway_MQB,LEH_MQB + SG_ MO_Gangposition : 20|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ MO_StartStopp_Fahrerwunsch : 24|2@1+ (1,0) [0|3] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_HYB_Fahrbereitschaft : 26|1@1+ (1,0) [0|1] "" BMS_MQB,Gateway_MQB + SG_ MO_Ext_E_Fahrt_aktiv : 27|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Fahrer_bremst : 28|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_QBit_Fahrer_bremst : 29|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_BLS : 30|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Konsistenz_Bremsped : 31|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Timeout_ESP : 32|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Klima_Eingr : 33|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_Aussp_Anlass : 35|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Freig_Anlass : 36|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Kuppl_schalter : 37|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Interlock : 38|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Motor_laeuft : 39|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Kickdown : 40|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Status_Zylabschalt_01 : 41|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_EKlKomLeiRed : 42|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_Handshake_STH : 44|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_BKV_Unterdruckwarnung : 45|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Freigabe_Segeln : 46|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_PTC_Status : 47|3@1+ (1,0) [0|7] "" Gateway_MQB + SG_ MO_QBit_Gangposition : 50|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Signalquelle_Gangposition : 51|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Remotestart_Betrieb : 52|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 960 Klemmen_Status_01: 4 Gateway_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Airbag_MQB,BMS_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_MQB,BMS_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ZAS_Kl_S : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ZAS_Kl_15 : 17|1@1+ (1,0) [0|1] "" Airbag_MQB,BMS_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ ZAS_Kl_X : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ZAS_Kl_50 : 19|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 967 Motor_26: 8 Motor_Diesel_MQB + SG_ MO_HYB_Status_HV_Ladung : 8|3@1+ (1,0) [0|7] "" Gateway_MQB + SG_ WIV_Anzeige_aktiv : 12|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Oelmin_Warn : 13|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Sensorfehler : 14|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Schieflage : 15|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Oelstand : 16|4@1+ (12.5,0) [0|100] "Unit_PerCent" Gateway_MQB + SG_ MO_Zustand_HWP : 20|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ WIV_Oelsystem_aktiv : 24|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_nicht_betriebswarm : 25|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Ueberfuell_Warn : 26|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_laufender_Motor : 27|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_HYB_Text_1 : 28|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_HYB_Text_2 : 29|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_HYB_Text_3 : 30|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_HYB_Text_4 : 31|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Text_Motorstart : 32|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ MO_HYB_Text_5 : 36|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_HYB_Text_6 : 37|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_HYB_Text_7 : 38|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Text_Partikelfil_Reg : 41|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Oelmenge : 43|5@1+ (125,0) [0|3875] "Unit_MilliLiter" Gateway_MQB + SG_ MO_Systemlampe : 48|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_OBD2_Lampe : 49|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Heissleuchte : 50|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Partikel_Lampe : 51|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Winterfahrprog : 52|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ WIV_Oelstand_nicht_vorhanden : 53|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_nachfuellanzeige_ein : 54|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Ueberfuell_deaktiv : 55|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Unterfuell_Warn : 56|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Tankdeckel_Lampe : 57|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Text_Tankdeckelwarn : 58|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ WIV_Oeldr_Warn_Motor : 60|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 968 Getriebe_14: 8 Getriebe_DQ_Hybrid_MQB + SG_ GE_OBD_AbsperrVent : 12|4@1+ (1,0) [0|15] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_amax_moeglich : 16|9@1+ (0.024,-2.016) [-2.016|10.224] "Unit_MeterPerSeconSquar" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Charisma_FahrPr : 25|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ GE_Charisma_Status : 29|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ GE_Verlustmoment : 32|8@1+ (1,0) [0|254] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Freigabe_Verfallsinfo_WFS : 49|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ GE_Codierung_MSG : 50|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ GE_LaunchControl : 51|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ GE_Heizwunsch : 52|2@1+ (1,0) [0|3] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_OBD_Status : 54|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_LFR_Adaption : 55|1@1+ (1,0) [0|1] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ GE_Sumpftemperatur : 56|8@1+ (1,-58) [-58|196] "Unit_DegreCelsi" Gateway_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 981 Licht_Anf_01: 8 XXX + +BO_ 982 Licht_hinten_01: 8 Gateway_MQB + SG_ Licht_hinten_01_BZ : 0|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BCM2_Bremsl_durch_ECD : 5|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ LH_Aussenlicht_def : 7|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Standlicht_H_aktiv : 8|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Parklicht_HL_aktiv : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Parklicht_HR_aktiv : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Bremslicht_H_aktiv : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Nebelschluss_aktiv : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Rueckfahrlicht_aktiv : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Blinker_HL_akt : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Blinker_HR_akt : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Blinker_li_def : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Bremsl_li_def : 17|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Schlusslicht_li_def : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Rueckf_li_def : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Nebel_li_def : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Schluss_Brems_Nebel_li_def : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Schluss_Brems_Nebel_re_def : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Schluss_Brems_li_def : 24|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Schluss_Nebel_li_def : 25|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_SL_BRL_BLK_li_def : 26|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Brems_Blk_li_def : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Blinker_re_def : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Bremsl_re_def : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Schlusslicht_re_def : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Rueckf_re_def : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Nebel_re_def : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Schluss_Brems_re_def : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Schluss_Nebel_re_def : 41|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_SL_BRL_BLK_re_def : 42|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Brems_Blk_re_def : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Kennzl_def : 48|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_3_Bremsl_def : 49|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ LH_Nebel_mi_def : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Rueckf_mi_def : 51|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ LH_Bremsl_li_ges_def : 54|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ LH_Bremsl_re_ges_def : 55|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 984 RGS_VL_01: 8 Airbag_MQB + SG_ RGS_VL_Texte : 12|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ RGS_VL_Charisma_FahrPr : 14|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ RGS_VL_Charisma_Status : 18|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ RGS_VL_aktiv : 21|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ RGS_VL_PC_Aktuator_Sitz : 25|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ RGS_VL_PC_Aktuator_Schiebedach : 26|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ RGS_VL_PC_Aktuator_Fenster : 27|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ RGS_VL_PC_Aktuator_Warnblinken : 28|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ RGS_VL_Precrash_Basis : 32|8@1+ (1,0) [0|255] "" Gateway_MQB + SG_ RGS_VL_Precrash_Front : 40|8@1+ (1,0) [0|255] "" Gateway_MQB + SG_ RGS_VL_Precrash_Rear : 48|8@1+ (1,0) [0|255] "" Gateway_MQB + +BO_ 987 Gateway_72: 8 Gateway_MQB + SG_ BCM_01_alt : 0|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ SMLS_01_alt : 1|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ ZV_02_alt : 2|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ Wischer_01_alt : 3|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ Anhaenger_01_alt : 4|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ Klima_Sensor_02_alt : 5|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ VSG_01_alt : 6|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ Klima_01_alt : 7|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ WFS_01_alt : 8|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ Licht_Anf_01_alt : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ZV_HFS_offen : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ZV_HBFS_offen : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ VS_VD_offen_ver : 22|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ VS_VD_zu_ver : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ZV_BT_offen : 24|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Rueckfahrlicht_Schalter : 25|1@1+ (1,0) [0|1] "" Airbag_MQB + SG_ ZV_FT_offen : 26|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ Wischer_vorne_aktiv : 27|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ AAG_Anhaenger_erkannt : 28|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ BCM1_MH_Schalter : 29|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ZV_HD_offen : 30|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ Waschen_vorne_aktiv : 31|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KL_Thermomanagement : 32|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ WFS_Schluessel_Fahrberecht : 34|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ BCM1_RFahrlicht_Fzg_Anf : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_RFahrlicht_Ahg_Anf : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BH_Fernlicht : 49|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BH_Blinker_li : 50|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ BH_Blinker_re : 51|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ BCM1_OBD_FStatus_ATemp : 52|4@1+ (1,0) [0|15] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BCM1_Aussen_Temp_ungef : 56|8@1+ (0.5,-50) [-50|76] "Unit_DegreCelsi" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 988 Gateway_73: 8 XXX + +BO_ 989 Gateway_74: 8 Gateway_MQB + SG_ LH_EPS_01_alt : 0|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB + SG_ Kessy_04_alt : 1|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ LIN_2_alt : 2|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MFG_01_alt : 3|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ GW_74_va_14 : 4|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ Klima_02_alt : 5|1@1+ (1,0) [0|1] "" BMS_MQB + SG_ Parkhilfe_01_alt : 6|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ ELV_01_alt : 7|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KY_StartStopp_Info : 16|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ PH_StartStopp_Info : 18|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ EPS_Lenkerposition : 20|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB + SG_ ELV_Anf_Klemme_50 : 22|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ MF_StartStopp_Info : 25|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ KL_Geblaesespannung_Soll : 40|8@1+ (0.05,0.5) [2|13] "Unit_Volt" BMS_MQB + SG_ KL_Umluftklappe_Status : 48|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ MFL_Tip_Down : 56|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MFL_Tip_Up : 57|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ LS_Tiptronic_Fehler : 58|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 991 Gateway_76: 8 XXX + +BO_ 997 TSG_FT_02: 8 XXX + SG_ TSG_FT_02_CRC : 0|8@1+ (1,0) [0|255] "" XXX + SG_ TSG_FT_02_BZ : 8|4@1+ (1,0) [0|15] "" XXX + +BO_ 1122 PSD_04: 8 XXX + SG_ PSD_Object_Index : 0|6@1+ (1,0) [0|63] "" XXX + +BO_ 1123 PSD_05: 8 XXX + SG_ PSD_Current_Route_Index : 0|6@1+ (1,0) [0|63] "" XXX + SG_ Route_Distance_Remaining : 8|5@1+ (1,0) [0|31] "" XXX + +BO_ 1124 PSD_06: 8 XXX + +BO_ 1172 STS_01: 8 Gateway_MQB + SG_ STS_01_CRC : 0|8@1+ (1,0) [0|255] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ STS_01_BZ : 8|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ STS_Car_not_under_theft : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Car_under_theft : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Anlassersperre : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Typencodierung : 16|5@1+ (1,0) [0|31] "" Vector__XXX + SG_ STS_LIN_aktiv : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Standlicht : 24|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Fahrlicht : 25|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Alarm_still : 26|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Texte : 27|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ STS_Laderelais : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Summer : 48|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Alarm_Blinker : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Notstart : 51|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Signalhorn : 55|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STS_Leerlaufschaltung : 56|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 1175 Parkhilfe_01: 8 XXX + +BO_ 1312 Airbag_02: 8 Airbag_MQB + SG_ AB_Belegung_VB : 26|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Gurtschloss_FA : 40|2@1+ (1,0) [0|3] "" Gateway_MQB,Motor_Diesel_MQB,Motor_Otto_MQB + SG_ AB_Gurtschloss_BF : 42|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Gurtschloss_Reihe2_FA : 44|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Gurtschloss_Reihe2_MI : 46|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Gurtschloss_Reihe2_BF : 48|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Gurtschloss_Reihe3_FA : 50|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Gurtschloss_Reihe3_MI : 52|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Gurtschloss_Reihe3_BF : 54|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Sitzpos_Sens_FA : 56|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ AB_Sitzpos_Sens_BF : 58|2@1+ (1,0) [0|3] "" Gateway_MQB + +BO_ 1313 STH_01: 8 Gateway_MQB + SG_ STH_Funk_ein : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_Funk_aus : 1|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_Zusatzheizung : 2|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_LED : 3|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ STH_Pumpe_ein : 4|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_Geblaese : 5|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_EKP_Anst : 6|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ STH_Start_folgt : 7|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_Ventiloeffnungszeit : 8|6@1+ (1,0) [0|63] "Unit_Minut" Vector__XXX + SG_ STH_Ventil_Status : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_Waermeeintrag : 16|6@1+ (1,0) [0|63] "" Vector__XXX + SG_ STH_KVS : 24|13@1+ (1,0) [0|8191] "Unit_MilliLiter" Vector__XXX + SG_ STH_Fehlerstatus : 37|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ STH_Heizleistung : 40|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ STH_Wassertemp : 48|8@1+ (0.75,-40) [-40|142.25] "Unit_DegreCelsi" Vector__XXX + SG_ STH_Motorvorwaermung : 59|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ STH_Servicemode : 60|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_war_aktiv : 61|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ STH_KVS_Ueberlauf : 62|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_KD_Fehler : 63|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 1385 HVEM_04: 8 XXX + +BO_ 1413 Systeminfo_01: 8 Gateway_MQB + SG_ SI_Sammel_SG_Fehler : 0|6@1+ (1,0) [0|60] "" Vector__XXX + SG_ SI_Rollenmode : 6|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ SI_QRS_Mode : 8|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ SI_T_Mode : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_NWDF : 10|1@1+ (1,0) [0|1] "" SAK_MQB + SG_ SI_NWDF_gueltig : 11|1@1+ (1,0) [0|1] "" SAK_MQB + SG_ SI_Sammelfehler : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ GW_KD_Fehler : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_01 : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_02 : 17|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_03 : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_04 : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_05 : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_06 : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_07 : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_08 : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_09 : 24|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_10 : 25|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_11 : 26|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_12 : 27|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_13 : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_14 : 29|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SI_BUS_15 : 30|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 1437 Remotestart_FFB: 8 Gateway_MQB + SG_ RSF_Tastencode_1 : 0|8@1+ (1,0) [0|255] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ RSF_Tastencode_2 : 8|8@1+ (1,0) [0|255] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ RSF_Tastencode_Maske : 16|8@1+ (1,0) [0|255] "" Motor_Diesel_MQB,Motor_Otto_MQB + +BO_ 1440 RLS_01: 8 XXX + +BO_ 1520 Dimmung_01: 8 Gateway_MQB + SG_ DI_KL_58xd : 0|8@1+ (1,0) [0|253] "" Airbag_MQB + SG_ DI_KL_58xs : 8|7@1+ (1,0) [0|100] "Unit_PerCent" Vector__XXX + SG_ DI_Display_Nachtdesign : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ DI_KL_58xt : 16|7@1+ (1,0) [0|100] "Unit_PerCent" Vector__XXX + SG_ DI_Fotosensor : 24|16@1+ (1,0) [0|65535] "" Vector__XXX + +BO_ 1528 SAK_01: 8 SAK_MQB + SG_ SAK_Charisma_FahrPr : 16|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ SAK_Charisma_Status : 20|2@1+ (1,0) [0|3] "" Gateway_MQB + +BO_ 1600 Motor_07: 8 Motor_Diesel_MQB + SG_ MO_QBit_Ansaugluft_Temp : 0|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_QBit_Oel_Temp : 1|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_QBit_Kuehlmittel_Temp : 2|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ MO_Stellgliedtest_Soundaktuator : 3|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_HYB_Fehler_HV_Netz : 4|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_aktives_Getriebeheizen : 5|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Absperrventil_oeffnen : 6|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_Ansaugluft_Temp : 8|8@1+ (0.75,-48) [-48|141.75] "Unit_DegreCelsi" Gateway_MQB + SG_ MO_Oel_Temp : 16|8@1+ (1,-60) [-60|192] "Unit_DegreCelsi" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Kuehlmittel_Temp : 24|8@1+ (0.75,-48) [-48|141.75] "Unit_DegreCelsi" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB + SG_ MO_Hoeheninfo : 32|8@1+ (0.00781,0) [0|1.98374] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Kennfeldk : 40|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Versionsinfo : 41|6@1+ (1,0) [0|63] "" Gateway_MQB + SG_ MO_Getriebe_kuehlen : 47|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Mom_Traegheit_02 : 48|5@1+ (0.01,0) [0|0.31] "Unit_KiloGramMeterSquar" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Heizungspumpenansteuerung : 53|4@1+ (10,0) [0|100] "Unit_PerCent" Gateway_MQB + SG_ MO_SpannungsAnf : 57|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Nachlaufzeit_Heizungspumpe : 58|6@1+ (15,0) [0|945] "Unit_Secon" Gateway_MQB + +BO_ 1601 Motor_Code_01: 8 Motor_Diesel_MQB + SG_ Motor_Code_01_CRC : 0|8@1+ (1,0) [0|255] "" Gateway_MQB + SG_ Motor_Code_01_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ MO_Faktor_Momente_02 : 12|2@1+ (1,0) [0|3] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Hybridfahrzeug : 14|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_Code : 16|8@1+ (1,0) [0|255] "" Gateway_MQB,SAK_MQB + SG_ MO_Getriebe_Code : 24|6@1+ (1,0) [0|63] "" Gateway_MQB + SG_ MO_StartStopp_Codiert : 30|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Anzahl_Zyl : 32|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ MO_Kraftstoffart : 36|4@1+ (1,0) [0|15] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Hubraum : 40|7@1+ (0.1,0) [0|12.7] "Unit_Liter" Gateway_MQB + SG_ MO_Ansaugsystem : 47|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_Leistung : 48|9@1+ (1,0) [0|511] "Unit_KiloWatt" Gateway_MQB + SG_ MO_Abgastyp_EOBD : 57|1@1+ (1,0) [0|1] "" BMS_MQB,Gateway_MQB,LEH_MQB + SG_ MO_Abgastyp_OBD : 58|1@1+ (1,0) [0|1] "" BMS_MQB,Gateway_MQB,LEH_MQB + SG_ MO_DPF_verbaut : 59|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ TSK_Codierung : 60|3@1+ (1,0) [0|7] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Einspritzart : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 1602 WIV_01: 8 Motor_Diesel_MQB + SG_ WIV_Verschleissindex : 0|16@1+ (2e-08,0) [0|0.00131068] "" Gateway_MQB + SG_ WIV_Russindex : 16|16@1+ (2e-08,0) [0|0.00131068] "" Gateway_MQB + SG_ WIV_t_min : 32|6@1+ (1,0) [0|63] "Unit_Month" Gateway_MQB + SG_ WIV_t_max : 40|6@1+ (1,0) [0|63] "Unit_Month" Gateway_MQB + SG_ WIV_W_min : 48|7@1+ (1000,0) [0|127000] "Unit_KiloMeter" Gateway_MQB + SG_ WIV_W_max : 56|7@1+ (1000,0) [0|127000] "Unit_KiloMeter" Gateway_MQB + +BO_ 1603 Einheiten_01: 8 Gateway_MQB + SG_ KBI_Einheit_Datum : 0|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ KBI_Einheit_Druck : 2|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ KBI_Einheit_Streckenanz : 4|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB + SG_ KBI_MFA_v_Einheit_02 : 5|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Einheit_Temp : 6|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Einheit_Uhrzeit : 7|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ KBI_Einheit_Verbrauch : 8|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ KBI_Einheit_Volumen : 10|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ KBI_Einheit_Sprache : 16|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 1605 FLA_01: 8 XXX + +BO_ 1607 Motor_09: 8 Motor_Diesel_MQB + SG_ MO_ITM_Kuehlmittel_Temp : 0|8@1+ (0.75,-48) [-45.75|143.25] "Unit_DegreCelsi" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_E85_Sensor : 8|4@1+ (10,0) [0|100] "Unit_PerCent" Gateway_MQB + SG_ SCR_Anz_Motorstarts : 12|4@1+ (1,0) [0|8] "" Gateway_MQB + SG_ SCR_Reichweite : 16|15@1+ (1,0) [0|32766] "" Gateway_MQB + SG_ SCR_Warnstufe_1 : 32|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ SCR_Warnstufe_2 : 33|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ SCR_Text : 34|3@1+ (1,0) [0|7] "" Gateway_MQB + SG_ SCR_Akustik : 37|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_Kraftstofffilter_Wasser : 40|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ SCR_Systemfehler : 41|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ SCR_Inducement_Strategie : 42|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_CO2_Faktor : 44|12@1+ (1,0) [1|4094] "Unit_GramPerLiter" Gateway_MQB + +BO_ 1624 Licht_vorne_01: 8 XXX + +BO_ 1625 Klimakomp_01: 8 Gateway_MQB + SG_ EKL_KD_Fehler : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EKL_Comp_SCI_com_stat : 16|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ EKL_Comp_output_stat : 18|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ EKL_Comp_main_stat : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EKL_Comp_ovld_stat : 21|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ EKL_Comp_Inv_stat : 24|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ EKL_Comp_photo_temp_stat : 30|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ EKL_Comp_photo_temp : 32|8@1+ (1,0) [0|254] "Unit_DegreCelsi" Vector__XXX + SG_ EKL_Comp_current : 40|8@1+ (0.1,0) [0|25.4] "Unit_Amper" Motor_Hybrid_MQB + SG_ EKL_Comp_rev_stat : 48|8@1+ (50,0) [0|8600] "Unit_MinutInver" Vector__XXX + +BO_ 1626 BCM_01: 8 Gateway_MQB + SG_ BCM_Bremsbelag_Sensor : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM_Bremsfluessigkeit_Sensor : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Licht_Warn : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM_Waschwasser_Sensor : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM_Kuehlmittel_Sensor : 16|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ BCM1_Kl_15_HW_erkannt : 17|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM_Eis_Offroad_Taste : 18|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Otto_MQB + SG_ ZZH_Endlage_oben : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ZZH_Endlage_unten : 20|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ZZH_Endlage_unplausibel : 21|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM2_EZS_gedrueckt : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM2_SST_gedrueckt : 23|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM_Hybrid_StartStopp_Taste : 24|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BCM1_Warnblink_Taster : 25|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Valet_Parking_Taster : 26|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM_Remotestart_Betrieb : 27|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ BCM1_HSK_Taster : 28|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Heckrollo_Taster : 29|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_Rueckfahrlicht_Schalter : 30|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BCM1_MH_Schalter : 31|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Otto_MQB + SG_ BCM1_MH_WIV_Schalter : 32|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BCM_Eco_Charisma_Taste : 33|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ BCM_Thermomanagement : 34|2@1+ (1,0) [0|3] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BCM_Thermomanagement_Fehler : 36|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BCM_Thermomanagement_gueltig : 37|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ BCM1_Lichtwarn_Texte : 38|2@1+ (1,0) [0|3] "" Vector__XXX + +BO_ 1628 BMS_Hybrid_01: 8 BMS_MQB + SG_ BMS_HYB_ASV_hinten_Status : 13|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ BMS_HYB_ASV_vorne_Status : 14|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ BMS_HYB_KD_Fehler : 15|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ BMS_HYB_BattFanSpd : 16|4@1+ (10,0) [0|100] "Unit_PerCent" Gateway_MQB + SG_ BMS_HYB_VentilationReq : 20|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ BMS_HYB_Spuelbetrieb_Status : 21|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ BMS_HYB_Kuehlung_Anf : 22|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ BMS_HYB_Temp_vor_Verd : 24|8@1+ (0.5,-40) [-40|86.5] "Unit_DegreCelsi" Gateway_MQB + SG_ BMS_HYB_Temp_nach_Verd : 32|8@1+ (0.5,-40) [-40|86.5] "Unit_DegreCelsi" Gateway_MQB + SG_ BMS_Temperatur : 40|8@1+ (0.5,-40) [-40|86.5] "Unit_DegreCelsi" Gateway_MQB + SG_ BMS_Temperatur_Ansaugluft : 48|8@1+ (0.5,-40) [-40|86.5] "Unit_DegreCelsi" Gateway_MQB + SG_ BMS_IstSpannung_HV : 56|8@1+ (1,100) [100|350] "Unit_Volt" Gateway_MQB + +BO_ 1629 ESP_20: 8 Gateway_MQB + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ BR_Systemart : 12|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ ESP_Zaehnezahl : 16|8@1+ (1,0) [0|255] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ ESP_Charisma_FahrPr : 24|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ ESP_Charisma_Status : 28|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ BR_QBit_Reifenumfang : 51|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ BR_Reifenumfang : 52|12@1+ (1,0) [0|4095] "Unit_MilliMeter" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 1630 OBD_Tankgeber_01: 8 Gateway_MQB + SG_ OBD_TG_F_Status_1 : 0|4@1+ (1,0) [0|15] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_TG_F_Status_2 : 4|4@1+ (1,0) [0|15] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_TG_F_Status_3 : 8|4@1+ (1,0) [0|15] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_TG_F_Status_4 : 12|4@1+ (1,0) [0|15] "" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_TG_Sens_Rohwert_1 : 16|12@1+ (0.5,0) [0|2047.5] "Unit_Ohm" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_TG_Sens_Rohwert_2 : 28|12@1+ (0.5,0) [0|2047.5] "Unit_Ohm" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_TG_Sens_Rohwert_3 : 40|12@1+ (0.5,0) [0|2047.5] "Unit_Ohm" Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ OBD_TG_Sens_Rohwert_4 : 52|12@1+ (0.5,0) [0|2047.5] "Unit_Ohm" Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 1631 Motor_16: 8 Motor_Diesel_MQB + SG_ TSK_QBit_Steigung : 12|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_QBit_Fahrzeugmasse : 13|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_SpannungsAnf_02 : 14|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_DPF_reg : 16|1@1+ (1,0) [0|1] "" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ MO_Heizstrom_EKAT : 17|7@1+ (1,0) [0|126] "Unit_Amper" Gateway_MQB + SG_ MO_Heizstrom_SCR : 24|6@1+ (1,0) [0|62] "Unit_Amper" Gateway_MQB + SG_ TSK_Fahrzeugmasse_02 : 48|8@1+ (32,0) [0|8128] "Unit_KiloGram" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + SG_ TSK_Steigung : 56|8@1+ (0.8,-101.6) [-101.6|101.6] "Unit_PerCent" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 1633 Anhaenger_01: 8 Gateway_MQB + SG_ AAG_BZ : 0|4@1+ (1,0) [0|15] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ AAG_Bremsl_durch_ECD : 5|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ AAG_Anhaenger_abgesteckt : 6|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ AAG_NSL_aktiv : 7|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ AAG_Anhaenger_erkannt : 8|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ AAG_Blinker_H_aktiv : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ AAG_Blinker_HL_def : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ AAG_Blinker_HR_def : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ AAG_Bremslicht_H_def : 12|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ AAG_Schlusslicht_HL_def : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ AAG_Schlusslicht_HR_def : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ AAG_AVS_Fehler_02 : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ AAG_AVS_Stati : 20|4@1+ (1,0) [0|15] "" Vector__XXX + +BO_ 1646 Klima_03: 8 XXX + +BO_ 1648 Motor_18: 8 Motor_Diesel_MQB + SG_ MO_Hybrid_StartStopp_LED : 43|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_Eis_Offroad_LED : 45|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_Anzahl_Abgesch_Zyl : 47|3@1+ (1,0) [0|7] "" Gateway_MQB + SG_ MO_Zylabsch_Texte : 50|2@1+ (1,0) [0|3] "" Gateway_MQB + SG_ MO_E85_BS_Texte : 52|3@1+ (1,0) [0|7] "" Gateway_MQB + SG_ MO_Drehzahl_Warnung : 55|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ MO_obere_Drehzahlgrenze : 56|8@1+ (50,0) [50|12750] "Unit_MinutInver" Gateway_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB + +BO_ 1714 Diagnose_01: 8 Gateway_MQB + SG_ DGN_Verlernzaehler : 0|8@1+ (1,0) [0|254] "" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,SAK_MQB + SG_ KBI_Kilometerstand : 8|20@1+ (1,0) [0|1048573] "Unit_KiloMeter" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ UH_Jahr : 28|7@1+ (1,2000) [2000|2127] "Unit_Year" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ UH_Monat : 35|4@1+ (1,0) [1|12] "Unit_Month" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ UH_Tag : 39|5@1+ (1,0) [1|31] "Unit_Day" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ UH_Stunde : 44|5@1+ (1,0) [0|23] "Unit_Hours" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ UH_Minute : 49|6@1+ (1,0) [0|59] "Unit_Minut" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ UH_Sekunde : 55|6@1+ (1,0) [0|59] "Unit_Secon" Airbag_MQB,BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB,SAK_MQB + SG_ Kombi_02_alt : 62|1@1+ (1,0) [0|1] "" Airbag_MQB,BMS_MQB,LEH_MQB + SG_ Uhrzeit_01_alt : 63|1@1+ (1,0) [0|1] "" Airbag_MQB,BMS_MQB,LEH_MQB + +BO_ 1716 VIN_01: 8 Gateway_MQB + SG_ VIN_01_MUX M : 0|2@1+ (1,0) [0|3] "" Airbag_MQB + SG_ KS_Geheimnis_1 m0 : 8|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ KS_Geheimnis_2 m0 : 16|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ KS_Geheimnis_3 m0 : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ KS_Geheimnis_4 m0 : 32|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ VIN_1 m0 : 40|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_2 m0 : 48|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_3 m0 : 56|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_4 m1 : 8|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_5 m1 : 16|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_6 m1 : 24|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_7 m1 : 32|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_8 m1 : 40|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_9 m1 : 48|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_10 m1 : 56|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_11 m2 : 8|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_12 m2 : 16|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_13 m2 : 24|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_14 m2 : 32|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_15 m2 : 40|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_16 m2 : 48|8@1+ (1,0) [0|255] "" Airbag_MQB + SG_ VIN_17 m2 : 56|8@1+ (1,0) [0|255] "" Airbag_MQB + +BO_ 1719 Kombi_02: 8 Gateway_MQB + SG_ KBI_Kilometerstand : 0|20@1+ (1,0) [0|1048573] "Unit_KiloMeter" Vector__XXX + SG_ KBI_Standzeit_02 : 20|17@1+ (1,0) [0|131068] "Unit_Secon" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_Inhalt_Tank : 40|7@1+ (1,0) [0|125] "Unit_Liter" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_FStatus_Tank : 47|1@1+ (1,0) [0|1] "" Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_QBit_Aussen_Temp_gef : 55|1@1+ (1,0) [0|1] "" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ KBI_Aussen_Temp_gef : 56|8@1+ (0.5,-50) [-50|75] "Unit_DegreCelsi" Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + +BO_ 1720 Kombi_03: 8 XXX + SG_ KBI_Reifenumfang : 0|12@1+ (1,0) [0|4095] "Unit_MilliMeter" XXX + SG_ KBI_Variante_USA : 12|1@1+ (1,0) [0|1] "" XXX + SG_ KBI_Variante : 13|1@1+ (1,0) [0|1] "" XXX + SG_ KBI_BCmE_aktiv : 16|1@1+ (1,0) [0|1] "" XXX + SG_ KBI_Sparhinweis_quittiert : 17|1@1+ (1,0) [0|1] "" XXX + SG_ KBI_Tankfuellstand_Prozent : 18|7@1+ (1,0) [0|100] "Unit_PerCent" XXX + SG_ KBI_Nachtanken_erkannt : 25|1@1+ (1,0) [0|1] "" XXX + SG_ KBI_Tankinhalt_hochaufl : 26|14@1+ (0.01,0) [0|163.81] "Unit_Liter" XXX + SG_ KBI_Max_Tankinhalt : 40|8@1+ (0.5,0) [0|126.5] "" XXX + SG_ KBI_Reifenumfang_Sekundaer : 48|12@1+ (1,0) [0|4095] "Unit_MilliMeter" XXX + +BO_ 316495015 CAMERA_NEW_6: 32 XXX + +BO_ 380196019 CAMERA_NEW_16: 16 XXX + +BO_ 380196036 CAMERA_NEW_18: 8 XXX + +BO_ 389224720 CAMERA_NEW_13: 3 XXX + +BO_ 389226768 CAMERA_NEW_12: 2 XXX + +BO_ 389241616 CAMERA_NEW_14: 5 XXX + +BO_ 401604687 CAMERA_NEW_9: 8 XXX + +BO_ 441800082 CAMERA_NEW_15: 8 XXX + +BO_ 441800100 CAMERA_NEW_8: 64 XXX + +BO_ 441800101 CAMERA_NEW_7: 64 XXX + +BO_ 2549088277 KN_Airbag_01: 8 Airbag_MQB + SG_ Airbag_01_KompSchutz : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ Airbag_01_Nachlauftyp : 4|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ AB_KD_Fehler : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 2549088284 KN_SAK: 8 SAK_MQB + SG_ SAK_KompSchutz : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ SAK_Nachlauftyp : 4|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ SAK_KD_Fehler : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 2549088374 KN_MO_01: 8 Motor_Diesel_MQB + SG_ Motor_KompSchutz : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ Motor_Nachlauftyp : 4|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ MO_KD_Fehler : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 2549088375 KN_Getriebe_01: 8 Getriebe_DQ_Hybrid_MQB + SG_ Getriebe_KompSchutz : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ Getriebe_Nachlauftyp : 4|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ GE_KD_Fehler : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 2549088379 KN_Hybrid_01: 8 BMS_MQB + SG_ Hybrid_KompSchutz : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ Hybrid_Nachlauftyp : 4|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ BMS_HYB_KD_Fehler : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 2549088380 KN_EMotor_01: 8 LEH_MQB + SG_ EMotor_KompSchutz : 0|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EMotor_Nachlauftyp : 4|4@1+ (1,0) [0|15] "" Gateway_MQB + SG_ EM_HYB_KD_Fehler : 63|1@1+ (1,0) [0|1] "" Gateway_MQB + +BO_ 2600468496 NMH_Gateway: 8 Gateway_MQB + SG_ NM_Gateway_SNI : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_Gateway_NM_State : 16|6@1+ (1,0) [0|63] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ NM_Gateway_Car_Wakeup : 22|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_Wakeup : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_Gateway_NM_aktiv_KL15 : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_NM_aktiv_Diagnose : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_NM_aktiv_Tmin : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_ACAN_Aktivitaet : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_FCAN_Aktivitaet : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_KCAN_Aktivitaet : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_ICAN_Aktivitaet : 38|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_DiagCAN_Aktivitaet : 39|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_ECAN_Aktivitaet : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_Energie_LIN_Aktivi000 : 41|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_Bedien_LIN_Aktivitaet : 42|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_EM_Aktivitaet : 43|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_NL_EM : 48|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_NL_Shutdown : 49|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_NL_Spg_Messung : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_NL_Wakeup_Monitor : 51|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Gateway_UDS_CC : 63|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 2600468501 NMH_Airbag_01: 8 Airbag_MQB + SG_ NM_Airbag_01_SNI : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_Airbag_01_NM_State : 16|6@1+ (1,0) [0|63] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ NM_Airbag_01_Car_Wakeup : 22|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ NM_Airbag_01_Wakeup : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_Airbag_01_NM_aktiv_KL15 : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Airbag_01_NM_aktiv_Diagnose : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Airbag_01_NM_aktiv_Tmin : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Airbag_01_UDS_CC : 63|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 2600468598 NMH_MO_01: 8 Motor_Diesel_MQB + SG_ NM_MO_01_SNI : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_MO_01_NM_State : 16|6@1+ (1,0) [0|63] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ NM_MO_01_Car_Wakeup : 22|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ NM_MO_01_Wakeup : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_MO_01_NM_aktiv_KL15 : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NM_aktiv_Diagnose : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NM_aktiv_Tmin : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NM_aktiv_HV_Abschaltung : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NM_aktiv_EKP_Vorlauf : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NM_aktiv_STH_Betrieb : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NL_Kuehlerluefter : 48|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NL_Diagnose : 49|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NL_WFS : 50|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NL_EEPROM : 51|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_NL_Sonstige : 52|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_MO_01_UDS_CC : 63|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 2600468599 NMH_Getriebe_01: 8 Getriebe_DQ_Hybrid_MQB + SG_ NM_Getriebe_01_SNI : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_Getriebe_01_NM_State : 16|6@1+ (1,0) [0|63] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ NM_Getriebe_01_Car_Wakeup : 22|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ NM_Getriebe_01_Wakeup : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_Getriebe_01_NM_aktiv_KL15 : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Getriebe_01_NM_aktiv_Diagnose : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Getriebe_01_NM_aktiv_Tmin : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Getriebe_01_NM_aktiv_v_gr_0 : 35|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Getriebe_01_NM_aktiv_Pos_Erk : 36|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Getriebe_01_NM_aktiv_Umg_Bed : 37|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Getriebe_01_NL_Daten_EEPROM : 48|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Getriebe_01_UDS_CC : 63|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 2600468603 NMH_Hybrid_01: 8 BMS_MQB + SG_ NM_Hybrid_01_SNI : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_Hybrid_01_NM_State : 16|6@1+ (1,0) [0|63] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ NM_Hybrid_01_Car_Wakeup : 22|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ NM_Hybrid_01_Wakeup : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_Hybrid_01_NM_aktiv_KL15 : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Hybrid_01_NM_aktiv_Diagnose : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Hybrid_01_NM_aktiv_Tmin : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Hybrid_01_NL_Daten_EEPROM : 48|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Hybrid_01_NL_Luefter : 49|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_Hybrid_01_UDS_CC : 63|1@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 2600468604 NMH_EMotor_01: 8 LEH_MQB + SG_ NM_EMotor_01_SNI : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_EMotor_01_NM_State : 16|6@1+ (1,0) [0|63] "" BMS_MQB,Getriebe_DQ_Hybrid_MQB,Getriebe_DQ_MQB,LEH_MQB,Motor_Diesel_MQB,Motor_Hybrid_MQB,Motor_Otto_MQB + SG_ NM_EMotor_01_Car_Wakeup : 22|1@1+ (1,0) [0|1] "" Gateway_MQB + SG_ NM_EMotor_01_Wakeup : 24|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ NM_EMotor_01_NM_aktiv_KL15 : 32|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_EMotor_01_NM_aktiv_Diagnose : 33|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_EMotor_01_NM_aktiv_Tmin : 34|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_EMotor_01_NL_Daten_EEPROM : 48|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ NM_EMotor_01_UDS_CC : 63|1@1+ (1,0) [0|1] "" Vector__XXX + +CM_ SG_ 134 LWI_Lenkradwinkel "Steering angle WITH variable ratio effect included"; +CM_ SG_ 159 EPS_Berechneter_LW "Raw steering angle, degrees"; +CM_ SG_ 159 EPS_VZ_BLW "Raw steering angle, direction"; +CM_ SG_ 159 EPS_HCA_Status "Status of Heading Control Assist feature"; +CM_ SG_ 159 EPS_Lenkmoment "Steering input by driver, torque"; +CM_ SG_ 159 EPS_VZ_Lenkmoment "Steering input by driver, direction"; +CM_ SG_ 173 COUNTERXX "Message not renamed to COUNTER because J533 rate-limiting makes it look like messages are being lost"; +CM_ SG_ 294 HCA_01_Vib_Freq "Frequenz der Lenkradvibration"; +CM_ SG_ 294 HCA_01_LM_Offset "Von HCA angefordertes Lenkmoment (Betrag)"; +CM_ SG_ 294 EA_ACC_Sollstatus "Status-Anforderung ACC von Emergency Alert. Statuswechsel bei Flanke. Solange Wert=1, wird EA_ACC_Wunschgeschwindigkeit übernommen. Wert=2 führt zu Zustand ¿ACC_GRA_passiv¿"; +CM_ SG_ 294 EA_Ruckprofil "Emergency Alert Anforderung an ESP, welcher Ruck verwendet werden soll. Eine Umsetzung der Ruckanforderung im ESP erfolgt nur mit gesetztem Bit 'EA_Ruckfreigabe'."; +CM_ SG_ 294 HCA_01_Sendestatus "Gibt den Sendestatus der HCA_01 an (notwendig für IL-Unterstützung)"; +CM_ SG_ 294 HCA_01_LM_OffSign "Vorzeichen des HCA-Lenkmoments"; +CM_ SG_ 294 HCA_01_Status_HCA "Statusinformation vom HCA und Manoevrierassistent für Handshakemechanismus mit der Lenkung"; +CM_ SG_ 294 HCA_01_Vib_Amp "Momentenamplitude der Lenkradvibration"; +CM_ SG_ 294 EA_Ruckfreigabe "Emergency Alert Freigabit für die Warnruck-Anforderung an das ESP"; +CM_ SG_ 294 EA_ACC_Wunschgeschwindigkeit "Emergency Alert Anforderung neue Wunschgeschwindigkeit"; +CM_ SG_ 391 GearPosition "Traditional PRND plus B-mode aggressive regen, B-mode mapped to Drive"; +CM_ SG_ 771 SET_ME_0X54 "Varies but not sure how, may indicate path or curvature"; +CM_ SG_ 870 Hazard_Switch "Four-way flashers active"; +CM_ SG_ 870 Comfort_Signal_Left "Comfort turn signal active, left"; +CM_ SG_ 870 Comfort_Signal_Right "Comfort turn signal active, right"; +CM_ SG_ 870 Left_Turn_Exterior_Bulb_1 "Probably front"; +CM_ SG_ 870 Right_Turn_Exterior_Bulb_1 "Probably front"; +CM_ SG_ 870 Left_Turn_Exterior_Bulb_2 "Probably rear"; +CM_ SG_ 870 Right_Turn_Exterior_Bulb_2 "Probably rear"; +CM_ SG_ 870 Fast_Send_Rate_Active "CAN message send rate"; +CM_ SG_ 919 LDW_DLC "Probable DLC (distance to line crossing)"; +CM_ SG_ 919 LDW_TLC "Probable TLC (time to line crossing)"; +CM_ SG_ 960 ZAS_Kl_15 "Indicates ignition on"; +CM_ SG_ 1720 KBI_Reifenumfang "Mittlerer Radumfang aus der K-Zahl gerechnet in Millimeter. Byte 2 Bit 5,4 reserviert, Byte 2 Bit 3..0 und Byte 1 Bit 7..0; Wertebereich 0..4096 mm"; +CM_ SG_ 1720 KBI_Variante_USA "In diesem Signal wird die HW-Variante des Kombis ausgegeben, ACC plausibilisiert auf dieses Signal hin seine US-Codierung"; +CM_ SG_ 1720 KBI_Variante "Zeigt an ob es sich um ein konventionelles Zeiger-Kombiinstrument handelt oder um eine Volldisplay-Kombiinstrument"; +CM_ SG_ 1720 KBI_BCmE_aktiv "Anzeige BCmE aktiv (BCmE-Screen oder Einsparhinweis in der Anzeige)"; +CM_ SG_ 1720 KBI_Sparhinweis_quittiert "angezeigter Sparhinweis ist quittiert. Signal wird nach zwei Sendebotschaften wieder auf '0' gesetzt."; +CM_ SG_ 1720 KBI_Tankfuellstand_Prozent "Tankfüllstand in %"; +CM_ SG_ 1720 KBI_Nachtanken_erkannt "Statusinformation Nachtankmodus"; +CM_ SG_ 1720 KBI_Tankinhalt_hochaufl "angezeigter Tankinhalt hochauflösend zur Restreichweitenberechnung"; +CM_ SG_ 1720 KBI_Max_Tankinhalt "Mitteilung des maximalen Tankinhalts an das Reichweitenmodul"; +CM_ SG_ 1720 KBI_Reifenumfang_Sekundaer "Fahrzeuge mit unterschiedlichen Reifenumfängen Vorderachse / Hinterachse: + +Primärachse: KBI_Reifenumfang +Sekundärachse: KBI_Reifenumfang_Sekundaer"; +VAL_ 159 EPS_HCA_Status 0 "disabled" 1 "initializing" 2 "fault" 3 "ready" 4 "rejected" 5 "active"; +VAL_ 173 GE_Fahrstufe 5 "P" 6 "R" 7 "N" 8 "D" 9 "S" 10 "E" 13 "T" 14 "T"; +VAL_ 279 AWV1_Anf_Prefill 0 "Prefill_nicht_aktivieren" 1 "Prefill_aktivieren"; +VAL_ 279 ANB_CM_Info 0 "Standard" 1 "Erweitert"; +VAL_ 279 AWV2_Freigabe 0 "keine_Freigabe" 1 "Freigabe"; +VAL_ 279 AWV1_HBA_Param 0 "Defaultparametersatz" 1 "Parametersatz_mit_leicht_erhoehter_Empfindlichkeit" 2 "Parametersatz_mit_erhoehter_Empfindlichkeit" 3 "Parametersatz_mit_hoechster_Empfindlichkeit"; +VAL_ 279 AWV2_Priowarnung 0 "Anzeige_Verlassen_der_Fahrspur_wird_nicht_unterdrueckt" 1 "Anzeige_Verlassen_der_Fahrspur_wird_unterdrueckt"; +VAL_ 279 ANB_CM_Anforderung 0 "keine_Anforderung" 1 "Anforderung_aktiv"; +VAL_ 279 ANB_Info_Teilbremsung 0 "Auspraegung_Standard" 1 "Auspraegung_Erweitert"; +VAL_ 279 ANB_Notfallblinken 0 "kein_ANB_Notfallblinken" 1 "Notfallblinken_ANB_angefordert"; +VAL_ 279 ANB_Teilbremsung_Freigabe 0 "Teilbremsung_nicht_freigegeben" 1 "Teilbremsung_freigegeben"; +VAL_ 279 ANB_Zielbremsung_Freigabe 0 "Zielbremsung_nicht_freigegeben" 1 "Zielbremsung_freigegeben"; +VAL_ 279 AWV_Vorstufe 0 "keine_Notbremsung_erwartet" 1 "Notbremsung_in_Kuerze"; +VAL_ 279 AWV_Halten 0 "keine_Anforderung" 1 "Anforderung_das_Fzg_im_Stillstand_zu_halten"; +VAL_ 279 AWV_CityANB_Auspraegung 0 "autom_Bremsung_im_ges_vBereich" 1 "autom_Bremsung_im_def_vBereich"; +VAL_ 279 PCF_Freigabe 0 "keine_Freigabe_PreCrashFront" 1 "Freigabe_PreCrashFront"; +VAL_ 279 AWV1_ECD_Anlauf 0 "ECD_Anlauf_nicht_aktivieren" 1 "ECD_Anlauf_aktivieren"; +VAL_ 279 PCF_Time_to_collision 255 "Objektstatus=0x0__oder_berechneter_TTC_Wert_groesser_als_Maximalwert"; +VAL_ 288 TSK_Status 0 "init" 1 "disabled" 2 "enabled" 3 "regulating" 4 "accel_pedal_override" 5 "brake_only" 6 "temp_fault" 7 "perm_fault"; +VAL_ 290 ACC_limitierte_Anfahrdyn 0 "keine_Limitierung" 1 "Limitierung_Anfahrdynamik_angefordert"; +VAL_ 290 ACC_nachtr_Stopp_Anf 0 "nicht_angefordert" 1 "angefordert"; +VAL_ 290 ACC_StartStopp_Info 0 "Motorlauf_langfristig_nicht_notwendig_Stoppfreigabe" 1 "Motoranlauf_nicht_zwingend_notwendig_Stoppverbot_keine_Startanforderung" 2 "Motoranlauf_zwingend_notwendig_Startanforderung" 3 "Systemfehler"; +VAL_ 290 ACC_Sollbeschleunigung_02 2046 "Neutralwert" 2047 "Fehler"; +VAL_ 290 ACC_Anfahren 0 "keine_Anforderung_Anfahren" 1 "Anforderung_Anfahren"; +VAL_ 290 ACC_Anhalten 0 "kein_Anhalten_gewuenscht" 1 "Anhalten_gewuenscht"; +VAL_ 290 ACC_Typ 0 "Basis_ACC" 1 "ACC_mit_FollowToStop" 2 "ACC_mit_StopAndGo" 3 "ACC_nicht_codiert"; +VAL_ 290 ACC_Status_ACC 0 "ACC_OFF_Hauptschalter_aus" 1 "ACC_INIT" 2 "ACC_STANDBY" 3 "ACC_AKTIV_regelt" 4 "ACC_OVERRIDE" 5 "ACC_Abschaltreaktion" 6 "reversibler_Fehler_im_ACC_System" 7 "irreversibler_Fehler_im_ACC_System"; +VAL_ 290 ACC_Minimale_Bremsung 0 "Anforderung_Minimale_Bremsung_nicht_aktiv" 1 "Anforderung_Minimale_Bremsung_aktiv"; +VAL_ 294 EA_ACC_Sollstatus 0 "Init" 1 "ACC_aktivieren" 2 "ACC_deaktivieren"; +VAL_ 294 EA_Ruckprofil 0 "Init" 1 "Profil_1" 2 "Profil_2" 3 "Profil_3" 4 "Profil_4" 5 "Profil_5" 6 "Profil_6" 7 "Profil_7"; +VAL_ 294 HCA_01_Sendestatus 0 "HCA_sendet_mit_1000ms" 1 "HCA_sendet_mit_20ms"; +VAL_ 294 HCA_01_LM_OffSign 0 "positives_Vorzeichen" 1 "negatives_Vorzeichen"; +VAL_ 294 HCA_01_Status_HCA 0 "deaktiviert" 1 "reserviert" 2 "reserviert" 3 "funktionsbereit" 4 "reserviert" 5 "HCA_Momenteneingriff_1" 6 "MA_Aktiv" 7 "HCA_Momenteneingriff_2" 8 "reserviert" 9 "reserviert" 10 "reserviert" 11 "reserviert" 12 "reserviert" 13 "reserviert" 14 "reserviert" 15 "reserviert"; +VAL_ 294 EA_Ruckfreigabe 0 "keine_Freigabe" 1 "Freigabe"; +VAL_ 294 EA_ACC_Wunschgeschwindigkeit 1023 "Init"; +VAL_ 302 ACC_Anhalteweg 2046 "Neutralwert" 2047 "Fehler"; +VAL_ 302 ACC_Anhalten 0 "kein_Anhalten_gewuenscht" 1 "Anhalten_gewuenscht"; +VAL_ 302 ACC_Freilauf_Anf 0 "keine Freilauf-Anforderung" 1 "Freilauf-Anforderung"; +VAL_ 302 ACC_Freilauf_Info 0 "Freilauf_freigegeben" 1 "kein_Uebergang_in_Freilauf_zulaessig" 2 "Freilauf_nicht_freigegeben" 3 "Freilauf_Anforderung"; +VAL_ 302 ACC_Anforderung_HMS 0 "keine_Anforderung" 1 "halten" 2 "parken" 3 "halten_Standby" 4 "anfahren" 5 "Loesen_ueber_Rampe"; +VAL_ 302 ACC_Anfahren 0 "keine_Anforderung_Anfahren" 1 "Anforderung_Anfahren"; +VAL_ 302 ACC_Folgebeschl 254 "Neutralwert"; +VAL_ 302 ACC_Sollbeschleunigung_02 2046 "Neutralwert" 2047 "Fehler"; +VAL_ 391 RegenBrakingMode 0 "default" 1 "B1" 2 "B2" 3 "B3"; +VAL_ 391 GearPosition 2 "P" 3 "R" 4 "N" 5 "D" 6 "D"; +VAL_ 679 ACC_Regelgeschw 1023 "keine_Anzeige"; +VAL_ 679 ACC_Einheit_maxSetzgeschw 0 "kmh" 1 "mph"; +VAL_ 679 ACC_maxSetzgeschw 511 "Init_Neutralwert"; +VAL_ 679 ACC_minRegelgeschw 255 "keine_Anzeige"; +VAL_ 679 ACC_maxRegelgeschw 255 "keine_Anzeige"; +VAL_ 679 ACC_Tempolimitassistent 0 "keine_Anzeige" 1 "Tempolimitassistent_aktiv" 2 "Tempolimitassistent_nicht_verfuegbar" 3 "Tempolimitassistent_Fahreruebernahme"; +VAL_ 679 ACC_Kurvenassistent 0 "keine_Anzeige" 1 "Kreuzung" 2 "Rechtskurve" 3 "Linkskurve" 4 "Kreisverkehr"; +VAL_ 679 ACC_RUV 0 "keine_Anzeige" 1 "RUV_aktiv_Rechtsverkehr" 2 "RUV_aktiv_Linksverkehr"; +VAL_ 679 ACC_Tachokranz 0 "Tachokranz_nicht_beleuchtet" 1 "Tachokranz_beleuchtet"; +VAL_ 679 ACC_Typ_Tachokranz_unten 0 "LEDs_an" 1 "LEDs_aus"; +VAL_ 679 ACC_ENG_Texte 0 "keine_Anzeige" 1 "keine_Laenderverfuegbarkeit" 2 "nicht_verfuegbar" 3 "Geschwindigkeitsgrenze"; +VAL_ 681 AWV_Warnung 0 "keine_Anzeige" 1 "latente_Vorwarnung" 2 "Vorwarnung" 3 "Akutwarnung" 4 "Eingriff" 5 "Fahreruebernahmeaufforderung" 6 "Abbiegewarnung"; +VAL_ 681 AWV_Texte 0 "keine_Anzeige" 1 "Systemstoerung" 2 "keine_Sensorsicht" 3 "Demomodus" 4 "System_aus" 5 "nicht_definiert" 6 "ESC_aus" 7 "zurzeit_eingeschraenkt"; +VAL_ 681 AWV_Status_Anzeige 0 "Init" 1 "verfuegbar" 2 "nicht_verfuegbar"; +VAL_ 681 AWV_Einstellung_System_FSG 0 "deaktiviert" 1 "aktiviert"; +VAL_ 681 AWV_Einstellung_Warnung_FSG 0 "Aus" 1 "Setting_2" 2 "Setting_3" 3 "Setting_4" 4 "Setting_5" 5 "Ein"; +VAL_ 681 AWV_Warnlevel 0 "keine_Gefaehrdung" 63 "max_Gefaehrdung"; +VAL_ 780 ACC_Wunschgeschw_02 1023 "keine_Anzeige"; +VAL_ 780 ACC_Status_Prim_Anz 0 "Symbol nicht beleuchtet" 1 "Farbe 1 (typisch 'gruen')" 2 "Farbe 2 (typisch 'rot')" 3 "Farbe 3 (typisch 'gelb')"; +VAL_ 780 ACC_Abstandsindex 0 "Sonderanzeige_graue_Fahrbahn" 1022 "Sonderanzeige_graue_Fahrbahn" 1023 "Sonderanzeige_Fahrbahn_mit_gruenem_roten_Bereich"; +VAL_ 780 ACC_Akustik_02 0 "keine_Akustik" 1 "hochpriore_Akustik" 2 "niederpriore_Akustik" 3 "hochpriore_Dauerakustik"; +VAL_ 780 ACC_Warnung_Verkehrszeichen_1 0 "keine_Warnung_Initialwert" 1 "Warnung"; +VAL_ 780 ACC_Gesetzte_Zeitluecke 0 "keine_Anzeige" 1 "Zeitluecke_1" 2 "Zeitluecke_2" 3 "Zeitluecke_3" 4 "Zeitluecke_4" 5 "Zeitluecke_5" 6 "nicht_definiert" 7 "nicht_definiert"; +VAL_ 780 ACC_Optischer_Fahrerhinweis 0 "optischer_Fahrerhinweis_AUS" 1 "optischer_Fahrerhinweis_EIN"; +VAL_ 780 ACC_Typ_Tachokranz 0 "Tachokranz_lang" 1 "Tachokranz_kurz"; +VAL_ 780 ACC_Anzeige_Zeitluecke 0 "Anzeige_Zeitluecke_nicht_angefordert" 1 "Anzeige_Zeitluecke_angefordert"; +VAL_ 780 ACC_Tachokranz 0 "Tachokranz_nicht_beleuchtet" 1 "Tachokranz_beleuchtet"; +VAL_ 780 ACC_Display_Prio 0 "hoechste_Prio" 1 "mittlere_Prio" 2 "geringe_Prio" 3 "keine_Prio"; +VAL_ 780 ACC_Relevantes_Objekt 0 "Symbol_nicht_beleuchtet" 1 "Farbe_1_typisch_gruen" 2 "Farbe_2_typisch_rot" 3 "Farbe_3_typisch_gelb"; +VAL_ 780 ACC_Texte_Primaeranz 0 "keine Anzeige" 1 "ACC nicht verfuegbar !" 2 "Auto_Auto_ _ _" 3 "Auto_ _Auto_ _" 4 "Auto_ _ _Auto_" 5 "Auto_ _ _ _Auto" 6 "Auto_Auto_ _ _ Gong (durchgestrichen)" 7 "Auto_ _Auto_ _ Gong (durchgestrichen)" 8 "Auto_ _ _Auto_ Gong (durchgestrichen)" 9 "Auto_ _ _ _Auto Gong (durchgestrichen)" 10 "ACC bereit" 11 "keine Abstandsregelung" 12 "ACC Sensor Sicht !" 13 "ACC nicht verfuegbar" 14 "o o o" 15 "Hochschalten" 16 "ESP Eingriff" 17 "Herunterschalten" 18 "Parkbremse !" 19 "Geschwindigkeitsgrenze" 20 "Waehlhebelposition !" 21 "VDA ACC-Symbol YYY km/h / mph" 22 "Tempolimit XXX km/h / mph" 23 "Kurve XXX km/h / mph" 24 "ACC Abschaltung" 25 "Symbol 'Eieruhr'" 26 "!" 27 "--- km/h / mph" 28 "XXX km/h / mph (Schriftart 2)" 29 "Lenkradwinkel" 30 "Anfahren bestaetigen" 31 "Fahrzeug verloren" 32 "Im Stand nicht moeglich" 33 "Ungueltiger Anfahrbefehl" 34 "Tuer offen !" 35 "Fahrer Gurtschloss offen !" 36 "Schalthebelposition !" 37 "Drehzahl !" 38 "Kurvenassistent aus" 39 "Tempolimit aus" 40 "Abbiegeassistent" 41 "Ortsanfang XXX km/h / mph" 42 "Ortsende XXX km/h / mph" 43 "Tempolimit Ende XXX km/h / mph" 44 "HDC aktiv" 45 "braking guard Bremsruck" 46 "braking guard aus" 47 "braking guard aus" 48 "Uebernehmen !" 49 "Steigung zu gross" 50 "Stehendes Objekt voraus" 51 "SET / 'GRA Symbol'___xxx km/h / mph" 52 "SET / 'GRA Symbol' xxx km/h / mph" 53 "ACC aus" 54 "ACC startet" 55 "ACC reinigen" 56 "ACC Fehler" 57 "ACC haelt an !" 58 "Bremse betaetigen !" 59 "Kupplung betaetigt" 60 "LIM AUS" 61 "LIM AKTIV" 62 "LIM PASSIV" 63 "LIM FEHLER" 64 "Bremse ueberhitzt !" 65 "Bremse haelt !" 66 "ESP PASSIV !" 67 "ACC_anfahrbereit" 68 "Gang_einlegen" 69 "Rechtsueberholen_verhindert" 70 "Linksueberholen_verhindert" 71 "Achtung_Geschwindigkeitsueberschreitung" 72 "Tempolimit_und_Kurvenassistent_nicht_verfuegbar"; +VAL_ 780 ACC_Wunschgeschw_erreicht 0 "Wunschgeschwindigkeit_nicht_erreicht" 1 "Wunschgeschwindigkeit_erreicht"; +VAL_ 780 ACC_Typ_Tachokranz_unten 0 "LEDs_an" 1 "LEDs_aus"; +VAL_ 780 ACC_Status_Anzeige 0 "ACC_GRA_Hauptschalter_aus" 1 "ACC_in_Init_nicht_bei_GRA" 2 "ACC_GRA_passiv" 3 "ACC_GRA_aktiv" 4 "ACC_GRA_im_Hintergrund_uebertreten" 5 "ACC_GRA_Abschaltreaktion" 6 "ACC_reversibel_aus_nicht_bei_GRA" 7 "ACC_GRA_irreversibel_aus"; +VAL_ 804 ACC_Texte_Sekundaeranz 0 "keine_Anzeige" 1 "Zielfahrzeug_erkannt" 2 "Rechtskurve_voraus" 3 "Linkskurve_voraus" 4 "Tempolimit_voraus" 5 "Sensorsicht" 6 "Anfahrbereit" 7 "Tempolimit_erkannt" 8 "Kreuzung_voraus" 9 "Kreisverkehr_voraus"; +VAL_ 804 ACC_Texte_Zusatzanz 0 "keine_Anzeige" 1 "ACC_AUS" 2 "ACC_BEREIT" 3 "UEBERTRETEN" 4 "ABSTAND" 5 "DISTANZ_1" 6 "DISTANZ_2" 7 "DISTANZ_3" 8 "DISTANZ_4" 9 "DISTANZ_1__dyn" 10 "DISTANZ_2__dyn" 11 "DISTANZ_3__dyn" 12 "DISTANZ_4__dyn" 13 "DISTANZ_1__stand" 14 "DISTANZ_2__stand" 15 "DISTANZ_3__stand" 16 "DISTANZ_4__stand" 17 "DISTANZ_1__comf" 18 "DISTANZ_2__comf" 19 "DISTANZ_3__comf" 20 "DISTANZ_4__comf" 21 "DISTANZ_1__efficiency" 22 "DISTANZ_2__efficiency" 23 "DISTANZ_3__efficiency" 24 "DISTANZ_4__efficiency" 25 "DISTANZ_5" 26 "DISTANZ_5__dyn" 27 "DISTANZ_5__stand" 28 "DISTANZ_5__comf" 29 "DISTANZ_5__efficiency" 30 "ACHTUNG" 31 "Abstandsanzeige" 32 "Abstandsanz_Warnung_aktiviert"; +VAL_ 804 ACC_Status_Zusatzanz 0 "keine Anzeige" 1 "Bild 1 (Fzg. Silhouette, typ. farblos)" 2 "Bild 2 (Fzg. Farbe 1, typ. grau)" 3 "Bild 3 (Fzg. Farbe 2, typ. rot)" 4 "Bild 4 (Symbol 1 ACCplus, typ. Doppelfzg. gelb)" 5 "Bild 5 (Symbol 2 ACCplus, typ. Doppelfzg. grau)" 6 "Bild 6 (Fzg. Farbe 2, typ. rot) mit Priorität im Kombi (Pop-up)"; +VAL_ 804 ACC_Texte 0 "keine_Anzeige" 1 "ACC_nicht_verfuegbar" 2 "ACC_und_AWV_nicht_verfuegbar" 3 "ACC_keine_Sensorsicht" 4 "ACC_und_AWV_keine_Sensorsicht" 5 "ACC_Steigung_zu_gross" 6 "ACC_nur_in_Fahrstufe_verfuegbar" 7 "ACC_Parkbremse_betaetigt" 8 "ACC_ESP_Eingriff" 9 "ACC_Bitte_uebernehmen" 10 "ACC_HDC_betaetigt" 11 "ACC_Geschwindigkeitsgrenze" 12 "ACC_Schalthebelposition" 13 "ACC_Drehzahl" 14 "ACC_Kupplung_betaetigt" 15 "ACC_Aktivierverhinderung" 16 "ACC_Abschaltung" 17 "ACC_Parkassistent_aktiv" 18 "ACC_ESC_aus" 19 "ACC_Charisma_Modus_inkompatibel" 20 "ACC_Stehendes_Objekt_voraus" 21 "ACA_Fahreruebernahme" 22 "ACA_Querfuehrung_nicht_verfuegbar"; +VAL_ 804 ACC_Texte_braking_guard 0 "keine_Anzeige" 1 "AWV_aus" 2 "AWV_Warnung" 3 "AWV_Demomodus" 4 "AWV_Systemstoerung" 5 "AWV_Eingriff" 6 "AWV_Vorwarnung_aus" 7 "AWV_keine_Sensorsicht"; +VAL_ 804 ACC_Warnhinweis 0 "kein_Warnhinweis" 1 "Warnhinweis"; +VAL_ 804 ACC_Zeitluecke_Abstandswarner 61 "Freifahrt" 62 "nicht_definiert" 63 "keine_Anzeige"; +VAL_ 804 ACC_Abstand_Abstandswarner 509 "Freifahrt" 510 "nicht_definiert" 511 "keine_Anzeige"; +VAL_ 804 ACC_Tempolimit 0 "keine_Anzeige" 1 "5_zulHoechstgeschw" 2 "7_zulHoechstgeschw" 3 "10_zulHoechstgeschw" 4 "15_zulHoechstgeschw" 5 "20_zulHoechstgeschw" 6 "25_zulHoechstgeschw" 7 "30_zulHoechstgeschw" 8 "35_zulHoechstgeschw" 9 "40_zulHoechstgeschw" 10 "45_zulHoechstgeschw" 11 "50_zulHoechstgeschw" 12 "55_zulHoechstgeschw" 13 "60_zulHoechstgeschw" 14 "65_zulHoechstgeschw" 15 "70_zulHoechstgeschw" 16 "75_zulHoechstgeschw" 17 "80_zulHoechstgeschw" 18 "85_zulHoechstgeschw" 19 "90_zulHoechstgeschw" 20 "95_zulHoechstgeschw" 21 "100_zulHoechstgeschw" 22 "110_zulHoechstgeschw" 23 "120_zulHoechstgeschw" 24 "130_zulHoechstgeschw" 25 "140_zulHoechstgeschw" 26 "150_zulHoechstgeschw" 27 "160_zulHoechstgeschw" 28 "200_zulHoechstgeschw" 30 "250_zulHoechstgeschw" 31 "Ende_zulHoechstgeschw"; +VAL_ 804 ACC_Charisma_FahrPr 0 "keine_Funktion" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" 8 "Programm_8" 9 "Programm_9" 10 "Programm_10" 11 "Programm_11" 12 "Programm_12" 13 "Programm_13" 14 "Programm_14" 15 "Programm_15"; +VAL_ 804 ACC_Charisma_Status 0 "Init" 1 "verfuegbar" 2 "nicht_verfuegbar" 3 "asynchron_durch_Fahrerwunsch"; +VAL_ 804 ACC_Texte_Abstandswarner 0 "keine_Anzeige" 1 "Systemstoerung" 2 "keine_Sensorsicht" 3 "zurzeit_eingeschraenkt"; +VAL_ 870 Fast_Send_Rate_Active 0 "1 Hz" 1 "50 Hz"; +VAL_ 1720 KBI_Variante_USA 0 "keine USA-Variante" 1 "USA-Variante"; +VAL_ 1720 KBI_Variante 0 "Zeiger Kombiinstrument" 1 "Volldisplay Kombiinstrument"; +VAL_ 1720 KBI_BCmE_aktiv 0 "Anzeige_nicht_aktiv" 1 "Anzeige_aktiv"; +VAL_ 1720 KBI_Sparhinweis_quittiert 0 "nicht_quittiert" 1 "quittiert"; +VAL_ 1720 KBI_Tankfuellstand_Prozent 126 "Init" 127 "Fehler"; +VAL_ 1720 KBI_Nachtanken_erkannt 0 "Geberbetrieb" 1 "Nachtankmodus"; +VAL_ 1720 KBI_Tankinhalt_hochaufl 16382 "Init" 16383 "Fehler"; +VAL_ 1720 KBI_Max_Tankinhalt 254 "Init" 255 "Fehler"; diff --git a/opendbc_repo/pyproject.toml b/opendbc_repo/pyproject.toml new file mode 100644 index 000000000000000..0ffe452185d5bb7 --- /dev/null +++ b/opendbc_repo/pyproject.toml @@ -0,0 +1,111 @@ +[project] +name = "opendbc" +version = "1.0.0" +description = "CAN bus databases and tools" +license = { file = "LICENSE" } +authors = [{ name = "Vehicle Researcher", email = "user@comma.ai" }] +readme = "README.md" +requires-python = ">=3.9" + +urls = { "homepage" = "https://github.com/commaai/opendbc" } + +# setuptools includes distutils which is needed by Cython and pre-commit. +# distutils was removed in python3.12 from the standard library. +dependencies = [ + "scons", + "numpy", + "Cython", + "crcmod", + "tqdm", + "pycapnp", + "pandacan@git+https://github.com/commaai/panda.git@master", + "setuptools", + "pycryptodome", +] + +[project.optional-dependencies] +testing = [ + "ruff", + "pytest", + "pytest-mock", + "pytest-xdist", + "pytest-subtests", + "hypothesis==6.47.*", + "parameterized>=0.8,<0.9", + "pre-commit", +] +docs = [ + "Jinja2", + "natsort", +] +examples = [ + "inputs", + "matplotlib", +] + +[tool.pytest.ini_options] +addopts = "--ignore=panda/ -Werror --strict-config --strict-markers --durations=10 -n auto" +python_files = "test_*.py" +testpaths = [ + "opendbc" +] + +[tool.codespell] +quiet-level = 3 +ignore-words-list = "alo,ba,bu,deque,hda,grey,arange" +builtin = "clear,rare,informal,code,names,en-GB_to_en-US" +check-hidden = true + +[tool.cython-lint] +max-line-length = 120 +ignore = ["E111", "E114"] + +[tool.mypy] +# helpful warnings +warn_redundant_casts=true +warn_unreachable=true +warn_unused_ignores=true + +# restrict dynamic typing +warn_return_any=true + +# allow implicit optionals for default args +implicit_optional = true + +explicit_package_bases=true + +# https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml +[tool.ruff] +line-length = 160 +indent-width = 2 +target-version="py311" + +[tool.ruff.lint] +select = [ + "E", "F", "W", "PIE", "C4", "ISC", "A", "B", + "NPY", # numpy + "UP", # pyupgrade + "TRY302", "TRY400", "TRY401", # try/excepts + "RUF008", "RUF100", + "TID251", + "PLR1704", + "INP001", +] +ignore = [ + "W292", + "E741", + "E402", + "C408", + "ISC003", + "B027", + "B024", + "NPY002", # new numpy random syntax is worse +] +flake8-implicit-str-concat.allow-multiline=false + +[tool.ruff.lint.per-file-ignores] +"site_scons/*" = ["ALL"] + +[tool.ruff.lint.flake8-tidy-imports.banned-api] +"pytest.main".msg = "pytest.main requires special handling that is easy to mess up!" +"unittest".msg = "Use pytest" diff --git a/opendbc/site_scons/site_tools/cython.py b/opendbc_repo/site_scons/site_tools/cython.py similarity index 100% rename from opendbc/site_scons/site_tools/cython.py rename to opendbc_repo/site_scons/site_tools/cython.py diff --git a/opendbc_repo/test.sh b/opendbc_repo/test.sh new file mode 100755 index 000000000000000..a574da2fde207a4 --- /dev/null +++ b/opendbc_repo/test.sh @@ -0,0 +1,20 @@ +#!/bin/bash +set -e + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR + +# ensure we're up to date +uv venv --allow-existing +source .venv/bin/activate + +uv pip install -e .[testing,docs] + +uv run scons -j8 + +uv run pre-commit run --all-files +uv run pytest -n8 + +GREEN='\033[0;32m' +NC='\033[0m' +printf "\n${GREEN}All good!${NC} Finished build, lint, and test in ${SECONDS}s\n" diff --git a/panda/.gitignore b/panda/.gitignore index 2dfa0947686d1a1..89eed6e4c571c8c 100644 --- a/panda/.gitignore +++ b/panda/.gitignore @@ -11,6 +11,7 @@ a.out *~ .#* dist/ +build/ pandacan.egg-info/ obj/ examples/output.csv @@ -28,3 +29,7 @@ nosetests.xml *.gcno tests/safety/coverage-out tests/safety/coverage.info + +*.profraw +*.profdata +mull.yml diff --git a/panda/Jenkinsfile b/panda/Jenkinsfile index 2d4c615dfe9653a..3e6b888e11ef3fa 100644 --- a/panda/Jenkinsfile +++ b/panda/Jenkinsfile @@ -4,7 +4,7 @@ def docker_run(String step_label, int timeout_mins, String cmd) { --env PYTHONWARNINGS=error \ --volume /dev/bus/usb:/dev/bus/usb \ --volume /var/run/dbus:/var/run/dbus \ - --workdir /tmp/openpilot/panda \ + --workdir /tmp/pythonpath/panda \ --net host \ ${env.DOCKER_IMAGE_TAG} \ bash -c 'scons -j8 && ${cmd}'", \ @@ -73,56 +73,57 @@ pipeline { } stages { - stage('panda tests') { - parallel { - stage('test dos') { - agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + stage ('Acquire resource locks') { + options { + lock(resource: "pandas") + } + stages { + stage('Build Docker Image') { steps { - phone_steps("panda-dos", [ - ["build", "scons -j4"], - ["flash", "cd tests/ && ./reflash_internal_panda.py"], - ["flash jungle", "cd board/jungle && ./flash.py"], - ["test", "cd tests/hitl && HW_TYPES=6 pytest -n0 --durations=0 [2-9]*.py -k 'not test_send_recv'"], - ]) + timeout(time: 20, unit: 'MINUTES') { + script { + sh 'git archive -v -o panda.tar.gz --format=tar.gz HEAD' + dockerImage = docker.build("${env.DOCKER_IMAGE_TAG}") + } + } } } - - stage('test tres') { - agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } + stage('jungle tests') { steps { - phone_steps("panda-tres", [ - ["build", "scons -j4"], - ["flash", "cd tests/ && ./reflash_internal_panda.py"], - ["flash jungle", "cd board/jungle && ./flash.py"], - ["test", "cd tests/hitl && HW_TYPES=9 pytest -n0 --durations=0 2*.py [5-9]*.py"], - ]) + script { + retry (3) { + docker_run("reset hardware", 3, "python3 ./tests/hitl/reset_jungles.py") + } + } } } - stage ('Acquire resource locks') { - options { - lock(resource: "pandas") - } - stages { - stage('Build Docker Image') { + stage('parallel tests') { + parallel { + stage('test tres') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } steps { - timeout(time: 20, unit: 'MINUTES') { - script { - sh 'git archive -v -o panda.tar.gz --format=tar.gz HEAD' - dockerImage = docker.build("${env.DOCKER_IMAGE_TAG}") - } - } + phone_steps("panda-tres", [ + ["build", "scons -j4"], + ["flash", "cd tests/ && ./reflash_internal_panda.py"], + ["flash jungle", "cd board/jungle && ./flash.py --all"], + ["test", "cd tests/hitl && HW_TYPES=9 pytest -n0 --durations=0 2*.py [5-9]*.py"], + ]) } } - stage('jungle tests') { + + stage('test dos') { + agent { docker { image 'ghcr.io/commaai/alpine-ssh'; args '--user=root' } } steps { - script { - retry (3) { - docker_run("reset hardware", 3, "python ./tests/hitl/reset_jungles.py") - } - } + phone_steps("panda-dos", [ + ["build", "scons -j4"], + ["flash", "cd tests/ && ./reflash_internal_panda.py"], + ["flash jungle", "cd board/jungle && ./flash.py --all"], + ["test", "cd tests/hitl && HW_TYPES=6 pytest -n0 --durations=0 [2-9]*.py -k 'not test_send_recv'"], + ]) } } + stage('bootkick tests') { steps { script { diff --git a/panda/README.md b/panda/README.md index b2830b21efe3370..854e6a252268949 100644 --- a/panda/README.md +++ b/panda/README.md @@ -23,7 +23,7 @@ Safety modes optionally support `controls_allowed`, which allows or blocks a sub ## Code Rigor -The panda firmware is written for its use in conjuction with [openpilot](https://github.com/commaai/openpilot). The panda firmware, through its safety model, provides and enforces the +The panda firmware is written for its use in conjunction with [openpilot](https://github.com/commaai/openpilot). The panda firmware, through its safety model, provides and enforces the [openpilot safety](https://github.com/commaai/openpilot/blob/master/docs/SAFETY.md). Due to its critical function, it's important that the application code rigor within the `board` folder is held to high standards. These are the [CI regression tests](https://github.com/commaai/panda/actions) we have in place: @@ -49,7 +49,7 @@ In addition, we run the [ruff linter](https://github.com/astral-sh/ruff) and [my Setup dependencies: ```bash # Ubuntu -sudo apt-get install dfu-util gcc-arm-none-eabi python3-pip libffi-dev git +sudo apt-get install dfu-util gcc-arm-none-eabi python3-pip libffi-dev git clang-17 # macOS brew install --cask gcc-arm-embedded @@ -62,7 +62,7 @@ git clone https://github.com/commaai/panda.git cd panda # install dependencies -pip install -r requirements.txt +pip install -e .[dev] # install panda python setup.py install @@ -97,7 +97,7 @@ The panda jungle uses different udev rules. See [the repo](https://github.com/co As a universal car interface, it should support every reasonable software interface. - [Python library](https://github.com/commaai/panda/tree/master/python) -- [C++ library](https://github.com/commaai/openpilot/tree/master/selfdrive/boardd) +- [C++ library](https://github.com/commaai/openpilot/tree/master/selfdrive/pandad) - [socketcan in kernel](https://github.com/commaai/panda/tree/master/drivers/linux) (alpha) ## Licensing diff --git a/panda/SConscript b/panda/SConscript index 8f4db5993543ad6..f6501e88cc1b63c 100644 --- a/panda/SConscript +++ b/panda/SConscript @@ -167,7 +167,9 @@ Export('base_project_f4', 'base_project_h7', 'build_project') # Common autogenerated includes with open("board/obj/gitversion.h", "w") as f: - f.write(f'const uint8_t gitversion[] = "{get_version(BUILDER, BUILD_TYPE)}";\n') + version = get_version(BUILDER, BUILD_TYPE) + f.write(f'extern const uint8_t gitversion[{len(version)}];\n') + f.write(f'const uint8_t gitversion[{len(version)}] = "{version}";\n') with open("board/obj/version", "w") as f: f.write(f'{get_version(BUILDER, BUILD_TYPE)}') diff --git a/panda/SConstruct b/panda/SConstruct index aa13f5922994ee6..11ff21738e55c3b 100644 --- a/panda/SConstruct +++ b/panda/SConstruct @@ -16,6 +16,10 @@ AddOption('--compile_db', action='store_true', help='build clang compilation database') +AddOption('--mutation', + action='store_true', + help='generate mutation-ready code') + env = Environment( COMPILATIONDB_USE_ABSPATH=True, tools=["default", "compilation_db"], diff --git a/panda/__init__.py b/panda/__init__.py index bf487fddccd1ecb..665682521fae8e3 100644 --- a/panda/__init__.py +++ b/panda/__init__.py @@ -2,7 +2,8 @@ from .python.spi import PandaSpiException, PandaProtocolMismatch, STBootloaderSPIHandle # noqa: F401 from .python.serial import PandaSerial # noqa: F401 from .python.canhandle import CanHandle # noqa: F401 -from .python import (Panda, PandaDFU, # noqa: F401 +from .python.utils import logger # noqa: F401 +from .python import (Panda, PandaDFU, uds, isotp, # noqa: F401 pack_can_buffer, unpack_can_buffer, calculate_checksum, DLC_TO_LEN, LEN_TO_DLC, ALTERNATIVE_EXPERIENCE, CANPACKET_HEAD_SIZE) diff --git a/panda/board/SConscript b/panda/board/SConscript index 93fd47b07edc3a8..3ff77648ba96ff2 100644 --- a/panda/board/SConscript +++ b/panda/board/SConscript @@ -15,7 +15,4 @@ for project_name, project in build_projects.items(): 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 c860d1401d43751..133c11fb2d0e9f3 100644 --- a/panda/board/boards/black.h +++ b/panda/board/boards/black.h @@ -1,8 +1,12 @@ +#pragma once + +#include "board_declarations.h" + // /////////////////////////////// // // Black Panda (STM32F4) + Harness // // /////////////////////////////// // -void black_enable_can_transceiver(uint8_t transceiver, bool enabled) { +static void black_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver){ case 1U: set_gpio_output(GPIOC, 1, !enabled); @@ -22,7 +26,7 @@ void black_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -void black_enable_can_transceivers(bool enabled) { +static void black_enable_can_transceivers(bool enabled) { for(uint8_t i=1U; i<=4U; i++){ // Leave main CAN always on for CAN-based ignition detection if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ @@ -33,7 +37,7 @@ void black_enable_can_transceivers(bool enabled) { } } -void black_set_led(uint8_t color, bool enabled) { +static void black_set_led(uint8_t color, bool enabled) { switch (color){ case LED_RED: set_gpio_output(GPIOC, 9, !enabled); @@ -49,11 +53,11 @@ void black_set_led(uint8_t color, bool enabled) { } } -void black_set_usb_load_switch(bool enabled) { +static void black_set_usb_load_switch(bool enabled) { set_gpio_output(GPIOB, 1, !enabled); } -void black_set_can_mode(uint8_t mode) { +static void black_set_can_mode(uint8_t mode) { black_enable_can_transceiver(2U, false); black_enable_can_transceiver(4U, false); switch (mode) { @@ -86,12 +90,12 @@ void black_set_can_mode(uint8_t mode) { } } -bool black_check_ignition(void){ +static bool black_check_ignition(void){ // ignition is checked through harness return harness_check_ignition(); } -void black_init(void) { +static void black_init(void) { common_init_gpio(); // A8,A15: normal CAN3 mode @@ -135,13 +139,13 @@ void black_init(void) { black_set_can_mode(CAN_MODE_NORMAL); } -void black_init_bootloader(void) { +static void black_init_bootloader(void) { // GPS OFF set_gpio_output(GPIOC, 5, 0); set_gpio_output(GPIOC, 12, 0); } -harness_configuration black_harness_config = { +static harness_configuration black_harness_config = { .has_harness = true, .GPIO_SBU1 = GPIOC, .GPIO_SBU2 = GPIOC, @@ -162,6 +166,7 @@ board board_black = { .has_spi = false, .has_canfd = false, .fan_max_rpm = 0U, + .fan_max_pwm = 100U, .avdd_mV = 3300U, .fan_stall_recovery = false, .fan_enable_cooldown_time = 0U, @@ -177,5 +182,6 @@ board board_black = { .set_fan_enabled = unused_set_fan_enabled, .set_ir_power = unused_set_ir_power, .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio + .read_som_gpio = unused_read_som_gpio, + .set_amp_enabled = unused_set_amp_enabled }; diff --git a/panda/board/boards/board_declarations.h b/panda/board/boards/board_declarations.h index a9ff9297baec738..61e9ce2d8e38087 100644 --- a/panda/board/boards/board_declarations.h +++ b/panda/board/boards/board_declarations.h @@ -1,3 +1,8 @@ +#pragma once + +#include +#include + // ******************** Prototypes ******************** typedef enum { BOOT_STANDBY, @@ -19,6 +24,7 @@ typedef void (*board_set_fan_enabled)(bool enabled); typedef void (*board_set_siren)(bool enabled); typedef void (*board_set_bootkick)(BootState state); typedef bool (*board_read_som_gpio)(void); +typedef void (*board_set_amp_enabled)(bool enabled); struct board { harness_configuration *harness_config; @@ -29,6 +35,7 @@ struct board { const uint16_t avdd_mV; const bool fan_stall_recovery; const uint8_t fan_enable_cooldown_time; + const uint8_t fan_max_pwm; board_init init; board_init_bootloader init_bootloader; board_enable_can_transceiver enable_can_transceiver; @@ -43,6 +50,7 @@ struct board { board_set_siren set_siren; board_set_bootkick set_bootkick; board_read_som_gpio read_som_gpio; + board_set_amp_enabled set_amp_enabled; }; // ******************* Definitions ******************** @@ -73,3 +81,12 @@ struct board { // CAN modes #define CAN_MODE_NORMAL 0U #define CAN_MODE_OBD_CAN2 1U + +extern struct board board_black; +extern struct board board_dos; +extern struct board board_uno; +extern struct board board_tres; +extern struct board board_grey; +extern struct board board_white; +extern struct board board_cuatro; +extern struct board board_red; diff --git a/panda/board/boards/cuatro.h b/panda/board/boards/cuatro.h index 43a5dfc5052f2b1..4a6b5da0962b0e6 100644 --- a/panda/board/boards/cuatro.h +++ b/panda/board/boards/cuatro.h @@ -1,14 +1,18 @@ +#pragma once + +#include "board_declarations.h" + // ////////////////////////// // // Cuatro (STM32H7) + Harness // // ////////////////////////// // -void cuatro_set_led(uint8_t color, bool enabled) { +static 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); + case LED_GREEN: + set_gpio_output(GPIOB, 2, !enabled); break; case LED_BLUE: set_gpio_output(GPIOE, 2, !enabled); @@ -18,7 +22,7 @@ void cuatro_set_led(uint8_t color, bool enabled) { } } -void cuatro_enable_can_transceiver(uint8_t transceiver, bool enabled) { +static void cuatro_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver) { case 1U: set_gpio_output(GPIOB, 7, !enabled); @@ -37,7 +41,7 @@ void cuatro_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -void cuatro_enable_can_transceivers(bool enabled) { +static 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 @@ -49,17 +53,40 @@ void cuatro_enable_can_transceivers(bool enabled) { } } -uint32_t cuatro_read_voltage_mV(void) { +static uint32_t cuatro_read_voltage_mV(void) { return adc_get_mV(8) * 11U; } -uint32_t cuatro_read_current_mA(void) { +static uint32_t cuatro_read_current_mA(void) { return adc_get_mV(3) * 2U; } -void cuatro_init(void) { +static void cuatro_set_fan_enabled(bool enabled) { + set_gpio_output(GPIOD, 3, !enabled); +} + +static void cuatro_set_bootkick(BootState state) { + set_gpio_output(GPIOA, 0, state != BOOT_BOOTKICK); + // only use if we have to + //set_gpio_output(GPIOC, 12, state != BOOT_RESET); +} + +static void cuatro_set_siren(bool enabled){ + beeper_enable(enabled); +} + +static void cuatro_set_amp_enabled(bool enabled){ + set_gpio_output(GPIOA, 5, enabled); +} + +static void cuatro_init(void) { red_chiplet_init(); + // init LEDs as open drain + set_gpio_output_type(GPIOE, 2, OUTPUT_TYPE_OPEN_DRAIN); + set_gpio_output_type(GPIOB, 2, OUTPUT_TYPE_OPEN_DRAIN); + set_gpio_output_type(GPIOD, 15, OUTPUT_TYPE_OPEN_DRAIN); + // Power readout set_gpio_mode(GPIOC, 5, MODE_ANALOG); set_gpio_mode(GPIOA, 6, MODE_ANALOG); @@ -81,8 +108,7 @@ void cuatro_init(void) { set_gpio_pullup(GPIOC, 2, PULL_DOWN); // SOM bootkick + reset lines - set_gpio_mode(GPIOC, 12, MODE_OUTPUT); - tres_set_bootkick(BOOT_BOOTKICK); + cuatro_set_bootkick(BOOT_BOOTKICK); // SOM debugging UART gpio_uart7_init(); @@ -93,6 +119,7 @@ void cuatro_init(void) { // fan setup set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); + register_set_bits(&(GPIOC->OTYPER), GPIO_OTYPER_OT8); // open drain // Initialize IR PWM and set to 0% set_gpio_alternate(GPIOC, 9, GPIO_AF2_TIM3); @@ -101,6 +128,21 @@ void cuatro_init(void) { // Clock source clock_source_init(); + + // Beeper + set_gpio_alternate(GPIOD, 14, GPIO_AF2_TIM4); + beeper_init(); + + // Sound codec + cuatro_set_amp_enabled(false); + set_gpio_alternate(GPIOA, 2, GPIO_AF8_SAI4); // SAI4_SCK_B + set_gpio_alternate(GPIOC, 0, GPIO_AF8_SAI4); // SAI4_FS_B + set_gpio_alternate(GPIOD, 11, GPIO_AF10_SAI4); // SAI4_SD_A + set_gpio_alternate(GPIOE, 3, GPIO_AF8_SAI4); // SAI4_SD_B + set_gpio_alternate(GPIOE, 4, GPIO_AF2_SAI1); // SAI1_D2 + set_gpio_alternate(GPIOE, 5, GPIO_AF2_SAI1); // SAI1_CK2 + set_gpio_alternate(GPIOE, 6, GPIO_AF10_SAI4); // SAI4_MCLK_B + sound_init(); } board board_cuatro = { @@ -108,7 +150,8 @@ board board_cuatro = { .has_obd = true, .has_spi = true, .has_canfd = true, - .fan_max_rpm = 6600U, + .fan_max_rpm = 12500U, + .fan_max_pwm = 99U, // it can go up to 14k RPM, but 99% -> 100% is very non-linear .avdd_mV = 1800U, .fan_stall_recovery = false, .fan_enable_cooldown_time = 3U, @@ -121,9 +164,10 @@ board board_cuatro = { .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_fan_enabled = cuatro_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 + .set_siren = cuatro_set_siren, + .set_bootkick = cuatro_set_bootkick, + .read_som_gpio = tres_read_som_gpio, + .set_amp_enabled = cuatro_set_amp_enabled }; diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h index 0164f2b262de561..d96cee4ca4900cf 100644 --- a/panda/board/boards/dos.h +++ b/panda/board/boards/dos.h @@ -1,8 +1,12 @@ +#pragma once + +#include "board_declarations.h" + // /////////////////////// // // Dos (STM32F4) + Harness // // /////////////////////// // -void dos_enable_can_transceiver(uint8_t transceiver, bool enabled) { +static void dos_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver){ case 1U: set_gpio_output(GPIOC, 1, !enabled); @@ -22,7 +26,7 @@ void dos_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -void dos_enable_can_transceivers(bool enabled) { +static void dos_enable_can_transceivers(bool enabled) { for(uint8_t i=1U; i<=4U; i++){ // Leave main CAN always on for CAN-based ignition detection if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ @@ -33,7 +37,7 @@ void dos_enable_can_transceivers(bool enabled) { } } -void dos_set_led(uint8_t color, bool enabled) { +static void dos_set_led(uint8_t color, bool enabled) { switch (color){ case LED_RED: set_gpio_output(GPIOC, 9, !enabled); @@ -49,11 +53,11 @@ void dos_set_led(uint8_t color, bool enabled) { } } -void dos_set_bootkick(BootState state) { +static void dos_set_bootkick(BootState state) { set_gpio_output(GPIOC, 4, state != BOOT_BOOTKICK); } -void dos_set_can_mode(uint8_t mode) { +static void dos_set_can_mode(uint8_t mode) { dos_enable_can_transceiver(2U, false); dos_enable_can_transceiver(4U, false); switch (mode) { @@ -85,28 +89,28 @@ void dos_set_can_mode(uint8_t mode) { } } -bool dos_check_ignition(void){ +static bool dos_check_ignition(void){ // ignition is checked through harness return harness_check_ignition(); } -void dos_set_ir_power(uint8_t percentage){ +static void dos_set_ir_power(uint8_t percentage){ pwm_set(TIM4, 2, percentage); } -void dos_set_fan_enabled(bool enabled){ +static void dos_set_fan_enabled(bool enabled){ set_gpio_output(GPIOA, 1, enabled); } -void dos_set_siren(bool enabled){ +static void dos_set_siren(bool enabled){ set_gpio_output(GPIOC, 12, enabled); } -bool dos_read_som_gpio (void){ +static bool dos_read_som_gpio (void){ return (get_gpio_input(GPIOC, 2) != 0); } -void dos_init(void) { +static void dos_init(void) { common_init_gpio(); // A8,A15: normal CAN3 mode @@ -166,7 +170,7 @@ void dos_init(void) { clock_source_init(); } -harness_configuration dos_harness_config = { +static harness_configuration dos_harness_config = { .has_harness = true, .GPIO_SBU1 = GPIOC, .GPIO_SBU2 = GPIOC, @@ -190,6 +194,7 @@ board board_dos = { #endif .has_canfd = false, .fan_max_rpm = 6500U, + .fan_max_pwm = 100U, .avdd_mV = 3300U, .fan_stall_recovery = true, .fan_enable_cooldown_time = 3U, @@ -206,5 +211,6 @@ board board_dos = { .set_ir_power = dos_set_ir_power, .set_siren = dos_set_siren, .set_bootkick = dos_set_bootkick, - .read_som_gpio = dos_read_som_gpio + .read_som_gpio = dos_read_som_gpio, + .set_amp_enabled = unused_set_amp_enabled }; diff --git a/panda/board/boards/grey.h b/panda/board/boards/grey.h index 516d0fa70fe7470..b3e40bc6fe31c30 100644 --- a/panda/board/boards/grey.h +++ b/panda/board/boards/grey.h @@ -1,3 +1,7 @@ +#pragma once + +#include "board_declarations.h" + // //////////////////// // // Grey Panda (STM32F4) // // //////////////////// // @@ -11,6 +15,7 @@ board board_grey = { .has_spi = false, .has_canfd = false, .fan_max_rpm = 0U, + .fan_max_pwm = 100U, .avdd_mV = 3300U, .fan_stall_recovery = false, .fan_enable_cooldown_time = 0U, @@ -26,5 +31,6 @@ board board_grey = { .set_fan_enabled = unused_set_fan_enabled, .set_ir_power = unused_set_ir_power, .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio + .read_som_gpio = unused_read_som_gpio, + .set_amp_enabled = unused_set_amp_enabled }; diff --git a/panda/board/boards/red.h b/panda/board/boards/red.h index 746c54b622b9ef0..f1d8d9c44bdac5a 100644 --- a/panda/board/boards/red.h +++ b/panda/board/boards/red.h @@ -1,8 +1,12 @@ +#pragma once + +#include "board_declarations.h" + // ///////////////////////////// // // Red Panda (STM32H7) + Harness // // ///////////////////////////// // -void red_enable_can_transceiver(uint8_t transceiver, bool enabled) { +static void red_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver) { case 1U: set_gpio_output(GPIOG, 11, !enabled); @@ -21,7 +25,7 @@ void red_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -void red_enable_can_transceivers(bool enabled) { +static void red_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 @@ -33,7 +37,7 @@ void red_enable_can_transceivers(bool enabled) { } } -void red_set_led(uint8_t color, bool enabled) { +static void red_set_led(uint8_t color, bool enabled) { switch (color) { case LED_RED: set_gpio_output(GPIOE, 4, !enabled); @@ -49,7 +53,7 @@ void red_set_led(uint8_t color, bool enabled) { } } -void red_set_can_mode(uint8_t mode) { +static void red_set_can_mode(uint8_t mode) { red_enable_can_transceiver(2U, false); red_enable_can_transceiver(4U, false); switch (mode) { @@ -91,16 +95,16 @@ void red_set_can_mode(uint8_t mode) { } } -bool red_check_ignition(void) { +static bool red_check_ignition(void) { // ignition is checked through harness return harness_check_ignition(); } -uint32_t red_read_voltage_mV(void){ +static uint32_t red_read_voltage_mV(void){ return adc_get_mV(2) * 11U; // TODO: is this correct? } -void red_init(void) { +static void red_init(void) { common_init_gpio(); //C10,C11 : OBD_SBU1_RELAY, OBD_SBU2_RELAY @@ -153,7 +157,7 @@ void red_init(void) { red_set_can_mode(CAN_MODE_NORMAL); } -harness_configuration red_harness_config = { +static harness_configuration red_harness_config = { .has_harness = true, .GPIO_SBU1 = GPIOC, .GPIO_SBU2 = GPIOA, @@ -174,6 +178,7 @@ board board_red = { .has_spi = false, .has_canfd = true, .fan_max_rpm = 0U, + .fan_max_pwm = 100U, .avdd_mV = 3300U, .fan_stall_recovery = false, .fan_enable_cooldown_time = 0U, @@ -189,5 +194,6 @@ board board_red = { .set_fan_enabled = unused_set_fan_enabled, .set_ir_power = unused_set_ir_power, .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio + .read_som_gpio = unused_read_som_gpio, + .set_amp_enabled = unused_set_amp_enabled }; diff --git a/panda/board/boards/red_chiplet.h b/panda/board/boards/red_chiplet.h index d79f8f83a648298..e5d1aa097f676c7 100644 --- a/panda/board/boards/red_chiplet.h +++ b/panda/board/boards/red_chiplet.h @@ -1,10 +1,14 @@ +#pragma once + +#include "board_declarations.h" + // ///////////////////////////////////// // // Red Panda chiplet (STM32H7) + Harness // // ///////////////////////////////////// // // Most hardware functionality is similar to red panda -void red_chiplet_enable_can_transceiver(uint8_t transceiver, bool enabled) { +static void red_chiplet_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver) { case 1U: set_gpio_output(GPIOG, 11, !enabled); @@ -23,7 +27,7 @@ void red_chiplet_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -void red_chiplet_enable_can_transceivers(bool enabled) { +static void red_chiplet_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 @@ -35,7 +39,7 @@ void red_chiplet_enable_can_transceivers(bool enabled) { } } -void red_chiplet_set_can_mode(uint8_t mode) { +static void red_chiplet_set_can_mode(uint8_t mode) { red_chiplet_enable_can_transceiver(2U, false); red_chiplet_enable_can_transceiver(4U, false); switch (mode) { @@ -77,11 +81,11 @@ void red_chiplet_set_can_mode(uint8_t mode) { } } -void red_chiplet_set_fan_or_usb_load_switch(bool enabled) { +static void red_chiplet_set_fan_or_usb_load_switch(bool enabled) { set_gpio_output(GPIOD, 3, enabled); } -void red_chiplet_init(void) { +static void red_chiplet_init(void) { common_init_gpio(); // A8, A3: OBD_SBU1_RELAY, OBD_SBU2_RELAY @@ -132,7 +136,7 @@ void red_chiplet_init(void) { red_chiplet_set_can_mode(CAN_MODE_NORMAL); } -harness_configuration red_chiplet_harness_config = { +static harness_configuration red_chiplet_harness_config = { .has_harness = true, .GPIO_SBU1 = GPIOC, .GPIO_SBU2 = GPIOA, diff --git a/panda/board/boards/tres.h b/panda/board/boards/tres.h index 91b94f68e222e9f..f0602ae60b105cc 100644 --- a/panda/board/boards/tres.h +++ b/panda/board/boards/tres.h @@ -1,35 +1,39 @@ +#pragma once + +#include "board_declarations.h" + // /////////////////////////// // Tres (STM32H7) + Harness // // /////////////////////////// -bool tres_ir_enabled; -bool tres_fan_enabled; -void tres_update_fan_ir_power(void) { +static bool tres_ir_enabled; +static bool tres_fan_enabled; +static void tres_update_fan_ir_power(void) { red_chiplet_set_fan_or_usb_load_switch(tres_ir_enabled || tres_fan_enabled); } -void tres_set_ir_power(uint8_t percentage){ +static void tres_set_ir_power(uint8_t percentage){ tres_ir_enabled = (percentage > 0U); tres_update_fan_ir_power(); pwm_set(TIM3, 4, percentage); } -void tres_set_bootkick(BootState state) { +static void tres_set_bootkick(BootState state) { set_gpio_output(GPIOA, 0, state != BOOT_BOOTKICK); set_gpio_output(GPIOC, 12, state != BOOT_RESET); } -void tres_set_fan_enabled(bool enabled) { +static void tres_set_fan_enabled(bool enabled) { // NOTE: fan controller reset doesn't work on a tres if IR is enabled tres_fan_enabled = enabled; tres_update_fan_ir_power(); } -bool tres_read_som_gpio (void) { +static bool tres_read_som_gpio (void) { return (get_gpio_input(GPIOC, 2) != 0); } -void tres_init(void) { +static void tres_init(void) { // Enable USB 3.3V LDO for USB block register_set_bits(&(PWR->CR3), PWR_CR3_USBREGEN); register_set_bits(&(PWR->CR3), PWR_CR3_USB33DEN); @@ -42,8 +46,9 @@ void tres_init(void) { set_gpio_pullup(GPIOC, 2, PULL_DOWN); // SOM bootkick + reset lines - set_gpio_mode(GPIOC, 12, MODE_OUTPUT); + // WARNING: make sure output state is set before configuring as output tres_set_bootkick(BOOT_BOOTKICK); + set_gpio_mode(GPIOC, 12, MODE_OUTPUT); // SOM debugging UART gpio_uart7_init(); @@ -64,7 +69,6 @@ void tres_init(void) { set_gpio_alternate(GPIOC, 10, GPIO_AF4_I2C5); set_gpio_alternate(GPIOC, 11, GPIO_AF4_I2C5); register_set_bits(&(GPIOC->OTYPER), GPIO_OTYPER_OT10 | GPIO_OTYPER_OT11); // open drain - fake_siren_init(); // Clock source clock_source_init(); @@ -76,6 +80,7 @@ board board_tres = { .has_spi = true, .has_canfd = true, .fan_max_rpm = 6600U, + .fan_max_pwm = 100U, .avdd_mV = 1800U, .fan_stall_recovery = false, .fan_enable_cooldown_time = 3U, @@ -92,5 +97,6 @@ board board_tres = { .set_ir_power = tres_set_ir_power, .set_siren = fake_siren_set, .set_bootkick = tres_set_bootkick, - .read_som_gpio = tres_read_som_gpio + .read_som_gpio = tres_read_som_gpio, + .set_amp_enabled = unused_set_amp_enabled }; diff --git a/panda/board/boards/uno.h b/panda/board/boards/uno.h index a2e1e983542808c..d1728f1f9fb1ef3 100644 --- a/panda/board/boards/uno.h +++ b/panda/board/boards/uno.h @@ -1,8 +1,12 @@ +#pragma once + +#include "board_declarations.h" + // /////////////////////// // // Uno (STM32F4) + Harness // // /////////////////////// // -void uno_enable_can_transceiver(uint8_t transceiver, bool enabled) { +static void uno_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver){ case 1U: set_gpio_output(GPIOC, 1, !enabled); @@ -22,7 +26,7 @@ void uno_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -void uno_enable_can_transceivers(bool enabled) { +static void uno_enable_can_transceivers(bool enabled) { for(uint8_t i=1U; i<=4U; i++){ // Leave main CAN always on for CAN-based ignition detection if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ @@ -33,7 +37,7 @@ void uno_enable_can_transceivers(bool enabled) { } } -void uno_set_led(uint8_t color, bool enabled) { +static void uno_set_led(uint8_t color, bool enabled) { switch (color){ case LED_RED: set_gpio_output(GPIOC, 9, !enabled); @@ -49,7 +53,7 @@ void uno_set_led(uint8_t color, bool enabled) { } } -void uno_set_bootkick(BootState state) { +static void uno_set_bootkick(BootState state) { if (state == BOOT_BOOTKICK) { set_gpio_output(GPIOB, 14, false); } else { @@ -58,7 +62,7 @@ void uno_set_bootkick(BootState state) { } } -void uno_set_can_mode(uint8_t mode) { +static void uno_set_can_mode(uint8_t mode) { uno_enable_can_transceiver(2U, false); uno_enable_can_transceiver(4U, false); switch (mode) { @@ -90,24 +94,24 @@ void uno_set_can_mode(uint8_t mode) { } } -bool uno_check_ignition(void){ +static bool uno_check_ignition(void){ // ignition is checked through harness return harness_check_ignition(); } -void uno_set_usb_switch(bool phone){ +static void uno_set_usb_switch(bool phone){ set_gpio_output(GPIOB, 3, phone); } -void uno_set_ir_power(uint8_t percentage){ +static void uno_set_ir_power(uint8_t percentage){ pwm_set(TIM4, 2, percentage); } -void uno_set_fan_enabled(bool enabled){ +static void uno_set_fan_enabled(bool enabled){ set_gpio_output(GPIOA, 1, enabled); } -void uno_init(void) { +static void uno_init(void) { common_init_gpio(); // A8,A15: normal CAN3 mode @@ -170,14 +174,14 @@ void uno_init(void) { uno_set_bootkick(BOOT_BOOTKICK); } -void uno_init_bootloader(void) { +static void uno_init_bootloader(void) { // GPS off set_gpio_output(GPIOB, 1, 0); set_gpio_output(GPIOC, 5, 0); set_gpio_output(GPIOC, 12, 0); } -harness_configuration uno_harness_config = { +static harness_configuration uno_harness_config = { .has_harness = true, .GPIO_SBU1 = GPIOC, .GPIO_SBU2 = GPIOC, @@ -197,6 +201,7 @@ board board_uno = { .has_spi = false, .has_canfd = false, .fan_max_rpm = 5100U, + .fan_max_pwm = 100U, .avdd_mV = 3300U, .fan_stall_recovery = false, .fan_enable_cooldown_time = 0U, @@ -213,5 +218,6 @@ board board_uno = { .set_ir_power = uno_set_ir_power, .set_siren = unused_set_siren, .set_bootkick = uno_set_bootkick, - .read_som_gpio = unused_read_som_gpio + .read_som_gpio = unused_read_som_gpio, + .set_amp_enabled = unused_set_amp_enabled }; diff --git a/panda/board/boards/unused_funcs.h b/panda/board/boards/unused_funcs.h index 7bfde01391eea89..588cf63654d0563 100644 --- a/panda/board/boards/unused_funcs.h +++ b/panda/board/boards/unused_funcs.h @@ -1,3 +1,5 @@ +#pragma once + void unused_init_bootloader(void) { } @@ -23,4 +25,8 @@ void unused_set_bootkick(BootState state) { bool unused_read_som_gpio(void) { return false; -} \ No newline at end of file +} + +void unused_set_amp_enabled(bool enabled) { + UNUSED(enabled); +} diff --git a/panda/board/boards/white.h b/panda/board/boards/white.h index 8d22afbc9b4fa41..c4a2559353083db 100644 --- a/panda/board/boards/white.h +++ b/panda/board/boards/white.h @@ -1,8 +1,12 @@ +#pragma once + +#include "board_declarations.h" + // ///////////////////// // // White Panda (STM32F4) // // ///////////////////// // -void white_enable_can_transceiver(uint8_t transceiver, bool enabled) { +static void white_enable_can_transceiver(uint8_t transceiver, bool enabled) { switch (transceiver){ case 1U: set_gpio_output(GPIOC, 1, !enabled); @@ -19,14 +23,14 @@ void white_enable_can_transceiver(uint8_t transceiver, bool enabled) { } } -void white_enable_can_transceivers(bool enabled) { +static void white_enable_can_transceivers(bool enabled) { uint8_t t1 = enabled ? 1U : 2U; // leave transceiver 1 enabled to detect CAN ignition for(uint8_t i=t1; i<=3U; i++) { white_enable_can_transceiver(i, enabled); } } -void white_set_led(uint8_t color, bool enabled) { +static void white_set_led(uint8_t color, bool enabled) { switch (color){ case LED_RED: set_gpio_output(GPIOC, 9, !enabled); @@ -42,7 +46,7 @@ void white_set_led(uint8_t color, bool enabled) { } } -void white_set_usb_power_mode(uint8_t mode){ +static void white_set_usb_power_mode(uint8_t mode){ switch (mode) { case USB_POWER_CLIENT: // B2,A13: set client mode @@ -65,7 +69,7 @@ void white_set_usb_power_mode(uint8_t mode){ } } -void white_set_can_mode(uint8_t mode){ +static void white_set_can_mode(uint8_t mode){ if (mode == CAN_MODE_NORMAL) { // B12,B13: disable GMLAN mode set_gpio_mode(GPIOB, 12, MODE_INPUT); @@ -85,21 +89,21 @@ void white_set_can_mode(uint8_t mode){ } } -uint32_t white_read_voltage_mV(void){ +static uint32_t white_read_voltage_mV(void){ return adc_get_mV(12) * 11U; } -uint32_t white_read_current_mA(void){ +static 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){ +static bool white_check_ignition(void){ // ignition is on PA1 return !get_gpio_input(GPIOA, 1); } -void white_grey_init(void) { +static void white_grey_init(void) { common_init_gpio(); // C3: current sense @@ -174,13 +178,13 @@ void white_grey_init(void) { set_gpio_output(GPIOC, 14, 0); } -void white_grey_init_bootloader(void) { +static void white_grey_init_bootloader(void) { // ESP/GPS off set_gpio_output(GPIOC, 5, 0); set_gpio_output(GPIOC, 14, 0); } -harness_configuration white_harness_config = { +static harness_configuration white_harness_config = { .has_harness = false }; @@ -191,6 +195,7 @@ board board_white = { .has_spi = false, .has_canfd = false, .fan_max_rpm = 0U, + .fan_max_pwm = 100U, .avdd_mV = 3300U, .fan_stall_recovery = false, .fan_enable_cooldown_time = 0U, @@ -206,5 +211,6 @@ board board_white = { .set_fan_enabled = unused_set_fan_enabled, .set_ir_power = unused_set_ir_power, .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio + .read_som_gpio = unused_read_som_gpio, + .set_amp_enabled = unused_set_amp_enabled }; diff --git a/panda/board/can.h b/panda/board/can.h new file mode 100644 index 000000000000000..9b1200384de44ad --- /dev/null +++ b/panda/board/can.h @@ -0,0 +1,7 @@ +#pragma once +#include "can_declarations.h" + +static const uint8_t PANDA_CAN_CNT = 3U; +static const uint8_t PANDA_BUS_CNT = 3U; + +static const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U}; diff --git a/panda/board/can_comms.h b/panda/board/can_comms.h index c8f071abd570a4d..99ee968b0a0325b 100644 --- a/panda/board/can_comms.h +++ b/panda/board/can_comms.h @@ -18,7 +18,7 @@ typedef struct { uint8_t data[72]; } asm_buffer; -asm_buffer can_read_buffer = {.ptr = 0U, .tail_size = 0U}; +static asm_buffer can_read_buffer = {.ptr = 0U, .tail_size = 0U}; int comms_can_read(uint8_t *data, uint32_t max_len) { uint32_t pos = 0U; @@ -38,10 +38,10 @@ int comms_can_read(uint8_t *data, uint32_t max_len) { while ((pos < max_len) && can_pop(&can_rx_q, &can_packet)) { uint32_t pckt_len = CANPACKET_HEAD_SIZE + dlc_to_len[can_packet.data_len_code]; if ((pos + pckt_len) <= max_len) { - (void)memcpy(&data[pos], &can_packet, pckt_len); + (void)memcpy(&data[pos], (uint8_t*)&can_packet, pckt_len); pos += pckt_len; } else { - (void)memcpy(&data[pos], &can_packet, max_len - pos); + (void)memcpy(&data[pos], (uint8_t*)&can_packet, max_len - pos); can_read_buffer.ptr += pckt_len - (max_len - pos); // cppcheck-suppress objectIndex (void)memcpy(can_read_buffer.data, &((uint8_t*)&can_packet)[(max_len - pos)], can_read_buffer.ptr); @@ -53,7 +53,7 @@ int comms_can_read(uint8_t *data, uint32_t max_len) { return pos; } -asm_buffer can_write_buffer = {.ptr = 0U, .tail_size = 0U}; +static asm_buffer can_write_buffer = {.ptr = 0U, .tail_size = 0U}; // send on CAN void comms_can_write(const uint8_t *data, uint32_t len) { @@ -69,7 +69,7 @@ void comms_can_write(const uint8_t *data, uint32_t len) { pos += can_write_buffer.tail_size; // send out - (void)memcpy(&to_push, can_write_buffer.data, can_write_buffer.ptr); + (void)memcpy((uint8_t*)&to_push, can_write_buffer.data, can_write_buffer.ptr); can_send(&to_push, to_push.bus, false); // reset overflow buffer @@ -90,7 +90,7 @@ void comms_can_write(const uint8_t *data, uint32_t len) { uint32_t pckt_len = CANPACKET_HEAD_SIZE + dlc_to_len[(data[pos] >> 4U)]; if ((pos + pckt_len) <= len) { CANPacket_t to_push = {0}; - (void)memcpy(&to_push, &data[pos], pckt_len); + (void)memcpy((uint8_t*)&to_push, &data[pos], pckt_len); can_send(&to_push, to_push.bus, false); pos += pckt_len; } else { diff --git a/panda/board/can_declarations.h b/panda/board/can_declarations.h new file mode 100644 index 000000000000000..569e2939acfca6c --- /dev/null +++ b/panda/board/can_declarations.h @@ -0,0 +1,29 @@ +#pragma once + +// bump this when changing the CAN packet +#define CAN_PACKET_VERSION 4 + +#define CANPACKET_HEAD_SIZE 6U + +#if !defined(STM32F4) + #define CANFD + #define CANPACKET_DATA_SIZE_MAX 64U +#else + #define CANPACKET_DATA_SIZE_MAX 8U +#endif + +typedef struct { + unsigned char reserved : 1; + unsigned char bus : 3; + unsigned char data_len_code : 4; // lookup length with dlc_to_len + unsigned char rejected : 1; + unsigned char returned : 1; + unsigned char extended : 1; + unsigned int addr : 29; + unsigned char checksum; + unsigned char data[CANPACKET_DATA_SIZE_MAX]; +} __attribute__((packed, aligned(4))) CANPacket_t; + +#define GET_BUS(msg) ((msg)->bus) +#define GET_LEN(msg) (dlc_to_len[(msg)->data_len_code]) +#define GET_ADDR(msg) ((msg)->addr) diff --git a/panda/board/can_definitions.h b/panda/board/can_definitions.h deleted file mode 100644 index f3ce4378276ef53..000000000000000 --- a/panda/board/can_definitions.h +++ /dev/null @@ -1,34 +0,0 @@ -#pragma once - -const uint8_t PANDA_CAN_CNT = 3U; -const uint8_t PANDA_BUS_CNT = 3U; - -// bump this when changing the CAN packet -#define CAN_PACKET_VERSION 4 - -#define CANPACKET_HEAD_SIZE 6U - -#if !defined(STM32F4) - #define CANFD - #define CANPACKET_DATA_SIZE_MAX 64U -#else - #define CANPACKET_DATA_SIZE_MAX 8U -#endif - -typedef struct { - unsigned char reserved : 1; - unsigned char bus : 3; - unsigned char data_len_code : 4; // lookup length with dlc_to_len - unsigned char rejected : 1; - unsigned char returned : 1; - unsigned char extended : 1; - unsigned int addr : 29; - unsigned char checksum; - unsigned char data[CANPACKET_DATA_SIZE_MAX]; -} __attribute__((packed, aligned(4))) CANPacket_t; - -const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U}; - -#define GET_BUS(msg) ((msg)->bus) -#define GET_LEN(msg) (dlc_to_len[(msg)->data_len_code]) -#define GET_ADDR(msg) ((msg)->addr) diff --git a/panda/board/critical.h b/panda/board/critical.h index c8cf52c7a115330..ae2d5c0a699d8bc 100644 --- a/panda/board/critical.h +++ b/panda/board/critical.h @@ -1,5 +1,9 @@ +#include "critical_declarations.h" + // ********************* Critical section helpers ********************* -volatile bool interrupts_enabled = false; +uint8_t global_critical_depth = 0U; + +static volatile bool interrupts_enabled = false; void enable_interrupts(void) { interrupts_enabled = true; @@ -10,14 +14,3 @@ void disable_interrupts(void) { interrupts_enabled = false; __disable_irq(); } - -uint8_t global_critical_depth = 0U; -#define ENTER_CRITICAL() \ - __disable_irq(); \ - global_critical_depth += 1U; - -#define EXIT_CRITICAL() \ - global_critical_depth -= 1U; \ - if ((global_critical_depth == 0U) && interrupts_enabled) { \ - __enable_irq(); \ - } diff --git a/panda/board/critical_declarations.h b/panda/board/critical_declarations.h new file mode 100644 index 000000000000000..42211d46c38b4f2 --- /dev/null +++ b/panda/board/critical_declarations.h @@ -0,0 +1,17 @@ +#pragma once + +// ********************* Critical section helpers ********************* +void enable_interrupts(void); +void disable_interrupts(void); + +extern uint8_t global_critical_depth; + +#define ENTER_CRITICAL() \ + __disable_irq(); \ + global_critical_depth += 1U; + +#define EXIT_CRITICAL() \ + global_critical_depth -= 1U; \ + if ((global_critical_depth == 0U) && interrupts_enabled) { \ + __enable_irq(); \ + } diff --git a/panda/board/debug/debug_h7.sh b/panda/board/debug/debug_h7.sh index a2bd88434e2bbda..126a9c378c9cd58 100755 --- a/panda/board/debug/debug_h7.sh +++ b/panda/board/debug/debug_h7.sh @@ -1,3 +1,4 @@ -#!/bin/bash -e +#!/usr/bin/env bash +set -e sudo openocd -f "interface/stlink.cfg" -c "transport select hla_swd" -f "target/stm32h7x.cfg" -c "init" diff --git a/panda/board/drivers/beeper.h b/panda/board/drivers/beeper.h new file mode 100644 index 000000000000000..0ae02ff5e69cbfe --- /dev/null +++ b/panda/board/drivers/beeper.h @@ -0,0 +1,26 @@ + +#define BEEPER_COUNTER_OVERFLOW 25000U // 4kHz + +void beeper_enable(bool enabled) { + if (enabled) { + register_set_bits(&(TIM4->CCER), TIM_CCER_CC3E); + } else { + register_clear_bits(&(TIM4->CCER), TIM_CCER_CC3E); + } +} + +void beeper_init(void) { + // Enable timer and auto-reload + register_set(&(TIM4->CR1), TIM_CR1_CEN | TIM_CR1_ARPE, 0x3FU); + + // Set channel as PWM mode 1 and disable output + register_set_bits(&(TIM4->CCMR2), (TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3PE)); + beeper_enable(false); + + // Set max counter value and compare to get 50% duty + register_set(&(TIM4->CCR3), BEEPER_COUNTER_OVERFLOW / 2U, 0xFFFFU); + register_set(&(TIM4->ARR), BEEPER_COUNTER_OVERFLOW, 0xFFFFU); + + // Update registers and clear counter + TIM4->EGR |= TIM_EGR_UG; +} diff --git a/panda/board/drivers/bootkick.h b/panda/board/drivers/bootkick.h index 4b75f09088d21e1..eab7da3ebc4d8bf 100644 --- a/panda/board/drivers/bootkick.h +++ b/panda/board/drivers/bootkick.h @@ -1,13 +1,14 @@ -bool bootkick_ign_prev = false; -BootState boot_state = BOOT_BOOTKICK; -uint8_t bootkick_harness_status_prev = HARNESS_STATUS_NC; +#include "bootkick_declarations.h" -uint8_t boot_reset_countdown = 0; -uint8_t waiting_to_boot_countdown = 0; bool bootkick_reset_triggered = false; -uint16_t bootkick_last_serial_ptr = 0; void bootkick_tick(bool ignition, bool recent_heartbeat) { + static uint16_t bootkick_last_serial_ptr = 0; + static uint8_t waiting_to_boot_countdown = 0; + static uint8_t boot_reset_countdown = 0; + static uint8_t bootkick_harness_status_prev = HARNESS_STATUS_NC; + static bool bootkick_ign_prev = false; + static BootState boot_state = BOOT_BOOTKICK; BootState boot_state_prev = boot_state; const bool harness_inserted = (harness.status != bootkick_harness_status_prev) && (harness.status != HARNESS_STATUS_NC); diff --git a/panda/board/drivers/bootkick_declarations.h b/panda/board/drivers/bootkick_declarations.h new file mode 100644 index 000000000000000..3b55b72ac662f0e --- /dev/null +++ b/panda/board/drivers/bootkick_declarations.h @@ -0,0 +1,5 @@ +#pragma once + +extern bool bootkick_reset_triggered; + +void bootkick_tick(bool ignition, bool recent_heartbeat); diff --git a/panda/board/drivers/bxcan.h b/panda/board/drivers/bxcan.h index 27ffcee525c7346..e4c72c61aa017a7 100644 --- a/panda/board/drivers/bxcan.h +++ b/panda/board/drivers/bxcan.h @@ -1,9 +1,11 @@ +#include "bxcan_declarations.h" + // IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE // CAN2_TX, CAN2_RX0, CAN2_SCE // CAN3_TX, CAN3_RX0, CAN3_SCE -CAN_TypeDef *cans[] = {CAN1, CAN2, CAN3}; -uint8_t can_irq_number[3][3] = { +CAN_TypeDef *cans[CAN_ARRAY_SIZE] = {CAN1, CAN2, CAN3}; +uint8_t can_irq_number[CAN_IRQS_ARRAY_SIZE][CAN_IRQS_ARRAY_SIZE] = { { CAN1_TX_IRQn, CAN1_RX0_IRQn, CAN1_SCE_IRQn }, { CAN2_TX_IRQn, CAN2_RX0_IRQn, CAN2_SCE_IRQn }, { CAN3_TX_IRQn, CAN3_RX0_IRQn, CAN3_SCE_IRQn }, @@ -23,6 +25,11 @@ bool can_set_speed(uint8_t can_number) { return ret; } +void can_clear_send(CAN_TypeDef *CANx, uint8_t can_number) { + can_health[can_number].can_core_reset_cnt += 1U; + llcan_clear_send(CANx); +} + 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; @@ -52,14 +59,13 @@ void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) { can_health[can_number].total_rx_lost_cnt += 1U; CANx->RF0R &= ~(CAN_RF0R_FOVR0); } - can_health[can_number].can_core_reset_cnt += 1U; - llcan_clear_send(CANx); + can_clear_send(CANx, can_number); } } // ***************************** CAN ***************************** // CANx_SCE IRQ Handler -void can_sce(uint8_t can_number) { +static void can_sce(uint8_t can_number) { update_can_health_pkt(can_number, 1U); } @@ -177,17 +183,17 @@ void can_rx(uint8_t can_number) { } } -void CAN1_TX_IRQ_Handler(void) { process_can(0); } -void CAN1_RX0_IRQ_Handler(void) { can_rx(0); } -void CAN1_SCE_IRQ_Handler(void) { can_sce(0); } +static void CAN1_TX_IRQ_Handler(void) { process_can(0); } +static void CAN1_RX0_IRQ_Handler(void) { can_rx(0); } +static void CAN1_SCE_IRQ_Handler(void) { can_sce(0); } -void CAN2_TX_IRQ_Handler(void) { process_can(1); } -void CAN2_RX0_IRQ_Handler(void) { can_rx(1); } -void CAN2_SCE_IRQ_Handler(void) { can_sce(1); } +static void CAN2_TX_IRQ_Handler(void) { process_can(1); } +static void CAN2_RX0_IRQ_Handler(void) { can_rx(1); } +static void CAN2_SCE_IRQ_Handler(void) { can_sce(1); } -void CAN3_TX_IRQ_Handler(void) { process_can(2); } -void CAN3_RX0_IRQ_Handler(void) { can_rx(2); } -void CAN3_SCE_IRQ_Handler(void) { can_sce(2); } +static void CAN3_TX_IRQ_Handler(void) { process_can(2); } +static void CAN3_RX0_IRQ_Handler(void) { can_rx(2); } +static void CAN3_SCE_IRQ_Handler(void) { can_sce(2); } bool can_init(uint8_t can_number) { bool ret = false; diff --git a/panda/board/drivers/bxcan_declarations.h b/panda/board/drivers/bxcan_declarations.h new file mode 100644 index 000000000000000..c0ed577943828e6 --- /dev/null +++ b/panda/board/drivers/bxcan_declarations.h @@ -0,0 +1,22 @@ +#pragma once + +// IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE +// CAN2_TX, CAN2_RX0, CAN2_SCE +// CAN3_TX, CAN3_RX0, CAN3_SCE + +#define CAN_ARRAY_SIZE 3 +#define CAN_IRQS_ARRAY_SIZE 3 +extern CAN_TypeDef *cans[CAN_ARRAY_SIZE]; +extern uint8_t can_irq_number[CAN_IRQS_ARRAY_SIZE][CAN_IRQS_ARRAY_SIZE]; + +bool can_set_speed(uint8_t can_number); +void can_clear_send(CAN_TypeDef *CANx, uint8_t can_number); +void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg); + +// ***************************** CAN ***************************** +// CANx_TX IRQ Handler +void process_can(uint8_t can_number); +// CANx_RX0 IRQ Handler +// blink blue when we are receiving CAN messages +void can_rx(uint8_t can_number); +bool can_init(uint8_t can_number); diff --git a/panda/board/drivers/can_common.h b/panda/board/drivers/can_common.h index 3a829c69ab62ac1..5a074e775cf5ca1 100644 --- a/panda/board/drivers/can_common.h +++ b/panda/board/drivers/can_common.h @@ -1,54 +1,25 @@ -typedef struct { - volatile uint32_t w_ptr; - volatile uint32_t r_ptr; - uint32_t fifo_size; - CANPacket_t *elems; -} can_ring; - -typedef struct { - uint8_t bus_lookup; - uint8_t can_num_lookup; - int8_t forwarding_bus; - uint32_t can_speed; - uint32_t can_data_speed; - bool canfd_enabled; - bool brs_enabled; - bool canfd_non_iso; -} bus_config_t; +#include "can_common_declarations.h" uint32_t safety_tx_blocked = 0; uint32_t safety_rx_invalid = 0; uint32_t tx_buffer_overflow = 0; uint32_t rx_buffer_overflow = 0; -can_health_t can_health[] = {{0}, {0}, {0}}; - -extern int can_live; -extern int pending_can_live; - -// must reinit after changing these -extern int can_silent; -extern bool can_loopback; +can_health_t can_health[CAN_HEALTH_ARRAY_SIZE] = {{0}, {0}, {0}}; // Ignition detected from CAN meessages bool ignition_can = false; uint32_t ignition_can_cnt = 0U; -#define ALL_CAN_SILENT 0xFF -#define ALL_CAN_LIVE 0 - int can_live = 0; int pending_can_live = 0; int can_silent = ALL_CAN_SILENT; bool can_loopback = false; -// ******************* functions prototypes ********************* -bool can_init(uint8_t can_number); -void process_can(uint8_t can_number); - // ********************* instantiate queues ********************* #define can_buffer(x, size) \ - CANPacket_t elems_##x[size]; \ + static CANPacket_t elems_##x[size]; \ + extern can_ring can_##x; \ can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = (size), .elems = (CANPacket_t *)&(elems_##x) }; #define CAN_RX_BUFFER_SIZE 4096U @@ -68,11 +39,7 @@ can_buffer(tx3_q, CAN_TX_BUFFER_SIZE) // FIXME: // cppcheck-suppress misra-c2012-9.3 -can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q}; - -// helpers -#define WORD_TO_BYTE_ARRAY(dst8, src32) 0[dst8] = ((src32) & 0xFFU); 1[dst8] = (((src32) >> 8U) & 0xFFU); 2[dst8] = (((src32) >> 16U) & 0xFFU); 3[dst8] = (((src32) >> 24U) & 0xFFU) -#define BYTE_ARRAY_TO_WORD(dst32, src8) ((dst32) = 0[src8] | (1[src8] << 8U) | (2[src8] << 16U) | (3[src8] << 24U)) +can_ring *can_queues[CAN_QUEUES_ARRAY_SIZE] = {&can_tx1_q, &can_tx2_q, &can_tx3_q}; // ********************* interrupt safe queue ********************* bool can_pop(can_ring *q, CANPacket_t *elem) { @@ -163,17 +130,13 @@ void can_clear(can_ring *q) { // Helpers // Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3 -bus_config_t bus_config[] = { +bus_config_t bus_config[BUS_CONFIG_ARRAY_SIZE] = { { .bus_lookup = 0U, .can_num_lookup = 0U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false }, { .bus_lookup = 1U, .can_num_lookup = 1U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false }, { .bus_lookup = 2U, .can_num_lookup = 2U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false }, { .bus_lookup = 0xFFU, .can_num_lookup = 0xFFU, .forwarding_bus = -1, .can_speed = 333U, .can_data_speed = 333U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false }, }; -#define CANIF_FROM_CAN_NUM(num) (cans[num]) -#define BUS_NUM_FROM_CAN_NUM(num) (bus_config[num].bus_lookup) -#define CAN_NUM_FROM_BUS_NUM(num) (bus_config[num].can_num_lookup) - void can_init_all(void) { for (uint8_t i=0U; i < PANDA_CAN_CNT; i++) { if (!current_board->has_canfd) { @@ -191,9 +154,11 @@ void can_set_orientation(bool flipped) { bus_config[2].can_num_lookup = flipped ? 0U : 2U; } +#ifdef PANDA_JUNGLE void can_set_forwarding(uint8_t from, uint8_t to) { bus_config[from].forwarding_bus = to; } +#endif void ignition_can_hook(CANPacket_t *to_push) { int bus = GET_BUS(to_push); diff --git a/panda/board/drivers/can_common_declarations.h b/panda/board/drivers/can_common_declarations.h new file mode 100644 index 000000000000000..1a3518c2a856c16 --- /dev/null +++ b/panda/board/drivers/can_common_declarations.h @@ -0,0 +1,87 @@ +#pragma once + +typedef struct { + volatile uint32_t w_ptr; + volatile uint32_t r_ptr; + uint32_t fifo_size; + CANPacket_t *elems; +} can_ring; + +typedef struct { + uint8_t bus_lookup; + uint8_t can_num_lookup; + int8_t forwarding_bus; + uint32_t can_speed; + uint32_t can_data_speed; + bool canfd_enabled; + bool brs_enabled; + bool canfd_non_iso; +} bus_config_t; + +extern uint32_t safety_tx_blocked; +extern uint32_t safety_rx_invalid; +extern uint32_t tx_buffer_overflow; +extern uint32_t rx_buffer_overflow; + +#define CAN_HEALTH_ARRAY_SIZE 3 +extern can_health_t can_health[CAN_HEALTH_ARRAY_SIZE]; + +// Ignition detected from CAN meessages +extern bool ignition_can; +extern uint32_t ignition_can_cnt; + +#define ALL_CAN_SILENT 0xFF +#define ALL_CAN_LIVE 0 + +extern int can_live; +extern int pending_can_live; +extern int can_silent; +extern bool can_loopback; + +// ******************* functions prototypes ********************* +bool can_init(uint8_t can_number); +void process_can(uint8_t can_number); + +// ********************* instantiate queues ********************* +#define CAN_QUEUES_ARRAY_SIZE 3 +extern can_ring *can_queues[CAN_QUEUES_ARRAY_SIZE]; + +// helpers +#define WORD_TO_BYTE_ARRAY(dst8, src32) 0[dst8] = ((src32) & 0xFFU); 1[dst8] = (((src32) >> 8U) & 0xFFU); 2[dst8] = (((src32) >> 16U) & 0xFFU); 3[dst8] = (((src32) >> 24U) & 0xFFU) +#define BYTE_ARRAY_TO_WORD(dst32, src8) ((dst32) = 0[src8] | (1[src8] << 8U) | (2[src8] << 16U) | (3[src8] << 24U)) + +// ********************* interrupt safe queue ********************* +bool can_pop(can_ring *q, CANPacket_t *elem); +bool can_push(can_ring *q, const CANPacket_t *elem); +uint32_t can_slots_empty(const can_ring *q); + +// assign CAN numbering +// bus num: CAN Bus numbers in panda, sent to/from USB +// Min: 0; Max: 127; Bit 7 marks message as receipt (bus 129 is receipt for but 1) +// cans: Look up MCU can interface from bus number +// can number: numeric lookup for MCU CAN interfaces (0 = CAN1, 1 = CAN2, etc); +// bus_lookup: Translates from 'can number' to 'bus number'. +// can_num_lookup: Translates from 'bus number' to 'can number'. +// forwarding bus: If >= 0, forward all messages from this bus to the specified bus. + +// Helpers +// Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3 +#define BUS_CONFIG_ARRAY_SIZE 4 +extern bus_config_t bus_config[BUS_CONFIG_ARRAY_SIZE]; + +#define CANIF_FROM_CAN_NUM(num) (cans[num]) +#define BUS_NUM_FROM_CAN_NUM(num) (bus_config[num].bus_lookup) +#define CAN_NUM_FROM_BUS_NUM(num) (bus_config[num].can_num_lookup) + +void can_init_all(void); +void can_set_orientation(bool flipped); +#ifdef PANDA_JUNGLE +void can_set_forwarding(uint8_t from, uint8_t to); +#endif +void ignition_can_hook(CANPacket_t *to_push); +bool can_tx_check_min_slots_free(uint32_t min); +uint8_t calculate_checksum(const uint8_t *dat, uint32_t len); +void can_set_checksum(CANPacket_t *packet); +bool can_check_checksum(CANPacket_t *packet); +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 *all_speeds, uint8_t len); diff --git a/panda/board/drivers/clock_source.h b/panda/board/drivers/clock_source.h index 5d6fdc8a77b5287..18d12d579a295ed 100644 --- a/panda/board/drivers/clock_source.h +++ b/panda/board/drivers/clock_source.h @@ -1,5 +1,4 @@ -#define CLOCK_SOURCE_PERIOD_MS 50U -#define CLOCK_SOURCE_PULSE_LEN_MS 2U +#include "clock_source_declarations.h" void clock_source_set_period(uint8_t period) { register_set(&(TIM1->ARR), ((period*10U) - 1U), 0xFFFFU); diff --git a/panda/board/drivers/clock_source_declarations.h b/panda/board/drivers/clock_source_declarations.h new file mode 100644 index 000000000000000..013f75303a9a650 --- /dev/null +++ b/panda/board/drivers/clock_source_declarations.h @@ -0,0 +1,7 @@ +#pragma once + +#define CLOCK_SOURCE_PERIOD_MS 50U +#define CLOCK_SOURCE_PULSE_LEN_MS 2U + +void clock_source_set_period(uint8_t period); +void clock_source_init(void); diff --git a/panda/board/drivers/fake_siren.h b/panda/board/drivers/fake_siren.h index 7c73be0b1c34932..9468afd806a7678 100644 --- a/panda/board/drivers/fake_siren.h +++ b/panda/board/drivers/fake_siren.h @@ -2,10 +2,7 @@ #define CODEC_I2C_ADDR 0x10 -// 1Vpp sine wave with 1V offset -const uint8_t fake_siren_lut[360] = { 134U, 135U, 137U, 138U, 139U, 140U, 141U, 143U, 144U, 145U, 146U, 148U, 149U, 150U, 151U, 152U, 154U, 155U, 156U, 157U, 158U, 159U, 160U, 162U, 163U, 164U, 165U, 166U, 167U, 168U, 169U, 170U, 171U, 172U, 174U, 175U, 176U, 177U, 177U, 178U, 179U, 180U, 181U, 182U, 183U, 184U, 185U, 186U, 186U, 187U, 188U, 189U, 190U, 190U, 191U, 192U, 193U, 193U, 194U, 195U, 195U, 196U, 196U, 197U, 197U, 198U, 199U, 199U, 199U, 200U, 200U, 201U, 201U, 202U, 202U, 202U, 203U, 203U, 203U, 203U, 204U, 204U, 204U, 204U, 204U, 204U, 204U, 205U, 205U, 205U, 205U, 205U, 205U, 205U, 204U, 204U, 204U, 204U, 204U, 204U, 204U, 203U, 203U, 203U, 203U, 202U, 202U, 202U, 201U, 201U, 200U, 200U, 199U, 199U, 199U, 198U, 197U, 197U, 196U, 196U, 195U, 195U, 194U, 193U, 193U, 192U, 191U, 190U, 190U, 189U, 188U, 187U, 186U, 186U, 185U, 184U, 183U, 182U, 181U, 180U, 179U, 178U, 177U, 177U, 176U, 175U, 174U, 172U, 171U, 170U, 169U, 168U, 167U, 166U, 165U, 164U, 163U, 162U, 160U, 159U, 158U, 157U, 156U, 155U, 154U, 152U, 151U, 150U, 149U, 148U, 146U, 145U, 144U, 143U, 141U, 140U, 139U, 138U, 137U, 135U, 134U, 133U, 132U, 130U, 129U, 128U, 127U, 125U, 124U, 123U, 122U, 121U, 119U, 118U, 117U, 116U, 115U, 113U, 112U, 111U, 110U, 109U, 108U, 106U, 105U, 104U, 103U, 102U, 101U, 100U, 99U, 98U, 97U, 96U, 95U, 94U, 93U, 92U, 91U, 90U, 89U, 88U, 87U, 86U, 85U, 84U, 83U, 82U, 82U, 81U, 80U, 79U, 78U, 78U, 77U, 76U, 76U, 75U, 74U, 74U, 73U, 72U, 72U, 71U, 71U, 70U, 70U, 69U, 69U, 68U, 68U, 67U, 67U, 67U, 66U, 66U, 66U, 65U, 65U, 65U, 65U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 63U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 65U, 65U, 65U, 65U, 66U, 66U, 66U, 67U, 67U, 67U, 68U, 68U, 69U, 69U, 70U, 70U, 71U, 71U, 72U, 72U, 73U, 74U, 74U, 75U, 76U, 76U, 77U, 78U, 78U, 79U, 80U, 81U, 82U, 82U, 83U, 84U, 85U, 86U, 87U, 88U, 89U, 90U, 91U, 92U, 93U, 94U, 95U, 96U, 97U, 98U, 99U, 100U, 101U, 102U, 103U, 104U, 105U, 106U, 108U, 109U, 110U, 111U, 112U, 113U, 115U, 116U, 117U, 118U, 119U, 121U, 122U, 123U, 124U, 125U, 127U, 128U, 129U, 130U, 132U, 133U }; - -bool fake_siren_enabled = false; +void fake_siren_init(void); void fake_siren_codec_enable(bool enabled) { if (enabled) { @@ -33,6 +30,14 @@ void fake_siren_codec_enable(bool enabled) { void fake_siren_set(bool enabled) { + static bool initialized = false; + static bool fake_siren_enabled = false; + + if (!initialized) { + fake_siren_init(); + initialized = true; + } + if (enabled != fake_siren_enabled) { fake_siren_codec_enable(enabled); } @@ -46,6 +51,9 @@ void fake_siren_set(bool enabled) { } void fake_siren_init(void) { + // 1Vpp sine wave with 1V offset + static const uint8_t fake_siren_lut[360] = { 134U, 135U, 137U, 138U, 139U, 140U, 141U, 143U, 144U, 145U, 146U, 148U, 149U, 150U, 151U, 152U, 154U, 155U, 156U, 157U, 158U, 159U, 160U, 162U, 163U, 164U, 165U, 166U, 167U, 168U, 169U, 170U, 171U, 172U, 174U, 175U, 176U, 177U, 177U, 178U, 179U, 180U, 181U, 182U, 183U, 184U, 185U, 186U, 186U, 187U, 188U, 189U, 190U, 190U, 191U, 192U, 193U, 193U, 194U, 195U, 195U, 196U, 196U, 197U, 197U, 198U, 199U, 199U, 199U, 200U, 200U, 201U, 201U, 202U, 202U, 202U, 203U, 203U, 203U, 203U, 204U, 204U, 204U, 204U, 204U, 204U, 204U, 205U, 205U, 205U, 205U, 205U, 205U, 205U, 204U, 204U, 204U, 204U, 204U, 204U, 204U, 203U, 203U, 203U, 203U, 202U, 202U, 202U, 201U, 201U, 200U, 200U, 199U, 199U, 199U, 198U, 197U, 197U, 196U, 196U, 195U, 195U, 194U, 193U, 193U, 192U, 191U, 190U, 190U, 189U, 188U, 187U, 186U, 186U, 185U, 184U, 183U, 182U, 181U, 180U, 179U, 178U, 177U, 177U, 176U, 175U, 174U, 172U, 171U, 170U, 169U, 168U, 167U, 166U, 165U, 164U, 163U, 162U, 160U, 159U, 158U, 157U, 156U, 155U, 154U, 152U, 151U, 150U, 149U, 148U, 146U, 145U, 144U, 143U, 141U, 140U, 139U, 138U, 137U, 135U, 134U, 133U, 132U, 130U, 129U, 128U, 127U, 125U, 124U, 123U, 122U, 121U, 119U, 118U, 117U, 116U, 115U, 113U, 112U, 111U, 110U, 109U, 108U, 106U, 105U, 104U, 103U, 102U, 101U, 100U, 99U, 98U, 97U, 96U, 95U, 94U, 93U, 92U, 91U, 90U, 89U, 88U, 87U, 86U, 85U, 84U, 83U, 82U, 82U, 81U, 80U, 79U, 78U, 78U, 77U, 76U, 76U, 75U, 74U, 74U, 73U, 72U, 72U, 71U, 71U, 70U, 70U, 69U, 69U, 68U, 68U, 67U, 67U, 67U, 66U, 66U, 66U, 65U, 65U, 65U, 65U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 63U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 65U, 65U, 65U, 65U, 66U, 66U, 66U, 67U, 67U, 67U, 68U, 68U, 69U, 69U, 70U, 70U, 71U, 71U, 72U, 72U, 73U, 74U, 74U, 75U, 76U, 76U, 77U, 78U, 78U, 79U, 80U, 81U, 82U, 82U, 83U, 84U, 85U, 86U, 87U, 88U, 89U, 90U, 91U, 92U, 93U, 94U, 95U, 96U, 97U, 98U, 99U, 100U, 101U, 102U, 103U, 104U, 105U, 106U, 108U, 109U, 110U, 111U, 112U, 113U, 115U, 116U, 117U, 118U, 119U, 121U, 122U, 123U, 124U, 125U, 127U, 128U, 129U, 130U, 132U, 133U }; + // Init DAC register_set(&DAC1->MCR, 0U, 0xFFFFFFFFU); register_set(&DAC1->CR, DAC_CR_TEN1 | (6U << DAC_CR_TSEL1_Pos) | DAC_CR_DMAEN1, 0xFFFFFFFFU); diff --git a/panda/board/drivers/fan.h b/panda/board/drivers/fan.h index 15296079aef4f61..daadd23833dfed0 100644 --- a/panda/board/drivers/fan.h +++ b/panda/board/drivers/fan.h @@ -1,21 +1,9 @@ -struct fan_state_t { - uint16_t tach_counter; - uint16_t rpm; - uint16_t target_rpm; - uint8_t power; - float error_integral; - uint8_t stall_counter; - uint8_t stall_threshold; - uint8_t total_stall_count; - uint8_t cooldown_counter; -} fan_state_t; -struct fan_state_t fan_state; +#include "fan_declarations.h" -const float FAN_I = 0.001f; +struct fan_state_t fan_state; -const uint8_t FAN_TICK_FREQ = 8U; -const uint8_t FAN_STALL_THRESHOLD_MIN = 3U; -const uint8_t FAN_STALL_THRESHOLD_MAX = 8U; +static const uint8_t FAN_TICK_FREQ = 8U; +static const uint8_t FAN_STALL_THRESHOLD_MIN = 3U; void fan_set_power(uint8_t percentage) { @@ -31,6 +19,9 @@ void fan_init(void) { // Call this at FAN_TICK_FREQ void fan_tick(void) { + const float FAN_I = 0.001f; + const uint8_t FAN_STALL_THRESHOLD_MAX = 8U; + if (current_board->fan_max_rpm > 0U) { // Measure fan RPM uint16_t fan_rpm_fast = fan_state.tach_counter * (60U * FAN_TICK_FREQ / 4U); // 4 interrupts per rotation @@ -86,7 +77,7 @@ void fan_tick(void) { float error = fan_state.target_rpm - fan_rpm_fast; fan_state.error_integral += FAN_I * error; } - fan_state.power = CLAMP(fan_state.error_integral, 0U, 100U); + fan_state.power = CLAMP(fan_state.error_integral, 0U, current_board->fan_max_pwm); // Set PWM and enable line pwm_set(TIM3, 3, fan_state.power); diff --git a/panda/board/drivers/fan_declarations.h b/panda/board/drivers/fan_declarations.h new file mode 100644 index 000000000000000..4b7c1dc9e1fadc6 --- /dev/null +++ b/panda/board/drivers/fan_declarations.h @@ -0,0 +1,20 @@ +#pragma once + +struct fan_state_t { + uint16_t tach_counter; + uint16_t rpm; + uint16_t target_rpm; + uint8_t power; + float error_integral; + uint8_t stall_counter; + uint8_t stall_threshold; + uint8_t total_stall_count; + uint8_t cooldown_counter; +}; +extern struct fan_state_t fan_state; + +void fan_set_power(uint8_t percentage); +void llfan_init(void); +void fan_init(void); +// Call this at FAN_TICK_FREQ +void fan_tick(void); diff --git a/panda/board/drivers/fdcan.h b/panda/board/drivers/fdcan.h index 0ba228a9e666ef8..0144aa17c27ad6a 100644 --- a/panda/board/drivers/fdcan.h +++ b/panda/board/drivers/fdcan.h @@ -1,25 +1,8 @@ -// IRQs: FDCAN1_IT0, FDCAN1_IT1 -// FDCAN2_IT0, FDCAN2_IT1 -// FDCAN3_IT0, FDCAN3_IT1 +#include "fdcan_declarations.h" -#define CANFD +FDCAN_GlobalTypeDef *cans[CANS_ARRAY_SIZE] = {FDCAN1, FDCAN2, FDCAN3}; -typedef struct { - volatile uint32_t header[2]; - volatile uint32_t data_word[CANPACKET_DATA_SIZE_MAX/4U]; -} canfd_fifo; - -FDCAN_GlobalTypeDef *cans[] = {FDCAN1, FDCAN2, FDCAN3}; - -uint8_t can_irq_number[3][2] = { - { FDCAN1_IT0_IRQn, FDCAN1_IT1_IRQn }, - { FDCAN2_IT0_IRQn, FDCAN2_IT1_IRQn }, - { FDCAN3_IT0_IRQn, FDCAN3_IT1_IRQn }, -}; - -#define CAN_ACK_ERROR 3U - -bool can_set_speed(uint8_t can_number) { +static bool can_set_speed(uint8_t can_number) { bool ret = true; FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number); uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); @@ -35,7 +18,19 @@ bool can_set_speed(uint8_t can_number) { return ret; } +void can_clear_send(FDCAN_GlobalTypeDef *FDCANx, uint8_t can_number) { + can_health[can_number].can_core_reset_cnt += 1U; + can_health[can_number].total_tx_lost_cnt += (FDCAN_TX_FIFO_EL_CNT - (FDCANx->TXFQS & FDCAN_TXFQS_TFFL)); // TX FIFO msgs will be lost after reset + llcan_clear_send(FDCANx); +} + void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) { + uint8_t can_irq_number[3][2] = { + { FDCAN1_IT0_IRQn, FDCAN1_IT1_IRQn }, + { FDCAN2_IT0_IRQn, FDCAN2_IT1_IRQn }, + { FDCAN3_IT0_IRQn, FDCAN3_IT1_IRQn }, + }; + FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number); uint32_t psr_reg = FDCANx->PSR; uint32_t ecr_reg = FDCANx->ECR; @@ -75,9 +70,7 @@ void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) { // 2. H7 gets stuck in bus off recovery state indefinitely if ((((can_health[can_number].last_error == CAN_ACK_ERROR) || (can_health[can_number].last_data_error == CAN_ACK_ERROR)) && (can_health[can_number].transmit_error_cnt > 127U)) || ((ir_reg & FDCAN_IR_BO) != 0U)) { - can_health[can_number].can_core_reset_cnt += 1U; - can_health[can_number].total_tx_lost_cnt += (FDCAN_TX_FIFO_EL_CNT - (FDCANx->TXFQS & FDCAN_TXFQS_TFFL)); // TX FIFO msgs will be lost after reset - llcan_clear_send(FDCANx); + can_clear_send(FDCANx, can_number); } } } @@ -237,14 +230,14 @@ void can_rx(uint8_t can_number) { } } -void FDCAN1_IT0_IRQ_Handler(void) { can_rx(0); } -void FDCAN1_IT1_IRQ_Handler(void) { process_can(0); } +static void FDCAN1_IT0_IRQ_Handler(void) { can_rx(0); } +static void FDCAN1_IT1_IRQ_Handler(void) { process_can(0); } -void FDCAN2_IT0_IRQ_Handler(void) { can_rx(1); } -void FDCAN2_IT1_IRQ_Handler(void) { process_can(1); } +static void FDCAN2_IT0_IRQ_Handler(void) { can_rx(1); } +static void FDCAN2_IT1_IRQ_Handler(void) { process_can(1); } -void FDCAN3_IT0_IRQ_Handler(void) { can_rx(2); } -void FDCAN3_IT1_IRQ_Handler(void) { process_can(2); } +static void FDCAN3_IT0_IRQ_Handler(void) { can_rx(2); } +static void FDCAN3_IT1_IRQ_Handler(void) { process_can(2); } bool can_init(uint8_t can_number) { bool ret = false; diff --git a/panda/board/drivers/fdcan_declarations.h b/panda/board/drivers/fdcan_declarations.h new file mode 100644 index 000000000000000..9cdc424e6b7bc49 --- /dev/null +++ b/panda/board/drivers/fdcan_declarations.h @@ -0,0 +1,28 @@ +#pragma once + +// IRQs: FDCAN1_IT0, FDCAN1_IT1 +// FDCAN2_IT0, FDCAN2_IT1 +// FDCAN3_IT0, FDCAN3_IT1 + +#define CANFD + +typedef struct { + volatile uint32_t header[2]; + volatile uint32_t data_word[CANPACKET_DATA_SIZE_MAX/4U]; +} canfd_fifo; + +#define CANS_ARRAY_SIZE 3 +extern FDCAN_GlobalTypeDef *cans[CANS_ARRAY_SIZE]; + +#define CAN_ACK_ERROR 3U + +void can_clear_send(FDCAN_GlobalTypeDef *FDCANx, uint8_t can_number); +void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg); + +// ***************************** CAN ***************************** +// FDFDCANx_IT1 IRQ Handler (TX) +void process_can(uint8_t can_number); +// FDFDCANx_IT0 IRQ Handler (RX and errors) +// blink blue when we are receiving CAN messages +void can_rx(uint8_t can_number); +bool can_init(uint8_t can_number); diff --git a/panda/board/drivers/harness.h b/panda/board/drivers/harness.h index f8f0ccb7d38cca1..cfb6965c0344a4a 100644 --- a/panda/board/drivers/harness.h +++ b/panda/board/drivers/harness.h @@ -1,29 +1,6 @@ -#define HARNESS_STATUS_NC 0U -#define HARNESS_STATUS_NORMAL 1U -#define HARNESS_STATUS_FLIPPED 2U - -struct harness_t { - uint8_t status; - uint16_t sbu1_voltage_mV; - uint16_t sbu2_voltage_mV; - bool relay_driven; - bool sbu_adc_lock; -}; -struct harness_t harness; +#include "harness_declarations.h" -struct harness_configuration { - const bool has_harness; - GPIO_TypeDef * const GPIO_SBU1; - GPIO_TypeDef * const GPIO_SBU2; - GPIO_TypeDef * const GPIO_relay_SBU1; - GPIO_TypeDef * const GPIO_relay_SBU2; - const uint8_t pin_SBU1; - const uint8_t pin_SBU2; - const uint8_t pin_relay_SBU1; - const uint8_t pin_relay_SBU2; - const uint8_t adc_channel_SBU1; - const uint8_t adc_channel_SBU2; -}; +struct harness_t harness; // The ignition relay is only used for testing purposes void set_intercept_relay(bool intercept, bool ignition_relay) { @@ -74,7 +51,7 @@ bool harness_check_ignition(void) { return ret; } -uint8_t harness_detect_orientation(void) { +static uint8_t harness_detect_orientation(void) { uint8_t ret = harness.status; #ifndef BOOTSTUB diff --git a/panda/board/drivers/harness_declarations.h b/panda/board/drivers/harness_declarations.h new file mode 100644 index 000000000000000..953941f6214bc8f --- /dev/null +++ b/panda/board/drivers/harness_declarations.h @@ -0,0 +1,34 @@ +#pragma once + +#define HARNESS_STATUS_NC 0U +#define HARNESS_STATUS_NORMAL 1U +#define HARNESS_STATUS_FLIPPED 2U + +struct harness_t { + uint8_t status; + uint16_t sbu1_voltage_mV; + uint16_t sbu2_voltage_mV; + bool relay_driven; + bool sbu_adc_lock; +}; +extern struct harness_t harness; + +struct harness_configuration { + const bool has_harness; + GPIO_TypeDef * const GPIO_SBU1; + GPIO_TypeDef * const GPIO_SBU2; + GPIO_TypeDef * const GPIO_relay_SBU1; + GPIO_TypeDef * const GPIO_relay_SBU2; + const uint8_t pin_SBU1; + const uint8_t pin_SBU2; + const uint8_t pin_relay_SBU1; + const uint8_t pin_relay_SBU2; + const uint8_t adc_channel_SBU1; + const uint8_t adc_channel_SBU2; +}; + +// The ignition relay is only used for testing purposes +void set_intercept_relay(bool intercept, bool ignition_relay); +bool harness_check_ignition(void); +void harness_tick(void); +void harness_init(void); diff --git a/panda/board/drivers/interrupts.h b/panda/board/drivers/interrupts.h index 77988f6e45e5391..1188a8ec07b287f 100644 --- a/panda/board/drivers/interrupts.h +++ b/panda/board/drivers/interrupts.h @@ -1,14 +1,4 @@ -typedef struct interrupt { - IRQn_Type irq_type; - void (*handler)(void); - uint32_t call_counter; - uint32_t call_rate; - uint32_t max_call_rate; // Call rate is defined as the amount of calls each second - uint32_t call_rate_fault; -} interrupt; - -void interrupt_timer_init(void); -uint32_t microsecond_timer_get(void); +#include "interrupts_declarations.h" void unused_interrupt_handler(void) { // Something is wrong if this handler is called! @@ -18,23 +8,15 @@ void unused_interrupt_handler(void) { interrupt interrupts[NUM_INTERRUPTS]; -#define REGISTER_INTERRUPT(irq_num, func_ptr, call_rate_max, rate_fault) \ - interrupts[irq_num].irq_type = (irq_num); \ - interrupts[irq_num].handler = (func_ptr); \ - interrupts[irq_num].call_counter = 0U; \ - interrupts[irq_num].call_rate = 0U; \ - interrupts[irq_num].max_call_rate = (call_rate_max); \ - interrupts[irq_num].call_rate_fault = (rate_fault); - -bool check_interrupt_rate = false; +static bool check_interrupt_rate = false; -uint8_t interrupt_depth = 0U; -uint32_t last_time = 0U; -uint32_t idle_time = 0U; -uint32_t busy_time = 0U; +static uint32_t idle_time = 0U; +static uint32_t busy_time = 0U; float interrupt_load = 0.0f; void handle_interrupt(IRQn_Type irq_type){ + static uint8_t interrupt_depth = 0U; + static uint32_t last_time = 0U; ENTER_CRITICAL(); if (interrupt_depth == 0U) { uint32_t time = microsecond_timer_get(); diff --git a/panda/board/drivers/interrupts_declarations.h b/panda/board/drivers/interrupts_declarations.h new file mode 100644 index 000000000000000..4112453ca645976 --- /dev/null +++ b/panda/board/drivers/interrupts_declarations.h @@ -0,0 +1,31 @@ +#pragma once + +typedef struct interrupt { + IRQn_Type irq_type; + void (*handler)(void); + uint32_t call_counter; + uint32_t call_rate; + uint32_t max_call_rate; // Call rate is defined as the amount of calls each second + uint32_t call_rate_fault; +} interrupt; + +void interrupt_timer_init(void); +uint32_t microsecond_timer_get(void); +void unused_interrupt_handler(void); + +extern interrupt interrupts[NUM_INTERRUPTS]; + +#define REGISTER_INTERRUPT(irq_num, func_ptr, call_rate_max, rate_fault) \ + interrupts[irq_num].irq_type = (irq_num); \ + interrupts[irq_num].handler = (func_ptr); \ + interrupts[irq_num].call_counter = 0U; \ + interrupts[irq_num].call_rate = 0U; \ + interrupts[irq_num].max_call_rate = (call_rate_max); \ + interrupts[irq_num].call_rate_fault = (rate_fault); + +extern float interrupt_load; + +void handle_interrupt(IRQn_Type irq_type); +// Every second +void interrupt_timer_handler(void); +void init_interrupts(bool check_rate_limit); diff --git a/panda/board/drivers/registers.h b/panda/board/drivers/registers.h index 5d5a4257d77b22e..92b6b0faa2962e1 100644 --- a/panda/board/drivers/registers.h +++ b/panda/board/drivers/registers.h @@ -1,21 +1,11 @@ +#include "registers_declarations.h" -typedef struct reg { - volatile uint32_t *address; - uint32_t value; - uint32_t check_mask; -} reg; - -// 10 bit hash with 23 as a prime -#define REGISTER_MAP_SIZE 0x3FFU -#define HASHING_PRIME 23U -#define CHECK_COLLISION(hash, addr) (((uint32_t) register_map[hash].address != 0U) && (register_map[hash].address != (addr))) - -reg register_map[REGISTER_MAP_SIZE]; +static reg register_map[REGISTER_MAP_SIZE]; // Hash spread in first and second iterations seems to be reasonable. // See: tests/development/register_hashmap_spread.py // Also, check the collision warnings in the debug output, and minimize those. -uint16_t hash_addr(uint32_t input){ +static uint16_t hash_addr(uint32_t input){ return (((input >> 16U) ^ ((((input + 1U) & 0xFFFFU) * HASHING_PRIME) & 0xFFFFU)) & REGISTER_MAP_SIZE); } diff --git a/panda/board/drivers/registers_declarations.h b/panda/board/drivers/registers_declarations.h new file mode 100644 index 000000000000000..13180117b421aae --- /dev/null +++ b/panda/board/drivers/registers_declarations.h @@ -0,0 +1,24 @@ +#pragma once + +typedef struct reg { + volatile uint32_t *address; + uint32_t value; + uint32_t check_mask; +} reg; + +// 10 bit hash with 23 as a prime +#define REGISTER_MAP_SIZE 0x3FFU +#define HASHING_PRIME 23U +#define CHECK_COLLISION(hash, addr) (((uint32_t) register_map[hash].address != 0U) && (register_map[hash].address != (addr))) + +// Do not put bits in the check mask that get changed by the hardware +void register_set(volatile uint32_t *addr, uint32_t val, uint32_t mask); +// Set individual bits. Also add them to the check_mask. +// Do not use this to change bits that get reset by the hardware +void register_set_bits(volatile uint32_t *addr, uint32_t val); +// Clear individual bits. Also add them to the check_mask. +// Do not use this to clear bits that get set by the hardware +void register_clear_bits(volatile uint32_t *addr, uint32_t val); +// To be called periodically +void check_registers(void); +void init_registers(void); diff --git a/panda/board/drivers/simple_watchdog.h b/panda/board/drivers/simple_watchdog.h index fe0c856afcfde70..f679cb19393e4fd 100644 --- a/panda/board/drivers/simple_watchdog.h +++ b/panda/board/drivers/simple_watchdog.h @@ -1,11 +1,6 @@ -typedef struct simple_watchdog_state_t { - uint32_t fault; - uint32_t last_ts; - uint32_t threshold; -} simple_watchdog_state_t; - -simple_watchdog_state_t wd_state; +#include "simple_watchdog_declarations.h" +static simple_watchdog_state_t wd_state; void simple_watchdog_kick(void) { uint32_t ts = microsecond_timer_get(); diff --git a/panda/board/drivers/simple_watchdog_declarations.h b/panda/board/drivers/simple_watchdog_declarations.h new file mode 100644 index 000000000000000..2bda71590bac6a8 --- /dev/null +++ b/panda/board/drivers/simple_watchdog_declarations.h @@ -0,0 +1,10 @@ +#pragma once + +typedef struct simple_watchdog_state_t { + uint32_t fault; + uint32_t last_ts; + uint32_t threshold; +} simple_watchdog_state_t; + +void simple_watchdog_kick(void); +void simple_watchdog_init(uint32_t fault, uint32_t threshold); diff --git a/panda/board/drivers/spi.h b/panda/board/drivers/spi.h index 61ae2aba9d6a84f..36f4dd29aa3e072 100644 --- a/panda/board/drivers/spi.h +++ b/panda/board/drivers/spi.h @@ -1,13 +1,8 @@ #pragma once +#include "spi_declarations.h" #include "crc.h" -#define SPI_TIMEOUT_US 10000U - -// got max rate from hitting a non-existent endpoint -// in a tight loop, plus some buffer -#define SPI_IRQ_RATE 16000U - #ifdef STM32H7 #define SPI_BUF_SIZE 2048U // H7 DMA2 located in D2 domain, so we need to use SRAM1/SRAM2 @@ -19,44 +14,15 @@ uint8_t spi_buf_rx[SPI_BUF_SIZE]; uint8_t spi_buf_tx[SPI_BUF_SIZE]; #endif -#define SPI_CHECKSUM_START 0xABU -#define SPI_SYNC_BYTE 0x5AU -#define SPI_HACK 0x79U -#define SPI_DACK 0x85U -#define SPI_NACK 0x1FU - -// SPI states -enum { - SPI_STATE_HEADER, - SPI_STATE_HEADER_ACK, - SPI_STATE_HEADER_NACK, - SPI_STATE_DATA_RX, - SPI_STATE_DATA_RX_ACK, - SPI_STATE_DATA_TX -}; - -bool spi_tx_dma_done = false; -uint8_t spi_state = SPI_STATE_HEADER; -uint8_t spi_endpoint; -uint16_t spi_data_len_mosi; -uint16_t spi_data_len_miso; uint16_t spi_checksum_error_count = 0; -bool spi_can_tx_ready = false; - -const unsigned char version_text[] = "VERSION"; -#define SPI_HEADER_SIZE 7U - -// low level SPI prototypes -void llspi_init(void); -void llspi_mosi_dma(uint8_t *addr, int len); -void llspi_miso_dma(uint8_t *addr, int len); - -void can_tx_comms_resume_spi(void) { - spi_can_tx_ready = true; -} +#if defined(ENABLE_SPI) || defined(BOOTSTUB) +static uint8_t spi_state = SPI_STATE_HEADER; +static uint16_t spi_data_len_mosi; +static bool spi_can_tx_ready = false; +static const unsigned char version_text[] = "VERSION"; -uint16_t spi_version_packet(uint8_t *out) { +static uint16_t spi_version_packet(uint8_t *out) { // this protocol version request is a stable portion of // the panda's SPI protocol. its contents match that of the // panda USB descriptors and are sufficent to list/enumerate @@ -109,7 +75,7 @@ void spi_init(void) { llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE); } -bool validate_checksum(const uint8_t *data, uint16_t len) { +static 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++){ @@ -122,6 +88,8 @@ void spi_rx_done(void) { uint16_t response_len = 0U; uint8_t next_rx_state = SPI_STATE_HEADER_NACK; bool checksum_valid = false; + static uint8_t spi_endpoint; + static uint16_t spi_data_len_miso; // parse header spi_endpoint = spi_buf_rx[1]; @@ -153,7 +121,7 @@ void spi_rx_done(void) { if (spi_endpoint == 0U) { if (spi_data_len_mosi >= sizeof(ControlPacket_t)) { ControlPacket_t ctrl = {0}; - (void)memcpy(&ctrl, &spi_buf_rx[SPI_HEADER_SIZE], sizeof(ControlPacket_t)); + (void)memcpy((uint8_t*)&ctrl, &spi_buf_rx[SPI_HEADER_SIZE], sizeof(ControlPacket_t)); response_len = comms_control_handler(&ctrl, &spi_buf_tx[3]); response_ack = true; } else { @@ -258,3 +226,12 @@ void spi_tx_done(bool reset) { print("SPI: TX unexpected state: "); puth(spi_state); print("\n"); } } + +void can_tx_comms_resume_spi(void) { + spi_can_tx_ready = true; +} +#else +void can_tx_comms_resume_spi(void) { + return; +} +#endif diff --git a/panda/board/drivers/spi_declarations.h b/panda/board/drivers/spi_declarations.h new file mode 100644 index 000000000000000..8c830e6b0426aeb --- /dev/null +++ b/panda/board/drivers/spi_declarations.h @@ -0,0 +1,52 @@ +#pragma once + +#include "crc.h" + +#define SPI_TIMEOUT_US 10000U + +// got max rate from hitting a non-existent endpoint +// in a tight loop, plus some buffer +#define SPI_IRQ_RATE 16000U + +#ifdef STM32H7 +#define SPI_BUF_SIZE 2048U +// H7 DMA2 located in D2 domain, so we need to use SRAM1/SRAM2 +__attribute__((section(".sram12"))) extern uint8_t spi_buf_rx[SPI_BUF_SIZE]; +__attribute__((section(".sram12"))) extern uint8_t spi_buf_tx[SPI_BUF_SIZE]; +#else +#define SPI_BUF_SIZE 1024U +extern uint8_t spi_buf_rx[SPI_BUF_SIZE]; +extern uint8_t spi_buf_tx[SPI_BUF_SIZE]; +#endif + +#define SPI_CHECKSUM_START 0xABU +#define SPI_SYNC_BYTE 0x5AU +#define SPI_HACK 0x79U +#define SPI_DACK 0x85U +#define SPI_NACK 0x1FU + +// SPI states +enum { + SPI_STATE_HEADER, + SPI_STATE_HEADER_ACK, + SPI_STATE_HEADER_NACK, + SPI_STATE_DATA_RX, + SPI_STATE_DATA_RX_ACK, + SPI_STATE_DATA_TX +}; + +extern uint16_t spi_checksum_error_count; + +#define SPI_HEADER_SIZE 7U + +// low level SPI prototypes +void llspi_init(void); +void llspi_mosi_dma(uint8_t *addr, int len); +void llspi_miso_dma(uint8_t *addr, int len); + +void can_tx_comms_resume_spi(void); +#if defined(ENABLE_SPI) || defined(BOOTSTUB) +void spi_init(void); +void spi_rx_done(void); +void spi_tx_done(bool reset); +#endif diff --git a/panda/board/drivers/timers.h b/panda/board/drivers/timers.h index d7f3f01fd0fb285..49d9f5c4d1447a4 100644 --- a/panda/board/drivers/timers.h +++ b/panda/board/drivers/timers.h @@ -1,4 +1,4 @@ -void timer_init(TIM_TypeDef *TIM, int psc) { +static void timer_init(TIM_TypeDef *TIM, int psc) { register_set(&(TIM->PSC), (psc-1), 0xFFFFU); register_set(&(TIM->DIER), TIM_DIER_UIE, 0x5F5FU); register_set(&(TIM->CR1), TIM_CR1_CEN, 0x3FU); diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h index 01d8c2ac0518ce7..737539c9558f79f 100644 --- a/panda/board/drivers/uart.h +++ b/panda/board/drivers/uart.h @@ -1,25 +1,13 @@ +#include "uart_declarations.h" + // IRQs: USART2, USART3, UART5 // ***************************** Definitions ***************************** -#define FIFO_SIZE_INT 0x400U - -typedef struct uart_ring { - volatile uint16_t w_ptr_tx; - volatile uint16_t r_ptr_tx; - uint8_t *elems_tx; - uint32_t tx_fifo_size; - volatile uint16_t w_ptr_rx; - volatile uint16_t r_ptr_rx; - uint8_t *elems_rx; - uint32_t rx_fifo_size; - USART_TypeDef *uart; - void (*callback)(struct uart_ring*); - bool overwrite; -} uart_ring; #define UART_BUFFER(x, size_rx, size_tx, uart_ptr, callback_ptr, overwrite_mode) \ - uint8_t elems_rx_##x[size_rx]; \ - uint8_t elems_tx_##x[size_tx]; \ + static uint8_t elems_rx_##x[size_rx]; \ + static uint8_t elems_tx_##x[size_tx]; \ + extern uart_ring uart_ring_##x; \ uart_ring uart_ring_##x = { \ .w_ptr_tx = 0, \ .r_ptr_tx = 0, \ @@ -34,11 +22,6 @@ typedef struct uart_ring { .overwrite = (overwrite_mode) \ }; -// ***************************** Function prototypes ***************************** -void debug_ring_callback(uart_ring *ring); -void uart_tx_ring(uart_ring *q); -void uart_send_break(uart_ring *u); - // ******************************** UART buffers ******************************** // debug = USART2 @@ -151,20 +134,6 @@ void print(const char *a) { } } -void putui(uint32_t i) { - uint32_t i_copy = i; - char str[11]; - uint8_t idx = 10; - str[idx] = '\0'; - idx--; - do { - str[idx] = (i_copy % 10U) + 0x30U; - idx--; - i_copy /= 10; - } while (i_copy != 0U); - print(&str[idx + 1U]); -} - void puthx(uint32_t i, uint8_t len) { const char c[] = "0123456789abcdef"; for (int pos = ((int)len * 4) - 4; pos > -4; pos -= 4) { @@ -180,10 +149,13 @@ void puth2(unsigned int i) { puthx(i, 2U); } +#if defined(ENABLE_SPI) || defined(BOOTSTUB) || defined(DEBUG) void puth4(unsigned int i) { puthx(i, 4U); } +#endif +#if defined(ENABLE_SPI) || defined(BOOTSTUB) || defined(DEBUG_USB) || defined(DEBUG_COMMS) void hexdump(const void *a, int l) { if (a != NULL) { for (int i=0; i < l; i++) { @@ -194,3 +166,4 @@ void hexdump(const void *a, int l) { } print("\n"); } +#endif diff --git a/panda/board/drivers/uart_declarations.h b/panda/board/drivers/uart_declarations.h new file mode 100644 index 000000000000000..041fd377c3169f9 --- /dev/null +++ b/panda/board/drivers/uart_declarations.h @@ -0,0 +1,40 @@ +#pragma once + +// IRQs: USART2, USART3, UART5 + +// ***************************** Definitions ***************************** +#define FIFO_SIZE_INT 0x400U + +typedef struct uart_ring { + volatile uint16_t w_ptr_tx; + volatile uint16_t r_ptr_tx; + uint8_t *elems_tx; + uint32_t tx_fifo_size; + volatile uint16_t w_ptr_rx; + volatile uint16_t r_ptr_rx; + uint8_t *elems_rx; + uint32_t rx_fifo_size; + USART_TypeDef *uart; + void (*callback)(struct uart_ring*); + bool overwrite; +} uart_ring; + +// ***************************** Function prototypes ***************************** +void debug_ring_callback(uart_ring *ring); +void uart_tx_ring(uart_ring *q); +uart_ring *get_ring_by_number(int a); +// ************************* Low-level buffer functions ************************* +bool get_char(uart_ring *q, char *elem); +bool injectc(uart_ring *q, char elem); +bool put_char(uart_ring *q, char elem); +void clear_uart_buff(uart_ring *q); +// ************************ High-level debug functions ********************** +void putch(const char a); +void print(const char *a); +void puthx(uint32_t i, uint8_t len); +void puth(unsigned int i); +void puth2(unsigned int i); +#if defined(ENABLE_SPI) || defined(BOOTSTUB) || defined(DEBUG) +void puth4(unsigned int i); +#endif +void hexdump(const void *a, int l); diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h index e0063722166b92c..cfc9c4fb79b0810 100644 --- a/panda/board/drivers/usb.h +++ b/panda/board/drivers/usb.h @@ -1,361 +1,21 @@ -// IRQs: OTG_FS - -typedef union { - uint16_t w; - struct BW { - uint8_t msb; - uint8_t lsb; - } - bw; -} -uint16_t_uint8_t; - -typedef union _USB_Setup { - uint32_t d8[2]; - struct _SetupPkt_Struc - { - uint8_t bmRequestType; - uint8_t bRequest; - uint16_t_uint8_t wValue; - uint16_t_uint8_t wIndex; - uint16_t_uint8_t wLength; - } b; -} -USB_Setup_TypeDef; +#include "usb_declarations.h" bool usb_enumerated = false; -uint16_t usb_last_frame_num = 0U; - -void usb_init(void); -void refresh_can_tx_slots_available(void); - -// **** supporting defines **** - -#define USB_REQ_GET_STATUS 0x00 -#define USB_REQ_CLEAR_FEATURE 0x01 -#define USB_REQ_SET_FEATURE 0x03 -#define USB_REQ_SET_ADDRESS 0x05 -#define USB_REQ_GET_DESCRIPTOR 0x06 -#define USB_REQ_SET_DESCRIPTOR 0x07 -#define USB_REQ_GET_CONFIGURATION 0x08 -#define USB_REQ_SET_CONFIGURATION 0x09 -#define USB_REQ_GET_INTERFACE 0x0A -#define USB_REQ_SET_INTERFACE 0x0B -#define USB_REQ_SYNCH_FRAME 0x0C - -#define USB_DESC_TYPE_DEVICE 0x01 -#define USB_DESC_TYPE_CONFIGURATION 0x02 -#define USB_DESC_TYPE_STRING 0x03 -#define USB_DESC_TYPE_INTERFACE 0x04 -#define USB_DESC_TYPE_ENDPOINT 0x05 -#define USB_DESC_TYPE_DEVICE_QUALIFIER 0x06 -#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 0x07 -#define USB_DESC_TYPE_BINARY_OBJECT_STORE 0x0f - -// offsets for configuration strings -#define STRING_OFFSET_LANGID 0x00 -#define STRING_OFFSET_IMANUFACTURER 0x01 -#define STRING_OFFSET_IPRODUCT 0x02 -#define STRING_OFFSET_ISERIAL 0x03 -#define STRING_OFFSET_ICONFIGURATION 0x04 -#define STRING_OFFSET_IINTERFACE 0x05 - -// WebUSB requests -#define WEBUSB_REQ_GET_URL 0x02 - -// WebUSB types -#define WEBUSB_DESC_TYPE_URL 0x03 -#define WEBUSB_URL_SCHEME_HTTPS 0x01 -#define WEBUSB_URL_SCHEME_HTTP 0x00 - -// WinUSB requests -#define WINUSB_REQ_GET_COMPATID_DESCRIPTOR 0x04 -#define WINUSB_REQ_GET_EXT_PROPS_OS 0x05 -#define WINUSB_REQ_GET_DESCRIPTOR 0x07 - -#define STS_GOUT_NAK 1 -#define STS_DATA_UPDT 2 -#define STS_XFER_COMP 3 -#define STS_SETUP_COMP 4 -#define STS_SETUP_UPDT 6 - -uint8_t response[USBPACKET_MAX_SIZE]; - -// for the repeating interfaces -#define DSCR_INTERFACE_LEN 9 -#define DSCR_ENDPOINT_LEN 7 -#define DSCR_CONFIG_LEN 9 -#define DSCR_DEVICE_LEN 18 - -// endpoint types -#define ENDPOINT_TYPE_CONTROL 0 -#define ENDPOINT_TYPE_ISO 1 -#define ENDPOINT_TYPE_BULK 2 -#define ENDPOINT_TYPE_INT 3 - -// These are arbitrary values used in bRequest -#define MS_VENDOR_CODE 0x20 -#define WEBUSB_VENDOR_CODE 0x30 - -// BOS constants -#define BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH 0x05 -#define BINARY_OBJECT_STORE_DESCRIPTOR 0x0F -#define WINUSB_PLATFORM_DESCRIPTOR_LENGTH 0x9E - -// Convert machine byte order to USB byte order -#define TOUSBORDER(num)\ - ((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)\ - (((((size) * 2) + 2) & 0xFF) | 0x0300) - -uint8_t device_desc[] = { - DSCR_DEVICE_LEN, USB_DESC_TYPE_DEVICE, //Length, Type - 0x10, 0x02, // bcdUSB max version of USB supported (2.1) - 0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size - TOUSBORDER(USB_VID), // idVendor - TOUSBORDER(USB_PID), // idProduct - 0x00, 0x00, // bcdDevice - 0x01, 0x02, // Manufacturer, Product - 0x03, 0x01 // Serial Number, Num Configurations -}; - -uint8_t device_qualifier[] = { - 0x0a, USB_DESC_TYPE_DEVICE_QUALIFIER, //Length, Type - 0x10, 0x02, // bcdUSB max version of USB supported (2.1) - 0xFF, 0xFF, 0xFF, 0x40, // bDeviceClass, bDeviceSubClass, bDeviceProtocol, bMaxPacketSize0 - 0x01, 0x00 // bNumConfigurations, bReserved -}; - -#define ENDPOINT_RCV 0x80 -#define ENDPOINT_SND 0x00 - -uint8_t configuration_desc[] = { - DSCR_CONFIG_LEN, USB_DESC_TYPE_CONFIGURATION, // Length, Type, - TOUSBORDER(0x0045U), // Total Len (uint16) - 0x01, 0x01, STRING_OFFSET_ICONFIGURATION, // Num Interface, Config Value, Configuration - 0xc0, 0x32, // Attributes, Max Power - // interface 0 ALT 0 - DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type - 0x00, 0x00, 0x03, // Index, Alt Index idx, Endpoint count - 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol - 0x00, // Interface - // endpoint 1, read CAN - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval (NA) - // endpoint 2, send serial - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval - // endpoint 3, send CAN - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval - // interface 0 ALT 1 - DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type - 0x00, 0x01, 0x03, // Index, Alt Index idx, Endpoint count - 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol - 0x00, // Interface - // endpoint 1, read CAN - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x05, // Polling Interval (5 frames) - // endpoint 2, send serial - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval - // endpoint 3, send CAN - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval -}; - -// STRING_DESCRIPTOR_HEADER is for uint16 string descriptors -// it takes in a string length, which is bytes/2 because unicode -uint16_t string_language_desc[] = { - STRING_DESCRIPTOR_HEADER(1), - 0x0409 // american english -}; - -// these strings are all uint16's so that we don't need to spam ,0 after every character -uint16_t string_manufacturer_desc[] = { - STRING_DESCRIPTOR_HEADER(8), - 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i' -}; - -uint16_t string_product_desc[] = { - STRING_DESCRIPTOR_HEADER(5), - 'p', 'a', 'n', 'd', 'a' -}; - -// default serial number when we're not a panda -uint16_t string_serial_desc[] = { - STRING_DESCRIPTOR_HEADER(4), - 'n', 'o', 'n', 'e' -}; - -// a string containing the default configuration index -uint16_t string_configuration_desc[] = { - STRING_DESCRIPTOR_HEADER(2), - '0', '1' // "01" -}; - -// WCID (auto install WinUSB driver) -// https://github.com/pbatard/libwdi/wiki/WCID-Devices -// https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation#automatic-installation-of--winusb-without-an-inf-file -// WinUSB 1.0 descriptors, this is mostly used by Windows XP -uint8_t string_238_desc[] = { - 0x12, USB_DESC_TYPE_STRING, // bLength, bDescriptorType - 'M',0, 'S',0, 'F',0, 'T',0, '1',0, '0',0, '0',0, // qwSignature (MSFT100) - MS_VENDOR_CODE, 0x00 // bMS_VendorCode, bPad -}; -uint8_t winusb_ext_compatid_os_desc[] = { - 0x28, 0x00, 0x00, 0x00, // dwLength - 0x00, 0x01, // bcdVersion - 0x04, 0x00, // wIndex - 0x01, // bCount - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved - 0x00, // bFirstInterfaceNumber - 0x00, // Reserved - 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // subcompatible ID (none) - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved -}; -uint8_t winusb_ext_prop_os_desc[] = { - 0x8e, 0x00, 0x00, 0x00, // dwLength - 0x00, 0x01, // bcdVersion - 0x05, 0x00, // wIndex - 0x01, 0x00, // wCount - // first property - 0x84, 0x00, 0x00, 0x00, // dwSize - 0x01, 0x00, 0x00, 0x00, // dwPropertyDataType - 0x28, 0x00, // wPropertyNameLength - 'D',0, 'e',0, 'v',0, 'i',0, 'c',0, 'e',0, 'I',0, 'n',0, 't',0, 'e',0, 'r',0, 'f',0, 'a',0, 'c',0, 'e',0, 'G',0, 'U',0, 'I',0, 'D',0, 0, 0, // bPropertyName (DeviceInterfaceGUID) - 0x4e, 0x00, 0x00, 0x00, // dwPropertyDataLength - '{',0, 'c',0, 'c',0, 'e',0, '5',0, '2',0, '9',0, '1',0, 'c',0, '-',0, 'a',0, '6',0, '9',0, 'f',0, '-',0, '4',0 ,'9',0 ,'9',0 ,'5',0 ,'-',0, 'a',0, '4',0, 'c',0, '2',0, '-',0, '2',0, 'a',0, 'e',0, '5',0, '7',0, 'a',0, '5',0, '1',0, 'a',0, 'd',0, 'e',0, '9',0, '}',0, 0, 0, // bPropertyData ({CCE5291C-A69F-4995-A4C2-2AE57A51ADE9}) -}; - -/* -Binary Object Store descriptor used to expose WebUSB (and more WinUSB) metadata -comments are from the wicg spec -References used: - https://wicg.github.io/webusb/#webusb-platform-capability-descriptor - https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c - https://os.mbed.com/users/larsgk/code/USBDevice_WebUSB/file/1d8a6665d607/WebUSBDevice/ - -*/ -uint8_t binary_object_store_desc[] = { - // BOS header - BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH, // bLength, this is only the length of the header - BINARY_OBJECT_STORE_DESCRIPTOR, // bDescriptorType - 0x39, 0x00, // wTotalLength (LSB, MSB) - 0x02, // bNumDeviceCaps (WebUSB + WinUSB) - - // ------------------------------------------------- - // WebUSB descriptor - // header - 0x18, // bLength, Size of this descriptor. Must be set to 24. - 0x10, // bDescriptorType, DEVICE CAPABILITY descriptor - 0x05, // bDevCapabilityType, PLATFORM capability - 0x00, // bReserved, This field is reserved and shall be set to zero. - - // PlatformCapabilityUUID, Must be set to {3408b638-09a9-47a0-8bfd-a0768815b665}. - 0x38, 0xB6, 0x08, 0x34, - 0xA9, 0x09, 0xA0, 0x47, - 0x8B, 0xFD, 0xA0, 0x76, - 0x88, 0x15, 0xB6, 0x65, - // - - 0x00, 0x01, // bcdVersion, Protocol version supported. Must be set to 0x0100. - WEBUSB_VENDOR_CODE, // bVendorCode, bRequest value used for issuing WebUSB requests. - // there used to be a concept of "allowed origins", but it was removed from the spec - // it was intended to be a security feature, but then the entire security model relies on domain ownership - // https://github.com/WICG/webusb/issues/49 - // other implementations use various other indexed to leverate this no-longer-valid feature. we wont. - // the spec says we *must* reply to index 0x03 with the url, so we'll hint that that's the right index - 0x03, // iLandingPage, URL descriptor index of the device’s landing page. - - // ------------------------------------------------- - // WinUSB descriptor - // header - 0x1C, // Descriptor size (28 bytes) - 0x10, // Descriptor type (Device Capability) - 0x05, // Capability type (Platform) - 0x00, // Reserved - - // MS OS 2.0 Platform Capability ID (D8DD60DF-4589-4CC7-9CD2-659D9E648A9F) - // Indicates the device supports the Microsoft OS 2.0 descriptor - 0xDF, 0x60, 0xDD, 0xD8, - 0x89, 0x45, 0xC7, 0x4C, - 0x9C, 0xD2, 0x65, 0x9D, - 0x9E, 0x64, 0x8A, 0x9F, - - 0x00, 0x00, 0x03, 0x06, // Windows version, currently set to 8.1 (0x06030000) - - WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // MS OS 2.0 descriptor size (word) - MS_VENDOR_CODE, 0x00 // vendor code, no alternate enumeration -}; - -// WinUSB 2.0 descriptor. This is what modern systems use -// https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c -// http://janaxelson.com/files/ms_os_20_descriptors.c -// https://books.google.com/books?id=pkefBgAAQBAJ&pg=PA353&lpg=PA353 -uint8_t winusb_20_desc[WINUSB_PLATFORM_DESCRIPTOR_LENGTH] = { - // Microsoft OS 2.0 descriptor set header (table 10) - 0x0A, 0x00, // Descriptor size (10 bytes) - 0x00, 0x00, // MS OS 2.0 descriptor set header - - 0x00, 0x00, 0x03, 0x06, // Windows version (8.1) (0x06030000) - WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // Total size of MS OS 2.0 descriptor set - - // Microsoft OS 2.0 compatible ID descriptor - 0x14, 0x00, // Descriptor size (20 bytes) - 0x03, 0x00, // MS OS 2.0 compatible ID descriptor - 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Sub-compatible ID - - // Registry property descriptor - 0x80, 0x00, // Descriptor size (130 bytes) - 0x04, 0x00, // Registry Property descriptor - 0x01, 0x00, // Strings are null-terminated Unicode - 0x28, 0x00, // Size of Property Name (40 bytes) "DeviceInterfaceGUID" - - // bPropertyName (DeviceInterfaceGUID) - 'D', 0x00, 'e', 0x00, 'v', 0x00, 'i', 0x00, 'c', 0x00, 'e', 0x00, 'I', 0x00, 'n', 0x00, - 't', 0x00, 'e', 0x00, 'r', 0x00, 'f', 0x00, 'a', 0x00, 'c', 0x00, 'e', 0x00, 'G', 0x00, - 'U', 0x00, 'I', 0x00, 'D', 0x00, 0x00, 0x00, - 0x4E, 0x00, // Size of Property Data (78 bytes) - - // Vendor-defined property data: {CCE5291C-A69F-4995-A4C2-2AE57A51ADE9} - '{', 0x00, 'c', 0x00, 'c', 0x00, 'e', 0x00, '5', 0x00, '2', 0x00, '9', 0x00, '1', 0x00, // 16 - 'c', 0x00, '-', 0x00, 'a', 0x00, '6', 0x00, '9', 0x00, 'f', 0x00, '-', 0x00, '4', 0x00, // 32 - '9', 0x00, '9', 0x00, '5', 0x00, '-', 0x00, 'a', 0x00, '4', 0x00, 'c', 0x00, '2', 0x00, // 48 - '-', 0x00, '2', 0x00, 'a', 0x00, 'e', 0x00, '5', 0x00, '7', 0x00, 'a', 0x00, '5', 0x00, // 64 - '1', 0x00, 'a', 0x00, 'd', 0x00, 'e', 0x00, '9', 0x00, '}', 0x00, 0x00, 0x00 // 78 bytes -}; +static uint8_t response[USBPACKET_MAX_SIZE]; // current packet -USB_Setup_TypeDef setup; -uint8_t usbdata[0x100] __attribute__((aligned(4))); -uint8_t* ep0_txdata = NULL; -uint16_t ep0_txlen = 0; -bool outep3_processing = false; +static USB_Setup_TypeDef setup; +static uint8_t* ep0_txdata = NULL; +static uint16_t ep0_txlen = 0; +static bool outep3_processing = false; // Store the current interface alt setting. -int current_int0_alt_setting = 0; +static int current_int0_alt_setting = 0; // packet read and write -void *USB_ReadPacket(void *dest, uint16_t len) { +static void *USB_ReadPacket(void *dest, uint16_t len) { uint32_t *dest_copy = (uint32_t *)dest; uint32_t count32b = ((uint32_t)len + 3U) / 4U; @@ -366,7 +26,7 @@ void *USB_ReadPacket(void *dest, uint16_t len) { return ((void *)dest_copy); } -void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) { +static void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) { #ifdef DEBUG_USB print("writing "); hexdump(src, len); @@ -393,7 +53,7 @@ void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) { // IN EP 0 TX FIFO has a max size of 127 bytes (much smaller than the rest) // so use TX FIFO empty interrupt to send larger amounts of data -void USB_WritePacket_EP0(uint8_t *src, uint16_t len) { +static void USB_WritePacket_EP0(uint8_t *src, uint16_t len) { #ifdef DEBUG_USB print("writing "); hexdump(src, len); @@ -411,7 +71,7 @@ void USB_WritePacket_EP0(uint8_t *src, uint16_t len) { } } -void usb_reset(void) { +static void usb_reset(void) { // unmask endpoint interrupts, so many sets USBx_DEVICE->DAINT = 0xFFFFFFFFU; USBx_DEVICE->DAINTMSK = 0xFFFFFFFFU; @@ -454,7 +114,7 @@ void usb_reset(void) { USBx_OUTEP(0U)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1UL << 19)) | (3U << 3); } -char to_hex_char(uint8_t a) { +static char to_hex_char(uint8_t a) { char ret; if (a < 10U) { ret = '0' + a; @@ -465,12 +125,238 @@ char to_hex_char(uint8_t a) { } void usb_tick(void) { + static uint16_t usb_last_frame_num = 0U; uint16_t current_frame_num = (USBx_DEVICE->DSTS & USB_OTG_DSTS_FNSOF_Msk) >> USB_OTG_DSTS_FNSOF_Pos; usb_enumerated = (current_frame_num != usb_last_frame_num); usb_last_frame_num = current_frame_num; } -void usb_setup(void) { +static void usb_setup(void) { + static uint8_t device_desc[] = { + DSCR_DEVICE_LEN, USB_DESC_TYPE_DEVICE, //Length, Type + 0x10, 0x02, // bcdUSB max version of USB supported (2.1) + 0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size + TOUSBORDER(USB_VID), // idVendor + TOUSBORDER(USB_PID), // idProduct + 0x00, 0x00, // bcdDevice + 0x01, 0x02, // Manufacturer, Product + 0x03, 0x01 // Serial Number, Num Configurations + }; + + static uint8_t device_qualifier[] = { + 0x0a, USB_DESC_TYPE_DEVICE_QUALIFIER, //Length, Type + 0x10, 0x02, // bcdUSB max version of USB supported (2.1) + 0xFF, 0xFF, 0xFF, 0x40, // bDeviceClass, bDeviceSubClass, bDeviceProtocol, bMaxPacketSize0 + 0x01, 0x00 // bNumConfigurations, bReserved + }; + + static uint8_t configuration_desc[] = { + DSCR_CONFIG_LEN, USB_DESC_TYPE_CONFIGURATION, // Length, Type, + TOUSBORDER(0x0045U), // Total Len (uint16) + 0x01, 0x01, STRING_OFFSET_ICONFIGURATION, // Num Interface, Config Value, Configuration + 0xc0, 0x32, // Attributes, Max Power + // interface 0 ALT 0 + DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type + 0x00, 0x00, 0x03, // Index, Alt Index idx, Endpoint count + 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol + 0x00, // Interface + // endpoint 1, read CAN + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040U), // Max Packet (0x0040) + 0x00, // Polling Interval (NA) + // endpoint 2, send serial + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040U), // Max Packet (0x0040) + 0x00, // Polling Interval + // endpoint 3, send CAN + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040U), // Max Packet (0x0040) + 0x00, // Polling Interval + // interface 0 ALT 1 + DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type + 0x00, 0x01, 0x03, // Index, Alt Index idx, Endpoint count + 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol + 0x00, // Interface + // endpoint 1, read CAN + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040U), // Max Packet (0x0040) + 0x05, // Polling Interval (5 frames) + // endpoint 2, send serial + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040U), // Max Packet (0x0040) + 0x00, // Polling Interval + // endpoint 3, send CAN + DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type + ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type + TOUSBORDER(0x0040U), // Max Packet (0x0040) + 0x00, // Polling Interval + }; + + // STRING_DESCRIPTOR_HEADER is for uint16 string descriptors + // it takes in a string length, which is bytes/2 because unicode + static uint16_t string_language_desc[] = { + STRING_DESCRIPTOR_HEADER(1), + 0x0409 // american english + }; + + // these strings are all uint16's so that we don't need to spam ,0 after every character + static uint16_t string_manufacturer_desc[] = { + STRING_DESCRIPTOR_HEADER(8), + 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i' + }; + + static uint16_t string_product_desc[] = { + STRING_DESCRIPTOR_HEADER(5), + 'p', 'a', 'n', 'd', 'a' + }; + + // a string containing the default configuration index + static uint16_t string_configuration_desc[] = { + STRING_DESCRIPTOR_HEADER(2), + '0', '1' // "01" + }; + + // WCID (auto install WinUSB driver) + // https://github.com/pbatard/libwdi/wiki/WCID-Devices + // https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation#automatic-installation-of--winusb-without-an-inf-file + // WinUSB 1.0 descriptors, this is mostly used by Windows XP + static uint8_t string_238_desc[] = { + 0x12, USB_DESC_TYPE_STRING, // bLength, bDescriptorType + 'M',0, 'S',0, 'F',0, 'T',0, '1',0, '0',0, '0',0, // qwSignature (MSFT100) + MS_VENDOR_CODE, 0x00 // bMS_VendorCode, bPad + }; + + static uint8_t winusb_ext_compatid_os_desc[] = { + 0x28, 0x00, 0x00, 0x00, // dwLength + 0x00, 0x01, // bcdVersion + 0x04, 0x00, // wIndex + 0x01, // bCount + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved + 0x00, // bFirstInterfaceNumber + 0x00, // Reserved + 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // subcompatible ID (none) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved + }; + + static uint8_t winusb_ext_prop_os_desc[] = { + 0x8e, 0x00, 0x00, 0x00, // dwLength + 0x00, 0x01, // bcdVersion + 0x05, 0x00, // wIndex + 0x01, 0x00, // wCount + // first property + 0x84, 0x00, 0x00, 0x00, // dwSize + 0x01, 0x00, 0x00, 0x00, // dwPropertyDataType + 0x28, 0x00, // wPropertyNameLength + 'D',0, 'e',0, 'v',0, 'i',0, 'c',0, 'e',0, 'I',0, 'n',0, 't',0, 'e',0, 'r',0, 'f',0, 'a',0, 'c',0, 'e',0, 'G',0, 'U',0, 'I',0, 'D',0, 0, 0, // bPropertyName (DeviceInterfaceGUID) + 0x4e, 0x00, 0x00, 0x00, // dwPropertyDataLength + '{',0, 'c',0, 'c',0, 'e',0, '5',0, '2',0, '9',0, '1',0, 'c',0, '-',0, 'a',0, '6',0, '9',0, 'f',0, '-',0, '4',0 ,'9',0 ,'9',0 ,'5',0 ,'-',0, 'a',0, '4',0, 'c',0, '2',0, '-',0, '2',0, 'a',0, 'e',0, '5',0, '7',0, 'a',0, '5',0, '1',0, 'a',0, 'd',0, 'e',0, '9',0, '}',0, 0, 0, // bPropertyData ({CCE5291C-A69F-4995-A4C2-2AE57A51ADE9}) + }; + + /* + Binary Object Store descriptor used to expose WebUSB (and more WinUSB) metadata + comments are from the wicg spec + References used: + https://wicg.github.io/webusb/#webusb-platform-capability-descriptor + https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c + https://os.mbed.com/users/larsgk/code/USBDevice_WebUSB/file/1d8a6665d607/WebUSBDevice/ + */ + static uint8_t binary_object_store_desc[] = { + // BOS header + BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH, // bLength, this is only the length of the header + BINARY_OBJECT_STORE_DESCRIPTOR, // bDescriptorType + 0x39, 0x00, // wTotalLength (LSB, MSB) + 0x02, // bNumDeviceCaps (WebUSB + WinUSB) + + // ------------------------------------------------- + // WebUSB descriptor + // header + 0x18, // bLength, Size of this descriptor. Must be set to 24. + 0x10, // bDescriptorType, DEVICE CAPABILITY descriptor + 0x05, // bDevCapabilityType, PLATFORM capability + 0x00, // bReserved, This field is reserved and shall be set to zero. + + // PlatformCapabilityUUID, Must be set to {3408b638-09a9-47a0-8bfd-a0768815b665}. + 0x38, 0xB6, 0x08, 0x34, + 0xA9, 0x09, 0xA0, 0x47, + 0x8B, 0xFD, 0xA0, 0x76, + 0x88, 0x15, 0xB6, 0x65, + // + + 0x00, 0x01, // bcdVersion, Protocol version supported. Must be set to 0x0100. + WEBUSB_VENDOR_CODE, // bVendorCode, bRequest value used for issuing WebUSB requests. + // there used to be a concept of "allowed origins", but it was removed from the spec + // it was intended to be a security feature, but then the entire security model relies on domain ownership + // https://github.com/WICG/webusb/issues/49 + // other implementations use various other indexed to leverate this no-longer-valid feature. we wont. + // the spec says we *must* reply to index 0x03 with the url, so we'll hint that that's the right index + 0x03, // iLandingPage, URL descriptor index of the device’s landing page. + + // ------------------------------------------------- + // WinUSB descriptor + // header + 0x1C, // Descriptor size (28 bytes) + 0x10, // Descriptor type (Device Capability) + 0x05, // Capability type (Platform) + 0x00, // Reserved + + // MS OS 2.0 Platform Capability ID (D8DD60DF-4589-4CC7-9CD2-659D9E648A9F) + // Indicates the device supports the Microsoft OS 2.0 descriptor + 0xDF, 0x60, 0xDD, 0xD8, + 0x89, 0x45, 0xC7, 0x4C, + 0x9C, 0xD2, 0x65, 0x9D, + 0x9E, 0x64, 0x8A, 0x9F, + + 0x00, 0x00, 0x03, 0x06, // Windows version, currently set to 8.1 (0x06030000) + + WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // MS OS 2.0 descriptor size (word) + MS_VENDOR_CODE, 0x00 // vendor code, no alternate enumeration + }; + + // WinUSB 2.0 descriptor. This is what modern systems use + // https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c + // http://janaxelson.com/files/ms_os_20_descriptors.c + // https://books.google.com/books?id=pkefBgAAQBAJ&pg=PA353&lpg=PA353 + static uint8_t winusb_20_desc[WINUSB_PLATFORM_DESCRIPTOR_LENGTH] = { + // Microsoft OS 2.0 descriptor set header (table 10) + 0x0A, 0x00, // Descriptor size (10 bytes) + 0x00, 0x00, // MS OS 2.0 descriptor set header + + 0x00, 0x00, 0x03, 0x06, // Windows version (8.1) (0x06030000) + WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // Total size of MS OS 2.0 descriptor set + + // Microsoft OS 2.0 compatible ID descriptor + 0x14, 0x00, // Descriptor size (20 bytes) + 0x03, 0x00, // MS OS 2.0 compatible ID descriptor + 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Sub-compatible ID + + // Registry property descriptor + 0x80, 0x00, // Descriptor size (130 bytes) + 0x04, 0x00, // Registry Property descriptor + 0x01, 0x00, // Strings are null-terminated Unicode + 0x28, 0x00, // Size of Property Name (40 bytes) "DeviceInterfaceGUID" + + // bPropertyName (DeviceInterfaceGUID) + 'D', 0x00, 'e', 0x00, 'v', 0x00, 'i', 0x00, 'c', 0x00, 'e', 0x00, 'I', 0x00, 'n', 0x00, + 't', 0x00, 'e', 0x00, 'r', 0x00, 'f', 0x00, 'a', 0x00, 'c', 0x00, 'e', 0x00, 'G', 0x00, + 'U', 0x00, 'I', 0x00, 'D', 0x00, 0x00, 0x00, + + 0x4E, 0x00, // Size of Property Data (78 bytes) + + // Vendor-defined property data: {CCE5291C-A69F-4995-A4C2-2AE57A51ADE9} + '{', 0x00, 'c', 0x00, 'c', 0x00, 'e', 0x00, '5', 0x00, '2', 0x00, '9', 0x00, '1', 0x00, // 16 + 'c', 0x00, '-', 0x00, 'a', 0x00, '6', 0x00, '9', 0x00, 'f', 0x00, '-', 0x00, '4', 0x00, // 32 + '9', 0x00, '9', 0x00, '5', 0x00, '-', 0x00, 'a', 0x00, '4', 0x00, 'c', 0x00, '2', 0x00, // 48 + '-', 0x00, '2', 0x00, 'a', 0x00, 'e', 0x00, '5', 0x00, '7', 0x00, 'a', 0x00, '5', 0x00, // 64 + '1', 0x00, 'a', 0x00, 'd', 0x00, 'e', 0x00, '9', 0x00, '}', 0x00, 0x00, 0x00 // 78 bytes + }; + int resp_len; ControlPacket_t control_req; @@ -639,7 +525,7 @@ void usb_setup(void) { void usb_irqhandler(void) { //USBx->GINTMSK = 0; - + static uint8_t usbdata[0x100] __attribute__((aligned(4))); unsigned int gintsts = USBx->GINTSTS; unsigned int gotgint = USBx->GOTGINT; unsigned int daint = USBx_DEVICE->DAINT; @@ -914,11 +800,3 @@ void can_tx_comms_resume_usb(void) { } EXIT_CRITICAL(); } - -void usb_soft_disconnect(bool enable) { - if (enable) { - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - } else { - USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_SDIS; - } -} diff --git a/panda/board/drivers/usb_declarations.h b/panda/board/drivers/usb_declarations.h new file mode 100644 index 000000000000000..77f6f5e816c0c68 --- /dev/null +++ b/panda/board/drivers/usb_declarations.h @@ -0,0 +1,115 @@ +#pragma once + +// IRQs: OTG_FS + +typedef union { + uint16_t w; + struct BW { + uint8_t msb; + uint8_t lsb; + } + bw; +} uint16_t_uint8_t; + +typedef union _USB_Setup { + uint32_t d8[2]; + struct _SetupPkt_Struc + { + uint8_t bmRequestType; + uint8_t bRequest; + uint16_t_uint8_t wValue; + uint16_t_uint8_t wIndex; + uint16_t_uint8_t wLength; + } b; +} USB_Setup_TypeDef; + +extern bool usb_enumerated; + +void usb_init(void); +void refresh_can_tx_slots_available(void); + +// **** supporting defines **** +#define USB_REQ_GET_STATUS 0x00 +#define USB_REQ_CLEAR_FEATURE 0x01 +#define USB_REQ_SET_FEATURE 0x03 +#define USB_REQ_SET_ADDRESS 0x05 +#define USB_REQ_GET_DESCRIPTOR 0x06 +#define USB_REQ_SET_DESCRIPTOR 0x07 +#define USB_REQ_GET_CONFIGURATION 0x08 +#define USB_REQ_SET_CONFIGURATION 0x09 +#define USB_REQ_GET_INTERFACE 0x0A +#define USB_REQ_SET_INTERFACE 0x0B +#define USB_REQ_SYNCH_FRAME 0x0C + +#define USB_DESC_TYPE_DEVICE 0x01 +#define USB_DESC_TYPE_CONFIGURATION 0x02 +#define USB_DESC_TYPE_STRING 0x03 +#define USB_DESC_TYPE_INTERFACE 0x04 +#define USB_DESC_TYPE_ENDPOINT 0x05 +#define USB_DESC_TYPE_DEVICE_QUALIFIER 0x06 +#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 0x07 +#define USB_DESC_TYPE_BINARY_OBJECT_STORE 0x0f + +// offsets for configuration strings +#define STRING_OFFSET_LANGID 0x00 +#define STRING_OFFSET_IMANUFACTURER 0x01 +#define STRING_OFFSET_IPRODUCT 0x02 +#define STRING_OFFSET_ISERIAL 0x03 +#define STRING_OFFSET_ICONFIGURATION 0x04 +#define STRING_OFFSET_IINTERFACE 0x05 + +// WebUSB requests +#define WEBUSB_REQ_GET_URL 0x02 + +// WebUSB types +#define WEBUSB_DESC_TYPE_URL 0x03 +#define WEBUSB_URL_SCHEME_HTTPS 0x01 +#define WEBUSB_URL_SCHEME_HTTP 0x00 + +// WinUSB requests +#define WINUSB_REQ_GET_COMPATID_DESCRIPTOR 0x04 +#define WINUSB_REQ_GET_EXT_PROPS_OS 0x05 +#define WINUSB_REQ_GET_DESCRIPTOR 0x07 + +#define STS_GOUT_NAK 1 +#define STS_DATA_UPDT 2 +#define STS_XFER_COMP 3 +#define STS_SETUP_COMP 4 +#define STS_SETUP_UPDT 6 + +// for the repeating interfaces +#define DSCR_INTERFACE_LEN 9 +#define DSCR_ENDPOINT_LEN 7 +#define DSCR_CONFIG_LEN 9 +#define DSCR_DEVICE_LEN 18 + +// endpoint types +#define ENDPOINT_TYPE_CONTROL 0 +#define ENDPOINT_TYPE_ISO 1 +#define ENDPOINT_TYPE_BULK 2 +#define ENDPOINT_TYPE_INT 3 + +// These are arbitrary values used in bRequest +#define MS_VENDOR_CODE 0x20 +#define WEBUSB_VENDOR_CODE 0x30 + +// BOS constants +#define BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH 0x05 +#define BINARY_OBJECT_STORE_DESCRIPTOR 0x0F +#define WINUSB_PLATFORM_DESCRIPTOR_LENGTH 0x9E + +// Convert machine byte order to USB byte order +#define TOUSBORDER(num)\ + ((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)\ + (((((size) * 2) + 2) & 0xFF) | 0x0300) + +#define ENDPOINT_RCV 0x80 +#define ENDPOINT_SND 0x00 + +// packet read and write +void usb_tick(void); +// ***************************** USB port ***************************** +void can_tx_comms_resume_usb(void); diff --git a/panda/board/drivers/watchdog.h b/panda/board/drivers/watchdog.h index 89cf01e07efc1f2..51337ba6ef2ee81 100644 --- a/panda/board/drivers/watchdog.h +++ b/panda/board/drivers/watchdog.h @@ -3,7 +3,7 @@ typedef enum { WATCHDOG_500_MS = 4000U, } WatchdogTimeout; -void watchdog_feed(void) { +static void watchdog_feed(void) { IND_WDG->KR = 0xAAAAU; } diff --git a/panda/board/early_init.h b/panda/board/early_init.h index 0e78274c3c93fa8..1837019d099431d 100644 --- a/panda/board/early_init.h +++ b/panda/board/early_init.h @@ -9,7 +9,7 @@ extern uint32_t enter_bootloader_mode; typedef void (*bootloader_fcn)(void); typedef bootloader_fcn *bootloader_fcn_ptr; -void jump_to_bootloader(void) { +static void jump_to_bootloader(void) { // do enter bootloader enter_bootloader_mode = 0; diff --git a/panda/board/faults.h b/panda/board/faults.h index dc6c1f2aa405c81..0fc9d2c5cfba146 100644 --- a/panda/board/faults.h +++ b/panda/board/faults.h @@ -1,38 +1,4 @@ -#define FAULT_STATUS_NONE 0U -#define FAULT_STATUS_TEMPORARY 1U -#define FAULT_STATUS_PERMANENT 2U - -// Fault types, matches cereal.log.PandaState.FaultType -#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) // deprecated -#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 +#include "faults_declarations.h" uint8_t fault_status = FAULT_STATUS_NONE; uint32_t faults = 0U; diff --git a/panda/board/faults_declarations.h b/panda/board/faults_declarations.h new file mode 100644 index 000000000000000..eab9fcc08bb7706 --- /dev/null +++ b/panda/board/faults_declarations.h @@ -0,0 +1,44 @@ +#pragma once + +#define FAULT_STATUS_NONE 0U +#define FAULT_STATUS_TEMPORARY 1U +#define FAULT_STATUS_PERMANENT 2U + +// Fault types, matches cereal.log.PandaState.FaultType +#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) // deprecated +#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) +#define FAULT_INTERRUPT_RATE_SOUND_DMA (1UL << 27) + +// Permanent faults +#define PERMANENT_FAULTS 0U + +extern uint8_t fault_status; +extern uint32_t faults; + +void fault_occurred(uint32_t fault); +void fault_recovered(uint32_t fault); diff --git a/panda/board/flash.py b/panda/board/flash.py index 903a6a645f22058..3943814625d0889 100755 --- a/panda/board/flash.py +++ b/panda/board/flash.py @@ -1,18 +1,27 @@ #!/usr/bin/env python3 import os import subprocess +import argparse from panda import Panda board_path = os.path.dirname(os.path.realpath(__file__)) if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--all", action="store_true", help="Recover all Panda devices") + args = parser.parse_args() + subprocess.check_call(f"scons -C {board_path}/.. -j$(nproc) {board_path}", shell=True) - serials = Panda.list() - print(f"found {len(serials)} panda(s) - {serials}") + if args.all: + serials = Panda.list() + print(f"found {len(serials)} panda(s) - {serials}") + else: + serials = [None] + for s in serials: - print("flashing", s) with Panda(serial=s) as p: + print("flashing", p.get_usb_serial()) p.flash() exit(1 if len(serials) == 0 else 0) diff --git a/panda/board/flasher.h b/panda/board/flasher.h index d6c2c4021137936..9a046a25d03f4d3 100644 --- a/panda/board/flasher.h +++ b/panda/board/flasher.h @@ -1,3 +1,10 @@ +// from the linker script +#ifdef STM32H7 + #define APP_START_ADDRESS 0x8020000U +#elif defined(STM32F4) + #define APP_START_ADDRESS 0x8004000U +#endif + // flasher state variables uint32_t *prog_ptr = NULL; bool unlocked = false; diff --git a/panda/board/gdb.sh b/panda/board/gdb.sh new file mode 100755 index 000000000000000..aa695d6ab70b74c --- /dev/null +++ b/panda/board/gdb.sh @@ -0,0 +1,3 @@ +#!/usr/bin/env bash + +gdb-multiarch --eval-command="target extended-remote localhost:3333" diff --git a/panda/board/jungle/flash.py b/panda/board/jungle/flash.py index 5b6c6e9046a6f21..8378169e4439daf 100755 --- a/panda/board/jungle/flash.py +++ b/panda/board/jungle/flash.py @@ -1,19 +1,27 @@ #!/usr/bin/env python3 import os import subprocess +import argparse from panda import PandaJungle board_path = os.path.dirname(os.path.realpath(__file__)) if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--all", action="store_true", help="Recover all panda jungle devices") + args = parser.parse_args() + subprocess.check_call(f"scons -C {board_path}/.. -u -j$(nproc) {board_path}", shell=True) - serials = PandaJungle.list() - print(f"found {len(serials)} panda jungle(s) - {serials}") + if args.all: + serials = PandaJungle.list() + print(f"found {len(serials)} panda jungles(s) - {serials}") + else: + serials = [None] + for s in serials: - print("flashing", s) with PandaJungle(serial=s) as p: + print("flashing", p.get_usb_serial()) p.flash() - exit(1 if len(serials) == 0 else 0) diff --git a/panda/board/jungle/main.c b/panda/board/jungle/main.c index 40777d9965e99d1..329ee98a1fb2ddd 100644 --- a/panda/board/jungle/main.c +++ b/panda/board/jungle/main.c @@ -156,10 +156,7 @@ int main(void) { print("\n\n\n************************ MAIN START ************************\n"); // check for non-supported board types - if (hw_type == HW_TYPE_UNKNOWN) { - print("Unsupported board type\n"); - while (1) { /* hang */ } - } + assert_fatal(hw_type != HW_TYPE_UNKNOWN, "Unsupported board type\n"); print("Config:\n"); print(" Board type: 0x"); puth(hw_type); print("\n"); diff --git a/panda/board/jungle/recover.py b/panda/board/jungle/recover.py index 19666c3edac451b..34c88e26ef75347 100755 --- a/panda/board/jungle/recover.py +++ b/panda/board/jungle/recover.py @@ -2,17 +2,23 @@ import os import time import subprocess +import argparse from panda import PandaJungle, PandaJungleDFU board_path = os.path.dirname(os.path.realpath(__file__)) if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--all", action="store_true", help="Recover all panda jungle devices") + args = parser.parse_args() + subprocess.check_call(f"scons -C {board_path}/.. -u -j$(nproc) {board_path}", shell=True) - for s in PandaJungle.list(): - print("putting", s, "in DFU mode") + serials = PandaJungle.list() if args.all else [None] + for s in serials: with PandaJungle(serial=s) as p: + print(f"putting {p.get_usb_serial()} in DFU mode") p.reset(enter_bootstub=True) p.reset(enter_bootloader=True) diff --git a/panda/board/jungle/scripts/can_health.py b/panda/board/jungle/scripts/can_health.py index ff068b5baa150a4..47efbb2e67378e3 100755 --- a/panda/board/jungle/scripts/can_health.py +++ b/panda/board/jungle/scripts/can_health.py @@ -1,13 +1,29 @@ #!/usr/bin/env python3 - import time +import re from panda import PandaJungle +RED = '\033[91m' +GREEN = '\033[92m' + +def colorize_errors(value): + if isinstance(value, str): + if re.search(r'(?i)No error', value): + return f'{GREEN}{value}\033[0m' + elif re.search(r'(?i)(? 0.1: dd = chr(27) + "[2J" dd += "%5.2f\n" % (sec_since_boot() - start) - for k,v in sorted(zip(list(msgs.keys()), [binascii.hexlify(x[-1]) for x in list(msgs.values())], strict=True)): - dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k,k),len(msgs[k]), v) + for (addr, bus), dat_log in sorted(all_msgs.items()): + dd += "%d: %s(%6d): %s\n" % (bus, "%04X(%4d)" % (addr, addr), len(dat_log), binascii.hexlify(dat_log[-1]).decode()) print(dd) lp = sec_since_boot() diff --git a/panda/board/jungle/scripts/echo_loopback_test.py b/panda/board/jungle/scripts/echo_loopback_test.py index 78b65b5341a339e..2cc523c8fa7b718 100755 --- a/panda/board/jungle/scripts/echo_loopback_test.py +++ b/panda/board/jungle/scripts/echo_loopback_test.py @@ -37,7 +37,7 @@ def test_loopback(): incoming = jungle.can_recv() found = False for message in incoming: - incomingAddress, _, incomingData, incomingBus = message + incomingAddress, incomingData, incomingBus = message if incomingAddress == address and incomingData == data[::-1] and incomingBus == bus: found = True break diff --git a/panda/board/jungle/scripts/loopback_test.py b/panda/board/jungle/scripts/loopback_test.py index 10caf42cc4f52ce..b7be5586b9f65e1 100755 --- a/panda/board/jungle/scripts/loopback_test.py +++ b/panda/board/jungle/scripts/loopback_test.py @@ -74,11 +74,11 @@ def can_loopback(sender): raise Exception("Amount of received CAN messages (" + str(len(content)) + ") does not equal 1. Bus: " + str(bus) +" OBD: " + str(obd)) # Check content - if content[0][0] != addr or content[0][2] != string: + if content[0][0] != addr or content[0][1] != string: raise Exception("Received CAN message content or address does not match") # Check bus - if content[0][3] != bus: + if content[0][2] != bus: raise Exception("Received CAN message bus does not match") ################################################################# diff --git a/panda/board/jungle/scripts/spam_can.py b/panda/board/jungle/scripts/spam_can.py new file mode 100755 index 000000000000000..c3d798b473aaba8 --- /dev/null +++ b/panda/board/jungle/scripts/spam_can.py @@ -0,0 +1,20 @@ +#!/usr/bin/env python3 +import os +import random +from panda import PandaJungle + +def get_test_string(): + return b"test" + os.urandom(10) + +if __name__ == "__main__": + p = PandaJungle() + + p.set_safety_mode(PandaJungle.SAFETY_ALLOUTPUT) + + print("Spamming all buses...") + while True: + at = random.randint(1, 2000) + st = get_test_string()[0:8] + bus = random.randint(0, 2) + p.can_send(at, st, bus) + # print("Sent message on bus: ", bus) diff --git a/panda/board/libc.h b/panda/board/libc.h index 7f669b95ab98519..c5f02193509ae94 100644 --- a/panda/board/libc.h +++ b/panda/board/libc.h @@ -5,6 +5,16 @@ void delay(uint32_t a) { for (i = 0; i < a; i++); } +void assert_fatal(bool condition, const char *msg) { + if (!condition) { + print("ASSERT FAILED\n"); + print(msg); + while (1) { + // hang + } + } +} + // cppcheck-suppress misra-c2012-21.2 void *memset(void *str, int c, unsigned int n) { uint8_t *s = str; diff --git a/panda/board/main.c b/panda/board/main.c index b481c28b46847df..b1dc685417df9dc 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -31,7 +31,7 @@ // ********************* Serial debugging ********************* -bool check_started(void) { +static bool check_started(void) { bool started = current_board->check_ignition() || ignition_can; return started; } @@ -67,12 +67,8 @@ void set_safety_mode(uint16_t mode, uint16_t param) { print("Error: safety set mode failed. Falling back to SILENT\n"); mode_copy = SAFETY_SILENT; err = set_safety_hooks(mode_copy, 0U); - if (err == -1) { - print("Error: Failed setting SILENT mode. Hanging\n"); - while (true) { - // TERMINAL ERROR: we can't continue if SILENT safety mode isn't succesfully set - } - } + // TERMINAL ERROR: we can't continue if SILENT safety mode isn't succesfully set + assert_fatal(err == 0, "Error: Failed setting SILENT mode. Hanging\n"); } safety_tx_blocked = 0; safety_rx_invalid = 0; @@ -99,7 +95,7 @@ void set_safety_mode(uint16_t mode, uint16_t param) { if (current_board->has_obd) { // Clear any pending messages in the can core (i.e. sending while comma power is unplugged) // TODO: rewrite using hardware queues rather than fifo to cancel specific messages - llcan_clear_send(CANIF_FROM_CAN_NUM(1)); + can_clear_send(CANIF_FROM_CAN_NUM(1), 1); if (param == 0U) { current_board->set_can_mode(CAN_MODE_OBD_CAN2); } else { @@ -131,11 +127,12 @@ bool is_car_safety_mode(uint16_t mode) { // ***************************** main code ***************************** // cppcheck-suppress unusedFunction ; used in headers not included in cppcheck +// cppcheck-suppress misra-c2012-8.4 void __initialize_hardware_early(void) { early_initialization(); } -void __attribute__ ((noinline)) enable_fpu(void) { +static void __attribute__ ((noinline)) enable_fpu(void) { // enable the FPU SCB->CPACR |= ((3UL << (10U * 2U)) | (3UL << (11U * 2U))); } @@ -145,9 +142,12 @@ void __attribute__ ((noinline)) enable_fpu(void) { #define HEARTBEAT_IGNITION_CNT_OFF 2U // called at 8Hz -uint8_t loop_counter = 0U; -uint8_t prev_harness_status = HARNESS_STATUS_NC; -void tick_handler(void) { +static void tick_handler(void) { + static uint32_t siren_countdown = 0; // siren plays while countdown > 0 + static uint32_t controls_allowed_countdown = 0; + static uint8_t prev_harness_status = HARNESS_STATUS_NC; + static uint8_t loop_counter = 0U; + if (TICK_TIMER->SR != 0U) { // siren @@ -158,6 +158,7 @@ void tick_handler(void) { usb_tick(); harness_tick(); simple_watchdog_kick(); + sound_tick(); // re-init everything that uses harness status if (harness.status != prev_harness_status) { @@ -314,10 +315,7 @@ int main(void) { print("\n\n\n************************ MAIN START ************************\n"); // check for non-supported board types - if(hw_type == HW_TYPE_UNKNOWN){ - print("Unsupported board type\n"); - while (1) { /* hang */ } - } + assert_fatal(hw_type != HW_TYPE_UNKNOWN, "Unsupported board type"); print("Config:\n"); print(" Board type: 0x"); puth(hw_type); print("\n"); @@ -328,12 +326,13 @@ int main(void) { // panda has an FPU, let's use it! enable_fpu(); + microsecond_timer_init(); + + current_board->set_siren(false); if (current_board->fan_max_rpm > 0U) { fan_init(); } - microsecond_timer_init(); - // init to SILENT and can silent set_safety_mode(SAFETY_SILENT, 0U); diff --git a/panda/board/main_comms.h b/panda/board/main_comms.h index 4c5d509624742d4..7d754d050f7f927 100644 --- a/panda/board/main_comms.h +++ b/panda/board/main_comms.h @@ -4,7 +4,7 @@ extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used void set_safety_mode(uint16_t mode, uint16_t param); bool is_car_safety_mode(uint16_t mode); -int get_health_pkt(void *dat) { +static int get_health_pkt(void *dat) { COMPILE_TIME_ASSERT(sizeof(struct health_t) <= USBPACKET_MAX_SIZE); struct health_t * health = (struct health_t*)dat; @@ -117,7 +117,7 @@ int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { can_health[req->param1].brs_enabled = bus_config[req->param1].brs_enabled; can_health[req->param1].canfd_non_iso = bus_config[req->param1].canfd_non_iso; resp_len = sizeof(can_health[req->param1]); - (void)memcpy(resp, &can_health[req->param1], resp_len); + (void)memcpy(resp, (uint8_t*)(&can_health[req->param1]), resp_len); } break; // **** 0xc3: fetch MCU UID diff --git a/panda/board/main_declarations.h b/panda/board/main_declarations.h index a1496c0d0ac235d..2704a01a0322900 100644 --- a/panda/board/main_declarations.h +++ b/panda/board/main_declarations.h @@ -1,3 +1,5 @@ +#pragma once + // ******************** Prototypes ******************** void print(const char *a); void puth(unsigned int i); @@ -10,18 +12,15 @@ void pwm_init(TIM_TypeDef *TIM, uint8_t channel); void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage); // ********************* Globals ********************** -uint8_t hw_type = 0; -board *current_board; -uint32_t uptime_cnt = 0; -bool green_led_enabled = false; +extern uint8_t hw_type; +extern board *current_board; +extern uint32_t uptime_cnt; +extern bool green_led_enabled; // heartbeat state -uint32_t heartbeat_counter = 0; -bool heartbeat_lost = false; -bool heartbeat_disabled = false; // set over USB +extern uint32_t heartbeat_counter; +extern bool heartbeat_lost; +extern bool heartbeat_disabled; // set over USB // siren state -bool siren_enabled = false; -uint32_t siren_countdown = 0; // siren plays while countdown > 0 -uint32_t controls_allowed_countdown = 0; - +extern bool siren_enabled; diff --git a/panda/board/main_definitions.h b/panda/board/main_definitions.h new file mode 100644 index 000000000000000..137d987362c37b0 --- /dev/null +++ b/panda/board/main_definitions.h @@ -0,0 +1,15 @@ +#include "main_declarations.h" + +// ********************* Globals ********************** +uint8_t hw_type = 0; +board *current_board; +uint32_t uptime_cnt = 0; +bool green_led_enabled = false; + +// heartbeat state +uint32_t heartbeat_counter = 0; +bool heartbeat_lost = false; +bool heartbeat_disabled = false; // set over USB + +// siren state +bool siren_enabled = false; diff --git a/panda/board/power_saving.h b/panda/board/power_saving.h index 61541cae9eec7bb..7fcc181ea9e08fd 100644 --- a/panda/board/power_saving.h +++ b/panda/board/power_saving.h @@ -1,9 +1,8 @@ +#include "power_saving_declarations.h" + // WARNING: To stay in compliance with the SIL2 rules laid out in STM UM1840, we should never implement any of the available hardware low power modes. // See rule: CoU_3 -#define POWER_SAVE_STATUS_DISABLED 0 -#define POWER_SAVE_STATUS_ENABLED 1 - int power_save_status = POWER_SAVE_STATUS_DISABLED; void set_power_save_state(int state) { diff --git a/panda/board/power_saving_declarations.h b/panda/board/power_saving_declarations.h new file mode 100644 index 000000000000000..7a474a559492dae --- /dev/null +++ b/panda/board/power_saving_declarations.h @@ -0,0 +1,11 @@ +#pragma once + +// WARNING: To stay in compliance with the SIL2 rules laid out in STM UM1840, we should never implement any of the available hardware low power modes. +// See rule: CoU_3 + +#define POWER_SAVE_STATUS_DISABLED 0 +#define POWER_SAVE_STATUS_ENABLED 1 + +extern int power_save_status; + +void set_power_save_state(int state); diff --git a/panda/board/provision.h b/panda/board/provision.h index 2a8ce893d3d0663..d191e53f677dc24 100644 --- a/panda/board/provision.h +++ b/panda/board/provision.h @@ -3,9 +3,9 @@ #define PROVISION_CHUNK_LEN 0x20 -const unsigned 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) { + const unsigned 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)memcpy(resp, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); if (memcmp(resp, unprovisioned_text, 0x20) == 0) { (void)memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20); diff --git a/panda/board/recover.py b/panda/board/recover.py index 0a248525a8000b4..c149e948d197671 100755 --- a/panda/board/recover.py +++ b/panda/board/recover.py @@ -2,17 +2,23 @@ import os import time import subprocess +import argparse from panda import Panda, PandaDFU board_path = os.path.dirname(os.path.realpath(__file__)) if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--all", action="store_true", help="Recover all Panda devices") + args = parser.parse_args() + subprocess.check_call(f"scons -C {board_path}/.. -j$(nproc) {board_path}", shell=True) - for s in Panda.list(): - print("putting", s, "in DFU mode") + serials = Panda.list() if args.all else [None] + for s in serials: with Panda(serial=s) as p: + print(f"putting {p.get_usb_serial()} in DFU mode") p.reset(enter_bootstub=True) p.reset(enter_bootloader=True) diff --git a/panda/board/safety.h b/panda/board/safety.h index 048d7cca4899125..913109957cba832 100644 --- a/panda/board/safety.h +++ b/panda/board/safety.h @@ -1,5 +1,7 @@ +#pragma once + #include "safety_declarations.h" -#include "can_definitions.h" +#include "can.h" // include the safety policies. #include "safety/safety_defaults.h" @@ -52,11 +54,156 @@ #define SAFETY_BODY 27U #define SAFETY_HYUNDAI_CANFD 28U +uint32_t GET_BYTES(const CANPacket_t *msg, int start, int len) { + uint32_t ret = 0U; + for (int i = 0; i < len; i++) { + const uint32_t shift = i * 8; + ret |= (((uint32_t)msg->data[start + i]) << shift); + } + return ret; +} + +const int MAX_WRONG_COUNTERS = 5; + +// This can be set by the safety hooks +bool controls_allowed = false; +bool relay_malfunction = false; +bool gas_pressed = false; +bool gas_pressed_prev = false; +bool brake_pressed = false; +bool brake_pressed_prev = false; +bool regen_braking = false; +bool regen_braking_prev = false; +bool cruise_engaged_prev = false; +struct sample_t vehicle_speed; +bool vehicle_moving = false; +bool acc_main_on = false; // referred to as "ACC off" in ISO 15622:2018 +int cruise_button_prev = 0; +bool safety_rx_checks_invalid = false; + +// for safety modes with torque steering control +int desired_torque_last = 0; // last desired steer torque +int rt_torque_last = 0; // last desired torque for real time check +int valid_steer_req_count = 0; // counter for steer request bit matching non-zero torque +int invalid_steer_req_count = 0; // counter to allow multiple frames of mismatching torque request bit +struct sample_t torque_meas; // last 6 motor torques produced by the eps +struct sample_t torque_driver; // last 6 driver torques measured +uint32_t ts_torque_check_last = 0; +uint32_t ts_steer_req_mismatch_last = 0; // last timestamp steer req was mismatched with torque + +// state for controls_allowed timeout logic +bool heartbeat_engaged = false; // openpilot enabled, passed in heartbeat USB command +uint32_t heartbeat_engaged_mismatches = 0; // count of mismatches between heartbeat_engaged and controls_allowed + +// for safety modes with angle steering control +uint32_t ts_angle_last = 0; +int desired_angle_last = 0; +struct sample_t angle_meas; // last 6 steer angles/curvatures + + +int alternative_experience = 0; + +// time since safety mode has been changed +uint32_t safety_mode_cnt = 0U; + uint16_t current_safety_mode = SAFETY_SILENT; uint16_t current_safety_param = 0; -const safety_hooks *current_hooks = &nooutput_hooks; +static const safety_hooks *current_hooks = &nooutput_hooks; safety_config current_safety_config; +static bool is_msg_valid(RxCheck addr_list[], int index) { + bool valid = true; + if (index != -1) { + 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; + } + } + return valid; +} + +static 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); + + 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].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].status.index = j; + addr_list[i].status.msg_seen = true; + break; + } + } + } + + 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; + break; + } + } + } + return index; +} + +static void update_addr_timestamp(RxCheck addr_list[], int index) { + if (index != -1) { + uint32_t ts = microsecond_timer_get(); + addr_list[index].status.last_timestamp = ts; + } +} + +static void update_counter(RxCheck addr_list[], int index, uint8_t counter) { + if (index != -1) { + 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; + } +} + +static 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, cfg->rx_checks, cfg->rx_checks_len); + update_addr_timestamp(cfg->rx_checks, index); + + if (index != -1) { + // checksum check + 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 { + cfg->rx_checks[index].status.valid_checksum = true; + } + + // counter check (max_counter == 0 means skip check) + 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 { + cfg->rx_checks[index].status.wrong_counters = 0U; + } + + // quality flag check + 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 { + cfg->rx_checks[index].status.valid_quality_flag = true; + } + } + return is_msg_valid(cfg->rx_checks, index); +} + bool safety_rx_hook(const CANPacket_t *to_push) { bool controls_allowed_prev = controls_allowed; @@ -73,6 +220,21 @@ bool safety_rx_hook(const CANPacket_t *to_push) { return valid; } +static 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); + + bool allowed = false; + for (int i = 0; i < len; i++) { + if ((addr == msg_list[i].addr) && (bus == msg_list[i].bus) && (length == msg_list[i].len)) { + allowed = true; + break; + } + } + return allowed; +} + 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)) { @@ -107,6 +269,7 @@ void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]) { } } +#ifdef CANFD void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) { for (uint16_t i = 0; i < 256U; i++) { uint16_t crc = i << 8U; @@ -120,55 +283,11 @@ void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) { crc_lut[i] = crc; } } - -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); - - bool allowed = false; - for (int i = 0; i < len; i++) { - if ((addr == msg_list[i].addr) && (bus == msg_list[i].bus) && (length == msg_list[i].len)) { - allowed = true; - break; - } - } - return allowed; -} - -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); - - 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].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].status.index = j; - addr_list[i].status.msg_seen = true; - break; - } - } - } - - 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; - break; - } - } - } - return index; -} +#endif // 1Hz safety function called by main. Now just a check for lagging safety messages void safety_tick(const safety_config *cfg) { + const uint8_t MAX_MISSED_MSGS = 10U; bool rx_checks_invalid = false; uint32_t ts = microsecond_timer_get(); if (cfg != NULL) { @@ -193,69 +312,15 @@ void safety_tick(const safety_config *cfg) { safety_rx_checks_invalid = rx_checks_invalid; } -void update_counter(RxCheck addr_list[], int index, uint8_t counter) { - if (index != -1) { - 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(RxCheck addr_list[], int index) { - bool valid = true; - if (index != -1) { - 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; - } - } - return valid; -} - -void update_addr_timestamp(RxCheck addr_list[], int index) { - if (index != -1) { - uint32_t ts = microsecond_timer_get(); - addr_list[index].status.last_timestamp = ts; - } -} - -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, cfg->rx_checks, cfg->rx_checks_len); - update_addr_timestamp(cfg->rx_checks, index); - - if (index != -1) { - // checksum check - 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 { - cfg->rx_checks[index].status.valid_checksum = true; - } - - // counter check (max_counter == 0 means skip check) - 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 { - cfg->rx_checks[index].status.wrong_counters = 0U; - } - - // quality flag check - 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 { - cfg->rx_checks[index].status.valid_quality_flag = true; - } - } - return is_msg_valid(cfg->rx_checks, index); +static void relay_malfunction_set(void) { + relay_malfunction = true; + fault_occurred(FAULT_RELAY_MALFUNCTION); } void generic_rx_checks(bool stock_ecu_detected) { + // allow 1s of transition timeout after relay changes state before assessing malfunctioning + const uint32_t RELAY_TRNS_TIMEOUT = 1U; + // exit controls on rising edge of gas press if (gas_pressed && !gas_pressed_prev && !(alternative_experience & ALT_EXP_DISABLE_DISENGAGE_ON_GAS)) { controls_allowed = false; @@ -280,50 +345,48 @@ void generic_rx_checks(bool stock_ecu_detected) { } } -void relay_malfunction_set(void) { - relay_malfunction = true; - fault_occurred(FAULT_RELAY_MALFUNCTION); -} - -void relay_malfunction_reset(void) { +static void relay_malfunction_reset(void) { relay_malfunction = false; fault_recovered(FAULT_RELAY_MALFUNCTION); } -typedef struct { - uint16_t id; - const safety_hooks *hooks; -} safety_hook_config; - -const safety_hook_config safety_hook_registry[] = { - {SAFETY_SILENT, &nooutput_hooks}, - {SAFETY_HONDA_NIDEC, &honda_nidec_hooks}, - {SAFETY_TOYOTA, &toyota_hooks}, - {SAFETY_ELM327, &elm327_hooks}, - {SAFETY_GM, &gm_hooks}, - {SAFETY_HONDA_BOSCH, &honda_bosch_hooks}, - {SAFETY_HYUNDAI, &hyundai_hooks}, - {SAFETY_CHRYSLER, &chrysler_hooks}, - {SAFETY_SUBARU, &subaru_hooks}, - {SAFETY_VOLKSWAGEN_MQB, &volkswagen_mqb_hooks}, - {SAFETY_NISSAN, &nissan_hooks}, - {SAFETY_NOOUTPUT, &nooutput_hooks}, - {SAFETY_HYUNDAI_LEGACY, &hyundai_legacy_hooks}, - {SAFETY_MAZDA, &mazda_hooks}, - {SAFETY_BODY, &body_hooks}, - {SAFETY_FORD, &ford_hooks}, +// resets values and min/max for sample_t struct +static void reset_sample(struct sample_t *sample) { + for (int i = 0; i < MAX_SAMPLE_VALS; i++) { + sample->values[i] = 0; + } + update_sample(sample, 0); +} + +int set_safety_hooks(uint16_t mode, uint16_t param) { + const safety_hook_config safety_hook_registry[] = { + {SAFETY_SILENT, &nooutput_hooks}, + {SAFETY_HONDA_NIDEC, &honda_nidec_hooks}, + {SAFETY_TOYOTA, &toyota_hooks}, + {SAFETY_ELM327, &elm327_hooks}, + {SAFETY_GM, &gm_hooks}, + {SAFETY_HONDA_BOSCH, &honda_bosch_hooks}, + {SAFETY_HYUNDAI, &hyundai_hooks}, + {SAFETY_CHRYSLER, &chrysler_hooks}, + {SAFETY_SUBARU, &subaru_hooks}, + {SAFETY_VOLKSWAGEN_MQB, &volkswagen_mqb_hooks}, + {SAFETY_NISSAN, &nissan_hooks}, + {SAFETY_NOOUTPUT, &nooutput_hooks}, + {SAFETY_HYUNDAI_LEGACY, &hyundai_legacy_hooks}, + {SAFETY_MAZDA, &mazda_hooks}, + {SAFETY_BODY, &body_hooks}, + {SAFETY_FORD, &ford_hooks}, #ifdef CANFD - {SAFETY_HYUNDAI_CANFD, &hyundai_canfd_hooks}, + {SAFETY_HYUNDAI_CANFD, &hyundai_canfd_hooks}, #endif #ifdef ALLOW_DEBUG - {SAFETY_TESLA, &tesla_hooks}, - {SAFETY_SUBARU_PREGLOBAL, &subaru_preglobal_hooks}, - {SAFETY_VOLKSWAGEN_PQ, &volkswagen_pq_hooks}, - {SAFETY_ALLOUTPUT, &alloutput_hooks}, + {SAFETY_TESLA, &tesla_hooks}, + {SAFETY_SUBARU_PREGLOBAL, &subaru_preglobal_hooks}, + {SAFETY_VOLKSWAGEN_PQ, &volkswagen_pq_hooks}, + {SAFETY_ALLOUTPUT, &alloutput_hooks}, #endif -}; + }; -int set_safety_hooks(uint16_t mode, uint16_t param) { // reset state set by safety mode safety_mode_cnt = 0U; relay_malfunction = false; @@ -415,20 +478,12 @@ void update_sample(struct sample_t *sample, int sample_new) { } } -// resets values and min/max for sample_t struct -void reset_sample(struct sample_t *sample) { - for (int i = 0; i < MAX_SAMPLE_VALS; i++) { - sample->values[i] = 0; - } - update_sample(sample, 0); -} - -bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) { +static bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) { return (val > MAX_VAL) || (val < MIN_VAL); } // check that commanded torque value isn't too far from measured -bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, +static 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) { // *** val rate limit check *** @@ -444,7 +499,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, const struct sample_t *val_driver, +static 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) { @@ -468,7 +523,7 @@ bool driver_limit_check(int val, int val_last, const struct sample_t *val_driver // real time check, mainly used for steer torque rate limiter -bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) { +static bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) { // *** torque real time rate limit check *** int highest_val = MAX(val_last, 0) + MAX_RT_DELTA; @@ -480,7 +535,7 @@ bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) { // interp function that holds extreme values -float interpolate(struct lookup_t xy, float x) { +static float interpolate(struct lookup_t xy, float x) { int size = sizeof(xy.x) / sizeof(xy.x[0]); float ret = xy.y[size - 1]; // default output is last point diff --git a/panda/board/safety/safety_body.h b/panda/board/safety/safety_body.h index 2ebca280f13dfbf..fcba1b577ab9508 100644 --- a/panda/board/safety/safety_body.h +++ b/panda/board/safety/safety_body.h @@ -1,10 +1,6 @@ -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 - {0x1, 0, 8}}; // CAN flasher +#pragma once -RxCheck body_rx_checks[] = { - {.msg = {{0x201, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, -}; +#include "safety_declarations.h" static void body_rx_hook(const CANPacket_t *to_push) { // body is never at standstill @@ -34,6 +30,14 @@ static bool body_tx_hook(const CANPacket_t *to_send) { } static safety_config body_init(uint16_t param) { + static RxCheck body_rx_checks[] = { + {.msg = {{0x201, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, + }; + + static 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 + {0x1, 0, 8}}; // CAN flasher + UNUSED(param); return BUILD_SAFETY_CFG(body_rx_checks, BODY_TX_MSGS); } diff --git a/panda/board/safety/safety_chrysler.h b/panda/board/safety/safety_chrysler.h index be27832c9dda27d..2bbc9427154f649 100644 --- a/panda/board/safety/safety_chrysler.h +++ b/panda/board/safety/safety_chrysler.h @@ -1,32 +1,6 @@ -const SteeringLimits CHRYSLER_STEERING_LIMITS = { - .max_steer = 261, - .max_rt_delta = 112, - .max_rt_interval = 250000, - .max_rate_up = 3, - .max_rate_down = 3, - .max_torque_error = 80, - .type = TorqueMotorLimited, -}; - -const SteeringLimits CHRYSLER_RAM_DT_STEERING_LIMITS = { - .max_steer = 350, - .max_rt_delta = 112, - .max_rt_interval = 250000, - .max_rate_up = 6, - .max_rate_down = 6, - .max_torque_error = 80, - .type = TorqueMotorLimited, -}; +#pragma once -const SteeringLimits CHRYSLER_RAM_HD_STEERING_LIMITS = { - .max_steer = 361, - .max_rt_delta = 182, - .max_rt_interval = 250000, - .max_rate_up = 14, - .max_rate_down = 14, - .max_torque_error = 80, - .type = TorqueMotorLimited, -}; +#include "safety_declarations.h" typedef struct { const int EPS_2; @@ -39,97 +13,13 @@ typedef struct { const int CRUISE_BUTTONS; } ChryslerAddrs; -// CAN messages for Chrysler/Jeep platforms -const ChryslerAddrs CHRYSLER_ADDRS = { - .EPS_2 = 0x220, // EPS driver input torque - .ESP_1 = 0x140, // Brake pedal and vehicle speed - .ESP_8 = 0x11C, // Brake pedal and vehicle speed - .ECM_5 = 0x22F, // Throttle position sensor - .DAS_3 = 0x1F4, // ACC engagement states from DASM - .DAS_6 = 0x2A6, // LKAS HUD and auto headlight control from DASM - .LKAS_COMMAND = 0x292, // LKAS controls from DASM - .CRUISE_BUTTONS = 0x23B, // Cruise control buttons -}; - -// CAN messages for the 5th gen RAM DT platform -const ChryslerAddrs CHRYSLER_RAM_DT_ADDRS = { - .EPS_2 = 0x31, // EPS driver input torque - .ESP_1 = 0x83, // Brake pedal and vehicle speed - .ESP_8 = 0x79, // Brake pedal and vehicle speed - .ECM_5 = 0x9D, // Throttle position sensor - .DAS_3 = 0x99, // ACC engagement states from DASM - .DAS_6 = 0xFA, // LKAS HUD and auto headlight control from DASM - .LKAS_COMMAND = 0xA6, // LKAS controls from DASM - .CRUISE_BUTTONS = 0xB1, // Cruise control buttons -}; - -// CAN messages for the 5th gen RAM HD platform -const ChryslerAddrs CHRYSLER_RAM_HD_ADDRS = { - .EPS_2 = 0x220, // EPS driver input torque - .ESP_1 = 0x140, // Brake pedal and vehicle speed - .ESP_8 = 0x11C, // Brake pedal and vehicle speed - .ECM_5 = 0x22F, // Throttle position sensor - .DAS_3 = 0x1F4, // ACC engagement states from DASM - .DAS_6 = 0x275, // LKAS HUD and auto headlight control from DASM - .LKAS_COMMAND = 0x276, // LKAS controls from DASM - .CRUISE_BUTTONS = 0x23A, // Cruise control buttons -}; - -const CanMsg CHRYSLER_TX_MSGS[] = { - {CHRYSLER_ADDRS.CRUISE_BUTTONS, 0, 3}, - {CHRYSLER_ADDRS.LKAS_COMMAND, 0, 6}, - {CHRYSLER_ADDRS.DAS_6, 0, 8}, -}; - -const CanMsg CHRYSLER_RAM_DT_TX_MSGS[] = { - {CHRYSLER_RAM_DT_ADDRS.CRUISE_BUTTONS, 2, 3}, - {CHRYSLER_RAM_DT_ADDRS.LKAS_COMMAND, 0, 8}, - {CHRYSLER_RAM_DT_ADDRS.DAS_6, 0, 8}, -}; - -const CanMsg CHRYSLER_RAM_HD_TX_MSGS[] = { - {CHRYSLER_RAM_HD_ADDRS.CRUISE_BUTTONS, 2, 3}, - {CHRYSLER_RAM_HD_ADDRS.LKAS_COMMAND, 0, 8}, - {CHRYSLER_RAM_HD_ADDRS.DAS_6, 0, 8}, -}; - -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 }}}, -}; - -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 }}}, -}; - -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 }}}, -}; - - - -const uint32_t CHRYSLER_PARAM_RAM_DT = 1U; // set for Ram DT platform -const uint32_t CHRYSLER_PARAM_RAM_HD = 2U; // set for Ram HD platform - typedef enum { CHRYSLER_RAM_DT, CHRYSLER_RAM_HD, CHRYSLER_PACIFICA, // plus Jeep } ChryslerPlatform; -ChryslerPlatform chrysler_platform = CHRYSLER_PACIFICA; -const ChryslerAddrs *chrysler_addrs = &CHRYSLER_ADDRS; +static ChryslerPlatform chrysler_platform; +static const ChryslerAddrs *chrysler_addrs; static uint32_t chrysler_get_checksum(const CANPacket_t *to_push) { int checksum_byte = GET_LEN(to_push) - 1U; @@ -215,6 +105,36 @@ static void chrysler_rx_hook(const CANPacket_t *to_push) { } static bool chrysler_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits CHRYSLER_STEERING_LIMITS = { + .max_steer = 261, + .max_rt_delta = 112, + .max_rt_interval = 250000, + .max_rate_up = 3, + .max_rate_down = 3, + .max_torque_error = 80, + .type = TorqueMotorLimited, + }; + + const SteeringLimits CHRYSLER_RAM_DT_STEERING_LIMITS = { + .max_steer = 350, + .max_rt_delta = 112, + .max_rt_interval = 250000, + .max_rate_up = 6, + .max_rate_down = 6, + .max_torque_error = 80, + .type = TorqueMotorLimited, + }; + + const SteeringLimits CHRYSLER_RAM_HD_STEERING_LIMITS = { + .max_steer = 361, + .max_rt_delta = 182, + .max_rt_interval = 250000, + .max_rate_up = 14, + .max_rate_down = 14, + .max_torque_error = 80, + .type = TorqueMotorLimited, + }; + bool tx = true; int addr = GET_ADDR(to_send); @@ -264,15 +184,103 @@ static int chrysler_fwd_hook(int bus_num, int addr) { } static safety_config chrysler_init(uint16_t param) { + + const uint32_t CHRYSLER_PARAM_RAM_DT = 1U; // set for Ram DT platform + + // CAN messages for Chrysler/Jeep platforms + static const ChryslerAddrs CHRYSLER_ADDRS = { + .EPS_2 = 0x220, // EPS driver input torque + .ESP_1 = 0x140, // Brake pedal and vehicle speed + .ESP_8 = 0x11C, // Brake pedal and vehicle speed + .ECM_5 = 0x22F, // Throttle position sensor + .DAS_3 = 0x1F4, // ACC engagement states from DASM + .DAS_6 = 0x2A6, // LKAS HUD and auto headlight control from DASM + .LKAS_COMMAND = 0x292, // LKAS controls from DASM + .CRUISE_BUTTONS = 0x23B, // Cruise control buttons + }; + + // CAN messages for the 5th gen RAM DT platform + static const ChryslerAddrs CHRYSLER_RAM_DT_ADDRS = { + .EPS_2 = 0x31, // EPS driver input torque + .ESP_1 = 0x83, // Brake pedal and vehicle speed + .ESP_8 = 0x79, // Brake pedal and vehicle speed + .ECM_5 = 0x9D, // Throttle position sensor + .DAS_3 = 0x99, // ACC engagement states from DASM + .DAS_6 = 0xFA, // LKAS HUD and auto headlight control from DASM + .LKAS_COMMAND = 0xA6, // LKAS controls from DASM + .CRUISE_BUTTONS = 0xB1, // Cruise control buttons + }; + + static 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 }}}, + }; + + static 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 }}}, + }; + + static const CanMsg CHRYSLER_TX_MSGS[] = { + {CHRYSLER_ADDRS.CRUISE_BUTTONS, 0, 3}, + {CHRYSLER_ADDRS.LKAS_COMMAND, 0, 6}, + {CHRYSLER_ADDRS.DAS_6, 0, 8}, + }; + + static const CanMsg CHRYSLER_RAM_DT_TX_MSGS[] = { + {CHRYSLER_RAM_DT_ADDRS.CRUISE_BUTTONS, 2, 3}, + {CHRYSLER_RAM_DT_ADDRS.LKAS_COMMAND, 0, 8}, + {CHRYSLER_RAM_DT_ADDRS.DAS_6, 0, 8}, + }; + +#ifdef ALLOW_DEBUG + // CAN messages for the 5th gen RAM HD platform + static const ChryslerAddrs CHRYSLER_RAM_HD_ADDRS = { + .EPS_2 = 0x220, // EPS driver input torque + .ESP_1 = 0x140, // Brake pedal and vehicle speed + .ESP_8 = 0x11C, // Brake pedal and vehicle speed + .ECM_5 = 0x22F, // Throttle position sensor + .DAS_3 = 0x1F4, // ACC engagement states from DASM + .DAS_6 = 0x275, // LKAS HUD and auto headlight control from DASM + .LKAS_COMMAND = 0x276, // LKAS controls from DASM + .CRUISE_BUTTONS = 0x23A, // Cruise control buttons + }; + + static 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 }}}, + }; + + static const CanMsg CHRYSLER_RAM_HD_TX_MSGS[] = { + {CHRYSLER_RAM_HD_ADDRS.CRUISE_BUTTONS, 2, 3}, + {CHRYSLER_RAM_HD_ADDRS.LKAS_COMMAND, 0, 8}, + {CHRYSLER_RAM_HD_ADDRS.DAS_6, 0, 8}, + }; + + const uint32_t CHRYSLER_PARAM_RAM_HD = 2U; // set for Ram HD platform + bool enable_ram_hd = GET_FLAG(param, CHRYSLER_PARAM_RAM_HD); +#endif + 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; 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)) { + } else if (enable_ram_hd) { chrysler_platform = CHRYSLER_RAM_HD; chrysler_addrs = &CHRYSLER_RAM_HD_ADDRS; ret = BUILD_SAFETY_CFG(chrysler_ram_hd_rx_checks, CHRYSLER_RAM_HD_TX_MSGS); diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h index 6c47dba3d644b06..6716b57b3c0909b 100644 --- a/panda/board/safety/safety_defaults.h +++ b/panda/board/safety/safety_defaults.h @@ -1,3 +1,7 @@ +#pragma once + +#include "safety_declarations.h" + void default_rx_hook(const CANPacket_t *to_push) { UNUSED(to_push); } @@ -30,10 +34,11 @@ const safety_hooks nooutput_hooks = { // *** all output safety mode *** // Enables passthrough mode where relay is open and bus 0 gets forwarded to bus 2 and vice versa -const uint16_t ALLOUTPUT_PARAM_PASSTHROUGH = 1; -bool alloutput_passthrough = false; +static bool alloutput_passthrough = false; static safety_config alloutput_init(uint16_t param) { + // Enables passthrough mode where relay is open and bus 0 gets forwarded to bus 2 and vice versa + const uint16_t ALLOUTPUT_PARAM_PASSTHROUGH = 1; controls_allowed = true; alloutput_passthrough = GET_FLAG(param, ALLOUTPUT_PARAM_PASSTHROUGH); return (safety_config){NULL, 0, NULL, 0}; diff --git a/panda/board/safety/safety_elm327.h b/panda/board/safety/safety_elm327.h index 954efca8d59e625..83efd826b92bb0b 100644 --- a/panda/board/safety/safety_elm327.h +++ b/panda/board/safety/safety_elm327.h @@ -1,6 +1,11 @@ -const int GM_CAMERA_DIAG_ADDR = 0x24B; +#pragma once + +#include "safety_declarations.h" +#include "safety_defaults.h" static bool elm327_tx_hook(const CANPacket_t *to_send) { + const int GM_CAMERA_DIAG_ADDR = 0x24B; + bool tx = true; int addr = GET_ADDR(to_send); int len = GET_LEN(to_send); diff --git a/panda/board/safety/safety_ford.h b/panda/board/safety/safety_ford.h index d6ee208036a1d85..5b19dd9ca5a145e 100644 --- a/panda/board/safety/safety_ford.h +++ b/panda/board/safety/safety_ford.h @@ -1,3 +1,7 @@ +#pragma once + +#include "safety_declarations.h" + // Safety-relevant CAN messages for Ford vehicles. #define FORD_EngBrakeData 0x165 // RX from PCM, for driver brake pedal and cruise state #define FORD_EngVehicleSpThrottle 0x204 // RX from PCM, for driver throttle input @@ -17,59 +21,6 @@ #define FORD_MAIN_BUS 0U #define FORD_CAM_BUS 2U -const CanMsg FORD_STOCK_TX_MSGS[] = { - {FORD_Steering_Data_FD1, 0, 8}, - {FORD_Steering_Data_FD1, 2, 8}, - {FORD_ACCDATA_3, 0, 8}, - {FORD_Lane_Assist_Data1, 0, 8}, - {FORD_LateralMotionControl, 0, 8}, - {FORD_IPMA_Data, 0, 8}, -}; - -const CanMsg FORD_LONG_TX_MSGS[] = { - {FORD_Steering_Data_FD1, 0, 8}, - {FORD_Steering_Data_FD1, 2, 8}, - {FORD_ACCDATA, 0, 8}, - {FORD_ACCDATA_3, 0, 8}, - {FORD_Lane_Assist_Data1, 0, 8}, - {FORD_LateralMotionControl, 0, 8}, - {FORD_IPMA_Data, 0, 8}, -}; - -const CanMsg FORD_CANFD_STOCK_TX_MSGS[] = { - {FORD_Steering_Data_FD1, 0, 8}, - {FORD_Steering_Data_FD1, 2, 8}, - {FORD_ACCDATA_3, 0, 8}, - {FORD_Lane_Assist_Data1, 0, 8}, - {FORD_LateralMotionControl2, 0, 8}, - {FORD_IPMA_Data, 0, 8}, -}; - -const CanMsg FORD_CANFD_LONG_TX_MSGS[] = { - {FORD_Steering_Data_FD1, 0, 8}, - {FORD_Steering_Data_FD1, 2, 8}, - {FORD_ACCDATA, 0, 8}, - {FORD_ACCDATA_3, 0, 8}, - {FORD_Lane_Assist_Data1, 0, 8}, - {FORD_LateralMotionControl2, 0, 8}, - {FORD_IPMA_Data, 0, 8}, -}; - -// warning: quality flags are not yet checked in openpilot's CAN parser, -// this may be the cause of blocked messages -RxCheck ford_rx_checks[] = { - {.msg = {{FORD_BrakeSysFeatures, 0, 8, .check_checksum = true, .max_counter = 15U, .quality_flag=true, .frequency = 50U}, { 0 }, { 0 }}}, - // FORD_EngVehicleSpThrottle2 has a counter that either randomly skips or by 2, likely ECU bug - // Some hybrid models also experience a bug where this checksum mismatches for one or two frames under heavy acceleration with ACC - // It has been confirmed that the Bronco Sport's camera only disallows ACC for bad quality flags, not counters or checksums, so we match that - {.msg = {{FORD_EngVehicleSpThrottle2, 0, 8, .check_checksum = false, .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, .frequency = 10U}, { 0 }, { 0 }}}, - {.msg = {{FORD_EngVehicleSpThrottle, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{FORD_DesiredTorqBrk, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, -}; - static uint8_t ford_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); @@ -137,25 +88,7 @@ static bool ford_get_quality_flag_valid(const CANPacket_t *to_push) { return valid; } -const uint16_t FORD_PARAM_LONGITUDINAL = 1; -const uint16_t FORD_PARAM_CANFD = 2; - -bool ford_longitudinal = false; -bool ford_canfd = false; - -const LongitudinalLimits FORD_LONG_LIMITS = { - // acceleration cmd limits (used for brakes) - // Signal: AccBrkTot_A_Rq - .max_accel = 5641, // 1.9999 m/s^s - .min_accel = 4231, // -3.4991 m/s^2 - .inactive_accel = 5128, // -0.0008 m/s^2 - - // gas cmd limits - // 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 -}; +static bool ford_longitudinal = false; #define FORD_INACTIVE_CURVATURE 1000U #define FORD_INACTIVE_CURVATURE_RATE 4096U @@ -175,17 +108,17 @@ static bool ford_lkas_msg_check(int addr) { } // Curvature rate limits -const SteeringLimits FORD_STEERING_LIMITS = { +static const SteeringLimits FORD_STEERING_LIMITS = { .max_steer = 1000, .angle_deg_to_can = 50000, // 1 / (2e-5) rad to can .max_angle_error = 100, // 0.002 * FORD_STEERING_LIMITS.angle_deg_to_can .angle_rate_up_lookup = { {5., 25., 25.}, - {0.0002, 0.0001, 0.0001} + {0.00045, 0.0001, 0.0001} }, .angle_rate_down_lookup = { {5., 25., 25.}, - {0.000225, 0.00015, 0.00015} + {0.00045, 0.00015, 0.00015} }, // no blending at low speed due to lack of torque wind-up and inaccurate current curvature @@ -261,6 +194,20 @@ static void ford_rx_hook(const CANPacket_t *to_push) { } static bool ford_tx_hook(const CANPacket_t *to_send) { + const LongitudinalLimits FORD_LONG_LIMITS = { + // acceleration cmd limits (used for brakes) + // Signal: AccBrkTot_A_Rq + .max_accel = 5641, // 1.9999 m/s^s + .min_accel = 4231, // -3.4991 m/s^2 + .inactive_accel = 5128, // -0.0008 m/s^2 + + // gas cmd limits + // 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 + }; + bool tx = true; int addr = GET_ADDR(to_send); @@ -276,6 +223,9 @@ static bool ford_tx_hook(const CANPacket_t *to_send) { // Signal: CmbbDeny_B_Actl bool cmbb_deny = GET_BIT(to_send, 37U); + // Signal: AccBrkPrchg_B_Rq & AccBrkDecel_B_Rq + bool brake_actuation = GET_BIT(to_send, 54U) || GET_BIT(to_send, 55U); + bool violation = false; violation |= longitudinal_accel_checks(accel, FORD_LONG_LIMITS); violation |= longitudinal_gas_checks(gas, FORD_LONG_LIMITS); @@ -284,6 +234,8 @@ static bool ford_tx_hook(const CANPacket_t *to_send) { // Safety check for stock AEB violation |= cmbb_deny; // do not prevent stock AEB actuation + violation |= !get_longitudinal_allowed() && brake_actuation; + if (violation) { tx = false; } @@ -394,13 +346,73 @@ static int ford_fwd_hook(int bus_num, int addr) { } static safety_config ford_init(uint16_t param) { + bool ford_canfd = false; + + // warning: quality flags are not yet checked in openpilot's CAN parser, + // this may be the cause of blocked messages + static RxCheck ford_rx_checks[] = { + {.msg = {{FORD_BrakeSysFeatures, 0, 8, .check_checksum = true, .max_counter = 15U, .quality_flag=true, .frequency = 50U}, { 0 }, { 0 }}}, + // FORD_EngVehicleSpThrottle2 has a counter that either randomly skips or by 2, likely ECU bug + // Some hybrid models also experience a bug where this checksum mismatches for one or two frames under heavy acceleration with ACC + // It has been confirmed that the Bronco Sport's camera only disallows ACC for bad quality flags, not counters or checksums, so we match that + {.msg = {{FORD_EngVehicleSpThrottle2, 0, 8, .check_checksum = false, .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, .frequency = 10U}, { 0 }, { 0 }}}, + {.msg = {{FORD_EngVehicleSpThrottle, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, + {.msg = {{FORD_DesiredTorqBrk, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, + }; + + static const CanMsg FORD_CANFD_LONG_TX_MSGS[] = { + {FORD_Steering_Data_FD1, 0, 8}, + {FORD_Steering_Data_FD1, 2, 8}, + {FORD_ACCDATA, 0, 8}, + {FORD_ACCDATA_3, 0, 8}, + {FORD_Lane_Assist_Data1, 0, 8}, + {FORD_LateralMotionControl2, 0, 8}, + {FORD_IPMA_Data, 0, 8}, + }; + + static const CanMsg FORD_CANFD_STOCK_TX_MSGS[] = { + {FORD_Steering_Data_FD1, 0, 8}, + {FORD_Steering_Data_FD1, 2, 8}, + {FORD_ACCDATA_3, 0, 8}, + {FORD_Lane_Assist_Data1, 0, 8}, + {FORD_LateralMotionControl2, 0, 8}, + {FORD_IPMA_Data, 0, 8}, + }; + + static const CanMsg FORD_STOCK_TX_MSGS[] = { + {FORD_Steering_Data_FD1, 0, 8}, + {FORD_Steering_Data_FD1, 2, 8}, + {FORD_ACCDATA_3, 0, 8}, + {FORD_Lane_Assist_Data1, 0, 8}, + {FORD_LateralMotionControl, 0, 8}, + {FORD_IPMA_Data, 0, 8}, + }; + + static const CanMsg FORD_LONG_TX_MSGS[] = { + {FORD_Steering_Data_FD1, 0, 8}, + {FORD_Steering_Data_FD1, 2, 8}, + {FORD_ACCDATA, 0, 8}, + {FORD_ACCDATA_3, 0, 8}, + {FORD_Lane_Assist_Data1, 0, 8}, + {FORD_LateralMotionControl, 0, 8}, + {FORD_IPMA_Data, 0, 8}, + }; + UNUSED(param); #ifdef ALLOW_DEBUG + const uint16_t FORD_PARAM_LONGITUDINAL = 1; + const uint16_t FORD_PARAM_CANFD = 2; ford_longitudinal = GET_FLAG(param, FORD_PARAM_LONGITUDINAL); ford_canfd = GET_FLAG(param, FORD_PARAM_CANFD); #endif safety_config ret; + // FIXME: cppcheck thinks that ford_canfd is always false. This is not true + // if ALLOW_DEBUG is defined but cppcheck is run without ALLOW_DEBUG + // cppcheck-suppress knownConditionTrueFalse 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); diff --git a/panda/board/safety/safety_gm.h b/panda/board/safety/safety_gm.h index 09ac34ecbd09fc2..f0902a921aa958d 100644 --- a/panda/board/safety/safety_gm.h +++ b/panda/board/safety/safety_gm.h @@ -1,56 +1,8 @@ -const SteeringLimits GM_STEERING_LIMITS = { - .max_steer = 300, - .max_rate_up = 10, - .max_rate_down = 15, - .driver_torque_allowance = 65, - .driver_torque_factor = 4, - .max_rt_delta = 128, - .max_rt_interval = 250000, - .type = TorqueDriverLimited, -}; - -const LongitudinalLimits GM_ASCM_LONG_LIMITS = { - .max_gas = 3072, - .min_gas = 1404, - .inactive_gas = 1404, - .max_brake = 400, -}; - -const LongitudinalLimits GM_CAM_LONG_LIMITS = { - .max_gas = 3400, - .min_gas = 1514, - .inactive_gas = 1554, - .max_brake = 400, -}; +#pragma once -const LongitudinalLimits *gm_long_limits; +#include "safety_declarations.h" -const int GM_STANDSTILL_THRSLD = 10; // 0.311kph - -const CanMsg GM_ASCM_TX_MSGS[] = {{0x180, 0, 4}, {0x409, 0, 7}, {0x40A, 0, 7}, {0x2CB, 0, 8}, {0x370, 0, 6}, // pt bus - {0xA1, 1, 7}, {0x306, 1, 8}, {0x308, 1, 7}, {0x310, 1, 2}, // obs bus - {0x315, 2, 5}}; // ch bus - -const CanMsg GM_CAM_TX_MSGS[] = {{0x180, 0, 4}, // pt bus - {0x1E1, 2, 7}, {0x184, 2, 8}}; // camera bus - -const CanMsg GM_CAM_LONG_TX_MSGS[] = {{0x180, 0, 4}, {0x315, 0, 5}, {0x2CB, 0, 8}, {0x370, 0, 6}, // pt bus - {0x184, 2, 8}}; // camera bus - -// TODO: do checksum and counter checks. Add correct timestep, 0.1s for now. -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 }}}, -}; - -const uint16_t GM_PARAM_HW_CAM = 1; -const uint16_t GM_PARAM_HW_CAM_LONG = 2; +static const LongitudinalLimits *gm_long_limits; enum { GM_BTN_UNPRESS = 1, @@ -63,11 +15,16 @@ typedef enum { GM_ASCM, GM_CAM } GmHardware; -GmHardware gm_hw = GM_ASCM; -bool gm_cam_long = false; -bool gm_pcm_cruise = false; +static GmHardware gm_hw = GM_ASCM; +static bool gm_cam_long = false; +static bool gm_pcm_cruise = false; static void gm_rx_hook(const CANPacket_t *to_push) { + + const int GM_STANDSTILL_THRSLD = 10; // 0.311kph + + + if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); @@ -139,6 +96,17 @@ static void gm_rx_hook(const CANPacket_t *to_push) { } static bool gm_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits GM_STEERING_LIMITS = { + .max_steer = 300, + .max_rate_up = 10, + .max_rate_down = 15, + .driver_torque_allowance = 65, + .driver_torque_factor = 4, + .max_rt_delta = 128, + .max_rt_interval = 250000, + .type = TorqueDriverLimited, + }; + bool tx = true; int addr = GET_ADDR(to_send); @@ -218,6 +186,46 @@ static int gm_fwd_hook(int bus_num, int addr) { } static safety_config gm_init(uint16_t param) { + const uint16_t GM_PARAM_HW_CAM = 1; + + static const LongitudinalLimits GM_ASCM_LONG_LIMITS = { + .max_gas = 3072, + .min_gas = 1404, + .inactive_gas = 1404, + .max_brake = 400, + }; + + static const CanMsg GM_ASCM_TX_MSGS[] = {{0x180, 0, 4}, {0x409, 0, 7}, {0x40A, 0, 7}, {0x2CB, 0, 8}, {0x370, 0, 6}, // pt bus + {0xA1, 1, 7}, {0x306, 1, 8}, {0x308, 1, 7}, {0x310, 1, 2}, // obs bus + {0x315, 2, 5}}; // ch bus + + + static const LongitudinalLimits GM_CAM_LONG_LIMITS = { + .max_gas = 3400, + .min_gas = 1514, + .inactive_gas = 1554, + .max_brake = 400, + }; + + static const CanMsg GM_CAM_LONG_TX_MSGS[] = {{0x180, 0, 4}, {0x315, 0, 5}, {0x2CB, 0, 8}, {0x370, 0, 6}, // pt bus + {0x184, 2, 8}}; // camera bus + + + // TODO: do checksum and counter checks. Add correct timestep, 0.1s for now. + static 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 }}}, + }; + + static const CanMsg GM_CAM_TX_MSGS[] = {{0x180, 0, 4}, // pt bus + {0x1E1, 2, 7}, {0x184, 2, 8}}; // camera bus + gm_hw = GET_FLAG(param, GM_PARAM_HW_CAM) ? GM_CAM : GM_ASCM; if (gm_hw == GM_ASCM) { @@ -228,12 +236,16 @@ static safety_config gm_init(uint16_t param) { } #ifdef ALLOW_DEBUG + const uint16_t GM_PARAM_HW_CAM_LONG = 2; gm_cam_long = GET_FLAG(param, GM_PARAM_HW_CAM_LONG); #endif gm_pcm_cruise = (gm_hw == GM_CAM) && !gm_cam_long; safety_config ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_ASCM_TX_MSGS); if (gm_hw == GM_CAM) { + // FIXME: cppcheck thinks that gm_cam_long is always false. This is not true + // if ALLOW_DEBUG is defined but cppcheck is run without ALLOW_DEBUG + // cppcheck-suppress knownConditionTrueFalse 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; diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h index 630f6d731cdef8e..60ccea1e16ea8e9 100644 --- a/panda/board/safety/safety_honda.h +++ b/panda/board/safety/safety_honda.h @@ -1,23 +1,6 @@ -const CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {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 -const CanMsg HONDA_RADARLESS_LONG_TX_MSGS[] = {{0xE4, 0, 5}, {0x33D, 0, 8}, {0x1C8, 0, 8}, {0x30C, 0, 8}}; // Bosch radarless w/ gas and brakes - -const LongitudinalLimits HONDA_BOSCH_LONG_LIMITS = { - .max_accel = 200, // accel is used for brakes - .min_accel = -350, - - .max_gas = 2000, - .inactive_gas = -30000, -}; - -const LongitudinalLimits HONDA_NIDEC_LONG_LIMITS = { - .max_gas = 198, // 0xc6 - .max_brake = 255, +#pragma once - .inactive_speed = 0, -}; +#include "safety_declarations.h" // 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) \ @@ -36,35 +19,10 @@ const LongitudinalLimits HONDA_NIDEC_LONG_LIMITS = { // Nidec and bosch radarless has the powertrain bus on bus 0 -RxCheck honda_common_rx_checks[] = { - HONDA_COMMON_RX_CHECKS(0) -}; - -RxCheck honda_common_alt_brake_rx_checks[] = { +static RxCheck honda_common_rx_checks[] = { HONDA_COMMON_RX_CHECKS(0) - HONDA_ALT_BRAKE_ADDR_CHECK(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) }; -// 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) -}; - -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; - enum { HONDA_BTN_NONE = 0, HONDA_BTN_MAIN = 1, @@ -73,17 +31,17 @@ enum { HONDA_BTN_RESUME = 4, }; -int honda_brake = 0; -bool honda_brake_switch_prev = false; -bool honda_alt_brake_msg = false; -bool honda_fwd_brake = false; -bool honda_bosch_long = false; -bool honda_bosch_radarless = false; +static int honda_brake = 0; +static bool honda_brake_switch_prev = false; +static bool honda_alt_brake_msg = false; +static bool honda_fwd_brake = false; +static bool honda_bosch_long = false; +static bool honda_bosch_radarless = false; typedef enum {HONDA_NIDEC, HONDA_BOSCH} HondaHw; -HondaHw honda_hw = HONDA_NIDEC; +static HondaHw honda_hw = HONDA_NIDEC; -int honda_get_pt_bus(void) { +static int honda_get_pt_bus(void) { return ((honda_hw == HONDA_BOSCH) && !honda_bosch_radarless) ? 1 : 0; } @@ -233,6 +191,22 @@ static void honda_rx_hook(const CANPacket_t *to_push) { } static bool honda_tx_hook(const CANPacket_t *to_send) { + + const LongitudinalLimits HONDA_BOSCH_LONG_LIMITS = { + .max_accel = 200, // accel is used for brakes + .min_accel = -350, + + .max_gas = 2000, + .inactive_gas = -30000, + }; + + const LongitudinalLimits HONDA_NIDEC_LONG_LIMITS = { + .max_gas = 198, // 0xc6 + .max_brake = 255, + + .inactive_speed = 0, + }; + bool tx = true; int addr = GET_ADDR(to_send); int bus = GET_BUS(to_send); @@ -329,6 +303,10 @@ static bool honda_tx_hook(const CANPacket_t *to_send) { } static safety_config honda_nidec_init(uint16_t param) { + static CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x30C, 0, 8}, {0x33D, 0, 5}}; + + const uint16_t HONDA_PARAM_NIDEC_ALT = 4; + honda_hw = HONDA_NIDEC; honda_brake = 0; honda_brake_switch_prev = false; @@ -342,16 +320,45 @@ static safety_config honda_nidec_init(uint16_t param) { bool enable_nidec_alt = GET_FLAG(param, HONDA_PARAM_NIDEC_ALT); if (enable_nidec_alt) { + // For Nidecs with main on signal on an alternate msg (missing 0x326) + static RxCheck honda_nidec_alt_rx_checks[] = { + HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(0) + }; + SET_RX_CHECKS(honda_nidec_alt_rx_checks, ret); } else { SET_RX_CHECKS(honda_common_rx_checks, ret); } + SET_TX_MSGS(HONDA_N_TX_MSGS, ret); return ret; } static safety_config honda_bosch_init(uint16_t param) { + static CanMsg HONDA_BOSCH_TX_MSGS[] = {{0xE4, 0, 5}, {0xE5, 0, 8}, {0x296, 1, 4}, {0x33D, 0, 5}, {0x33DA, 0, 5}, {0x33DB, 0, 8}}; // Bosch + static 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 + static CanMsg HONDA_RADARLESS_TX_MSGS[] = {{0xE4, 0, 5}, {0x296, 2, 4}, {0x33D, 0, 8}}; // Bosch radarless + static CanMsg HONDA_RADARLESS_LONG_TX_MSGS[] = {{0xE4, 0, 5}, {0x33D, 0, 8}, {0x1C8, 0, 8}, {0x30C, 0, 8}}; // Bosch radarless w/ gas and brakes + + const uint16_t HONDA_PARAM_ALT_BRAKE = 1; + const uint16_t HONDA_PARAM_RADARLESS = 8; + + static RxCheck honda_common_alt_brake_rx_checks[] = { + HONDA_COMMON_RX_CHECKS(0) + HONDA_ALT_BRAKE_ADDR_CHECK(0) + }; + + static RxCheck honda_bosch_alt_brake_rx_checks[] = { + HONDA_COMMON_RX_CHECKS(1) + HONDA_ALT_BRAKE_ADDR_CHECK(1) + }; + + // Bosch has pt on bus 1, verified 0x1A6 does not exist + static RxCheck honda_bosch_rx_checks[] = { + HONDA_COMMON_RX_CHECKS(1) + }; + honda_hw = HONDA_BOSCH; honda_brake_switch_prev = false; honda_bosch_radarless = GET_FLAG(param, HONDA_PARAM_RADARLESS); @@ -360,6 +367,7 @@ static safety_config honda_bosch_init(uint16_t param) { // radar disabled so allow gas/brakes #ifdef ALLOW_DEBUG + const uint16_t HONDA_PARAM_BOSCH_LONG = 2; honda_bosch_long = GET_FLAG(param, HONDA_PARAM_BOSCH_LONG); #endif @@ -375,11 +383,17 @@ static safety_config honda_bosch_init(uint16_t param) { } if (honda_bosch_radarless) { - honda_bosch_long ? SET_TX_MSGS(HONDA_RADARLESS_LONG_TX_MSGS, ret) : \ - SET_TX_MSGS(HONDA_RADARLESS_TX_MSGS, ret); + if (honda_bosch_long) { + SET_TX_MSGS(HONDA_RADARLESS_LONG_TX_MSGS, ret); + } else { + SET_TX_MSGS(HONDA_RADARLESS_TX_MSGS, ret); + } } else { - honda_bosch_long ? SET_TX_MSGS(HONDA_BOSCH_LONG_TX_MSGS, ret) : \ - SET_TX_MSGS(HONDA_BOSCH_TX_MSGS, ret); + if (honda_bosch_long) { + SET_TX_MSGS(HONDA_BOSCH_LONG_TX_MSGS, ret); + } else { + SET_TX_MSGS(HONDA_BOSCH_TX_MSGS, ret); + } } return ret; } diff --git a/panda/board/safety/safety_hyundai.h b/panda/board/safety/safety_hyundai.h index 5a324bff29f0ab0..3e9d23216c3602f 100644 --- a/panda/board/safety/safety_hyundai.h +++ b/panda/board/safety/safety_hyundai.h @@ -1,3 +1,6 @@ +#pragma once + +#include "safety_declarations.h" #include "safety_hyundai_common.h" #define HYUNDAI_LIMITS(steer, rate_up, rate_down) { \ @@ -17,38 +20,16 @@ .has_steer_req_tolerance = true, \ } -const SteeringLimits HYUNDAI_STEERING_LIMITS = HYUNDAI_LIMITS(384, 3, 7); -const SteeringLimits HYUNDAI_STEERING_LIMITS_ALT = HYUNDAI_LIMITS(270, 2, 3); - +extern const LongitudinalLimits HYUNDAI_LONG_LIMITS; const LongitudinalLimits HYUNDAI_LONG_LIMITS = { .max_accel = 200, // 1/100 m/s2 .min_accel = -350, // 1/100 m/s2 }; -const CanMsg HYUNDAI_TX_MSGS[] = { - {0x340, 0, 8}, // LKAS11 Bus 0 - {0x4F1, 0, 4}, // CLU11 Bus 0 - {0x485, 0, 4}, // LFAHDA_MFC Bus 0 -}; - -const CanMsg HYUNDAI_LONG_TX_MSGS[] = { +static const CanMsg HYUNDAI_TX_MSGS[] = { {0x340, 0, 8}, // LKAS11 Bus 0 {0x4F1, 0, 4}, // CLU11 Bus 0 {0x485, 0, 4}, // LFAHDA_MFC Bus 0 - {0x420, 0, 8}, // SCC11 Bus 0 - {0x421, 0, 8}, // SCC12 Bus 0 - {0x50A, 0, 8}, // SCC13 Bus 0 - {0x389, 0, 8}, // SCC14 Bus 0 - {0x4A2, 0, 2}, // FRT_RADAR11 Bus 0 - {0x38D, 0, 8}, // FCA11 Bus 0 - {0x483, 0, 8}, // FCA12 Bus 0 - {0x7D0, 0, 8}, // radar UDS TX addr Bus 0 (for radar disable) -}; - -const CanMsg HYUNDAI_CAMERA_SCC_TX_MSGS[] = { - {0x340, 0, 8}, // LKAS11 Bus 0 - {0x4F1, 2, 4}, // CLU11 Bus 2 - {0x485, 0, 4}, // LFAHDA_MFC Bus 0 }; #define HYUNDAI_COMMON_RX_CHECKS(legacy) \ @@ -60,30 +41,7 @@ const CanMsg HYUNDAI_CAMERA_SCC_TX_MSGS[] = { #define HYUNDAI_SCC12_ADDR_CHECK(scc_bus) \ {.msg = {{0x421, (scc_bus), 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ -RxCheck hyundai_rx_checks[] = { - HYUNDAI_COMMON_RX_CHECKS(false) - HYUNDAI_SCC12_ADDR_CHECK(0) -}; - -RxCheck hyundai_cam_scc_rx_checks[] = { - HYUNDAI_COMMON_RX_CHECKS(false) - HYUNDAI_SCC12_ADDR_CHECK(2) -}; - -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, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -// older hyundai models have less checks due to missing counters and checksums -RxCheck hyundai_legacy_rx_checks[] = { - HYUNDAI_COMMON_RX_CHECKS(true) - HYUNDAI_SCC12_ADDR_CHECK(0) -}; - -bool hyundai_legacy = false; - +static bool hyundai_legacy = false; static uint8_t hyundai_get_counter(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); @@ -215,6 +173,9 @@ static void hyundai_rx_hook(const CANPacket_t *to_push) { } static bool hyundai_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits HYUNDAI_STEERING_LIMITS = HYUNDAI_LIMITS(384, 3, 7); + const SteeringLimits HYUNDAI_STEERING_LIMITS_ALT = HYUNDAI_LIMITS(270, 2, 3); + bool tx = true; int addr = GET_ADDR(to_send); @@ -297,6 +258,26 @@ static int hyundai_fwd_hook(int bus_num, int addr) { } static safety_config hyundai_init(uint16_t param) { + static const CanMsg HYUNDAI_LONG_TX_MSGS[] = { + {0x340, 0, 8}, // LKAS11 Bus 0 + {0x4F1, 0, 4}, // CLU11 Bus 0 + {0x485, 0, 4}, // LFAHDA_MFC Bus 0 + {0x420, 0, 8}, // SCC11 Bus 0 + {0x421, 0, 8}, // SCC12 Bus 0 + {0x50A, 0, 8}, // SCC13 Bus 0 + {0x389, 0, 8}, // SCC14 Bus 0 + {0x4A2, 0, 2}, // FRT_RADAR11 Bus 0 + {0x38D, 0, 8}, // FCA11 Bus 0 + {0x483, 0, 8}, // FCA12 Bus 0 + {0x7D0, 0, 8}, // radar UDS TX addr Bus 0 (for radar disable) + }; + + static const CanMsg HYUNDAI_CAMERA_SCC_TX_MSGS[] = { + {0x340, 0, 8}, // LKAS11 Bus 0 + {0x4F1, 2, 4}, // CLU11 Bus 2 + {0x485, 0, 4}, // LFAHDA_MFC Bus 0 + }; + hyundai_common_init(param); hyundai_legacy = false; @@ -306,16 +287,38 @@ static safety_config hyundai_init(uint16_t param) { safety_config ret; if (hyundai_longitudinal) { + static 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, .frequency = 50U}, { 0 }, { 0 }}}, + }; + ret = BUILD_SAFETY_CFG(hyundai_long_rx_checks, HYUNDAI_LONG_TX_MSGS); } else if (hyundai_camera_scc) { + static RxCheck hyundai_cam_scc_rx_checks[] = { + HYUNDAI_COMMON_RX_CHECKS(false) + HYUNDAI_SCC12_ADDR_CHECK(2) + }; + ret = BUILD_SAFETY_CFG(hyundai_cam_scc_rx_checks, HYUNDAI_CAMERA_SCC_TX_MSGS); } else { + static RxCheck hyundai_rx_checks[] = { + HYUNDAI_COMMON_RX_CHECKS(false) + HYUNDAI_SCC12_ADDR_CHECK(0) + }; + ret = BUILD_SAFETY_CFG(hyundai_rx_checks, HYUNDAI_TX_MSGS); } return ret; } static safety_config hyundai_legacy_init(uint16_t param) { + // older hyundai models have less checks due to missing counters and checksums + static RxCheck hyundai_legacy_rx_checks[] = { + HYUNDAI_COMMON_RX_CHECKS(true) + HYUNDAI_SCC12_ADDR_CHECK(0) + }; + hyundai_common_init(param); hyundai_legacy = true; hyundai_longitudinal = false; diff --git a/panda/board/safety/safety_hyundai_canfd.h b/panda/board/safety/safety_hyundai_canfd.h index fb6ccf55a0db41f..b42889bb0ed49fb 100644 --- a/panda/board/safety/safety_hyundai_canfd.h +++ b/panda/board/safety/safety_hyundai_canfd.h @@ -1,58 +1,7 @@ -#include "safety_hyundai_common.h" - -const SteeringLimits HYUNDAI_CANFD_STEERING_LIMITS = { - .max_steer = 270, - .max_rt_delta = 112, - .max_rt_interval = 250000, - .max_rate_up = 2, - .max_rate_down = 3, - .driver_torque_allowance = 250, - .driver_torque_factor = 2, - .type = TorqueDriverLimited, - - // the EPS faults when the steering angle is above a certain threshold for too long. to prevent this, - // we allow setting torque actuation bit to 0 while maintaining the requested torque value for two consecutive frames - .min_valid_request_frames = 89, - .max_invalid_request_frames = 2, - .min_valid_request_rt_interval = 810000, // 810ms; a ~10% buffer on cutting every 90 frames - .has_steer_req_tolerance = true, -}; - -const CanMsg HYUNDAI_CANFD_HDA2_TX_MSGS[] = { - {0x50, 0, 16}, // LKAS - {0x1CF, 1, 8}, // CRUISE_BUTTON - {0x2A4, 0, 24}, // CAM_0x2A4 -}; - -const CanMsg HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS[] = { - {0x110, 0, 32}, // LKAS_ALT - {0x1CF, 1, 8}, // CRUISE_BUTTON - {0x362, 0, 32}, // CAM_0x362 -}; - -const CanMsg HYUNDAI_CANFD_HDA2_LONG_TX_MSGS[] = { - {0x50, 0, 16}, // LKAS - {0x1CF, 1, 8}, // CRUISE_BUTTON - {0x2A4, 0, 24}, // CAM_0x2A4 - {0x51, 0, 32}, // ADRV_0x51 - {0x730, 1, 8}, // tester present for ADAS ECU disable - {0x12A, 1, 16}, // LFA - {0x160, 1, 16}, // ADRV_0x160 - {0x1E0, 1, 16}, // LFAHDA_CLUSTER - {0x1A0, 1, 32}, // CRUISE_INFO - {0x1EA, 1, 32}, // ADRV_0x1ea - {0x200, 1, 8}, // ADRV_0x200 - {0x345, 1, 8}, // ADRV_0x345 - {0x1DA, 1, 32}, // ADRV_0x1da -}; - -const CanMsg HYUNDAI_CANFD_HDA1_TX_MSGS[] = { - {0x12A, 0, 16}, // LFA - {0x1A0, 0, 32}, // CRUISE_INFO - {0x1CF, 2, 8}, // CRUISE_BUTTON - {0x1E0, 0, 16}, // LFAHDA_CLUSTER -}; +#pragma once +#include "safety_declarations.h" +#include "safety_hyundai_common.h" // *** Addresses checked in rx hook *** // EV, ICE, HYBRID: ACCELERATOR (0x35), ACCELERATOR_BRAKE_ALT (0x100), ACCELERATOR_ALT (0x105) @@ -74,66 +23,10 @@ const CanMsg HYUNDAI_CANFD_HDA1_TX_MSGS[] = { #define HYUNDAI_CANFD_SCC_ADDR_CHECK(scc_bus) \ {.msg = {{0x1a0, (scc_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \ +static bool hyundai_canfd_alt_buttons = false; +static bool hyundai_canfd_hda2_alt_steering = false; -// *** 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 -RxCheck hyundai_canfd_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(0) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) - HYUNDAI_CANFD_SCC_ADDR_CHECK(2) -}; -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 -RxCheck hyundai_canfd_long_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(0) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(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 -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) -}; -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) -}; - - -// *** HDA2 checks *** -// E-CAN is on bus 1, ADAS unit sends SCC messages on HDA2. -// Does not use the alt buttons message -RxCheck hyundai_canfd_hda2_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(1) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1) - HYUNDAI_CANFD_SCC_ADDR_CHECK(1) -}; -RxCheck hyundai_canfd_hda2_long_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(1) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1) -}; - - - -const int HYUNDAI_PARAM_CANFD_ALT_BUTTONS = 32; -const int HYUNDAI_PARAM_CANFD_HDA2_ALT_STEERING = 128; -bool hyundai_canfd_alt_buttons = false; -bool hyundai_canfd_hda2_alt_steering = false; - - -int hyundai_canfd_hda2_get_lkas_addr(void) { +static int hyundai_canfd_hda2_get_lkas_addr(void) { return hyundai_canfd_hda2_alt_steering ? 0x110 : 0x50; } @@ -228,6 +121,24 @@ static void hyundai_canfd_rx_hook(const CANPacket_t *to_push) { } static bool hyundai_canfd_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits HYUNDAI_CANFD_STEERING_LIMITS = { + .max_steer = 270, + .max_rt_delta = 112, + .max_rt_interval = 250000, + .max_rate_up = 2, + .max_rate_down = 3, + .driver_torque_allowance = 250, + .driver_torque_factor = 2, + .type = TorqueDriverLimited, + + // the EPS faults when the steering angle is above a certain threshold for too long. to prevent this, + // we allow setting torque actuation bit to 0 while maintaining the requested torque value for two consecutive frames + .min_valid_request_frames = 89, + .max_invalid_request_frames = 2, + .min_valid_request_rt_interval = 810000, // 810ms; a ~10% buffer on cutting every 90 frames + .has_steer_req_tolerance = true, + }; + bool tx = true; int addr = GET_ADDR(to_send); @@ -314,6 +225,45 @@ static int hyundai_canfd_fwd_hook(int bus_num, int addr) { } static safety_config hyundai_canfd_init(uint16_t param) { + const int HYUNDAI_PARAM_CANFD_HDA2_ALT_STEERING = 128; + const int HYUNDAI_PARAM_CANFD_ALT_BUTTONS = 32; + + static const CanMsg HYUNDAI_CANFD_HDA2_TX_MSGS[] = { + {0x50, 0, 16}, // LKAS + {0x1CF, 1, 8}, // CRUISE_BUTTON + {0x2A4, 0, 24}, // CAM_0x2A4 + }; + + static const CanMsg HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS[] = { + {0x110, 0, 32}, // LKAS_ALT + {0x1CF, 1, 8}, // CRUISE_BUTTON + {0x362, 0, 32}, // CAM_0x362 + }; + + static const CanMsg HYUNDAI_CANFD_HDA2_LONG_TX_MSGS[] = { + {0x50, 0, 16}, // LKAS + {0x1CF, 1, 8}, // CRUISE_BUTTON + {0x2A4, 0, 24}, // CAM_0x2A4 + {0x51, 0, 32}, // ADRV_0x51 + {0x730, 1, 8}, // tester present for ADAS ECU disable + {0x12A, 1, 16}, // LFA + {0x160, 1, 16}, // ADRV_0x160 + {0x1E0, 1, 16}, // LFAHDA_CLUSTER + {0x1A0, 1, 32}, // CRUISE_INFO + {0x1EA, 1, 32}, // ADRV_0x1ea + {0x200, 1, 8}, // ADRV_0x200 + {0x345, 1, 8}, // ADRV_0x345 + {0x1DA, 1, 32}, // ADRV_0x1da + }; + + static const CanMsg HYUNDAI_CANFD_HDA1_TX_MSGS[] = { + {0x12A, 0, 16}, // LFA + {0x1A0, 0, 32}, // CRUISE_INFO + {0x1CF, 2, 8}, // CRUISE_BUTTON + {0x1E0, 0, 16}, // LFAHDA_CLUSTER + }; + + hyundai_common_init(param); gen_crc_lookup_table_16(0x1021, hyundai_canfd_crc_lut); @@ -328,19 +278,72 @@ static safety_config hyundai_canfd_init(uint16_t param) { safety_config ret; if (hyundai_longitudinal) { if (hyundai_canfd_hda2) { + static RxCheck hyundai_canfd_hda2_long_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(1) + HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1) + }; + ret = BUILD_SAFETY_CFG(hyundai_canfd_hda2_long_rx_checks, HYUNDAI_CANFD_HDA2_LONG_TX_MSGS); } else { + static RxCheck hyundai_canfd_long_alt_buttons_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) + HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0) + }; + + // Longitudinal checks for HDA1 + static RxCheck hyundai_canfd_long_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) + HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) + }; + 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) { + // *** HDA2 checks *** + // E-CAN is on bus 1, ADAS unit sends SCC messages on HDA2. + // Does not use the alt buttons message + static RxCheck hyundai_canfd_hda2_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(1) + HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1) + HYUNDAI_CANFD_SCC_ADDR_CHECK(1) + }; + 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) { + static 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) + }; + + // Radar sends SCC messages on these cars instead of camera + static 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) + }; + 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 { + // *** Non-HDA2 checks *** + static 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) + }; + + // Camera sends SCC messages on HDA1. + // Both button messages exist on some platforms, so we ensure we track the correct one using flag + static RxCheck hyundai_canfd_rx_checks[] = { + HYUNDAI_CANFD_COMMON_RX_CHECKS(0) + HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) + HYUNDAI_CANFD_SCC_ADDR_CHECK(2) + }; + 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); } diff --git a/panda/board/safety/safety_hyundai_common.h b/panda/board/safety/safety_hyundai_common.h index 54ea0f024af74e4..d83b39640100879 100644 --- a/panda/board/safety/safety_hyundai_common.h +++ b/panda/board/safety/safety_hyundai_common.h @@ -1,14 +1,13 @@ -#ifndef SAFETY_HYUNDAI_COMMON_H -#define SAFETY_HYUNDAI_COMMON_H +#pragma once -const int HYUNDAI_PARAM_EV_GAS = 1; -const int HYUNDAI_PARAM_HYBRID_GAS = 2; -const int HYUNDAI_PARAM_LONGITUDINAL = 4; -const int HYUNDAI_PARAM_CAMERA_SCC = 8; -const int HYUNDAI_PARAM_CANFD_HDA2 = 16; -const int HYUNDAI_PARAM_ALT_LIMITS = 64; // TODO: shift this down with the rest of the common flags +#include "safety_declarations.h" -const uint8_t HYUNDAI_PREV_BUTTON_SAMPLES = 8; // roughly 160 ms +extern uint16_t hyundai_canfd_crc_lut[256]; +uint16_t hyundai_canfd_crc_lut[256]; + +static const uint8_t HYUNDAI_PREV_BUTTON_SAMPLES = 8; // roughly 160 ms + // +extern const uint32_t HYUNDAI_STANDSTILL_THRSLD; const uint32_t HYUNDAI_STANDSTILL_THRSLD = 12; // 0.375 kph enum { @@ -19,17 +18,33 @@ enum { }; // common state +extern bool hyundai_ev_gas_signal; bool hyundai_ev_gas_signal = false; + +extern bool hyundai_hybrid_gas_signal; bool hyundai_hybrid_gas_signal = false; + +extern bool hyundai_longitudinal; bool hyundai_longitudinal = false; + +extern bool hyundai_camera_scc; bool hyundai_camera_scc = false; + +extern bool hyundai_canfd_hda2; bool hyundai_canfd_hda2 = false; + +extern bool hyundai_alt_limits; bool hyundai_alt_limits = false; -uint8_t hyundai_last_button_interaction; // button messages since the user pressed an enable button -uint16_t hyundai_canfd_crc_lut[256]; +static uint8_t hyundai_last_button_interaction; // button messages since the user pressed an enable button void hyundai_common_init(uint16_t param) { + const int HYUNDAI_PARAM_EV_GAS = 1; + const int HYUNDAI_PARAM_HYBRID_GAS = 2; + const int HYUNDAI_PARAM_CAMERA_SCC = 8; + const int HYUNDAI_PARAM_CANFD_HDA2 = 16; + const int HYUNDAI_PARAM_ALT_LIMITS = 64; // TODO: shift this down with the rest of the common flags + hyundai_ev_gas_signal = GET_FLAG(param, HYUNDAI_PARAM_EV_GAS); hyundai_hybrid_gas_signal = !hyundai_ev_gas_signal && GET_FLAG(param, HYUNDAI_PARAM_HYBRID_GAS); hyundai_camera_scc = GET_FLAG(param, HYUNDAI_PARAM_CAMERA_SCC); @@ -39,6 +54,7 @@ void hyundai_common_init(uint16_t param) { hyundai_last_button_interaction = HYUNDAI_PREV_BUTTON_SAMPLES; #ifdef ALLOW_DEBUG + const int HYUNDAI_PARAM_LONGITUDINAL = 4; hyundai_longitudinal = GET_FLAG(param, HYUNDAI_PARAM_LONGITUDINAL); #else hyundai_longitudinal = false; @@ -110,5 +126,3 @@ uint32_t hyundai_common_canfd_compute_checksum(const CANPacket_t *to_push) { return crc; } - -#endif diff --git a/panda/board/safety/safety_mazda.h b/panda/board/safety/safety_mazda.h index ea4ce92d00edd85..ed87451f771cc4a 100644 --- a/panda/board/safety/safety_mazda.h +++ b/panda/board/safety/safety_mazda.h @@ -1,3 +1,7 @@ +#pragma once + +#include "safety_declarations.h" + // CAN msgs we care about #define MAZDA_LKAS 0x243 #define MAZDA_LKAS_HUD 0x440 @@ -9,30 +13,8 @@ // CAN bus numbers #define MAZDA_MAIN 0 -#define MAZDA_AUX 1 #define MAZDA_CAM 2 -const SteeringLimits MAZDA_STEERING_LIMITS = { - .max_steer = 800, - .max_rate_up = 10, - .max_rate_down = 25, - .max_rt_delta = 300, - .max_rt_interval = 250000, - .driver_torque_factor = 1, - .driver_torque_allowance = 15, - .type = TorqueDriverLimited, -}; - -const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8}, {MAZDA_CRZ_BTNS, 0, 8}, {MAZDA_LKAS_HUD, 0, 8}}; - -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 }}}, -}; - // track msgs coming from OP so that we know what CAM msgs to drop and what to forward static void mazda_rx_hook(const CANPacket_t *to_push) { if ((int)GET_BUS(to_push) == MAZDA_MAIN) { @@ -69,6 +51,17 @@ static void mazda_rx_hook(const CANPacket_t *to_push) { } static bool mazda_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits MAZDA_STEERING_LIMITS = { + .max_steer = 800, + .max_rate_up = 10, + .max_rate_down = 25, + .max_rt_delta = 300, + .max_rt_interval = 250000, + .driver_torque_factor = 1, + .driver_torque_allowance = 15, + .type = TorqueDriverLimited, + }; + bool tx = true; int bus = GET_BUS(to_send); // Check if msg is sent on the main BUS @@ -116,6 +109,16 @@ static int mazda_fwd_hook(int bus, int addr) { } static safety_config mazda_init(uint16_t param) { + static const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8}, {MAZDA_CRZ_BTNS, 0, 8}, {MAZDA_LKAS_HUD, 0, 8}}; + + static 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 }}}, + }; + UNUSED(param); return BUILD_SAFETY_CFG(mazda_rx_checks, MAZDA_TX_MSGS); } diff --git a/panda/board/safety/safety_nissan.h b/panda/board/safety/safety_nissan.h index c2406260fe9ec23..fd47e0944822647 100644 --- a/panda/board/safety/safety_nissan.h +++ b/panda/board/safety/safety_nissan.h @@ -1,44 +1,8 @@ -const SteeringLimits NISSAN_STEERING_LIMITS = { - .angle_deg_to_can = 100, - .angle_rate_up_lookup = { - {0., 5., 15.}, - {5., .8, .15} - }, - .angle_rate_down_lookup = { - {0., 5., 15.}, - {5., 3.5, .4} - }, -}; - -const CanMsg NISSAN_TX_MSGS[] = { - {0x169, 0, 8}, // LKAS - {0x2b1, 0, 8}, // PROPILOT_HUD - {0x4cc, 0, 8}, // PROPILOT_HUD_INFO_MSG - {0x20b, 2, 6}, // CRUISE_THROTTLE (X-Trail) - {0x20b, 1, 6}, // CRUISE_THROTTLE (Altima) - {0x280, 2, 8} // CANCEL_MSG (Leaf) -}; +#pragma once -// Signals duplicated below due to the fact that these messages can come in on either CAN bus, depending on car model. -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 -}; +#include "safety_declarations.h" -// EPS Location. false = V-CAN, true = C-CAN -const int NISSAN_PARAM_ALT_EPS_BUS = 1; - -bool nissan_alt_eps = false; +static bool nissan_alt_eps = false; static void nissan_rx_hook(const CANPacket_t *to_push) { int bus = GET_BUS(to_push); @@ -94,6 +58,18 @@ static void nissan_rx_hook(const CANPacket_t *to_push) { static bool nissan_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits NISSAN_STEERING_LIMITS = { + .angle_deg_to_can = 100, + .angle_rate_up_lookup = { + {0., 5., 15.}, + {5., .8, .15} + }, + .angle_rate_down_lookup = { + {0., 5., 15.}, + {5., 3.5, .4} + }, + }; + bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; @@ -147,6 +123,34 @@ static int nissan_fwd_hook(int bus_num, int addr) { } static safety_config nissan_init(uint16_t param) { + static const CanMsg NISSAN_TX_MSGS[] = { + {0x169, 0, 8}, // LKAS + {0x2b1, 0, 8}, // PROPILOT_HUD + {0x4cc, 0, 8}, // PROPILOT_HUD_INFO_MSG + {0x20b, 2, 6}, // CRUISE_THROTTLE (X-Trail) + {0x20b, 1, 6}, // CRUISE_THROTTLE (Altima) + {0x280, 2, 8} // CANCEL_MSG (Leaf) + }; + + // Signals duplicated below due to the fact that these messages can come in on either CAN bus, depending on car model. + static 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 + }; + + // EPS Location. false = V-CAN, true = C-CAN + const int NISSAN_PARAM_ALT_EPS_BUS = 1; + nissan_alt_eps = GET_FLAG(param, NISSAN_PARAM_ALT_EPS_BUS); return BUILD_SAFETY_CFG(nissan_rx_checks, NISSAN_TX_MSGS); } diff --git a/panda/board/safety/safety_subaru.h b/panda/board/safety/safety_subaru.h index 581dc50b7f18365..290150657e506a8 100644 --- a/panda/board/safety/safety_subaru.h +++ b/panda/board/safety/safety_subaru.h @@ -1,3 +1,7 @@ +#pragma once + +#include "safety_declarations.h" + #define SUBARU_STEERING_LIMITS_GENERATOR(steer_max, rate_up, rate_down) \ { \ .max_steer = (steer_max), \ @@ -16,21 +20,6 @@ .has_steer_req_tolerance = true, \ } - -const SteeringLimits SUBARU_STEERING_LIMITS = SUBARU_STEERING_LIMITS_GENERATOR(2047, 50, 70); -const SteeringLimits SUBARU_GEN2_STEERING_LIMITS = SUBARU_STEERING_LIMITS_GENERATOR(1000, 40, 40); - - -const LongitudinalLimits SUBARU_LONG_LIMITS = { - .min_gas = 808, // appears to be engine braking - .max_gas = 3400, // approx 2 m/s^2 when maxing cruise_rpm and cruise_throttle - .inactive_gas = 1818, // this is zero acceleration - .max_brake = 600, // approx -3.5 m/s^2 - - .min_transmission_rpm = 0, - .max_transmission_rpm = 3600, -}; - #define MSG_SUBARU_Brake_Status 0x13c #define MSG_SUBARU_CruiseControl 0x240 #define MSG_SUBARU_Throttle 0x40 @@ -38,7 +27,6 @@ const LongitudinalLimits SUBARU_LONG_LIMITS = { #define MSG_SUBARU_Wheel_Speeds 0x13a #define MSG_SUBARU_ES_LKAS 0x122 -#define MSG_SUBARU_ES_LKAS_ANGLE 0x124 #define MSG_SUBARU_ES_Brake 0x220 #define MSG_SUBARU_ES_Distance 0x221 #define MSG_SUBARU_ES_Status 0x222 @@ -80,40 +68,8 @@ const LongitudinalLimits SUBARU_LONG_LIMITS = { {.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) -}; - -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) -}; - -const CanMsg SUBARU_GEN2_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) -}; - -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() -}; - -RxCheck subaru_rx_checks[] = { - SUBARU_COMMON_RX_CHECKS(SUBARU_MAIN_BUS) -}; - -RxCheck subaru_gen2_rx_checks[] = { - SUBARU_COMMON_RX_CHECKS(SUBARU_ALT_BUS) -}; - - -const uint16_t SUBARU_PARAM_GEN2 = 1; -const uint16_t SUBARU_PARAM_LONGITUDINAL = 2; - -bool subaru_gen2 = false; -bool subaru_longitudinal = false; - +static bool subaru_gen2 = false; +static bool subaru_longitudinal = false; static uint32_t subaru_get_checksum(const CANPacket_t *to_push) { return (uint8_t)GET_BYTE(to_push, 0); @@ -180,6 +136,19 @@ static void subaru_rx_hook(const CANPacket_t *to_push) { } static bool subaru_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits SUBARU_STEERING_LIMITS = SUBARU_STEERING_LIMITS_GENERATOR(2047, 50, 70); + const SteeringLimits SUBARU_GEN2_STEERING_LIMITS = SUBARU_STEERING_LIMITS_GENERATOR(1000, 40, 40); + + const LongitudinalLimits SUBARU_LONG_LIMITS = { + .min_gas = 808, // appears to be engine braking + .max_gas = 3400, // approx 2 m/s^2 when maxing cruise_rpm and cruise_throttle + .inactive_gas = 1818, // this is zero acceleration + .max_brake = 600, // approx -3.5 m/s^2 + + .min_transmission_rpm = 0, + .max_transmission_rpm = 3600, + }; + bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; @@ -266,9 +235,39 @@ static int subaru_fwd_hook(int bus_num, int addr) { } static safety_config subaru_init(uint16_t param) { + static const CanMsg SUBARU_TX_MSGS[] = { + SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) + }; + + static 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) + }; + + static const CanMsg SUBARU_GEN2_TX_MSGS[] = { + SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) + }; + + static 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() + }; + + static RxCheck subaru_rx_checks[] = { + SUBARU_COMMON_RX_CHECKS(SUBARU_MAIN_BUS) + }; + + static RxCheck subaru_gen2_rx_checks[] = { + SUBARU_COMMON_RX_CHECKS(SUBARU_ALT_BUS) + }; + + const uint16_t SUBARU_PARAM_GEN2 = 1; + subaru_gen2 = GET_FLAG(param, SUBARU_PARAM_GEN2); #ifdef ALLOW_DEBUG + const uint16_t SUBARU_PARAM_LONGITUDINAL = 2; subaru_longitudinal = GET_FLAG(param, SUBARU_PARAM_LONGITUDINAL); #endif diff --git a/panda/board/safety/safety_subaru_preglobal.h b/panda/board/safety/safety_subaru_preglobal.h index 1047814ac351271..760840f333b9258 100644 --- a/panda/board/safety/safety_subaru_preglobal.h +++ b/panda/board/safety/safety_subaru_preglobal.h @@ -1,13 +1,6 @@ -const SteeringLimits SUBARU_PG_STEERING_LIMITS = { - .max_steer = 2047, - .max_rt_delta = 940, - .max_rt_interval = 250000, - .max_rate_up = 50, - .max_rate_down = 70, - .driver_torque_factor = 10, - .driver_torque_allowance = 75, - .type = TorqueDriverLimited, -}; +#pragma once + +#include "safety_declarations.h" // Preglobal platform // 0x161 is ES_CruiseThrottle @@ -24,22 +17,7 @@ const SteeringLimits SUBARU_PG_STEERING_LIMITS = { #define SUBARU_PG_MAIN_BUS 0 #define SUBARU_PG_CAM_BUS 2 -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} -}; - -// TODO: do checksum and counter checks after adding the signals to the outback dbc file -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 }}}, -}; - - -const int SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE = 1; -bool subaru_pg_reversed_driver_torque = false; - +static bool subaru_pg_reversed_driver_torque = false; static void subaru_preglobal_rx_hook(const CANPacket_t *to_push) { const int bus = GET_BUS(to_push); @@ -78,6 +56,17 @@ static void subaru_preglobal_rx_hook(const CANPacket_t *to_push) { } static bool subaru_preglobal_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits SUBARU_PG_STEERING_LIMITS = { + .max_steer = 2047, + .max_rt_delta = 940, + .max_rt_interval = 250000, + .max_rate_up = 50, + .max_rate_down = 70, + .driver_torque_factor = 10, + .driver_torque_allowance = 75, + .type = TorqueDriverLimited, + }; + bool tx = true; int addr = GET_ADDR(to_send); @@ -114,6 +103,20 @@ static int subaru_preglobal_fwd_hook(int bus_num, int addr) { } static safety_config subaru_preglobal_init(uint16_t param) { + static 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} + }; + + // TODO: do checksum and counter checks after adding the signals to the outback dbc file + static 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 }}}, + }; + + const int SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE = 1; + subaru_pg_reversed_driver_torque = GET_FLAG(param, SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE); return BUILD_SAFETY_CFG(subaru_preglobal_rx_checks, SUBARU_PG_TX_MSGS); } diff --git a/panda/board/safety/safety_tesla.h b/panda/board/safety/safety_tesla.h index 652161ff2c1ecda..7ea50dcfe537346 100644 --- a/panda/board/safety/safety_tesla.h +++ b/panda/board/safety/safety_tesla.h @@ -1,70 +1,12 @@ -const SteeringLimits TESLA_STEERING_LIMITS = { - .angle_deg_to_can = 10, - .angle_rate_up_lookup = { - {0., 5., 15.}, - {10., 1.6, .3} - }, - .angle_rate_down_lookup = { - {0., 5., 15.}, - {10., 7.0, .8} - }, -}; - -const LongitudinalLimits TESLA_LONG_LIMITS = { - .max_accel = 425, // 2. m/s^2 - .min_accel = 287, // -3.52 m/s^2 // TODO: limit to -3.48 - .inactive_accel = 375, // 0. m/s^2 -}; +#pragma once +#include "safety_declarations.h" -const int TESLA_FLAG_POWERTRAIN = 1; -const int TESLA_FLAG_LONGITUDINAL_CONTROL = 2; -const int TESLA_FLAG_RAVEN = 4; +static bool tesla_longitudinal = false; +static bool tesla_powertrain = false; // Are we the second panda intercepting the powertrain bus? +static bool tesla_raven = false; -const CanMsg TESLA_TX_MSGS[] = { - {0x488, 0, 4}, // DAS_steeringControl - {0x45, 0, 8}, // STW_ACTN_RQ - {0x45, 2, 8}, // STW_ACTN_RQ - {0x2b9, 0, 8}, // DAS_control -}; - -const CanMsg TESLA_PT_TX_MSGS[] = { - {0x2bf, 0, 8}, // DAS_control -}; - -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 -}; - -RxCheck tesla_raven_rx_checks[] = { - {.msg = {{0x2b9, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control - {.msg = {{0x131, 2, 8, .frequency = 100U}, { 0 }, { 0 }}}, // EPAS3P_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 -}; - -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 -}; - -bool tesla_longitudinal = false; -bool tesla_powertrain = false; // Are we the second panda intercepting the powertrain bus? -bool tesla_raven = false; - -bool tesla_stock_aeb = false; +static bool tesla_stock_aeb = false; static void tesla_rx_hook(const CANPacket_t *to_push) { int bus = GET_BUS(to_push); @@ -129,6 +71,24 @@ static void tesla_rx_hook(const CANPacket_t *to_push) { static bool tesla_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits TESLA_STEERING_LIMITS = { + .angle_deg_to_can = 10, + .angle_rate_up_lookup = { + {0., 5., 15.}, + {10., 1.6, .3} + }, + .angle_rate_down_lookup = { + {0., 5., 15.}, + {10., 7.0, .8} + }, + }; + + const LongitudinalLimits TESLA_LONG_LIMITS = { + .max_accel = 425, // 2. m/s^2 + .min_accel = 287, // -3.52 m/s^2 // TODO: limit to -3.48 + .inactive_accel = 375, // 0. m/s^2 + }; + bool tx = true; int addr = GET_ADDR(to_send); bool violation = false; @@ -216,6 +176,21 @@ static int tesla_fwd_hook(int bus_num, int addr) { } static safety_config tesla_init(uint16_t param) { + const int TESLA_FLAG_POWERTRAIN = 1; + const int TESLA_FLAG_LONGITUDINAL_CONTROL = 2; + const int TESLA_FLAG_RAVEN = 4; + + static const CanMsg TESLA_TX_MSGS[] = { + {0x488, 0, 4}, // DAS_steeringControl + {0x45, 0, 8}, // STW_ACTN_RQ + {0x45, 2, 8}, // STW_ACTN_RQ + {0x2b9, 0, 8}, // DAS_control + }; + + static const CanMsg TESLA_PT_TX_MSGS[] = { + {0x2bf, 0, 8}, // DAS_control + }; + tesla_powertrain = GET_FLAG(param, TESLA_FLAG_POWERTRAIN); tesla_longitudinal = GET_FLAG(param, TESLA_FLAG_LONGITUDINAL_CONTROL); tesla_raven = GET_FLAG(param, TESLA_FLAG_RAVEN); @@ -224,10 +199,38 @@ static safety_config tesla_init(uint16_t param) { safety_config ret; if (tesla_powertrain) { + static 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 + }; + ret = BUILD_SAFETY_CFG(tesla_pt_rx_checks, TESLA_PT_TX_MSGS); } else if (tesla_raven) { + static RxCheck tesla_raven_rx_checks[] = { + {.msg = {{0x2b9, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control + {.msg = {{0x131, 2, 8, .frequency = 100U}, { 0 }, { 0 }}}, // EPAS3P_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 + }; + ret = BUILD_SAFETY_CFG(tesla_raven_rx_checks, TESLA_TX_MSGS); } else { + static 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 + }; + ret = BUILD_SAFETY_CFG(tesla_rx_checks, TESLA_TX_MSGS); } return ret; diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h index 05f84e46049e603..7008bf8419efe22 100644 --- a/panda/board/safety/safety_toyota.h +++ b/panda/board/safety/safety_toyota.h @@ -1,45 +1,18 @@ -const SteeringLimits TOYOTA_STEERING_LIMITS = { - .max_steer = 1500, - .max_rate_up = 15, // ramp up slow - .max_rate_down = 25, // ramp down fast - .max_torque_error = 350, // max torque cmd in excess of motor torque - .max_rt_delta = 450, // the real time limit is 1800/sec, a 20% buffer - .max_rt_interval = 250000, - .type = TorqueMotorLimited, - - // the EPS faults when the steering angle rate is above a certain threshold for too long. to prevent this, - // we allow setting STEER_REQUEST bit to 0 while maintaining the requested torque value for a single frame - .min_valid_request_frames = 18, - .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; +#pragma once -// longitudinal limits -const LongitudinalLimits TOYOTA_LONG_LIMITS = { - .max_accel = 2000, // 2.0 m/s2 - .min_accel = -3500, // -3.5 m/s2 -}; +#include "safety_declarations.h" // 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_BASE_TX_MSGS \ + {0x191, 0, 8}, {0x412, 0, 8}, {0x343, 0, 8}, {0x1D2, 0, 8}, /* LKAS + LTA + ACC & PCM cancel cmds */ \ + +#define TOYOTA_COMMON_TX_MSGS \ + TOYOTA_BASE_TX_MSGS \ + {0x2E4, 0, 5}, \ + +#define TOYOTA_COMMON_SECOC_TX_MSGS \ + TOYOTA_BASE_TX_MSGS \ + {0x2E4, 0, 8}, {0x131, 0, 8}, \ #define TOYOTA_COMMON_LONG_TX_MSGS \ TOYOTA_COMMON_TX_MSGS \ @@ -48,42 +21,20 @@ const LongitudinalLimits TOYOTA_LONG_LIMITS = { {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 -}; - #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) -}; - -// 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) -}; - -// safety param flags -// first byte is for EPS factor, second is for flags -const uint32_t TOYOTA_PARAM_OFFSET = 8U; -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; - -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 + {.msg = {{0x1D2, 0, 8, .check_checksum = true, .frequency = 33U}, \ + {0x176, 0, 8, .check_checksum = true, .frequency = 32U}, { 0 }}}, \ + {.msg = {{0x101, 0, 8, .check_checksum = false, .frequency = 50U}, \ + {0x224, 0, 8, .check_checksum = false, .frequency = 40U}, \ + {0x226, 0, 8, .check_checksum = false, .frequency = 40U}}}, \ + +static bool toyota_secoc = false; +static bool toyota_alt_brake = false; +static bool toyota_stock_longitudinal = false; +static bool toyota_lta = false; +static int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file static uint32_t toyota_compute_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); @@ -111,6 +62,8 @@ static bool toyota_get_quality_flag_valid(const CANPacket_t *to_push) { } static void toyota_rx_hook(const CANPacket_t *to_push) { + const int TOYOTA_LTA_MAX_ANGLE = 1657; // EPS only accepts up to 94.9461 + if (GET_BUS(to_push) == 0U) { int addr = GET_ADDR(to_push); @@ -145,14 +98,31 @@ static void toyota_rx_hook(const CANPacket_t *to_push) { } // 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); - pcm_cruise_check(cruise_engaged); - - // sample gas pedal - gas_pressed = !GET_BIT(to_push, 4U); + // exit controls on rising edge of gas press, if not alternative experience + // exit controls on rising edge of brake press + if (toyota_secoc) { + if (addr == 0x176) { + bool cruise_engaged = GET_BIT(to_push, 5U); // PCM_CRUISE.CRUISE_ACTIVE + pcm_cruise_check(cruise_engaged); + } + if (addr == 0x116) { + gas_pressed = GET_BYTE(to_push, 1) != 0U; // GAS_PEDAL.GAS_PEDAL_USER + } + if (addr == 0x101) { + brake_pressed = GET_BIT(to_push, 3U); // BRAKE_MODULE.BRAKE_PRESSED (toyota_rav4_prime_generated.dbc) + } + } else { + if (addr == 0x1D2) { + bool cruise_engaged = GET_BIT(to_push, 5U); // PCM_CRUISE.CRUISE_ACTIVE + pcm_cruise_check(cruise_engaged); + gas_pressed = !GET_BIT(to_push, 4U); // PCM_CRUISE.GAS_RELEASED + } + if (!toyota_alt_brake && (addr == 0x226)) { + brake_pressed = GET_BIT(to_push, 37U); // BRAKE_MODULE.BRAKE_PRESSED (toyota_nodsu_pt_generated.dbc) + } + if (toyota_alt_brake && (addr == 0x224)) { + brake_pressed = GET_BIT(to_push, 5U); // BRAKE_MODULE.BRAKE_PRESSED (toyota_new_mc_pt_generated.dbc) + } } // sample speed @@ -169,12 +139,6 @@ static void toyota_rx_hook(const CANPacket_t *to_push) { 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); - } - bool stock_ecu_detected = addr == 0x2E4; // STEERING_LKA if (!toyota_stock_longitudinal && (addr == 0x343)) { stock_ecu_detected = true; // ACC_CONTROL @@ -184,6 +148,44 @@ static void toyota_rx_hook(const CANPacket_t *to_push) { } static bool toyota_tx_hook(const CANPacket_t *to_send) { + const SteeringLimits TOYOTA_STEERING_LIMITS = { + .max_steer = 1500, + .max_rate_up = 15, // ramp up slow + .max_rate_down = 25, // ramp down fast + .max_torque_error = 350, // max torque cmd in excess of motor torque + .max_rt_delta = 450, // the real time limit is 1800/sec, a 20% buffer + .max_rt_interval = 250000, + .type = TorqueMotorLimited, + + // the EPS faults when the steering angle rate is above a certain threshold for too long. to prevent this, + // we allow setting STEER_REQUEST bit to 0 while maintaining the requested torque value for a single frame + .min_valid_request_frames = 18, + .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_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 + .min_accel = -3500, // -3.5 m/s2 + }; + bool tx = true; int addr = GET_ADDR(to_send); int bus = GET_BUS(to_send); @@ -223,7 +225,7 @@ static bool toyota_tx_hook(const CANPacket_t *to_send) { } } - // LTA angle steering check + // STEERING_LTA angle steering check if (addr == 0x191) { // check the STEER_REQUEST, STEER_REQUEST_2, TORQUE_WIND_DOWN, STEER_ANGLE_CMD signals bool lta_request = GET_BIT(to_send, 0U); @@ -271,6 +273,20 @@ static bool toyota_tx_hook(const CANPacket_t *to_send) { } } + // STEERING_LTA_2 angle steering check (SecOC) + if (toyota_secoc && (addr == 0x131)) { + // SecOC cars block any form of LTA actuation for now + bool lta_request = GET_BIT(to_send, 3U); // STEERING_LTA_2.STEER_REQUEST + bool lta_request2 = GET_BIT(to_send, 0U); // STEERING_LTA_2.STEER_REQUEST_2 + int lta_angle_msb = GET_BYTE(to_send, 2); // STEERING_LTA_2.STEER_ANGLE_CMD (MSB) + int lta_angle_lsb = GET_BYTE(to_send, 3); // STEERING_LTA_2.STEER_ANGLE_CMD (LSB) + + bool actuation = lta_request || lta_request2 || (lta_angle_msb != 0) || (lta_angle_lsb != 0); + if (actuation) { + tx = false; + } + } + // STEER: safety check on bytes 2-3 if (addr == 0x2E4) { int desired_torque = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2); @@ -302,6 +318,31 @@ static bool toyota_tx_hook(const CANPacket_t *to_send) { } static safety_config toyota_init(uint16_t param) { + static const CanMsg TOYOTA_TX_MSGS[] = { + TOYOTA_COMMON_TX_MSGS + }; + + static const CanMsg TOYOTA_SECOC_TX_MSGS[] = { + TOYOTA_COMMON_SECOC_TX_MSGS + }; + + static const CanMsg TOYOTA_LONG_TX_MSGS[] = { + TOYOTA_COMMON_LONG_TX_MSGS + }; + + // safety param flags + // first byte is for EPS factor, second is for flags + const uint32_t TOYOTA_PARAM_OFFSET = 8U; + 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; + +#ifdef ALLOW_DEBUG + const uint32_t TOYOTA_PARAM_SECOC = 8UL << TOYOTA_PARAM_OFFSET; + toyota_secoc = GET_FLAG(param, TOYOTA_PARAM_SECOC); +#endif + 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); @@ -309,13 +350,30 @@ static safety_config toyota_init(uint16_t param) { safety_config ret; if (toyota_stock_longitudinal) { - SET_TX_MSGS(TOYOTA_TX_MSGS, ret); + if (toyota_secoc) { + SET_TX_MSGS(TOYOTA_SECOC_TX_MSGS, ret); + } else { + SET_TX_MSGS(TOYOTA_TX_MSGS, ret); + } } else { SET_TX_MSGS(TOYOTA_LONG_TX_MSGS, ret); } - toyota_lta ? SET_RX_CHECKS(toyota_lta_rx_checks, ret) : \ - SET_RX_CHECKS(toyota_lka_rx_checks, ret); + if (toyota_lta) { + // Check the quality flag for angle measurement when using LTA, since it's not set on TSS-P cars + static RxCheck toyota_lta_rx_checks[] = { + TOYOTA_COMMON_RX_CHECKS(true) + }; + + SET_RX_CHECKS(toyota_lta_rx_checks, ret); + } else { + static RxCheck toyota_lka_rx_checks[] = { + TOYOTA_COMMON_RX_CHECKS(false) + }; + + SET_RX_CHECKS(toyota_lka_rx_checks, ret); + } + return ret; } @@ -331,6 +389,8 @@ static int toyota_fwd_hook(int bus_num, int addr) { // 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 bool is_lkas_msg = ((addr == 0x2E4) || (addr == 0x412) || (addr == 0x191)); + // on SecOC cars 0x131 is also LTA + is_lkas_msg |= toyota_secoc && (addr == 0x131); // in TSS2 the camera does ACC as well, so filter 0x343 bool is_acc_msg = (addr == 0x343); bool block_msg = is_lkas_msg || (is_acc_msg && !toyota_stock_longitudinal); diff --git a/panda/board/safety/safety_volkswagen_common.h b/panda/board/safety/safety_volkswagen_common.h index ce2bf580feacde0..f94879212bf2a48 100644 --- a/panda/board/safety/safety_volkswagen_common.h +++ b/panda/board/safety/safety_volkswagen_common.h @@ -1,10 +1,13 @@ -#ifndef SAFETY_VOLKSWAGEN_COMMON_H -#define SAFETY_VOLKSWAGEN_COMMON_H +#pragma once +extern const uint16_t FLAG_VOLKSWAGEN_LONG_CONTROL; const uint16_t FLAG_VOLKSWAGEN_LONG_CONTROL = 1; +extern bool volkswagen_longitudinal; bool volkswagen_longitudinal = false; + +extern bool volkswagen_set_button_prev; bool volkswagen_set_button_prev = false; -bool volkswagen_resume_button_prev = false; -#endif +extern bool volkswagen_resume_button_prev; +bool volkswagen_resume_button_prev = false; diff --git a/panda/board/safety/safety_volkswagen_mqb.h b/panda/board/safety/safety_volkswagen_mqb.h index d880a69a6e59f23..40f7cbccc9f5e94 100644 --- a/panda/board/safety/safety_volkswagen_mqb.h +++ b/panda/board/safety/safety_volkswagen_mqb.h @@ -1,24 +1,7 @@ -#include "safety_volkswagen_common.h" - -// lateral limits -const SteeringLimits VOLKSWAGEN_MQB_STEERING_LIMITS = { - .max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) - .max_rt_delta = 75, // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75 - .max_rt_interval = 250000, // 250ms between real time checks - .max_rate_up = 4, // 2.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) - .max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) - .driver_torque_allowance = 80, - .driver_torque_factor = 3, - .type = TorqueDriverLimited, -}; +#pragma once -// longitudinal limits -// acceleration in m/s2 * 1000 to avoid floating point math -const LongitudinalLimits VOLKSWAGEN_MQB_LONG_LIMITS = { - .max_accel = 2000, - .min_accel = -3500, - .inactive_accel = 3010, // VW sends one increment above the max range when inactive -}; +#include "safety_declarations.h" +#include "safety_volkswagen_common.h" #define MSG_ESP_19 0x0B2 // RX from ABS, for wheel speeds #define MSG_LH_EPS_03 0x09F // RX from EPS, for driver steering torque @@ -33,25 +16,9 @@ const LongitudinalLimits VOLKSWAGEN_MQB_LONG_LIMITS = { #define MSG_MOTOR_14 0x3BE // RX from ECU, for brake switch status #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}, {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}}; - -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 }}}, -}; - -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 uint8_t volkswagen_crc8_lut_8h2f[256]; // Static lookup table for CRC8 poly 0x2F, aka 8H2F/AUTOSAR +static bool volkswagen_mqb_brake_pedal_switch = false; +static bool volkswagen_mqb_brake_pressure_detected = false; static uint32_t volkswagen_mqb_get_checksum(const CANPacket_t *to_push) { return (uint8_t)GET_BYTE(to_push, 0); @@ -95,6 +62,23 @@ static uint32_t volkswagen_mqb_compute_crc(const CANPacket_t *to_push) { } static safety_config volkswagen_mqb_init(uint16_t param) { + // Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration + static 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}}; + + static 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}}; + + static 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 }}}, + }; + UNUSED(param); volkswagen_set_button_prev = false; @@ -197,6 +181,26 @@ static void volkswagen_mqb_rx_hook(const CANPacket_t *to_push) { } static bool volkswagen_mqb_tx_hook(const CANPacket_t *to_send) { + // lateral limits + const SteeringLimits VOLKSWAGEN_MQB_STEERING_LIMITS = { + .max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) + .max_rt_delta = 75, // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75 + .max_rt_interval = 250000, // 250ms between real time checks + .max_rate_up = 4, // 2.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) + .max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) + .driver_torque_allowance = 80, + .driver_torque_factor = 3, + .type = TorqueDriverLimited, + }; + + // longitudinal limits + // acceleration in m/s2 * 1000 to avoid floating point math + const LongitudinalLimits VOLKSWAGEN_MQB_LONG_LIMITS = { + .max_accel = 2000, + .min_accel = -3500, + .inactive_accel = 3010, // VW sends one increment above the max range when inactive + }; + int addr = GET_ADDR(to_send); bool tx = true; diff --git a/panda/board/safety/safety_volkswagen_pq.h b/panda/board/safety/safety_volkswagen_pq.h index de147cb58ad235e..75979a5149f6fe6 100644 --- a/panda/board/safety/safety_volkswagen_pq.h +++ b/panda/board/safety/safety_volkswagen_pq.h @@ -1,24 +1,7 @@ -#include "safety_volkswagen_common.h" - -// lateral limits -const SteeringLimits VOLKSWAGEN_PQ_STEERING_LIMITS = { - .max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) - .max_rt_delta = 113, // 6 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 75 ; 125 * 1.5 for safety pad = 113 - .max_rt_interval = 250000, // 250ms between real time checks - .max_rate_up = 6, // 3.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) - .max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) - .driver_torque_factor = 3, - .driver_torque_allowance = 80, - .type = TorqueDriverLimited, -}; +#pragma once -// longitudinal limits -// acceleration in m/s2 * 1000 to avoid floating point math -const LongitudinalLimits VOLKSWAGEN_PQ_LONG_LIMITS = { - .max_accel = 2000, - .min_accel = -3500, - .inactive_accel = 3010, // VW sends one increment above the max range when inactive -}; +#include "safety_declarations.h" +#include "safety_volkswagen_common.h" #define MSG_LENKHILFE_3 0x0D0 // RX from EPS, for steering angle and driver steering torque #define MSG_HCA_1 0x0D2 // TX by OP, Heading Control Assist steering torque @@ -31,21 +14,6 @@ const LongitudinalLimits VOLKSWAGEN_PQ_LONG_LIMITS = { #define MSG_ACC_GRA_ANZEIGE 0x56A // TX by OP, ACC HUD #define MSG_LDW_1 0x5BE // TX by OP, Lane line recognition and text alerts -// Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration -const CanMsg VOLKSWAGEN_PQ_STOCK_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_LDW_1, 0, 8}, - {MSG_GRA_NEU, 0, 4}, {MSG_GRA_NEU, 2, 4}}; -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}}; - -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 }}}, -}; - static uint32_t volkswagen_pq_get_checksum(const CANPacket_t *to_push) { int addr = GET_ADDR(to_push); @@ -83,6 +51,22 @@ static uint32_t volkswagen_pq_compute_checksum(const CANPacket_t *to_push) { } static safety_config volkswagen_pq_init(uint16_t param) { + // Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration + static const CanMsg VOLKSWAGEN_PQ_STOCK_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_LDW_1, 0, 8}, + {MSG_GRA_NEU, 0, 4}, {MSG_GRA_NEU, 2, 4}}; + + static 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}}; + + static 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 }}}, + }; + UNUSED(param); volkswagen_set_button_prev = false; @@ -170,6 +154,26 @@ static void volkswagen_pq_rx_hook(const CANPacket_t *to_push) { } static bool volkswagen_pq_tx_hook(const CANPacket_t *to_send) { + // lateral limits + const SteeringLimits VOLKSWAGEN_PQ_STEERING_LIMITS = { + .max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) + .max_rt_delta = 113, // 6 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 75 ; 125 * 1.5 for safety pad = 113 + .max_rt_interval = 250000, // 250ms between real time checks + .max_rate_up = 6, // 3.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) + .max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) + .driver_torque_factor = 3, + .driver_torque_allowance = 80, + .type = TorqueDriverLimited, + }; + + // longitudinal limits + // acceleration in m/s2 * 1000 to avoid floating point math + const LongitudinalLimits VOLKSWAGEN_PQ_LONG_LIMITS = { + .max_accel = 2000, + .min_accel = -3500, + .inactive_accel = 3010, // VW sends one increment above the max range when inactive + }; + int addr = GET_ADDR(to_send); bool tx = true; diff --git a/panda/board/safety_declarations.h b/panda/board/safety_declarations.h index e3cdc47cde48a91..b0e9588e95741ee 100644 --- a/panda/board/safety_declarations.h +++ b/panda/board/safety_declarations.h @@ -1,28 +1,31 @@ #pragma once +#include +#include + #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)) // cppcheck-suppress misra-c2012-1.2; allow __typeof__ #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 SET_RX_CHECKS(rx, config) \ + do { \ + (config).rx_checks = (rx); \ + (config).rx_checks_len = sizeof((rx)) / sizeof((rx)[0]); \ + } while (0); + +#define SET_TX_MSGS(tx, config) \ + do { \ + (config).tx_msgs = (tx); \ + (config).tx_msgs_len = sizeof((tx)) / sizeof((tx)[0]); \ + } while(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 uint32_t shift = i * 8; - ret |= (((uint32_t)msg->data[start + i]) << shift); - } - return ret; -} - -const int MAX_WRONG_COUNTERS = 5; -const uint8_t MAX_MISSED_MSGS = 10U; +uint32_t GET_BYTES(const CANPacket_t *msg, int start, int len); + +extern const int MAX_WRONG_COUNTERS; #define MAX_ADDR_CHECK_MSGS 3U #define MAX_SAMPLE_VALS 6 // used to represent floating point vehicle speed in a sample_t @@ -34,7 +37,7 @@ struct sample_t { int values[MAX_SAMPLE_VALS]; int min; int max; -} sample_t_default = {.values = {0}, .min = 0, .max = 0}; +}; // safety code requires floats struct lookup_t { @@ -170,32 +173,13 @@ 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); -void reset_sample(struct sample_t *sample); -bool max_limit_check(int val, const int MAX, const int MIN); -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, 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); -bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA); -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[]); +#ifdef CANFD void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]); -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); +#endif void generic_rx_checks(bool stock_ecu_detected); -void relay_malfunction_set(void); -void relay_malfunction_reset(void); bool steer_torque_cmd_checks(int desired_torque, int steer_req, const SteeringLimits limits); bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const SteeringLimits limits); bool longitudinal_accel_checks(int desired_accel, const LongitudinalLimits limits); @@ -208,39 +192,39 @@ void pcm_cruise_check(bool cruise_engaged); 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_pressed = false; -bool gas_pressed_prev = false; -bool brake_pressed = false; -bool brake_pressed_prev = false; -bool regen_braking = false; -bool regen_braking_prev = false; -bool cruise_engaged_prev = false; -struct sample_t vehicle_speed; -bool vehicle_moving = false; -bool acc_main_on = false; // referred to as "ACC off" in ISO 15622:2018 -int cruise_button_prev = 0; -bool safety_rx_checks_invalid = false; +extern bool controls_allowed; +extern bool relay_malfunction; +extern bool gas_pressed; +extern bool gas_pressed_prev; +extern bool brake_pressed; +extern bool brake_pressed_prev; +extern bool regen_braking; +extern bool regen_braking_prev; +extern bool cruise_engaged_prev; +extern struct sample_t vehicle_speed; +extern bool vehicle_moving; +extern bool acc_main_on; // referred to as "ACC off" in ISO 15622:2018 +extern int cruise_button_prev; +extern bool safety_rx_checks_invalid; // for safety modes with torque steering control -int desired_torque_last = 0; // last desired steer torque -int rt_torque_last = 0; // last desired torque for real time check -int valid_steer_req_count = 0; // counter for steer request bit matching non-zero torque -int invalid_steer_req_count = 0; // counter to allow multiple frames of mismatching torque request bit -struct sample_t torque_meas; // last 6 motor torques produced by the eps -struct sample_t torque_driver; // last 6 driver torques measured -uint32_t ts_torque_check_last = 0; -uint32_t ts_steer_req_mismatch_last = 0; // last timestamp steer req was mismatched with torque +extern int desired_torque_last; // last desired steer torque +extern int rt_torque_last; // last desired torque for real time check +extern int valid_steer_req_count; // counter for steer request bit matching non-zero torque +extern int invalid_steer_req_count; // counter to allow multiple frames of mismatching torque request bit +extern struct sample_t torque_meas; // last 6 motor torques produced by the eps +extern struct sample_t torque_driver; // last 6 driver torques measured +extern uint32_t ts_torque_check_last; +extern uint32_t ts_steer_req_mismatch_last; // last timestamp steer req was mismatched with torque // state for controls_allowed timeout logic -bool heartbeat_engaged = false; // openpilot enabled, passed in heartbeat USB command -uint32_t heartbeat_engaged_mismatches = 0; // count of mismatches between heartbeat_engaged and controls_allowed +extern bool heartbeat_engaged; // openpilot enabled, passed in heartbeat USB command +extern uint32_t heartbeat_engaged_mismatches; // count of mismatches between heartbeat_engaged and controls_allowed // for safety modes with angle steering control -uint32_t ts_angle_last = 0; -int desired_angle_last = 0; -struct sample_t angle_meas; // last 6 steer angles/curvatures +extern uint32_t ts_angle_last; +extern int desired_angle_last; +extern struct sample_t angle_meas; // last 6 steer angles/curvatures // This can be set with a USB command // It enables features that allow alternative experiences, like not disengaging on gas press @@ -260,9 +244,40 @@ struct sample_t angle_meas; // last 6 steer angles/curvatures // This flag allows AEB to be commanded from openpilot. #define ALT_EXP_ALLOW_AEB 16 -int alternative_experience = 0; +extern int alternative_experience; // time since safety mode has been changed -uint32_t safety_mode_cnt = 0U; -// allow 1s of transition timeout after relay changes state before assessing malfunctioning -const uint32_t RELAY_TRNS_TIMEOUT = 1U; +extern uint32_t safety_mode_cnt; + +typedef struct { + uint16_t id; + const safety_hooks *hooks; +} safety_hook_config; + +extern uint16_t current_safety_mode; +extern uint16_t current_safety_param; +extern safety_config current_safety_config; + +int safety_fwd_hook(int bus_num, int addr); +int set_safety_hooks(uint16_t mode, uint16_t param); + +extern const safety_hooks body_hooks; +extern const safety_hooks chrysler_hooks; +extern const safety_hooks elm327_hooks; +extern const safety_hooks nooutput_hooks; +extern const safety_hooks alloutput_hooks; +extern const safety_hooks ford_hooks; +extern const safety_hooks gm_hooks; +extern const safety_hooks honda_nidec_hooks; +extern const safety_hooks honda_bosch_hooks; +extern const safety_hooks hyundai_canfd_hooks; +extern const safety_hooks hyundai_hooks; +extern const safety_hooks hyundai_legacy_hooks; +extern const safety_hooks mazda_hooks; +extern const safety_hooks nissan_hooks; +extern const safety_hooks subaru_hooks; +extern const safety_hooks subaru_preglobal_hooks; +extern const safety_hooks tesla_hooks; +extern const safety_hooks toyota_hooks; +extern const safety_hooks volkswagen_mqb_hooks; +extern const safety_hooks volkswagen_pq_hooks; diff --git a/panda/board/stm32f4/board.h b/panda/board/stm32f4/board.h index bf95d58eaa9f6c6..0cbaae602535010 100644 --- a/panda/board/stm32f4/board.h +++ b/panda/board/stm32f4/board.h @@ -16,6 +16,9 @@ #include "boards/uno.h" #include "boards/dos.h" +// Unused functions on F4 +void sound_tick(void) {} + void detect_board_type(void) { // 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); diff --git a/panda/board/stm32f4/inc/stm32f413xx.h b/panda/board/stm32f4/inc/stm32f413xx.h index 0962a8def1a3a6c..2e2a7bc591d6794 100644 --- a/panda/board/stm32f4/inc/stm32f413xx.h +++ b/panda/board/stm32f4/inc/stm32f413xx.h @@ -2,41 +2,22 @@ ****************************************************************************** * @file stm32f413xx.h * @author MCD Application Team - * @version V2.6.0 - * @date 04-November-2016 * @brief CMSIS STM32F413xx 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 + * - Macros to access peripheral's registers hardware * ****************************************************************************** * @attention * - *

© COPYRIGHT(c) 2016 STMicroelectronics

+ * Copyright (c) 2017 STMicroelectronics. + * All rights reserved. * - * 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. + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. * ****************************************************************************** */ @@ -53,7 +34,7 @@ #define __STM32F413xx_H #ifdef __cplusplus - extern "C" { +extern "C" { #endif /* __cplusplus */ /** @addtogroup Configuration_section_for_CMSIS @@ -83,7 +64,7 @@ */ typedef enum { -/****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ + /****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ @@ -92,7 +73,7 @@ typedef enum DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ + /****** 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 */ @@ -141,7 +122,7 @@ typedef enum TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare global interrupt */ DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + FSMC_IRQn = 48, SDIO_IRQn = 49, /*!< SDIO global Interrupt */ TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ @@ -173,21 +154,21 @@ typedef enum CAN3_SCE_IRQn = 77, /*!< CAN3 SCE Interrupt */ RNG_IRQn = 80, /*!< RNG global Interrupt */ FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - UART9_IRQn = 88, /*!< UART9 global Interrupt */ - UART10_IRQn = 89, /*!< UART10 global Interrupt */ - QUADSPI_IRQn = 92, /*!< QuadSPI global Interrupt */ - FMPI2C1_EV_IRQn = 95, /*!< FMPI2C1 Event Interrupt */ - FMPI2C1_ER_IRQn = 96, /*!< FMPI2C1 Error Interrupt */ - LPTIM1_IRQn = 97, /*!< LP TIM1 interrupt */ - DFSDM2_FLT0_IRQn = 98, /*!< DFSDM2 Filter 0 global Interrupt */ - DFSDM2_FLT1_IRQn = 99, /*!< DFSDM2 Filter 1 global Interrupt */ - DFSDM2_FLT2_IRQn = 100, /*!< DFSDM2 Filter 2 global Interrupt */ - DFSDM2_FLT3_IRQn = 101 /*!< DFSDM2 Filter 3 global Interrupt */ + UART7_IRQn = 82, /*!< UART7 global interrupt */ + UART8_IRQn = 83, /*!< UART8 global interrupt */ + SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ + SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ + SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ + UART9_IRQn = 88, /*!< UART9 global Interrupt */ + UART10_IRQn = 89, /*!< UART10 global Interrupt */ + QUADSPI_IRQn = 92, /*!< QuadSPI global Interrupt */ + FMPI2C1_EV_IRQn = 95, /*!< FMPI2C1 Event Interrupt */ + FMPI2C1_ER_IRQn = 96, /*!< FMPI2C1 Error Interrupt */ + LPTIM1_IRQn = 97, /*!< LP TIM1 interrupt */ + DFSDM2_FLT0_IRQn = 98, /*!< DFSDM2 Filter 0 global Interrupt */ + DFSDM2_FLT1_IRQn = 99, /*!< DFSDM2 Filter 1 global Interrupt */ + DFSDM2_FLT2_IRQn = 100, /*!< DFSDM2 Filter 2 global Interrupt */ + DFSDM2_FLT3_IRQn = 101 /*!< DFSDM2 Filter 3 global Interrupt */ } IRQn_Type; /** @@ -383,7 +364,7 @@ typedef struct __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; +} DBGMCU_TypeDef; /** @@ -931,164 +912,167 @@ typedef struct /** @addtogroup Peripheral_memory_map * @{ */ -#define FLASH_BASE 0x08000000U /*!< FLASH (up to 1.5 MB) base address in the alias region */ -#define SRAM1_BASE 0x20000000U /*!< SRAM1(256 KB) base address in the alias region */ -#define SRAM2_BASE 0x20040000U /*!< SRAM2(64 KB) base address in the alias region */ -#define PERIPH_BASE 0x40000000U /*!< Peripheral base address in the alias region */ -#define FSMC_R_BASE 0xA0000000U /*!< FSMC registers base address */ -#define QSPI_R_BASE 0xA0001000U /*!< QuadSPI registers base address */ -#define SRAM1_BB_BASE 0x22000000U /*!< SRAM1(256 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE 0x22800000U /*!< SRAM2(64 KB) base address in the bit-band region */ -#define PERIPH_BB_BASE 0x42000000U /*!< Peripheral base address in the bit-band region */ -#define FLASH_END 0x0817FFFFU /*!< FLASH end address */ +#define FLASH_BASE 0x08000000UL /*!< FLASH (up to 1.5 MB) base address in the alias region */ +#define SRAM1_BASE 0x20000000UL /*!< SRAM1(256 KB) base address in the alias region */ +#define SRAM2_BASE 0x20040000UL /*!< SRAM2(64 KB) base address in the alias region */ +#define PERIPH_BASE 0x40000000UL /*!< Peripheral base address in the alias region */ +#define FSMC_R_BASE 0xA0000000UL /*!< FSMC registers base address */ +#define QSPI_R_BASE 0xA0001000UL /*!< QuadSPI registers base address */ +#define SRAM1_BB_BASE 0x22000000UL /*!< SRAM1(256 KB) base address in the bit-band region */ +#define SRAM2_BB_BASE 0x22800000UL /*!< SRAM2(64 KB) base address in the bit-band region */ +#define PERIPH_BB_BASE 0x42000000UL /*!< Peripheral base address in the bit-band region */ +#define FLASH_END 0x0817FFFFUL /*!< FLASH end address */ +#define FLASH_OTP_BASE 0x1FFF7800UL /*!< Base address of : (up to 528 Bytes) embedded FLASH OTP Area */ +#define FLASH_OTP_END 0x1FFF7A0FUL /*!< End address of : (up to 528 Bytes) embedded FLASH OTP Area */ /* 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) +#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) +#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) +#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000UL) /*!< 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 LPTIM1_BASE (APB1PERIPH_BASE + 0x2400U) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800U) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00U) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000U) -#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400U) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800U) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00U) -#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000U) -#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 FMPI2C1_BASE (APB1PERIPH_BASE + 0x6000U) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400U) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800U) -#define CAN3_BASE (APB1PERIPH_BASE + 0x6C00U) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000U) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400U) -#define UART7_BASE (APB1PERIPH_BASE + 0x7800U) -#define UART8_BASE (APB1PERIPH_BASE + 0x7C00U) +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000UL) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400UL) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800UL) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00UL) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000UL) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400UL) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800UL) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00UL) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000UL) +#define LPTIM1_BASE (APB1PERIPH_BASE + 0x2400UL) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800UL) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00UL) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000UL) +#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400UL) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800UL) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00UL) +#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000UL) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400UL) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800UL) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00UL) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000UL) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400UL) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800UL) +#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00UL) +#define FMPI2C1_BASE (APB1PERIPH_BASE + 0x6000UL) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400UL) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800UL) +#define CAN3_BASE (APB1PERIPH_BASE + 0x6C00UL) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000UL) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400UL) +#define UART7_BASE (APB1PERIPH_BASE + 0x7800UL) +#define UART8_BASE (APB1PERIPH_BASE + 0x7C00UL) /*!< 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 UART9_BASE (APB2PERIPH_BASE + 0x1800U) -#define UART10_BASE (APB2PERIPH_BASE + 0x1C00U) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2000U) -#define ADC_BASE (APB2PERIPH_BASE + 0x2300U) -#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00U) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000U) -#define SPI4_BASE (APB2PERIPH_BASE + 0x3400U) -#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) -#define SPI5_BASE (APB2PERIPH_BASE + 0x5000U) -#define DFSDM1_BASE (APB2PERIPH_BASE + 0x6000U) -#define DFSDM2_BASE (APB2PERIPH_BASE + 0x6400U) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00U) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20U) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40U) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60U) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100U) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180U) -#define DFSDM2_Channel0_BASE (DFSDM2_BASE + 0x00U) -#define DFSDM2_Channel1_BASE (DFSDM2_BASE + 0x20U) -#define DFSDM2_Channel2_BASE (DFSDM2_BASE + 0x40U) -#define DFSDM2_Channel3_BASE (DFSDM2_BASE + 0x60U) -#define DFSDM2_Channel4_BASE (DFSDM2_BASE + 0x80U) -#define DFSDM2_Channel5_BASE (DFSDM2_BASE + 0xA0U) -#define DFSDM2_Channel6_BASE (DFSDM2_BASE + 0xC0U) -#define DFSDM2_Channel7_BASE (DFSDM2_BASE + 0xE0U) -#define DFSDM2_Filter0_BASE (DFSDM2_BASE + 0x100U) -#define DFSDM2_Filter1_BASE (DFSDM2_BASE + 0x180U) -#define DFSDM2_Filter2_BASE (DFSDM2_BASE + 0x200U) -#define DFSDM2_Filter3_BASE (DFSDM2_BASE + 0x280U) -#define SAI1_BASE (APB2PERIPH_BASE + 0x5800U) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004U) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024U) +#define TIM1_BASE (APB2PERIPH_BASE + 0x0000UL) +#define TIM8_BASE (APB2PERIPH_BASE + 0x0400UL) +#define USART1_BASE (APB2PERIPH_BASE + 0x1000UL) +#define USART6_BASE (APB2PERIPH_BASE + 0x1400UL) +#define UART9_BASE (APB2PERIPH_BASE + 0x1800UL) +#define UART10_BASE (APB2PERIPH_BASE + 0x1C00UL) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2000UL) +#define ADC1_COMMON_BASE (APB2PERIPH_BASE + 0x2300UL) +/* Legacy define */ +#define ADC_BASE ADC1_COMMON_BASE +#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00UL) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000UL) +#define SPI4_BASE (APB2PERIPH_BASE + 0x3400UL) +#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800UL) +#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00UL) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4000UL) +#define TIM10_BASE (APB2PERIPH_BASE + 0x4400UL) +#define TIM11_BASE (APB2PERIPH_BASE + 0x4800UL) +#define SPI5_BASE (APB2PERIPH_BASE + 0x5000UL) +#define DFSDM1_BASE (APB2PERIPH_BASE + 0x6000UL) +#define DFSDM2_BASE (APB2PERIPH_BASE + 0x6400UL) +#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00UL) +#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20UL) +#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40UL) +#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60UL) +#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) +#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) +#define DFSDM2_Channel0_BASE (DFSDM2_BASE + 0x00UL) +#define DFSDM2_Channel1_BASE (DFSDM2_BASE + 0x20UL) +#define DFSDM2_Channel2_BASE (DFSDM2_BASE + 0x40UL) +#define DFSDM2_Channel3_BASE (DFSDM2_BASE + 0x60UL) +#define DFSDM2_Channel4_BASE (DFSDM2_BASE + 0x80UL) +#define DFSDM2_Channel5_BASE (DFSDM2_BASE + 0xA0UL) +#define DFSDM2_Channel6_BASE (DFSDM2_BASE + 0xC0UL) +#define DFSDM2_Channel7_BASE (DFSDM2_BASE + 0xE0UL) +#define DFSDM2_Filter0_BASE (DFSDM2_BASE + 0x100UL) +#define DFSDM2_Filter1_BASE (DFSDM2_BASE + 0x180UL) +#define DFSDM2_Filter2_BASE (DFSDM2_BASE + 0x200UL) +#define DFSDM2_Filter3_BASE (DFSDM2_BASE + 0x280UL) +#define SAI1_BASE (APB2PERIPH_BASE + 0x5800UL) +#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) +#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) /*!< 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 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) +#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000UL) +#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400UL) +#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800UL) +#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00UL) +#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000UL) +#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400UL) +#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800UL) +#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00UL) +#define CRC_BASE (AHB1PERIPH_BASE + 0x3000UL) +#define RCC_BASE (AHB1PERIPH_BASE + 0x3800UL) +#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00UL) +#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000UL) +#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) +#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) +#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) +#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) +#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) +#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) +#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) +#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) +#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400UL) +#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) +#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) +#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) +#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) +#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) +#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) +#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) +#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) /*!< AHB2 peripherals */ -#define RNG_BASE (AHB2PERIPH_BASE + 0x60800U) +#define RNG_BASE (AHB2PERIPH_BASE + 0x60800UL) /*!< 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_Bank1_R_BASE (FSMC_R_BASE + 0x0000UL) +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104UL) /*!< Debug MCU registers base address */ -#define DBGMCU_BASE 0xE0042000U +#define DBGMCU_BASE 0xE0042000UL /*!< USB registers base address */ -#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 - -#define UID_BASE 0x1FFF7A10U /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE 0x1FFF7A22U /*!< FLASH Size register base address */ -#define PACKAGE_BASE 0x1FFF7BF0U /*!< Package size register base address */ +#define USB_OTG_FS_PERIPH_BASE 0x50000000UL + +#define USB_OTG_GLOBAL_BASE 0x000UL +#define USB_OTG_DEVICE_BASE 0x800UL +#define USB_OTG_IN_ENDPOINT_BASE 0x900UL +#define USB_OTG_OUT_ENDPOINT_BASE 0xB00UL +#define USB_OTG_EP_REG_SIZE 0x20UL +#define USB_OTG_HOST_BASE 0x400UL +#define USB_OTG_HOST_PORT_BASE 0x440UL +#define USB_OTG_HOST_CHANNEL_BASE 0x500UL +#define USB_OTG_HOST_CHANNEL_SIZE 0x20UL +#define USB_OTG_PCGCCTL_BASE 0xE00UL +#define USB_OTG_FIFO_BASE 0x1000UL +#define USB_OTG_FIFO_SIZE 0x1000UL + +#define UID_BASE 0x1FFF7A10UL /*!< Unique device ID register base address */ +#define FLASHSIZE_BASE 0x1FFF7A22UL /*!< FLASH Size register base address */ +#define PACKAGE_BASE 0x1FFF7BF0UL /*!< Package size register base address */ /** * @} */ @@ -1135,8 +1119,10 @@ typedef struct #define USART6 ((USART_TypeDef *) USART6_BASE) #define UART9 ((USART_TypeDef *) UART9_BASE) #define UART10 ((USART_TypeDef *) UART10_BASE) -#define ADC ((ADC_Common_TypeDef *) ADC_BASE) #define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC1_COMMON ((ADC_Common_TypeDef *) ADC1_COMMON_BASE) +/* Legacy define */ +#define ADC ADC1_COMMON #define SDIO ((SDIO_TypeDef *) SDIO_BASE) #define SPI1 ((SPI_TypeDef *) SPI1_BASE) #define SPI4 ((SPI_TypeDef *) SPI4_BASE) @@ -1211,9 +1197,17 @@ typedef struct * @{ */ - /** @addtogroup Peripheral_Registers_Bits_Definition +/** @addtogroup Hardware_Constant_Definition * @{ */ +#define LSI_STARTUP_TIME 40U /*!< LSI Maximum startup time in us */ +/** + * @} + */ + +/** @addtogroup Peripheral_Registers_Bits_Definition +* @{ +*/ /******************************************************************************/ /* Peripheral Registers_Bits_Definition */ @@ -1224,504 +1218,505 @@ typedef struct /* Analog to Digital Converter */ /* */ /******************************************************************************/ + /******************** Bit definition for ADC_SR register ********************/ #define ADC_SR_AWD_Pos (0U) -#define ADC_SR_AWD_Msk (0x1U << ADC_SR_AWD_Pos) /*!< 0x00000001 */ +#define ADC_SR_AWD_Msk (0x1UL << ADC_SR_AWD_Pos) /*!< 0x00000001 */ #define ADC_SR_AWD ADC_SR_AWD_Msk /*! 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0xFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) -#define GET_MAILBOX_BYTES_04(msg) ((msg)->RDLR) -#define GET_MAILBOX_BYTES_48(msg) ((msg)->RDHR) - -// SAE 2284-3 : minimum 16 tq, SJW 3, sample point at 81.3% -#define CAN_QUANTA 16U -#define CAN_SEQ1 12U -#define CAN_SEQ2 3U -#define CAN_SJW 3U - -#define CAN_PCLK 48000U -// 333 = 33.3 kbps -// 5000 = 500 kbps -#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) - -#define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==CAN1) ? "CAN1" : (((CAN_DEV) == CAN2) ? "CAN2" : "CAN3")) - -void print(const char *a); +#include "llbxcan_declarations.h" // kbps multiplied by 10 -const uint32_t speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U}; -const uint32_t data_speeds[] = {0U}; // No separate data speed, dummy +const uint32_t speeds[SPEEDS_ARRAY_SIZE] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U}; +const uint32_t data_speeds[DATA_SPEEDS_ARRAY_SIZE] = {0U}; // No separate data speed, dummy bool llcan_set_speed(CAN_TypeDef *CANx, uint32_t speed, bool loopback, bool silent) { bool ret = true; diff --git a/panda/board/stm32f4/llbxcan_declarations.h b/panda/board/stm32f4/llbxcan_declarations.h new file mode 100644 index 000000000000000..aa10719457028b3 --- /dev/null +++ b/panda/board/stm32f4/llbxcan_declarations.h @@ -0,0 +1,28 @@ +#pragma once + +// SAE 2284-3 : minimum 16 tq, SJW 3, sample point at 81.3% +#define CAN_QUANTA 16U +#define CAN_SEQ1 12U +#define CAN_SEQ2 3U +#define CAN_SJW 3U + +#define CAN_PCLK 48000U +// 333 = 33.3 kbps +// 5000 = 500 kbps +#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) + +#define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==CAN1) ? "CAN1" : (((CAN_DEV) == CAN2) ? "CAN2" : "CAN3")) + +void print(const char *a); + +// kbps multiplied by 10 +#define SPEEDS_ARRAY_SIZE 8 +extern const uint32_t speeds[SPEEDS_ARRAY_SIZE]; +#define DATA_SPEEDS_ARRAY_SIZE 1 +extern const uint32_t data_speeds[DATA_SPEEDS_ARRAY_SIZE]; // No separate data speed, dummy + +bool llcan_set_speed(CAN_TypeDef *CANx, uint32_t speed, bool loopback, bool silent); +void llcan_irq_disable(const CAN_TypeDef *CANx); +void llcan_irq_enable(const CAN_TypeDef *CANx); +bool llcan_init(CAN_TypeDef *CANx); +void llcan_clear_send(CAN_TypeDef *CANx); diff --git a/panda/board/stm32f4/llfan.h b/panda/board/stm32f4/llfan.h index 9e3f0c654b1846a..95861661219a57f 100644 --- a/panda/board/stm32f4/llfan.h +++ b/panda/board/stm32f4/llfan.h @@ -1,5 +1,5 @@ // TACH interrupt handler -void EXTI2_IRQ_Handler(void) { +static void EXTI2_IRQ_Handler(void) { volatile unsigned int pr = EXTI->PR & (1U << 2); if ((pr & (1U << 2)) != 0U) { fan_state.tach_counter++; diff --git a/panda/board/stm32f4/llspi.h b/panda/board/stm32f4/llspi.h index 31e419b6f74b116..e986adb4afad01e 100644 --- a/panda/board/stm32f4/llspi.h +++ b/panda/board/stm32f4/llspi.h @@ -1,3 +1,4 @@ +#if defined(ENABLE_SPI) || defined(BOOTSTUB) void llspi_miso_dma(uint8_t *addr, int len) { // disable DMA DMA2_Stream3->CR &= ~DMA_SxCR_EN; @@ -29,9 +30,8 @@ void llspi_mosi_dma(uint8_t *addr, int len) { DMA2_Stream2->CR |= DMA_SxCR_EN; register_set_bits(&(SPI1->CR2), SPI_CR2_RXDMAEN); } - // SPI MOSI DMA FINISHED -void DMA2_Stream2_IRQ_Handler(void) { +static void DMA2_Stream2_IRQ_Handler(void) { // Clear interrupt flag ENTER_CRITICAL(); DMA2->LIFCR = DMA_LIFCR_CTCIF2; @@ -42,7 +42,7 @@ void DMA2_Stream2_IRQ_Handler(void) { } // SPI MISO DMA FINISHED -void DMA2_Stream3_IRQ_Handler(void) { +static void DMA2_Stream3_IRQ_Handler(void) { // Clear interrupt flag DMA2->LIFCR = DMA_LIFCR_CTCIF3; @@ -88,3 +88,4 @@ void llspi_init(void) { NVIC_EnableIRQ(DMA2_Stream2_IRQn); NVIC_EnableIRQ(DMA2_Stream3_IRQn); } +#endif diff --git a/panda/board/stm32f4/lluart.h b/panda/board/stm32f4/lluart.h index 64094119f4dcb76..f4b1a5f1db1fc74 100644 --- a/panda/board/stm32f4/lluart.h +++ b/panda/board/stm32f4/lluart.h @@ -20,7 +20,7 @@ void uart_tx_ring(uart_ring *q){ EXIT_CRITICAL(); } -void uart_rx_ring(uart_ring *q){ +static void uart_rx_ring(uart_ring *q){ ENTER_CRITICAL(); // Read out RX buffer @@ -45,15 +45,10 @@ void uart_rx_ring(uart_ring *q){ EXIT_CRITICAL(); } -void uart_send_break(uart_ring *u) { - while ((u->uart->CR1 & USART_CR1_SBK) != 0U); - u->uart->CR1 |= USART_CR1_SBK; -} - // This read after reading SR clears all error interrupts. We don't want compiler warnings, nor optimizations #define UART_READ_DR(uart) volatile uint8_t t = (uart)->DR; UNUSED(t); -void uart_interrupt_handler(uart_ring *q) { +static void uart_interrupt_handler(uart_ring *q) { ENTER_CRITICAL(); // Read UART status. This is also the first step necessary in clearing most interrupts diff --git a/panda/board/stm32f4/llusb.h b/panda/board/stm32f4/llusb.h index 6f15c89e1182a2f..3d3b35e588fc2b2 100644 --- a/panda/board/stm32f4/llusb.h +++ b/panda/board/stm32f4/llusb.h @@ -1,19 +1,8 @@ -USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; - -#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_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 5UL -#define USB_OTG_SPEED_FULL 3UL +#include "llusb_declarations.h" +USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; -void usb_irqhandler(void); - -void OTG_FS_IRQ_Handler(void) { +static void OTG_FS_IRQ_Handler(void) { NVIC_DisableIRQ(OTG_FS_IRQn); //__disable_irq(); usb_irqhandler(); diff --git a/panda/board/stm32f4/llusb_declarations.h b/panda/board/stm32f4/llusb_declarations.h new file mode 100644 index 000000000000000..5ca962b1a096220 --- /dev/null +++ b/panda/board/stm32f4/llusb_declarations.h @@ -0,0 +1,16 @@ +#pragma once + +extern USB_OTG_GlobalTypeDef *USBx; + +#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 5UL +#define USB_OTG_SPEED_FULL 3UL + + +void usb_irqhandler(void); +void usb_init(void); diff --git a/panda/board/stm32f4/peripherals.h b/panda/board/stm32f4/peripherals.h index 711f1b82a0e6d88..9c0b8ee65040c3e 100644 --- a/panda/board/stm32f4/peripherals.h +++ b/panda/board/stm32f4/peripherals.h @@ -1,4 +1,8 @@ +#ifdef BOOTSTUB void gpio_usb_init(void) { +#else +static void gpio_usb_init(void) { +#endif // A11,A12: USB set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); diff --git a/panda/board/stm32f4/stm32f4_config.h b/panda/board/stm32f4/stm32f4_config.h index 85baff25b5f9f7c..eae9222a9d97553 100644 --- a/panda/board/stm32f4/stm32f4_config.h +++ b/panda/board/stm32f4/stm32f4_config.h @@ -2,9 +2,6 @@ #include "stm32f4/inc/stm32f4xx_hal_gpio_ex.h" #define MCU_IDCODE 0x463U -// from the linker script -#define APP_START_ADDRESS 0x8004000U - #define CORE_FREQ 96U // in MHz #define APB1_FREQ (CORE_FREQ/2U) #define APB1_TIMER_FREQ (APB1_FREQ*2U) // APB1 is multiplied by 2 for the timer peripherals @@ -33,11 +30,11 @@ #define PROVISION_CHUNK_ADDRESS 0x1FFF79E0U #define DEVICE_SERIAL_NUMBER_ADDRESS 0x1FFF79C0U -#include "can_definitions.h" +#include "can.h" #include "comms_definitions.h" #ifndef BOOTSTUB - #include "main_declarations.h" + #include "main_definitions.h" #else #include "bootstub_declarations.h" #endif diff --git a/panda/board/stm32h7/board.h b/panda/board/stm32h7/board.h index f5a8e55aa8048d4..ea4812245eefedb 100644 --- a/panda/board/stm32h7/board.h +++ b/panda/board/stm32h7/board.h @@ -10,7 +10,9 @@ #include "drivers/fan.h" #include "stm32h7/llfan.h" #include "stm32h7/lldac.h" +#include "drivers/beeper.h" #include "drivers/fake_siren.h" +#include "stm32h7/sound.h" #include "drivers/clock_source.h" #include "boards/red.h" #include "boards/red_chiplet.h" @@ -18,36 +20,33 @@ #include "boards/cuatro.h" -uint8_t get_board_id(void) { - return detect_with_pull(GPIOF, 7, PULL_UP) | - (detect_with_pull(GPIOF, 8, PULL_UP) << 1U) | - (detect_with_pull(GPIOF, 9, PULL_UP) << 2U) | - (detect_with_pull(GPIOF, 10, PULL_UP) << 3U); -} - void detect_board_type(void) { - const uint8_t board_id = get_board_id(); + // On STM32H7 pandas, we use two different sets of pins. + const uint8_t id1 = detect_with_pull(GPIOF, 7, PULL_UP) | + (detect_with_pull(GPIOF, 8, PULL_UP) << 1U) | + (detect_with_pull(GPIOF, 9, PULL_UP) << 2U) | + (detect_with_pull(GPIOF, 10, PULL_UP) << 3U); - if (board_id == 0U) { + const uint8_t id2 = detect_with_pull(GPIOD, 4, PULL_UP) | + (detect_with_pull(GPIOD, 5, PULL_UP) << 1U) | + (detect_with_pull(GPIOD, 6, PULL_UP) << 2U) | + (detect_with_pull(GPIOD, 7, PULL_UP) << 3U); + + if (id2 == 3U) { + hw_type = HW_TYPE_CUATRO; + current_board = &board_cuatro; + } else if (id1 == 0U) { hw_type = HW_TYPE_RED_PANDA; current_board = &board_red; - } else if (board_id == 1U) { + } else if (id1 == 1U) { // deprecated //hw_type = HW_TYPE_RED_PANDA_V2; - } else if (board_id == 2U) { + hw_type = HW_TYPE_UNKNOWN; + } else if (id1 == 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 2e3ab701d81465e..4a29d459b985cce 100644 --- a/panda/board/stm32h7/clock.h +++ b/panda/board/stm32h7/clock.h @@ -17,13 +17,55 @@ APB4 per: 60MHz PCLK1: 60MHz (for USART2,3,4,5,7,8) */ +typedef enum { + PACKAGE_UNKNOWN = 0, + PACKAGE_WITH_SMPS = 1, + PACKAGE_WITHOUT_SMPS = 2, +} PackageSMPSType; + +// TODO: find a better way to distinguish between H725 (using SMPS) and H723 (lacking SMPS) +// The package will do for now, since we have only used TFBGA100 for H723 +static PackageSMPSType get_package_smps_type(void) { + PackageSMPSType ret; + RCC->APB4ENR |= RCC_APB4ENR_SYSCFGEN; // make sure SYSCFG clock is enabled. does seem to read fine without too though + + switch(SYSCFG->PKGR & 0xFU) { + case 0b0001U: // TFBGA100 Legacy + case 0b0011U: // TFBGA100 + ret = PACKAGE_WITHOUT_SMPS; + break; + case 0b0101U: // LQFP144 Legacy + case 0b0111U: // LQFP144 Industrial + case 0b1000U: // UFBGA169 + ret = PACKAGE_WITH_SMPS; + break; + default: + ret = PACKAGE_UNKNOWN; + } + return ret; +} + void clock_init(void) { - // 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 -#else - register_set(&(PWR->CR3), PWR_CR3_LDOEN, 0xFU); -#endif + /* + WARNING: PWR->CR3's lower byte can only be written once + * subsequent writes will silently fail + * only cleared with a full power-on-reset, not soft reset or reset pin + * some H7 have a bootrom with a DFU routine that writes (and locks) CR3 + * if the CR3 config doesn't match the HW, the core will deadlock and require immediately going into DFU from a cold boot + + In a normal bootup, the bootstub will be the first to write this. The app section calls clock_init again, but the CR3 write will silently fail. This is fine for most cases, but caution should be taken that the bootstub and app always write the same config. + */ + + // Set power mode to direct SMPS power supply (depends on the board layout) + PackageSMPSType package_smps = get_package_smps_type(); + if (package_smps == PACKAGE_WITHOUT_SMPS) { + register_set(&(PWR->CR3), PWR_CR3_LDOEN, 0xFU); // no SMPS, so powered by LDO + } else if (package_smps == PACKAGE_WITH_SMPS) { + register_set(&(PWR->CR3), PWR_CR3_SMPSEN, 0xFU); // powered only by SMPS + } else { + while(true); // unknown package, let's hang here + } + // 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) == 0U); diff --git a/panda/board/stm32h7/interrupt_handlers.h b/panda/board/stm32h7/interrupt_handlers.h index fb1298d77bdc7ff..8148021d6976975 100644 --- a/panda/board/stm32h7/interrupt_handlers.h +++ b/panda/board/stm32h7/interrupt_handlers.h @@ -20,6 +20,10 @@ void DMA1_Stream4_IRQHandler(void) {handle_interrupt(DMA1_Stream4_IRQn);} void DMA1_Stream5_IRQHandler(void) {handle_interrupt(DMA1_Stream5_IRQn);} void DMA1_Stream6_IRQHandler(void) {handle_interrupt(DMA1_Stream6_IRQn);} void ADC_IRQHandler(void) {handle_interrupt(ADC_IRQn);} +void FDCAN1_IT0_IRQHandler(void) {handle_interrupt(FDCAN1_IT0_IRQn);} +void FDCAN2_IT0_IRQHandler(void) {handle_interrupt(FDCAN2_IT0_IRQn);} +void FDCAN1_IT1_IRQHandler(void) {handle_interrupt(FDCAN1_IT1_IRQn);} +void FDCAN2_IT1_IRQHandler(void) {handle_interrupt(FDCAN2_IT1_IRQn);} void EXTI9_5_IRQHandler(void) {handle_interrupt(EXTI9_5_IRQn);} void TIM1_BRK_IRQHandler(void) {handle_interrupt(TIM1_BRK_IRQn);} void TIM1_UP_TIM10_IRQHandler(void) {handle_interrupt(TIM1_UP_TIM10_IRQn);} @@ -44,9 +48,10 @@ void TIM8_UP_TIM13_IRQHandler(void) {handle_interrupt(TIM8_UP_TIM13_IRQn);} void TIM8_TRG_COM_TIM14_IRQHandler(void) {handle_interrupt(TIM8_TRG_COM_TIM14_IRQn);} void TIM8_CC_IRQHandler(void) {handle_interrupt(TIM8_CC_IRQn);} void DMA1_Stream7_IRQHandler(void) {handle_interrupt(DMA1_Stream7_IRQn);} +void FMC_IRQHandler(void) {handle_interrupt(FMC_IRQn);} +void SDMMC1_IRQHandler(void) {handle_interrupt(SDMMC1_IRQn);} void TIM5_IRQHandler(void) {handle_interrupt(TIM5_IRQn);} void SPI3_IRQHandler(void) {handle_interrupt(SPI3_IRQn);} -void SPI4_IRQHandler(void) {handle_interrupt(SPI4_IRQn);} void UART4_IRQHandler(void) {handle_interrupt(UART4_IRQn);} void UART5_IRQHandler(void) {handle_interrupt(UART5_IRQn);} void TIM6_DAC_IRQHandler(void) {handle_interrupt(TIM6_DAC_IRQn);} @@ -56,21 +61,83 @@ void DMA2_Stream1_IRQHandler(void) {handle_interrupt(DMA2_Stream1_IRQn);} void DMA2_Stream2_IRQHandler(void) {handle_interrupt(DMA2_Stream2_IRQn);} void DMA2_Stream3_IRQHandler(void) {handle_interrupt(DMA2_Stream3_IRQn);} void DMA2_Stream4_IRQHandler(void) {handle_interrupt(DMA2_Stream4_IRQn);} +void ETH_IRQHandler(void) {handle_interrupt(ETH_IRQn);} +void ETH_WKUP_IRQHandler(void) {handle_interrupt(ETH_WKUP_IRQn);} +void FDCAN_CAL_IRQHandler(void) {handle_interrupt(FDCAN_CAL_IRQn);} void DMA2_Stream5_IRQHandler(void) {handle_interrupt(DMA2_Stream5_IRQn);} void DMA2_Stream6_IRQHandler(void) {handle_interrupt(DMA2_Stream6_IRQn);} 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);} -void FDCAN1_IT0_IRQHandler(void) {handle_interrupt(FDCAN1_IT0_IRQn);} -void FDCAN1_IT1_IRQHandler(void) {handle_interrupt(FDCAN1_IT1_IRQn);} -void FDCAN2_IT0_IRQHandler(void) {handle_interrupt(FDCAN2_IT0_IRQn);} -void FDCAN2_IT1_IRQHandler(void) {handle_interrupt(FDCAN2_IT1_IRQn);} -void FDCAN3_IT0_IRQHandler(void) {handle_interrupt(FDCAN3_IT0_IRQn);} -void FDCAN3_IT1_IRQHandler(void) {handle_interrupt(FDCAN3_IT1_IRQn);} -void FDCAN_CAL_IRQHandler(void) {handle_interrupt(FDCAN_CAL_IRQn);} void OTG_HS_EP1_OUT_IRQHandler(void) {handle_interrupt(OTG_HS_EP1_OUT_IRQn);} void OTG_HS_EP1_IN_IRQHandler(void) {handle_interrupt(OTG_HS_EP1_IN_IRQn);} void OTG_HS_WKUP_IRQHandler(void) {handle_interrupt(OTG_HS_WKUP_IRQn);} void OTG_HS_IRQHandler(void) {handle_interrupt(OTG_HS_IRQn);} +void DCMI_PSSI_IRQHandler(void) {handle_interrupt(DCMI_PSSI_IRQn);} +void CRYP_IRQHandler(void) {handle_interrupt(CRYP_IRQn);} +void HASH_RNG_IRQHandler(void) {handle_interrupt(HASH_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 SPI6_IRQHandler(void) {handle_interrupt(SPI6_IRQn);} +void SAI1_IRQHandler(void) {handle_interrupt(SAI1_IRQn);} +void LTDC_IRQHandler(void) {handle_interrupt(LTDC_IRQn);} +void LTDC_ER_IRQHandler(void) {handle_interrupt(LTDC_ER_IRQn);} +void DMA2D_IRQHandler(void) {handle_interrupt(DMA2D_IRQn);} +void OCTOSPI1_IRQHandler(void) {handle_interrupt(OCTOSPI1_IRQn);} +void LPTIM1_IRQHandler(void) {handle_interrupt(LPTIM1_IRQn);} +void CEC_IRQHandler(void) {handle_interrupt(CEC_IRQn);} +void I2C4_EV_IRQHandler(void) {handle_interrupt(I2C4_EV_IRQn);} +void I2C4_ER_IRQHandler(void) {handle_interrupt(I2C4_ER_IRQn);} +void SPDIF_RX_IRQHandler(void) {handle_interrupt(SPDIF_RX_IRQn);} +void DMAMUX1_OVR_IRQHandler(void) {handle_interrupt(DMAMUX1_OVR_IRQn);} +void DFSDM1_FLT0_IRQHandler(void) {handle_interrupt(DFSDM1_FLT0_IRQn);} +void DFSDM1_FLT1_IRQHandler(void) {handle_interrupt(DFSDM1_FLT1_IRQn);} +void DFSDM1_FLT2_IRQHandler(void) {handle_interrupt(DFSDM1_FLT2_IRQn);} +void DFSDM1_FLT3_IRQHandler(void) {handle_interrupt(DFSDM1_FLT3_IRQn);} +void SWPMI1_IRQHandler(void) {handle_interrupt(SWPMI1_IRQn);} +void TIM15_IRQHandler(void) {handle_interrupt(TIM15_IRQn);} +void TIM16_IRQHandler(void) {handle_interrupt(TIM16_IRQn);} +void TIM17_IRQHandler(void) {handle_interrupt(TIM17_IRQn);} +void MDIOS_WKUP_IRQHandler(void) {handle_interrupt(MDIOS_WKUP_IRQn);} +void MDIOS_IRQHandler(void) {handle_interrupt(MDIOS_IRQn);} +void MDMA_IRQHandler(void) {handle_interrupt(MDMA_IRQn);} +void SDMMC2_IRQHandler(void) {handle_interrupt(SDMMC2_IRQn);} +void HSEM1_IRQHandler(void) {handle_interrupt(HSEM1_IRQn);} +void ADC3_IRQHandler(void) {handle_interrupt(ADC3_IRQn);} +void DMAMUX2_OVR_IRQHandler(void) {handle_interrupt(DMAMUX2_OVR_IRQn);} +void BDMA_Channel0_IRQHandler(void) {handle_interrupt(BDMA_Channel0_IRQn);} +void BDMA_Channel1_IRQHandler(void) {handle_interrupt(BDMA_Channel1_IRQn);} +void BDMA_Channel2_IRQHandler(void) {handle_interrupt(BDMA_Channel2_IRQn);} +void BDMA_Channel3_IRQHandler(void) {handle_interrupt(BDMA_Channel3_IRQn);} +void BDMA_Channel4_IRQHandler(void) {handle_interrupt(BDMA_Channel4_IRQn);} +void BDMA_Channel5_IRQHandler(void) {handle_interrupt(BDMA_Channel5_IRQn);} +void BDMA_Channel6_IRQHandler(void) {handle_interrupt(BDMA_Channel6_IRQn);} +void BDMA_Channel7_IRQHandler(void) {handle_interrupt(BDMA_Channel7_IRQn);} +void COMP_IRQHandler(void) {handle_interrupt(COMP_IRQn);} +void LPTIM2_IRQHandler(void) {handle_interrupt(LPTIM2_IRQn);} +void LPTIM3_IRQHandler(void) {handle_interrupt(LPTIM3_IRQn);} +void LPTIM4_IRQHandler(void) {handle_interrupt(LPTIM4_IRQn);} +void LPTIM5_IRQHandler(void) {handle_interrupt(LPTIM5_IRQn);} +void LPUART1_IRQHandler(void) {handle_interrupt(LPUART1_IRQn);} +void CRS_IRQHandler(void) {handle_interrupt(CRS_IRQn);} +void ECC_IRQHandler(void) {handle_interrupt(ECC_IRQn);} +void SAI4_IRQHandler(void) {handle_interrupt(SAI4_IRQn);} +void DTS_IRQHandler(void) {handle_interrupt(DTS_IRQn);} +void WAKEUP_PIN_IRQHandler(void) {handle_interrupt(WAKEUP_PIN_IRQn);} +void OCTOSPI2_IRQHandler(void) {handle_interrupt(OCTOSPI2_IRQn);} +void OTFDEC1_IRQHandler(void) {handle_interrupt(OTFDEC1_IRQn);} +void OTFDEC2_IRQHandler(void) {handle_interrupt(OTFDEC2_IRQn);} +void FMAC_IRQHandler(void) {handle_interrupt(FMAC_IRQn);} +void CORDIC_IRQHandler(void) {handle_interrupt(CORDIC_IRQn);} +void UART9_IRQHandler(void) {handle_interrupt(UART9_IRQn);} +void USART10_IRQHandler(void) {handle_interrupt(USART10_IRQn);} +void I2C5_EV_IRQHandler(void) {handle_interrupt(I2C5_EV_IRQn);} +void I2C5_ER_IRQHandler(void) {handle_interrupt(I2C5_ER_IRQn);} +void FDCAN3_IT0_IRQHandler(void) {handle_interrupt(FDCAN3_IT0_IRQn);} +void FDCAN3_IT1_IRQHandler(void) {handle_interrupt(FDCAN3_IT1_IRQn);} +void TIM23_IRQHandler(void) {handle_interrupt(TIM23_IRQn);} +void TIM24_IRQHandler(void) {handle_interrupt(TIM24_IRQn);} diff --git a/panda/board/stm32h7/lladc.h b/panda/board/stm32h7/lladc.h index 7d818f27af1b7d6..248fa310afb7cc9 100644 --- a/panda/board/stm32h7/lladc.h +++ b/panda/board/stm32h7/lladc.h @@ -14,7 +14,7 @@ void adc_init(void) { while(!(ADC1->ISR & ADC_ISR_ADRDY)); } -uint16_t adc_get_raw(uint8_t channel) { +static uint16_t adc_get_raw(uint8_t channel) { uint16_t res = 0U; ADC1->SQR1 &= ~(ADC_SQR1_L); ADC1->SQR1 = (uint32_t)channel << 6U; diff --git a/panda/board/stm32h7/llfan.h b/panda/board/stm32h7/llfan.h index dce622503ab92c0..06309d0633f002d 100644 --- a/panda/board/stm32h7/llfan.h +++ b/panda/board/stm32h7/llfan.h @@ -1,5 +1,5 @@ // TACH interrupt handler -void EXTI2_IRQ_Handler(void) { +static void EXTI2_IRQ_Handler(void) { volatile unsigned int pr = EXTI->PR1 & (1U << 2); if ((pr & (1U << 2)) != 0U) { fan_state.tach_counter++; @@ -8,8 +8,8 @@ void EXTI2_IRQ_Handler(void) { } void llfan_init(void) { - // 5000RPM * 4 tach edges / 60 seconds - REGISTER_INTERRUPT(EXTI2_IRQn, EXTI2_IRQ_Handler, 700U, FAULT_INTERRUPT_RATE_TACH) + // 12000RPM * 4 tach edges / 60 seconds + REGISTER_INTERRUPT(EXTI2_IRQn, EXTI2_IRQ_Handler, 1000U, FAULT_INTERRUPT_RATE_TACH) // Init PWM speed control pwm_init(TIM3, 3); diff --git a/panda/board/stm32h7/llfdcan.h b/panda/board/stm32h7/llfdcan.h index db42024c43b3984..64a40bd072ed3f8 100644 --- a/panda/board/stm32h7/llfdcan.h +++ b/panda/board/stm32h7/llfdcan.h @@ -1,52 +1,10 @@ -// SAE J2284-4 document specifies a bus-line network running at 2 Mbit/s -// SAE J2284-5 document specifies a point-to-point communication running at 5 Mbit/s - -#define CAN_PCLK 80000U // KHz, sourced from PLL1Q -#define BITRATE_PRESCALER 2U // Valid from 250Kbps to 5Mbps with 80Mhz clock -#define CAN_SP_NOMINAL 80U // 80% for both SAE J2284-4 and SAE J2284-5 -#define CAN_SP_DATA_2M 80U // 80% for SAE J2284-4 -#define CAN_SP_DATA_5M 75U // 75% for SAE J2284-5 -#define CAN_QUANTA(speed, prescaler) (CAN_PCLK / ((speed) / 10U * (prescaler))) -#define CAN_SEG1(tq, sp) (((tq) * (sp) / 100U)- 1U) -#define CAN_SEG2(tq, sp) ((tq) * (100U - (sp)) / 100U) - -// FDCAN core settings -#define FDCAN_MESSAGE_RAM_SIZE 0x2800UL -#define FDCAN_START_ADDRESS 0x4000AC00UL -#define FDCAN_OFFSET 3384UL // bytes for each FDCAN module, equally -#define FDCAN_OFFSET_W 846UL // words for each FDCAN module, equally -#define FDCAN_END_ADDRESS 0x4000D3FCUL // Message RAM has a width of 4 bytes - -// FDCAN_RX_FIFO_0_EL_CNT + FDCAN_TX_FIFO_EL_CNT can't exceed 47 elements (47 * 72 bytes = 3,384 bytes) per FDCAN module - -// RX FIFO 0 -#define FDCAN_RX_FIFO_0_EL_CNT 46UL -#define FDCAN_RX_FIFO_0_HEAD_SIZE 8UL // bytes -#define FDCAN_RX_FIFO_0_DATA_SIZE 64UL // bytes -#define FDCAN_RX_FIFO_0_EL_SIZE (FDCAN_RX_FIFO_0_HEAD_SIZE + FDCAN_RX_FIFO_0_DATA_SIZE) -#define FDCAN_RX_FIFO_0_EL_W_SIZE (FDCAN_RX_FIFO_0_EL_SIZE / 4UL) -#define FDCAN_RX_FIFO_0_OFFSET 0UL - -// TX FIFO -#define FDCAN_TX_FIFO_EL_CNT 1UL -#define FDCAN_TX_FIFO_HEAD_SIZE 8UL // bytes -#define FDCAN_TX_FIFO_DATA_SIZE 64UL // bytes -#define FDCAN_TX_FIFO_EL_SIZE (FDCAN_TX_FIFO_HEAD_SIZE + FDCAN_TX_FIFO_DATA_SIZE) -#define FDCAN_TX_FIFO_EL_W_SIZE (FDCAN_TX_FIFO_EL_SIZE / 4UL) -#define FDCAN_TX_FIFO_OFFSET (FDCAN_RX_FIFO_0_OFFSET + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_W_SIZE)) - -#define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==FDCAN1) ? "FDCAN1" : (((CAN_DEV) == FDCAN2) ? "FDCAN2" : "FDCAN3")) -#define CAN_NUM_FROM_CANIF(CAN_DEV) (((CAN_DEV)==FDCAN1) ? 0UL : (((CAN_DEV) == FDCAN2) ? 1UL : 2UL)) - - -void print(const char *a); +#include "llfdcan_declarations.h" // kbps multiplied by 10 -const uint32_t speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U}; -const uint32_t data_speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U, 20000U, 50000U}; +const uint32_t speeds[SPEEDS_ARRAY_SIZE] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U}; +const uint32_t data_speeds[DATA_SPEEDS_ARRAY_SIZE] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U, 20000U, 50000U}; - -bool fdcan_request_init(FDCAN_GlobalTypeDef *FDCANx) { +static bool fdcan_request_init(FDCAN_GlobalTypeDef *FDCANx) { bool ret = true; // Exit from sleep mode FDCANx->CCCR &= ~(FDCAN_CCCR_CSR); @@ -68,7 +26,7 @@ bool fdcan_request_init(FDCAN_GlobalTypeDef *FDCANx) { return ret; } -bool fdcan_exit_init(FDCAN_GlobalTypeDef *FDCANx) { +static bool fdcan_exit_init(FDCAN_GlobalTypeDef *FDCANx) { bool ret = true; FDCANx->CCCR &= ~(FDCAN_CCCR_INIT); diff --git a/panda/board/stm32h7/llfdcan_declarations.h b/panda/board/stm32h7/llfdcan_declarations.h new file mode 100644 index 000000000000000..793849011ebaab8 --- /dev/null +++ b/panda/board/stm32h7/llfdcan_declarations.h @@ -0,0 +1,53 @@ +#pragma once + +// SAE J2284-4 document specifies a bus-line network running at 2 Mbit/s +// SAE J2284-5 document specifies a point-to-point communication running at 5 Mbit/s + +#define CAN_PCLK 80000U // KHz, sourced from PLL1Q +#define BITRATE_PRESCALER 2U // Valid from 250Kbps to 5Mbps with 80Mhz clock +#define CAN_SP_NOMINAL 80U // 80% for both SAE J2284-4 and SAE J2284-5 +#define CAN_SP_DATA_2M 80U // 80% for SAE J2284-4 +#define CAN_SP_DATA_5M 75U // 75% for SAE J2284-5 +#define CAN_QUANTA(speed, prescaler) (CAN_PCLK / ((speed) / 10U * (prescaler))) +#define CAN_SEG1(tq, sp) (((tq) * (sp) / 100U)- 1U) +#define CAN_SEG2(tq, sp) ((tq) * (100U - (sp)) / 100U) + +// FDCAN core settings +#define FDCAN_START_ADDRESS 0x4000AC00UL +#define FDCAN_OFFSET 3384UL // bytes for each FDCAN module, equally +#define FDCAN_OFFSET_W 846UL // words for each FDCAN module, equally + +// FDCAN_RX_FIFO_0_EL_CNT + FDCAN_TX_FIFO_EL_CNT can't exceed 47 elements (47 * 72 bytes = 3,384 bytes) per FDCAN module + +// RX FIFO 0 +#define FDCAN_RX_FIFO_0_EL_CNT 46UL +#define FDCAN_RX_FIFO_0_HEAD_SIZE 8UL // bytes +#define FDCAN_RX_FIFO_0_DATA_SIZE 64UL // bytes +#define FDCAN_RX_FIFO_0_EL_SIZE (FDCAN_RX_FIFO_0_HEAD_SIZE + FDCAN_RX_FIFO_0_DATA_SIZE) +#define FDCAN_RX_FIFO_0_EL_W_SIZE (FDCAN_RX_FIFO_0_EL_SIZE / 4UL) +#define FDCAN_RX_FIFO_0_OFFSET 0UL + +// TX FIFO +#define FDCAN_TX_FIFO_EL_CNT 1UL +#define FDCAN_TX_FIFO_HEAD_SIZE 8UL // bytes +#define FDCAN_TX_FIFO_DATA_SIZE 64UL // bytes +#define FDCAN_TX_FIFO_EL_SIZE (FDCAN_TX_FIFO_HEAD_SIZE + FDCAN_TX_FIFO_DATA_SIZE) +#define FDCAN_TX_FIFO_OFFSET (FDCAN_RX_FIFO_0_OFFSET + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_W_SIZE)) + +#define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==FDCAN1) ? "FDCAN1" : (((CAN_DEV) == FDCAN2) ? "FDCAN2" : "FDCAN3")) +#define CAN_NUM_FROM_CANIF(CAN_DEV) (((CAN_DEV)==FDCAN1) ? 0UL : (((CAN_DEV) == FDCAN2) ? 1UL : 2UL)) + + +void print(const char *a); + +// kbps multiplied by 10 +#define SPEEDS_ARRAY_SIZE 8 +extern const uint32_t speeds[SPEEDS_ARRAY_SIZE]; +#define DATA_SPEEDS_ARRAY_SIZE 10 +extern const uint32_t data_speeds[DATA_SPEEDS_ARRAY_SIZE]; + +bool llcan_set_speed(FDCAN_GlobalTypeDef *FDCANx, uint32_t speed, uint32_t data_speed, bool non_iso, bool loopback, bool silent); +void llcan_irq_disable(const FDCAN_GlobalTypeDef *FDCANx); +void llcan_irq_enable(const FDCAN_GlobalTypeDef *FDCANx); +bool llcan_init(FDCAN_GlobalTypeDef *FDCANx); +void llcan_clear_send(FDCAN_GlobalTypeDef *FDCANx); diff --git a/panda/board/stm32h7/lli2c.h b/panda/board/stm32h7/lli2c.h index b423c94bddb3c79..5d79beb653ee437 100644 --- a/panda/board/stm32h7/lli2c.h +++ b/panda/board/stm32h7/lli2c.h @@ -1,20 +1,27 @@ - // TODO: this driver relies heavily on polling, // if we want it to be more async, we should use interrupts +#define I2C_RETRY_COUNT 10U #define I2C_TIMEOUT_US 100000U -// cppcheck-suppress misra-c2012-2.7; not sure why it triggers here? bool i2c_status_wait(const volatile uint32_t *reg, uint32_t mask, uint32_t val) { uint32_t start_time = microsecond_timer_get(); while(((*reg & mask) != val) && (get_ts_elapsed(microsecond_timer_get(), start_time) < I2C_TIMEOUT_US)); return ((*reg & mask) == val); } +void i2c_reset(I2C_TypeDef *I2C) { + // peripheral reset + register_clear_bits(&I2C->CR1, I2C_CR1_PE); + while ((I2C->CR1 & I2C_CR1_PE) != 0U); + register_set_bits(&I2C->CR1, I2C_CR1_PE); +} + bool i2c_write_reg(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t value) { - // Setup transfer and send START + addr bool ret = false; - for(uint32_t i=0U; i<10U; i++) { + + // Setup transfer and send START + addr + for (uint32_t i = 0U; i < I2C_RETRY_COUNT; i++) { register_clear_bits(&I2C->CR2, I2C_CR2_ADD10); I2C->CR2 = ((uint32_t)addr << 1U) & I2C_CR2_SADD_Msk; register_clear_bits(&I2C->CR2, I2C_CR2_RD_WRN); @@ -57,9 +64,10 @@ bool i2c_write_reg(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t value) { } bool i2c_read_reg(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t *value) { - // Setup transfer and send START + addr bool ret = false; - for(uint32_t i=0U; i<10U; i++) { + + // Setup transfer and send START + addr + for (uint32_t i = 0U; i < I2C_RETRY_COUNT; i++) { register_clear_bits(&I2C->CR2, I2C_CR2_ADD10); I2C->CR2 = ((uint32_t)addr << 1U) & I2C_CR2_SADD_Msk; register_clear_bits(&I2C->CR2, I2C_CR2_RD_WRN); @@ -116,6 +124,11 @@ bool i2c_read_reg(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t *value) { I2C->CR2 |= I2C_CR2_STOP; end: + + if (!ret) { + i2c_reset(I2C); + } + return ret; } @@ -131,7 +144,7 @@ bool i2c_set_reg_bits(I2C_TypeDef *I2C, uint8_t address, uint8_t regis, uint8_t bool i2c_clear_reg_bits(I2C_TypeDef *I2C, uint8_t address, uint8_t regis, uint8_t bits) { uint8_t value; bool ret = i2c_read_reg(I2C, address, regis, &value); - if(ret) { + if (ret) { ret = i2c_write_reg(I2C, address, regis, value & (uint8_t) (~bits)); } return ret; @@ -149,5 +162,6 @@ bool i2c_set_reg_mask(I2C_TypeDef *I2C, uint8_t address, uint8_t regis, uint8_t void i2c_init(I2C_TypeDef *I2C) { // 100kHz clock speed I2C->TIMINGR = 0x107075B0; - I2C->CR1 = I2C_CR1_PE; -} \ No newline at end of file + + i2c_reset(I2C); +} diff --git a/panda/board/stm32h7/llspi.h b/panda/board/stm32h7/llspi.h index 903f6a5ecc0b250..a5dca37aa9584a8 100644 --- a/panda/board/stm32h7/llspi.h +++ b/panda/board/stm32h7/llspi.h @@ -1,3 +1,4 @@ +#if defined(ENABLE_SPI) || defined(BOOTSTUB) // master -> panda DMA start void llspi_mosi_dma(uint8_t *addr, int len) { // disable DMA + SPI @@ -48,8 +49,9 @@ void llspi_miso_dma(uint8_t *addr, int len) { register_set_bits(&(SPI4->CR1), SPI_CR1_SPE); } +static bool spi_tx_dma_done = false; // master -> panda DMA finished -void DMA2_Stream2_IRQ_Handler(void) { +static void DMA2_Stream2_IRQ_Handler(void) { // Clear interrupt flag DMA2->LIFCR = DMA_LIFCR_CTCIF2; @@ -57,7 +59,7 @@ void DMA2_Stream2_IRQ_Handler(void) { } // panda -> master DMA finished -void DMA2_Stream3_IRQ_Handler(void) { +static void DMA2_Stream3_IRQ_Handler(void) { ENTER_CRITICAL(); DMA2->LIFCR = DMA_LIFCR_CTCIF3; @@ -67,7 +69,7 @@ void DMA2_Stream3_IRQ_Handler(void) { } // panda TX finished -void SPI4_IRQ_Handler(void) { +static void SPI4_IRQ_Handler(void) { // clear flag SPI4->IFCR |= (0x1FFU << 3U); @@ -104,3 +106,4 @@ void llspi_init(void) { NVIC_EnableIRQ(DMA2_Stream3_IRQn); NVIC_EnableIRQ(SPI4_IRQn); } +#endif diff --git a/panda/board/stm32h7/lluart.h b/panda/board/stm32h7/lluart.h index 6ca6dcec3dd6087..742549bb1deec60 100644 --- a/panda/board/stm32h7/lluart.h +++ b/panda/board/stm32h7/lluart.h @@ -1,4 +1,4 @@ -void uart_rx_ring(uart_ring *q){ +static void uart_rx_ring(uart_ring *q){ // Do not read out directly if DMA enabled ENTER_CRITICAL(); @@ -52,7 +52,7 @@ void uart_set_baud(USART_TypeDef *u, unsigned int baud) { // This read after reading ISR clears all error interrupts. We don't want compiler warnings, nor optimizations #define UART_READ_RDR(uart) volatile uint8_t t = (uart)->RDR; UNUSED(t); -void uart_interrupt_handler(uart_ring *q) { +static void uart_interrupt_handler(uart_ring *q) { ENTER_CRITICAL(); // Read UART status. This is also the first step necessary in clearing most interrupts @@ -88,7 +88,7 @@ void uart_interrupt_handler(uart_ring *q) { EXIT_CRITICAL(); } -void UART7_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_som_debug); } +static void UART7_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_som_debug); } void uart_init(uart_ring *q, int baud) { if (q->uart == UART7) { diff --git a/panda/board/stm32h7/llusb.h b/panda/board/stm32h7/llusb.h index 2975f62be61dda5..f1bcf16ad5e9968 100644 --- a/panda/board/stm32h7/llusb.h +++ b/panda/board/stm32h7/llusb.h @@ -1,20 +1,8 @@ -USB_OTG_GlobalTypeDef *USBx = USB_OTG_HS; - -#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_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 6UL -#define USB_OTG_SPEED_FULL 3U -#define DCFG_FRAME_INTERVAL_80 0U +#include "llusb_declarations.h" +USB_OTG_GlobalTypeDef *USBx = USB_OTG_HS; -void usb_irqhandler(void); - -void OTG_HS_IRQ_Handler(void) { +static void OTG_HS_IRQ_Handler(void) { NVIC_DisableIRQ(OTG_HS_IRQn); usb_irqhandler(); NVIC_EnableIRQ(OTG_HS_IRQn); diff --git a/panda/board/stm32h7/llusb_declarations.h b/panda/board/stm32h7/llusb_declarations.h new file mode 100644 index 000000000000000..a11d3f52c6bd4be --- /dev/null +++ b/panda/board/stm32h7/llusb_declarations.h @@ -0,0 +1,16 @@ +#pragma once + +extern USB_OTG_GlobalTypeDef *USBx; + +#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 6UL +#define USB_OTG_SPEED_FULL 3U +#define DCFG_FRAME_INTERVAL_80 0U + +void usb_irqhandler(void); +void usb_init(void); diff --git a/panda/board/stm32h7/peripherals.h b/panda/board/stm32h7/peripherals.h index b60f19016d728a0..f0bd727fdf4025a 100644 --- a/panda/board/stm32h7/peripherals.h +++ b/panda/board/stm32h7/peripherals.h @@ -1,4 +1,8 @@ +#ifdef BOOTSTUB void gpio_usb_init(void) { +#else +static void gpio_usb_init(void) { +#endif // A11,A12: USB set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG1_FS); set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG1_FS); @@ -97,13 +101,14 @@ void peripherals_init(void) { RCC->AHB4ENR |= RCC_AHB4ENR_GPIOFEN; RCC->AHB4ENR |= RCC_AHB4ENR_GPIOGEN; - // Enable CPU access to SRAM1 and SRAM2 (in domain D2) for DMA + // Enable CPU access to SRAMs for DMA RCC->AHB2ENR |= RCC_AHB2ENR_SRAM1EN | RCC_AHB2ENR_SRAM2EN; // Supplemental RCC->AHB1ENR |= RCC_AHB1ENR_DMA1EN; // DAC DMA RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; // SPI DMA RCC->APB4ENR |= RCC_APB4ENR_SYSCFGEN; + RCC->AHB4ENR |= RCC_AHB4ENR_BDMAEN; // Audio DMA // Connectivity RCC->APB2ENR |= RCC_APB2ENR_SPI4EN; // SPI @@ -118,10 +123,14 @@ void peripherals_init(void) { RCC->AHB1ENR |= RCC_AHB1ENR_ADC12EN; // Enable ADC12 clocks RCC->APB1LENR |= RCC_APB1LENR_DAC12EN; // DAC + // Audio + RCC->APB4ENR |= RCC_APB4ENR_SAI4EN; // SAI4 + // Timers RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // clock source timer RCC->APB1LENR |= RCC_APB1LENR_TIM2EN; // main counter RCC->APB1LENR |= RCC_APB1LENR_TIM3EN; // fan pwm + RCC->APB1LENR |= RCC_APB1LENR_TIM4EN; // beeper source RCC->APB1LENR |= RCC_APB1LENR_TIM6EN; // interrupt timer RCC->APB1LENR |= RCC_APB1LENR_TIM7EN; // DMA trigger timer RCC->APB2ENR |= RCC_APB2ENR_TIM8EN; // tick timer diff --git a/panda/board/stm32h7/sound.h b/panda/board/stm32h7/sound.h new file mode 100644 index 000000000000000..9228b16134d24d7 --- /dev/null +++ b/panda/board/stm32h7/sound.h @@ -0,0 +1,95 @@ + +#define SOUND_RX_BUF_SIZE 2000U +#define SOUND_TX_BUF_SIZE (SOUND_RX_BUF_SIZE/2U) + +__attribute__((section(".sram4"))) static uint16_t sound_rx_buf[2][SOUND_RX_BUF_SIZE]; + +typedef enum { + OFF = 0, + IDLE = 1, + PLAYING = 2, +} SoundStatus; +static SoundStatus sound_status = OFF; + +// Playback processing +static void BDMA_Channel0_IRQ_Handler(void) { + __attribute__((section(".sram4"))) static uint16_t tx_buf[SOUND_TX_BUF_SIZE]; + + BDMA->IFCR |= BDMA_IFCR_CGIF0; // clear flag + + // process samples (shift to 12b and bias to be unsigned) + // since we are playing mono and receiving stereo, we take every other sample + uint8_t buf_idx = (((BDMA_Channel0->CCR & BDMA_CCR_CT) >> BDMA_CCR_CT_Pos) == 1U) ? 0U : 1U; + for (uint16_t i=0U; i < SOUND_RX_BUF_SIZE; i += 2U) { + tx_buf[i/2U] = ((sound_rx_buf[buf_idx][i] + (1UL << 14)) >> 3); + } + + if (sound_status == OFF) { + current_board->set_amp_enabled(true); + } + sound_status = PLAYING; + + DMA1->LIFCR |= 0xF40; + DMA1_Stream1->CR &= ~DMA_SxCR_EN; + register_set(&DMA1_Stream1->M0AR, (uint32_t) tx_buf, 0xFFFFFFFFU); + DMA1_Stream1->NDTR = SOUND_TX_BUF_SIZE; + DMA1_Stream1->CR |= DMA_SxCR_EN; +} + +void sound_tick(void) { + switch (sound_status) { + case IDLE: + current_board->set_amp_enabled(false); + sound_status = OFF; + break; + case PLAYING: + sound_status = IDLE; + break; + default: + break; + } +} + +void sound_init(void) { + REGISTER_INTERRUPT(BDMA_Channel0_IRQn, BDMA_Channel0_IRQ_Handler, 64U, FAULT_INTERRUPT_RATE_SOUND_DMA) + + // Init DAC + register_set(&DAC1->MCR, 0U, 0xFFFFFFFFU); + register_set(&DAC1->CR, DAC_CR_TEN1 | (6U << DAC_CR_TSEL1_Pos) | DAC_CR_DMAEN1, 0xFFFFFFFFU); + register_set_bits(&DAC1->CR, DAC_CR_EN1); + + // Setup DMAMUX (DAC_CH1_DMA as input) + register_set(&DMAMUX1_Channel1->CCR, 67U, DMAMUX_CxCR_DMAREQ_ID_Msk); + + // Setup DMA + register_set(&DMA1_Stream1->PAR, (uint32_t) &(DAC1->DHR12R1), 0xFFFFFFFFU); + register_set(&DMA1_Stream1->FCR, 0U, 0x00000083U); + DMA1_Stream1->CR = (0b11UL << DMA_SxCR_PL_Pos) | (0b01UL << DMA_SxCR_MSIZE_Pos) | (0b01UL << DMA_SxCR_PSIZE_Pos) | DMA_SxCR_MINC | (1U << DMA_SxCR_DIR_Pos); + + // Init trigger timer (48kHz) + register_set(&TIM7->PSC, 0U, 0xFFFFU); + register_set(&TIM7->ARR, 2494U, 0xFFFFU); + register_set(&TIM7->CR2, (0b10U << TIM_CR2_MMS_Pos), TIM_CR2_MMS_Msk); + register_set(&TIM7->CR1, TIM_CR1_ARPE | TIM_CR1_URS, 0x088EU); + TIM7->SR = 0U; + TIM7->CR1 |= TIM_CR1_CEN; + + // stereo audio in + register_set(&SAI4_Block_B->CR1, SAI_xCR1_DMAEN | (0b00UL << SAI_xCR1_SYNCEN_Pos) | (0b100U << SAI_xCR1_DS_Pos) | (0b11U << SAI_xCR1_MODE_Pos), 0x0FFB3FEFU); + register_set(&SAI4_Block_B->CR2, (0b001U << SAI_xCR2_FTH_Pos), 0xFFFBU); + register_set(&SAI4_Block_B->FRCR, (31U << SAI_xFRCR_FRL_Pos), 0x7FFFFU); + register_set(&SAI4_Block_B->SLOTR, (0b11UL << SAI_xSLOTR_SLOTEN_Pos) | (1UL << SAI_xSLOTR_NBSLOT_Pos) | (0b01UL << SAI_xSLOTR_SLOTSZ_Pos), 0xFFFF0FDFU); // NBSLOT definition is vague + + // init sound DMA (SAI4_B -> memory, double buffers) + register_set(&BDMA_Channel0->CPAR, (uint32_t) &(SAI4_Block_B->DR), 0xFFFFFFFFU); + register_set(&BDMA_Channel0->CM0AR, (uint32_t) sound_rx_buf[0], 0xFFFFFFFFU); + register_set(&BDMA_Channel0->CM1AR, (uint32_t) sound_rx_buf[1], 0xFFFFFFFFU); + BDMA_Channel0->CNDTR = SOUND_RX_BUF_SIZE; + register_set(&BDMA_Channel0->CCR, BDMA_CCR_DBM | (0b01UL << BDMA_CCR_MSIZE_Pos) | (0b01UL << BDMA_CCR_PSIZE_Pos) | BDMA_CCR_MINC | BDMA_CCR_CIRC | BDMA_CCR_TCIE, 0xFFFFU); + register_set(&DMAMUX2_Channel0->CCR, 16U, DMAMUX_CxCR_DMAREQ_ID_Msk); // SAI4_B_DMA + register_set_bits(&BDMA_Channel0->CCR, BDMA_CCR_EN); + + // enable all initted blocks + register_set_bits(&SAI4_Block_B->CR1, SAI_xCR1_SAIEN); + NVIC_EnableIRQ(BDMA_Channel0_IRQn); +} diff --git a/panda/board/stm32h7/stm32h7_config.h b/panda/board/stm32h7/stm32h7_config.h index 64f149848dfd6d7..bfc12e8c3a2f7d8 100644 --- a/panda/board/stm32h7/stm32h7_config.h +++ b/panda/board/stm32h7/stm32h7_config.h @@ -2,9 +2,6 @@ #include "stm32h7/inc/stm32h7xx_hal_gpio_ex.h" #define MCU_IDCODE 0x483U -// from the linker script -#define APP_START_ADDRESS 0x8020000U - #define CORE_FREQ 240U // in Mhz //APB1 - 120Mhz, APB2 - 120Mhz #define APB1_FREQ (CORE_FREQ/4U) @@ -46,11 +43,11 @@ separate IRQs for RX and TX. #define PROVISION_CHUNK_ADDRESS 0x080FFFE0U #define DEVICE_SERIAL_NUMBER_ADDRESS 0x080FFFC0U -#include "can_definitions.h" +#include "can.h" #include "comms_definitions.h" #ifndef BOOTSTUB - #include "main_declarations.h" + #include "main_definitions.h" #else #include "bootstub_declarations.h" #endif diff --git a/panda/pyproject.toml b/panda/pyproject.toml index 375885e54d16455..5b0697d67b51d50 100644 --- a/panda/pyproject.toml +++ b/panda/pyproject.toml @@ -12,4 +12,4 @@ flake8-implicit-str-concat.allow-multiline=false "pytest.main".msg = "pytest.main requires special handling that is easy to mess up!" [tool.pytest.ini_options] -addopts = "-n auto" +addopts = "-n auto --ignore-glob='*.sh'" diff --git a/panda/python/__init__.py b/panda/python/__init__.py index a18fdc5f918abb4..14d324ab931d5c3 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -6,7 +6,6 @@ import struct import hashlib import binascii -import logging from functools import wraps, partial from itertools import accumulate @@ -16,17 +15,14 @@ from .isotp import isotp_send, isotp_recv from .spi import PandaSpiHandle, PandaSpiException, PandaProtocolMismatch from .usb import PandaUsbHandle +from .utils import logger __version__ = '0.0.10' -# setup logging -LOGLEVEL = os.environ.get('LOGLEVEL', 'INFO').upper() -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 +PANDA_BUS_CNT = 3 def calculate_checksum(data): @@ -37,9 +33,9 @@ def calculate_checksum(data): def pack_can_buffer(arr): snds = [b''] - for address, _, dat, bus in arr: + for address, dat, bus in arr: assert len(dat) in LEN_TO_DLC - #logging.debug(" W 0x%x: 0x%s", address, dat.hex()) + #logger.debug(" W 0x%x: 0x%s", address, dat.hex()) extended = 1 if address >= 0x800 else 0 data_len_code = LEN_TO_DLC[len(dat)] @@ -85,7 +81,7 @@ def unpack_can_buffer(dat): data = dat[CANPACKET_HEAD_SIZE:(CANPACKET_HEAD_SIZE+data_len)] dat = dat[(CANPACKET_HEAD_SIZE+data_len):] - ret.append((address, 0, data, bus)) + ret.append((address, data, bus)) return (ret, dat) @@ -191,6 +187,7 @@ class Panda: FLAG_TOYOTA_ALT_BRAKE = (1 << 8) FLAG_TOYOTA_STOCK_LONGITUDINAL = (2 << 8) FLAG_TOYOTA_LTA = (4 << 8) + FLAG_TOYOTA_SECOC = (8 << 8) FLAG_HONDA_ALT_BRAKE = 1 FLAG_HONDA_BOSCH_LONG = 2 @@ -228,8 +225,7 @@ class Panda: FLAG_FORD_LONG_CONTROL = 1 FLAG_FORD_CANFD = 2 - def __init__(self, serial: str | None = None, claim: bool = True, disable_checks: bool = True, can_speed_kbps: int = 500): - self._connect_serial = serial + def __init__(self, serial: str | None = None, claim: bool = True, disable_checks: bool = True, can_speed_kbps: int = 500, cli: bool = True): self._disable_checks = disable_checks self._handle: BaseHandle @@ -237,9 +233,37 @@ def __init__(self, serial: str | None = None, claim: bool = True, disable_checks self.can_rx_overflow_buffer = b'' self._can_speed_kbps = can_speed_kbps + if cli and serial is None: + self._connect_serial = self._cli_select_panda() + else: + self._connect_serial = serial + # connect and set mcu type self.connect(claim) + def _cli_select_panda(self): + dfu_pandas = PandaDFU.list() + if len(dfu_pandas) > 0: + print("INFO: some attached pandas are in DFU mode.") + + pandas = self.list() + if len(pandas) == 0: + print("INFO: panda not available") + return None + if len(pandas) == 1: + print(f"INFO: connecting to panda {pandas[0]}") + return pandas[0] + while True: + print("Multiple pandas available:") + pandas.sort() + for idx, serial in enumerate(pandas): + print(f"{[idx]}: {serial}") + try: + choice = int(input("Choose serial [0]:") or "0") + return pandas[choice] + except (ValueError, IndexError): + print("Enter a valid index.") + def __enter__(self): return self @@ -259,7 +283,7 @@ def connect(self, claim=True, wait=False): self._handle = None while self._handle is None: # try USB first, then SPI - self._context, self._handle, serial, self.bootstub, bcd = self.usb_connect(self._connect_serial, claim=claim) + self._context, self._handle, serial, self.bootstub, bcd = self.usb_connect(self._connect_serial, claim=claim, no_error=wait) if self._handle is None: self._context, self._handle, serial, self.bootstub, bcd = self.spi_connect(self._connect_serial) if not wait: @@ -290,7 +314,7 @@ def connect(self, claim=True, wait=False): self._handle_open = True self._mcu_type = self.get_mcu_type() self.health_version, self.can_version, self.can_health_version = self.get_packets_versions() - logging.debug("connected") + logger.debug("connected") # disable openpilot's heartbeat checks if self._disable_checks: @@ -351,7 +375,7 @@ def spi_connect(cls, serial, ignore_version=False): return None, handle, spi_serial, bootstub, None @classmethod - def usb_connect(cls, serial, claim=True): + def usb_connect(cls, serial, claim=True, no_error=False): handle, usb_serial, bootstub, bcd = None, None, None, None context = usb1.USBContext() context.open() @@ -361,11 +385,13 @@ def usb_connect(cls, serial, claim=True): try: this_serial = device.getSerialNumber() except Exception: - logging.exception("failed to get serial number of panda") + # Allow to ignore errors on reconnect. USB hubs need some time to initialize after panda reset + if not no_error: + logger.exception("failed to get serial number of panda") continue if serial is None or this_serial == serial: - logging.debug("opening device %s %s", this_serial, hex(device.getProductID())) + logger.debug("opening device %s %s", this_serial, hex(device.getProductID())) usb_serial = this_serial bootstub = (device.getProductID() & 0xF0) == 0xe0 @@ -383,7 +409,7 @@ def usb_connect(cls, serial, claim=True): break except Exception: - logging.exception("USB connect error") + logger.exception("USB connect error") usb_handle = None if handle is not None: @@ -393,6 +419,12 @@ def usb_connect(cls, serial, claim=True): return context, usb_handle, usb_serial, bootstub, bcd + def is_connected_spi(self): + return isinstance(self._handle, PandaSpiHandle) + + def is_connected_usb(self): + return isinstance(self._handle, PandaUsbHandle) + @classmethod def list(cls): ret = cls.usb_list() @@ -411,11 +443,11 @@ def usb_list(cls): if len(serial) == 24: ret.append(serial) else: - logging.warning(f"found device with panda descriptors but invalid serial: {serial}", RuntimeWarning) + logger.warning(f"found device with panda descriptors but invalid serial: {serial}", RuntimeWarning) except Exception: - logging.exception("error connecting to panda") + logger.exception("error connecting to panda") except Exception: - logging.exception("exception while listing pandas") + logger.exception("exception while listing pandas") return ret @classmethod @@ -455,7 +487,7 @@ def reconnect(self): # wait up to 15 seconds for _ in range(15*10): try: - self.connect() + self.connect(claim=False, wait=True) success = True break except Exception: @@ -483,22 +515,22 @@ def flash_static(handle, code, mcu_type): assert last_sector < 7, "Binary too large! Risk of overwriting provisioning chunk." # unlock flash - logging.warning("flash: unlocking") + logger.info("flash: unlocking") handle.controlWrite(Panda.REQUEST_IN, 0xb1, 0, 0, b'') # erase sectors - logging.warning(f"flash: erasing sectors 1 - {last_sector}") + logger.info(f"flash: erasing sectors 1 - {last_sector}") for i in range(1, last_sector + 1): handle.controlWrite(Panda.REQUEST_IN, 0xb2, i, 0, b'') # flash over EP2 STEP = 0x10 - logging.warning("flash: flashing") + logger.info("flash: flashing") for i in range(0, len(code), STEP): handle.bulkWrite(2, code[i:i + STEP]) # reset - logging.warning("flash: resetting") + logger.info("flash: resetting") try: handle.controlWrite(Panda.REQUEST_IN, 0xd8, 0, 0, b'', expect_disconnect=True) except Exception: @@ -506,13 +538,13 @@ def flash_static(handle, code, mcu_type): def flash(self, fn=None, code=None, reconnect=True): if self.up_to_date(fn=fn): - logging.debug("flash: already up to date") + logger.info("flash: already up to date") return if not fn: fn = os.path.join(FW_PATH, self._mcu_type.config.app_fn) assert os.path.isfile(fn) - logging.debug("flash: main version is %s", self.get_version()) + logger.debug("flash: main version is %s", self.get_version()) if not self.bootstub: self.reset(enter_bootstub=True) assert(self.bootstub) @@ -522,7 +554,7 @@ def flash(self, fn=None, code=None, reconnect=True): code = f.read() # get version - logging.debug("flash: bootstub version is %s", self.get_version()) + logger.debug("flash: bootstub version is %s", self.get_version()) # do flash Panda.flash_static(self._handle, code, mcu_type=self._mcu_type) @@ -554,7 +586,7 @@ def wait_for_dfu(dfu_serial: str | None, timeout: int | None = None) -> bool: t_start = time.monotonic() dfu_list = PandaDFU.list() while (dfu_serial is None and len(dfu_list) == 0) or (dfu_serial is not None and dfu_serial not in dfu_list): - logging.debug("waiting for DFU...") + logger.debug("waiting for DFU...") time.sleep(0.1) if timeout is not None and (time.monotonic() - t_start) > timeout: return False @@ -566,7 +598,7 @@ def wait_for_panda(serial: str | None, timeout: int) -> bool: t_start = time.monotonic() serials = Panda.list() while (serial is None and len(serials) == 0) or (serial is not None and serial not in serials): - logging.debug("waiting for panda...") + logger.debug("waiting for panda...") time.sleep(0.1) if timeout is not None and (time.monotonic() - t_start) > timeout: return False @@ -798,21 +830,13 @@ def can_reset_communications(self): @ensure_can_packet_version def can_send_many(self, arr, timeout=CAN_SEND_TIMEOUT_MS): snds = pack_can_buffer(arr) - while True: - try: - for tx in snds: - while True: - bs = self._handle.bulkWrite(3, tx, timeout=timeout) - tx = tx[bs:] - if len(tx) == 0: - break - logging.error("CAN: PARTIAL SEND MANY, RETRYING") - break - except (usb1.USBErrorIO, usb1.USBErrorOverflow): - logging.error("CAN: BAD SEND MANY, RETRYING") + for tx in snds: + while len(tx) > 0: + bs = self._handle.bulkWrite(3, tx, timeout=timeout) + tx = tx[bs:] def can_send(self, addr, dat, bus, timeout=CAN_SEND_TIMEOUT_MS): - self.can_send_many([[addr, None, dat, bus]], timeout=timeout) + self.can_send_many([[addr, dat, bus]], timeout=timeout) @ensure_can_packet_version def can_recv(self): @@ -822,7 +846,7 @@ def can_recv(self): dat = self._handle.bulkRead(1, 16384) # Max receive batch size + 2 extra reserve frames break except (usb1.USBErrorIO, usb1.USBErrorOverflow): - logging.error("CAN: BAD RECV, RETRYING") + logger.error("CAN: BAD RECV, RETRYING") time.sleep(0.1) msgs, self.can_rx_overflow_buffer = unpack_can_buffer(self.can_rx_overflow_buffer + dat) return msgs diff --git a/panda/python/ccp.py b/panda/python/ccp.py index 50a5f87a3df26ba..20ca3c62da1e4d2 100644 --- a/panda/python/ccp.py +++ b/panda/python/ccp.py @@ -2,6 +2,35 @@ import time import struct from enum import IntEnum, Enum +from dataclasses import dataclass +from typing import Optional + +@dataclass +class ExchangeStationIdsReturn: + id_length: int + data_type: int + available: int + protected: int + +@dataclass +class GetDaqListSizeReturn: + list_size: int + first_pid: int + +@dataclass +class GetSessionStatusReturn: + status: int + info: Optional[int] + +@dataclass +class DiagnosticServiceReturn: + length: int + type: int + +@dataclass +class ActionServiceReturn: + length: int + type: int class COMMAND_CODE(IntEnum): CONNECT = 0x01 @@ -99,7 +128,7 @@ def _recv_dto(self, timeout: float) -> bytes: msgs = self._panda.can_recv() or [] if len(msgs) >= 256: print("CAN RX buffer overflow!!!", file=sys.stderr) - for rx_addr, _, rx_data_bytearray, rx_bus in msgs: + for rx_addr, rx_data_bytearray, rx_bus in msgs: if rx_bus == self.can_bus and rx_addr == self.rx_addr: rx_data = bytes(rx_data_bytearray) if self.debug: @@ -140,20 +169,15 @@ def connect(self, station_addr: int) -> None: self._send_cro(COMMAND_CODE.CONNECT, struct.pack(" dict: + def exchange_station_ids(self, device_id_info: bytes = b"") -> ExchangeStationIdsReturn: self._send_cro(COMMAND_CODE.EXCHANGE_ID, device_id_info) resp = self._recv_dto(0.025) - return { # TODO: define a type - "id_length": resp[0], - "data_type": resp[1], - "available": resp[2], - "protected": resp[3], - } + return ExchangeStationIdsReturn(id_length=resp[0], data_type=resp[1], available=resp[2], protected=resp[3]) def get_seed(self, resource_mask: int) -> bytes: if resource_mask > 255: raise ValueError("resource mask must be less than 256") - self._send_cro(COMMAND_CODE.GET_SEED) + self._send_cro(COMMAND_CODE.GET_SEED, bytes([resource_mask])) resp = self._recv_dto(0.025) # protected = resp[0] == 0 seed = resp[1:] @@ -197,7 +221,7 @@ def upload(self, size: int) -> bytes: if size > 5: raise ValueError("size must be less than 6") self._send_cro(COMMAND_CODE.UPLOAD, bytes([size])) - return self._recv_dto(0.025) + return self._recv_dto(0.025)[:size] def short_upload(self, size: int, addr_ext: int, addr: int) -> bytes: if size > 5: @@ -205,21 +229,18 @@ def short_upload(self, size: int, addr_ext: int, addr: int) -> bytes: if addr_ext > 255: raise ValueError("address extension must be less than 256") self._send_cro(COMMAND_CODE.SHORT_UP, bytes([size, addr_ext]) + struct.pack(f"{self.byte_order.value}I", addr)) - return self._recv_dto(0.025) + return self._recv_dto(0.025)[:size] def select_calibration_page(self) -> None: self._send_cro(COMMAND_CODE.SELECT_CAL_PAGE) self._recv_dto(0.025) - def get_daq_list_size(self, list_num: int, can_id: int = 0) -> dict: + def get_daq_list_size(self, list_num: int, can_id: int = 0) -> GetDaqListSizeReturn: if list_num > 255: raise ValueError("list number must be less than 256") self._send_cro(COMMAND_CODE.GET_DAQ_SIZE, bytes([list_num, 0]) + struct.pack(f"{self.byte_order.value}I", can_id)) resp = self._recv_dto(0.025) - return { # TODO: define a type - "list_size": resp[0], - "first_pid": resp[1], - } + return GetDaqListSizeReturn(list_size=resp[0], first_pid=resp[1]) def set_daq_list_pointer(self, list_num: int, odt_num: int, element_num: int) -> None: if list_num > 255: @@ -266,13 +287,11 @@ def set_session_status(self, status: int) -> None: self._send_cro(COMMAND_CODE.SET_S_STATUS, bytes([status])) self._recv_dto(0.025) - def get_session_status(self) -> dict: + def get_session_status(self) -> GetSessionStatusReturn: self._send_cro(COMMAND_CODE.GET_S_STATUS) resp = self._recv_dto(0.025) - return { # TODO: define a type - "status": resp[0], - "info": resp[2] if resp[1] else None, - } + info = resp[2] if resp[1] else None + return GetSessionStatusReturn(status=resp[0], info=info) def build_checksum(self, size: int) -> bytes: self._send_cro(COMMAND_CODE.BUILD_CHKSUM, struct.pack(f"{self.byte_order.value}I", size)) @@ -310,29 +329,23 @@ def move_memory_block(self, size: int) -> None: self._send_cro(COMMAND_CODE.MOVE, struct.pack(f"{self.byte_order.value}I", size)) self._recv_dto(0.025) - def diagnostic_service(self, service_num: int, data: bytes = b"") -> dict: + def diagnostic_service(self, service_num: int, data: bytes = b"") -> DiagnosticServiceReturn: if service_num > 65535: raise ValueError("service number must be less than 65536") if len(data) > 4: raise ValueError("max data size is 4 bytes") self._send_cro(COMMAND_CODE.DIAG_SERVICE, struct.pack(f"{self.byte_order.value}H", service_num) + data) resp = self._recv_dto(0.025) - return { # TODO: define a type - "length": resp[0], - "type": resp[1], - } + return DiagnosticServiceReturn(length=resp[0], type=resp[1]) - def action_service(self, service_num: int, data: bytes = b"") -> dict: + def action_service(self, service_num: int, data: bytes = b"") -> ActionServiceReturn: if service_num > 65535: raise ValueError("service number must be less than 65536") if len(data) > 4: raise ValueError("max data size is 4 bytes") self._send_cro(COMMAND_CODE.ACTION_SERVICE, struct.pack(f"{self.byte_order.value}H", service_num) + data) resp = self._recv_dto(0.025) - return { # TODO: define a type - "length": resp[0], - "type": resp[1], - } + return ActionServiceReturn(length=resp[0], type=resp[1]) def test_availability(self, station_addr: int) -> None: if station_addr > 65535: diff --git a/panda/python/isotp.py b/panda/python/isotp.py index d0bef7d94288342..ac64c413be09da5 100644 --- a/panda/python/isotp.py +++ b/panda/python/isotp.py @@ -18,12 +18,12 @@ def recv(panda, cnt, addr, nbus): while len(ret) < cnt: kmsgs += panda.can_recv() nmsgs = [] - for ids, ts, dat, bus in kmsgs: + for ids, dat, bus in kmsgs: if ids == addr and bus == nbus and len(ret) < cnt: ret.append(dat) else: # leave around - nmsgs.append((ids, ts, dat, bus)) + nmsgs.append((ids, dat, bus)) kmsgs = nmsgs[-256:] return ret @@ -96,7 +96,7 @@ def isotp_send(panda, x, addr, bus=0, recvaddr=None, subaddr=None, rate=None): panda.can_send(addr, sends[-1], 0) else: if rate is None: - panda.can_send_many([(addr, None, s, bus) for s in sends]) + panda.can_send_many([(addr, s, bus) for s in sends]) else: for dat in sends: panda.can_send(addr, dat, bus) diff --git a/panda/python/socketpanda.py b/panda/python/socketpanda.py new file mode 100644 index 000000000000000..d6115acf5514818 --- /dev/null +++ b/panda/python/socketpanda.py @@ -0,0 +1,94 @@ +import socket +import struct + +# /** +# * struct canfd_frame - CAN flexible data rate frame structure +# * @can_id: CAN ID of the frame and CAN_*_FLAG flags, see canid_t definition +# * @len: frame payload length in byte (0 .. CANFD_MAX_DLEN) +# * @flags: additional flags for CAN FD +# * @__res0: reserved / padding +# * @__res1: reserved / padding +# * @data: CAN FD frame payload (up to CANFD_MAX_DLEN byte) +# */ +# struct canfd_frame { +# canid_t can_id; /* 32 bit CAN_ID + EFF/RTR/ERR flags */ +# __u8 len; /* frame payload length in byte */ +# __u8 flags; /* additional flags for CAN FD */ +# __u8 __res0; /* reserved / padding */ +# __u8 __res1; /* reserved / padding */ +# __u8 data[CANFD_MAX_DLEN] __attribute__((aligned(8))); +# }; +CAN_HEADER_FMT = "=IBB2x" +CAN_HEADER_LEN = struct.calcsize(CAN_HEADER_FMT) +CAN_MAX_DLEN = 8 +CANFD_MAX_DLEN = 64 + +CANFD_BRS = 0x01 # bit rate switch (second bitrate for payload data) +CANFD_FDF = 0x04 # mark CAN FD for dual use of struct canfd_frame + +# socket.SO_RXQ_OVFL is missing +# https://github.com/torvalds/linux/blob/47ac09b91befbb6a235ab620c32af719f8208399/include/uapi/asm-generic/socket.h#L61 +SO_RXQ_OVFL = 40 + +def create_socketcan(interface:str, recv_buffer_size:int, fd:bool) -> socket.socket: + # settings mostly from https://github.com/linux-can/can-utils/blob/master/candump.c + socketcan = socket.socket(socket.AF_CAN, socket.SOCK_RAW, socket.CAN_RAW) + if fd: + socketcan.setsockopt(socket.SOL_CAN_RAW, socket.CAN_RAW_FD_FRAMES, 1) + socketcan.setsockopt(socket.SOL_SOCKET, socket.SO_RCVBUF, recv_buffer_size) + # TODO: why is it always 2x the requested size? + assert socketcan.getsockopt(socket.SOL_SOCKET, socket.SO_RCVBUF) == recv_buffer_size * 2 + # TODO: how to dectect and alert on buffer overflow? + socketcan.setsockopt(socket.SOL_SOCKET, SO_RXQ_OVFL, 1) + socketcan.bind((interface,)) + return socketcan + +# Panda class substitute for socketcan device (to support using the uds/iso-tp/xcp/ccp library) +class SocketPanda(): + def __init__(self, interface:str="can0", bus:int=0, fd:bool=False, recv_buffer_size:int=212992) -> None: + self.interface = interface + self.bus = bus + self.fd = fd + self.flags = CANFD_BRS | CANFD_FDF if fd else 0 + self.data_len = CANFD_MAX_DLEN if fd else CAN_MAX_DLEN + self.recv_buffer_size = recv_buffer_size + self.socket = create_socketcan(interface, recv_buffer_size, fd) + + def __del__(self): + self.socket.close() + + def get_serial(self) -> tuple[int, int]: + return (0, 0) # TODO: implemented in panda socketcan driver + + def get_version(self) -> int: + return 0 # TODO: implemented in panda socketcan driver + + def can_clear(self, bus:int) -> None: + # TODO: implemented in panda socketcan driver + self.socket.close() + self.socket = create_socketcan(self.interface, self.recv_buffer_size, self.fd) + + def set_safety_mode(self, mode:int, param=0) -> None: + pass # TODO: implemented in panda socketcan driver + + def has_obd(self) -> bool: + return False # TODO: implemented in panda socketcan driver + + def can_send(self, addr, dat, bus=0, timeout=0) -> None: + msg_len = len(dat) + msg_dat = dat.ljust(self.data_len, b'\x00') + can_frame = struct.pack(CAN_HEADER_FMT, addr, msg_len, self.flags) + msg_dat + self.socket.sendto(can_frame, (self.interface,)) + + def can_recv(self) -> list[tuple[int, bytes, int]]: + msgs = list() + while True: + try: + dat, _ = self.socket.recvfrom(self.recv_buffer_size, socket.MSG_DONTWAIT) + assert len(dat) == CAN_HEADER_LEN + self.data_len, f"ERROR: received {len(dat)} bytes" + can_id, msg_len, _ = struct.unpack(CAN_HEADER_FMT, dat[:CAN_HEADER_LEN]) + msg_dat = dat[CAN_HEADER_LEN:CAN_HEADER_LEN+msg_len] + msgs.append((can_id, msg_dat, self.bus)) + except BlockingIOError: + break # buffered data exhausted + return msgs diff --git a/panda/python/spi.py b/panda/python/spi.py index be4f7dcf46e9318..5be1e56b6b9acb7 100644 --- a/panda/python/spi.py +++ b/panda/python/spi.py @@ -5,7 +5,6 @@ import math import time import struct -import logging import threading from contextlib import contextmanager from functools import reduce @@ -13,6 +12,7 @@ from .base import BaseHandle, BaseSTBootloaderHandle, TIMEOUT from .constants import McuType, MCU_TYPE_BY_IDCODE, USBPACKET_MAX_SIZE +from .utils import logger try: import spidev @@ -70,8 +70,6 @@ class PandaSpiTransferFailed(PandaSpiException): pass -SPI_LOCK = threading.Lock() - class PandaSpiTransfer(ctypes.Structure): _fields_ = [ ('rx_buf', ctypes.c_uint64), @@ -83,6 +81,9 @@ class PandaSpiTransfer(ctypes.Structure): ('expect_disconnect', ctypes.c_uint8), ] + +SPI_LOCK = threading.Lock() +SPI_DEVICES = {} class SpiDevice: """ Provides locked, thread-safe access to a panda's SPI interface. @@ -100,9 +101,12 @@ def __init__(self, speed=MAX_SPEED): if spidev is None: raise PandaSpiUnavailable("spidev is not installed") - self._spidev = spidev.SpiDev() # pylint: disable=c-extension-no-member - self._spidev.open(0, 0) - self._spidev.max_speed_hz = speed + with SPI_LOCK: + if speed not in SPI_DEVICES: + SPI_DEVICES[speed] = spidev.SpiDev() # pylint: disable=c-extension-no-member + SPI_DEVICES[speed].open(0, 0) + SPI_DEVICES[speed].max_speed_hz = speed + self._spidev = SPI_DEVICES[speed] @contextmanager def acquire(self): @@ -115,8 +119,7 @@ def acquire(self): SPI_LOCK.release() def close(self): - self._spidev.close() - + pass class PandaSpiHandle(BaseHandle): @@ -167,23 +170,23 @@ def _wait_for_ack(self, spi, ack_val: int, timeout: int, tx: int, length: int = def _transfer_spidev(self, spi, endpoint: int, data, timeout: int, max_rx_len: int = 1000, expect_disconnect: bool = False) -> bytes: max_rx_len = max(USBPACKET_MAX_SIZE, max_rx_len) - logging.debug("- send header") + logger.debug("- send header") packet = struct.pack(" bytes: - logging.debug("starting transfer: endpoint=%d, max_rx_len=%d", endpoint, max_rx_len) - logging.debug("==============================================") + logger.debug("starting transfer: endpoint=%d, max_rx_len=%d", endpoint, max_rx_len) + logger.debug("==============================================") n = 0 start_time = time.monotonic() exc = PandaSpiException() while (timeout == 0) or (time.monotonic() - start_time) < timeout*1e-3: n += 1 - logging.debug("\ntry #%d", n) + logger.debug("\ntry #%d", n) with self.dev.acquire() as spi: try: return self._transfer_raw(spi, endpoint, data, timeout, max_rx_len, expect_disconnect) except PandaSpiException as e: exc = e - logging.debug("SPI transfer failed, retrying", exc_info=True) + logger.debug("SPI transfer failed, retrying", exc_info=True) raise exc @@ -245,7 +248,7 @@ def get_protocol_version(self) -> bytes: def _get_version(spi) -> bytes: spi.writebytes(vers_str) - logging.debug("- waiting for echo") + logger.debug("- waiting for echo") start = time.monotonic() while True: version_bytes = spi.readbytes(len(vers_str) + 2) @@ -273,7 +276,7 @@ def _get_version(spi) -> bytes: return _get_version(spi) except PandaSpiException as e: exc = e - logging.debug("SPI get protocol version failed, retrying", exc_info=True) + logger.debug("SPI get protocol version failed, retrying", exc_info=True) raise exc # libusb1 functions @@ -378,7 +381,7 @@ def _cmd(self, cmd: int, data: list[bytes] | None = None, read_bytes: int = 0, p return self._cmd_no_retry(cmd, data, read_bytes, predata) except PandaSpiException as e: exc = e - logging.debug("SPI transfer failed, %d retries left", MAX_XFER_RETRY_COUNT - n - 1, exc_info=True) + logger.debug("SPI transfer failed, %d retries left", MAX_XFER_RETRY_COUNT - n - 1, exc_info=True) raise exc def _checksum(self, data: bytes) -> bytes: @@ -394,6 +397,9 @@ def read(self, address: int, length: int): data = [struct.pack('>I', address), struct.pack('B', length - 1)] return self._cmd(0x11, data=data, read_bytes=length) + def get_bootloader_id(self): + return self.read(0x1FF1E7FE, 1) + def get_chip_id(self) -> int: r = self._cmd(0x02, read_bytes=3) assert r[0] == 1 # response length - 1 diff --git a/panda/python/uds.py b/panda/python/uds.py index 32b0de09612e6d5..612eb206b08b426 100644 --- a/panda/python/uds.py +++ b/panda/python/uds.py @@ -301,7 +301,7 @@ def get_dtc_status_names(status): return result class CanClient(): - def __init__(self, can_send: Callable[[int, bytes, int], None], can_recv: Callable[[], list[tuple[int, int, bytes, int]]], + def __init__(self, can_send: Callable[[int, bytes, int], None], can_recv: Callable[[], list[tuple[int, bytes, int]]], tx_addr: int, rx_addr: int, bus: int, sub_addr: int | None = None, debug: bool = False): self.tx = can_send self.rx = can_recv @@ -339,7 +339,7 @@ def _recv_buffer(self, drain: bool = False) -> None: print(f"CAN-RX: drain - {len(msgs)}") self.rx_buff.clear() else: - for rx_addr, _, rx_data, rx_bus in msgs or []: + for rx_addr, rx_data, rx_bus in msgs or []: if self._recv_filter(rx_bus, rx_addr) and len(rx_data) > 0: rx_data = bytes(rx_data) # convert bytearray to bytes @@ -820,7 +820,7 @@ def write_memory_by_address(self, memory_address: int, memory_size: int, data_re data += struct.pack('!I', memory_size)[4 - memory_size_bytes:] data += data_record - self._uds_request(SERVICE_TYPE.WRITE_MEMORY_BY_ADDRESS, subfunction=0x00, data=data) + self._uds_request(SERVICE_TYPE.WRITE_MEMORY_BY_ADDRESS, subfunction=None, data=data) def clear_diagnostic_information(self, dtc_group_type: DTC_GROUP_TYPE): data = struct.pack('!I', dtc_group_type)[1:] # 3 bytes diff --git a/panda/python/utils.py b/panda/python/utils.py new file mode 100644 index 000000000000000..55181e08b11990c --- /dev/null +++ b/panda/python/utils.py @@ -0,0 +1,11 @@ +import os +import logging + +# set up logging +LOGLEVEL = os.environ.get('LOGLEVEL', 'INFO').upper() +logger = logging.getLogger('panda') +logger.setLevel(LOGLEVEL) + +handler = logging.StreamHandler() +handler.setFormatter(logging.Formatter('%(message)s')) +logger.addHandler(handler) diff --git a/panda/python/xcp.py b/panda/python/xcp.py index bb294046ecc257d..066ed9885ab3333 100644 --- a/panda/python/xcp.py +++ b/panda/python/xcp.py @@ -145,7 +145,7 @@ def _recv_dto(self, timeout: float) -> bytes: msgs = self._panda.can_recv() or [] if len(msgs) >= 256: print("CAN RX buffer overflow!!!", file=sys.stderr) - for rx_addr, _, rx_data, rx_bus in msgs: + for rx_addr, rx_data, rx_bus in msgs: if rx_bus == self.can_bus and rx_addr == self.rx_addr: rx_data = bytes(rx_data) # convert bytearray to bytes if self.debug: diff --git a/panda/release/make_release.sh b/panda/release/make_release.sh index 5628c4998dbfd1b..cfecac3a1656b4b 100755 --- a/panda/release/make_release.sh +++ b/panda/release/make_release.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/panda/requirements.txt b/panda/requirements.txt deleted file mode 100644 index 5ee8636fd5913c5..000000000000000 --- a/panda/requirements.txt +++ /dev/null @@ -1,18 +0,0 @@ -ruff -libusb1 -numpy -hexdump -pycryptodome -tqdm>=4.14.0 -pytest -pytest-mock -pytest-xdist -pytest-timeout -pytest-randomly -parameterized -cffi -pre-commit -scons>=4.4.0 -flaky -spidev -termcolor \ No newline at end of file diff --git a/panda/setup.py b/panda/setup.py index 25ee66923620ccd..a7729cc6f89970f 100644 --- a/panda/setup.py +++ b/panda/setup.py @@ -44,12 +44,27 @@ def find_version(*file_paths): platforms='any', license='MIT', install_requires=[ - 'libusb1 == 2.0.1', - 'hexdump >= 3.3', - 'pycryptodome >= 3.9.8', - 'tqdm >= 4.14.0', - 'requests' + 'libusb1', ], + extras_require = { + 'dev': [ + "scons", + "pycryptodome >= 3.9.8", + "cffi", + "flaky", + "pytest", + "pytest-mock", + "pytest-xdist", + "pytest-timeout", + "pytest-randomly", + "parameterized", + "pre-commit", + "numpy", + "ruff", + "spidev", + "setuptools", # for setup.py + ], + }, ext_modules=[], description="Code powering the comma.ai panda", long_description='See https://github.com/commaai/panda', diff --git a/panda/tests/black_white_loopback_test.py b/panda/tests/black_white_loopback_test.py index 8198a30d5fd2865..69b0cfbd1e939c1 100755 --- a/panda/tests/black_white_loopback_test.py +++ b/panda/tests/black_white_loopback_test.py @@ -118,11 +118,11 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): loop_buses = [] for loop in cans_loop: - if (loop[0] != at) or (loop[2] != st): + if (loop[0] != at) or (loop[1] != st): content_errors += 1 - print(" Loop on bus", str(loop[3])) - loop_buses.append(loop[3]) + print(" Loop on bus", str(loop[2])) + loop_buses.append(loop[2]) if len(cans_loop) == 0: print(" No loop") assert not os.getenv("NOASSERT") diff --git a/panda/tests/black_white_relay_endurance.py b/panda/tests/black_white_relay_endurance.py index 005277c15adf007..433f12343a9a662 100755 --- a/panda/tests/black_white_relay_endurance.py +++ b/panda/tests/black_white_relay_endurance.py @@ -126,11 +126,11 @@ def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): loop_buses = [] for loop in cans_loop: - if (loop[0] != at) or (loop[2] != st): + if (loop[0] != at) or (loop[1] != st): content_errors += 1 - print(" Loop on bus", str(loop[3])) - loop_buses.append(loop[3]) + print(" Loop on bus", str(loop[2])) + loop_buses.append(loop[2]) if len(cans_loop) == 0: print(" No loop") assert os.getenv("NOASSERT") diff --git a/panda/tests/black_white_relay_test.py b/panda/tests/black_white_relay_test.py index 38db06a1a524a0f..dce44f567518694 100755 --- a/panda/tests/black_white_relay_test.py +++ b/panda/tests/black_white_relay_test.py @@ -109,9 +109,9 @@ def test_buses(black_panda, other_panda, test_obj): loop_buses = [] for loop in cans_loop: - if (loop[0] != at) or (loop[2] != st): + if (loop[0] != at) or (loop[1] != st): content_errors += 1 - loop_buses.append(loop[3]) + loop_buses.append(loop[2]) # test loop buses recv_buses.sort() diff --git a/panda/tests/bulk_write_test.py b/panda/tests/bulk_write_test.py index 278766a1990de37..e886efb06dc106b 100755 --- a/panda/tests/bulk_write_test.py +++ b/panda/tests/bulk_write_test.py @@ -16,7 +16,7 @@ def flood_tx(panda): print('Sending!') msg = b"\xaa" * 4 - packet = [[0xaa, None, msg, 0], [0xaa, None, msg, 1], [0xaa, None, msg, 2]] * NUM_MESSAGES_PER_BUS + packet = [[0xaa, msg, 0], [0xaa, msg, 1], [0xaa, msg, 2]] * NUM_MESSAGES_PER_BUS panda.can_send_many(packet, timeout=10000) print(f"Done sending {3*NUM_MESSAGES_PER_BUS} messages!") diff --git a/panda/tests/can_health.py b/panda/tests/can_health.py new file mode 100755 index 000000000000000..26de9cdab1a9dab --- /dev/null +++ b/panda/tests/can_health.py @@ -0,0 +1,29 @@ +#!/usr/bin/env python3 +import time +import re +from panda import Panda + +RED = '\033[91m' +GREEN = '\033[92m' + +def colorize_errors(value): + if isinstance(value, str): + if re.search(r'(?i)No error', value): + return f'{GREEN}{value}\033[0m' + elif re.search(r'(?i)(? 0.1: dd = chr(27) + "[2J" dd += "%5.2f\n" % (sec_since_boot() - start) - for k, v in sorted(zip(list(msgs.keys()), [binascii.hexlify(x[-1]) for x in list(msgs.values())], strict=True)): - dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k, k), len(msgs[k]), v) + for (addr, bus), dat_log in sorted(all_msgs.items()): + dd += "%d: %s(%6d): %s\n" % (bus, "%04X(%4d)" % (addr, addr), len(dat_log), binascii.hexlify(dat_log[-1]).decode()) print(dd) lp = sec_since_boot() diff --git a/panda/tests/canfd/test_canfd.py b/panda/tests/canfd/test_canfd.py index 873bc796ba57dd6..500a69aa06024fb 100755 --- a/panda/tests/canfd/test_canfd.py +++ b/panda/tests/canfd/test_canfd.py @@ -86,7 +86,7 @@ def canfd_test(p_send, p_recv): data = bytearray(random.getrandbits(8) for _ in range(DLC_TO_LEN[dlc])) if len(data) >= 2: data[0] = calculate_checksum(data[1:] + bytes(str(address), encoding="utf-8")) - to_send.append([address, 0, data, bus]) + to_send.append([address, data, bus]) sent_msgs[bus].add((address, bytes(data))) p_send.can_send_many(to_send, timeout=0) @@ -95,7 +95,7 @@ def canfd_test(p_send, p_recv): while (time.monotonic() - start_time < 1) and any(len(x) > 0 for x in sent_msgs.values()): incoming = p_recv.can_recv() for msg in incoming: - address, _, data, bus = msg + address, data, bus = msg if len(data) >= 2: assert calculate_checksum(data[1:] + bytes(str(address), encoding="utf-8")) == data[0] k = (address, bytes(data)) diff --git a/panda/tests/ci_shell.sh b/panda/tests/ci_shell.sh index 92c0f96e8abe1c6..ab87f36cae032a3 100755 --- a/panda/tests/ci_shell.sh +++ b/panda/tests/ci_shell.sh @@ -1,4 +1,5 @@ -#!/bin/bash -e +#!/usr/bin/env bash +set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" OP_ROOT="$DIR/../../" diff --git a/panda/tests/echo.py b/panda/tests/echo.py index 90bf4a8c769aa45..1c20561b10bc140 100755 --- a/panda/tests/echo.py +++ b/panda/tests/echo.py @@ -11,6 +11,6 @@ while True: incoming = p.can_recv() for message in incoming: - address, notused, data, bus = message + address, data, bus = message if b'test' in data: p.can_send(address, data[::-1], bus) diff --git a/panda/tests/elm_car_simulator.py b/panda/tests/elm_car_simulator.py index 56e825f5dd848ab..90024a25417dddb 100755 --- a/panda/tests/elm_car_simulator.py +++ b/panda/tests/elm_car_simulator.py @@ -77,11 +77,11 @@ def __can_monitor(self): self.panda.can_recv() # Toss whatever was already there while not self.__stop: - for address, ts, data, src in self.panda.can_recv(): + for address, data, src in self.panda.can_recv(): if self.__on and src == 0 and len(data) == 8 and data[0] >= 2: if not self.__silent: print("Processing CAN message", src, hex(address), binascii.hexlify(data)) - self.__can_process_msg(data[1], data[2], address, ts, data, src) + self.__can_process_msg(data[1], data[2], address, data, src) elif not self.__silent: print("Rejecting CAN message", src, hex(address), binascii.hexlify(data)) @@ -120,7 +120,7 @@ def _can_addr_matches(self, addr): return True return False - def __can_process_msg(self, mode, pid, address, ts, data, src): + def __can_process_msg(self, mode, pid, address, data, src): if not self.__silent: print("CAN MSG", binascii.hexlify(data[1:1 + data[0]]), "Addr:", hex(address), "Mode:", hex(mode)[2:].zfill(2), diff --git a/panda/tests/hitl/3_usb_to_can.py b/panda/tests/hitl/3_usb_to_can.py index c0a9035fe4d1480..9920f44a873898e 100644 --- a/panda/tests/hitl/3_usb_to_can.py +++ b/panda/tests/hitl/3_usb_to_can.py @@ -18,14 +18,14 @@ def test_can_loopback(p): # confirm receive both on loopback and send receipt time.sleep(0.05) r = p.can_recv() - sr = [x for x in r if x[3] == 0x80 | bus] - lb = [x for x in r if x[3] == bus] + sr = [x for x in r if x[2] == 0x80 | bus] + lb = [x for x in r if x[2] == bus] assert len(sr) == 1 assert len(lb) == 1 # confirm data is correct assert 0x1aa == sr[0][0] == lb[0][0] - assert b"message" == sr[0][2] == lb[0][2] + assert b"message" == sr[0][1] == lb[0][1] def test_reliability(p): MSG_COUNT = 100 @@ -35,7 +35,7 @@ def test_reliability(p): p.set_can_speed_kbps(0, 1000) addrs = list(range(100, 100 + MSG_COUNT)) - ts = [(j, 0, b"\xaa" * 8, 0) for j in addrs] + ts = [(j, b"\xaa" * 8, 0) for j in addrs] for _ in range(100): st = time.monotonic() @@ -46,8 +46,8 @@ def test_reliability(p): while len(r) < 200 and (time.monotonic() - st) < 0.5: r.extend(p.can_recv()) - sent_echo = [x for x in r if x[3] == 0x80] - loopback_resp = [x for x in r if x[3] == 0] + sent_echo = [x for x in r if x[2] == 0x80] + loopback_resp = [x for x in r if x[2] == 0] assert sorted([x[0] for x in loopback_resp]) == addrs assert sorted([x[0] for x in sent_echo]) == addrs diff --git a/panda/tests/hitl/4_can_loopback.py b/panda/tests/hitl/4_can_loopback.py index a7e1aea1eef0fa9..c482ba8227e3ae3 100644 --- a/panda/tests/hitl/4_can_loopback.py +++ b/panda/tests/hitl/4_can_loopback.py @@ -118,10 +118,10 @@ def test(p_send, p_recv, address=None): assert len(content) == 1 # Check content - assert content[0][0] == addr and content[0][2] == string + assert content[0][0] == addr and content[0][1] == string # Check bus - assert content[0][3] == bus + assert content[0][2] == bus print("Bus:", bus, "address:", addr, "OBD:", obd, "OK") @@ -148,9 +148,9 @@ def flood_tx(panda): msg = b"\xaa" * 8 packet = [] # start with many messages on a single bus (higher contention for single TX ring buffer) - packet += [[0xaa, None, msg, 0]] * NUM_MESSAGES_PER_BUS + packet += [[0xaa, msg, 0]] * NUM_MESSAGES_PER_BUS # end with many messages on multiple buses - packet += [[0xaa, None, msg, 0], [0xaa, None, msg, 1], [0xaa, None, msg, 2]] * NUM_MESSAGES_PER_BUS + packet += [[0xaa, msg, 0], [0xaa, msg, 1], [0xaa, msg, 2]] * NUM_MESSAGES_PER_BUS # Disable timeout panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) @@ -182,18 +182,18 @@ def test_message_integrity(p): for _ in range(random.randrange(10)): to_send = get_random_can_messages(random.randrange(100)) for m in to_send: - sent_msgs[m[3]].add((m[0], m[2])) + sent_msgs[m[2]].add((m[0], m[1])) p.can_send_many(to_send, timeout=0) start_time = time.monotonic() while time.monotonic() - start_time < 2 and any(len(sent_msgs[bus]) for bus in range(3)): recvd = p.can_recv() for msg in recvd: - if msg[3] >= 128: - k = (msg[0], bytes(msg[2])) - bus = msg[3]-128 + if msg[2] >= 128: + k = (msg[0], bytes(msg[1])) + bus = msg[2]-128 assert k in sent_msgs[bus], f"message {k} was never sent on bus {bus}" - sent_msgs[msg[3]-128].discard(k) + sent_msgs[msg[2]-128].discard(k) # if a set isn't empty, messages got dropped for bus in range(3): diff --git a/panda/tests/hitl/6_safety.py b/panda/tests/hitl/6_safety.py index 2237f5303600f4e..67c646166e90863 100644 --- a/panda/tests/hitl/6_safety.py +++ b/panda/tests/hitl/6_safety.py @@ -14,8 +14,8 @@ def test_safety_nooutput(p): time.sleep(0.05) r = p.can_recv() # bus 192 is messages blocked by TX safety hook on bus 0 - assert len([x for x in r if x[3] != 192]) == 0 - assert len([x for x in r if x[3] == 192]) == 1 + assert len([x for x in r if x[2] != 192]) == 0 + assert len([x for x in r if x[2] == 192]) == 1 def test_canfd_safety_modes(p): diff --git a/panda/tests/hitl/9_harness.py b/panda/tests/hitl/9_harness.py index 5689892b8a4f2c2..b3544899be5de3b 100644 --- a/panda/tests/hitl/9_harness.py +++ b/panda/tests/hitl/9_harness.py @@ -51,7 +51,7 @@ def test_harness_status(p, panda_jungle): time.sleep(0.5) msgs = p.can_recv() - buses = {int(dat): bus for _, _, dat, bus in msgs if bus <= 3} + buses = {int(dat): bus for _, dat, bus in msgs if bus <= 3} print(msgs) # jungle doesn't actually switch buses when switching orientation diff --git a/panda/tests/hitl/helpers.py b/panda/tests/hitl/helpers.py index 4eee4373116d442..d4656713095673c 100644 --- a/panda/tests/hitl/helpers.py +++ b/panda/tests/hitl/helpers.py @@ -8,7 +8,7 @@ def get_random_can_messages(n): bus = random.randrange(3) addr = random.randrange(1 << 29) dat = bytes([random.getrandbits(8) for _ in range(random.randrange(1, 9))]) - m.append([addr, None, dat, bus]) + m.append([addr, dat, bus]) return m @@ -19,7 +19,7 @@ def time_many_sends(p, bus, p_recv=None, msg_count=100, two_pandas=False, msg_le raise ValueError("Cannot have two pandas that are the same panda") msg_id = random.randint(0x100, 0x200) - to_send = [(msg_id, 0, b"\xaa" * msg_len, bus)] * msg_count + to_send = [(msg_id, b"\xaa" * msg_len, bus)] * msg_count start_time = time.monotonic() p.can_send_many(to_send) @@ -35,11 +35,11 @@ def time_many_sends(p, bus, p_recv=None, msg_count=100, two_pandas=False, msg_le while len(r_echo) < r_echo_len_exected and (time.monotonic() - start_time) < 10: r_echo.extend(p.can_recv()) - sent_echo = [x for x in r if x[3] == 0x80 | bus and x[0] == msg_id] - sent_echo.extend([x for x in r_echo if x[3] == 0x80 | bus and x[0] == msg_id]) - resp = [x for x in r if x[3] == bus and x[0] == msg_id] + sent_echo = [x for x in r if x[2] == 0x80 | bus and x[0] == msg_id] + sent_echo.extend([x for x in r_echo if x[2] == 0x80 | bus and x[0] == msg_id]) + resp = [x for x in r if x[2] == bus and x[0] == msg_id] - leftovers = [x for x in r if (x[3] != 0x80 | bus and x[3] != bus) or x[0] != msg_id] + leftovers = [x for x in r if (x[2] != 0x80 | bus and x[2] != bus) or x[0] != msg_id] assert len(leftovers) == 0 assert len(resp) == msg_count diff --git a/panda/tests/hitl/run_parallel_tests.sh b/panda/tests/hitl/run_parallel_tests.sh index b6b79d99f6c54ea..f60d838c5b7a8f4 100755 --- a/panda/tests/hitl/run_parallel_tests.sh +++ b/panda/tests/hitl/run_parallel_tests.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/panda/tests/hitl/run_serial_tests.sh b/panda/tests/hitl/run_serial_tests.sh index 31270f044c39076..4feae5e30c2224a 100755 --- a/panda/tests/hitl/run_serial_tests.sh +++ b/panda/tests/hitl/run_serial_tests.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/panda/tests/libpanda/SConscript b/panda/tests/libpanda/SConscript index cc0890730838086..2ad405f5e2715f4 100644 --- a/panda/tests/libpanda/SConscript +++ b/panda/tests/libpanda/SConscript @@ -21,6 +21,18 @@ env = Environment( if system == "Darwin": env.PrependENVPath('PATH', '/opt/homebrew/bin') +if GetOption('mutation'): + env['CC'] = 'clang-17' + flags = [ + '-fprofile-instr-generate', + '-fcoverage-mapping', + '-fpass-plugin=/usr/lib/mull-ir-frontend-17', + '-g', + '-grecord-command-line', + ] + env['CFLAGS'] += flags + env['LINKFLAGS'] += flags + if GetOption('ubsan'): flags = [ "-fsanitize=undefined", diff --git a/panda/tests/libpanda/panda.c b/panda/tests/libpanda/panda.c index f34c028048c3b41..66a21f80cc3b248 100644 --- a/panda/tests/libpanda/panda.c +++ b/panda/tests/libpanda/panda.c @@ -1,6 +1,6 @@ #include "fake_stm.h" #include "config.h" -#include "can_definitions.h" +#include "can.h" bool can_init(uint8_t can_number) { return true; } void process_can(uint8_t can_number) { } @@ -16,7 +16,7 @@ void can_tx_comms_resume_spi(void) { }; #include "libc.h" #include "boards/board_declarations.h" #include "safety.h" -#include "main_declarations.h" +#include "main_definitions.h" #include "drivers/can_common.h" can_ring *rx_q = &can_rx_q; diff --git a/panda/tests/libpanda/safety_helpers.h b/panda/tests/libpanda/safety_helpers.h index 36887c8963dc46d..ab4db4757c9fd6e 100644 --- a/panda/tests/libpanda/safety_helpers.h +++ b/panda/tests/libpanda/safety_helpers.h @@ -47,6 +47,10 @@ bool get_gas_pressed_prev(void){ return gas_pressed_prev; } +void set_gas_pressed_prev(bool c){ + gas_pressed_prev = c; +} + bool get_brake_pressed_prev(void){ return brake_pressed_prev; } diff --git a/panda/tests/libpanda/safety_helpers.py b/panda/tests/libpanda/safety_helpers.py index ea41264ae086330..6b510da6a83fe3e 100644 --- a/panda/tests/libpanda/safety_helpers.py +++ b/panda/tests/libpanda/safety_helpers.py @@ -11,6 +11,7 @@ def setup_safety_helpers(ffi): void set_relay_malfunction(bool c); bool get_relay_malfunction(void); bool get_gas_pressed_prev(void); + void set_gas_pressed_prev(bool); bool get_brake_pressed_prev(void); bool get_regen_braking_prev(void); bool get_acc_main_on(void); @@ -61,6 +62,7 @@ def get_alternative_experience(self) -> int: ... def set_relay_malfunction(self, c: bool) -> None: ... def get_relay_malfunction(self) -> bool: ... def get_gas_pressed_prev(self) -> bool: ... + def set_gas_pressed_prev(self, c: bool) -> None: ... def get_brake_pressed_prev(self) -> bool: ... def get_regen_braking_prev(self) -> bool: ... def get_acc_main_on(self) -> bool: ... diff --git a/panda/tests/loopback_test.py b/panda/tests/loopback_test.py index a95c2ea2285f6de..2b6eb530851c240 100755 --- a/panda/tests/loopback_test.py +++ b/panda/tests/loopback_test.py @@ -69,13 +69,13 @@ def run_test_w_pandas(pandas, sleep_duration): assert cans_echo[0][0] == at assert cans_loop[0][0] == at - assert cans_echo[0][2] == st - assert cans_loop[0][2] == st + assert cans_echo[0][1] == st + assert cans_loop[0][1] == st - assert cans_echo[0][3] == 0x80 | bus - if cans_loop[0][3] != bus: - print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3])) - assert cans_loop[0][3] == bus + assert cans_echo[0][2] == 0x80 | bus + if cans_loop[0][2] != bus: + print("EXPECTED %d GOT %d" % (bus, cans_loop[0][2])) + assert cans_loop[0][2] == bus print("CAN pass", bus, ho) time.sleep(sleep_duration) diff --git a/panda/tests/message_drop_test.py b/panda/tests/message_drop_test.py index bf485e454528c96..a131a9c914423b0 100755 --- a/panda/tests/message_drop_test.py +++ b/panda/tests/message_drop_test.py @@ -16,7 +16,7 @@ # Generate unique messages NUM_MESSAGES_PER_BUS = 10000 messages = [bytes(struct.pack("Q", i)) for i in range(NUM_MESSAGES_PER_BUS)] -tx_messages = list(itertools.chain.from_iterable([[0xaa, None, msg, 0], [0xaa, None, msg, 1], [0xaa, None, msg, 2]] for msg in messages)) +tx_messages = list(itertools.chain.from_iterable([[0xaa, msg, 0], [0xaa, msg, 1], [0xaa, msg, 2]] for msg in messages)) def flood_tx(panda): print('Sending!') @@ -65,6 +65,6 @@ def flood_tx(panda): # Check if we received everything for bus in range(3): - received_msgs = {bytes(m[2]) for m in filter(lambda m, b=bus: m[3] == b, rx)} # type: ignore + received_msgs = {bytes(m[1]) for m in filter(lambda m, b=bus: m[2] == b, rx)} # type: ignore dropped_msgs = set(messages).difference(received_msgs) print(f"Bus {bus} dropped msgs: {len(list(dropped_msgs))} / {len(messages)}") diff --git a/panda/tests/misra/checkers.txt b/panda/tests/misra/checkers.txt index a9cc72173c9560c..00160a5baff1a26 100644 --- a/panda/tests/misra/checkers.txt +++ b/panda/tests/misra/checkers.txt @@ -146,6 +146,7 @@ Yes CheckOther::clarifyCalculation Yes CheckOther::clarifyStatement Yes CheckOther::invalidPointerCast Yes CheckOther::redundantBitwiseOperationInSwitch +Yes CheckOther::suspiciousFloatingPointCast No CheckOther::warningOldStylePointerCast require:style,c++ No CheckPostfixOperator::postfixOperator require:performance Yes CheckSizeof::checkSizeofForArrayParameter @@ -222,11 +223,32 @@ Not available, Cppcheck Premium is not used Misra C 2012 ------------ +No Misra C 2012: Dir 1.1 +No Misra C 2012: Dir 2.1 +No Misra C 2012: Dir 3.1 +No Misra C 2012: Dir 4.1 +No Misra C 2012: Dir 4.2 +No Misra C 2012: Dir 4.3 +No Misra C 2012: Dir 4.4 +No Misra C 2012: Dir 4.5 +No Misra C 2012: Dir 4.6 amendment:3 +No Misra C 2012: Dir 4.7 +No Misra C 2012: Dir 4.8 +No Misra C 2012: Dir 4.9 amendment:3 +No Misra C 2012: Dir 4.10 +No Misra C 2012: Dir 4.11 amendment:3 +No Misra C 2012: Dir 4.12 +No Misra C 2012: Dir 4.13 +No Misra C 2012: Dir 4.14 amendment:2 +No Misra C 2012: Dir 4.15 amendment:3 +No Misra C 2012: Dir 5.1 amendment:4 +No Misra C 2012: Dir 5.2 amendment:4 +No Misra C 2012: Dir 5.3 amendment:4 Yes Misra C 2012: 1.1 Yes Misra C 2012: 1.2 Yes Misra C 2012: 1.3 -Yes Misra C 2012: 1.4 amendment:2 -No Misra C 2012: 1.5 amendment:3 require:premium +Yes Misra C 2012: 1.4 amendment:2 +No Misra C 2012: 1.5 amendment:3 require:premium Yes Misra C 2012: 2.1 Yes Misra C 2012: 2.2 Yes Misra C 2012: 2.3 @@ -303,8 +325,8 @@ Yes Misra C 2012: 12.1 Yes Misra C 2012: 12.2 Yes Misra C 2012: 12.3 Yes Misra C 2012: 12.4 -Yes Misra C 2012: 12.5 amendment:1 -No Misra C 2012: 12.6 amendment:4 require:premium +Yes Misra C 2012: 12.5 amendment:1 +No Misra C 2012: 12.6 amendment:4 require:premium Yes Misra C 2012: 13.1 No Misra C 2012: 13.2 Yes Misra C 2012: 13.3 @@ -380,48 +402,48 @@ Yes Misra C 2012: 21.9 Yes Misra C 2012: 21.10 Yes Misra C 2012: 21.11 Yes Misra C 2012: 21.12 -Yes Misra C 2012: 21.13 amendment:1 -Yes Misra C 2012: 21.14 amendment:1 -Yes Misra C 2012: 21.15 amendment:1 -Yes Misra C 2012: 21.16 amendment:1 -Yes Misra C 2012: 21.17 amendment:1 -Yes Misra C 2012: 21.18 amendment:1 -Yes Misra C 2012: 21.19 amendment:1 -Yes Misra C 2012: 21.20 amendment:1 -Yes Misra C 2012: 21.21 amendment:3 -No Misra C 2012: 21.22 amendment:3 require:premium -No Misra C 2012: 21.23 amendment:3 require:premium -No Misra C 2012: 21.24 amendment:3 require:premium -No Misra C 2012: 21.25 amendment:4 require:premium -No Misra C 2012: 21.26 amendment:4 require:premium +Yes Misra C 2012: 21.13 amendment:1 +Yes Misra C 2012: 21.14 amendment:1 +Yes Misra C 2012: 21.15 amendment:1 +Yes Misra C 2012: 21.16 amendment:1 +Yes Misra C 2012: 21.17 amendment:1 +Yes Misra C 2012: 21.18 amendment:1 +Yes Misra C 2012: 21.19 amendment:1 +Yes Misra C 2012: 21.20 amendment:1 +Yes Misra C 2012: 21.21 amendment:3 +No Misra C 2012: 21.22 amendment:3 require:premium +No Misra C 2012: 21.23 amendment:3 require:premium +No Misra C 2012: 21.24 amendment:3 require:premium +No Misra C 2012: 21.25 amendment:4 require:premium +No Misra C 2012: 21.26 amendment:4 require:premium Yes Misra C 2012: 22.1 Yes Misra C 2012: 22.2 Yes Misra C 2012: 22.3 Yes Misra C 2012: 22.4 Yes Misra C 2012: 22.5 Yes Misra C 2012: 22.6 -Yes Misra C 2012: 22.7 amendment:1 -Yes Misra C 2012: 22.8 amendment:1 -Yes Misra C 2012: 22.9 amendment:1 -Yes Misra C 2012: 22.10 amendment:1 -No Misra C 2012: 22.11 amendment:4 require:premium -No Misra C 2012: 22.12 amendment:4 require:premium -No Misra C 2012: 22.13 amendment:4 require:premium -No Misra C 2012: 22.14 amendment:4 require:premium -No Misra C 2012: 22.15 amendment:4 require:premium -No Misra C 2012: 22.16 amendment:4 require:premium -No Misra C 2012: 22.17 amendment:4 require:premium -No Misra C 2012: 22.18 amendment:4 require:premium -No Misra C 2012: 22.19 amendment:4 require:premium -No Misra C 2012: 22.20 amendment:4 require:premium -No Misra C 2012: 23.1 amendment:3 require:premium -No Misra C 2012: 23.2 amendment:3 require:premium -No Misra C 2012: 23.3 amendment:3 require:premium -No Misra C 2012: 23.4 amendment:3 require:premium -No Misra C 2012: 23.5 amendment:3 require:premium -No Misra C 2012: 23.6 amendment:3 require:premium -No Misra C 2012: 23.7 amendment:3 require:premium -No Misra C 2012: 23.8 amendment:3 require:premium +Yes Misra C 2012: 22.7 amendment:1 +Yes Misra C 2012: 22.8 amendment:1 +Yes Misra C 2012: 22.9 amendment:1 +Yes Misra C 2012: 22.10 amendment:1 +No Misra C 2012: 22.11 amendment:4 require:premium +No Misra C 2012: 22.12 amendment:4 require:premium +No Misra C 2012: 22.13 amendment:4 require:premium +No Misra C 2012: 22.14 amendment:4 require:premium +No Misra C 2012: 22.15 amendment:4 require:premium +No Misra C 2012: 22.16 amendment:4 require:premium +No Misra C 2012: 22.17 amendment:4 require:premium +No Misra C 2012: 22.18 amendment:4 require:premium +No Misra C 2012: 22.19 amendment:4 require:premium +No Misra C 2012: 22.20 amendment:4 require:premium +No Misra C 2012: 23.1 amendment:3 require:premium +No Misra C 2012: 23.2 amendment:3 require:premium +No Misra C 2012: 23.3 amendment:3 require:premium +No Misra C 2012: 23.4 amendment:3 require:premium +No Misra C 2012: 23.5 amendment:3 require:premium +No Misra C 2012: 23.6 amendment:3 require:premium +No Misra C 2012: 23.7 amendment:3 require:premium +No Misra C 2012: 23.8 amendment:3 require:premium Misra C++ 2008 @@ -579,6 +601,7 @@ Yes CheckOther::clarifyCalculation Yes CheckOther::clarifyStatement Yes CheckOther::invalidPointerCast Yes CheckOther::redundantBitwiseOperationInSwitch +Yes CheckOther::suspiciousFloatingPointCast No CheckOther::warningOldStylePointerCast require:style,c++ No CheckPostfixOperator::postfixOperator require:performance Yes CheckSizeof::checkSizeofForArrayParameter @@ -655,11 +678,32 @@ Not available, Cppcheck Premium is not used Misra C 2012 ------------ +No Misra C 2012: Dir 1.1 +No Misra C 2012: Dir 2.1 +No Misra C 2012: Dir 3.1 +No Misra C 2012: Dir 4.1 +No Misra C 2012: Dir 4.2 +No Misra C 2012: Dir 4.3 +No Misra C 2012: Dir 4.4 +No Misra C 2012: Dir 4.5 +No Misra C 2012: Dir 4.6 amendment:3 +No Misra C 2012: Dir 4.7 +No Misra C 2012: Dir 4.8 +No Misra C 2012: Dir 4.9 amendment:3 +No Misra C 2012: Dir 4.10 +No Misra C 2012: Dir 4.11 amendment:3 +No Misra C 2012: Dir 4.12 +No Misra C 2012: Dir 4.13 +No Misra C 2012: Dir 4.14 amendment:2 +No Misra C 2012: Dir 4.15 amendment:3 +No Misra C 2012: Dir 5.1 amendment:4 +No Misra C 2012: Dir 5.2 amendment:4 +No Misra C 2012: Dir 5.3 amendment:4 Yes Misra C 2012: 1.1 Yes Misra C 2012: 1.2 Yes Misra C 2012: 1.3 -Yes Misra C 2012: 1.4 amendment:2 -No Misra C 2012: 1.5 amendment:3 require:premium +Yes Misra C 2012: 1.4 amendment:2 +No Misra C 2012: 1.5 amendment:3 require:premium Yes Misra C 2012: 2.1 Yes Misra C 2012: 2.2 Yes Misra C 2012: 2.3 @@ -736,8 +780,8 @@ Yes Misra C 2012: 12.1 Yes Misra C 2012: 12.2 Yes Misra C 2012: 12.3 Yes Misra C 2012: 12.4 -Yes Misra C 2012: 12.5 amendment:1 -No Misra C 2012: 12.6 amendment:4 require:premium +Yes Misra C 2012: 12.5 amendment:1 +No Misra C 2012: 12.6 amendment:4 require:premium Yes Misra C 2012: 13.1 No Misra C 2012: 13.2 Yes Misra C 2012: 13.3 @@ -813,48 +857,48 @@ Yes Misra C 2012: 21.9 Yes Misra C 2012: 21.10 Yes Misra C 2012: 21.11 Yes Misra C 2012: 21.12 -Yes Misra C 2012: 21.13 amendment:1 -Yes Misra C 2012: 21.14 amendment:1 -Yes Misra C 2012: 21.15 amendment:1 -Yes Misra C 2012: 21.16 amendment:1 -Yes Misra C 2012: 21.17 amendment:1 -Yes Misra C 2012: 21.18 amendment:1 -Yes Misra C 2012: 21.19 amendment:1 -Yes Misra C 2012: 21.20 amendment:1 -Yes Misra C 2012: 21.21 amendment:3 -No Misra C 2012: 21.22 amendment:3 require:premium -No Misra C 2012: 21.23 amendment:3 require:premium -No Misra C 2012: 21.24 amendment:3 require:premium -No Misra C 2012: 21.25 amendment:4 require:premium -No Misra C 2012: 21.26 amendment:4 require:premium +Yes Misra C 2012: 21.13 amendment:1 +Yes Misra C 2012: 21.14 amendment:1 +Yes Misra C 2012: 21.15 amendment:1 +Yes Misra C 2012: 21.16 amendment:1 +Yes Misra C 2012: 21.17 amendment:1 +Yes Misra C 2012: 21.18 amendment:1 +Yes Misra C 2012: 21.19 amendment:1 +Yes Misra C 2012: 21.20 amendment:1 +Yes Misra C 2012: 21.21 amendment:3 +No Misra C 2012: 21.22 amendment:3 require:premium +No Misra C 2012: 21.23 amendment:3 require:premium +No Misra C 2012: 21.24 amendment:3 require:premium +No Misra C 2012: 21.25 amendment:4 require:premium +No Misra C 2012: 21.26 amendment:4 require:premium Yes Misra C 2012: 22.1 Yes Misra C 2012: 22.2 Yes Misra C 2012: 22.3 Yes Misra C 2012: 22.4 Yes Misra C 2012: 22.5 Yes Misra C 2012: 22.6 -Yes Misra C 2012: 22.7 amendment:1 -Yes Misra C 2012: 22.8 amendment:1 -Yes Misra C 2012: 22.9 amendment:1 -Yes Misra C 2012: 22.10 amendment:1 -No Misra C 2012: 22.11 amendment:4 require:premium -No Misra C 2012: 22.12 amendment:4 require:premium -No Misra C 2012: 22.13 amendment:4 require:premium -No Misra C 2012: 22.14 amendment:4 require:premium -No Misra C 2012: 22.15 amendment:4 require:premium -No Misra C 2012: 22.16 amendment:4 require:premium -No Misra C 2012: 22.17 amendment:4 require:premium -No Misra C 2012: 22.18 amendment:4 require:premium -No Misra C 2012: 22.19 amendment:4 require:premium -No Misra C 2012: 22.20 amendment:4 require:premium -No Misra C 2012: 23.1 amendment:3 require:premium -No Misra C 2012: 23.2 amendment:3 require:premium -No Misra C 2012: 23.3 amendment:3 require:premium -No Misra C 2012: 23.4 amendment:3 require:premium -No Misra C 2012: 23.5 amendment:3 require:premium -No Misra C 2012: 23.6 amendment:3 require:premium -No Misra C 2012: 23.7 amendment:3 require:premium -No Misra C 2012: 23.8 amendment:3 require:premium +Yes Misra C 2012: 22.7 amendment:1 +Yes Misra C 2012: 22.8 amendment:1 +Yes Misra C 2012: 22.9 amendment:1 +Yes Misra C 2012: 22.10 amendment:1 +No Misra C 2012: 22.11 amendment:4 require:premium +No Misra C 2012: 22.12 amendment:4 require:premium +No Misra C 2012: 22.13 amendment:4 require:premium +No Misra C 2012: 22.14 amendment:4 require:premium +No Misra C 2012: 22.15 amendment:4 require:premium +No Misra C 2012: 22.16 amendment:4 require:premium +No Misra C 2012: 22.17 amendment:4 require:premium +No Misra C 2012: 22.18 amendment:4 require:premium +No Misra C 2012: 22.19 amendment:4 require:premium +No Misra C 2012: 22.20 amendment:4 require:premium +No Misra C 2012: 23.1 amendment:3 require:premium +No Misra C 2012: 23.2 amendment:3 require:premium +No Misra C 2012: 23.3 amendment:3 require:premium +No Misra C 2012: 23.4 amendment:3 require:premium +No Misra C 2012: 23.5 amendment:3 require:premium +No Misra C 2012: 23.6 amendment:3 require:premium +No Misra C 2012: 23.7 amendment:3 require:premium +No Misra C 2012: 23.8 amendment:3 require:premium Misra C++ 2008 diff --git a/panda/tests/misra/install.sh b/panda/tests/misra/install.sh index e0a743b72e49723..c1fdbe838349cf4 100755 --- a/panda/tests/misra/install.sh +++ b/panda/tests/misra/install.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" @@ -10,7 +10,7 @@ fi cd $CPPCHECK_DIR -VERS="2.14.1" +VERS="2.15.0" git fetch --all --tags --force git checkout $VERS diff --git a/panda/tests/misra/suppressions.txt b/panda/tests/misra/suppressions.txt index 5c0b953b5100c18..4800a270bcb266e 100644 --- a/panda/tests/misra/suppressions.txt +++ b/panda/tests/misra/suppressions.txt @@ -19,9 +19,3 @@ unusedFunction:*/interrupt_handlers*.h # cppcheck from 2.5 -> 2.13. they are listed here to separate the update from # fixing the violations and all are intended to be removed soon after misra-c2012-2.5 # unused macros. a few legit, rest aren't common between F4/H7 builds. should we do this in the unusedFunction pass? -misra-c2012-8.7 -misra-c2012-8.4 -misra-c2012-21.15 - -# FIXME: violations are in ST's F4 headers -misra-c2012-12.2 diff --git a/panda/tests/misra/test_misra.sh b/panda/tests/misra/test_misra.sh index e65f6a5e5ab2089..c35ed02a131a5bc 100755 --- a/panda/tests/misra/test_misra.sh +++ b/panda/tests/misra/test_misra.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" @@ -19,7 +19,7 @@ fi # ensure checked in coverage table is up to date cd $DIR if [ -z "$SKIP_TABLES_DIFF" ]; then - python $CPPCHECK_DIR/addons/misra.py -generate-table > coverage_table + python3 $CPPCHECK_DIR/addons/misra.py -generate-table > coverage_table if ! git diff --quiet coverage_table; then echo -e "${YELLOW}MISRA coverage table doesn't match. Update and commit:${NC}" exit 3 @@ -48,10 +48,10 @@ cppcheck() { -I "$(arm-none-eabi-gcc -print-file-name=include)" \ -I $PANDA_DIR/board/stm32f4/inc/ -I $PANDA_DIR/board/stm32h7/inc/ \ --suppressions-list=$DIR/suppressions.txt --suppress=*:*inc/* \ - --suppress=*:*include/* --error-exitcode=2 --check-level=exhaustive \ + --suppress=*:*include/* --error-exitcode=2 --check-level=exhaustive --safety \ --platform=arm32-wchar_t4 $COMMON_DEFINES --checkers-report=$CHECKLIST.tmp \ --std=c11 "$@" |& tee $OUTPUT - + cat $CHECKLIST.tmp >> $CHECKLIST rm $CHECKLIST.tmp # cppcheck bug: some MISRA errors won't result in the error exit code, diff --git a/panda/tests/read_st_flash.sh b/panda/tests/read_st_flash.sh index ffcfd7bbfe725b6..65b0709f6cd46ea 100755 --- a/panda/tests/read_st_flash.sh +++ b/panda/tests/read_st_flash.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash rm -f /tmp/dump_bootstub rm -f /tmp/dump_main dfu-util -a 0 -s 0x08000000 -U /tmp/dump_bootstub diff --git a/panda/tests/setup_device_ci.sh b/panda/tests/setup_device_ci.sh index b45c6b466b2c586..a74ce7a2c998688 100755 --- a/panda/tests/setup_device_ci.sh +++ b/panda/tests/setup_device_ci.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e @@ -19,7 +19,7 @@ fi CONTINUE_PATH="/data/continue.sh" tee $CONTINUE_PATH << EOF -#!/usr/bin/bash +#!/usr/bin/env bash sudo abctl --set_success diff --git a/panda/tests/som_debug.sh b/panda/tests/som_debug.sh index 9bb4219713e9072..6f0a86537c4ec8b 100755 --- a/panda/tests/som_debug.sh +++ b/panda/tests/som_debug.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/panda/tests/usbprotocol/test.sh b/panda/tests/usbprotocol/test.sh index 8e3886da7d54d22..b4c32166b988496 100755 --- a/panda/tests/usbprotocol/test.sh +++ b/panda/tests/usbprotocol/test.sh @@ -4,5 +4,5 @@ set -e # Loops over all HW_TYPEs, see board/boards/board_declarations.h for hw_type in {0..7}; do echo "Testing HW_TYPE: $hw_type" - HW_TYPE=$hw_type python -m unittest discover . + HW_TYPE=$hw_type python3 -m unittest discover . done diff --git a/panda/tests/usbprotocol/test_comms.py b/panda/tests/usbprotocol/test_comms.py index 8efefef7ca75b2e..e649bdaeabf515e 100755 --- a/panda/tests/usbprotocol/test_comms.py +++ b/panda/tests/usbprotocol/test_comms.py @@ -14,7 +14,7 @@ def unpackage_can_msg(pkt): dat_len = DLC_TO_LEN[pkt[0].data_len_code] dat = bytes(pkt[0].data[0:dat_len]) - return pkt[0].addr, 0, dat, pkt[0].bus + return pkt[0].addr, dat, pkt[0].bus def random_can_messages(n, bus=None): @@ -24,7 +24,7 @@ def random_can_messages(n, bus=None): bus = random.randint(0, 3) address = random.randint(1, (1 << 29) - 1) data = bytes([random.getrandbits(8) for _ in range(DLC_TO_LEN[random.randrange(0, len(DLC_TO_LEN))])]) - msgs.append((address, 0, data, bus)) + msgs.append((address, data, bus)) return msgs @@ -34,9 +34,9 @@ def setUp(self): def test_tx_queues(self): for bus in range(len(TX_QUEUES)): - message = (0x100, 0, b"test", bus) + message = (0x100, b"test", bus) - can_pkt_tx = libpanda_py.make_CANPacket(message[0], message[3], message[2]) + can_pkt_tx = libpanda_py.make_CANPacket(message[0], message[2], message[1]) can_pkt_rx = libpanda_py.ffi.new('CANPacket_t *') assert lpp.can_push(TX_QUEUES[bus], can_pkt_tx), "CAN push failed" @@ -46,9 +46,9 @@ def test_tx_queues(self): def test_comms_reset_rx(self): # store some test messages in the queue - test_msg = (0x100, 0, b"test", 0) + test_msg = (0x100, b"test", 0) for _ in range(100): - can_pkt_tx = libpanda_py.make_CANPacket(test_msg[0], test_msg[3], test_msg[2]) + can_pkt_tx = libpanda_py.make_CANPacket(test_msg[0], test_msg[2], test_msg[1]) lpp.can_push(lpp.rx_q, can_pkt_tx) # read a small chunk such that we have some overflow @@ -76,7 +76,7 @@ def test_comms_reset_rx(self): def test_comms_reset_tx(self): # store some test messages in the queue - test_msg = (0x100, 0, b"test", 0) + test_msg = (0x100, b"test", 0) packed = pack_can_buffer([test_msg for _ in range(100)]) # write a small chunk such that we have some overflow @@ -126,7 +126,7 @@ def test_can_send_usb(self): def test_can_receive_usb(self): msgs = random_can_messages(50000) - packets = [libpanda_py.make_CANPacket(m[0], m[3], m[2]) for m in msgs] + packets = [libpanda_py.make_CANPacket(m[0], m[2], m[1]) for m in msgs] rx_msgs = [] overflow_buf = b"" diff --git a/panda/tests/usbprotocol/test_pandalib.py b/panda/tests/usbprotocol/test_pandalib.py index c03f246f318e4a1..ef725948c795804 100755 --- a/panda/tests/usbprotocol/test_pandalib.py +++ b/panda/tests/usbprotocol/test_pandalib.py @@ -12,7 +12,7 @@ def test_panda_lib_pack_unpack(self): for _ in range(10000): address = random.randint(1, (1 << 29) - 1) data = bytes([random.getrandbits(8) for _ in range(DLC_TO_LEN[random.randrange(0, len(DLC_TO_LEN))])]) - to_pack.append((address, 0, data, 0)) + to_pack.append((address, data, 0)) packed = pack_can_buffer(to_pack) unpacked = [] diff --git a/pyproject.toml b/pyproject.toml index 007245540f88901..c27ebcdb4fae7ef 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,18 +1,146 @@ [project] name = "openpilot" -requires-python = ">= 3.11" -readme = "README.md" +requires-python = ">= 3.11, <= 3.12" license = {text = "MIT License"} +version = "0.1.0" +description = "an open source driver assistance system" +authors = [ + {name ="Vehicle Researcher", email="user@comma.ai"} +] + +dependencies = [ + # multiple users + "sounddevice", # micd + soundd + "pyserial", # pigeond + qcomgpsd + "requests", # many one-off uses + "sympy", # rednose + friends + "crcmod", # cars + qcomgpsd + "tqdm", # cars (fw_versions.py) on start + many one-off uses + + # hardwared + "smbus2", # configuring amp + + # core + "cffi", + "scons", + "pycapnp", + "Cython", + "setuptools", + "numpy < 2.0.0", + + # body / webrtcd + "aiohttp", + "aiortc", + "pyaudio", + + # panda + "libusb1", + "spidev; platform_system == 'Linux'", + + # modeld + "onnx >= 1.14.0", + "onnxruntime >=1.16.3; platform_system == 'Linux' and platform_machine == 'aarch64'", + "onnxruntime-gpu >=1.16.3; platform_system == 'Linux' and platform_machine == 'x86_64'", + + # logging + "pyzmq", + "sentry-sdk", + + # athena + "PyJWT", + "json-rpc", + "websocket_client", + + # acados deps + "casadi >=3.6.6", # 3.12 fixed in 3.6.6 + "future-fstrings", + + # joystickd + "inputs", + + # these should be removed + "psutil", + "pycryptodome", # used in updated/casync, panda, body, and a test + "setproctitle", + + # logreader + "zstandard", +] + +[project.optional-dependencies] +docs = [ + "Jinja2", + "natsort", + "mkdocs", +] + +testing = [ + "coverage", + "hypothesis ==6.47.*", + "mypy", + "pytest", + "pytest-cov", + "pytest-cpp", + "pytest-subtests", + "pytest-xdist", + "pytest-timeout", + "pytest-randomly", + "pytest-asyncio", + "pytest-mock", + "pytest-repeat", + "ruff", + "codespell", + "pre-commit-hooks", +] + +dev = [ + "av", + "azure-identity", + "azure-storage-blob", + "dictdiffer", + "flaky", + "lru-dict", + "matplotlib", + "parameterized >=0.8, <0.9", + #"pprofile", + "pyautogui", + "pyopencl; platform_machine != 'aarch64'", # broken on arm64 + "pytools < 2024.1.11; platform_machine != 'aarch64'", # pyopencl use a broken version + "pywinctl", + "pyprof2calltree", + "tabulate", + "types-requests", + "types-tabulate", + + # this is only pinned since 5.15.11 is broken + "pyqt5 ==5.15.2; platform_machine == 'x86_64'", # no aarch64 wheels for macOS/linux +] + +tools = [ + "metadrive-simulator @ https://github.com/commaai/metadrive/releases/download/MetaDrive-minimal/metadrive_simulator-0.4.2.3-py3-none-any.whl ; (platform_machine != 'aarch64')", + "rerun-sdk >= 0.18", +] [project.urls] Homepage = "https://comma.ai" +[build-system] +requires = ["hatchling"] +build-backend = "hatchling.build" + +[tool.hatch.build.targets.wheel] +packages = [ "." ] + +[tool.hatch.metadata] +allow-direct-references = true + [tool.pytest.ini_options] minversion = "6.0" -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" +addopts = "--ignore=openpilot/ --ignore=opendbc/ --ignore=panda/ --ignore=rednose_repo/ --ignore=tinygrad_repo/ --ignore=teleoprtc_repo/ --ignore=msgq/ -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" +asyncio_default_fixture_loop_scope = "function" #timeout = "30" # you get this long by default markers = [ "slow: tests that take awhile to run and can be skipped with -m 'not slow'", @@ -20,14 +148,7 @@ markers = [ ] testpaths = [ "common", - "selfdrive/pandad", - "selfdrive/car", - "selfdrive/controls", - "selfdrive/locationd", - "selfdrive/monitoring", - "selfdrive/navd/tests", - "selfdrive/test/longitudinal_maneuvers", - "selfdrive/test/process_replay/test_fuzzy.py", + "selfdrive", "system/updated", "system/athena", "system/camerad", @@ -43,15 +164,24 @@ testpaths = [ "cereal/messaging/tests", ] +[tool.codespell] +quiet-level = 3 +# if you've got a short variable name that's getting flagged, add it here +ignore-words-list = "bu,ro,te,ue,alo,hda,ois,nam,nams,ned,som,parm,setts,inout,warmup,bumb,nd,sie,preints,whit,indexIn,ws,uint,grey,deque,stdio,amin,BA,LITE,atEnd,UIs,errorString,arange,FocusIn,od,tim,relA,hist,copyable,jupyter,thead" +builtin = "clear,rare,informal,code,names,en-GB_to_en-US" +skip = "./third_party/*, ./tinygrad/*, ./tinygrad_repo/*, ./msgq/*, ./panda/*, ./opendbc/*, ./opendbc_repo/*, ./rednose/*, ./rednose_repo/*, ./teleoprtc/*, ./teleoprtc_repo/*, *.ts, uv.lock, *.onnx, ./cereal/gen/*, */c_generated_code/*" + [tool.mypy] python_version = "3.11" plugins = [ "numpy.typing.mypy_plugin", ] exclude = [ - "body/", "cereal/", + "msgq/", + "msgq_repo/", "opendbc/", + "opendbc_repo/", "panda/", "rednose/", "rednose_repo/", @@ -76,127 +206,9 @@ warn_return_any=true # allow implicit optionals for default args implicit_optional = true - -[tool.poetry] -name = "openpilot" -version = "0.1.0" -description = "an open source driver assistance system" -authors = ["Vehicle Researcher "] -license = "MIT" -readme = "README.md" -repository = "https://github.com/commaai/openpilot" -documentation = "https://docs.comma.ai" - -[tool.poetry.dependencies] -python = "~3.11" - -# multiple users -sounddevice = "*" # micd + soundd -pyserial = "*" # pigeond + qcomgpsd -requests = "*" # many one-off uses -sympy = "*" # rednose + friends -crcmod = "*" # cars + qcomgpsd - -# hardwared -smbus2 = "*" # configuring amp - -# core -cffi = "*" -scons = "*" -pycapnp = "*" -Cython = "*" -numpy = "*" - -# body / webrtcd -aiohttp = "*" -aiortc = "*" -pyaudio = "*" - -# panda -libusb1 = "*" -spidev = { version = "*", platform = "linux" } - -# modeld -onnx = ">=1.14.0" -onnxruntime = { version = ">=1.16.3", platform = "linux", markers = "platform_machine == 'aarch64'" } -onnxruntime-gpu = { version = ">=1.16.3", platform = "linux", markers = "platform_machine == 'x86_64'" } - -# logging -pyzmq = "*" -sentry-sdk = "*" - -# athena -PyJWT = "*" -json-rpc = "*" -websocket_client = "*" - -# acados deps -casadi = "*" -future-fstrings = "*" - -# these should be removed -psutil = "*" -timezonefinder = "*" # just used for nav ETA -setproctitle = "*" -pycryptodome = "*" # used in updated/casync, panda, body, and a test - -[tool.poetry.group.dev.dependencies] -av = "*" -azure-identity = "*" -azure-storage-blob = "*" -breathe = "*" -control = "*" -coverage = "*" -dictdiffer = "*" -flaky = "*" -hypothesis = "~6.47" -inputs = "*" -Jinja2 = "*" -lru-dict = "*" -matplotlib = "*" -# No release for this fix https://github.com/metadriverse/metadrive/issues/632. Pinned to this commit until next release -metadrive-simulator = {git = "https://github.com/metadriverse/metadrive.git", rev ="233a3a1698be7038ec3dd050ca10b547b4b3324c", markers = "platform_machine != 'aarch64'" } # no linux/aarch64 wheels for certain dependencies -mpld3 = "*" -mypy = "*" -myst-parser = "*" -natsort = "*" -opencv-python-headless = "*" -parameterized = "^0.8" -pprofile = "*" -polyline = "*" -pre-commit = "*" -pyautogui = "*" -pytools = "<=2024.1.3" # our pinned version of pyopencl use a broken version of pytools -pyopencl = "==2023.1.4" # 2024.1 is broken on arm64 -pygame = "*" -pywinctl = "*" -pyprof2calltree = "*" -pytest = "*" -pytest-cov = "*" -pytest-cpp = "*" -pytest-subtests = "*" -pytest-xdist = "*" -pytest-timeout = "*" -pytest-randomly = "*" -pytest-asyncio = "*" -pytest-mock = "*" -pytest-repeat = "*" -rerun-sdk = "*" -ruff = "*" -sphinx = "*" -sphinx-rtd-theme = "*" -sphinx-sitemap = "*" -tabulate = "*" -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 - -[build-system] -requires = ["poetry-core"] -build-backend = "poetry.core.masonry.api" +local_partial_types=true +explicit_package_bases=true +disable_error_code = "annotation-unchecked" # https://beta.ruff.rs/docs/configuration/#using-pyprojecttoml [tool.ruff] @@ -207,7 +219,8 @@ lint.select = [ "UP", # pyupgrade "TRY302", "TRY400", "TRY401", # try/excepts "RUF008", "RUF100", - "TID251" + "TID251", + "PLR1704", ] lint.ignore = [ "E741", @@ -220,7 +233,7 @@ lint.ignore = [ "UP038", # (x, y) -> x|y for isinstance ] line-length = 160 -target-version="py311" +target-version ="py311" exclude = [ "body", "cereal", @@ -231,8 +244,10 @@ exclude = [ "teleoprtc", "teleoprtc_repo", "third_party", + "*.ipynb", ] -lint.flake8-implicit-str-concat.allow-multiline=false +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" @@ -244,5 +259,6 @@ lint.flake8-implicit-str-concat.allow-multiline=false [tool.coverage.run] concurrency = ["multiprocessing", "thread"] + [tool.ruff.format] quote-style = "preserve" diff --git a/rednose_repo/examples/test_compare.py b/rednose_repo/examples/test_compare.py index 0b2cdd3e6acd647..291f29e826f9bef 100755 --- a/rednose_repo/examples/test_compare.py +++ b/rednose_repo/examples/test_compare.py @@ -1,9 +1,9 @@ #!/usr/bin/env python3 +import pytest import os import sys import sympy as sp import numpy as np -import unittest if __name__ == '__main__': # generating sympy code from rednose.helpers.ekf_sym import gen_code @@ -83,7 +83,7 @@ def get_R(self, kind, n): return R -class TestCompare(unittest.TestCase): +class TestCompare: def test_compare(self): np.random.seed(0) @@ -115,9 +115,9 @@ def test_compare(self): kf.filter_py.predict_and_update_batch(t, ObservationKind.POSITION, z, R) kf.filter_pyx.predict_and_update_batch(t, ObservationKind.POSITION, z, R) - self.assertAlmostEqual(kf.filter_py.get_filter_time(), kf.filter_pyx.get_filter_time()) - self.assertTrue(np.allclose(kf.filter_py.state(), kf.filter_pyx.state())) - self.assertTrue(np.allclose(kf.filter_py.covs(), kf.filter_pyx.covs())) + assert kf.filter_py.get_filter_time() == pytest.approx(kf.filter_pyx.get_filter_time()) + assert np.allclose(kf.filter_py.state(), kf.filter_pyx.state()) + assert np.allclose(kf.filter_py.covs(), kf.filter_pyx.covs()) if __name__ == "__main__": diff --git a/rednose_repo/examples/test_kinematic_kf.py b/rednose_repo/examples/test_kinematic_kf.py index 749eaf04f4737c7..05d4d3efd0b7968 100644 --- a/rednose_repo/examples/test_kinematic_kf.py +++ b/rednose_repo/examples/test_kinematic_kf.py @@ -1,12 +1,12 @@ +import pytest import os import numpy as np -import unittest -from kinematic_kf import KinematicKalman, ObservationKind, States # pylint: disable=import-error +from .kinematic_kf import KinematicKalman, ObservationKind, States GENERATED_DIR = os.path.abspath(os.path.join(os.path.dirname(__file__), 'generated')) -class TestKinematic(unittest.TestCase): +class TestKinematic: def test_kinematic_kf(self): np.random.seed(0) @@ -49,10 +49,10 @@ def test_kinematic_kf(self): xs, xs_meas, xs_kf, vs_kf, xs_kf_std, vs_kf_std = (np.asarray(a) for a in (xs, xs_meas, xs_kf, vs_kf, xs_kf_std, vs_kf_std)) - self.assertAlmostEqual(xs_kf[-1], -0.010866289677966417) - self.assertAlmostEqual(xs_kf_std[-1], 0.04477103863330089) - self.assertAlmostEqual(vs_kf[-1], -0.8553720537261753) - self.assertAlmostEqual(vs_kf_std[-1], 0.6695762270974388) + assert xs_kf[-1] == pytest.approx(-0.010866289677966417) + assert xs_kf_std[-1] == pytest.approx(0.04477103863330089) + assert vs_kf[-1] == pytest.approx(-0.8553720537261753) + assert vs_kf_std[-1] == pytest.approx(0.6695762270974388) if "PLOT" in os.environ: import matplotlib.pyplot as plt # pylint: disable=import-error @@ -80,7 +80,3 @@ def test_kinematic_kf(self): plt.legend() plt.show() - - -if __name__ == "__main__": - unittest.main() diff --git a/rednose_repo/pyproject.toml b/rednose_repo/pyproject.toml index b417c708cfbb5f1..fa6ae11d1c11967 100644 --- a/rednose_repo/pyproject.toml +++ b/rednose_repo/pyproject.toml @@ -7,3 +7,10 @@ target-version="py311" select = ["E", "F", "W", "PIE", "C4", "ISC", "RUF100", "A"] ignore = ["W292", "E741", "E402", "C408", "ISC003"] flake8-implicit-str-concat.allow-multiline=false + +[tool.ruff.lint.flake8-tidy-imports.banned-api] +"pytest.main".msg = "pytest.main requires special handling that is easy to mess up!" +"unittest".msg = "Use pytest" + +[tool.pytest.ini_options] +addopts = "--durations=10 -n auto" diff --git a/rednose_repo/rednose/helpers/__init__.py b/rednose_repo/rednose/helpers/__init__.py index b2beede2b8cd49f..3acc14afffb2b39 100644 --- a/rednose_repo/rednose/helpers/__init__.py +++ b/rednose_repo/rednose/helpers/__init__.py @@ -9,8 +9,10 @@ def write_code(folder, name, code, header): if not os.path.exists(folder): os.mkdir(folder) - open(os.path.join(folder, f"{name}.cpp"), 'w', encoding='utf-8').write(code) - open(os.path.join(folder, f"{name}.h"), 'w', encoding='utf-8').write(header) + with open(os.path.join(folder, f"{name}.cpp"), 'w', encoding='utf-8') as f: + f.write(code) + with open(os.path.join(folder, f"{name}.h"), 'w', encoding='utf-8') as f: + f.write(header) def load_code(folder, name): diff --git a/rednose_repo/rednose/helpers/ekf_sym.py b/rednose_repo/rednose/helpers/ekf_sym.py index e8bd6420f635c3e..9dffe50e1dee4f1 100644 --- a/rednose_repo/rednose/helpers/ekf_sym.py +++ b/rednose_repo/rednose/helpers/ekf_sym.py @@ -204,14 +204,17 @@ def gen_code(folder, name, f_sym, dt_sym, x_sym, obs_eqs, dim_x, dim_err, eskf_p # merge code blocks header += "}" - code = "\n".join([pre_code, code, open(os.path.join(TEMPLATE_DIR, "ekf_c.c"), encoding='utf-8').read(), post_code]) + with open(os.path.join(TEMPLATE_DIR, "ekf_c.c"), encoding='utf-8') as f: + code = "\n".join([pre_code, code, f.read(), post_code]) # write to file if not os.path.exists(folder): os.mkdir(folder) - open(os.path.join(folder, f"{name}.h"), 'w', encoding='utf-8').write(header) # header is used for ffi import - open(os.path.join(folder, f"{name}.cpp"), 'w', encoding='utf-8').write(code) + with open(os.path.join(folder, f"{name}.h"), 'w', encoding='utf-8') as f: + f.write(header) # header is used for ffi import + with open(os.path.join(folder, f"{name}.cpp"), 'w', encoding='utf-8') as f: + f.write(code) class EKF_sym(): diff --git a/rednose_repo/rednose/helpers/sympy_helpers.py b/rednose_repo/rednose/helpers/sympy_helpers.py index 71a12d03d303088..7f8813e8a65c606 100644 --- a/rednose_repo/rednose/helpers/sympy_helpers.py +++ b/rednose_repo/rednose/helpers/sympy_helpers.py @@ -55,6 +55,7 @@ def euler2quat(eulers): def euler2rot(eulers): return quat2rot(euler2quat(eulers)) + rotations_from_quats = quat2rot @@ -66,6 +67,13 @@ def cross(x): return ret +def rot_to_euler(R): + gamma = sp.atan2(R[2, 1], R[2, 2]) + theta = sp.asin(-R[2, 0]) + psi = sp.atan2(R[1, 0], R[0, 0]) + return sp.Matrix([gamma, theta, psi]) + + def rot_matrix(roll, pitch, yaw): cr, sr = np.cos(roll), np.sin(roll) cp, sp = np.cos(pitch), np.sin(pitch) diff --git a/rednose_repo/requirements.txt b/rednose_repo/requirements.txt index 453554b06de56bd..81875a88ba3a19c 100644 --- a/rednose_repo/requirements.txt +++ b/rednose_repo/requirements.txt @@ -7,3 +7,5 @@ cffi scons pre-commit Cython +pytest +pytest-xdist diff --git a/release/README.md b/release/README.md new file mode 100644 index 000000000000000..1d3e78493694d89 --- /dev/null +++ b/release/README.md @@ -0,0 +1,36 @@ +# openpilot releases + +## release checklist + +**Go to `devel-staging`** +- [ ] update `devel-staging`: `git reset --hard origin/master-ci` +- [ ] open a pull request from `devel-staging` to `devel` + +**Go to `devel`** +- [ ] update RELEASES.md +- [ ] close out milestone +- [ ] post on Discord dev channel +- [ ] bump version on master: `common/version.h` and `RELEASES.md` +- [ ] merge the pull request + +tests: +- [ ] update from previous release -> new release +- [ ] update from new release -> previous release +- [ ] fresh install with `openpilot-test.comma.ai` +- [ ] drive on fresh install +- [ ] comma body test +- [ ] no submodules or LFS +- [ ] check sentry, MTBF, etc. + +**Go to `release3`** +- [ ] publish the blog post +- [ ] `git reset --hard origin/release3-staging` +- [ ] tag the release +``` +git tag v0.X.X +git push origin v0.X.X +``` +- [ ] create GitHub release +- [ ] final test install on `openpilot.comma.ai` +- [ ] update production +- [ ] Post on Discord, X, etc. diff --git a/release/build_devel.sh b/release/build_devel.sh index 7fce11ca729147b..c6d04396fe397d7 100755 --- a/release/build_devel.sh +++ b/release/build_devel.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -ex DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/release/build_release.sh b/release/build_release.sh index a9e00d583da9b34..8b26dc74ab4282a 100755 --- a/release/build_release.sh +++ b/release/build_release.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e set -x @@ -50,8 +50,13 @@ git commit -a -m "openpilot v$VERSION release" export PYTHONPATH="$BUILD_DIR" scons -j$(nproc) --minimal -# release panda fw -CERT=/data/pandaextra/certs/release RELEASE=1 scons -j$(nproc) panda/ +if [ -z "$PANDA_DEBUG_BUILD" ]; then + # release panda fw + CERT=/data/pandaextra/certs/release RELEASE=1 scons -j$(nproc) panda/ +else + # build with ALLOW_DEBUG=1 to enable features like experimental longitudinal + scons -j$(nproc) panda/ +fi # Ensure no submodules in release if test "$(git submodule--helper list | wc -l)" -gt "0"; then @@ -92,7 +97,7 @@ cp -pR -n --parents $TEST_FILES $BUILD_DIR/ cd $BUILD_DIR RELEASE=1 pytest -n0 -s selfdrive/test/test_onroad.py #system/manager/test/test_manager.py -#pytest selfdrive/car/tests/test_car_interfaces.py +pytest selfdrive/car/tests/test_car_interfaces.py rm -rf $TEST_FILES if [ ! -z "$RELEASE_BRANCH" ]; then diff --git a/release/check-dirty.sh b/release/check-dirty.sh index 9c6389f3801ac6e..ac049970cf06bc4 100755 --- a/release/check-dirty.sh +++ b/release/check-dirty.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" diff --git a/release/check-submodules.sh b/release/check-submodules.sh index bff8d7a28fe3016..93869a740347d96 100755 --- a/release/check-submodules.sh +++ b/release/check-submodules.sh @@ -1,7 +1,12 @@ -#!/bin/bash +#!/usr/bin/env bash while read hash submodule ref; do - git -C $submodule fetch --depth 2000 origin master + if [ "$submodule" = "tinygrad_repo" ]; then + echo "Skipping $submodule" + continue + fi + + git -C $submodule fetch --depth 100 origin master git -C $submodule branch -r --contains $hash | grep "origin/master" if [ "$?" -eq 0 ]; then echo "$submodule ok" diff --git a/release/release_files.py b/release/release_files.py index 031b51737d76562..afd0d468b67adca 100755 --- a/release/release_files.py +++ b/release/release_files.py @@ -10,25 +10,22 @@ # - minimizing release download size # - keeping the diff readable blacklist = [ - "body/STL/", - "panda/drivers/", "panda/examples/", "panda/tests/safety/", - "opendbc/.*.dbc$", - "opendbc/generator/", + "opendbc_repo/dbc/.*.dbc$", + "opendbc_repo/dbc/generator/", "cereal/.*test.*", "^common/tests/", # particularly large text files - "poetry.lock", + "uv.lock", "third_party/catch2", "selfdrive/car/tests/test_models.*", "^tools/", - "^scripts/", "^tinygrad_repo/", "matlab.*.md", @@ -55,6 +52,8 @@ whitelist = [ "tools/lib/", "tools/bodyteleop/", + "tools/joystick/", + "tools/longitudinal_maneuvers/", "tinygrad_repo/openpilot/compile2.py", "tinygrad_repo/extra/onnx.py", @@ -76,55 +75,51 @@ "tinygrad_repo/tinygrad/.*.py", # TODO: do this automatically - "opendbc/comma_body.dbc", - "opendbc/chrysler_ram_hd_generated.dbc", - "opendbc/chrysler_ram_dt_generated.dbc", - "opendbc/chrysler_pacifica_2017_hybrid_generated.dbc", - "opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc", - "opendbc/gm_global_a_powertrain_generated.dbc", - "opendbc/gm_global_a_object.dbc", - "opendbc/gm_global_a_chassis.dbc", - "opendbc/FORD_CADS.dbc", - "opendbc/ford_fusion_2018_adas.dbc", - "opendbc/ford_lincoln_base_pt.dbc", - "opendbc/honda_accord_2018_can_generated.dbc", - "opendbc/acura_ilx_2016_can_generated.dbc", - "opendbc/acura_rdx_2018_can_generated.dbc", - "opendbc/acura_rdx_2020_can_generated.dbc", - "opendbc/honda_civic_touring_2016_can_generated.dbc", - "opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc", - "opendbc/honda_crv_touring_2016_can_generated.dbc", - "opendbc/honda_crv_ex_2017_can_generated.dbc", - "opendbc/honda_crv_ex_2017_body_generated.dbc", - "opendbc/honda_crv_executive_2016_can_generated.dbc", - "opendbc/honda_fit_ex_2018_can_generated.dbc", - "opendbc/honda_odyssey_exl_2018_generated.dbc", - "opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc", - "opendbc/honda_insight_ex_2019_can_generated.dbc", - "opendbc/acura_ilx_2016_nidec.dbc", - "opendbc/honda_civic_ex_2022_can_generated.dbc", - "opendbc/hyundai_canfd.dbc", - "opendbc/hyundai_kia_generic.dbc", - "opendbc/hyundai_kia_mando_front_radar_generated.dbc", - "opendbc/mazda_2017.dbc", - "opendbc/nissan_x_trail_2017_generated.dbc", - "opendbc/nissan_leaf_2018_generated.dbc", - "opendbc/subaru_global_2017_generated.dbc", - "opendbc/subaru_global_2020_hybrid_generated.dbc", - "opendbc/subaru_outback_2015_generated.dbc", - "opendbc/subaru_outback_2019_generated.dbc", - "opendbc/subaru_forester_2017_generated.dbc", - "opendbc/toyota_tnga_k_pt_generated.dbc", - "opendbc/toyota_new_mc_pt_generated.dbc", - "opendbc/toyota_nodsu_pt_generated.dbc", - "opendbc/toyota_adas.dbc", - "opendbc/toyota_tss2_adas.dbc", - "opendbc/vw_golf_mk4.dbc", - "opendbc/vw_mqb_2010.dbc", - "opendbc/tesla_can.dbc", - "opendbc/tesla_radar_bosch_generated.dbc", - "opendbc/tesla_radar_continental_generated.dbc", - "opendbc/tesla_powertrain.dbc", + "opendbc_repo/dbc/comma_body.dbc", + "opendbc_repo/dbc/chrysler_ram_hd_generated.dbc", + "opendbc_repo/dbc/chrysler_ram_dt_generated.dbc", + "opendbc_repo/dbc/chrysler_pacifica_2017_hybrid_generated.dbc", + "opendbc_repo/dbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc", + "opendbc_repo/dbc/gm_global_a_powertrain_generated.dbc", + "opendbc_repo/dbc/gm_global_a_object.dbc", + "opendbc_repo/dbc/gm_global_a_chassis.dbc", + "opendbc_repo/dbc/FORD_CADS.dbc", + "opendbc_repo/dbc/ford_fusion_2018_adas.dbc", + "opendbc_repo/dbc/ford_lincoln_base_pt.dbc", + "opendbc_repo/dbc/honda_accord_2018_can_generated.dbc", + "opendbc_repo/dbc/acura_ilx_2016_can_generated.dbc", + "opendbc_repo/dbc/acura_rdx_2018_can_generated.dbc", + "opendbc_repo/dbc/acura_rdx_2020_can_generated.dbc", + "opendbc_repo/dbc/honda_civic_touring_2016_can_generated.dbc", + "opendbc_repo/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc", + "opendbc_repo/dbc/honda_crv_touring_2016_can_generated.dbc", + "opendbc_repo/dbc/honda_crv_ex_2017_can_generated.dbc", + "opendbc_repo/dbc/honda_crv_ex_2017_body_generated.dbc", + "opendbc_repo/dbc/honda_crv_executive_2016_can_generated.dbc", + "opendbc_repo/dbc/honda_fit_ex_2018_can_generated.dbc", + "opendbc_repo/dbc/honda_odyssey_exl_2018_generated.dbc", + "opendbc_repo/dbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc", + "opendbc_repo/dbc/honda_insight_ex_2019_can_generated.dbc", + "opendbc_repo/dbc/acura_ilx_2016_nidec.dbc", + "opendbc_repo/dbc/honda_civic_ex_2022_can_generated.dbc", + "opendbc_repo/dbc/hyundai_canfd.dbc", + "opendbc_repo/dbc/hyundai_kia_generic.dbc", + "opendbc_repo/dbc/hyundai_kia_mando_front_radar_generated.dbc", + "opendbc_repo/dbc/mazda_2017.dbc", + "opendbc_repo/dbc/nissan_x_trail_2017_generated.dbc", + "opendbc_repo/dbc/nissan_leaf_2018_generated.dbc", + "opendbc_repo/dbc/subaru_global_2017_generated.dbc", + "opendbc_repo/dbc/subaru_global_2020_hybrid_generated.dbc", + "opendbc_repo/dbc/subaru_outback_2015_generated.dbc", + "opendbc_repo/dbc/subaru_outback_2019_generated.dbc", + "opendbc_repo/dbc/subaru_forester_2017_generated.dbc", + "opendbc_repo/dbc/toyota_tnga_k_pt_generated.dbc", + "opendbc_repo/dbc/toyota_new_mc_pt_generated.dbc", + "opendbc_repo/dbc/toyota_nodsu_pt_generated.dbc", + "opendbc_repo/dbc/toyota_adas.dbc", + "opendbc_repo/dbc/toyota_tss2_adas.dbc", + "opendbc_repo/dbc/vw_golf_mk4.dbc", + "opendbc_repo/dbc/vw_mqb_2010.dbc", ] diff --git a/scripts/__init__.py b/scripts/__init__.py new file mode 100644 index 000000000000000..e69de29bb2d1d64 diff --git a/scripts/apply-pr.sh b/scripts/apply-pr.sh new file mode 100755 index 000000000000000..ad0af46b49a9acf --- /dev/null +++ b/scripts/apply-pr.sh @@ -0,0 +1,11 @@ +#!/usr/bin/env bash + +if [ $# -eq 0 ]; then + echo "usage: $0 " + exit 1 +fi + +BASE="https://github.com/commaai/openpilot/pull/" +PR_NUM="$(echo $1 | grep -o -E '[0-9]+')" + +curl -L $BASE/$PR_NUM.patch | git apply -3 diff --git a/scripts/build_small.sh b/scripts/build_small.sh new file mode 100755 index 000000000000000..176ca5aaa8f92a9 --- /dev/null +++ b/scripts/build_small.sh @@ -0,0 +1,39 @@ +#!/usr/bin/env bash +set -ex + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR + +# git clone --mirror +SRC=/tmp/openpilot.git/ +OUT=/tmp/smallpilot/ + +echo "starting size $(du -hs .git/)" + +rm -rf $OUT + +cd $SRC +git remote update + +# copy contents +#rsync -a --exclude='.git/' $DIR $OUT + +cp -r $SRC $OUT + +cd $OUT + +# remove all tags +git tag -l | xargs git tag -d + +# remove non-master branches +BRANCHES="release2 release3 devel master-ci nightly" +for branch in $BRANCHES; do + git branch -D $branch + git branch -D ${branch}-staging || true +done + +#git gc +git reflog expire --expire=now --all +git gc --prune=now +git gc --aggressive --prune=now +echo "new one is $(du -hs .)" diff --git a/scripts/cell.sh b/scripts/cell.sh new file mode 100755 index 000000000000000..310a9694fd044bd --- /dev/null +++ b/scripts/cell.sh @@ -0,0 +1,3 @@ +#!/usr/bin/env bash +nmcli connection modify --temporary esim ipv4.route-metric 1 ipv6.route-metric 1 +nmcli con up esim diff --git a/scripts/checkout-pr.sh b/scripts/checkout-pr.sh new file mode 100755 index 000000000000000..eeba816d8898b56 --- /dev/null +++ b/scripts/checkout-pr.sh @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +set -e + +if [ $# -eq 0 ]; then + echo "usage: $0 " + exit 1 +fi + +BASE="https://github.com/commaai/openpilot/pull/" +PR_NUM="$(echo $1 | grep -o -E '[0-9]+')" +BRANCH=tmp-pr${PR_NUM} + +git branch -D -f $BRANCH || true +git fetch -u -f origin pull/$PR_NUM/head:$BRANCH +git switch $BRANCH +git reset --hard FETCH_HEAD diff --git a/scripts/code_stats.py b/scripts/code_stats.py new file mode 100755 index 000000000000000..3189cd7cc1bd20d --- /dev/null +++ b/scripts/code_stats.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python3 +import os +import ast +import stat +import subprocess + +fouts = {x.decode('utf-8') for x in subprocess.check_output(['git', 'ls-files']).strip().split()} + +pyf = [] +for d in ["cereal", "common", "scripts", "selfdrive", "tools"]: + for root, _, files in os.walk(d): + for f in files: + if f.endswith(".py"): + pyf.append(os.path.join(root, f)) + +imps: set[str] = set() + +class Analyzer(ast.NodeVisitor): + def visit_Import(self, node): + for alias in node.names: + imps.add(alias.name) + self.generic_visit(node) + + def visit_ImportFrom(self, node): + imps.add(node.module) + self.generic_visit(node) + +tlns = 0 +carlns = 0 +scriptlns = 0 +testlns = 0 +for f in sorted(pyf): + if f not in fouts: + continue + xbit = bool(os.stat(f)[stat.ST_MODE] & stat.S_IXUSR) + src = open(f).read() + lns = len(src.split("\n")) + tree = ast.parse(src) + Analyzer().visit(tree) + print("%5d %s %s" % (lns, f, xbit)) + if 'test' in f: + testlns += lns + elif f.startswith(('tools/', 'scripts/', 'selfdrive/debug')): + scriptlns += lns + elif f.startswith('selfdrive/car'): + carlns += lns + else: + tlns += lns + +print("%d lines of openpilot python" % tlns) +print("%d lines of car ports" % carlns) +print("%d lines of tools/scripts/debug" % scriptlns) +print("%d lines of tests" % testlns) +#print(sorted(list(imps))) diff --git a/scripts/count_cars.py b/scripts/count_cars.py new file mode 100755 index 000000000000000..19f486735a7a58f --- /dev/null +++ b/scripts/count_cars.py @@ -0,0 +1,11 @@ +#!/usr/bin/env python3 +from collections import Counter +from pprint import pprint + +from opendbc.car.docs import get_all_car_docs + +if __name__ == "__main__": + cars = get_all_car_docs() + make_count = Counter(l.make for l in cars) + print("\n", "*" * 20, len(cars), "total", "*" * 20, "\n") + pprint(make_count) diff --git a/scripts/disable-powersave.py b/scripts/disable-powersave.py new file mode 100755 index 000000000000000..367b4108b0d28b7 --- /dev/null +++ b/scripts/disable-powersave.py @@ -0,0 +1,5 @@ +#!/usr/bin/env python3 +from openpilot.system.hardware import HARDWARE + +if __name__ == "__main__": + HARDWARE.set_power_save(False) diff --git a/scripts/git_rewrite/rewrite-git-history.sh b/scripts/git_rewrite/rewrite-git-history.sh new file mode 100755 index 000000000000000..cce4455ce5be137 --- /dev/null +++ b/scripts/git_rewrite/rewrite-git-history.sh @@ -0,0 +1,391 @@ +#!/usr/bin/env bash +set -e + +SRC=/tmp/openpilot/ +SRC_CLONE=/tmp/openpilot-clone/ +OUT=/tmp/openpilot-tiny/ + +REWRITE_IGNORE_BRANCHES=( + dashcam3 + devel + master-ci + nightly + release2 + release3 + release3-staging +) + +VALIDATE_IGNORE_FILES=( + ".github/ISSUE_TEMPLATE/bug_report.md" + ".github/pull_request_template.md" +) + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR + +LOGS_DIR=$DIR/git-rewrite-$(date +"%Y-%m-%dT%H:%M:%S%z") +mkdir -p $LOGS_DIR + +GIT_REWRITE_LOG=$LOGS_DIR/git-rewrite-log.txt +BRANCH_DIFF_LOG=$LOGS_DIR/branch-diff-log.txt +COMMIT_DIFF_LOG=$LOGS_DIR/commit-diff-log.txt + +START_TIME=$(date +%s) +exec > >(while IFS= read -r line; do + CURRENT_TIME=$(date +%s) + ELAPSED_TIME=$((CURRENT_TIME - START_TIME)) + echo "[${ELAPSED_TIME}s] $line" +done | tee -a "$GIT_REWRITE_LOG") 2>&1 + +# INSTALL git-filter-repo +if [ ! -f /tmp/git-filter-repo ]; then + echo "Installing git-filter-repo..." + curl -sSo /tmp/git-filter-repo https://raw.githubusercontent.com/newren/git-filter-repo/main/git-filter-repo + chmod +x /tmp/git-filter-repo +fi + +# MIRROR openpilot +if [ ! -d $SRC ]; then + echo "Mirroring openpilot..." + git clone --mirror https://github.com/commaai/openpilot.git $SRC # 4.18 GiB (488034 objects) + + cd $SRC + + echo "Starting size $(du -sh .)" + + git remote update + + # the git-filter-repo analysis is bliss - can be found in the repo root/filter-repo/analysis + echo "Analyzing with git-filter-repo..." + /tmp/git-filter-repo --force --analyze + + echo "Pushing to openpilot-archive..." + # push to archive repo - in smaller parts because the 2 GB push limit - https://docs.github.com/en/get-started/using-git/troubleshooting-the-2-gb-push-limit + ARCHIVE_REPO=git@github.com:commaai/openpilot-archive.git + git push --prune $ARCHIVE_REPO +refs/heads/master:refs/heads/master # push master first so it's the default branch (when openpilot-archive is an empty repo) + git push --prune $ARCHIVE_REPO +refs/heads/*:refs/heads/* # 956.39 MiB (110725 objects) + git push --prune $ARCHIVE_REPO +refs/tags/*:refs/tags/* # 1.75 GiB (21694 objects) + # git push --mirror $ARCHIVE_REPO || true # fails to push refs/pull/* (deny updating a hidden ref) for pull requests + # we fail and continue - more reading: https://stackoverflow.com/a/34266401/639708 and https://blog.plataformatec.com.br/2013/05/how-to-properly-mirror-a-git-repository/ +fi + +# REWRITE master and tags +if [ ! -d $SRC_CLONE ]; then + echo "Cloning $SRC..." + GIT_LFS_SKIP_SMUDGE=1 git clone $SRC $SRC_CLONE + + cd $SRC_CLONE + + echo "Checking out old history..." + + git checkout tags/v0.7.1 > /dev/null 2>&1 + # checkout as main, since we need master ref later + git checkout -b main + + echo "Creating setup commits..." + + # rm these so we don't get conflicts later + git rm -r cereal opendbc panda selfdrive/ui/ui > /dev/null + git commit -m "removed conflicting files" > /dev/null + + # skip-smudge to get rid of some lfs errors that it can't find the reference of some lfs files + # we don't care about fetching/pushing lfs right now + git lfs install --skip-smudge --local + + # squash initial setup commits + git cherry-pick -n -X theirs 6c33a5c..59b3d06 > /dev/null + git commit -m "switching to master" > /dev/null + + # squash the two commits + git reset --soft HEAD~2 + git commit -m "switching to master" -m "$(git log --reverse --format=%B 6c33a5c..59b3d06)" -m "removed conflicting files" > /dev/null + + # get commits we want to cherry-pick + # will start with the next commit after #59b3d06 tools is local now + COMMITS=$(git rev-list --reverse 59b3d06..master) + + # we need this for logging + TOTAL_COMMITS=$(echo $COMMITS | wc -w | xargs) + CURRENT_COMMIT_NUMBER=0 + + # empty this file + > commit-map.txt + + echo "Rewriting master commits..." + + for COMMIT in $COMMITS; do + CURRENT_COMMIT_NUMBER=$((CURRENT_COMMIT_NUMBER + 1)) + # echo -ne "[$CURRENT_COMMIT_NUMBER/$TOTAL_COMMITS] Cherry-picking commit: $COMMIT"\\r + echo "[$CURRENT_COMMIT_NUMBER/$TOTAL_COMMITS] Cherry-picking commit: $COMMIT" + + # set environment variables to preserve author/committer and dates + export GIT_AUTHOR_NAME=$(git show -s --format='%an' $COMMIT) + export GIT_AUTHOR_EMAIL=$(git show -s --format='%ae' $COMMIT) + export GIT_COMMITTER_NAME=$(git show -s --format='%cn' $COMMIT) + export GIT_COMMITTER_EMAIL=$(git show -s --format='%ce' $COMMIT) + export GIT_AUTHOR_DATE=$(git show -s --format='%ad' $COMMIT) + export GIT_COMMITTER_DATE=$(git show -s --format='%cd' $COMMIT) + + # cherry-pick the commit + if ! GIT_OUTPUT=$(git cherry-pick -m 1 -X theirs $COMMIT 2>&1); then + # check if the failure is because of an empty commit + if [[ "$GIT_OUTPUT" == *"The previous cherry-pick is now empty"* ]]; then + echo "Empty commit detected. Skipping commit $COMMIT" + git cherry-pick --skip + # log it was empty to the mapping file + echo "$COMMIT EMPTY" >> commit-map.txt + else + # handle other errors or conflicts + echo "Cherry-pick failed. Handling error..." + echo "$GIT_OUTPUT" + exit 1 + fi + else + # capture the new commit hash + NEW_COMMIT=$(git rev-parse HEAD) + + # save the old and new commit hashes to the mapping file + echo "$COMMIT $NEW_COMMIT" >> commit-map.txt + + # append the old commit ID to the commit message + git commit --amend -m "$(git log -1 --pretty=%B)" -m "Former-commit-id: $COMMIT" > /dev/null + fi + + # prune every 3000 commits to avoid gc errors + if [ $((CURRENT_COMMIT_NUMBER % 3000)) -eq 0 ]; then + echo "Pruning repo..." + git gc + fi + done + + echo "Rewriting tags..." + + # remove all old tags + git tag -l | xargs git tag -d + + # read each line from the tag-commit-map.txt + while IFS=' ' read -r TAG OLD_COMMIT; do + # search for the new commit in commit-map.txt corresponding to the old commit + NEW_COMMIT=$(grep "^$OLD_COMMIT " "commit-map.txt" | awk '{print $2}') + + # check if this is a rebased commit + if [ -z "$NEW_COMMIT" ]; then + # if not, then just use old commit hash + NEW_COMMIT=$OLD_COMMIT + fi + + echo "Rewriting tag $TAG from commit $NEW_COMMIT" + git tag -f "$TAG" "$NEW_COMMIT" + done < "$DIR/tag-commit-map.txt" + + # uninstall lfs since we don't want to touch (push to) lfs right now + # git push will also push lfs, if we don't uninstall (--local so just for this repo) + git lfs uninstall --local + + # force push new master + git push --force origin main:master + + # force push new tags + git push --force --tags +fi + +# REWRITE branches based on master +if [ ! -f "$SRC_CLONE/rewrite-branches-done" ]; then + cd $SRC_CLONE + > rewrite-branches-done + + # empty file + > $BRANCH_DIFF_LOG + + echo "Rewriting branches based on master..." + + # will store raw diffs here, if exist + mkdir -p differences + + # get a list of all branches except master and REWRITE_IGNORE_BRANCHES + BRANCHES=$(git branch -r | grep -v ' -> ' | sed 's/.*origin\///' | grep -v '^master$' | grep -v -f <(echo "${REWRITE_IGNORE_BRANCHES[*]}" | tr ' ' '\n')) + + for BRANCH in $BRANCHES; do + # check if the branch is based on master history + MERGE_BASE=$(git merge-base master origin/$BRANCH) || true + if [ -n "$MERGE_BASE" ]; then + echo "Rewriting branch: $BRANCH" + + # create a new branch based on the new master + NEW_MERGE_BASE=$(grep "^$MERGE_BASE " "commit-map.txt" | awk '{print $2}') + if [ -z "$NEW_MERGE_BASE" ]; then + echo "Error: could not find new merge base for branch $BRANCH" >> $BRANCH_DIFF_LOG + continue + fi + git checkout -b ${BRANCH}_new $NEW_MERGE_BASE + + # get the range of commits unique to this branch + COMMITS=$(git rev-list --reverse $MERGE_BASE..origin/${BRANCH}) + + HAS_ERROR=0 + + # simple delimiter + echo "BRANCH ${BRANCH}" >> commit-map.txt + + for COMMIT in $COMMITS; do + # set environment variables to preserve author/committer and dates + export GIT_AUTHOR_NAME=$(git show -s --format='%an' $COMMIT) + export GIT_AUTHOR_EMAIL=$(git show -s --format='%ae' $COMMIT) + export GIT_COMMITTER_NAME=$(git show -s --format='%cn' $COMMIT) + export GIT_COMMITTER_EMAIL=$(git show -s --format='%ce' $COMMIT) + export GIT_AUTHOR_DATE=$(git show -s --format='%ad' $COMMIT) + export GIT_COMMITTER_DATE=$(git show -s --format='%cd' $COMMIT) + + # cherry-pick the commit + if ! GIT_OUTPUT=$(git cherry-pick -m 1 -X theirs $COMMIT 2>&1); then + # check if the failure is because of an empty commit + if [[ "$GIT_OUTPUT" == *"The previous cherry-pick is now empty"* ]]; then + echo "Empty commit detected. Skipping commit $COMMIT" + git cherry-pick --skip + # log it was empty to the mapping file + echo "$COMMIT EMPTY" >> commit-map.txt + else + # handle other errors or conflicts + echo "Cherry-pick of ${BRANCH} branch failed. Removing branch upstream..." >> $BRANCH_DIFF_LOG + echo "$GIT_OUTPUT" > "$LOGS_DIR/branch-${BRANCH}" + git cherry-pick --abort + git push --delete origin ${BRANCH} + HAS_ERROR=1 + break + fi + else + # capture the new commit hash + NEW_COMMIT=$(git rev-parse HEAD) + + # save the old and new commit hashes to the mapping file + echo "$COMMIT $NEW_COMMIT" >> commit-map.txt + + # append the old commit ID to the commit message + git commit --amend -m "$(git log -1 --pretty=%B)" -m "Former-commit-id: $COMMIT" > /dev/null + fi + done + + # force push the new branch + if [ $HAS_ERROR -eq 0 ]; then + # git lfs goes haywire here, so we need to install and uninstall + # git lfs install --skip-smudge --local + git lfs uninstall --local > /dev/null + git push -f origin ${BRANCH}_new:${BRANCH} + fi + + # clean up local branch + git checkout master > /dev/null + git branch -D ${BRANCH}_new > /dev/null + else + echo "Deleting branch $BRANCH as it's not based on master history" >> $BRANCH_DIFF_LOG + git push --delete origin ${BRANCH} + fi + done +fi + +# VALIDATE cherry-pick +if [ ! -f "$SRC_CLONE/validation-done" ]; then + cd $SRC_CLONE + > validation-done + + TOTAL_COMMITS=$(grep -cve '^\s*$' commit-map.txt) + CURRENT_COMMIT_NUMBER=0 + COUNT_SAME=0 + COUNT_DIFF=0 + + # empty file + > $COMMIT_DIFF_LOG + + echo "Validating commits..." + + # will store raw diffs here, if exist + mkdir -p differences + + # read each line from commit-map.txt + while IFS=' ' read -r OLD_COMMIT NEW_COMMIT; do + if [ "$NEW_COMMIT" == "EMPTY" ]; then + continue + fi + if [ "$OLD_COMMIT" == "BRANCH" ]; then + echo "Branch ${NEW_COMMIT} below:" >> $COMMIT_DIFF_LOG + continue + fi + CURRENT_COMMIT_NUMBER=$((CURRENT_COMMIT_NUMBER + 1)) + # retrieve short hashes and dates for the old and new commits + OLD_COMMIT_SHORT=$(git rev-parse --short $OLD_COMMIT) + NEW_COMMIT_SHORT=$(git rev-parse --short $NEW_COMMIT) + OLD_DATE=$(git show -s --format='%cd' $OLD_COMMIT) + NEW_DATE=$(git show -s --format='%cd' $NEW_COMMIT) + + # echo -ne "[$CURRENT_COMMIT_NUMBER/$TOTAL_COMMITS] Comparing old commit $OLD_COMMIT_SHORT ($OLD_DATE) with new commit $NEW_COMMIT_SHORT ($NEW_DATE)"\\r + echo "[$CURRENT_COMMIT_NUMBER/$TOTAL_COMMITS] Comparing old commit $OLD_COMMIT_SHORT ($OLD_DATE) with new commit $NEW_COMMIT_SHORT ($NEW_DATE)" + + # generate lists of files and their hashes for the old and new commits, excluding ignored files + OLD_FILES=$(git ls-tree -r $OLD_COMMIT | grep -vE "$(IFS='|'; echo "${VALIDATE_IGNORE_FILES[*]}")") + NEW_FILES=$(git ls-tree -r $NEW_COMMIT | grep -vE "$(IFS='|'; echo "${VALIDATE_IGNORE_FILES[*]}")") + + # Compare the diffs + if diff <(echo "$OLD_FILES") <(echo "$NEW_FILES") > /dev/null; then + # echo "Old commit $OLD_COMMIT_SHORT and new commit $NEW_COMMIT_SHORT are equivalent." + COUNT_SAME=$((COUNT_SAME + 1)) + else + echo "[$CURRENT_COMMIT_NUMBER/$TOTAL_COMMITS] Difference found between old commit $OLD_COMMIT_SHORT and new commit $NEW_COMMIT_SHORT" >> $COMMIT_DIFF_LOG + COUNT_DIFF=$((COUNT_DIFF + 1)) + set +e + diff -u <(echo "$OLD_FILES") <(echo "$NEW_FILES") > "$LOGS_DIR/commit-$CURRENT_COMMIT_NUMBER-$OLD_COMMIT_SHORT-$NEW_COMMIT_SHORT" + set -e + fi + done < "commit-map.txt" + + echo "Summary:" >> $COMMIT_DIFF_LOG + echo "Equivalent commits: $COUNT_SAME" >> $COMMIT_DIFF_LOG + echo "Different commits: $COUNT_DIFF" >> $COMMIT_DIFF_LOG +fi + +if [ ! -d $OUT ]; then + cp -r $SRC $OUT + + cd $OUT + + # remove all non-master branches + # git branch | grep -v "^ master$" | grep -v "\*" | xargs git branch -D + + # echo "cleaning up refs" + # delete pull request refs since we can't alter them anyway (https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/reviewing-changes-in-pull-requests/checking-out-pull-requests-locally#error-failed-to-push-some-refs) + # git for-each-ref --format='%(refname)' | grep '^refs/pull/' | xargs -I {} git update-ref -d {} + + echo "importing new lfs files" + # import "almost" everything to lfs + BRANCHES=$(git for-each-ref --format='%(refname)' refs/heads/ | sed 's%refs/heads/%%g' | grep -v -f <(echo "${REWRITE_IGNORE_BRANCHES[*]}" | tr ' ' '\n') | tr '\n' ' ') + git lfs migrate import --include="*.dlc,*.onnx,*.svg,*.png,*.gif,*.ttf,*.wav,selfdrive/car/tests/test_models_segs.txt,system/hardware/tici/updater,selfdrive/ui/qt/spinner_larch64,selfdrive/ui/qt/text_larch64,third_party/**/*.a,third_party/**/*.so,third_party/**/*.so.*,third_party/**/*.dylib,third_party/acados/*/t_renderer,third_party/qt5/larch64/bin/lrelease,third_party/qt5/larch64/bin/lupdate,third_party/catch2/include/catch2/catch.hpp,*.apk,*.apkpatch,*.jar,*.pdf,*.jpg,*.mp3,*.thneed,*.tar.gz,*.npy,*.csv,*.a,*.so*,*.dylib,*.o,*.b64,selfdrive/hardware/tici/updater,selfdrive/boardd/tests/test_boardd,selfdrive/ui/qt/spinner_aarch64,installer/updater/updater,selfdrive/debug/profiling/simpleperf/**/*,selfdrive/hardware/eon/updater,selfdrive/ui/qt/text_aarch64,selfdrive/debug/profiling/pyflame/**/*,installer/installers/installer_openpilot,installer/installers/installer_dashcam,selfdrive/ui/text/text,selfdrive/ui/android/text/text,selfdrive/ui/spinner/spinner,selfdrive/visiond/visiond,selfdrive/loggerd/loggerd,selfdrive/sensord/sensord,selfdrive/sensord/gpsd,selfdrive/ui/android/spinner/spinner,selfdrive/ui/qt/spinner,selfdrive/ui/qt/text,_stringdefs.py,dfu-util-aarch64-linux,dfu-util-aarch64,dfu-util-x86_64-linux,dfu-util-x86_64,stb_image.h,clpeak3,clwaste,apk/**/*,external/**/*,phonelibs/**/*,third_party/boringssl/**/*,flask/**/*,panda/**/*,board/**/*,messaging/**/*,opendbc/**/*,tools/cabana/chartswidget.cc,third_party/nanovg/**/*,selfdrive/controls/lib/lateral_mpc/lib_mpc_export/**/*,selfdrive/ui/paint.cc,werkzeug/**/*,pyextra/**/*,third_party/android_hardware_libhardware/**/*,selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/**/*,selfdrive/locationd/laikad.py,selfdrive/locationd/test/test_laikad.py,tools/gpstest/test_laikad.py,selfdrive/locationd/laikad_helpers.py,tools/nui/**/*,jsonrpc/**/*,selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/**/*,selfdrive/controls/lib/lateral_mpc/mpc_export/**/*,selfdrive/camerad/cameras/camera_qcom.cc,selfdrive/manager.py,selfdrive/modeld/models/driving.cc,third_party/curl/**/*,selfdrive/modeld/thneed/debug/**/*,selfdrive/modeld/thneed/include/**/*,third_party/openmax/**/*,selfdrive/controls/lib/longitudinal_mpc/mpc_export/**/*,selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/**/*,Pipfile,Pipfile.lock,gunicorn/**/*,*.qm,jinja2/**/*,click/**/*,dbcs/**/*,websocket/**/*" $BRANCHES + + echo "reflog and gc" + # this is needed after lfs import + git reflog expire --expire=now --all + git gc --prune=now --aggressive + + # check the git-filter-repo analysis again - can be found in the repo root/filter-repo/analysis + echo "Analyzing with git-filter-repo..." + /tmp/git-filter-repo --force --analyze + + echo "New size is $(du -sh .)" +fi + +cd $OUT + +# fetch all lfs files from https://github.com/commaai/openpilot.git +# some lfs files are missing on gitlab, but they can be found on github +git config lfs.url https://github.com/commaai/openpilot.git/info/lfs +git config lfs.pushurl ssh://git@github.com/commaai/openpilot.git +git lfs fetch --all || true + +# also fetch all lfs files from https://gitlab.com/commaai/openpilot-lfs.git +git config lfs.url https://gitlab.com/commaai/openpilot-lfs.git/info/lfs +git config lfs.pushurl ssh://git@gitlab.com/commaai/openpilot-lfs.git +git lfs fetch --all || true + +# final push - will also push lfs +# TODO: switch to git@github.com:commaai/openpilot.git when ready +# git push --mirror git@github.com:commaai/openpilot-tiny.git +# using this instead to ignore refs/pull/* - since this is also what --mirror does - https://blog.plataformatec.com.br/2013/05/how-to-properly-mirror-a-git-repository/ +git push --prune git@github.com:commaai/openpilot-tiny.git +refs/heads/*:refs/heads/* +refs/tags/*:refs/tags/* diff --git a/scripts/git_rewrite/rewrite.sh b/scripts/git_rewrite/rewrite.sh new file mode 100755 index 000000000000000..8a18b15bec9e037 --- /dev/null +++ b/scripts/git_rewrite/rewrite.sh @@ -0,0 +1,59 @@ +#!/usr/bin/env bash +set -e + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd $DIR + +git clone --bare https://github.com/commaai/openpilot +cp -r openpilot.git openpilot_backup +cd openpilot.git + +# backup old repo +git push git@github.com:commaai/openpilot-archive.git +refs/heads/master:refs/heads/master +git push git@github.com:commaai/openpilot-archive.git +refs/heads/*:refs/heads/* +git push git@github.com:commaai/openpilot-archive.git +refs/tags/*:refs/tags/* +git push --mirror git@github.com:commaai/openpilot-archive.git + +# ignore all release branches +git for-each-ref --format='delete %(refname)' | grep 'dashcam3\|devel\|master-ci\|nightly\|release2\|release3\|release3-staging' | git update-ref --stdin + +# re-tag old releases on master +declare -A TAGS=( ["f8cb04e4a8b032b72a909f68b808a50936184bee"]="v0.9.7" ["0b4d08fab8e35a264bc7383e878538f8083c33e5"]="v0.9.6" ["3b1e9017c560499786d8a0e46aaaeea65037acac"]="v0.9.5" ["fa310d9e2542cf497d92f007baec8fd751ffa99c"]="v0.9.4" ["8704c1ff952b5c85a44f50143bbd1a4f7b4887e2"]="v0.9.3" ["c7d3b28b93faa6c955fb24bc64031512ee985ee9"]="v0.9.2" ["89f68bf0cbf53a81b0553d3816fdbe522f941fa1"]="v0.9.1" ["58b84fb401a804967aa0dd5ee66fafa90194fd30"]="v0.9.0" ["f41dc62a12cc0f3cb8c5453c0caa0ba21e1bd01e"]="v0.8.16" ["5a7c2f90361e72e9c35e88abd2e11acdc4aba354"]="v0.8.15" ["71901c94dbbaa2f9f156a80c14cc7ea65219fc7c"]="v0.8.14" ["95da47079510afc91665263619e5939126da637c"]="v0.8.13" ["472177e2a8a1d002e56f9096326fd2dff62e54f9"]="v0.8.12" ["08078acbd0b4f7da469c7dff6159000e358974a9"]="v0.8.11" ["687925c775c375495f9827946138a724bde00b9d"]="v0.8.10" ["204e5a090735a059d69c29145a4cee49450da07e"]="v0.8.9" ["4be956f8861ecbb521ef9503a3c87b07c9d36721"]="v0.8.8" ["589f82c76627d634761a31a34b2488403556eb0b"]="v0.8.7" ["507cfc8910f74ddb8810039d68b880b426ff9ff9"]="v0.8.6" ["d47b00b45a866bef088f51d1ff31de5885ab04e9"]="v0.8.5" ["553e7d1cce314e7eb0587186b1764c3ff43bed62"]="v0.8.4" ["9896438d1511602a1ff87f7c4eb3c7172b30104a"]="v0.8.3" ["280192ed1443f112463417c2d815ea8ee2762fbd"]="v0.8.2" ["8039361567e4659eae2a084e6f39f34acadf4cac"]="v0.8.1" ["d56e04c0d960c8d3d4ab88b578dc508a2b4e07dc"]="v0.8" ["3d456e5d0fbf0c9887d0499dee812f2b029edf6d"]="v0.7.10" ["81763a18b5d0e379b749e090ecce36a91fca7c43"]="v0.7.9" ["9bc0b350fd273bbb2deb3dcaef0312944e4f6cfd"]="v0.7.8" ["ede5b632b58c55e4ff003f948efae07fe03c2280"]="v0.7.7" ["775acd11ba2e0a8c2f5a5655338718d796491b36"]="v0.7.6.1" ["302417b4cf0dcf00d45e4995b5410e543ad121d1"]="v0.7.5" ["12ff088b42221dd17d9d97decb1fc61a7cb0a861"]="v0.7.4" ["9563f7730252451fdcba9bc3d9fe36dab9c86a26"]="v0.7.3" ["8321cf283abbc2ca3fda7e0c7a069a77a492fe0c"]="v0.7.2" ["1e1de64a1e59476b7b3d3558b92149246d5c3292"]="v0.7.1" ["a2ae18d1dbd1e59c38ce22fa25ddffbd1d3084e3"]="v0.7" ["d4eb5a6eafdd4803d09e6f3963918216cca5a81f"]="v0.6.6" ["70d17cd69b80e7627dcad8fd5b6438f2309ac307"]="v0.6.5" ["58f376002e0c654fbc2de127765fa297cf694a33"]="v0.6.4" ["d5f9caa82d80cdcc7f1b7748f2cf3ccbf94f82a3"]="v0.6.3" ["095ef5f9f60fca1b269aabcc3cfd322b17b9e674"]="v0.6.2" ["cf5c4aeacb1703d0ffd35bdb5297d3494fee9a22"]="v0.6.1" ["60a20537c5f3fcc7f11946d81aebc8f90c08c117"]="v0.6" ["dd34ccfe288ebda8e2568cf550994ae890379f45"]="v0.5.13" ["3f9059fea886f1fa3b0c19a62a981d891dcc84eb"]="v0.5.12" ["2f92d577f995ff6ae1945ef6b89df3cb69b92999"]="v0.5.11" ["5a9d89ed42ddcd209d001a10d7eb828ef0e6d9de"]="v0.5.10" ["0207a970400ee28d3e366f2e8f5c551281accf02"]="v0.5.9" ["b967da5fc1f7a07e3561db072dd714d325e857b0"]="v0.5.8" ["210db686bb89f8696aa040e6e16de65424b808c9"]="v0.5.7" ["860a48765d1016ba226fb2c64aea35a45fe40e4a"]="v0.5.6" ["8f3539a27b28851153454eb737da9624cccaed2d"]="v0.5.5" ["a422246dc30bce11e970514f13f7c110f4470cc3"]="v0.5.4" ["285c52eb693265a0a530543e9ca0aeb593a2a55e"]="v0.5.3" ["0129a8a4ff8da5314e8e4d4d3336e89667ff6d54"]="v0.5.2" ["6f3d10a4c475c4c4509f0b370805419acd13912d"]="v0.5.1" ["de33bc46452b1046387ee2b3a03191b2c71135fb"]="v0.5" ["ae5cb7a0dab8b1bed9d52292f9b4e8e66a0f8ec9"]="v0.4.7" ["c6df34f55ba8c5a911b60d3f9eb20e3fa45f68c1"]="v0.4.6" ["37285038d3f91fa1b49159c4a35a8383168e644f"]="v0.4.5" ["9a9ff839a9b70cb2601d7696af743f5652395389"]="v0.4.4" ["28c0797d30175043bbfa31307b63aab4197cf996"]="v0.4.2" ["4474b9b3718653aeb0aee26422caefb90460cc0e"]="v0.4.1" ["da52d065a4c4f52d6017a537f3a80326f5af8bdc"]="v0.4.0.2" ["9d3963559ae7b15193057937ff3e72481899f40d"]="v0.3.5" ["1b8c44b5067525a5d266b6e99799d8097da76a29"]="v0.3.4" ["5cf91d0496688fed4f2a6c7021349b1fc0e057a2"]="v0.3.3" ["7fe46f1e1df5dec08a940451ba0feefd5c039165"]="v0.3.2" ["41e3a0f699f5c39cb61a15c0eb7a4aa816d47c24"]="v0.3.1" ["c5d8aec28b5230d34ae4b677c2091cc3dec7e3e8"]="v0.3.0" ["693bcb0f83478f2651db6bac9be5ca5ad60d03f3"]="v0.2.9" ["95a349abcc050712c50d4d85a1c8a804eee7f6c2"]="v0.2.8" ["c6ba5dc5391d3ca6cda479bf1923b88ce45509a0"]="v0.2.7" ["6c3afeec0fb439070b2912978b8dbb659033b1d9"]="v0.2.6" ["29c58b45882ac79595356caf98580c1d2a626011"]="v0.2.5" ["ecc565aa3fdc4c7e719aadc000e1fdc4d80d4fe0"]="v0.2.4" ["adaa4ed350acda4067fc0b455ad15b54cdf4c768"]="v0.2.3" ["a64b9aa9b8cb5863c917b6926516291a63c02fe5"]="v0.2.2" ["17d9becd3c673091b22f09aa02559a9ed9230f50"]="v0.2.1" ["449b482cc3236ccf31829830b4f6a44b2dcc06c2"]="v0.2" ["e94a30bec07e719c5a7b037ca1f4db8312702cce"]="v0.1" ) +for tag in "${!TAGS[@]}"; do git tag -f "${TAGS[$tag]}" "$tag" ; done + +# get master root commit +ROOT_COMMIT=$(git rev-list --max-parents=0 HEAD | tail -n 1) + +# link master and devel +git replace --graft $ROOT_COMMIT v0.7.1 +git-filter-repo --prune-empty never --force --commit-callback 'h=commit.original_id.decode("utf-8");m=commit.message.decode("utf-8");commit.message=str.encode(m + "\n" + "old-commit-hash: " + h)' + +# delete replace refs +git for-each-ref --format='delete %(refname)' refs/replace | git update-ref --stdin + +# machine validation +tail -n +2 "filter-repo/commit-map" | tr ' ' '\n' | xargs -P $(nproc) -n 2 bash -c 'H1=$(cd ../openpilot_backup && git ls-tree -r $0 | sha1sum) && H2=$(git ls-tree -r $1 | sha1sum) && echo "$H1 $H2" >> /tmp/GIT_HASHES && diff <(echo $H1) <(echo $H2) || exit 255' +# human validation +less /tmp/GIT_HASH + +# cleanup +git reflog expire --expire=now --all +git gc --prune=now --aggressive + +# get all lfs files +set +e +git config lfs.url https://github.com/commaai/openpilot.git/info/lfs +git lfs fetch --all +git config lfs.url https://gitlab.com/commaai/openpilot-lfs.git/info/lfs +git lfs fetch --all +set -e + +# add new files to lfs +git lfs migrate import --everything --include="*.ico,*.dlc,*.onnx,*.svg,*.png,*.gif,*.ttf,*.wav,system/hardware/tici/updater,selfdrive/ui/qt/spinner_larch64,selfdrive/ui/qt/text_larch64,third_party/**/*.a,third_party/**/*.so,third_party/**/*.so.*,third_party/**/*.dylib,third_party/acados/*/t_renderer,third_party/qt5/larch64/bin/lrelease,third_party/qt5/larch64/bin/lupdate,third_party/catch2/include/catch2/catch.hpp,*.apk,*.apkpatch,*.jar,*.pdf,*.jpg,*.mp3,*.thneed,*.tar.gz,*.npy,*.csv,*.a,*.so*,*.dylib,*.o,*.b64,selfdrive/hardware/tici/updater,selfdrive/boardd/tests/test_boardd,selfdrive/ui/qt/spinner_aarch64,installer/updater/updater,selfdrive/debug/profiling/simpleperf/**/*,selfdrive/hardware/eon/updater,selfdrive/ui/qt/text_aarch64,selfdrive/debug/profiling/pyflame/**/*,installer/installers/installer_openpilot,installer/installers/installer_dashcam,selfdrive/ui/text/text,selfdrive/ui/android/text/text,selfdrive/ui/spinner/spinner,selfdrive/visiond/visiond,selfdrive/loggerd/loggerd,selfdrive/sensord/sensord,selfdrive/sensord/gpsd,selfdrive/ui/android/spinner/spinner,selfdrive/ui/qt/spinner,selfdrive/ui/qt/text,_stringdefs.py,dfu-util-aarch64-linux,dfu-util-aarch64,dfu-util-x86_64-linux,dfu-util-x86_64,stb_image.h,clpeak3,clwaste,apk/**/*,external/**/*,phonelibs/**/*,third_party/boringssl/**/*,pyextra/**/*,panda/board/**/inc/*.h,panda/board/obj/*.elf,board/inc/*.h,third_party/nanovg/**/*,selfdrive/controls/lib/lateral_mpc/lib_mpc_export/**/*,pyextra/**/*,third_party/android_hardware_libhardware/**/*,selfdrive/controls/lib/lead_mpc_lib/lib_mpc_export/**/*,*.pro,selfdrive/controls/lib/longitudinal_mpc/lib_mpc_export/**/*,selfdrive/controls/lib/lateral_mpc/mpc_export/**/*,third_party/curl/**/*,selfdrive/modeld/thneed/debug/**/*,selfdrive/modeld/thneed/include/**/*,third_party/openmax/**/*,selfdrive/controls/lib/longitudinal_mpc/mpc_export/**/*,selfdrive/controls/lib/longitudinal_mpc_model/lib_mpc_export/**/*,Pipfile,Pipfile.lock,poetry.lock,*.qm" + +# set new lfs endpoint +git config lfs.url https://gitlab.com/commaai/openpilot-lfs.git/info/lfs +git config lfs.pushurl ssh://git@gitlab.com/commaai/openpilot-lfs.git + +# push all branch+tag (scary stuff...) +git push -f --set-upstream git@github.com:commaai/openpilot.git +refs/heads/*:refs/heads/* +refs/tags/*:refs/tags/* diff --git a/scripts/git_rewrite/tag-commit-map.txt b/scripts/git_rewrite/tag-commit-map.txt new file mode 100644 index 000000000000000..66b1fb00c182a08 --- /dev/null +++ b/scripts/git_rewrite/tag-commit-map.txt @@ -0,0 +1,82 @@ +v0.1 e94a30bec07e719c5a7b037ca1f4db8312702cce +v0.2 449b482cc3236ccf31829830b4f6a44b2dcc06c2 +v0.2.1 17d9becd3c673091b22f09aa02559a9ed9230f50 +v0.2.2 a64b9aa9b8cb5863c917b6926516291a63c02fe5 +v0.2.3 adaa4ed350acda4067fc0b455ad15b54cdf4c768 +v0.2.4 ecc565aa3fdc4c7e719aadc000e1fdc4d80d4fe0 +v0.2.5 29c58b45882ac79595356caf98580c1d2a626011 +v0.2.6 6c3afeec0fb439070b2912978b8dbb659033b1d9 +v0.2.7 c6ba5dc5391d3ca6cda479bf1923b88ce45509a0 +v0.2.8 95a349abcc050712c50d4d85a1c8a804eee7f6c2 +v0.2.9 693bcb0f83478f2651db6bac9be5ca5ad60d03f3 +v0.3.0 c5d8aec28b5230d34ae4b677c2091cc3dec7e3e8 +v0.3.1 41e3a0f699f5c39cb61a15c0eb7a4aa816d47c24 +v0.3.2 7fe46f1e1df5dec08a940451ba0feefd5c039165 +v0.3.3 5cf91d0496688fed4f2a6c7021349b1fc0e057a2 +v0.3.4 1b8c44b5067525a5d266b6e99799d8097da76a29 +v0.3.5 b111277f464cf66fa34b67819a83ea683e0f64df +v0.4.0.2 da52d065a4c4f52d6017a537f3a80326f5af8bdc +v0.4.1 4474b9b3718653aeb0aee26422caefb90460cc0e +v0.4.2 28c0797d30175043bbfa31307b63aab4197cf996 +v0.4.4 9a9ff839a9b70cb2601d7696af743f5652395389 +v0.4.5 37285038d3f91fa1b49159c4a35a8383168e644f +v0.4.6 c6df34f55ba8c5a911b60d3f9eb20e3fa45f68c1 +v0.4.7 ae5cb7a0dab8b1bed9d52292f9b4e8e66a0f8ec9 +v0.5 de33bc46452b1046387ee2b3a03191b2c71135fb +v0.5.1 8f22f52235c48eada586795ac57edb22688e4d08 +v0.5.2 0129a8a4ff8da5314e8e4d4d3336e89667ff6d54 +v0.5.3 285c52eb693265a0a530543e9ca0aeb593a2a55e +v0.5.4 a422246dc30bce11e970514f13f7c110f4470cc3 +v0.5.5 8f3539a27b28851153454eb737da9624cccaed2d +v0.5.6 860a48765d1016ba226fb2c64aea35a45fe40e4a +v0.5.7 9ce3045f139ee29bf0eea5ec59dfe7df9c3d2c51 +v0.5.8 2cee2e05ba0f3824fdbb8b957958800fa99071a1 +v0.5.9 ad145da3bcded0fe75306df02061d07a633963c3 +v0.5.10 ff4c1557d8358f158f4358788ff18ef93d2470ef +v0.5.11 d1866845df423c6855e2b365ff230cf7d89a420b +v0.5.12 f6e8ef27546e9a406724841e75f8df71cc4c2c97 +v0.5.13 dd34ccfe288ebda8e2568cf550994ae890379f45 +v0.6 60a20537c5f3fcc7f11946d81aebc8f90c08c117 +v0.6.1 cf5c4aeacb1703d0ffd35bdb5297d3494fee9a22 +v0.6.2 095ef5f9f60fca1b269aabcc3cfd322b17b9e674 +v0.6.3 d5f9caa82d80cdcc7f1b7748f2cf3ccbf94f82a3 +v0.6.4 58f376002e0c654fbc2de127765fa297cf694a33 +v0.6.5 70d17cd69b80e7627dcad8fd5b6438f2309ac307 +v0.6.6 d4eb5a6eafdd4803d09e6f3963918216cca5a81f +v0.7 a2ae18d1dbd1e59c38ce22fa25ddffbd1d3084e3 +v0.7.1 1e1de64a1e59476b7b3d3558b92149246d5c3292 +v0.7.2 59bd58c940673b4c4a6a86f299022614bcf42b22 +v0.7.3 d7acd8b68f8131e0e714400cf124a3e228638643 +v0.7.4 e93649882c5e914eec4a8b8b593dc0587e497033 +v0.7.5 8abc0afe464626a461d2c7e192c912eeebeccc65 +v0.7.6 69aacd9d179fe6dd3110253a099c38b34cff7899 +v0.7.7 f1caed7299cdba5e45635d8377da6cc1e5fd7072 +v0.7.8 2189fe8741b635d8394d55dee28959425cfd5ad0 +v0.7.9 86dc54b836a973f132ed26db9f5a60b29f9b25b2 +v0.7.10 47a42ff432db8a2494e922ca5e767e58020f0446 +v0.7.11 f46ed718ba8d6bb4d42cd7b0f0150c406017c373 +v0.8 d56e04c0d960c8d3d4ab88b578dc508a2b4e07dc +v0.8.1 cd6f26664cb8d32a13847d6648567c47c580e248 +v0.8.2 7cc0999aebfe63b6bb6dd83c1dff62c3915c4820 +v0.8.3 986500fe2f10870018f1fba1e5465476b8915977 +v0.8.4 f0d0b82b8d6f5f450952113e234d0a5a49e80c48 +v0.8.5 f5d9ddc6c2a2802a61e5ce590c6b6688bf736a69 +v0.8.6 75904ed7452c6cbfb2a70cd379a899d8a75b97c2 +v0.8.7 4f9e568019492126e236da85b5ca0a059f292900 +v0.8.8 a949a49d5efaaf2d881143d23e9fb5ff9e28e88c +v0.8.9 a034926264cd1025c69d6ceb3fe444965f960b75 +v0.8.10 59accdd814398b884167c0f41dbf46dcccf0c29c +v0.8.11 d630ec9092f039cb5e51c5dd6d92fc47b91407e4 +v0.8.12 57871c99031cf597ffa0d819057ac1401e129f32 +v0.8.13 e43e6e876513450d235124fcb711f1724ed9814c +v0.8.14 71901c94dbbaa2f9f156a80c14cc7ea65219fc7c +v0.8.15 5a7c2f90361e72e9c35e88abd2e11acdc4aba354 +v0.8.16 f41dc62a12cc0f3cb8c5453c0caa0ba21e1bd01e +v0.9.0 58b84fb401a804967aa0dd5ee66fafa90194fd30 +v0.9.1 89f68bf0cbf53a81b0553d3816fdbe522f941fa1 +v0.9.2 c7d3b28b93faa6c955fb24bc64031512ee985ee9 +v0.9.3 8704c1ff952b5c85a44f50143bbd1a4f7b4887e2 +v0.9.4 fa310d9e2542cf497d92f007baec8fd751ffa99c +v0.9.5 3b1e9017c560499786d8a0e46aaaeea65037acac +v0.9.6 0b4d08fab8e35a264bc7383e878538f8083c33e5 +v0.9.7 f8cb04e4a8b032b72a909f68b808a50936184bee diff --git a/scripts/launch_corolla.sh b/scripts/launch_corolla.sh new file mode 100755 index 000000000000000..926569a1e0e13d1 --- /dev/null +++ b/scripts/launch_corolla.sh @@ -0,0 +1,7 @@ +#!/usr/bin/env bash + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" + +export FINGERPRINT="TOYOTA_COROLLA_TSS2" +export SKIP_FW_QUERY="1" +$DIR/../launch_openpilot.sh diff --git a/scripts/lint/check_nomerge_comments.sh b/scripts/lint/check_nomerge_comments.sh new file mode 100755 index 000000000000000..6737d62a2053b2f --- /dev/null +++ b/scripts/lint/check_nomerge_comments.sh @@ -0,0 +1,10 @@ +#!/usr/bin/env bash + +FAIL=0 + +if grep -n '\(#\|//\)\([[:space:]]*\)NOMERGE' $@; then + echo -e "NOMERGE comments found! Remove them before merging\n" + FAIL=1 +fi + +exit $FAIL diff --git a/scripts/lint/check_shebang_format.sh b/scripts/lint/check_shebang_format.sh new file mode 100755 index 000000000000000..89b95d5929a3b20 --- /dev/null +++ b/scripts/lint/check_shebang_format.sh @@ -0,0 +1,15 @@ +#!/usr/bin/env bash + +FAIL=0 + +if grep '^#!.*python' $@ | grep -v '#!/usr/bin/env python3$'; then + echo -e "Invalid shebang! Must use '#!/usr/bin/env python3'\n" + FAIL=1 +fi + +if grep '^#!.*bash' $@ | grep -v '#!/usr/bin/env bash$'; then + echo -e "Invalid shebang! Must use '#!/usr/bin/env bash'" + FAIL=1 +fi + +exit $FAIL diff --git a/scripts/lint/lint.sh b/scripts/lint/lint.sh new file mode 100755 index 000000000000000..578c63cd1894d4e --- /dev/null +++ b/scripts/lint/lint.sh @@ -0,0 +1,117 @@ +#!/usr/bin/env bash +set -e + +RED='\033[0;31m' +GREEN='\033[0;32m' +UNDERLINE='\033[4m' +BOLD='\033[1m' +NC='\033[0m' + +DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" +ROOT="$DIR/../../" +cd $ROOT + +FAILED=0 + +IGNORED_FILES="uv\.lock|docs\/CARS.md" +IGNORED_DIRS="^third_party.*|^msgq.*|^msgq_repo.*|^opendbc.*|^opendbc_repo.*|^cereal.*|^panda.*|^rednose.*|^rednose_repo.*|^tinygrad.*|^tinygrad_repo.*|^teleoprtc.*|^teleoprtc_repo.*" + +function run() { + shopt -s extglob + case $1 in + $SKIP | $RUN ) return 0 ;; + esac + + echo -en "$1" + + for ((i=0; i<$((50 - ${#1})); i++)); do + echo -n "." + done + + shift 1; + CMD="$@" + + set +e + log="$((eval "$CMD" ) 2>&1)" + + if [[ $? -eq 0 ]]; then + echo -e "[${GREEN}✔${NC}]" + else + echo -e "[${RED}✗${NC}]" + echo "$log" + FAILED=1 + fi + set -e +} + +function run_tests() { + ALL_FILES=$1 + PYTHON_FILES=$2 + + run "ruff" ruff check $ROOT --quiet + run "check_added_large_files" python3 -m pre_commit_hooks.check_added_large_files --enforce-all $ALL_FILES --maxkb=120 + run "check_shebang_scripts_are_executable" python3 -m pre_commit_hooks.check_shebang_scripts_are_executable $ALL_FILES + run "check_shebang_format" $DIR/check_shebang_format.sh $ALL_FILES + run "check_nomerge_comments" $DIR/check_nomerge_comments.sh $ALL_FILES + + if [[ -z "$FAST" ]]; then + run "mypy" mypy $PYTHON_FILES + run "codespell" codespell $ALL_FILES + fi + + return $FAILED +} + +function help() { + echo "A fast linter" + echo "" + echo -e "${BOLD}${UNDERLINE}Usage:${NC} op lint [TESTS] [OPTIONS]" + echo "" + echo -e "${BOLD}${UNDERLINE}Tests:${NC}" + echo -e " ${BOLD}ruff${NC}" + echo -e " ${BOLD}mypy${NC}" + echo -e " ${BOLD}codespell${NC}" + echo -e " ${BOLD}check_added_large_files${NC}" + echo -e " ${BOLD}check_shebang_scripts_are_executable${NC}" + echo "" + echo -e "${BOLD}${UNDERLINE}Options:${NC}" + echo -e " ${BOLD}-f, --fast${NC}" + echo " Skip slow tests" + echo -e " ${BOLD}-s, --skip${NC}" + echo " Specify tests to skip separated by spaces" + echo "" + echo -e "${BOLD}${UNDERLINE}Examples:${NC}" + echo " op lint mypy ruff" + echo " Only run the mypy and ruff tests" + echo "" + echo " op lint --skip mypy ruff" + echo " Skip the mypy and ruff tests" + echo "" + echo " op lint" + echo " Run all the tests" +} + +SKIP="" +RUN="" +while [[ $# -gt 0 ]]; do + case $1 in + -f | --fast ) shift 1; FAST="1" ;; + -s | --skip ) shift 1; SKIP=" " ;; + -h | --help | -help | --h ) help; exit 0 ;; + * ) if [[ -n $SKIP ]]; then SKIP+="$1 "; else RUN+="$1 "; fi; shift 1 ;; + esac +done + +RUN=$([ -z "$RUN" ] && echo "" || echo "!($(echo $RUN | sed 's/ /|/g'))") +SKIP="@($(echo $SKIP | sed 's/ /|/g'))" + +GIT_FILES="$(git ls-files | sed -E "s/$IGNORED_FILES|$IGNORED_DIRS//g")" +ALL_FILES="" +for f in $GIT_FILES; do + if [[ -f $f ]]; then + ALL_FILES+="$f"$'\n' + fi +done +PYTHON_FILES=$(echo "$ALL_FILES" | grep --color=never '.py$' || true) + +run_tests "$ALL_FILES" "$PYTHON_FILES" diff --git a/scripts/post-commit b/scripts/post-commit new file mode 100755 index 000000000000000..f9964639de41373 --- /dev/null +++ b/scripts/post-commit @@ -0,0 +1,7 @@ +#!/usr/bin/env bash +set -e +if [[ -f .git/hooks/post-commit.d/post-commit ]]; then + .git/hooks/post-commit.d/post-commit +fi +tools/op.sh lint --fast +echo "" diff --git a/scripts/pyqt_demo.py b/scripts/pyqt_demo.py new file mode 100755 index 000000000000000..783728bdb88e372 --- /dev/null +++ b/scripts/pyqt_demo.py @@ -0,0 +1,14 @@ +#!/usr/bin/env python3 + +from PyQt5.QtWidgets import QApplication, QLabel +from openpilot.selfdrive.ui.qt.python_helpers import set_main_window + + +if __name__ == "__main__": + app = QApplication([]) + label = QLabel('Hello World!') + + # Set full screen and rotate + set_main_window(label) + + app.exec_() diff --git a/scripts/retry.sh b/scripts/retry.sh new file mode 100755 index 000000000000000..23501d755959545 --- /dev/null +++ b/scripts/retry.sh @@ -0,0 +1,27 @@ +#!/usr/bin/env bash + +function fail { + echo $1 >&2 + exit 1 +} + +function retry { + local n=1 + local max=3 # 3 retries before failure + local delay=5 # delay between retries, 5 seconds + while true; do + echo "Running command '$@' with retry, attempt $n/$max" + "$@" && break || { + if [[ $n -lt $max ]]; then + ((n++)) + sleep $delay; + else + fail "The command has failed after $n attempts." + fi + } + done +} + +if [[ "${BASH_SOURCE[0]}" == "${0}" ]]; then + retry "$@" +fi diff --git a/scripts/stop_updater.sh b/scripts/stop_updater.sh new file mode 100755 index 000000000000000..703b3639282a48a --- /dev/null +++ b/scripts/stop_updater.sh @@ -0,0 +1,7 @@ +#!/usr/bin/env sh + +# Stop updater +pkill -2 -f system.updated.updated + +# Remove pending update +rm -f /data/safe_staging/finalized/.overlay_consistent diff --git a/scripts/update_now.sh b/scripts/update_now.sh new file mode 100755 index 000000000000000..c34228976a54e0b --- /dev/null +++ b/scripts/update_now.sh @@ -0,0 +1,4 @@ +#!/usr/bin/env sh + +# Send SIGHUP to updater +pkill -1 -f system.updated diff --git a/scripts/waste.c b/scripts/waste.c new file mode 100644 index 000000000000000..2e492916a73a899 --- /dev/null +++ b/scripts/waste.c @@ -0,0 +1,89 @@ +// gcc -O2 waste.c -lpthread -owaste +// gcc -O2 waste.c -lpthread -owaste -DMEM + +#define _GNU_SOURCE +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "../common/timing.h" + +int get_nprocs(void); +double *ttime, *oout; + +void waste(int pid) { + cpu_set_t my_set; + CPU_ZERO(&my_set); + CPU_SET(pid, &my_set); + int ret = sched_setaffinity(0, sizeof(cpu_set_t), &my_set); + printf("set affinity to %d: %d\n", pid, ret); + + // 128 MB + float32x4_t *tmp = (float32x4_t *)malloc(0x800000*sizeof(float32x4_t)); + + // comment out the memset for CPU only and not RAM + // otherwise we need this to avoid the zero page +#ifdef MEM + memset(tmp, 0xaa, 0x800000*sizeof(float32x4_t)); +#endif + + float32x4_t out; + + double sec = seconds_since_boot(); + while (1) { + for (int i = 0; i < 0x10; i++) { + for (int j = 0; j < 0x800000; j+=0x20) { + out = vmlaq_f32(out, tmp[j+0], tmp[j+1]); + out = vmlaq_f32(out, tmp[j+2], tmp[j+3]); + out = vmlaq_f32(out, tmp[j+4], tmp[j+5]); + out = vmlaq_f32(out, tmp[j+6], tmp[j+7]); + out = vmlaq_f32(out, tmp[j+8], tmp[j+9]); + out = vmlaq_f32(out, tmp[j+10], tmp[j+11]); + out = vmlaq_f32(out, tmp[j+12], tmp[j+13]); + out = vmlaq_f32(out, tmp[j+14], tmp[j+15]); + out = vmlaq_f32(out, tmp[j+16], tmp[j+17]); + out = vmlaq_f32(out, tmp[j+18], tmp[j+19]); + out = vmlaq_f32(out, tmp[j+20], tmp[j+21]); + out = vmlaq_f32(out, tmp[j+22], tmp[j+23]); + out = vmlaq_f32(out, tmp[j+24], tmp[j+25]); + out = vmlaq_f32(out, tmp[j+26], tmp[j+27]); + out = vmlaq_f32(out, tmp[j+28], tmp[j+29]); + out = vmlaq_f32(out, tmp[j+30], tmp[j+31]); + } + } + double nsec = seconds_since_boot(); + ttime[pid] = nsec-sec; + oout[pid] = out[0] + out[1] + out[2] + out[3]; + sec = nsec; + } +} + +int main() { + int CORES = get_nprocs(); + ttime = (double *)malloc(CORES*sizeof(double)); + oout = (double *)malloc(CORES*sizeof(double)); + + pthread_t waster[CORES]; + for (long i = 0; i < CORES; i++) { + ttime[i] = NAN; + pthread_create(&waster[i], NULL, (void *(*)(void *))waste, (void*)i); + } + while (1) { + double avg = 0.0; + double iavg = 0.0; + for (int i = 0; i < CORES; i++) { + avg += ttime[i]; + iavg += 1/ttime[i]; + printf("%4.2f ", ttime[i]); + } + double mb_per_sec = (16.*0x800000/(1024*1024))*sizeof(float32x4_t)*iavg; + printf("-- %4.2f -- %.2f MB/s \n", avg/CORES, mb_per_sec); + sleep(1); + } +} + diff --git a/scripts/waste.py b/scripts/waste.py new file mode 100755 index 000000000000000..0764ff77c37cb6b --- /dev/null +++ b/scripts/waste.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python3 +import os +import time +import numpy as np +from multiprocessing import Process +from setproctitle import setproctitle + +def waste(core): + os.sched_setaffinity(0, [core,]) + + m1 = np.zeros((200, 200)) + 0.8 + m2 = np.zeros((200, 200)) + 1.2 + + i = 1 + st = time.monotonic() + j = 0 + while 1: + if (i % 100) == 0: + setproctitle("%3d: %8d" % (core, i)) + lt = time.monotonic() + print("%3d: %8d %f %.2f" % (core, i, lt-st, j)) + st = lt + i += 1 + j = np.sum(np.matmul(m1, m2)) + +def main(gctx=None): + print("1-2 seconds is baseline") + for i in range(os.cpu_count()): + p = Process(target=waste, args=(i,)) + p.start() + +if __name__ == "__main__": + main() diff --git a/selfdrive/SConscript b/selfdrive/SConscript index 52898f758f2ae75..0b49e69116f395b 100644 --- a/selfdrive/SConscript +++ b/selfdrive/SConscript @@ -2,6 +2,5 @@ SConscript(['pandad/SConscript']) SConscript(['controls/lib/lateral_mpc_lib/SConscript']) SConscript(['controls/lib/longitudinal_mpc_lib/SConscript']) SConscript(['locationd/SConscript']) -SConscript(['navd/SConscript']) SConscript(['modeld/SConscript']) SConscript(['ui/SConscript']) \ No newline at end of file diff --git a/selfdrive/assets/compress-images.sh b/selfdrive/assets/compress-images.sh index a1a4f8bb40a4cf4..de59099bd133989 100755 --- a/selfdrive/assets/compress-images.sh +++ b/selfdrive/assets/compress-images.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash echo "compressing training guide images" optipng -o7 -strip all training/* diff --git a/selfdrive/assets/img_map.png b/selfdrive/assets/img_map.png deleted file mode 100644 index 8bdae4d7d81e0be..000000000000000 Binary files a/selfdrive/assets/img_map.png and /dev/null differ diff --git a/selfdrive/assets/navigation/default_marker.svg b/selfdrive/assets/navigation/default_marker.svg deleted file mode 100644 index 43d5290a96f56f6..000000000000000 --- a/selfdrive/assets/navigation/default_marker.svg +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/selfdrive/assets/navigation/direction_arrive.png b/selfdrive/assets/navigation/direction_arrive.png deleted file mode 100644 index 733c12909112694..000000000000000 Binary files a/selfdrive/assets/navigation/direction_arrive.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_arrive_left.png b/selfdrive/assets/navigation/direction_arrive_left.png deleted file mode 100644 index 92ff8e034141ac9..000000000000000 Binary files a/selfdrive/assets/navigation/direction_arrive_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_arrive_right.png b/selfdrive/assets/navigation/direction_arrive_right.png deleted file mode 100644 index f5983bfe61777aa..000000000000000 Binary files a/selfdrive/assets/navigation/direction_arrive_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_arrive_straight.png b/selfdrive/assets/navigation/direction_arrive_straight.png deleted file mode 100644 index 733c12909112694..000000000000000 Binary files a/selfdrive/assets/navigation/direction_arrive_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_close.png b/selfdrive/assets/navigation/direction_close.png deleted file mode 100644 index 4fdb5d195df1c07..000000000000000 Binary files a/selfdrive/assets/navigation/direction_close.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_continue.png b/selfdrive/assets/navigation/direction_continue.png deleted file mode 100644 index a01045ae6a2b586..000000000000000 Binary files a/selfdrive/assets/navigation/direction_continue.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_continue_left.png b/selfdrive/assets/navigation/direction_continue_left.png deleted file mode 100644 index 9a618026f0e00dd..000000000000000 Binary files a/selfdrive/assets/navigation/direction_continue_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_continue_right.png b/selfdrive/assets/navigation/direction_continue_right.png deleted file mode 100644 index 0fbaa3f253edb85..000000000000000 Binary files a/selfdrive/assets/navigation/direction_continue_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_continue_slight_left.png b/selfdrive/assets/navigation/direction_continue_slight_left.png deleted file mode 100644 index 08e964dbd6a68a9..000000000000000 Binary files a/selfdrive/assets/navigation/direction_continue_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_continue_slight_right.png b/selfdrive/assets/navigation/direction_continue_slight_right.png deleted file mode 100644 index 3e21cae11ed5209..000000000000000 Binary files a/selfdrive/assets/navigation/direction_continue_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_continue_straight.png b/selfdrive/assets/navigation/direction_continue_straight.png deleted file mode 100644 index a01045ae6a2b586..000000000000000 Binary files a/selfdrive/assets/navigation/direction_continue_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_continue_uturn.png b/selfdrive/assets/navigation/direction_continue_uturn.png deleted file mode 100644 index 0bd1b91777ed8d3..000000000000000 Binary files a/selfdrive/assets/navigation/direction_continue_uturn.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_depart.png b/selfdrive/assets/navigation/direction_depart.png deleted file mode 100644 index 4bf32c870d5f26d..000000000000000 Binary files a/selfdrive/assets/navigation/direction_depart.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_depart_left.png b/selfdrive/assets/navigation/direction_depart_left.png deleted file mode 100644 index 1f8d726911fcb7a..000000000000000 Binary files a/selfdrive/assets/navigation/direction_depart_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_depart_right.png b/selfdrive/assets/navigation/direction_depart_right.png deleted file mode 100644 index f359a685ffa5682..000000000000000 Binary files a/selfdrive/assets/navigation/direction_depart_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_depart_straight.png b/selfdrive/assets/navigation/direction_depart_straight.png deleted file mode 100644 index 4bf32c870d5f26d..000000000000000 Binary files a/selfdrive/assets/navigation/direction_depart_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_end_of_road_left.png b/selfdrive/assets/navigation/direction_end_of_road_left.png deleted file mode 100644 index 5c0a24e7cb11c45..000000000000000 Binary files a/selfdrive/assets/navigation/direction_end_of_road_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_end_of_road_right.png b/selfdrive/assets/navigation/direction_end_of_road_right.png deleted file mode 100644 index 8d9b89d36cdd610..000000000000000 Binary files a/selfdrive/assets/navigation/direction_end_of_road_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_flag.png b/selfdrive/assets/navigation/direction_flag.png deleted file mode 100644 index bad12ec6664679d..000000000000000 Binary files a/selfdrive/assets/navigation/direction_flag.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_fork.png b/selfdrive/assets/navigation/direction_fork.png deleted file mode 100644 index 3e0c262e2a2785e..000000000000000 Binary files a/selfdrive/assets/navigation/direction_fork.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_fork_left.png b/selfdrive/assets/navigation/direction_fork_left.png deleted file mode 100644 index b244b42b51e9066..000000000000000 Binary files a/selfdrive/assets/navigation/direction_fork_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_fork_right.png b/selfdrive/assets/navigation/direction_fork_right.png deleted file mode 100644 index aa3efaabca2cf7a..000000000000000 Binary files a/selfdrive/assets/navigation/direction_fork_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_fork_slight_left.png b/selfdrive/assets/navigation/direction_fork_slight_left.png deleted file mode 100644 index 82fa59859b603ee..000000000000000 Binary files a/selfdrive/assets/navigation/direction_fork_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_fork_slight_right.png b/selfdrive/assets/navigation/direction_fork_slight_right.png deleted file mode 100644 index 3596a2fbf2945d4..000000000000000 Binary files a/selfdrive/assets/navigation/direction_fork_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_fork_straight.png b/selfdrive/assets/navigation/direction_fork_straight.png deleted file mode 100644 index 86f30ab9b6edec7..000000000000000 Binary files a/selfdrive/assets/navigation/direction_fork_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_invalid.png b/selfdrive/assets/navigation/direction_invalid.png deleted file mode 100644 index a01045ae6a2b586..000000000000000 Binary files a/selfdrive/assets/navigation/direction_invalid.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_invalid_left.png b/selfdrive/assets/navigation/direction_invalid_left.png deleted file mode 100644 index 9a618026f0e00dd..000000000000000 Binary files a/selfdrive/assets/navigation/direction_invalid_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_invalid_right.png b/selfdrive/assets/navigation/direction_invalid_right.png deleted file mode 100644 index 0fbaa3f253edb85..000000000000000 Binary files a/selfdrive/assets/navigation/direction_invalid_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_invalid_slight_left.png b/selfdrive/assets/navigation/direction_invalid_slight_left.png deleted file mode 100644 index 08e964dbd6a68a9..000000000000000 Binary files a/selfdrive/assets/navigation/direction_invalid_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_invalid_slight_right.png b/selfdrive/assets/navigation/direction_invalid_slight_right.png deleted file mode 100644 index 3e21cae11ed5209..000000000000000 Binary files a/selfdrive/assets/navigation/direction_invalid_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_invalid_straight.png b/selfdrive/assets/navigation/direction_invalid_straight.png deleted file mode 100644 index a01045ae6a2b586..000000000000000 Binary files a/selfdrive/assets/navigation/direction_invalid_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_invalid_uturn.png b/selfdrive/assets/navigation/direction_invalid_uturn.png deleted file mode 100644 index 0bd1b91777ed8d3..000000000000000 Binary files a/selfdrive/assets/navigation/direction_invalid_uturn.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_merge_left.png b/selfdrive/assets/navigation/direction_merge_left.png deleted file mode 100644 index a713f52c56dddf6..000000000000000 Binary files a/selfdrive/assets/navigation/direction_merge_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_merge_right.png b/selfdrive/assets/navigation/direction_merge_right.png deleted file mode 100644 index 3390b31a05b26bb..000000000000000 Binary files a/selfdrive/assets/navigation/direction_merge_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_merge_slight_left.png b/selfdrive/assets/navigation/direction_merge_slight_left.png deleted file mode 100644 index 308f97b5a5d5b70..000000000000000 Binary files a/selfdrive/assets/navigation/direction_merge_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_merge_slight_right.png b/selfdrive/assets/navigation/direction_merge_slight_right.png deleted file mode 100644 index 8f5289011d67b43..000000000000000 Binary files a/selfdrive/assets/navigation/direction_merge_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_merge_straight.png b/selfdrive/assets/navigation/direction_merge_straight.png deleted file mode 100644 index 49c464389d2da20..000000000000000 Binary files a/selfdrive/assets/navigation/direction_merge_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_new_name_left.png b/selfdrive/assets/navigation/direction_new_name_left.png deleted file mode 100644 index 9a618026f0e00dd..000000000000000 Binary files a/selfdrive/assets/navigation/direction_new_name_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_new_name_right.png b/selfdrive/assets/navigation/direction_new_name_right.png deleted file mode 100644 index 0fbaa3f253edb85..000000000000000 Binary files a/selfdrive/assets/navigation/direction_new_name_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_new_name_sharp_left.png b/selfdrive/assets/navigation/direction_new_name_sharp_left.png deleted file mode 100644 index 77106b493ff6d51..000000000000000 Binary files a/selfdrive/assets/navigation/direction_new_name_sharp_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_new_name_sharp_right.png b/selfdrive/assets/navigation/direction_new_name_sharp_right.png deleted file mode 100644 index eb3a02f8b3adfe7..000000000000000 Binary files a/selfdrive/assets/navigation/direction_new_name_sharp_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_new_name_slight_left.png b/selfdrive/assets/navigation/direction_new_name_slight_left.png deleted file mode 100644 index 08e964dbd6a68a9..000000000000000 Binary files a/selfdrive/assets/navigation/direction_new_name_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_new_name_slight_right.png b/selfdrive/assets/navigation/direction_new_name_slight_right.png deleted file mode 100644 index 3e21cae11ed5209..000000000000000 Binary files a/selfdrive/assets/navigation/direction_new_name_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_new_name_straight.png b/selfdrive/assets/navigation/direction_new_name_straight.png deleted file mode 100644 index a01045ae6a2b586..000000000000000 Binary files a/selfdrive/assets/navigation/direction_new_name_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_notification_left.png b/selfdrive/assets/navigation/direction_notification_left.png deleted file mode 100644 index 9a618026f0e00dd..000000000000000 Binary files a/selfdrive/assets/navigation/direction_notification_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_notification_right.png b/selfdrive/assets/navigation/direction_notification_right.png deleted file mode 100644 index 0fbaa3f253edb85..000000000000000 Binary files a/selfdrive/assets/navigation/direction_notification_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_notification_sharp_left.png b/selfdrive/assets/navigation/direction_notification_sharp_left.png deleted file mode 100644 index dd8a4301db6dbee..000000000000000 Binary files a/selfdrive/assets/navigation/direction_notification_sharp_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_notification_sharp_right.png b/selfdrive/assets/navigation/direction_notification_sharp_right.png deleted file mode 100644 index a7e3c4cee56a7de..000000000000000 Binary files a/selfdrive/assets/navigation/direction_notification_sharp_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_notification_slight_left.png b/selfdrive/assets/navigation/direction_notification_slight_left.png deleted file mode 100644 index 08e964dbd6a68a9..000000000000000 Binary files a/selfdrive/assets/navigation/direction_notification_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_notification_slight_right.png b/selfdrive/assets/navigation/direction_notification_slight_right.png deleted file mode 100644 index 3e21cae11ed5209..000000000000000 Binary files a/selfdrive/assets/navigation/direction_notification_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_notification_straight.png b/selfdrive/assets/navigation/direction_notification_straight.png deleted file mode 100644 index a01045ae6a2b586..000000000000000 Binary files a/selfdrive/assets/navigation/direction_notification_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_off_ramp_left.png b/selfdrive/assets/navigation/direction_off_ramp_left.png deleted file mode 100644 index d3fd182893762ed..000000000000000 Binary files a/selfdrive/assets/navigation/direction_off_ramp_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_off_ramp_right.png b/selfdrive/assets/navigation/direction_off_ramp_right.png deleted file mode 100644 index 722e3f808f632c8..000000000000000 Binary files a/selfdrive/assets/navigation/direction_off_ramp_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_off_ramp_slight_left.png b/selfdrive/assets/navigation/direction_off_ramp_slight_left.png deleted file mode 100644 index ddac4aad6645923..000000000000000 Binary files a/selfdrive/assets/navigation/direction_off_ramp_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_off_ramp_slight_right.png b/selfdrive/assets/navigation/direction_off_ramp_slight_right.png deleted file mode 100644 index ed5760886451871..000000000000000 Binary files a/selfdrive/assets/navigation/direction_off_ramp_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_on_ramp_left.png b/selfdrive/assets/navigation/direction_on_ramp_left.png deleted file mode 100644 index 9a618026f0e00dd..000000000000000 Binary files a/selfdrive/assets/navigation/direction_on_ramp_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_on_ramp_right.png b/selfdrive/assets/navigation/direction_on_ramp_right.png deleted file mode 100644 index 0fbaa3f253edb85..000000000000000 Binary files a/selfdrive/assets/navigation/direction_on_ramp_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_on_ramp_sharp_left.png b/selfdrive/assets/navigation/direction_on_ramp_sharp_left.png deleted file mode 100644 index 77106b493ff6d51..000000000000000 Binary files a/selfdrive/assets/navigation/direction_on_ramp_sharp_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_on_ramp_sharp_right.png b/selfdrive/assets/navigation/direction_on_ramp_sharp_right.png deleted file mode 100644 index a7e3c4cee56a7de..000000000000000 Binary files a/selfdrive/assets/navigation/direction_on_ramp_sharp_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_on_ramp_slight_left.png b/selfdrive/assets/navigation/direction_on_ramp_slight_left.png deleted file mode 100644 index a5ea8a881e6b5e9..000000000000000 Binary files a/selfdrive/assets/navigation/direction_on_ramp_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_on_ramp_slight_right.png b/selfdrive/assets/navigation/direction_on_ramp_slight_right.png deleted file mode 100644 index f8ea3800e880fcf..000000000000000 Binary files a/selfdrive/assets/navigation/direction_on_ramp_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_on_ramp_straight.png b/selfdrive/assets/navigation/direction_on_ramp_straight.png deleted file mode 100644 index a01045ae6a2b586..000000000000000 Binary files a/selfdrive/assets/navigation/direction_on_ramp_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_rotary.png b/selfdrive/assets/navigation/direction_rotary.png deleted file mode 100644 index 2a5d264bd274263..000000000000000 Binary files a/selfdrive/assets/navigation/direction_rotary.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_rotary_left.png b/selfdrive/assets/navigation/direction_rotary_left.png deleted file mode 100644 index 0c4e4ab5e6cb838..000000000000000 Binary files a/selfdrive/assets/navigation/direction_rotary_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_rotary_right.png b/selfdrive/assets/navigation/direction_rotary_right.png deleted file mode 100644 index 32a6b2504ba9d91..000000000000000 Binary files a/selfdrive/assets/navigation/direction_rotary_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_rotary_sharp_left.png b/selfdrive/assets/navigation/direction_rotary_sharp_left.png deleted file mode 100644 index c84a6d96c01c676..000000000000000 Binary files a/selfdrive/assets/navigation/direction_rotary_sharp_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_rotary_sharp_right.png b/selfdrive/assets/navigation/direction_rotary_sharp_right.png deleted file mode 100644 index d15cbee00232cc8..000000000000000 Binary files a/selfdrive/assets/navigation/direction_rotary_sharp_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_rotary_slight_left.png b/selfdrive/assets/navigation/direction_rotary_slight_left.png deleted file mode 100644 index 3838e720a3553a7..000000000000000 Binary files a/selfdrive/assets/navigation/direction_rotary_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_rotary_slight_right.png b/selfdrive/assets/navigation/direction_rotary_slight_right.png deleted file mode 100644 index 8cd45fe61257481..000000000000000 Binary files a/selfdrive/assets/navigation/direction_rotary_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_rotary_straight.png b/selfdrive/assets/navigation/direction_rotary_straight.png deleted file mode 100644 index b6b0a7311bb2f5b..000000000000000 Binary files a/selfdrive/assets/navigation/direction_rotary_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_roundabout.png b/selfdrive/assets/navigation/direction_roundabout.png deleted file mode 100644 index 2a5d264bd274263..000000000000000 Binary files a/selfdrive/assets/navigation/direction_roundabout.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_roundabout_left.png b/selfdrive/assets/navigation/direction_roundabout_left.png deleted file mode 100644 index 0c4e4ab5e6cb838..000000000000000 Binary files a/selfdrive/assets/navigation/direction_roundabout_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_roundabout_right.png b/selfdrive/assets/navigation/direction_roundabout_right.png deleted file mode 100644 index 32a6b2504ba9d91..000000000000000 Binary files a/selfdrive/assets/navigation/direction_roundabout_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_roundabout_sharp_left.png b/selfdrive/assets/navigation/direction_roundabout_sharp_left.png deleted file mode 100644 index 1e8cce8c8e19d8e..000000000000000 Binary files a/selfdrive/assets/navigation/direction_roundabout_sharp_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_roundabout_sharp_right.png b/selfdrive/assets/navigation/direction_roundabout_sharp_right.png deleted file mode 100644 index d15cbee00232cc8..000000000000000 Binary files a/selfdrive/assets/navigation/direction_roundabout_sharp_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_roundabout_slight_left.png b/selfdrive/assets/navigation/direction_roundabout_slight_left.png deleted file mode 100644 index da1b1127051a19d..000000000000000 Binary files a/selfdrive/assets/navigation/direction_roundabout_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_roundabout_slight_right.png b/selfdrive/assets/navigation/direction_roundabout_slight_right.png deleted file mode 100644 index 8cd45fe61257481..000000000000000 Binary files a/selfdrive/assets/navigation/direction_roundabout_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_roundabout_straight.png b/selfdrive/assets/navigation/direction_roundabout_straight.png deleted file mode 100644 index b6b0a7311bb2f5b..000000000000000 Binary files a/selfdrive/assets/navigation/direction_roundabout_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_left.png b/selfdrive/assets/navigation/direction_turn_left.png deleted file mode 100644 index 9a618026f0e00dd..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_left_inactive.png b/selfdrive/assets/navigation/direction_turn_left_inactive.png deleted file mode 100644 index 2946984acd3252f..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_left_inactive.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_right.png b/selfdrive/assets/navigation/direction_turn_right.png deleted file mode 100644 index 0fbaa3f253edb85..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_right_inactive.png b/selfdrive/assets/navigation/direction_turn_right_inactive.png deleted file mode 100644 index 7d327766af13be2..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_right_inactive.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_sharp_left.png b/selfdrive/assets/navigation/direction_turn_sharp_left.png deleted file mode 100644 index dd8a4301db6dbee..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_sharp_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_sharp_right.png b/selfdrive/assets/navigation/direction_turn_sharp_right.png deleted file mode 100644 index a7e3c4cee56a7de..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_sharp_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_slight_left.png b/selfdrive/assets/navigation/direction_turn_slight_left.png deleted file mode 100644 index 08e964dbd6a68a9..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_slight_left.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_slight_left_inactive.png b/selfdrive/assets/navigation/direction_turn_slight_left_inactive.png deleted file mode 100644 index 37f1f83627230de..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_slight_left_inactive.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_slight_right.png b/selfdrive/assets/navigation/direction_turn_slight_right.png deleted file mode 100644 index 3e21cae11ed5209..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_slight_right.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_slight_right_inactive.png b/selfdrive/assets/navigation/direction_turn_slight_right_inactive.png deleted file mode 100644 index 8be224581142f30..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_slight_right_inactive.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_straight.png b/selfdrive/assets/navigation/direction_turn_straight.png deleted file mode 100644 index a01045ae6a2b586..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_straight.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_straight_inactive.png b/selfdrive/assets/navigation/direction_turn_straight_inactive.png deleted file mode 100644 index 4c567966ee8238f..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_straight_inactive.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_turn_uturn.png b/selfdrive/assets/navigation/direction_turn_uturn.png deleted file mode 100644 index 0bd1b91777ed8d3..000000000000000 Binary files a/selfdrive/assets/navigation/direction_turn_uturn.png and /dev/null differ diff --git a/selfdrive/assets/navigation/direction_updown.png b/selfdrive/assets/navigation/direction_updown.png deleted file mode 100644 index 16d0979f3ed040e..000000000000000 Binary files a/selfdrive/assets/navigation/direction_updown.png and /dev/null differ diff --git a/selfdrive/assets/navigation/home.png b/selfdrive/assets/navigation/home.png deleted file mode 100644 index 8a4f65c7d7a8367..000000000000000 Binary files a/selfdrive/assets/navigation/home.png and /dev/null differ diff --git a/selfdrive/assets/navigation/home.svg b/selfdrive/assets/navigation/home.svg deleted file mode 100644 index f5d89514c36bc08..000000000000000 --- a/selfdrive/assets/navigation/home.svg +++ /dev/null @@ -1,65 +0,0 @@ - - - - - - image/svg+xml - - - - - - - - - - diff --git a/selfdrive/assets/navigation/home_inactive.png b/selfdrive/assets/navigation/home_inactive.png deleted file mode 100644 index a58fd3864fdf30a..000000000000000 Binary files a/selfdrive/assets/navigation/home_inactive.png and /dev/null differ diff --git a/selfdrive/assets/navigation/icon_directions.svg b/selfdrive/assets/navigation/icon_directions.svg deleted file mode 100644 index 66009ac43ba426e..000000000000000 --- a/selfdrive/assets/navigation/icon_directions.svg +++ /dev/null @@ -1 +0,0 @@ - diff --git a/selfdrive/assets/navigation/icon_directions_outlined.svg b/selfdrive/assets/navigation/icon_directions_outlined.svg deleted file mode 100644 index 5c0c2fa3bef2a6f..000000000000000 --- a/selfdrive/assets/navigation/icon_directions_outlined.svg +++ /dev/null @@ -1 +0,0 @@ - diff --git a/selfdrive/assets/navigation/icon_favorite.svg b/selfdrive/assets/navigation/icon_favorite.svg deleted file mode 100644 index ba64df4ab915647..000000000000000 --- a/selfdrive/assets/navigation/icon_favorite.svg +++ /dev/null @@ -1 +0,0 @@ - \ No newline at end of file diff --git a/selfdrive/assets/navigation/icon_home.svg b/selfdrive/assets/navigation/icon_home.svg deleted file mode 100644 index cb870110907041c..000000000000000 --- a/selfdrive/assets/navigation/icon_home.svg +++ /dev/null @@ -1 +0,0 @@ - \ No newline at end of file diff --git a/selfdrive/assets/navigation/icon_recent.svg b/selfdrive/assets/navigation/icon_recent.svg deleted file mode 100644 index 668aa3820941035..000000000000000 --- a/selfdrive/assets/navigation/icon_recent.svg +++ /dev/null @@ -1 +0,0 @@ - \ No newline at end of file diff --git a/selfdrive/assets/navigation/icon_settings.svg b/selfdrive/assets/navigation/icon_settings.svg deleted file mode 100644 index 134cc0f31f418fb..000000000000000 --- a/selfdrive/assets/navigation/icon_settings.svg +++ /dev/null @@ -1 +0,0 @@ - diff --git a/selfdrive/assets/navigation/icon_work.svg b/selfdrive/assets/navigation/icon_work.svg deleted file mode 100644 index c1ea6c5e3b3486d..000000000000000 --- a/selfdrive/assets/navigation/icon_work.svg +++ /dev/null @@ -1 +0,0 @@ - \ No newline at end of file diff --git a/selfdrive/assets/navigation/work.png b/selfdrive/assets/navigation/work.png deleted file mode 100644 index 611f9b038dc9cd2..000000000000000 Binary files a/selfdrive/assets/navigation/work.png and /dev/null differ diff --git a/selfdrive/assets/navigation/work.svg b/selfdrive/assets/navigation/work.svg deleted file mode 100644 index 2da7bb7d39f2e90..000000000000000 --- a/selfdrive/assets/navigation/work.svg +++ /dev/null @@ -1,66 +0,0 @@ - - - - - - image/svg+xml - - - - - - - - - - diff --git a/selfdrive/assets/navigation/work_inactive.png b/selfdrive/assets/navigation/work_inactive.png deleted file mode 100644 index 679e6a54b2852e6..000000000000000 Binary files a/selfdrive/assets/navigation/work_inactive.png and /dev/null differ diff --git a/selfdrive/assets/offroad/icon_map.png b/selfdrive/assets/offroad/icon_map.png deleted file mode 100644 index 21dd0bacc65f76c..000000000000000 Binary files a/selfdrive/assets/offroad/icon_map.png and /dev/null differ diff --git a/selfdrive/assets/offroad/icon_map_speed.png b/selfdrive/assets/offroad/icon_map_speed.png deleted file mode 100644 index 1eeab84600e3f06..000000000000000 Binary files a/selfdrive/assets/offroad/icon_map_speed.png and /dev/null differ diff --git a/selfdrive/assets/offroad/icon_openpilot.png b/selfdrive/assets/offroad/icon_openpilot.png deleted file mode 100644 index 0a90a879106c894..000000000000000 Binary files a/selfdrive/assets/offroad/icon_openpilot.png and /dev/null differ diff --git a/selfdrive/assets/strip-svg-metadata.sh b/selfdrive/assets/strip-svg-metadata.sh index a8b35eadde300d6..e51dc9481d73a10 100755 --- a/selfdrive/assets/strip-svg-metadata.sh +++ b/selfdrive/assets/strip-svg-metadata.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash # sudo apt install scour diff --git a/selfdrive/car/README.md b/selfdrive/car/README.md deleted file mode 100644 index 2c49cf20511cc47..000000000000000 --- a/selfdrive/car/README.md +++ /dev/null @@ -1,19 +0,0 @@ -## Car port structure - -### interface.py -Generic interface to send and receive messages from CAN (controlsd uses this to communicate with car) - -### fingerprints.py -Fingerprints for matching to a specific car - -### carcontroller.py -Builds CAN messages to send to car - -##### carstate.py -Reads CAN from car and builds openpilot CarState message - -##### values.py -Limits for actuation, general constants for cars, and supported car documentation - -##### radar_interface.py -Interface for parsing radar points from the car diff --git a/selfdrive/car/__init__.py b/selfdrive/car/__init__.py index 4a1df550d055f4d..e69de29bb2d1d64 100644 --- a/selfdrive/car/__init__.py +++ b/selfdrive/car/__init__.py @@ -1,278 +0,0 @@ -# functions common among cars -from collections import namedtuple -from dataclasses import dataclass -from enum import IntFlag, ReprEnum, EnumType -from dataclasses import replace - -import capnp - -from cereal import car -from openpilot.common.numpy_fast import clip, interp -from openpilot.common.utils import Freezable -from openpilot.selfdrive.car.docs_definitions import CarDocs - - -# kg of standard extra cargo to count for drive, gas, etc... -STD_CARGO_KG = 136. - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -AngleRateLimit = namedtuple('AngleRateLimit', ['speed_bp', 'angle_v']) - - -def apply_hysteresis(val: float, val_steady: float, hyst_gap: float) -> float: - if val > val_steady + hyst_gap: - val_steady = val - hyst_gap - elif val < val_steady - hyst_gap: - val_steady = val + hyst_gap - return val_steady - - -def create_button_events(cur_btn: int, prev_btn: int, buttons_dict: dict[int, capnp.lib.capnp._EnumModule], - unpressed_btn: int = 0) -> list[capnp.lib.capnp._DynamicStructBuilder]: - events: list[capnp.lib.capnp._DynamicStructBuilder] = [] - - if cur_btn == prev_btn: - return events - - # Add events for button presses, multiple when a button switches without going to unpressed - for pressed, btn in ((False, prev_btn), (True, cur_btn)): - if btn != unpressed_btn: - events.append(car.CarState.ButtonEvent(pressed=pressed, - type=buttons_dict.get(btn, ButtonType.unknown))) - return events - - -def gen_empty_fingerprint(): - return {i: {} for i in range(8)} - - -# these params were derived for the Civic and used to calculate params for other cars -class VehicleDynamicsParams: - MASS = 1326. + STD_CARGO_KG - WHEELBASE = 2.70 - CENTER_TO_FRONT = WHEELBASE * 0.4 - CENTER_TO_REAR = WHEELBASE - CENTER_TO_FRONT - ROTATIONAL_INERTIA = 2500 - TIRE_STIFFNESS_FRONT = 192150 - TIRE_STIFFNESS_REAR = 202500 - - -# TODO: get actual value, for now starting with reasonable value for -# civic and scaling by mass and wheelbase -def scale_rot_inertia(mass, wheelbase): - return VehicleDynamicsParams.ROTATIONAL_INERTIA * mass * wheelbase ** 2 / (VehicleDynamicsParams.MASS * VehicleDynamicsParams.WHEELBASE ** 2) - - -# TODO: start from empirically derived lateral slip stiffness for the civic and scale by -# mass and CG position, so all cars will have approximately similar dyn behaviors -def scale_tire_stiffness(mass, wheelbase, center_to_front, tire_stiffness_factor): - center_to_rear = wheelbase - center_to_front - tire_stiffness_front = (VehicleDynamicsParams.TIRE_STIFFNESS_FRONT * tire_stiffness_factor) * mass / VehicleDynamicsParams.MASS * \ - (center_to_rear / wheelbase) / (VehicleDynamicsParams.CENTER_TO_REAR / VehicleDynamicsParams.WHEELBASE) - - tire_stiffness_rear = (VehicleDynamicsParams.TIRE_STIFFNESS_REAR * tire_stiffness_factor) * mass / VehicleDynamicsParams.MASS * \ - (center_to_front / wheelbase) / (VehicleDynamicsParams.CENTER_TO_FRONT / VehicleDynamicsParams.WHEELBASE) - - return tire_stiffness_front, tire_stiffness_rear - - -DbcDict = dict[str, str] - - -def dbc_dict(pt_dbc, radar_dbc, chassis_dbc=None, body_dbc=None) -> DbcDict: - return {'pt': pt_dbc, 'radar': radar_dbc, 'chassis': chassis_dbc, 'body': body_dbc} - - -def apply_driver_steer_torque_limits(apply_torque, apply_torque_last, driver_torque, LIMITS): - - # limits due to driver torque - driver_max_torque = LIMITS.STEER_MAX + (LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER - driver_min_torque = -LIMITS.STEER_MAX + (-LIMITS.STEER_DRIVER_ALLOWANCE + driver_torque * LIMITS.STEER_DRIVER_FACTOR) * LIMITS.STEER_DRIVER_MULTIPLIER - max_steer_allowed = max(min(LIMITS.STEER_MAX, driver_max_torque), 0) - min_steer_allowed = min(max(-LIMITS.STEER_MAX, driver_min_torque), 0) - apply_torque = clip(apply_torque, min_steer_allowed, max_steer_allowed) - - # slow rate if steer torque increases in magnitude - if apply_torque_last > 0: - apply_torque = clip(apply_torque, max(apply_torque_last - LIMITS.STEER_DELTA_DOWN, -LIMITS.STEER_DELTA_UP), - apply_torque_last + LIMITS.STEER_DELTA_UP) - else: - apply_torque = clip(apply_torque, apply_torque_last - LIMITS.STEER_DELTA_UP, - min(apply_torque_last + LIMITS.STEER_DELTA_DOWN, LIMITS.STEER_DELTA_UP)) - - return int(round(float(apply_torque))) - - -def apply_dist_to_meas_limits(val, val_last, val_meas, - STEER_DELTA_UP, STEER_DELTA_DOWN, - STEER_ERROR_MAX, STEER_MAX): - # limits due to comparison of commanded val VS measured val (torque/angle/curvature) - max_lim = min(max(val_meas + STEER_ERROR_MAX, STEER_ERROR_MAX), STEER_MAX) - min_lim = max(min(val_meas - STEER_ERROR_MAX, -STEER_ERROR_MAX), -STEER_MAX) - - val = clip(val, min_lim, max_lim) - - # slow rate if val increases in magnitude - if val_last > 0: - val = clip(val, - max(val_last - STEER_DELTA_DOWN, -STEER_DELTA_UP), - val_last + STEER_DELTA_UP) - else: - val = clip(val, - val_last - STEER_DELTA_UP, - min(val_last + STEER_DELTA_DOWN, STEER_DELTA_UP)) - - return float(val) - - -def apply_meas_steer_torque_limits(apply_torque, apply_torque_last, motor_torque, LIMITS): - return int(round(apply_dist_to_meas_limits(apply_torque, apply_torque_last, motor_torque, - LIMITS.STEER_DELTA_UP, LIMITS.STEER_DELTA_DOWN, - LIMITS.STEER_ERROR_MAX, LIMITS.STEER_MAX))) - - -def apply_std_steer_angle_limits(apply_angle, apply_angle_last, v_ego, LIMITS): - # pick angle rate limits based on wind up/down - steer_up = apply_angle_last * apply_angle >= 0. and abs(apply_angle) > abs(apply_angle_last) - rate_limits = LIMITS.ANGLE_RATE_LIMIT_UP if steer_up else LIMITS.ANGLE_RATE_LIMIT_DOWN - - angle_rate_lim = interp(v_ego, rate_limits.speed_bp, rate_limits.angle_v) - return clip(apply_angle, apply_angle_last - angle_rate_lim, apply_angle_last + angle_rate_lim) - - -def common_fault_avoidance(fault_condition: bool, request: bool, above_limit_frames: int, - max_above_limit_frames: int, max_mismatching_frames: int = 1): - """ - Several cars have the ability to work around their EPS limits by cutting the - request bit of their LKAS message after a certain number of frames above the limit. - """ - - # Count up to max_above_limit_frames, at which point we need to cut the request for above_limit_frames to avoid a fault - if request and fault_condition: - above_limit_frames += 1 - else: - above_limit_frames = 0 - - # Once we cut the request bit, count additionally to max_mismatching_frames before setting the request bit high again. - # Some brands do not respect our workaround without multiple messages on the bus, for example - if above_limit_frames > max_above_limit_frames: - request = False - - if above_limit_frames >= max_above_limit_frames + max_mismatching_frames: - above_limit_frames = 0 - - return above_limit_frames, request - - -def make_can_msg(addr, dat, bus): - return [addr, 0, dat, bus] - - -def get_safety_config(safety_model, safety_param = None): - ret = car.CarParams.SafetyConfig.new_message() - ret.safetyModel = safety_model - if safety_param is not None: - ret.safetyParam = safety_param - return ret - - -class CanBusBase: - offset: int - - def __init__(self, CP, fingerprint: dict[int, dict[int, int]] | None) -> None: - if CP is None: - assert fingerprint is not None - num = max([k for k, v in fingerprint.items() if len(v)], default=0) // 4 + 1 - else: - num = len(CP.safetyConfigs) - self.offset = 4 * (num - 1) - - -class CanSignalRateCalculator: - """ - Calculates the instantaneous rate of a CAN signal by using the counter - variable and the known frequency of the CAN message that contains it. - """ - def __init__(self, frequency): - self.frequency = frequency - self.previous_counter = 0 - self.previous_value = 0 - self.rate = 0 - - def update(self, current_value, current_counter): - if current_counter != self.previous_counter: - self.rate = (current_value - self.previous_value) * self.frequency - - self.previous_counter = current_counter - self.previous_value = current_value - - return self.rate - - -@dataclass(frozen=True, kw_only=True) -class CarSpecs: - mass: float # kg, curb weight - wheelbase: float # meters - steerRatio: float - centerToFrontRatio: float = 0.5 - minSteerSpeed: float = 0.0 # m/s - minEnableSpeed: float = -1.0 # m/s - tireStiffnessFactor: float = 1.0 - - def override(self, **kwargs): - return replace(self, **kwargs) - - -@dataclass(order=True) -class PlatformConfig(Freezable): - car_docs: list[CarDocs] - specs: CarSpecs - - dbc_dict: DbcDict - - flags: int = 0 - - platform_str: str | None = None - - def __hash__(self) -> int: - return hash(self.platform_str) - - def override(self, **kwargs): - return replace(self, **kwargs) - - def init(self): - pass - - def __post_init__(self): - self.init() - - -class PlatformsType(EnumType): - def __new__(metacls, cls, bases, classdict, *, boundary=None, _simple=False, **kwds): - for key in classdict._member_names.keys(): - cfg: PlatformConfig = classdict[key] - cfg.platform_str = key - cfg.freeze() - return super().__new__(metacls, cls, bases, classdict, boundary=boundary, _simple=_simple, **kwds) - - -class Platforms(str, ReprEnum, metaclass=PlatformsType): - config: PlatformConfig - - def __new__(cls, platform_config: PlatformConfig): - member = str.__new__(cls, platform_config.platform_str) - member.config = platform_config - member._value_ = platform_config.platform_str - return member - - def __repr__(self): - return f"<{self.__class__.__name__}.{self.name}>" - - @classmethod - def create_dbc_map(cls) -> dict[str, DbcDict]: - return {p: p.config.dbc_dict for p in cls} - - @classmethod - def with_flags(cls, flags: IntFlag) -> set['Platforms']: - return {p for p in cls if p.config.flags & flags} diff --git a/selfdrive/car/body/carcontroller.py b/selfdrive/car/body/carcontroller.py deleted file mode 100644 index 259126c416deed3..000000000000000 --- a/selfdrive/car/body/carcontroller.py +++ /dev/null @@ -1,84 +0,0 @@ -import numpy as np - -from openpilot.common.realtime import DT_CTRL -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car.body import bodycan -from openpilot.selfdrive.car.body.values import SPEED_FROM_RPM -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.controls.lib.pid import PIDController - - -MAX_TORQUE = 500 -MAX_TORQUE_RATE = 50 -MAX_ANGLE_ERROR = np.radians(7) -MAX_POS_INTEGRATOR = 0.2 # meters -MAX_TURN_INTEGRATOR = 0.1 # meters - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.frame = 0 - self.packer = CANPacker(dbc_name) - - # PIDs - self.turn_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) - self.wheeled_speed_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) - - self.torque_r_filtered = 0. - self.torque_l_filtered = 0. - - @staticmethod - def deadband_filter(torque, deadband): - if torque > 0: - torque += deadband - else: - torque -= deadband - return torque - - def update(self, CC, CS, now_nanos): - - torque_l = 0 - torque_r = 0 - - llk_valid = len(CC.orientationNED) > 1 and len(CC.angularVelocity) > 1 - if CC.enabled and llk_valid: - # Read these from the joystick - # TODO: this isn't acceleration, okay? - speed_desired = CC.actuators.accel / 5. - speed_diff_desired = -CC.actuators.steer / 2. - - speed_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl + CS.out.wheelSpeeds.fr) / 2. - speed_error = speed_desired - speed_measured - - torque = self.wheeled_speed_pid.update(speed_error, freeze_integrator=False) - - speed_diff_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl - CS.out.wheelSpeeds.fr) - turn_error = speed_diff_measured - speed_diff_desired - freeze_integrator = ((turn_error < 0 and self.turn_pid.error_integral <= -MAX_TURN_INTEGRATOR) or - (turn_error > 0 and self.turn_pid.error_integral >= MAX_TURN_INTEGRATOR)) - torque_diff = self.turn_pid.update(turn_error, freeze_integrator=freeze_integrator) - - # Combine 2 PIDs outputs - torque_r = torque + torque_diff - torque_l = torque - torque_diff - - # Torque rate limits - self.torque_r_filtered = np.clip(self.deadband_filter(torque_r, 10), - self.torque_r_filtered - MAX_TORQUE_RATE, - self.torque_r_filtered + MAX_TORQUE_RATE) - self.torque_l_filtered = np.clip(self.deadband_filter(torque_l, 10), - self.torque_l_filtered - MAX_TORQUE_RATE, - self.torque_l_filtered + MAX_TORQUE_RATE) - torque_r = int(np.clip(self.torque_r_filtered, -MAX_TORQUE, MAX_TORQUE)) - torque_l = int(np.clip(self.torque_l_filtered, -MAX_TORQUE, MAX_TORQUE)) - - can_sends = [] - can_sends.append(bodycan.create_control(self.packer, torque_l, torque_r)) - - new_actuators = CC.actuators.as_builder() - new_actuators.accel = torque_l - new_actuators.steer = torque_r - new_actuators.steerOutputCan = torque_r - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/body/carstate.py b/selfdrive/car/body/carstate.py deleted file mode 100644 index fca9bcc627432e7..000000000000000 --- a/selfdrive/car/body/carstate.py +++ /dev/null @@ -1,40 +0,0 @@ -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.body.values import DBC - -STARTUP_TICKS = 100 - -class CarState(CarStateBase): - def update(self, cp): - ret = car.CarState.new_message() - - ret.wheelSpeeds.fl = cp.vl['MOTORS_DATA']['SPEED_L'] - ret.wheelSpeeds.fr = cp.vl['MOTORS_DATA']['SPEED_R'] - - ret.vEgoRaw = ((ret.wheelSpeeds.fl + ret.wheelSpeeds.fr) / 2.) * self.CP.wheelSpeedFactor - - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = False - - ret.steerFaultPermanent = any([cp.vl['VAR_VALUES']['MOTOR_ERR_L'], cp.vl['VAR_VALUES']['MOTOR_ERR_R'], - cp.vl['VAR_VALUES']['FAULT']]) - - ret.charging = cp.vl["BODY_DATA"]["CHARGER_CONNECTED"] == 1 - ret.fuelGauge = cp.vl["BODY_DATA"]["BATT_PERCENTAGE"] / 100 - - # irrelevant for non-car - ret.gearShifter = car.CarState.GearShifter.drive - ret.cruiseState.enabled = True - ret.cruiseState.available = True - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - ("MOTORS_DATA", 100), - ("VAR_VALUES", 10), - ("BODY_DATA", 1), - ] - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) diff --git a/selfdrive/car/body/fingerprints.py b/selfdrive/car/body/fingerprints.py deleted file mode 100644 index ab7a5f8d7b34080..000000000000000 --- a/selfdrive/car/body/fingerprints.py +++ /dev/null @@ -1,28 +0,0 @@ -# ruff: noqa: E501 -from cereal import car -from openpilot.selfdrive.car.body.values import CAR - -Ecu = car.CarParams.Ecu - -# debug ecu fw version is the git hash of the firmware - - -FINGERPRINTS = { - CAR.COMMA_BODY: [{ - 513: 8, 516: 8, 514: 3, 515: 4 - }], -} - -FW_VERSIONS = { - CAR.COMMA_BODY: { - (Ecu.engine, 0x720, None): [ - b'0.0.01', - b'0.3.00a', - b'02/27/2022', - ], - (Ecu.debug, 0x721, None): [ - b'166bd860', - b'dc780f85', - ], - }, -} diff --git a/selfdrive/car/body/interface.py b/selfdrive/car/body/interface.py deleted file mode 100644 index f797a7ecf8143e1..000000000000000 --- a/selfdrive/car/body/interface.py +++ /dev/null @@ -1,39 +0,0 @@ -import math -from cereal import car -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.body.values import SPEED_FROM_RPM - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.notCar = True - ret.carName = "body" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.body)] - - ret.minSteerSpeed = -math.inf - ret.maxLateralAccel = math.inf # TODO: set to a reasonable value - ret.steerLimitTimer = 1.0 - ret.steerActuatorDelay = 0. - - ret.wheelSpeedFactor = SPEED_FROM_RPM - - ret.radarUnavailable = True - ret.openpilotLongitudinalControl = True - ret.steerControlType = car.CarParams.SteerControlType.angle - - return ret - - def _update(self, c): - ret = self.CS.update(self.cp) - - # wait for everything to init first - if self.frame > int(5. / DT_CTRL): - # body always wants to enable - ret.init('events', 1) - ret.events[0].name = car.CarEvent.EventName.pcmEnable - ret.events[0].enable = True - self.frame += 1 - - return ret diff --git a/selfdrive/car/body/radar_interface.py b/selfdrive/car/body/radar_interface.py deleted file mode 100644 index e654bd61fd4afdc..000000000000000 --- a/selfdrive/car/body/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/body/values.py b/selfdrive/car/body/values.py deleted file mode 100644 index a1195f7cb539c3e..000000000000000 --- a/selfdrive/car/body/values.py +++ /dev/null @@ -1,40 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - -SPEED_FROM_RPM = 0.008587 - - -class CarControllerParams: - ANGLE_DELTA_BP = [0., 5., 15.] - ANGLE_DELTA_V = [5., .8, .15] # windup limit - ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit - LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower - STEER_THRESHOLD = 1.0 - - def __init__(self, CP): - pass - - -class CAR(Platforms): - COMMA_BODY = PlatformConfig( - [CarDocs("comma body", package="All")], - CarSpecs(mass=9, wheelbase=0.406, steerRatio=0.5, centerToFrontRatio=0.44), - dbc_dict('comma_body', None), - ) - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - bus=0, - ), - ], -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py deleted file mode 100644 index 66097339b182bc5..000000000000000 --- a/selfdrive/car/car_helpers.py +++ /dev/null @@ -1,219 +0,0 @@ -import os -import time -from collections.abc import Callable - -from cereal import car -from openpilot.common.params import Params -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.selfdrive.car.mock.values import CAR as MOCK -from openpilot.common.swaglog import cloudlog -import cereal.messaging as messaging -from openpilot.selfdrive.car import gen_empty_fingerprint -from openpilot.system.version import get_build_metadata - -FRAME_FINGERPRINT = 100 # 1s - -EventName = car.CarEvent.EventName - - -def get_startup_event(car_recognized, controller_available, fw_seen): - build_metadata = get_build_metadata() - if build_metadata.openpilot.comma_remote and build_metadata.tested_channel: - event = EventName.startup - else: - event = EventName.startupMaster - - if not car_recognized: - if fw_seen: - event = EventName.startupNoCar - else: - event = EventName.startupNoFw - elif car_recognized and not controller_available: - event = EventName.startupNoControl - return event - - -def get_one_can(logcan): - while True: - can = messaging.recv_one_retry(logcan) - if len(can.can) > 0: - return can - - -def load_interfaces(brand_names): - ret = {} - for brand_name in brand_names: - path = f'openpilot.selfdrive.car.{brand_name}' - CarInterface = __import__(path + '.interface', fromlist=['CarInterface']).CarInterface - CarState = __import__(path + '.carstate', fromlist=['CarState']).CarState - CarController = __import__(path + '.carcontroller', fromlist=['CarController']).CarController - for model_name in brand_names[brand_name]: - ret[model_name] = (CarInterface, CarController, CarState) - return ret - - -def _get_interface_names() -> dict[str, list[str]]: - # returns a dict of brand name and its respective models - brand_names = {} - for brand_name, brand_models in get_interface_attr("CAR").items(): - brand_names[brand_name] = [model.value for model in brand_models] - - return brand_names - - -# imports from directory selfdrive/car// -interface_names = _get_interface_names() -interfaces = load_interfaces(interface_names) - - -def can_fingerprint(next_can: Callable) -> tuple[str | None, dict[int, dict]]: - finger = gen_empty_fingerprint() - candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1 - frame = 0 - car_fingerprint = None - done = False - - while not done: - a = next_can() - - for can in a.can: - # The fingerprint dict is generated for all buses, this way the car interface - # can use it to detect a (valid) multipanda setup and initialize accordingly - if can.src < 128: - if can.src not in finger: - finger[can.src] = {} - finger[can.src][can.address] = len(can.dat) - - for b in candidate_cars: - # Ignore extended messages and VIN query response. - if can.src == b and can.address < 0x800 and can.address not in (0x7df, 0x7e0, 0x7e8): - candidate_cars[b] = eliminate_incompatible_cars(can, candidate_cars[b]) - - # if we only have one car choice and the time since we got our first - # message has elapsed, exit - for b in candidate_cars: - if len(candidate_cars[b]) == 1 and frame > FRAME_FINGERPRINT: - # fingerprint done - car_fingerprint = candidate_cars[b][0] - - # bail if no cars left or we've been waiting for more than 2s - failed = (all(len(cc) == 0 for cc in candidate_cars.values()) and frame > FRAME_FINGERPRINT) or frame > 200 - succeeded = car_fingerprint is not None - done = failed or succeeded - - frame += 1 - - return car_fingerprint, finger - - -# **** for use live only **** -def fingerprint(logcan, sendcan, num_pandas): - fixed_fingerprint = os.environ.get('FINGERPRINT', "") - skip_fw_query = os.environ.get('SKIP_FW_QUERY', False) - disable_fw_cache = os.environ.get('DISABLE_FW_CACHE', False) - ecu_rx_addrs = set() - params = Params() - - start_time = time.monotonic() - if not skip_fw_query: - cached_params = params.get("CarParamsCache") - if cached_params is not None: - with car.CarParams.from_bytes(cached_params) as cached_params: - if cached_params.carName == "mock": - cached_params = None - - 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_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 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, vin, ecu_rx_addrs, num_pandas=num_pandas) - cached = False - - exact_fw_match, fw_candidates = match_fw_to_car(car_fw, vin) - else: - vin_rx_addr, vin_rx_bus, vin = -1, -1, VIN_UNKNOWN - exact_fw_match, fw_candidates, car_fw = True, set(), [] - cached = False - - if not is_valid_vin(vin): - cloudlog.event("Malformed VIN", vin=vin, error=True) - vin = VIN_UNKNOWN - cloudlog.warning("VIN %s", vin) - params.put("CarVin", vin) - - # disable OBD multiplexing for CAN fingerprinting and potential ECU knockouts - set_obd_multiplexing(params, False) - params.put_bool("FirmwareQueryDone", True) - - fw_query_time = time.monotonic() - start_time - - # CAN fingerprint - # drain CAN socket so we get the latest messages - messaging.drain_sock_raw(logcan) - car_fingerprint, finger = can_fingerprint(lambda: get_one_can(logcan)) - - exact_match = True - source = car.CarParams.FingerprintSource.can - - # If FW query returns exactly 1 candidate, use it - if len(fw_candidates) == 1: - car_fingerprint = list(fw_candidates)[0] - source = car.CarParams.FingerprintSource.fw - exact_match = exact_fw_match - - if fixed_fingerprint: - car_fingerprint = fixed_fingerprint - source = car.CarParams.FingerprintSource.fixed - - 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, 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 - - -def get_car_interface(CP): - CarInterface, CarController, CarState = interfaces[CP.carFingerprint] - return CarInterface(CP, CarController, CarState) - - -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=repr(fingerprints), error=True) - candidate = "MOCK" - - CarInterface, _, _ = interfaces[candidate] - CP = CarInterface.get_params(candidate, fingerprints, car_fw, experimental_long_allowed, docs=False) - CP.carVin = vin - CP.carFw = car_fw - CP.fingerprintSource = source - CP.fuzzyFingerprint = not exact_match - - return get_car_interface(CP), CP - -def write_car_param(platform=MOCK.MOCK): - params = Params() - CarInterface, _, _ = interfaces[platform] - CP = CarInterface.get_non_essential_params(platform) - params.put("CarParams", CP.to_bytes()) - -def get_demo_car_params(): - platform = MOCK.MOCK - CarInterface, _, _ = interfaces[platform] - CP = CarInterface.get_non_essential_params(platform) - return CP diff --git a/selfdrive/car/car_specific.py b/selfdrive/car/car_specific.py new file mode 100644 index 000000000000000..94afec50e2a3903 --- /dev/null +++ b/selfdrive/car/car_specific.py @@ -0,0 +1,249 @@ +from collections import deque +from cereal import car, log +import cereal.messaging as messaging +from opendbc.car import DT_CTRL, structs +from opendbc.car.interfaces import MAX_CTRL_SPEED +from opendbc.car.volkswagen.values import CarControllerParams as VWCarControllerParams +from opendbc.car.hyundai.interface import ENABLE_BUTTONS as HYUNDAI_ENABLE_BUTTONS +from opendbc.car.hyundai.carstate import PREV_BUTTON_SAMPLES as HYUNDAI_PREV_BUTTON_SAMPLES + +from openpilot.selfdrive.selfdrived.events import Events + +ButtonType = structs.CarState.ButtonEvent.Type +GearShifter = structs.CarState.GearShifter +EventName = log.OnroadEvent.EventName +NetworkLocation = structs.CarParams.NetworkLocation + + +# TODO: the goal is to abstract this file into the CarState struct and make events generic +class MockCarState: + def __init__(self): + self.sm = messaging.SubMaster(['gpsLocation', 'gpsLocationExternal']) + + def update(self, CS: car.CarState): + self.sm.update(0) + gps_sock = 'gpsLocationExternal' if self.sm.recv_frame['gpsLocationExternal'] > 1 else 'gpsLocation' + + CS.vEgo = self.sm[gps_sock].speed + CS.vEgoRaw = self.sm[gps_sock].speed + + return CS + + +class CarSpecificEvents: + def __init__(self, CP: structs.CarParams): + self.CP = CP + + self.steering_unpressed = 0 + self.low_speed_alert = False + self.no_steer_warning = False + self.silent_steer_warning = True + + self.cruise_buttons: deque = deque([], maxlen=HYUNDAI_PREV_BUTTON_SAMPLES) + + def update(self, CS: car.CarState, CS_prev: car.CarState, CC: car.CarControl): + if self.CP.carName in ('body', 'mock'): + events = Events() + + elif self.CP.carName in ('subaru', 'mazda'): + events = self.create_common_events(CS, CS_prev) + + elif self.CP.carName == 'ford': + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.manumatic]) + + elif self.CP.carName == 'nissan': + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.brake]) + + elif self.CP.carName == 'chrysler': + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.low]) + + # Low speed steer alert hysteresis logic + if self.CP.minSteerSpeed > 0. and CS.vEgo < (self.CP.minSteerSpeed + 0.5): + self.low_speed_alert = True + elif CS.vEgo > (self.CP.minSteerSpeed + 1.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + elif self.CP.carName == 'honda': + events = self.create_common_events(CS, CS_prev, pcm_enable=False) + + if self.CP.pcmCruise and CS.vEgo < self.CP.minEnableSpeed: + events.add(EventName.belowEngageSpeed) + + if self.CP.pcmCruise: + # we engage when pcm is active (rising edge) + if CS.cruiseState.enabled and not CS_prev.cruiseState.enabled: + events.add(EventName.pcmEnable) + elif not CS.cruiseState.enabled and (CC.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl): + # it can happen that car cruise disables while comma system is enabled: need to + # keep braking if needed or if the speed is very low + if CS.vEgo < self.CP.minEnableSpeed + 2.: + # non loud alert if cruise disables below 25mph as expected (+ a little margin) + events.add(EventName.speedTooLow) + else: + events.add(EventName.cruiseDisabled) + if self.CP.minEnableSpeed > 0 and CS.vEgo < 0.001: + events.add(EventName.manualRestart) + + elif self.CP.carName == 'toyota': + events = self.create_common_events(CS, CS_prev) + + if self.CP.openpilotLongitudinalControl: + if CS.cruiseState.standstill and not CS.brakePressed: + events.add(EventName.resumeRequired) + if CS.vEgo < self.CP.minEnableSpeed: + events.add(EventName.belowEngageSpeed) + if CC.actuators.accel > 0.3: + # some margin on the actuator to not false trigger cancellation while stopping + events.add(EventName.speedTooLow) + if CS.vEgo < 0.001: + # while in standstill, send a user alert + events.add(EventName.manualRestart) + + elif self.CP.carName == 'gm': + # The ECM allows enabling on falling edge of set, but only rising edge of resume + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.sport, GearShifter.low, + GearShifter.eco, GearShifter.manumatic], + pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,)) + if not self.CP.pcmCruise: + if any(b.type == ButtonType.accelCruise and b.pressed for b in CS.buttonEvents): + events.add(EventName.buttonEnable) + + # Enabling at a standstill with brake is allowed + # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs + if CS.vEgo < self.CP.minEnableSpeed and not (CS.standstill and CS.brake >= 20 and + self.CP.networkLocation == NetworkLocation.fwdCamera): + events.add(EventName.belowEngageSpeed) + if CS.cruiseState.standstill: + events.add(EventName.resumeRequired) + if CS.vEgo < self.CP.minSteerSpeed: + events.add(EventName.belowSteerSpeed) + + elif self.CP.carName == 'volkswagen': + events = self.create_common_events(CS, CS_prev, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], + pcm_enable=not self.CP.openpilotLongitudinalControl, + enable_buttons=(ButtonType.setCruise, ButtonType.resumeCruise)) + + # Low speed steer alert hysteresis logic + if (self.CP.minSteerSpeed - 1e-3) > VWCarControllerParams.DEFAULT_MIN_STEER_SPEED and CS.vEgo < (self.CP.minSteerSpeed + 1.): + self.low_speed_alert = True + elif CS.vEgo > (self.CP.minSteerSpeed + 2.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + if self.CP.openpilotLongitudinalControl: + if CS.vEgo < self.CP.minEnableSpeed + 0.5: + events.add(EventName.belowEngageSpeed) + if CC.enabled and CS.vEgo < self.CP.minEnableSpeed: + events.add(EventName.speedTooLow) + + # TODO: this needs to be implemented generically in carState struct + # if CC.eps_timer_soft_disable_alert: # type: ignore[attr-defined] + # events.add(EventName.steerTimeLimit) + + elif self.CP.carName == 'hyundai': + # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state + # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons + # Main button also can trigger an engagement on these cars + self.cruise_buttons.append(any(ev.type in HYUNDAI_ENABLE_BUTTONS for ev in CS.buttonEvents)) + events = self.create_common_events(CS, CS_prev, pcm_enable=self.CP.pcmCruise, allow_enable=any(self.cruise_buttons)) + + # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) + if CS.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: + self.low_speed_alert = True + if CS.vEgo > (self.CP.minSteerSpeed + 4.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + else: + raise ValueError(f"Unsupported car: {self.CP.carName}") + + return events + + def create_common_events(self, CS: structs.CarState, CS_prev: car.CarState, extra_gears=None, pcm_enable=True, + allow_enable=True, enable_buttons=(ButtonType.accelCruise, ButtonType.decelCruise)): + events = Events() + + if CS.doorOpen: + events.add(EventName.doorOpen) + if CS.seatbeltUnlatched: + events.add(EventName.seatbeltNotLatched) + if CS.gearShifter != GearShifter.drive and (extra_gears is None or + CS.gearShifter not in extra_gears): + events.add(EventName.wrongGear) + if CS.gearShifter == GearShifter.reverse: + events.add(EventName.reverseGear) + if not CS.cruiseState.available: + events.add(EventName.wrongCarMode) + if CS.espDisabled: + events.add(EventName.espDisabled) + if CS.espActive: + events.add(EventName.espActive) + if CS.stockFcw: + events.add(EventName.stockFcw) + if CS.stockAeb: + events.add(EventName.stockAeb) + if CS.vEgo > MAX_CTRL_SPEED: + events.add(EventName.speedTooHigh) + if CS.cruiseState.nonAdaptive: + events.add(EventName.wrongCruiseMode) + if CS.brakeHoldActive and self.CP.openpilotLongitudinalControl: + events.add(EventName.brakeHold) + if CS.parkingBrake: + events.add(EventName.parkBrake) + if CS.accFaulted: + events.add(EventName.accFaulted) + if CS.steeringPressed: + events.add(EventName.steerOverride) + if CS.brakePressed and CS.standstill: + events.add(EventName.preEnableStandstill) + if CS.gasPressed: + events.add(EventName.gasPressedOverride) + if CS.vehicleSensorsInvalid: + events.add(EventName.vehicleSensorsInvalid) + if CS.invalidLkasSetting: + events.add(EventName.invalidLkasSetting) + if CS.lowSpeedAlert: + events.add(EventName.belowSteerSpeed) + + # Handle button presses + for b in CS.buttonEvents: + # Enable OP long on falling edge of enable buttons (defaults to accelCruise and decelCruise, overridable per-port) + if not self.CP.pcmCruise and (b.type in enable_buttons and not b.pressed): + events.add(EventName.buttonEnable) + # Disable on rising and falling edge of cancel for both stock and OP long + if b.type == ButtonType.cancel: + events.add(EventName.buttonCancel) + + # Handle permanent and temporary steering faults + self.steering_unpressed = 0 if CS.steeringPressed else self.steering_unpressed + 1 + if CS.steerFaultTemporary: + if CS.steeringPressed and (not CS_prev.steerFaultTemporary or self.no_steer_warning): + self.no_steer_warning = True + else: + self.no_steer_warning = False + + # if the user overrode recently, show a less harsh alert + if self.silent_steer_warning or CS.standstill or self.steering_unpressed < int(1.5 / DT_CTRL): + self.silent_steer_warning = True + events.add(EventName.steerTempUnavailableSilent) + else: + events.add(EventName.steerTempUnavailable) + else: + self.no_steer_warning = False + self.silent_steer_warning = False + if CS.steerFaultPermanent: + events.add(EventName.steerUnavailable) + + # we engage when pcm is active (rising edge) + # enabling can optionally be blocked by the car interface + if pcm_enable: + if CS.cruiseState.enabled and not CS_prev.cruiseState.enabled and allow_enable: + events.add(EventName.pcmEnable) + elif not CS.cruiseState.enabled: + events.add(EventName.pcmDisable) + + return events diff --git a/selfdrive/car/card.py b/selfdrive/car/card.py index d9ee020ba493b1d..92d9b7eb11ddfd2 100755 --- a/selfdrive/car/card.py +++ b/selfdrive/car/card.py @@ -1,59 +1,116 @@ #!/usr/bin/env python3 import os import time +import threading import cereal.messaging as messaging -from cereal import car +from cereal import car, log from panda import ALTERNATIVE_EXPERIENCE from openpilot.common.params import Params -from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper, DT_CTRL - -from openpilot.selfdrive.pandad import can_list_to_can_capnp -from openpilot.selfdrive.car.car_helpers import get_car, get_one_can -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.controls.lib.events import Events +from openpilot.common.realtime import config_realtime_process, Priority, Ratekeeper +from openpilot.common.swaglog import cloudlog, ForwardingHandler + +from opendbc.car import DT_CTRL, carlog, structs +from opendbc.car.can_definitions import CanData, CanRecvCallable, CanSendCallable +from opendbc.car.fw_versions import ObdCallback +from opendbc.car.car_helpers import get_car, get_radar_interface +from opendbc.car.interfaces import CarInterfaceBase, RadarInterfaceBase +from openpilot.selfdrive.pandad import can_capnp_to_list, can_list_to_can_capnp +from openpilot.selfdrive.car.cruise import VCruiseHelper +from openpilot.selfdrive.car.car_specific import MockCarState REPLAY = "REPLAY" in os.environ -EventName = car.CarEvent.EventName +EventName = log.OnroadEvent.EventName + +# forward +carlog.addHandler(ForwardingHandler(cloudlog)) + + +def obd_callback(params: Params) -> ObdCallback: + def set_obd_multiplexing(obd_multiplexing: bool): + if params.get_bool("ObdMultiplexingEnabled") != obd_multiplexing: + cloudlog.warning(f"Setting OBD multiplexing to {obd_multiplexing}") + params.remove("ObdMultiplexingChanged") + params.put_bool("ObdMultiplexingEnabled", obd_multiplexing) + params.get_bool("ObdMultiplexingChanged", block=True) + cloudlog.warning("OBD multiplexing set successfully") + return set_obd_multiplexing + + +def can_comm_callbacks(logcan: messaging.SubSocket, sendcan: messaging.PubSocket) -> tuple[CanRecvCallable, CanSendCallable]: + def can_recv(wait_for_one: bool = False) -> list[list[CanData]]: + """ + wait_for_one: wait the normal logcan socket timeout for a CAN packet, may return empty list if nothing comes + + Returns: CAN packets comprised of CanData objects for easy access + """ + ret = [] + for can in messaging.drain_sock(logcan, wait_for_one=wait_for_one): + ret.append([CanData(msg.address, msg.dat, msg.src) for msg in can.can]) + return ret + + def can_send(msgs: list[CanData]) -> None: + sendcan.send(can_list_to_can_capnp(msgs, msgtype='sendcan')) + + return can_recv, can_send class Car: CI: CarInterfaceBase + RI: RadarInterfaceBase + CP: car.CarParams - def __init__(self, CI=None): + def __init__(self, CI=None, RI=None) -> None: self.can_sock = messaging.sub_sock('can', timeout=20) self.sm = messaging.SubMaster(['pandaStates', 'carControl', 'onroadEvents']) - self.pm = messaging.PubMaster(['sendcan', 'carState', 'carParams', 'carOutput']) + self.pm = messaging.PubMaster(['sendcan', 'carState', 'carParams', 'carOutput', 'liveTracks']) self.can_rcv_cum_timeout_counter = 0 self.CC_prev = car.CarControl.new_message() - self.CS_prev = car.CarState.new_message() self.initialized_prev = False - self.last_actuators_output = car.CarControl.Actuators.new_message() + self.last_actuators_output = structs.CarControl.Actuators() self.params = Params() + self.can_callbacks = can_comm_callbacks(self.can_sock, self.pm.sock['sendcan']) + if CI is None: # wait for one pandaState and one CAN packet print("Waiting for CAN messages...") - get_one_can(self.can_sock) + while True: + can = messaging.recv_one_retry(self.can_sock) + if len(can.can) > 0: + break - 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) + num_pandas = len(messaging.recv_one_retry(self.sm.sock['pandaStates']).pandaStates) + + cached_params = None + cached_params_raw = self.params.get("CarParamsCache") + if cached_params_raw is not None: + with car.CarParams.from_bytes(cached_params_raw) as _cached_params: + cached_params = _cached_params + + self.CI = get_car(*self.can_callbacks, obd_callback(self.params), experimental_long_allowed, num_pandas, cached_params) + self.RI = get_radar_interface(self.CI.CP) + self.CP = self.CI.CP + + # continue onto next fingerprinting step in pandad + self.params.put_bool("FirmwareQueryDone", True) else: self.CI, self.CP = CI, CI.CP + self.RI = RI # set alternative experiences from parameters - self.disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") + disengage_on_accelerator = self.params.get_bool("DisengageOnAccelerator") self.CP.alternativeExperience = 0 - if not self.disengage_on_accelerator: + if not disengage_on_accelerator: self.CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS openpilot_enabled_toggle = self.params.get_bool("OpenpilotEnabledToggle") @@ -62,10 +119,22 @@ def __init__(self, CI=None): self.CP.passive = not controller_available or self.CP.dashcamOnly if self.CP.passive: - safety_config = car.CarParams.SafetyConfig.new_message() - safety_config.safetyModel = car.CarParams.SafetyModel.noOutput + safety_config = structs.CarParams.SafetyConfig() + safety_config.safetyModel = structs.CarParams.SafetyModel.noOutput self.CP.safetyConfigs = [safety_config] + if self.CP.secOcRequired and not self.params.get_bool("IsReleaseBranch"): + secoc_key = self.params.get("SecOCKey", encoding='utf8') + if secoc_key is not None: + saved_secoc_key = bytes.fromhex(secoc_key.strip()) + if len(saved_secoc_key) == 16: + self.CP.secOcKeyAvailable = True + self.CI.CS.secoc_key = saved_secoc_key + if controller_available: + self.CI.CC.secoc_key = saved_secoc_key + else: + cloudlog.warning("Saved SecOC key is invalid") + # Write previous route's CarParams prev_cp = self.params.get("CarParamsPersistent") if prev_cp is not None: @@ -77,17 +146,28 @@ def __init__(self, CI=None): self.params.put_nonblocking("CarParamsCache", cp_bytes) self.params.put_nonblocking("CarParamsPersistent", cp_bytes) - self.events = Events() + self.mock_carstate = MockCarState() + self.v_cruise_helper = VCruiseHelper(self.CP) + + self.is_metric = self.params.get_bool("IsMetric") + self.experimental_mode = self.params.get_bool("ExperimentalMode") # card is driven by can recv, expected at 100Hz self.rk = Ratekeeper(100, print_delay_threshold=None) - def state_update(self) -> car.CarState: + def state_update(self) -> tuple[car.CarState, structs.RadarDataT | None]: """carState update loop, driven by can""" - # Update carState from CAN can_strs = messaging.drain_sock_raw(self.can_sock, wait_for_one=True) - CS = self.CI.update(self.CC_prev, can_strs) + can_list = can_capnp_to_list(can_strs) + + # Update carState from CAN + CS = self.CI.update(can_list) + if self.CP.carName == 'mock': + CS = self.mock_carstate.update(CS) + + # Update radar tracks from CAN + RD: structs.RadarDataT | None = self.RI.update(can_list) self.sm.update(0) @@ -100,22 +180,14 @@ def state_update(self) -> car.CarState: if can_rcv_valid and REPLAY: self.can_log_mono_time = messaging.log_from_bytes(can_strs[0]).logMonoTime - return CS - - def update_events(self, CS: car.CarState) -> car.CarState: - self.events.clear() - - self.events.add_from_msg(CS.events) + # TODO: mirror the carState.cruiseState struct? + self.v_cruise_helper.update_v_cruise(CS, self.sm['carControl'].enabled, self.is_metric) + CS.vCruise = float(self.v_cruise_helper.v_cruise_kph) + CS.vCruiseCluster = float(self.v_cruise_helper.v_cruise_cluster_kph) - # Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0 - if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \ - (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)) or \ - (CS.regenBraking and (not self.CS_prev.regenBraking or not CS.standstill)): - self.events.add(EventName.pedalPressed) + return CS, RD - CS.events = self.events.to_msg() - - def state_publish(self, CS: car.CarState): + def state_publish(self, CS: car.CarState, RD: structs.RadarDataT | None): """carState and carParams publish loop""" # carParams - logged every 50 seconds (> 1 per segment) @@ -139,13 +211,19 @@ def state_publish(self, CS: car.CarState): cs_send.carState.cumLagMs = -self.rk.remaining * 1000. self.pm.send('carState', cs_send) + if RD is not None: + tracks_msg = messaging.new_message('liveTracks') + tracks_msg.valid = len(RD.errors) == 0 + tracks_msg.liveTracks = RD + self.pm.send('liveTracks', tracks_msg) + def controls_update(self, CS: car.CarState, CC: car.CarControl): """control update loop, driven by carControl""" if not self.initialized_prev: # Initialize CarInterface, once controls are ready # TODO: this can make us miss at least a few cycles when doing an ECU knockout - self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) + self.CI.init(self.CP, *self.can_callbacks) # signal pandad to switch to car safety mode self.params.put_bool_nonblocking("ControlsReady", True) @@ -158,24 +236,37 @@ def controls_update(self, CS: car.CarState, CC: car.CarControl): self.CC_prev = CC def step(self): - CS = self.state_update() + CS, RD = self.state_update() - self.update_events(CS) + if self.sm['carControl'].enabled and not self.CC_prev.enabled: + self.v_cruise_helper.initialize_v_cruise(CS, self.experimental_mode) - self.state_publish(CS) + self.state_publish(CS, RD) - initialized = (not any(e.name == EventName.controlsInitializing for e in self.sm['onroadEvents']) and + initialized = (not any(e.name == EventName.selfdriveInitializing for e in self.sm['onroadEvents']) and self.sm.seen['onroadEvents']) if not self.CP.passive and initialized: self.controls_update(CS, self.sm['carControl']) self.initialized_prev = initialized - self.CS_prev = CS.as_reader() + + 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 + time.sleep(0.1) def card_thread(self): - while True: - self.step() - self.rk.monitor_time() + e = threading.Event() + t = threading.Thread(target=self.params_thread, args=(e, )) + try: + t.start() + while True: + self.step() + self.rk.monitor_time() + finally: + e.set() + t.join() def main(): diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py deleted file mode 100644 index 85f53f68eb4f578..000000000000000 --- a/selfdrive/car/chrysler/carcontroller.py +++ /dev/null @@ -1,85 +0,0 @@ -from opendbc.can.packer import CANPacker -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car import apply_meas_steer_torque_limits -from openpilot.selfdrive.car.chrysler import chryslercan -from openpilot.selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams, ChryslerFlags -from openpilot.selfdrive.car.interfaces import CarControllerBase - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.apply_steer_last = 0 - self.frame = 0 - - self.hud_count = 0 - self.last_lkas_falling_edge = 0 - self.lkas_control_bit_prev = False - self.last_button_frame = 0 - - self.packer = CANPacker(dbc_name) - self.params = CarControllerParams(CP) - - def update(self, CC, CS, now_nanos): - can_sends = [] - - lkas_active = CC.latActive and self.lkas_control_bit_prev - - # cruise buttons - if (self.frame - self.last_button_frame)*DT_CTRL > 0.05: - das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 - - # ACC cancellation - if CC.cruiseControl.cancel: - self.last_button_frame = self.frame - can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True)) - - # ACC resume from standstill - elif CC.cruiseControl.resume: - self.last_button_frame = self.frame - can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True)) - - # HUD alerts - if self.frame % 25 == 0: - if CS.lkas_car_model != -1: - can_sends.append(chryslercan.create_lkas_hud(self.packer, self.CP, lkas_active, CC.hudControl.visualAlert, - self.hud_count, CS.lkas_car_model, CS.auto_high_beam)) - self.hud_count += 1 - - # steering - if self.frame % self.params.STEER_STEP == 0: - - # TODO: can we make this more sane? why is it different for all the cars? - lkas_control_bit = self.lkas_control_bit_prev - if CS.out.vEgo > self.CP.minSteerSpeed: - lkas_control_bit = True - elif self.CP.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: - if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): - lkas_control_bit = False - elif self.CP.carFingerprint in RAM_CARS: - if CS.out.vEgo < (self.CP.minSteerSpeed - 0.5): - lkas_control_bit = False - - # EPS faults if LKAS re-enables too quickly - lkas_control_bit = lkas_control_bit and (self.frame - self.last_lkas_falling_edge > 200) - - if not lkas_control_bit and self.lkas_control_bit_prev: - self.last_lkas_falling_edge = self.frame - self.lkas_control_bit_prev = lkas_control_bit - - # steer torque - new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_meas_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) - if not lkas_active or not lkas_control_bit: - apply_steer = 0 - self.apply_steer_last = apply_steer - - can_sends.append(chryslercan.create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_control_bit)) - - self.frame += 1 - - new_actuators = CC.actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - return new_actuators, can_sends diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py deleted file mode 100644 index 91b922c59685868..000000000000000 --- a/selfdrive/car/chrysler/carstate.py +++ /dev/null @@ -1,156 +0,0 @@ -from cereal import car -from openpilot.common.conversions import Conversions as CV -from opendbc.can.parser import CANParser -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.chrysler.values import DBC, STEER_THRESHOLD, RAM_CARS - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.CP = CP - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.auto_high_beam = 0 - self.button_counter = 0 - self.lkas_car_model = -1 - - if CP.carFingerprint in RAM_CARS: - self.shifter_values = can_define.dv["Transmission_Status"]["Gear_State"] - else: - self.shifter_values = can_define.dv["GEAR"]["PRNDL"] - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRUISE_BUTTONS"]["ACC_Distance_Dec"] - - # lock info - ret.doorOpen = any([cp.vl["BCM_1"]["DOOR_OPEN_FL"], - cp.vl["BCM_1"]["DOOR_OPEN_FR"], - cp.vl["BCM_1"]["DOOR_OPEN_RL"], - cp.vl["BCM_1"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = cp.vl["ORC_1"]["SEATBELT_DRIVER_UNLATCHED"] == 1 - - # brake pedal - ret.brake = 0 - ret.brakePressed = cp.vl["ESP_1"]['Brake_Pedal_State'] == 1 # Physical brake pedal switch - - # gas pedal - ret.gas = cp.vl["ECM_5"]["Accelerator_Position"] - ret.gasPressed = ret.gas > 1e-5 - - # car speed - if self.CP.carFingerprint in RAM_CARS: - ret.vEgoRaw = cp.vl["ESP_8"]["Vehicle_Speed"] * CV.KPH_TO_MS - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["Transmission_Status"]["Gear_State"], None)) - else: - ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2. - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = not ret.vEgoRaw > 0.001 - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["ESP_6"]["WHEEL_SPEED_FL"], - cp.vl["ESP_6"]["WHEEL_SPEED_FR"], - cp.vl["ESP_6"]["WHEEL_SPEED_RL"], - cp.vl["ESP_6"]["WHEEL_SPEED_RR"], - unit=1, - ) - - # button presses - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(200, cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1, - cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2) - ret.genericToggle = cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"] == 1 - - # steering wheel - ret.steeringAngleDeg = cp.vl["STEERING"]["STEERING_ANGLE"] + cp.vl["STEERING"]["STEERING_ANGLE_HP"] - ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] - ret.steeringTorque = cp.vl["EPS_2"]["COLUMN_TORQUE"] - ret.steeringTorqueEps = cp.vl["EPS_2"]["EPS_TORQUE_MOTOR"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - - # cruise state - cp_cruise = cp_cam if self.CP.carFingerprint in RAM_CARS else cp - - ret.cruiseState.available = cp_cruise.vl["DAS_3"]["ACC_AVAILABLE"] == 1 - ret.cruiseState.enabled = cp_cruise.vl["DAS_3"]["ACC_ACTIVE"] == 1 - ret.cruiseState.speed = cp_cruise.vl["DAS_4"]["ACC_SET_SPEED_KPH"] * CV.KPH_TO_MS - ret.cruiseState.nonAdaptive = cp_cruise.vl["DAS_4"]["ACC_STATE"] in (1, 2) # 1 NormalCCOn and 2 NormalCCSet - ret.cruiseState.standstill = cp_cruise.vl["DAS_3"]["ACC_STANDSTILL"] == 1 - ret.accFaulted = cp_cruise.vl["DAS_3"]["ACC_FAULTED"] != 0 - - if self.CP.carFingerprint in RAM_CARS: - # Auto High Beam isn't Located in this message on chrysler or jeep currently located in 729 message - self.auto_high_beam = cp_cam.vl["DAS_6"]['AUTO_HIGH_BEAM_ON'] - ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1 - else: - ret.steerFaultTemporary = cp.vl["EPS_2"]["LKAS_TEMPORARY_FAULT"] == 1 - ret.steerFaultPermanent = cp.vl["EPS_2"]["LKAS_STATE"] == 4 - - # blindspot sensors - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["BSM_1"]["LEFT_STATUS"] == 1 - ret.rightBlindspot = cp.vl["BSM_1"]["RIGHT_STATUS"] == 1 - - self.lkas_car_model = cp_cam.vl["DAS_6"]["CAR_MODEL"] - self.button_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] - - return ret - - @staticmethod - def get_cruise_messages(): - messages = [ - ("DAS_3", 50), - ("DAS_4", 50), - ] - return messages - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("ESP_1", 50), - ("EPS_2", 100), - ("ESP_6", 50), - ("STEERING", 100), - ("ECM_5", 50), - ("CRUISE_BUTTONS", 50), - ("STEERING_LEVERS", 10), - ("ORC_1", 2), - ("BCM_1", 1), - ] - - if CP.enableBsm: - messages.append(("BSM_1", 2)) - - if CP.carFingerprint in RAM_CARS: - messages += [ - ("ESP_8", 50), - ("EPS_3", 50), - ("Transmission_Status", 50), - ] - else: - messages += [ - ("GEAR", 50), - ("SPEED_1", 100), - ] - messages += CarState.get_cruise_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - ("DAS_6", 4), - ] - - if CP.carFingerprint in RAM_CARS: - messages += CarState.get_cruise_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/chrysler/fingerprints.py b/selfdrive/car/chrysler/fingerprints.py deleted file mode 100644 index 5072aad5c021929..000000000000000 --- a/selfdrive/car/chrysler/fingerprints.py +++ /dev/null @@ -1,706 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.chrysler.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.CHRYSLER_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.CHRYSLER_PACIFICA_2018: { - (Ecu.combinationMeter, 0x742, None): [ - b'68227902AF', - b'68227902AG', - b'68227902AH', - b'68227905AG', - b'68360252AC', - ], - (Ecu.srs, 0x744, None): [ - b'68211617AF', - b'68211617AG', - b'68358974AC', - b'68405937AA', - ], - (Ecu.abs, 0x747, None): [ - b'68222747AG', - b'68330876AA', - b'68330876AB', - b'68352227AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AA', - b'68226356AF', - b'68226356AH', - b'68226356AI', - ], - (Ecu.eps, 0x75a, None): [ - b'68288891AE', - b'68378884AA', - b'68525338AA', - b'68525338AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'68267018AO ', - b'68267020AJ ', - b'68303534AG ', - b'68303534AJ ', - b'68340762AD ', - b'68340764AD ', - b'68352652AE ', - b'68352654AE ', - b'68366851AH ', - b'68366853AE ', - b'68372861AF ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'68277370AJ', - b'68277370AM', - b'68277372AD', - b'68277372AE', - b'68277372AN', - b'68277374AA', - b'68277374AB', - b'68277374AD', - b'68277374AN', - b'68367471AC', - b'68380571AB', - ], - }, - CAR.CHRYSLER_PACIFICA_2020: { - (Ecu.combinationMeter, 0x742, None): [ - b'68405327AC', - b'68436233AB', - b'68436233AC', - b'68436234AB', - b'68436250AE', - b'68529067AA', - b'68594993AB', - b'68594994AB', - ], - (Ecu.srs, 0x744, None): [ - b'68405565AB', - b'68405565AC', - b'68444299AC', - b'68480707AC', - b'68480708AC', - b'68526663AB', - ], - (Ecu.abs, 0x747, None): [ - b'68397394AA', - b'68433480AB', - b'68453575AF', - b'68577676AA', - b'68593395AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AA', - b'04672758AB', - b'68417813AF', - b'68540436AA', - b'68540436AC', - b'68540436AD', - b'68598670AB', - b'68598670AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68416742AA', - b'68460393AA', - b'68460393AB', - b'68494461AB', - b'68494461AC', - b'68524936AA', - b'68524936AB', - b'68525338AB', - b'68594337AB', - b'68594340AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'68413871AD ', - b'68413871AE ', - b'68413871AH ', - b'68413871AI ', - b'68413873AH ', - b'68413873AI ', - b'68443120AE ', - b'68443123AC ', - b'68443125AC ', - b'68496647AI ', - b'68496647AJ ', - b'68496650AH ', - b'68496650AI ', - b'68496652AH ', - b'68526752AD ', - b'68526752AE ', - b'68526754AE ', - b'68536264AE ', - b'68700304AB ', - b'68700306AB ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'68414271AC', - b'68414271AD', - b'68414275AC', - b'68414275AD', - b'68443154AB', - b'68443155AC', - b'68443158AB', - b'68501050AD', - b'68501051AD', - b'68501055AD', - b'68527221AB', - b'68527223AB', - b'68586231AD', - b'68586233AD', - ], - }, - CAR.CHRYSLER_PACIFICA_2018_HYBRID: { - (Ecu.combinationMeter, 0x742, None): [ - b'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.CHRYSLER_PACIFICA_2019_HYBRID: { - (Ecu.combinationMeter, 0x742, None): [ - b'68405292AC', - b'68434956AC', - b'68434956AD', - b'68434960AE', - b'68434960AF', - b'68529064AB', - b'68594990AB', - ], - (Ecu.srs, 0x744, None): [ - b'68405567AB', - b'68405567AC', - b'68453076AD', - b'68480710AC', - b'68526665AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AB', - b'68417813AF', - b'68540436AA', - b'68540436AB', - b'68540436AC', - b'68540436AD', - b'68598670AB', - b'68598670AC', - ], - (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'68243549AG', - b'68302211AC', - b'68302212AD', - b'68302223AC', - b'68302246AC', - b'68331511AC', - b'68331574AC', - b'68331687AC', - b'68331690AC', - b'68340272AD', - ], - (Ecu.srs, 0x744, None): [ - b'68309533AA', - b'68316742AB', - b'68355363AB', - ], - (Ecu.abs, 0x747, None): [ - b'68252642AG', - b'68306178AD', - b'68336276AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672627AB', - b'68251506AF', - b'68332015AB', - ], - (Ecu.eps, 0x75a, None): [ - b'68276201AG', - b'68321644AB', - b'68321644AC', - b'68321646AC', - b'68321648AC', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035920AE ', - b'68252272AG ', - b'68284455AI ', - b'68284456AI ', - b'68284477AF ', - b'68325564AH ', - b'68325565AH ', - b'68325565AI ', - b'68325618AD ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035517AH', - b'68253222AF', - b'68311218AC', - b'68311223AF', - b'68311223AG', - b'68361911AE', - b'68361911AF', - b'68361911AH', - b'68361916AD', - ], - }, - CAR.JEEP_GRAND_CHEROKEE_2019: { - (Ecu.combinationMeter, 0x742, None): [ - b'68402703AB', - b'68402704AB', - b'68402708AB', - b'68402971AD', - b'68454144AD', - b'68454145AB', - b'68454152AB', - b'68454156AB', - b'68516650AB', - b'68516651AB', - b'68516669AB', - b'68516671AB', - b'68516683AB', - ], - (Ecu.srs, 0x744, None): [ - b'68355363AB', - b'68355364AB', - ], - (Ecu.abs, 0x747, None): [ - b'68408639AC', - b'68408639AD', - b'68499978AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672788AA', - b'68456722AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68417279AA', - b'68417280AA', - b'68417281AA', - b'68453431AA', - b'68453433AA', - b'68453435AA', - b'68499171AA', - b'68499171AB', - b'68501183AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035674AB ', - b'68412635AG ', - b'68412660AD ', - b'68422860AB', - b'68449435AE ', - b'68496223AA ', - b'68504959AD ', - b'68504960AD ', - b'68504993AC ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035707AA', - b'68419672AC', - b'68419678AB', - b'68423905AB', - b'68449258AC', - b'68495807AA', - b'68495807AB', - b'68503641AC', - b'68503664AC', - ], - }, - CAR.RAM_1500_5TH_GEN: { - (Ecu.combinationMeter, 0x742, None): [ - b'68294051AG', - b'68294051AI', - b'68294052AG', - b'68294052AH', - b'68294063AG', - b'68294063AH', - b'68294063AI', - b'68434846AC', - b'68434847AC', - b'68434849AC', - b'68434856AC', - b'68434858AC', - b'68434859AC', - b'68434860AC', - b'68453483AC', - b'68453483AD', - b'68453487AD', - b'68453491AC', - b'68453491AD', - b'68453499AD', - b'68453503AC', - b'68453503AD', - b'68453505AC', - b'68453505AD', - b'68453511AC', - b'68453513AC', - b'68453513AD', - b'68453514AD', - b'68505633AB', - b'68510277AG', - b'68510277AH', - b'68510280AG', - b'68510282AG', - b'68510282AH', - b'68510283AG', - b'68527346AE', - b'68527361AD', - b'68527375AD', - b'68527381AE', - b'68527382AE', - b'68527383AD', - b'68527387AE', - b'68527403AC', - b'68527403AD', - b'68546047AF', - b'68631938AA', - b'68631939AA', - b'68631940AA', - b'68631940AB', - b'68631942AA', - b'68631943AB', - ], - (Ecu.srs, 0x744, None): [ - b'68428609AB', - b'68441329AB', - b'68473844AB', - b'68490898AA', - b'68500728AA', - b'68615033AA', - b'68615034AA', - ], - (Ecu.abs, 0x747, None): [ - b'68292406AG', - b'68292406AH', - b'68432418AB', - b'68432418AC', - b'68432418AD', - b'68436004AD', - b'68436004AE', - b'68438454AC', - b'68438454AD', - b'68438456AE', - b'68438456AF', - b'68535469AB', - b'68535470AC', - b'68548900AB', - b'68586307AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672892AB', - b'04672932AB', - b'04672932AC', - b'22DTRHD_AA', - b'68320950AH', - b'68320950AI', - b'68320950AJ', - b'68320950AL', - b'68320950AM', - b'68454268AB', - b'68475160AE', - b'68475160AF', - b'68475160AG', - ], - (Ecu.eps, 0x75a, None): [ - b'21590101AA', - b'21590101AB', - b'68273275AF', - b'68273275AG', - b'68273275AH', - b'68312176AE', - b'68312176AG', - b'68440789AC', - b'68466110AA', - b'68466110AB', - b'68466113AA', - b'68469901AA', - b'68469907AA', - b'68522583AA', - b'68522583AB', - b'68522584AA', - b'68522585AB', - b'68552788AA', - b'68552789AA', - b'68552790AA', - b'68552791AB', - b'68552794AA', - b'68552794AD', - b'68585106AB', - b'68585107AB', - b'68585108AB', - b'68585109AB', - b'68585112AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035699AG ', - b'05035841AC ', - b'05035841AD ', - b'05036026AB ', - b'05036065AE ', - b'05036066AE ', - b'05036193AA ', - 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'68378742AI ', - b'68378742AK ', - 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'68467916AC ', - b'68467936AC ', - b'68500630AD', - b'68500630AE', - b'68500631AE', - b'68502719AC ', - b'68502722AC ', - b'68502733AC ', - b'68502734AF ', - b'68502740AF ', - b'68502741AF ', - b'68502742AC ', - b'68502742AF ', - b'68539650AD', - b'68539650AF', - b'68539651AD', - b'68586101AA ', - b'68586105AB ', - b'68629919AC ', - b'68629922AC ', - b'68629925AC ', - b'68629926AC ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035706AD', - b'05035842AB', - b'05036069AA', - b'05036181AA', - b'05149536AC', - b'05149537AC', - b'05149543AC', - b'68360078AL', - b'68360080AL', - b'68360080AM', - b'68360081AM', - b'68360085AJ', - b'68360085AL', - b'68360086AH', - b'68360086AK', - b'68384328AD', - b'68384332AD', - b'68445531AC', - b'68445533AB', - b'68445536AB', - b'68445537AB', - b'68466081AB', - b'68466087AB', - b'68484466AC', - b'68484467AC', - b'68484471AC', - b'68502994AD', - b'68502996AD', - b'68520867AE', - b'68520867AF', - b'68520870AC', - b'68540431AB', - b'68540433AB', - b'68551676AA', - b'68629935AB', - b'68629936AC', - ], - }, - CAR.RAM_HD_5TH_GEN: { - (Ecu.combinationMeter, 0x742, None): [ - b'68361606AH', - b'68437735AC', - b'68492693AD', - b'68525485AB', - b'68525487AB', - b'68525498AB', - b'68528791AF', - b'68628474AB', - ], - (Ecu.srs, 0x744, None): [ - b'68399794AC', - b'68428503AA', - b'68428505AA', - b'68428507AA', - ], - (Ecu.abs, 0x747, None): [ - b'68334977AH', - b'68455481AC', - b'68504022AA', - b'68504022AB', - b'68504022AC', - b'68530686AB', - b'68530686AC', - b'68544596AC', - b'68641704AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672895AB', - b'04672934AB', - b'56029827AG', - b'56029827AH', - b'68462657AE', - b'68484694AD', - b'68484694AE', - b'68615489AB', - ], - (Ecu.eps, 0x761, None): [ - b'68421036AC', - b'68507906AB', - b'68534023AC', - ], - (Ecu.engine, 0x7e0, None): [ - b'52370131AF', - b'52370231AF', - b'52370231AG', - b'52370491AA', - b'52370931CT', - b'52401032AE', - b'52421132AF', - b'52421332AF', - b'68527616AD ', - b'M2370131MB', - b'M2421132MB', - ], - }, - CAR.DODGE_DURANGO: { - (Ecu.combinationMeter, 0x742, None): [ - b'68454261AD', - b'68471535AE', - ], - (Ecu.srs, 0x744, None): [ - b'68355362AB', - b'68492238AD', - ], - (Ecu.abs, 0x747, None): [ - b'68408639AD', - b'68499978AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'68440581AE', - b'68456722AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68453435AA', - b'68498477AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035786AE ', - b'68449476AE ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035826AC', - b'68449265AC', - ], - }, -} diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py deleted file mode 100755 index 217a1a756c52614..000000000000000 --- a/selfdrive/car/chrysler/interface.py +++ /dev/null @@ -1,97 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.chrysler.values import CAR, RAM_HD, RAM_DT, RAM_CARS, ChryslerFlags -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "chrysler" - ret.dashcamOnly = candidate in RAM_HD - - # radar parsing needs some work, see https://github.com/commaai/openpilot/issues/26842 - ret.radarUnavailable = True # DBC[candidate]['radar'] is None - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.4 - - # safety config - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.chrysler)] - if candidate in RAM_HD: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_HD - elif candidate in RAM_DT: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_DT - - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - if candidate not in RAM_CARS: - # Newer FW versions standard on the following platforms, or flashed by a dealer onto older platforms have a higher minimum steering speed. - new_eps_platform = candidate in (CAR.CHRYSLER_PACIFICA_2019_HYBRID, CAR.CHRYSLER_PACIFICA_2020, CAR.JEEP_GRAND_CHEROKEE_2019, CAR.DODGE_DURANGO) - new_eps_firmware = any(fw.ecu == 'eps' and fw.fwVersion[:4] >= b"6841" for fw in car_fw) - if new_eps_platform or new_eps_firmware: - ret.flags |= ChryslerFlags.HIGHER_MIN_STEERING_SPEED.value - - # Chrysler - if candidate in (CAR.CHRYSLER_PACIFICA_2017_HYBRID, CAR.CHRYSLER_PACIFICA_2018, CAR.CHRYSLER_PACIFICA_2018_HYBRID, \ - CAR.CHRYSLER_PACIFICA_2019_HYBRID, CAR.CHRYSLER_PACIFICA_2020, CAR.DODGE_DURANGO): - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] - ret.lateralTuning.pid.kf = 0.00006 - - # Jeep - elif candidate in (CAR.JEEP_GRAND_CHEROKEE, CAR.JEEP_GRAND_CHEROKEE_2019): - ret.steerActuatorDelay = 0.2 - - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] - ret.lateralTuning.pid.kf = 0.00006 - - # Ram - elif candidate == CAR.RAM_1500_5TH_GEN: - ret.steerActuatorDelay = 0.2 - ret.wheelbase = 3.88 - # Older EPS FW allow steer to zero - if any(fw.ecu == 'eps' and b"68" < fw.fwVersion[:4] <= b"6831" for fw in car_fw): - ret.minSteerSpeed = 0. - - elif candidate == CAR.RAM_HD_5TH_GEN: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, 1.0, False) - - else: - raise ValueError(f"Unsupported car: {candidate}") - - if ret.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: - # TODO: allow these cars to steer down to 13 m/s if already engaged. - # TODO: Durango 2020 may be able to steer to zero once above 38 kph - ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged. - - ret.centerToFront = ret.wheelbase * 0.44 - ret.enableBsm = 720 in fingerprint[0] - - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - # events - events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low]) - - # Low speed steer alert hysteresis logic - if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 0.5): - self.low_speed_alert = True - elif ret.vEgo > (self.CP.minSteerSpeed + 1.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(car.CarEvent.EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py deleted file mode 100755 index d9829584228b4d1..000000000000000 --- a/selfdrive/car/chrysler/radar_interface.py +++ /dev/null @@ -1,86 +0,0 @@ -#!/usr/bin/env python3 -from opendbc.can.parser import CANParser -from cereal import car -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.chrysler.values import DBC - -RADAR_MSGS_C = list(range(0x2c2, 0x2d4+2, 2)) # c_ messages 706,...,724 -RADAR_MSGS_D = list(range(0x2a2, 0x2b4+2, 2)) # d_ messages -LAST_MSG = max(RADAR_MSGS_C + RADAR_MSGS_D) -NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) - -def _create_radar_can_parser(car_fingerprint): - dbc = DBC[car_fingerprint]['radar'] - if dbc is None: - return None - - msg_n = len(RADAR_MSGS_C) - # list of [(signal name, message name or number), (...)] - # [('RADAR_STATE', 1024), - # ('LONG_DIST', 1072), - # ('LONG_DIST', 1073), - # ('LONG_DIST', 1074), - # ('LONG_DIST', 1075), - - messages = list(zip(RADAR_MSGS_C + - RADAR_MSGS_D, - [20] * msg_n + # 20Hz (0.05s) - [20] * msg_n, strict=True)) # 20Hz (0.05s) - - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - -def _address_to_track(address): - if address in RADAR_MSGS_C: - return (address - RADAR_MSGS_C[0]) // 2 - if address in RADAR_MSGS_D: - return (address - RADAR_MSGS_D[0]) // 2 - raise ValueError("radar received unexpected address %d" % address) - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.CP = CP - self.rcp = _create_radar_can_parser(CP.carFingerprint) - self.updated_messages = set() - self.trigger_msg = LAST_MSG - - def update(self, can_strings): - if self.rcp is None or self.CP.radarUnavailable: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for ii in self.updated_messages: # ii should be the message ID as a number - cpt = self.rcp.vl[ii] - trackId = _address_to_track(ii) - - if trackId not in self.pts: - self.pts[trackId] = car.RadarData.RadarPoint.new_message() - self.pts[trackId].trackId = trackId - self.pts[trackId].aRel = float('nan') - self.pts[trackId].yvRel = float('nan') - self.pts[trackId].measured = True - - if 'LONG_DIST' in cpt: # c_* message - self.pts[trackId].dRel = cpt['LONG_DIST'] # from front of car - # our lat_dist is positive to the right in car's frame. - # TODO what does yRel want? - self.pts[trackId].yRel = cpt['LAT_DIST'] # in car frame's y axis, left is positive - else: # d_* message - self.pts[trackId].vRel = cpt['REL_SPEED'] - - # We want a list, not a dictionary. Filter out LONG_DIST==0 because that means it's not valid. - ret.points = [x for x in self.pts.values() if x.dRel != 0] - - self.updated_messages.clear() - return ret diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py deleted file mode 100644 index 42ea94cf86c0691..000000000000000 --- a/selfdrive/car/chrysler/values.py +++ /dev/null @@ -1,156 +0,0 @@ -from enum import IntFlag -from dataclasses import dataclass, field - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu - - -class ChryslerFlags(IntFlag): - # Detected flags - HIGHER_MIN_STEERING_SPEED = 1 - -@dataclass -class ChryslerCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC)" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.fca])) - - -@dataclass -class ChryslerPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion')) - - -@dataclass(frozen=True) -class ChryslerCarSpecs(CarSpecs): - minSteerSpeed: float = 3.8 # m/s - - -class CAR(Platforms): - # Chrysler - CHRYSLER_PACIFICA_2017_HYBRID = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica Hybrid 2017")], - ChryslerCarSpecs(mass=2242., wheelbase=3.089, steerRatio=16.2), - ) - CHRYSLER_PACIFICA_2018_HYBRID = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica Hybrid 2018")], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - CHRYSLER_PACIFICA_2019_HYBRID = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica Hybrid 2019-23")], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - CHRYSLER_PACIFICA_2018 = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica 2017-18")], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - CHRYSLER_PACIFICA_2020 = ChryslerPlatformConfig( - [ - ChryslerCarDocs("Chrysler Pacifica 2019-20"), - ChryslerCarDocs("Chrysler Pacifica 2021-23", package="All"), - ], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - - # Dodge - DODGE_DURANGO = ChryslerPlatformConfig( - [ChryslerCarDocs("Dodge Durango 2020-21")], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - - # Jeep - JEEP_GRAND_CHEROKEE = ChryslerPlatformConfig( # includes 2017 Trailhawk - [ChryslerCarDocs("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk")], - ChryslerCarSpecs(mass=1778., wheelbase=2.71, steerRatio=16.7), - ) - - JEEP_GRAND_CHEROKEE_2019 = ChryslerPlatformConfig( # includes 2020 Trailhawk - [ChryslerCarDocs("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4")], - JEEP_GRAND_CHEROKEE.specs, - ) - - # Ram - RAM_1500_5TH_GEN = ChryslerPlatformConfig( - [ChryslerCarDocs("Ram 1500 2019-24", car_parts=CarParts.common([CarHarness.ram]))], - ChryslerCarSpecs(mass=2493., wheelbase=3.88, steerRatio=16.3, minSteerSpeed=14.5), - dbc_dict('chrysler_ram_dt_generated', None), - ) - RAM_HD_5TH_GEN = ChryslerPlatformConfig( - [ - ChryslerCarDocs("Ram 2500 2020-24", car_parts=CarParts.common([CarHarness.ram])), - ChryslerCarDocs("Ram 3500 2019-22", car_parts=CarParts.common([CarHarness.ram])), - ], - ChryslerCarSpecs(mass=3405., wheelbase=3.785, steerRatio=15.61, minSteerSpeed=16.), - dbc_dict('chrysler_ram_hd_generated', None), - ) - - -class CarControllerParams: - def __init__(self, CP): - self.STEER_STEP = 2 # 50 Hz - self.STEER_ERROR_MAX = 80 - if CP.carFingerprint in RAM_HD: - self.STEER_DELTA_UP = 14 - self.STEER_DELTA_DOWN = 14 - self.STEER_MAX = 361 # higher than this faults the EPS - elif CP.carFingerprint in RAM_DT: - self.STEER_DELTA_UP = 6 - self.STEER_DELTA_DOWN = 6 - self.STEER_MAX = 261 # EPS allows more, up to 350? - else: - self.STEER_DELTA_UP = 3 - self.STEER_DELTA_DOWN = 3 - self.STEER_MAX = 261 # higher than this faults the EPS - - -STEER_THRESHOLD = 120 - -RAM_DT = {CAR.RAM_1500_5TH_GEN, } -RAM_HD = {CAR.RAM_HD_5TH_GEN, } -RAM_CARS = RAM_DT | RAM_HD - - -CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf132) -CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xf132) - -CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) -CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) - -CHRYSLER_RX_OFFSET = -0x280 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [CHRYSLER_VERSION_REQUEST], - [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], - rx_offset=CHRYSLER_RX_OFFSET, - bus=0, - ), - Request( - [CHRYSLER_VERSION_REQUEST], - [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.hybrid, Ecu.engine, Ecu.transmission], - bus=0, - ), - Request( - [CHRYSLER_SOFTWARE_VERSION_REQUEST], - [CHRYSLER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], - bus=0, - ), - ], - extra_ecus=[ - (Ecu.abs, 0x7e4, None), # alt address for abs on hybrids, NOTE: not on all hybrid platforms - ], -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/cruise.py b/selfdrive/car/cruise.py new file mode 100644 index 000000000000000..b92d0c74659db3e --- /dev/null +++ b/selfdrive/car/cruise.py @@ -0,0 +1,135 @@ +import math + +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.common.numpy_fast import clip + + +# WARNING: this value was determined based on the model's training distribution, +# model predictions above this speed can be unpredictable +# V_CRUISE's are in kph +V_CRUISE_MIN = 8 +V_CRUISE_MAX = 145 +V_CRUISE_UNSET = 255 +V_CRUISE_INITIAL = 40 +V_CRUISE_INITIAL_EXPERIMENTAL_MODE = 105 +IMPERIAL_INCREMENT = round(CV.MPH_TO_KPH, 1) # round here to avoid rounding errors incrementing set speed + +ButtonEvent = car.CarState.ButtonEvent +ButtonType = car.CarState.ButtonEvent.Type +CRUISE_LONG_PRESS = 50 +CRUISE_NEAREST_FUNC = { + ButtonType.accelCruise: math.ceil, + ButtonType.decelCruise: math.floor, +} +CRUISE_INTERVAL_SIGN = { + ButtonType.accelCruise: +1, + ButtonType.decelCruise: -1, +} + + +class VCruiseHelper: + def __init__(self, CP): + self.CP = CP + self.v_cruise_kph = V_CRUISE_UNSET + self.v_cruise_cluster_kph = V_CRUISE_UNSET + self.v_cruise_kph_last = 0 + self.button_timers = {ButtonType.decelCruise: 0, ButtonType.accelCruise: 0} + self.button_change_states = {btn: {"standstill": False, "enabled": False} for btn in self.button_timers} + + @property + def v_cruise_initialized(self): + return self.v_cruise_kph != V_CRUISE_UNSET + + def update_v_cruise(self, CS, enabled, is_metric): + self.v_cruise_kph_last = self.v_cruise_kph + + if CS.cruiseState.available: + if not self.CP.pcmCruise: + # if stock cruise is completely disabled, then we can use our own set speed logic + self._update_v_cruise_non_pcm(CS, enabled, is_metric) + self.v_cruise_cluster_kph = self.v_cruise_kph + self.update_button_timers(CS, enabled) + else: + self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH + self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH + if CS.cruiseState.speed == 0: + self.v_cruise_kph = V_CRUISE_UNSET + self.v_cruise_cluster_kph = V_CRUISE_UNSET + else: + self.v_cruise_kph = V_CRUISE_UNSET + self.v_cruise_cluster_kph = V_CRUISE_UNSET + + def _update_v_cruise_non_pcm(self, CS, enabled, is_metric): + # handle button presses. TODO: this should be in state_control, but a decelCruise press + # would have the effect of both enabling and changing speed is checked after the state transition + if not enabled: + return + + long_press = False + button_type = None + + v_cruise_delta = 1. if is_metric else IMPERIAL_INCREMENT + + for b in CS.buttonEvents: + if b.type.raw in self.button_timers and not b.pressed: + if self.button_timers[b.type.raw] > CRUISE_LONG_PRESS: + return # end long press + button_type = b.type.raw + break + else: + for k, timer in self.button_timers.items(): + if timer and timer % CRUISE_LONG_PRESS == 0: + button_type = k + long_press = True + break + + if button_type is None: + return + + # Don't adjust speed when pressing resume to exit standstill + cruise_standstill = self.button_change_states[button_type]["standstill"] or CS.cruiseState.standstill + if button_type == ButtonType.accelCruise and cruise_standstill: + return + + # Don't adjust speed if we've enabled since the button was depressed (some ports enable on rising edge) + if not self.button_change_states[button_type]["enabled"]: + return + + v_cruise_delta = v_cruise_delta * (5 if long_press else 1) + if long_press and self.v_cruise_kph % v_cruise_delta != 0: # partial interval + self.v_cruise_kph = CRUISE_NEAREST_FUNC[button_type](self.v_cruise_kph / v_cruise_delta) * v_cruise_delta + else: + self.v_cruise_kph += v_cruise_delta * CRUISE_INTERVAL_SIGN[button_type] + + # If set is pressed while overriding, clip cruise speed to minimum of vEgo + if CS.gasPressed and button_type in (ButtonType.decelCruise, ButtonType.setCruise): + self.v_cruise_kph = max(self.v_cruise_kph, CS.vEgo * CV.MS_TO_KPH) + + self.v_cruise_kph = clip(round(self.v_cruise_kph, 1), V_CRUISE_MIN, V_CRUISE_MAX) + + def update_button_timers(self, CS, enabled): + # increment timer for buttons still pressed + for k in self.button_timers: + if self.button_timers[k] > 0: + self.button_timers[k] += 1 + + for b in CS.buttonEvents: + if b.type.raw in self.button_timers: + # Start/end timer and store current state on change of button pressed + self.button_timers[b.type.raw] = 1 if b.pressed else 0 + self.button_change_states[b.type.raw] = {"standstill": CS.cruiseState.standstill, "enabled": enabled} + + def initialize_v_cruise(self, CS, experimental_mode: bool) -> None: + # initializing is handled by the PCM + if self.CP.pcmCruise: + return + + initial = V_CRUISE_INITIAL_EXPERIMENTAL_MODE if experimental_mode else V_CRUISE_INITIAL + + if any(b.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for b in CS.buttonEvents) and self.v_cruise_initialized: + self.v_cruise_kph = self.v_cruise_kph_last + else: + self.v_cruise_kph = int(round(clip(CS.vEgo * CV.MS_TO_KPH, initial, V_CRUISE_MAX))) + + self.v_cruise_cluster_kph = self.v_cruise_kph diff --git a/selfdrive/car/disable_ecu.py b/selfdrive/car/disable_ecu.py deleted file mode 100755 index 1f731f03441d182..000000000000000 --- a/selfdrive/car/disable_ecu.py +++ /dev/null @@ -1,49 +0,0 @@ -#!/usr/bin/env python3 -from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery -from openpilot.common.swaglog import cloudlog - -EXT_DIAG_REQUEST = b'\x10\x03' -EXT_DIAG_RESPONSE = b'\x50\x03' - -COM_CONT_RESPONSE = b'' - - -def disable_ecu(logcan, sendcan, bus=0, addr=0x7d0, sub_addr=None, com_cont_req=b'\x28\x83\x01', timeout=0.1, retry=10, debug=False): - """Silence an ECU by disabling sending and receiving messages using UDS 0x28. - The ECU will stay silent as long as openpilot keeps sending Tester Present. - - This is used to disable the radar in some cars. Openpilot will emulate the radar. - WARNING: THIS DISABLES AEB!""" - cloudlog.warning(f"ecu disable {hex(addr), sub_addr} ...") - - for i in range(retry): - try: - query = IsoTpParallelQuery(sendcan, logcan, bus, [(addr, sub_addr)], [EXT_DIAG_REQUEST], [EXT_DIAG_RESPONSE], debug=debug) - - for _, _ in query.get_data(timeout).items(): - cloudlog.warning("communication control disable tx/rx ...") - - query = IsoTpParallelQuery(sendcan, logcan, bus, [(addr, sub_addr)], [com_cont_req], [COM_CONT_RESPONSE], debug=debug) - query.get_data(0) - - cloudlog.warning("ecu disabled") - return True - - except Exception: - cloudlog.exception("ecu disable exception") - - cloudlog.error(f"ecu disable retry ({i + 1}) ...") - cloudlog.error("ecu disable failed") - return False - - -if __name__ == "__main__": - import time - import cereal.messaging as messaging - sendcan = messaging.pub_sock('sendcan') - logcan = messaging.sub_sock('can') - time.sleep(1) - - # honda bosch radar disable - disabled = disable_ecu(logcan, sendcan, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03', timeout=0.5, debug=False) - print(f"disabled: {disabled}") diff --git a/selfdrive/car/docs.py b/selfdrive/car/docs.py index 7bf6a6ad22293bd..f807fc320edbe07 100755 --- a/selfdrive/car/docs.py +++ b/selfdrive/car/docs.py @@ -1,72 +1,13 @@ #!/usr/bin/env python3 import argparse -from collections import defaultdict -import jinja2 import os -from enum import Enum -from natsort import natsorted -from cereal import car from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car import gen_empty_fingerprint -from openpilot.selfdrive.car.docs_definitions import CarDocs, Column, CommonFootnote, PartType -from openpilot.selfdrive.car.car_helpers import interfaces, get_interface_attr -from openpilot.selfdrive.car.values import PLATFORMS - - -def get_all_footnotes() -> dict[Enum, int]: - all_footnotes = list(CommonFootnote) - for footnotes in get_interface_attr("Footnote", ignore_none=True).values(): - all_footnotes.extend(footnotes) - return {fn: idx + 1 for idx, fn in enumerate(all_footnotes)} - +from opendbc.car.docs import get_all_car_docs, generate_cars_md CARS_MD_OUT = os.path.join(BASEDIR, "docs", "CARS.md") CARS_MD_TEMPLATE = os.path.join(BASEDIR, "selfdrive", "car", "CARS_template.md") - -def get_all_car_docs() -> list[CarDocs]: - all_car_docs: list[CarDocs] = [] - footnotes = get_all_footnotes() - for model, platform in PLATFORMS.items(): - car_docs = platform.config.car_docs - # If available, uses experimental longitudinal limits for the docs - CP = interfaces[model][0].get_params(platform, fingerprint=gen_empty_fingerprint(), - car_fw=[car.CarParams.CarFw(ecu="unknown")], experimental_long=True, docs=True) - - if CP.dashcamOnly or not len(car_docs): - continue - - # A platform can include multiple car models - for _car_docs in car_docs: - if not hasattr(_car_docs, "row"): - _car_docs.init_make(CP) - _car_docs.init(CP, footnotes) - all_car_docs.append(_car_docs) - - # Sort cars by make and model + year - sorted_cars: list[CarDocs] = natsorted(all_car_docs, key=lambda car: car.name.lower()) - return sorted_cars - - -def group_by_make(all_car_docs: list[CarDocs]) -> dict[str, list[CarDocs]]: - sorted_car_docs = defaultdict(list) - for car_docs in all_car_docs: - sorted_car_docs[car_docs.make].append(car_docs) - return dict(sorted_car_docs) - - -def generate_cars_md(all_car_docs: list[CarDocs], template_fn: str) -> str: - with open(template_fn) as f: - template = jinja2.Template(f.read(), trim_blocks=True, lstrip_blocks=True) - - footnotes = [fn.value.text for fn in get_all_footnotes()] - cars_md: str = template.render(all_car_docs=all_car_docs, PartType=PartType, - group_by_make=group_by_make, footnotes=footnotes, - Column=Column) - return cars_md - - if __name__ == "__main__": parser = argparse.ArgumentParser(description="Auto generates supported cars documentation", formatter_class=argparse.ArgumentDefaultsHelpFormatter) diff --git a/selfdrive/car/ecu_addrs.py b/selfdrive/car/ecu_addrs.py deleted file mode 100755 index e7a9fbcf2cef0d0..000000000000000 --- a/selfdrive/car/ecu_addrs.py +++ /dev/null @@ -1,95 +0,0 @@ -#!/usr/bin/env python3 -import capnp -import time - -import cereal.messaging as messaging -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.pandad import can_list_to_can_capnp -from openpilot.common.swaglog import cloudlog - - -def make_tester_present_msg(addr, bus, subaddr=None): - dat = [0x02, SERVICE_TYPE.TESTER_PRESENT, 0x0] - if subaddr is not None: - dat.insert(0, subaddr) - - dat.extend([0x0] * (8 - len(dat))) - return make_can_msg(addr, bytes(dat), bus) - - -def is_tester_present_response(msg: capnp.lib.capnp._DynamicStructReader, subaddr: int = None) -> bool: - # ISO-TP messages are always padded to 8 bytes - # tester present response is always a single frame - dat_offset = 1 if subaddr is not None else 0 - if len(msg.dat) == 8 and 1 <= msg.dat[dat_offset] <= 7: - # success response - if msg.dat[dat_offset + 1] == (SERVICE_TYPE.TESTER_PRESENT + 0x40): - return True - # error response - if msg.dat[dat_offset + 1] == 0x7F and msg.dat[dat_offset + 2] == SERVICE_TYPE.TESTER_PRESENT: - return True - return False - - -def get_all_ecu_addrs(logcan: messaging.SubSocket, sendcan: messaging.PubSocket, bus: int, timeout: float = 1, debug: bool = True) -> set[EcuAddrBusType]: - addr_list = [0x700 + i for i in range(256)] + [0x18da00f1 + (i << 8) for i in range(256)] - queries: set[EcuAddrBusType] = {(addr, None, bus) for addr in addr_list} - responses = queries - return get_ecu_addrs(logcan, sendcan, queries, responses, timeout=timeout, debug=debug) - - -def get_ecu_addrs(logcan: messaging.SubSocket, sendcan: messaging.PubSocket, queries: set[EcuAddrBusType], - responses: set[EcuAddrBusType], timeout: float = 1, debug: bool = False) -> set[EcuAddrBusType]: - ecu_responses: set[EcuAddrBusType] = set() # set((addr, subaddr, bus),) - try: - msgs = [make_tester_present_msg(addr, bus, subaddr) for addr, subaddr, bus in queries] - - messaging.drain_sock_raw(logcan) - sendcan.send(can_list_to_can_capnp(msgs, msgtype='sendcan')) - start_time = time.monotonic() - while time.monotonic() - start_time < timeout: - can_packets = messaging.drain_sock(logcan, wait_for_one=True) - for packet in can_packets: - for msg in packet.can: - if not len(msg.dat): - cloudlog.warning("ECU addr scan: skipping empty remote frame") - continue - - subaddr = None if (msg.address, None, msg.src) in responses else msg.dat[0] - if (msg.address, subaddr, msg.src) in responses and is_tester_present_response(msg, subaddr): - if debug: - print(f"CAN-RX: {hex(msg.address)} - 0x{bytes.hex(msg.dat)}") - if (msg.address, subaddr, msg.src) in ecu_responses: - print(f"Duplicate ECU address: {hex(msg.address)}") - ecu_responses.add((msg.address, subaddr, msg.src)) - except Exception: - cloudlog.exception("ECU addr scan exception") - return ecu_responses - - -if __name__ == "__main__": - import argparse - - parser = argparse.ArgumentParser(description='Get addresses of all ECUs') - parser.add_argument('--debug', action='store_true') - parser.add_argument('--bus', type=int, default=1) - parser.add_argument('--timeout', type=float, default=1.0) - args = parser.parse_args() - - logcan = messaging.sub_sock('can') - sendcan = messaging.pub_sock('sendcan') - - time.sleep(1.0) - - print("Getting ECU addresses ...") - ecu_addrs = get_all_ecu_addrs(logcan, sendcan, args.bus, args.timeout, debug=args.debug) - - print() - print("Found ECUs on addresses:") - for addr, subaddr, _ in ecu_addrs: - msg = f" 0x{hex(addr)}" - if subaddr is not None: - msg += f" (sub-address: {hex(subaddr)})" - print(msg) diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py deleted file mode 100644 index 1128a31c2937229..000000000000000 --- a/selfdrive/car/fingerprints.py +++ /dev/null @@ -1,347 +0,0 @@ -from openpilot.selfdrive.car.interfaces import get_interface_attr -from openpilot.selfdrive.car.body.values import CAR as BODY -from openpilot.selfdrive.car.chrysler.values import CAR as CHRYSLER -from openpilot.selfdrive.car.ford.values import CAR as FORD -from openpilot.selfdrive.car.gm.values import CAR as GM -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.hyundai.values import CAR as HYUNDAI -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA -from openpilot.selfdrive.car.mock.values import CAR as MOCK -from openpilot.selfdrive.car.nissan.values import CAR as NISSAN -from openpilot.selfdrive.car.subaru.values import CAR as SUBARU -from openpilot.selfdrive.car.tesla.values import CAR as TESLA -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.volkswagen.values import CAR as VW - -FW_VERSIONS = get_interface_attr('FW_VERSIONS', combine_brands=True, ignore_none=True) -_FINGERPRINTS = get_interface_attr('FINGERPRINTS', combine_brands=True, ignore_none=True) - -_DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes - - -def is_valid_for_fingerprint(msg, car_fingerprint: dict[int, int]): - adr = msg.address - # ignore addresses that are more than 11 bits - return (adr in car_fingerprint and car_fingerprint[adr] == len(msg.dat)) or adr >= 0x800 - - -def eliminate_incompatible_cars(msg, candidate_cars): - """Removes cars that could not have sent msg. - - Inputs: - msg: A cereal/log CanData message from the car. - candidate_cars: A list of cars to consider. - - Returns: - A list containing the subset of candidate_cars that could have sent msg. - """ - compatible_cars = [] - - for car_name in candidate_cars: - car_fingerprints = _FINGERPRINTS[car_name] - - for fingerprint in car_fingerprints: - # add alien debug address - if is_valid_for_fingerprint(msg, fingerprint | _DEBUG_ADDRESS): - compatible_cars.append(car_name) - break - - return compatible_cars - - -def all_known_cars(): - """Returns a list of all known car strings.""" - return list({*FW_VERSIONS.keys(), *_FINGERPRINTS.keys()}) - - -def all_legacy_fingerprint_cars(): - """Returns a list of all known car strings, FPv1 only.""" - return list(_FINGERPRINTS.keys()) - - -# A dict that maps old platform strings to their latest representations -MIGRATION = { - "ACURA ILX 2016 ACURAWATCH PLUS": HONDA.ACURA_ILX, - "ACURA RDX 2018 ACURAWATCH PLUS": HONDA.ACURA_RDX, - "ACURA RDX 2020 TECH": HONDA.ACURA_RDX_3G, - "AUDI A3": VW.AUDI_A3_MK3, - "HONDA ACCORD 2018 HYBRID TOURING": HONDA.HONDA_ACCORD, - "HONDA ACCORD 1.5T 2018": HONDA.HONDA_ACCORD, - "HONDA ACCORD 2018 LX 1.5T": HONDA.HONDA_ACCORD, - "HONDA ACCORD 2018 SPORT 2T": HONDA.HONDA_ACCORD, - "HONDA ACCORD 2T 2018": HONDA.HONDA_ACCORD, - "HONDA ACCORD HYBRID 2018": HONDA.HONDA_ACCORD, - "HONDA CIVIC 2016 TOURING": HONDA.HONDA_CIVIC, - "HONDA CIVIC HATCHBACK 2017 SEDAN/COUPE 2019": HONDA.HONDA_CIVIC_BOSCH, - "HONDA CIVIC SEDAN 1.6 DIESEL": HONDA.HONDA_CIVIC_BOSCH_DIESEL, - "HONDA CR-V 2016 EXECUTIVE": HONDA.HONDA_CRV_EU, - "HONDA CR-V 2016 TOURING": HONDA.HONDA_CRV, - "HONDA CR-V 2017 EX": HONDA.HONDA_CRV_5G, - "HONDA CR-V 2019 HYBRID": HONDA.HONDA_CRV_HYBRID, - "HONDA FIT 2018 EX": HONDA.HONDA_FIT, - "HONDA HRV 2019 TOURING": HONDA.HONDA_HRV, - "HONDA INSIGHT 2019 TOURING": HONDA.HONDA_INSIGHT, - "HONDA ODYSSEY 2018 EX-L": HONDA.HONDA_ODYSSEY, - "HONDA ODYSSEY 2019 EXCLUSIVE CHN": HONDA.HONDA_ODYSSEY_CHN, - "HONDA PILOT 2017 TOURING": HONDA.HONDA_PILOT, - "HONDA PILOT 2019 ELITE": HONDA.HONDA_PILOT, - "HONDA PILOT 2019": HONDA.HONDA_PILOT, - "HONDA PASSPORT 2021": HONDA.HONDA_PILOT, - "HONDA RIDGELINE 2017 BLACK EDITION": HONDA.HONDA_RIDGELINE, - "HYUNDAI ELANTRA LIMITED ULTIMATE 2017": HYUNDAI.HYUNDAI_ELANTRA, - "HYUNDAI SANTA FE LIMITED 2019": HYUNDAI.HYUNDAI_SANTA_FE, - "HYUNDAI TUCSON DIESEL 2019": HYUNDAI.HYUNDAI_TUCSON, - "KIA OPTIMA 2016": HYUNDAI.KIA_OPTIMA_G4, - "KIA OPTIMA 2019": HYUNDAI.KIA_OPTIMA_G4_FL, - "KIA OPTIMA SX 2019 & 2016": HYUNDAI.KIA_OPTIMA_G4_FL, - "LEXUS CT 200H 2018": TOYOTA.LEXUS_CTH, - "LEXUS ES 300H 2018": TOYOTA.LEXUS_ES, - "LEXUS ES 300H 2019": TOYOTA.LEXUS_ES_TSS2, - "LEXUS IS300 2018": TOYOTA.LEXUS_IS, - "LEXUS NX300 2018": TOYOTA.LEXUS_NX, - "LEXUS NX300H 2018": TOYOTA.LEXUS_NX, - "LEXUS RX 350 2016": TOYOTA.LEXUS_RX, - "LEXUS RX350 2020": TOYOTA.LEXUS_RX_TSS2, - "LEXUS RX450 HYBRID 2020": TOYOTA.LEXUS_RX_TSS2, - "TOYOTA SIENNA XLE 2018": TOYOTA.TOYOTA_SIENNA, - "TOYOTA C-HR HYBRID 2018": TOYOTA.TOYOTA_CHR, - "TOYOTA COROLLA HYBRID TSS2 2019": TOYOTA.TOYOTA_COROLLA_TSS2, - "TOYOTA RAV4 HYBRID 2019": TOYOTA.TOYOTA_RAV4_TSS2, - "LEXUS ES HYBRID 2019": TOYOTA.LEXUS_ES_TSS2, - "LEXUS NX HYBRID 2018": TOYOTA.LEXUS_NX, - "LEXUS NX HYBRID 2020": TOYOTA.LEXUS_NX_TSS2, - "LEXUS RX HYBRID 2020": TOYOTA.LEXUS_RX_TSS2, - "TOYOTA ALPHARD HYBRID 2021": TOYOTA.TOYOTA_ALPHARD_TSS2, - "TOYOTA AVALON HYBRID 2019": TOYOTA.TOYOTA_AVALON_2019, - "TOYOTA AVALON HYBRID 2022": TOYOTA.TOYOTA_AVALON_TSS2, - "TOYOTA CAMRY HYBRID 2018": TOYOTA.TOYOTA_CAMRY, - "TOYOTA CAMRY HYBRID 2021": TOYOTA.TOYOTA_CAMRY_TSS2, - "TOYOTA C-HR HYBRID 2022": TOYOTA.TOYOTA_CHR_TSS2, - "TOYOTA HIGHLANDER HYBRID 2020": TOYOTA.TOYOTA_HIGHLANDER_TSS2, - "TOYOTA RAV4 HYBRID 2022": TOYOTA.TOYOTA_RAV4_TSS2_2022, - "TOYOTA RAV4 HYBRID 2023": TOYOTA.TOYOTA_RAV4_TSS2_2023, - "TOYOTA HIGHLANDER HYBRID 2018": TOYOTA.TOYOTA_HIGHLANDER, - "LEXUS ES HYBRID 2018": TOYOTA.LEXUS_ES, - "LEXUS RX HYBRID 2017": TOYOTA.LEXUS_RX, - "HYUNDAI TUCSON HYBRID 4TH GEN": HYUNDAI.HYUNDAI_TUCSON_4TH_GEN, - "KIA SPORTAGE HYBRID 5TH GEN": HYUNDAI.KIA_SPORTAGE_5TH_GEN, - "KIA SORENTO PLUG-IN HYBRID 4TH GEN": HYUNDAI.KIA_SORENTO_HEV_4TH_GEN, - "CADILLAC ESCALADE ESV PLATINUM 2019": GM.CADILLAC_ESCALADE_ESV_2019, - - # Removal of platform_str, see https://github.com/commaai/openpilot/pull/31868/ - "COMMA BODY": BODY.COMMA_BODY, - "CHRYSLER PACIFICA HYBRID 2017": CHRYSLER.CHRYSLER_PACIFICA_2017_HYBRID, - "CHRYSLER PACIFICA HYBRID 2018": CHRYSLER.CHRYSLER_PACIFICA_2018_HYBRID, - "CHRYSLER PACIFICA HYBRID 2019": CHRYSLER.CHRYSLER_PACIFICA_2019_HYBRID, - "CHRYSLER PACIFICA 2018": CHRYSLER.CHRYSLER_PACIFICA_2018, - "CHRYSLER PACIFICA 2020": CHRYSLER.CHRYSLER_PACIFICA_2020, - "DODGE DURANGO 2021": CHRYSLER.DODGE_DURANGO, - "JEEP GRAND CHEROKEE V6 2018": CHRYSLER.JEEP_GRAND_CHEROKEE, - "JEEP GRAND CHEROKEE 2019": CHRYSLER.JEEP_GRAND_CHEROKEE_2019, - "RAM 1500 5TH GEN": CHRYSLER.RAM_1500_5TH_GEN, - "RAM HD 5TH GEN": CHRYSLER.RAM_HD_5TH_GEN, - "FORD BRONCO SPORT 1ST GEN": FORD.FORD_BRONCO_SPORT_MK1, - "FORD ESCAPE 4TH GEN": FORD.FORD_ESCAPE_MK4, - "FORD EXPLORER 6TH GEN": FORD.FORD_EXPLORER_MK6, - "FORD F-150 14TH GEN": FORD.FORD_F_150_MK14, - "FORD F-150 LIGHTNING 1ST GEN": FORD.FORD_F_150_LIGHTNING_MK1, - "FORD FOCUS 4TH GEN": FORD.FORD_FOCUS_MK4, - "FORD MAVERICK 1ST GEN": FORD.FORD_MAVERICK_MK1, - "FORD MUSTANG MACH-E 1ST GEN": FORD.FORD_MUSTANG_MACH_E_MK1, - "HOLDEN ASTRA RS-V BK 2017": GM.HOLDEN_ASTRA, - "CHEVROLET VOLT PREMIER 2017": GM.CHEVROLET_VOLT, - "CADILLAC ATS Premium Performance 2018": GM.CADILLAC_ATS, - "CHEVROLET MALIBU PREMIER 2017": GM.CHEVROLET_MALIBU, - "GMC ACADIA DENALI 2018": GM.GMC_ACADIA, - "BUICK LACROSSE 2017": GM.BUICK_LACROSSE, - "BUICK REGAL ESSENCE 2018": GM.BUICK_REGAL, - "CADILLAC ESCALADE 2017": GM.CADILLAC_ESCALADE, - "CADILLAC ESCALADE ESV 2016": GM.CADILLAC_ESCALADE_ESV, - "CADILLAC ESCALADE ESV 2019": GM.CADILLAC_ESCALADE_ESV_2019, - "CHEVROLET BOLT EUV 2022": GM.CHEVROLET_BOLT_EUV, - "CHEVROLET SILVERADO 1500 2020": GM.CHEVROLET_SILVERADO, - "CHEVROLET EQUINOX 2019": GM.CHEVROLET_EQUINOX, - "CHEVROLET TRAILBLAZER 2021": GM.CHEVROLET_TRAILBLAZER, - "HONDA ACCORD 2018": HONDA.HONDA_ACCORD, - "HONDA CIVIC (BOSCH) 2019": HONDA.HONDA_CIVIC_BOSCH, - "HONDA CIVIC SEDAN 1.6 DIESEL 2019": HONDA.HONDA_CIVIC_BOSCH_DIESEL, - "HONDA CIVIC 2022": HONDA.HONDA_CIVIC_2022, - "HONDA CR-V 2017": HONDA.HONDA_CRV_5G, - "HONDA CR-V HYBRID 2019": HONDA.HONDA_CRV_HYBRID, - "HONDA HR-V 2023": HONDA.HONDA_HRV_3G, - "ACURA RDX 2020": HONDA.ACURA_RDX_3G, - "HONDA INSIGHT 2019": HONDA.HONDA_INSIGHT, - "HONDA E 2020": HONDA.HONDA_E, - "ACURA ILX 2016": HONDA.ACURA_ILX, - "HONDA CR-V 2016": HONDA.HONDA_CRV, - "HONDA CR-V EU 2016": HONDA.HONDA_CRV_EU, - "HONDA FIT 2018": HONDA.HONDA_FIT, - "HONDA FREED 2020": HONDA.HONDA_FREED, - "HONDA HRV 2019": HONDA.HONDA_HRV, - "HONDA ODYSSEY 2018": HONDA.HONDA_ODYSSEY, - "HONDA ODYSSEY CHN 2019": HONDA.HONDA_ODYSSEY_CHN, - "ACURA RDX 2018": HONDA.ACURA_RDX, - "HONDA PILOT 2017": HONDA.HONDA_PILOT, - "HONDA RIDGELINE 2017": HONDA.HONDA_RIDGELINE, - "HONDA CIVIC 2016": HONDA.HONDA_CIVIC, - "HYUNDAI AZERA 6TH GEN": HYUNDAI.HYUNDAI_AZERA_6TH_GEN, - "HYUNDAI AZERA HYBRID 6TH GEN": HYUNDAI.HYUNDAI_AZERA_HEV_6TH_GEN, - "HYUNDAI ELANTRA 2017": HYUNDAI.HYUNDAI_ELANTRA, - "HYUNDAI I30 N LINE 2019 & GT 2018 DCT": HYUNDAI.HYUNDAI_ELANTRA_GT_I30, - "HYUNDAI ELANTRA 2021": HYUNDAI.HYUNDAI_ELANTRA_2021, - "HYUNDAI ELANTRA HYBRID 2021": HYUNDAI.HYUNDAI_ELANTRA_HEV_2021, - "HYUNDAI GENESIS 2015-2016": HYUNDAI.HYUNDAI_GENESIS, - "HYUNDAI IONIQ HYBRID 2017-2019": HYUNDAI.HYUNDAI_IONIQ, - "HYUNDAI IONIQ HYBRID 2020-2022": HYUNDAI.HYUNDAI_IONIQ_HEV_2022, - "HYUNDAI IONIQ ELECTRIC LIMITED 2019": HYUNDAI.HYUNDAI_IONIQ_EV_LTD, - "HYUNDAI IONIQ ELECTRIC 2020": HYUNDAI.HYUNDAI_IONIQ_EV_2020, - "HYUNDAI IONIQ PLUG-IN HYBRID 2019": HYUNDAI.HYUNDAI_IONIQ_PHEV_2019, - "HYUNDAI IONIQ PHEV 2020": HYUNDAI.HYUNDAI_IONIQ_PHEV, - "HYUNDAI KONA 2020": HYUNDAI.HYUNDAI_KONA, - "HYUNDAI KONA ELECTRIC 2019": HYUNDAI.HYUNDAI_KONA_EV, - "HYUNDAI KONA ELECTRIC 2022": HYUNDAI.HYUNDAI_KONA_EV_2022, - "HYUNDAI KONA ELECTRIC 2ND GEN": HYUNDAI.HYUNDAI_KONA_EV_2ND_GEN, - "HYUNDAI KONA HYBRID 2020": HYUNDAI.HYUNDAI_KONA_HEV, - "HYUNDAI SANTA FE 2019": HYUNDAI.HYUNDAI_SANTA_FE, - "HYUNDAI SANTA FE 2022": HYUNDAI.HYUNDAI_SANTA_FE_2022, - "HYUNDAI SANTA FE HYBRID 2022": HYUNDAI.HYUNDAI_SANTA_FE_HEV_2022, - "HYUNDAI SANTA FE PlUG-IN HYBRID 2022": HYUNDAI.HYUNDAI_SANTA_FE_PHEV_2022, - "HYUNDAI SONATA 2020": HYUNDAI.HYUNDAI_SONATA, - "HYUNDAI SONATA 2019": HYUNDAI.HYUNDAI_SONATA_LF, - "HYUNDAI STARIA 4TH GEN": HYUNDAI.HYUNDAI_STARIA_4TH_GEN, - "HYUNDAI TUCSON 2019": HYUNDAI.HYUNDAI_TUCSON, - "HYUNDAI PALISADE 2020": HYUNDAI.HYUNDAI_PALISADE, - "HYUNDAI VELOSTER 2019": HYUNDAI.HYUNDAI_VELOSTER, - "HYUNDAI SONATA HYBRID 2021": HYUNDAI.HYUNDAI_SONATA_HYBRID, - "HYUNDAI IONIQ 5 2022": HYUNDAI.HYUNDAI_IONIQ_5, - "HYUNDAI IONIQ 6 2023": HYUNDAI.HYUNDAI_IONIQ_6, - "HYUNDAI TUCSON 4TH GEN": HYUNDAI.HYUNDAI_TUCSON_4TH_GEN, - "HYUNDAI SANTA CRUZ 1ST GEN": HYUNDAI.HYUNDAI_SANTA_CRUZ_1ST_GEN, - "HYUNDAI CUSTIN 1ST GEN": HYUNDAI.HYUNDAI_CUSTIN_1ST_GEN, - "KIA FORTE E 2018 & GT 2021": HYUNDAI.KIA_FORTE, - "KIA K5 2021": HYUNDAI.KIA_K5_2021, - "KIA K5 HYBRID 2020": HYUNDAI.KIA_K5_HEV_2020, - "KIA K8 HYBRID 1ST GEN": HYUNDAI.KIA_K8_HEV_1ST_GEN, - "KIA NIRO EV 2020": HYUNDAI.KIA_NIRO_EV, - "KIA NIRO EV 2ND GEN": HYUNDAI.KIA_NIRO_EV_2ND_GEN, - "KIA NIRO HYBRID 2019": HYUNDAI.KIA_NIRO_PHEV, - "KIA NIRO PLUG-IN HYBRID 2022": HYUNDAI.KIA_NIRO_PHEV_2022, - "KIA NIRO HYBRID 2021": HYUNDAI.KIA_NIRO_HEV_2021, - "KIA NIRO HYBRID 2ND GEN": HYUNDAI.KIA_NIRO_HEV_2ND_GEN, - "KIA OPTIMA 4TH GEN": HYUNDAI.KIA_OPTIMA_G4, - "KIA OPTIMA 4TH GEN FACELIFT": HYUNDAI.KIA_OPTIMA_G4_FL, - "KIA OPTIMA HYBRID 2017 & SPORTS 2019": HYUNDAI.KIA_OPTIMA_H, - "KIA OPTIMA HYBRID 4TH GEN FACELIFT": HYUNDAI.KIA_OPTIMA_H_G4_FL, - "KIA SELTOS 2021": HYUNDAI.KIA_SELTOS, - "KIA SPORTAGE 5TH GEN": HYUNDAI.KIA_SPORTAGE_5TH_GEN, - "KIA SORENTO GT LINE 2018": HYUNDAI.KIA_SORENTO, - "KIA SORENTO 4TH GEN": HYUNDAI.KIA_SORENTO_4TH_GEN, - "KIA SORENTO HYBRID 4TH GEN": HYUNDAI.KIA_SORENTO_HEV_4TH_GEN, - "KIA STINGER GT2 2018": HYUNDAI.KIA_STINGER, - "KIA STINGER 2022": HYUNDAI.KIA_STINGER_2022, - "KIA CEED INTRO ED 2019": HYUNDAI.KIA_CEED, - "KIA EV6 2022": HYUNDAI.KIA_EV6, - "KIA CARNIVAL 4TH GEN": HYUNDAI.KIA_CARNIVAL_4TH_GEN, - "GENESIS GV60 ELECTRIC 1ST GEN": HYUNDAI.GENESIS_GV60_EV_1ST_GEN, - "GENESIS G70 2018": HYUNDAI.GENESIS_G70, - "GENESIS G70 2020": HYUNDAI.GENESIS_G70_2020, - "GENESIS GV70 1ST GEN": HYUNDAI.GENESIS_GV70_1ST_GEN, - "GENESIS G80 2017": HYUNDAI.GENESIS_G80, - "GENESIS G90 2017": HYUNDAI.GENESIS_G90, - "GENESIS GV80 2023": HYUNDAI.GENESIS_GV80, - "MAZDA CX-5": MAZDA.MAZDA_CX5, - "MAZDA CX-9": MAZDA.MAZDA_CX9, - "MAZDA 3": MAZDA.MAZDA_3, - "MAZDA 6": MAZDA.MAZDA_6, - "MAZDA CX-9 2021": MAZDA.MAZDA_CX9_2021, - "MAZDA CX-5 2022": MAZDA.MAZDA_CX5_2022, - "NISSAN X-TRAIL 2017": NISSAN.NISSAN_XTRAIL, - "NISSAN LEAF 2018": NISSAN.NISSAN_LEAF, - "NISSAN LEAF 2018 Instrument Cluster": NISSAN.NISSAN_LEAF_IC, - "NISSAN ROGUE 2019": NISSAN.NISSAN_ROGUE, - "NISSAN ALTIMA 2020": NISSAN.NISSAN_ALTIMA, - "SUBARU ASCENT LIMITED 2019": SUBARU.SUBARU_ASCENT, - "SUBARU OUTBACK 6TH GEN": SUBARU.SUBARU_OUTBACK, - "SUBARU LEGACY 7TH GEN": SUBARU.SUBARU_LEGACY, - "SUBARU IMPREZA LIMITED 2019": SUBARU.SUBARU_IMPREZA, - "SUBARU IMPREZA SPORT 2020": SUBARU.SUBARU_IMPREZA_2020, - "SUBARU CROSSTREK HYBRID 2020": SUBARU.SUBARU_CROSSTREK_HYBRID, - "SUBARU FORESTER 2019": SUBARU.SUBARU_FORESTER, - "SUBARU FORESTER HYBRID 2020": SUBARU.SUBARU_FORESTER_HYBRID, - "SUBARU FORESTER 2017 - 2018": SUBARU.SUBARU_FORESTER_PREGLOBAL, - "SUBARU LEGACY 2015 - 2018": SUBARU.SUBARU_LEGACY_PREGLOBAL, - "SUBARU OUTBACK 2015 - 2017": SUBARU.SUBARU_OUTBACK_PREGLOBAL, - "SUBARU OUTBACK 2018 - 2019": SUBARU.SUBARU_OUTBACK_PREGLOBAL_2018, - "SUBARU FORESTER 2022": SUBARU.SUBARU_FORESTER_2022, - "SUBARU OUTBACK 7TH GEN": SUBARU.SUBARU_OUTBACK_2023, - "SUBARU ASCENT 2023": SUBARU.SUBARU_ASCENT_2023, - 'TESLA AP1 MODEL S': TESLA.TESLA_AP1_MODELS, - 'TESLA AP2 MODEL S': TESLA.TESLA_AP2_MODELS, - 'TESLA MODEL S RAVEN': TESLA.TESLA_MODELS_RAVEN, - "TOYOTA ALPHARD 2020": TOYOTA.TOYOTA_ALPHARD_TSS2, - "TOYOTA AVALON 2016": TOYOTA.TOYOTA_AVALON, - "TOYOTA AVALON 2019": TOYOTA.TOYOTA_AVALON_2019, - "TOYOTA AVALON 2022": TOYOTA.TOYOTA_AVALON_TSS2, - "TOYOTA CAMRY 2018": TOYOTA.TOYOTA_CAMRY, - "TOYOTA CAMRY 2021": TOYOTA.TOYOTA_CAMRY_TSS2, - "TOYOTA C-HR 2018": TOYOTA.TOYOTA_CHR, - "TOYOTA C-HR 2021": TOYOTA.TOYOTA_CHR_TSS2, - "TOYOTA COROLLA 2017": TOYOTA.TOYOTA_COROLLA, - "TOYOTA COROLLA TSS2 2019": TOYOTA.TOYOTA_COROLLA_TSS2, - "TOYOTA HIGHLANDER 2017": TOYOTA.TOYOTA_HIGHLANDER, - "TOYOTA HIGHLANDER 2020": TOYOTA.TOYOTA_HIGHLANDER_TSS2, - "TOYOTA PRIUS 2017": TOYOTA.TOYOTA_PRIUS, - "TOYOTA PRIUS v 2017": TOYOTA.TOYOTA_PRIUS_V, - "TOYOTA PRIUS TSS2 2021": TOYOTA.TOYOTA_PRIUS_TSS2, - "TOYOTA RAV4 2017": TOYOTA.TOYOTA_RAV4, - "TOYOTA RAV4 HYBRID 2017": TOYOTA.TOYOTA_RAV4H, - "TOYOTA RAV4 2019": TOYOTA.TOYOTA_RAV4_TSS2, - "TOYOTA RAV4 2022": TOYOTA.TOYOTA_RAV4_TSS2_2022, - "TOYOTA RAV4 2023": TOYOTA.TOYOTA_RAV4_TSS2_2023, - "TOYOTA MIRAI 2021": TOYOTA.TOYOTA_MIRAI, - "TOYOTA SIENNA 2018": TOYOTA.TOYOTA_SIENNA, - "LEXUS CT HYBRID 2018": TOYOTA.LEXUS_CTH, - "LEXUS ES 2018": TOYOTA.LEXUS_ES, - "LEXUS ES 2019": TOYOTA.LEXUS_ES_TSS2, - "LEXUS IS 2018": TOYOTA.LEXUS_IS, - "LEXUS IS 2023": TOYOTA.LEXUS_IS_TSS2, - "LEXUS NX 2018": TOYOTA.LEXUS_NX, - "LEXUS NX 2020": TOYOTA.LEXUS_NX_TSS2, - "LEXUS LC 2024": TOYOTA.LEXUS_LC_TSS2, - "LEXUS RC 2020": TOYOTA.LEXUS_RC, - "LEXUS RX 2016": TOYOTA.LEXUS_RX, - "LEXUS RX 2020": TOYOTA.LEXUS_RX_TSS2, - "LEXUS GS F 2016": TOYOTA.LEXUS_GS_F, - "VOLKSWAGEN ARTEON 1ST GEN": VW.VOLKSWAGEN_ARTEON_MK1, - "VOLKSWAGEN ATLAS 1ST GEN": VW.VOLKSWAGEN_ATLAS_MK1, - "VOLKSWAGEN CADDY 3RD GEN": VW.VOLKSWAGEN_CADDY_MK3, - "VOLKSWAGEN CRAFTER 2ND GEN": VW.VOLKSWAGEN_CRAFTER_MK2, - "VOLKSWAGEN GOLF 7TH GEN": VW.VOLKSWAGEN_GOLF_MK7, - "VOLKSWAGEN JETTA 7TH GEN": VW.VOLKSWAGEN_JETTA_MK7, - "VOLKSWAGEN PASSAT 8TH GEN": VW.VOLKSWAGEN_PASSAT_MK8, - "VOLKSWAGEN PASSAT NMS": VW.VOLKSWAGEN_PASSAT_NMS, - "VOLKSWAGEN POLO 6TH GEN": VW.VOLKSWAGEN_POLO_MK6, - "VOLKSWAGEN SHARAN 2ND GEN": VW.VOLKSWAGEN_SHARAN_MK2, - "VOLKSWAGEN TAOS 1ST GEN": VW.VOLKSWAGEN_TAOS_MK1, - "VOLKSWAGEN T-CROSS 1ST GEN": VW.VOLKSWAGEN_TCROSS_MK1, - "VOLKSWAGEN TIGUAN 2ND GEN": VW.VOLKSWAGEN_TIGUAN_MK2, - "VOLKSWAGEN TOURAN 2ND GEN": VW.VOLKSWAGEN_TOURAN_MK2, - "VOLKSWAGEN TRANSPORTER T6.1": VW.VOLKSWAGEN_TRANSPORTER_T61, - "VOLKSWAGEN T-ROC 1ST GEN": VW.VOLKSWAGEN_TROC_MK1, - "AUDI A3 3RD GEN": VW.AUDI_A3_MK3, - "AUDI Q2 1ST GEN": VW.AUDI_Q2_MK1, - "AUDI Q3 2ND GEN": VW.AUDI_Q3_MK2, - "SEAT ATECA 1ST GEN": VW.SEAT_ATECA_MK1, - "SEAT LEON 3RD GEN": VW.SEAT_ATECA_MK1, - "SEAT_LEON_MK3": VW.SEAT_ATECA_MK1, - "SKODA FABIA 4TH GEN": VW.SKODA_FABIA_MK4, - "SKODA KAMIQ 1ST GEN": VW.SKODA_KAMIQ_MK1, - "SKODA KAROQ 1ST GEN": VW.SKODA_KAROQ_MK1, - "SKODA KODIAQ 1ST GEN": VW.SKODA_KODIAQ_MK1, - "SKODA OCTAVIA 3RD GEN": VW.SKODA_OCTAVIA_MK3, - "SKODA SCALA 1ST GEN": VW.SKODA_KAMIQ_MK1, - "SKODA_SCALA_MK1": VW.SKODA_KAMIQ_MK1, - "SKODA SUPERB 3RD GEN": VW.SKODA_SUPERB_MK3, - - "mock": MOCK.MOCK, -} diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py deleted file mode 100644 index 7be3b2ebe9d0d18..000000000000000 --- a/selfdrive/car/ford/carcontroller.py +++ /dev/null @@ -1,120 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.common.numpy_fast import clip -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.ford import fordcan -from openpilot.selfdrive.car.ford.values import CarControllerParams, FordFlags -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX - -LongCtrlState = car.CarControl.Actuators.LongControlState -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -def apply_ford_curvature_limits(apply_curvature, apply_curvature_last, current_curvature, v_ego_raw): - # No blending at low speed due to lack of torque wind-up and inaccurate current curvature - if v_ego_raw > 9: - apply_curvature = clip(apply_curvature, current_curvature - CarControllerParams.CURVATURE_ERROR, - current_curvature + CarControllerParams.CURVATURE_ERROR) - - # Curvature rate limit after driver torque limit - apply_curvature = apply_std_steer_angle_limits(apply_curvature, apply_curvature_last, v_ego_raw, CarControllerParams) - - return clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX) - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.VM = VM - self.packer = CANPacker(dbc_name) - self.CAN = fordcan.CanBus(CP) - self.frame = 0 - - self.apply_curvature_last = 0 - self.main_on_last = False - self.lkas_enabled_last = False - self.steer_alert_last = False - self.lead_distance_bars_last = None - - def update(self, CC, CS, now_nanos): - can_sends = [] - - actuators = CC.actuators - hud_control = CC.hudControl - - main_on = CS.out.cruiseState.available - steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) - fcw_alert = hud_control.visualAlert == VisualAlert.fcw - - ### acc buttons ### - if CC.cruiseControl.cancel: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, cancel=True)) - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, cancel=True)) - elif CC.cruiseControl.resume and (self.frame % CarControllerParams.BUTTONS_STEP) == 0: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, resume=True)) - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, resume=True)) - # if stock lane centering isn't off, send a button press to toggle it off - # the stock system checks for steering pressed, and eventually disengages cruise control - elif CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0 and (self.frame % CarControllerParams.ACC_UI_STEP) == 0: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, tja_toggle=True)) - - ### lateral control ### - # send steer msg at 20Hz - if (self.frame % CarControllerParams.STEER_STEP) == 0: - if CC.latActive: - # apply rate limits, curvature error limit, and clip to signal range - current_curvature = -CS.out.yawRate / max(CS.out.vEgoRaw, 0.1) - apply_curvature = apply_ford_curvature_limits(actuators.curvature, self.apply_curvature_last, current_curvature, CS.out.vEgoRaw) - else: - apply_curvature = 0. - - self.apply_curvature_last = apply_curvature - - if self.CP.flags & FordFlags.CANFD: - # TODO: extended mode - mode = 1 if CC.latActive else 0 - counter = (self.frame // CarControllerParams.STEER_STEP) % 0x10 - can_sends.append(fordcan.create_lat_ctl2_msg(self.packer, self.CAN, mode, 0., 0., -apply_curvature, 0., counter)) - else: - can_sends.append(fordcan.create_lat_ctl_msg(self.packer, self.CAN, CC.latActive, 0., 0., -apply_curvature, 0.)) - - # send lka msg at 33Hz - if (self.frame % CarControllerParams.LKA_STEP) == 0: - can_sends.append(fordcan.create_lka_msg(self.packer, self.CAN)) - - ### longitudinal control ### - # send acc msg at 50Hz - if self.CP.openpilotLongitudinalControl and (self.frame % CarControllerParams.ACC_CONTROL_STEP) == 0: - # Both gas and accel are in m/s^2, accel is used solely for braking - accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) - gas = accel - if not CC.longActive or gas < CarControllerParams.MIN_GAS: - gas = CarControllerParams.INACTIVE_GAS - stopping = CC.actuators.longControlState == LongCtrlState.stopping - can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping, v_ego_kph=V_CRUISE_MAX)) - - ### ui ### - send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) - # send lkas ui msg at 1Hz or if ui state changes - if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: - can_sends.append(fordcan.create_lkas_ui_msg(self.packer, self.CAN, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values)) - - # send acc ui msg at 5Hz or if ui state changes - if hud_control.leadDistanceBars != self.lead_distance_bars_last: - send_ui = True - if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: - can_sends.append(fordcan.create_acc_ui_msg(self.packer, self.CAN, self.CP, main_on, CC.latActive, - fcw_alert, CS.out.cruiseState.standstill, hud_control, - CS.acc_tja_status_stock_values)) - - self.main_on_last = main_on - self.lkas_enabled_last = CC.latActive - self.steer_alert_last = steer_alert - self.lead_distance_bars_last = hud_control.leadDistanceBars - - new_actuators = actuators.as_builder() - new_actuators.curvature = self.apply_curvature_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py deleted file mode 100644 index 78f48ec5c46ff6c..000000000000000 --- a/selfdrive/car/ford/carstate.py +++ /dev/null @@ -1,174 +0,0 @@ -from cereal import car -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import DBC, CarControllerParams, FordFlags -from openpilot.selfdrive.car.interfaces import CarStateBase - -GearShifter = car.CarState.GearShifter -TransmissionType = car.CarParams.TransmissionType - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"] - - self.vehicle_sensors_valid = False - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - ret = car.CarState.new_message() - - # Occasionally on startup, the ABS module recalibrates the steering pinion offset, so we need to block engagement - # The vehicle usually recovers out of this state within a minute of normal driving - self.vehicle_sensors_valid = cp.vl["SteeringPinion_Data"]["StePinCompAnEst_D_Qf"] == 3 - - # car speed - ret.vEgoRaw = cp.vl["BrakeSysFeatures"]["Veh_V_ActlBrk"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] - ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1 - - # gas pedal - ret.gas = cp.vl["EngVehicleSpThrottle"]["ApedPos_Pc_ActlArb"] / 100. - ret.gasPressed = ret.gas > 1e-6 - - # brake pedal - ret.brake = cp.vl["BrakeSnData_4"]["BrkTot_Tq_Actl"] / 32756. # torque in Nm - ret.brakePressed = cp.vl["EngBrakeData"]["BpedDrvAppl_D_Actl"] == 2 - ret.parkingBrake = cp.vl["DesiredTorqBrk"]["PrkBrkStatus"] in (1, 2) - - # steering wheel - ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"] - ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE, 5) - ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1 - ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) - ret.espDisabled = cp.vl["Cluster_Info1_FD1"]["DrvSlipCtlMde_D_Rq"] != 0 # 0 is default mode - - if self.CP.flags & FordFlags.CANFD: - # this signal is always 0 on non-CAN FD cars - ret.steerFaultTemporary |= cp.vl["Lane_Assist_Data3_FD1"]["LatCtlSte_D_Stat"] not in (1, 2, 3) - - # cruise state - is_metric = cp.vl["INSTRUMENT_PANEL"]["METRIC_UNITS"] == 1 if not self.CP.flags & FordFlags.CANFD else False - ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * (CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS) - ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5) - ret.cruiseState.available = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (3, 4, 5) - ret.cruiseState.nonAdaptive = cp.vl["Cluster_Info1_FD1"]["AccEnbl_B_RqDrv"] == 0 - ret.cruiseState.standstill = cp.vl["EngBrakeData"]["AccStopMde_D_Rq"] == 3 - ret.accFaulted = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (1, 2) - if not self.CP.openpilotLongitudinalControl: - ret.accFaulted = ret.accFaulted or cp_cam.vl["ACCDATA"]["CmbbDeny_B_Actl"] == 1 - - # gear - if self.CP.transmissionType == TransmissionType.automatic: - gear = self.shifter_values.get(cp.vl["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"]) - ret.gearShifter = self.parse_gear_shifter(gear) - elif self.CP.transmissionType == TransmissionType.manual: - ret.clutchPressed = cp.vl["Engine_Clutch_Data"]["CluPdlPos_Pc_Meas"] > 0 - if bool(cp.vl["BCM_Lamp_Stat_FD1"]["RvrseLghtOn_B_Stat"]): - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # safety - ret.stockFcw = bool(cp_cam.vl["ACCDATA_3"]["FcwVisblWarn_B_Rq"]) - ret.stockAeb = bool(cp_cam.vl["ACCDATA_2"]["CmbbBrkDecel_B_Rq"]) - - # button presses - ret.leftBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 1 - ret.rightBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 2 - # TODO: block this going to the camera otherwise it will enable stock TJA - ret.genericToggle = bool(cp.vl["Steering_Data_FD1"]["TjaButtnOnOffPress"]) - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["Steering_Data_FD1"]["AccButtnGapTogglePress"] - - # lock info - ret.doorOpen = any([cp.vl["BodyInfo_3_FD1"]["DrStatDrv_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatPsngr_B_Actl"], - cp.vl["BodyInfo_3_FD1"]["DrStatRl_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatRr_B_Actl"]]) - ret.seatbeltUnlatched = cp.vl["RCMStatusMessage2_FD1"]["FirstRowBuckleDriver"] == 2 - - # blindspot sensors - if self.CP.enableBsm: - cp_bsm = cp_cam if self.CP.flags & FordFlags.CANFD else cp - ret.leftBlindspot = cp_bsm.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 - ret.rightBlindspot = cp_bsm.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 - - # Stock steering buttons so that we can passthru blinkers etc. - self.buttons_stock_values = cp.vl["Steering_Data_FD1"] - # Stock values from IPMA so that we can retain some stock functionality - self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"] - self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"] - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("VehicleOperatingModes", 100), - ("BrakeSysFeatures", 50), - ("Yaw_Data_FD1", 100), - ("DesiredTorqBrk", 50), - ("EngVehicleSpThrottle", 100), - ("BrakeSnData_4", 50), - ("EngBrakeData", 10), - ("Cluster_Info1_FD1", 10), - ("SteeringPinion_Data", 100), - ("EPAS_INFO", 50), - ("Steering_Data_FD1", 10), - ("BodyInfo_3_FD1", 2), - ("RCMStatusMessage2_FD1", 10), - ] - - if CP.flags & FordFlags.CANFD: - messages += [ - ("Lane_Assist_Data3_FD1", 33), - ] - else: - messages += [ - ("INSTRUMENT_PANEL", 1), - ] - - if CP.transmissionType == TransmissionType.automatic: - messages += [ - ("Gear_Shift_by_Wire_FD1", 10), - ] - elif CP.transmissionType == TransmissionType.manual: - messages += [ - ("Engine_Clutch_Data", 33), - ("BCM_Lamp_Stat_FD1", 1), - ] - - if CP.enableBsm and not (CP.flags & FordFlags.CANFD): - messages += [ - ("Side_Detect_L_Stat", 5), - ("Side_Detect_R_Stat", 5), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).main) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - # sig_address, frequency - ("ACCDATA", 50), - ("ACCDATA_2", 50), - ("ACCDATA_3", 5), - ("IPMA_Data", 1), - ] - - if CP.enableBsm and CP.flags & FordFlags.CANFD: - messages += [ - ("Side_Detect_L_Stat", 5), - ("Side_Detect_R_Stat", 5), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) diff --git a/selfdrive/car/ford/fingerprints.py b/selfdrive/car/ford/fingerprints.py deleted file mode 100644 index 2201072fa3a29d0..000000000000000 --- a/selfdrive/car/ford/fingerprints.py +++ /dev/null @@ -1,166 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.ford.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.FORD_BRONCO_SPORT_MK1: { - (Ecu.eps, 0x730, None): [ - b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LX6C-2D053-RD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-RE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-RF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'M1PT-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1PT-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_ESCAPE_MK4: { - (Ecu.eps, 0x730, None): [ - b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-NT\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-SA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-SD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LV4T-14F397-GG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_EXPLORER_MK6: { - (Ecu.eps, 0x730, None): [ - b'L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1MC-14D003-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'P1MC-14D003-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'L1MC-2D053-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LC5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_F_150_MK14: { - (Ecu.eps, 0x730, None): [ - b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABR\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_F_150_LIGHTNING_MK1: { - (Ecu.abs, 0x760, None): [ - b'PL38-2D053-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABT\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_MUSTANG_MACH_E_MK1: { - (Ecu.eps, 0x730, None): [ - b'LJ9C-14D003-AM\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LJ9C-14D003-CC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LK9C-2D053-CK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABS\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_FOCUS_MK4: { - (Ecu.eps, 0x730, None): [ - b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'JX7T-14D049-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'JX7T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_MAVERICK_MK1: { - (Ecu.eps, 0x730, None): [ - b'NZ6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NZ6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'NZ6C-2D053-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-ED\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-EE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-EF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_RANGER_MK2: { - (Ecu.eps, 0x730, None): [ - b'NL14-14D003-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'PB3C-2D053-ZD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, -} diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py deleted file mode 100644 index 2ef5d427e6fdb65..000000000000000 --- a/selfdrive/car/ford/interface.py +++ /dev/null @@ -1,85 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import Ecu, FordFlags -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type -TransmissionType = car.CarParams.TransmissionType -GearShifter = car.CarState.GearShifter - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "ford" - ret.dashcamOnly = bool(ret.flags & FordFlags.CANFD) - - ret.radarUnavailable = True - ret.steerControlType = car.CarParams.SteerControlType.angle - ret.steerActuatorDelay = 0.2 - ret.steerLimitTimer = 1.0 - - 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: - cfgs.insert(0, get_safety_config(car.CarParams.SafetyModel.noOutput)) - ret.safetyConfigs = cfgs - - ret.experimentalLongitudinalAvailable = True - if experimental_long: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_LONG_CONTROL - ret.openpilotLongitudinalControl = True - - if ret.flags & FordFlags.CANFD: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_CANFD - else: - # Lock out if the car does not have needed lateral and longitudinal control APIs. - # Note that we also check CAN for adaptive cruise, but no known signal for LCA exists - pscm_config = next((fw for fw in car_fw if fw.ecu == Ecu.eps and b'\x22\xDE\x01' in fw.request), None) - if pscm_config: - if len(pscm_config.fwVersion) != 24: - ret.dashcamOnly = True - else: - config_tja = pscm_config.fwVersion[7] # Traffic Jam Assist - config_lca = pscm_config.fwVersion[8] # Lane Centering Assist - if config_tja != 0xFF or config_lca != 0xFF: - ret.dashcamOnly = True - - # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1 - found_ecus = [fw.ecu for fw in car_fw] - if Ecu.shiftByWire in found_ecus or 0x5A in fingerprint[CAN.main] or docs: - ret.transmissionType = TransmissionType.automatic - else: - ret.transmissionType = TransmissionType.manual - ret.minEnableSpeed = 20.0 * CV.MPH_TO_MS - - # BSM: Side_Detect_L_Stat, Side_Detect_R_Stat - # TODO: detect bsm in car_fw? - ret.enableBsm = 0x3A6 in fingerprint[CAN.main] and 0x3A7 in fingerprint[CAN.main] - - # LCA can steer down to zero - ret.minSteerSpeed = 0. - - ret.autoResumeSng = ret.minEnableSpeed == -1. - ret.centerToFront = ret.wheelbase * 0.44 - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - events = self.create_common_events(ret, extra_gears=[GearShifter.manumatic]) - if not self.CS.vehicle_sensors_valid: - events.add(car.CarEvent.EventName.vehicleSensorsInvalid) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py deleted file mode 100644 index 209bbebae34d5f8..000000000000000 --- a/selfdrive/car/ford/radar_interface.py +++ /dev/null @@ -1,143 +0,0 @@ -from math import cos, sin -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import DBC, RADAR -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -DELPHI_ESR_RADAR_MSGS = list(range(0x500, 0x540)) - -DELPHI_MRR_RADAR_START_ADDR = 0x120 -DELPHI_MRR_RADAR_MSG_COUNT = 64 - - -def _create_delphi_esr_radar_can_parser(CP) -> CANParser: - msg_n = len(DELPHI_ESR_RADAR_MSGS) - messages = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n, strict=True)) - - return CANParser(RADAR.DELPHI_ESR, messages, CanBus(CP).radar) - - -def _create_delphi_mrr_radar_can_parser(CP) -> CANParser: - messages = [] - - for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): - msg = f"MRR_Detection_{i:03d}" - messages += [(msg, 20)] - - return CANParser(RADAR.DELPHI_MRR, messages, CanBus(CP).radar) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - - self.updated_messages = set() - self.track_id = 0 - self.radar = DBC[CP.carFingerprint]['radar'] - if self.radar is None or CP.radarUnavailable: - self.rcp = None - elif self.radar == RADAR.DELPHI_ESR: - self.rcp = _create_delphi_esr_radar_can_parser(CP) - self.trigger_msg = DELPHI_ESR_RADAR_MSGS[-1] - self.valid_cnt = {key: 0 for key in DELPHI_ESR_RADAR_MSGS} - elif self.radar == RADAR.DELPHI_MRR: - self.rcp = _create_delphi_mrr_radar_can_parser(CP) - self.trigger_msg = DELPHI_MRR_RADAR_START_ADDR + DELPHI_MRR_RADAR_MSG_COUNT - 1 - else: - raise ValueError(f"Unsupported radar: {self.radar}") - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - if self.radar == RADAR.DELPHI_ESR: - self._update_delphi_esr() - elif self.radar == RADAR.DELPHI_MRR: - self._update_delphi_mrr() - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret - - def _update_delphi_esr(self): - for ii in sorted(self.updated_messages): - cpt = self.rcp.vl[ii] - - if cpt['X_Rel'] > 0.00001: - self.valid_cnt[ii] = 0 # reset counter - - if cpt['X_Rel'] > 0.00001: - self.valid_cnt[ii] += 1 - else: - self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) - #print ii, self.valid_cnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] - - # radar point only valid if there have been enough valid measurements - if self.valid_cnt[ii] > 0: - if ii not in self.pts: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['X_Rel'] # from front of car - self.pts[ii].yRel = cpt['X_Rel'] * cpt['Angle'] * CV.DEG_TO_RAD # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['V_Rel'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = True - else: - if ii in self.pts: - del self.pts[ii] - - def _update_delphi_mrr(self): - for ii in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): - msg = self.rcp.vl[f"MRR_Detection_{ii:03d}"] - - # SCAN_INDEX rotates through 0..3 on each message - # treat these as separate points - scanIndex = msg[f"CAN_SCAN_INDEX_2LSB_{ii:02d}"] - i = (ii - 1) * 4 + scanIndex - - if i not in self.pts: - self.pts[i] = car.RadarData.RadarPoint.new_message() - self.pts[i].trackId = self.track_id - self.pts[i].aRel = float('nan') - self.pts[i].yvRel = float('nan') - self.track_id += 1 - - valid = bool(msg[f"CAN_DET_VALID_LEVEL_{ii:02d}"]) - - if valid: - azimuth = msg[f"CAN_DET_AZIMUTH_{ii:02d}"] # rad [-3.1416|3.13964] - dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] - distRate = msg[f"CAN_DET_RANGE_RATE_{ii:02d}"] # m/s [-128|127.984] - dRel = cos(azimuth) * dist # m from front of car - yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive - - # delphi doesn't notify of track switches, so do it manually - # TODO: refactor this to radard if more radars behave this way - if abs(self.pts[i].vRel - distRate) > 2 or abs(self.pts[i].dRel - dRel) > 5: - self.track_id += 1 - self.pts[i].trackId = self.track_id - - self.pts[i].dRel = dRel - self.pts[i].yRel = yRel - self.pts[i].vRel = distRate - - self.pts[i].measured = True - - else: - del self.pts[i] diff --git a/selfdrive/car/ford/tests/print_platform_codes.py b/selfdrive/car/ford/tests/print_platform_codes.py deleted file mode 100755 index 670199980a68384..000000000000000 --- a/selfdrive/car/ford/tests/print_platform_codes.py +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env python3 -from collections import defaultdict - -from cereal import car -from openpilot.selfdrive.car.ford.values import get_platform_codes -from openpilot.selfdrive.car.ford.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -if __name__ == "__main__": - cars_for_code: defaultdict = defaultdict(lambda: defaultdict(set)) - - for car_model, ecus in FW_VERSIONS.items(): - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - platform_codes = get_platform_codes(ecus[ecu]) - for code in platform_codes: - cars_for_code[ecu][code].add(car_model) - - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {sorted(platform_codes)}') - print() - - print('\nCar models vs. platform codes:') - for ecu, codes in cars_for_code.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - for code, cars in codes.items(): - print(f' {code!r}: {sorted(map(str, cars))}') diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py deleted file mode 100644 index b1868bfa9bb97dc..000000000000000 --- a/selfdrive/car/ford/values.py +++ /dev/null @@ -1,279 +0,0 @@ -import copy -import re -from dataclasses import dataclass, field, replace -from enum import Enum, IntFlag - -import panda.python.uds as uds -from cereal import car -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, dbc_dict, DbcDict, PlatformConfig, Platforms -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ - Device -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, LiveFwVersions, OfflineFwVersions, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - STEER_STEP = 5 # LateralMotionControl, 20Hz - LKA_STEP = 3 # Lane_Assist_Data1, 33Hz - ACC_CONTROL_STEP = 2 # ACCDATA, 50Hz - LKAS_UI_STEP = 100 # IPMA_Data, 1Hz - ACC_UI_STEP = 20 # ACCDATA_3, 5Hz - BUTTONS_STEP = 5 # Steering_Data_FD1, 10Hz, but send twice as fast - - CURVATURE_MAX = 0.02 # Max curvature for steering command, m^-1 - STEER_DRIVER_ALLOWANCE = 1.0 # Driver intervention threshold, Nm - - # Curvature rate limits - # The curvature signal is limited to 0.003 to 0.009 m^-1/sec by the EPS depending on speed and direction - # Limit to ~2 m/s^3 up, ~3 m/s^3 down at 75 mph - # Worst case, the low speed limits will allow 4.3 m/s^3 up, 4.9 m/s^3 down at 75 mph - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.0002, 0.0001]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.000225, 0.00015]) - CURVATURE_ERROR = 0.002 # ~6 degrees at 10 m/s, ~10 degrees at 35 m/s - - ACCEL_MAX = 2.0 # m/s^2 max acceleration - ACCEL_MIN = -3.5 # m/s^2 max deceleration - MIN_GAS = -0.5 - INACTIVE_GAS = -5.0 - - def __init__(self, CP): - pass - - -class FordFlags(IntFlag): - # Static flags - CANFD = 1 - - -class RADAR: - DELPHI_ESR = 'ford_fusion_2018_adas' - DELPHI_MRR = 'FORD_CADS' - - -class Footnote(Enum): - FOCUS = CarFootnote( - "Refers only to the Focus Mk4 (C519) available in Europe/China/Taiwan/Australasia, not the Focus Mk3 (C346) in " + - "North and South America/Southeast Asia.", - Column.MODEL, - ) - - -@dataclass -class FordCarDocs(CarDocs): - package: str = "Co-Pilot360 Assist+" - hybrid: bool = False - plug_in_hybrid: bool = False - - def init_make(self, CP: car.CarParams): - harness = CarHarness.ford_q4 if CP.flags & FordFlags.CANFD else CarHarness.ford_q3 - if CP.carFingerprint in (CAR.FORD_BRONCO_SPORT_MK1, CAR.FORD_MAVERICK_MK1, CAR.FORD_F_150_MK14, CAR.FORD_F_150_LIGHTNING_MK1): - self.car_parts = CarParts([Device.threex_angled_mount, harness]) - else: - self.car_parts = CarParts([Device.threex, harness]) - - -@dataclass -class FordPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR)) - - def init(self): - for car_docs in list(self.car_docs): - if car_docs.hybrid: - name = f"{car_docs.make} {car_docs.model} Hybrid {car_docs.years}" - self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) - if car_docs.plug_in_hybrid: - name = f"{car_docs.make} {car_docs.model} Plug-in Hybrid {car_docs.years}" - self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) - - -@dataclass -class FordCANFDPlatformConfig(FordPlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', None)) - - def init(self): - super().init() - self.flags |= FordFlags.CANFD - - -class CAR(Platforms): - FORD_BRONCO_SPORT_MK1 = FordPlatformConfig( - [FordCarDocs("Ford Bronco Sport 2021-23")], - CarSpecs(mass=1625, wheelbase=2.67, steerRatio=17.7), - ) - FORD_ESCAPE_MK4 = FordPlatformConfig( - [ - FordCarDocs("Ford Escape 2020-22", hybrid=True, plug_in_hybrid=True), - FordCarDocs("Ford Kuga 2020-22", "Adaptive Cruise Control with Lane Centering", hybrid=True, plug_in_hybrid=True), - ], - CarSpecs(mass=1750, wheelbase=2.71, steerRatio=16.7), - ) - FORD_EXPLORER_MK6 = FordPlatformConfig( - [ - FordCarDocs("Ford Explorer 2020-23", hybrid=True), # Hybrid: Limited and Platinum only - FordCarDocs("Lincoln Aviator 2020-23", "Co-Pilot360 Plus", plug_in_hybrid=True), # Hybrid: Grand Touring only - ], - CarSpecs(mass=2050, wheelbase=3.025, steerRatio=16.8), - ) - FORD_F_150_MK14 = FordCANFDPlatformConfig( - [FordCarDocs("Ford F-150 2022-23", "Co-Pilot360 Active 2.0", hybrid=True)], - CarSpecs(mass=2000, wheelbase=3.69, steerRatio=17.0), - ) - FORD_F_150_LIGHTNING_MK1 = FordCANFDPlatformConfig( - [FordCarDocs("Ford F-150 Lightning 2021-23", "Co-Pilot360 Active 2.0")], - CarSpecs(mass=2948, wheelbase=3.70, steerRatio=16.9), - ) - FORD_FOCUS_MK4 = FordPlatformConfig( - [FordCarDocs("Ford Focus 2018", "Adaptive Cruise Control with Lane Centering", footnotes=[Footnote.FOCUS], hybrid=True)], # mHEV only - CarSpecs(mass=1350, wheelbase=2.7, steerRatio=15.0), - ) - FORD_MAVERICK_MK1 = FordPlatformConfig( - [ - FordCarDocs("Ford Maverick 2022", "LARIAT Luxury", hybrid=True), - FordCarDocs("Ford Maverick 2023-24", "Co-Pilot360 Assist", hybrid=True), - ], - CarSpecs(mass=1650, wheelbase=3.076, steerRatio=17.0), - ) - FORD_MUSTANG_MACH_E_MK1 = FordCANFDPlatformConfig( - [FordCarDocs("Ford Mustang Mach-E 2021-23", "Co-Pilot360 Active 2.0")], - CarSpecs(mass=2200, wheelbase=2.984, steerRatio=17.0), # TODO: check steer ratio - ) - FORD_RANGER_MK2 = FordCANFDPlatformConfig( - [FordCarDocs("Ford Ranger 2024", "Adaptive Cruise Control with Lane Centering")], - CarSpecs(mass=2000, wheelbase=3.27, steerRatio=17.0), - ) - - -# FW response contains a combined software and part number -# A-Z except no I, O or W -# e.g. NZ6A-14C204-AAA -# 1222-333333-444 -# 1 = Model year hint (approximates model year/generation) -# 2 = Platform hint -# 3 = Part number -# 4 = Software version -FW_ALPHABET = b'A-HJ-NP-VX-Z' -FW_PATTERN = re.compile(b'^(?P[' + FW_ALPHABET + b'])' + - b'(?P[0-9' + FW_ALPHABET + b']{3})-' + - b'(?P[0-9' + FW_ALPHABET + b']{5,6})-' + - b'(?P[' + FW_ALPHABET + b']{2,})\x00*$') - - -def get_platform_codes(fw_versions: list[bytes] | set[bytes]) -> set[tuple[bytes, bytes]]: - codes = set() - for fw in fw_versions: - match = FW_PATTERN.match(fw) - if match is not None: - codes.add((match.group('platform_hint'), match.group('model_year_hint'))) - - return codes - - -def match_fw_to_car_fuzzy(live_fw_versions: LiveFwVersions, vin: str, offline_fw_versions: OfflineFwVersions) -> set[str]: - candidates: set[str] = set() - - for candidate, fws in offline_fw_versions.items(): - # Keep track of ECUs which pass all checks (platform hint, within model year hint range) - valid_found_ecus = set() - valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} - for ecu, expected_versions in fws.items(): - addr = ecu[1:] - # Only check ECUs expected to have platform codes - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Expected platform codes & model year hints - codes = get_platform_codes(expected_versions) - expected_platform_codes = {code for code, _ in codes} - expected_model_year_hints = {model_year_hint for _, model_year_hint in codes} - - # Found platform codes & model year hints - codes = get_platform_codes(live_fw_versions.get(addr, set())) - found_platform_codes = {code for code, _ in codes} - found_model_year_hints = {model_year_hint for _, model_year_hint in codes} - - # Check platform code matches for any found versions - if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): - break - - # Check any model year hint within range in the database. Note that some models have more than one - # platform code per ECU which we don't consider as separate ranges - if not any(min(expected_model_year_hints) <= found_model_year_hint <= max(expected_model_year_hints) for - found_model_year_hint in found_model_year_hints): - break - - valid_found_ecus.add(addr) - - # If all live ECUs pass all checks for candidate, add it as a match - if valid_expected_ecus.issubset(valid_found_ecus): - candidates.add(candidate) - - return candidates - - -# All of these ECUs must be present and are expected to have platform codes we can match -PLATFORM_CODE_ECUS = (Ecu.abs, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps) - -DATA_IDENTIFIER_FORD_ASBUILT = 0xDE00 - -ASBUILT_BLOCKS: list[tuple[int, list]] = [ - (1, [Ecu.debug, Ecu.fwdCamera, Ecu.eps]), - (2, [Ecu.abs, Ecu.debug, Ecu.eps]), - (3, [Ecu.abs, Ecu.debug, Ecu.eps]), - (4, [Ecu.debug, Ecu.fwdCamera]), - (5, [Ecu.debug]), - (6, [Ecu.debug]), - (7, [Ecu.debug]), - (8, [Ecu.debug]), - (9, [Ecu.debug]), - (16, [Ecu.debug, Ecu.fwdCamera]), - (18, [Ecu.fwdCamera]), - (20, [Ecu.fwdCamera]), - (21, [Ecu.fwdCamera]), -] - - -def ford_asbuilt_block_request(block_id: int): - return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) - - -def ford_asbuilt_block_response(block_id: int): - return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # CAN and CAN FD queries are combined. - # FIXME: For CAN FD, ECUs respond with frames larger than 8 bytes on the powertrain bus - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], - logging=True, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], - bus=0, - auxiliary=True, - ), - *[Request( - [StdQueries.TESTER_PRESENT_REQUEST, ford_asbuilt_block_request(block_id)], - [StdQueries.TESTER_PRESENT_RESPONSE, ford_asbuilt_block_response(block_id)], - whitelist_ecus=ecus, - bus=0, - logging=True, - ) for block_id, ecus in ASBUILT_BLOCKS], - ], - extra_ecus=[ - (Ecu.engine, 0x7e0, None), # Powertrain Control Module - # Note: We are unlikely to get a response from behind the gateway - (Ecu.shiftByWire, 0x732, None), # Gear Shift Module - (Ecu.debug, 0x7d0, None), # Accessory Protocol Interface Module - ], - # Custom fuzzy fingerprinting function using platform and model year hints - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py deleted file mode 100755 index 4bb6413d010c21e..000000000000000 --- a/selfdrive/car/fw_versions.py +++ /dev/null @@ -1,398 +0,0 @@ -#!/usr/bin/env python3 -from collections import defaultdict -from collections.abc import Iterator -from typing import Any, Protocol, TypeVar - -from tqdm import tqdm -import capnp - -import panda.python.uds as uds -from cereal import car -from openpilot.common.params import Params -from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.car.ecu_addrs import get_ecu_addrs -from openpilot.selfdrive.car.fingerprints import FW_VERSIONS -from openpilot.selfdrive.car.fw_query_definitions import AddrType, EcuAddrBusType, FwQueryConfig, LiveFwVersions, OfflineFwVersions -from openpilot.selfdrive.car.interfaces import get_interface_attr -from openpilot.selfdrive.car.isotp_parallel_query import IsoTpParallelQuery - -Ecu = car.CarParams.Ecu -ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.abs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] -FUZZY_EXCLUDE_ECUS = [Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps, Ecu.debug] - -FW_QUERY_CONFIGS: dict[str, FwQueryConfig] = get_interface_attr('FW_QUERY_CONFIG', ignore_none=True) -VERSIONS = get_interface_attr('FW_VERSIONS', ignore_none=True) - -MODEL_TO_BRAND = {c: b for b, e in VERSIONS.items() for c in e} -REQUESTS = [(brand, config, r) for brand, config in FW_QUERY_CONFIGS.items() for r in config.requests] - -T = TypeVar('T') - - -def chunks(l: list[T], n: int = 128) -> Iterator[list[T]]: - for i in range(0, len(l), n): - yield l[i:i + n] - - -def is_brand(brand: str, filter_brand: str | None) -> bool: - """Returns if brand matches filter_brand or no brand filter is specified""" - return filter_brand is None or brand == filter_brand - - -def build_fw_dict(fw_versions: list[capnp.lib.capnp._DynamicStructBuilder], filter_brand: str = None) -> dict[AddrType, set[bytes]]: - fw_versions_dict: defaultdict[AddrType, set[bytes]] = defaultdict(set) - for fw in fw_versions: - if is_brand(fw.brand, filter_brand) and not fw.logging: - sub_addr = fw.subAddress if fw.subAddress != 0 else None - fw_versions_dict[(fw.address, sub_addr)].add(fw.fwVersion) - return dict(fw_versions_dict) - - -class MatchFwToCar(Protocol): - def __call__(self, live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True) -> set[str]: - ... - - -def match_fw_to_car_fuzzy(live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True, exclude: str = None) -> set[str]: - """Do a fuzzy FW match. This function will return a match, and the number of firmware version - that were matched uniquely to that specific car. If multiple ECUs uniquely match to different cars - the match is rejected.""" - - # Build lookup table from (addr, sub_addr, fw) to list of candidate cars - all_fw_versions = defaultdict(list) - for candidate, fw_by_addr in FW_VERSIONS.items(): - if not is_brand(MODEL_TO_BRAND[candidate], match_brand): - continue - - if candidate == exclude: - continue - - for addr, fws in fw_by_addr.items(): - # These ECUs are known to be shared between models (EPS only between hybrid/ICE version) - # Getting this exactly right isn't crucial, but excluding camera and radar makes it almost - # impossible to get 3 matching versions, even if two models with shared parts are released at the same - # time and only one is in our database. - if addr[0] in FUZZY_EXCLUDE_ECUS: - continue - for f in fws: - all_fw_versions[(addr[1], addr[2], f)].append(candidate) - - matched_ecus = set() - match: str | None = None - for addr, versions in live_fw_versions.items(): - ecu_key = (addr[0], addr[1]) - for version in versions: - # All cars that have this FW response on the specified address - candidates = all_fw_versions[(*ecu_key, version)] - - if len(candidates) == 1: - matched_ecus.add(ecu_key) - if match is None: - match = candidates[0] - # We uniquely matched two different cars. No fuzzy match possible - elif match != candidates[0]: - return set() - - # Note that it is possible to match to a candidate without all its ECUs being present - # if there are enough matches. FIXME: parameterize this or require all ECUs to exist like exact matching - if match and len(matched_ecus) >= 2: - if log: - cloudlog.error(f"Fingerprinted {match} using fuzzy match. {len(matched_ecus)} matching ECUs") - return {match} - else: - return set() - - -def match_fw_to_car_exact(live_fw_versions: LiveFwVersions, match_brand: str = None, log: bool = True, extra_fw_versions: dict = None) -> set[str]: - """Do an exact FW match. Returns all cars that match the given - FW versions for a list of "essential" ECUs. If an ECU is not considered - essential the FW version can be missing to get a fingerprint, but if it's present it - needs to match the database.""" - if extra_fw_versions is None: - extra_fw_versions = {} - - invalid = set() - candidates = {c: f for c, f in FW_VERSIONS.items() if - is_brand(MODEL_TO_BRAND[c], match_brand)} - - for candidate, fws in candidates.items(): - config = FW_QUERY_CONFIGS[MODEL_TO_BRAND[candidate]] - for ecu, expected_versions in fws.items(): - expected_versions = expected_versions + extra_fw_versions.get(candidate, {}).get(ecu, []) - ecu_type = ecu[0] - addr = ecu[1:] - - found_versions = live_fw_versions.get(addr, set()) - if not len(found_versions): - # Some models can sometimes miss an ecu, or show on two different addresses - # FIXME: this logic can be improved to be more specific, should require one of the two addresses - if candidate in config.non_essential_ecus.get(ecu_type, []): - continue - - # Ignore non essential ecus - if ecu_type not in ESSENTIAL_ECUS: - continue - - # Virtual debug ecu doesn't need to match the database - if ecu_type == Ecu.debug: - continue - - if not any(found_version in expected_versions for found_version in found_versions): - invalid.add(candidate) - break - - return set(candidates.keys()) - invalid - - -def match_fw_to_car(fw_versions: list[capnp.lib.capnp._DynamicStructBuilder], vin: str, - allow_exact: bool = True, allow_fuzzy: bool = True, log: bool = True) -> tuple[bool, set[str]]: - # Try exact matching first - exact_matches: list[tuple[bool, MatchFwToCar]] = [] - if allow_exact: - exact_matches = [(True, match_fw_to_car_exact)] - if allow_fuzzy: - exact_matches.append((False, match_fw_to_car_fuzzy)) - - for exact_match, match_func in exact_matches: - # For each brand, attempt to fingerprint using all FW returned from its queries - matches: set[str] = set() - for brand in VERSIONS.keys(): - fw_versions_dict = build_fw_dict(fw_versions, filter_brand=brand) - matches |= match_func(fw_versions_dict, match_brand=brand, log=log) - - # If specified and no matches so far, fall back to brand's fuzzy fingerprinting function - config = FW_QUERY_CONFIGS[brand] - if not exact_match and not len(matches) and config.match_fw_to_car_fuzzy is not None: - matches |= config.match_fw_to_car_fuzzy(fw_versions_dict, vin, VERSIONS[brand]) - - if len(matches): - return exact_match, matches - - return True, set() - - -def get_present_ecus(logcan, sendcan, num_pandas: int = 1) -> set[EcuAddrBusType]: - params = Params() - # queries are split by OBD multiplexing mode - queries: dict[bool, list[list[EcuAddrBusType]]] = {True: [], False: []} - parallel_queries: dict[bool, list[EcuAddrBusType]] = {True: [], False: []} - responses: set[EcuAddrBusType] = set() - - for brand, config, r in REQUESTS: - # Skip query if no panda available - if r.bus > num_pandas * 4 - 1: - continue - - for ecu_type, addr, sub_addr in config.get_all_ecus(VERSIONS[brand]): - # Only query ecus in whitelist if whitelist is not empty - if len(r.whitelist_ecus) == 0 or ecu_type in r.whitelist_ecus: - a = (addr, sub_addr, r.bus) - # Build set of queries - if sub_addr is None: - if a not in parallel_queries[r.obd_multiplexing]: - parallel_queries[r.obd_multiplexing].append(a) - else: # subaddresses must be queried one by one - if [a] not in queries[r.obd_multiplexing]: - queries[r.obd_multiplexing].append([a]) - - # Build set of expected responses to filter - response_addr = uds.get_rx_addr_for_tx_addr(addr, r.rx_offset) - responses.add((response_addr, sub_addr, r.bus)) - - for obd_multiplexing in queries: - queries[obd_multiplexing].insert(0, parallel_queries[obd_multiplexing]) - - ecu_responses = set() - for obd_multiplexing in queries: - set_obd_multiplexing(params, obd_multiplexing) - for query in queries[obd_multiplexing]: - ecu_responses.update(get_ecu_addrs(logcan, sendcan, set(query), responses, timeout=0.1)) - return ecu_responses - - -def get_brand_ecu_matches(ecu_rx_addrs: set[EcuAddrBusType]) -> dict[str, set[AddrType]]: - """Returns dictionary of brands and matches with ECUs in their FW versions""" - - brand_addrs = {brand: {(addr, subaddr) for _, addr, subaddr in config.get_all_ecus(VERSIONS[brand])} for - brand, config in FW_QUERY_CONFIGS.items()} - brand_matches: dict[str, set[AddrType]] = {brand: set() for brand, _, _ in REQUESTS} - - brand_rx_offsets = {(brand, r.rx_offset) for brand, _, r in REQUESTS} - for addr, sub_addr, _ in ecu_rx_addrs: - # Since we can't know what request an ecu responded to, add matches for all possible rx offsets - for brand, rx_offset in brand_rx_offsets: - a = (uds.get_rx_addr_for_tx_addr(addr, -rx_offset), sub_addr) - if a in brand_addrs[brand]: - brand_matches[brand].add(a) - - return brand_matches - - -def set_obd_multiplexing(params: Params, obd_multiplexing: bool): - if params.get_bool("ObdMultiplexingEnabled") != obd_multiplexing: - cloudlog.warning(f"Setting OBD multiplexing to {obd_multiplexing}") - params.remove("ObdMultiplexingChanged") - params.put_bool("ObdMultiplexingEnabled", obd_multiplexing) - params.get_bool("ObdMultiplexingChanged", block=True) - cloudlog.warning("OBD multiplexing set successfully") - - -def get_fw_versions_ordered(logcan, sendcan, vin: str, ecu_rx_addrs: set[EcuAddrBusType], timeout: float = 0.1, num_pandas: int = 1, - debug: bool = False, progress: bool = False) -> list[capnp.lib.capnp._DynamicStructBuilder]: - """Queries for FW versions ordering brands by likelihood, breaks when exact match is found""" - - all_car_fw = [] - brand_matches = get_brand_ecu_matches(ecu_rx_addrs) - - for brand in sorted(brand_matches, key=lambda b: len(brand_matches[b]), reverse=True): - # Skip this brand if there are no matching present ECUs - if not len(brand_matches[brand]): - continue - - car_fw = get_fw_versions(logcan, sendcan, query_brand=brand, timeout=timeout, num_pandas=num_pandas, debug=debug, progress=progress) - all_car_fw.extend(car_fw) - - # If there is a match using this brand's FW alone, finish querying early - _, matches = match_fw_to_car(car_fw, vin, log=False) - if len(matches) == 1: - break - - return all_car_fw - - -def get_fw_versions(logcan, sendcan, query_brand: str = None, extra: OfflineFwVersions = None, timeout: float = 0.1, num_pandas: int = 1, - debug: bool = False, progress: bool = False) -> list[capnp.lib.capnp._DynamicStructBuilder]: - versions = VERSIONS.copy() - params = Params() - - if query_brand is not None: - versions = {query_brand: versions[query_brand]} - - if extra is not None: - versions.update(extra) - - # Extract ECU addresses to query from fingerprints - # ECUs using a subaddress need be queried one by one, the rest can be done in parallel - addrs = [] - parallel_addrs = [] - ecu_types = {} - - for brand, brand_versions in versions.items(): - config = FW_QUERY_CONFIGS[brand] - for ecu_type, addr, sub_addr in config.get_all_ecus(brand_versions): - a = (brand, addr, sub_addr) - if a not in ecu_types: - ecu_types[a] = ecu_type - - if sub_addr is None: - if a not in parallel_addrs: - parallel_addrs.append(a) - else: - if [a] not in addrs: - addrs.append([a]) - - addrs.insert(0, parallel_addrs) - - # Get versions and build capnp list to put into CarParams - car_fw = [] - requests = [(brand, config, r) for brand, config, r in REQUESTS if is_brand(brand, query_brand)] - for addr_group in tqdm(addrs, disable=not progress): # split by subaddr, if any - for addr_chunk in chunks(addr_group): - for brand, config, r in requests: - # Skip query if no panda available - if r.bus > num_pandas * 4 - 1: - continue - - # Toggle OBD multiplexing for each request - if r.bus % 4 == 1: - set_obd_multiplexing(params, r.obd_multiplexing) - - try: - query_addrs = [(a, s) for (b, a, s) in addr_chunk if b in (brand, 'any') and - (len(r.whitelist_ecus) == 0 or ecu_types[(b, a, s)] in r.whitelist_ecus)] - - if query_addrs: - query = IsoTpParallelQuery(sendcan, logcan, r.bus, query_addrs, r.request, r.response, r.rx_offset, debug=debug) - for (tx_addr, sub_addr), version in query.get_data(timeout).items(): - f = car.CarParams.CarFw.new_message() - - f.ecu = ecu_types.get((brand, tx_addr, sub_addr), Ecu.unknown) - f.fwVersion = version - f.address = tx_addr - f.responseAddress = uds.get_rx_addr_for_tx_addr(tx_addr, r.rx_offset) - f.request = r.request - f.brand = brand - f.bus = r.bus - f.logging = r.logging or (f.ecu, tx_addr, sub_addr) in config.extra_ecus - f.obdMultiplexing = r.obd_multiplexing - - if sub_addr is not None: - f.subAddress = sub_addr - - car_fw.append(f) - except Exception: - cloudlog.exception("FW query exception") - - return car_fw - - -if __name__ == "__main__": - import time - import argparse - import cereal.messaging as messaging - from openpilot.selfdrive.car.vin import get_vin - - parser = argparse.ArgumentParser(description='Get firmware version of ECUs') - parser.add_argument('--scan', action='store_true') - parser.add_argument('--debug', action='store_true') - parser.add_argument('--brand', help='Only query addresses/with requests for this brand') - args = parser.parse_args() - - logcan = messaging.sub_sock('can') - pandaStates_sock = messaging.sub_sock('pandaStates') - sendcan = messaging.pub_sock('sendcan') - - # Set up params for pandad - params = Params() - params.remove("FirmwareQueryDone") - params.put_bool("IsOnroad", False) - time.sleep(0.2) # thread is 10 Hz - params.put_bool("IsOnroad", True) - - extra: Any = None - if args.scan: - extra = {} - # Honda - for i in range(256): - extra[(Ecu.unknown, 0x18da00f1 + (i << 8), None)] = [] - extra[(Ecu.unknown, 0x700 + i, None)] = [] - extra[(Ecu.unknown, 0x750, i)] = [] - extra = {"any": {"debug": extra}} - - num_pandas = len(messaging.recv_one_retry(pandaStates_sock).pandaStates) - - t = time.time() - print("Getting vin...") - set_obd_multiplexing(params, True) - vin_rx_addr, vin_rx_bus, vin = get_vin(logcan, sendcan, (0, 1), debug=args.debug) - print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') - print(f"Getting VIN took {time.time() - t:.3f} s") - print() - - t = time.time() - fw_vers = get_fw_versions(logcan, sendcan, query_brand=args.brand, extra=extra, num_pandas=num_pandas, debug=args.debug, progress=True) - _, candidates = match_fw_to_car(fw_vers, vin) - - print() - print("Found FW versions") - print("{") - padding = max([len(fw.brand) for fw in fw_vers] or [0]) - for version in fw_vers: - subaddr = None if version.subAddress == 0 else hex(version.subAddress) - print(f" Brand: {version.brand:{padding}}, bus: {version.bus}, OBD: {version.obdMultiplexing} - " + - f"(Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion}]") - print("}") - - print() - print("Possible matches:", candidates) - print(f"Getting fw took {time.time() - t:.3f} s") diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py deleted file mode 100644 index b204d3b80ff0bfd..000000000000000 --- a/selfdrive/car/gm/carcontroller.py +++ /dev/null @@ -1,165 +0,0 @@ -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import interp -from openpilot.common.realtime import DT_CTRL -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits -from openpilot.selfdrive.car.gm import gmcan -from openpilot.selfdrive.car.gm.values import DBC, CanBus, CarControllerParams, CruiseButtons -from openpilot.selfdrive.car.interfaces import CarControllerBase - -VisualAlert = car.CarControl.HUDControl.VisualAlert -NetworkLocation = car.CarParams.NetworkLocation -LongCtrlState = car.CarControl.Actuators.LongControlState - -# Camera cancels up to 0.1s after brake is pressed, ECM allows 0.5s -CAMERA_CANCEL_DELAY_FRAMES = 10 -# Enforce a minimum interval between steering messages to avoid a fault -MIN_STEER_MSG_INTERVAL_MS = 15 - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.start_time = 0. - self.apply_steer_last = 0 - self.apply_gas = 0 - self.apply_brake = 0 - self.frame = 0 - self.last_steer_frame = 0 - self.last_button_frame = 0 - self.cancel_counter = 0 - - self.lka_steering_cmd_counter = 0 - self.lka_icon_status_last = (False, False) - - self.params = CarControllerParams(self.CP) - - self.packer_pt = CANPacker(DBC[self.CP.carFingerprint]['pt']) - self.packer_obj = CANPacker(DBC[self.CP.carFingerprint]['radar']) - self.packer_ch = CANPacker(DBC[self.CP.carFingerprint]['chassis']) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - hud_alert = hud_control.visualAlert - hud_v_cruise = hud_control.setSpeed - if hud_v_cruise > 70: - hud_v_cruise = 0 - - # Send CAN commands. - can_sends = [] - - # Steering (Active: 50Hz, inactive: 10Hz) - steer_step = self.params.STEER_STEP if CC.latActive else self.params.INACTIVE_STEER_STEP - - if self.CP.networkLocation == NetworkLocation.fwdCamera: - # Also send at 50Hz: - # - on startup, first few msgs are blocked - # - until we're in sync with camera so counters align when relay closes, preventing a fault. - # openpilot can subtly drift, so this is activated throughout a drive to stay synced - out_of_sync = self.lka_steering_cmd_counter % 4 != (CS.cam_lka_steering_cmd_counter + 1) % 4 - if CS.loopback_lka_steering_cmd_ts_nanos == 0 or out_of_sync: - steer_step = self.params.STEER_STEP - - self.lka_steering_cmd_counter += 1 if CS.loopback_lka_steering_cmd_updated else 0 - - # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we - # received the ASCMLKASteeringCmd loopback confirmation too recently - last_lka_steer_msg_ms = (now_nanos - CS.loopback_lka_steering_cmd_ts_nanos) * 1e-6 - if (self.frame - self.last_steer_frame) >= steer_step and last_lka_steer_msg_ms > MIN_STEER_MSG_INTERVAL_MS: - # Initialize ASCMLKASteeringCmd counter using the camera until we get a msg on the bus - if CS.loopback_lka_steering_cmd_ts_nanos == 0: - self.lka_steering_cmd_counter = CS.pt_lka_steering_cmd_counter + 1 - - if CC.latActive: - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) - else: - apply_steer = 0 - - self.last_steer_frame = self.frame - self.apply_steer_last = apply_steer - idx = self.lka_steering_cmd_counter % 4 - can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, CC.latActive)) - - if self.CP.openpilotLongitudinalControl: - # Gas/regen, brakes, and UI commands - all at 25Hz - if self.frame % 4 == 0: - stopping = actuators.longControlState == LongCtrlState.stopping - if not CC.longActive: - # ASCM sends max regen when not enabled - self.apply_gas = self.params.INACTIVE_REGEN - self.apply_brake = 0 - else: - self.apply_gas = int(round(interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) - self.apply_brake = int(round(interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) - # Don't allow any gas above inactive regen while stopping - # FIXME: brakes aren't applied immediately when enabling at a stop - if stopping: - self.apply_gas = self.params.INACTIVE_REGEN - - idx = (self.frame // 4) % 4 - - at_full_stop = CC.longActive and CS.out.standstill - near_stop = CC.longActive and (CS.out.vEgo < self.params.NEAR_STOP_BRAKE_PHASE) - friction_brake_bus = CanBus.CHASSIS - # GM Camera exceptions - # TODO: can we always check the longControlState? - if self.CP.networkLocation == NetworkLocation.fwdCamera: - at_full_stop = at_full_stop and stopping - friction_brake_bus = CanBus.POWERTRAIN - - # GasRegenCmdActive needs to be 1 to avoid cruise faults. It describes the ACC state, not actuation - can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, self.apply_gas, idx, CC.enabled, at_full_stop)) - can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, friction_brake_bus, self.apply_brake, - idx, CC.enabled, near_stop, at_full_stop, self.CP)) - - # Send dashboard UI commands (ACC status) - send_fcw = hud_alert == VisualAlert.fcw - can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, CC.enabled, - hud_v_cruise * CV.MS_TO_KPH, hud_control, send_fcw)) - - # Radar needs to know current speed and yaw rate (50hz), - # and that ADAS is alive (10hz) - if not self.CP.radarUnavailable: - tt = self.frame * DT_CTRL - time_and_headlights_step = 10 - if self.frame % time_and_headlights_step == 0: - idx = (self.frame // time_and_headlights_step) % 4 - can_sends.append(gmcan.create_adas_time_status(CanBus.OBSTACLE, int((tt - self.start_time) * 60), idx)) - can_sends.append(gmcan.create_adas_headlights_status(self.packer_obj, CanBus.OBSTACLE)) - - speed_and_accelerometer_step = 2 - if self.frame % speed_and_accelerometer_step == 0: - idx = (self.frame // speed_and_accelerometer_step) % 4 - can_sends.append(gmcan.create_adas_steering_status(CanBus.OBSTACLE, idx)) - can_sends.append(gmcan.create_adas_accelerometer_speed_status(CanBus.OBSTACLE, CS.out.vEgo, idx)) - - if self.CP.networkLocation == NetworkLocation.gateway and self.frame % self.params.ADAS_KEEPALIVE_STEP == 0: - can_sends += gmcan.create_adas_keepalive(CanBus.POWERTRAIN) - - else: - # While car is braking, cancel button causes ECM to enter a soft disable state with a fault status. - # A delayed cancellation allows camera to cancel and avoids a fault when user depresses brake quickly - self.cancel_counter = self.cancel_counter + 1 if CC.cruiseControl.cancel else 0 - - # Stock longitudinal, integrated at camera - if (self.frame - self.last_button_frame) * DT_CTRL > 0.04: - if self.cancel_counter > CAMERA_CANCEL_DELAY_FRAMES: - self.last_button_frame = self.frame - can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CS.buttons_counter, CruiseButtons.CANCEL)) - - if self.CP.networkLocation == NetworkLocation.fwdCamera: - # Silence "Take Steering" alert sent by camera, forward PSCMStatus with HandsOffSWlDetectionStatus=1 - if self.frame % 10 == 0: - can_sends.append(gmcan.create_pscm_status(self.packer_pt, CanBus.CAMERA, CS.pscm_status)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - new_actuators.gas = self.apply_gas - new_actuators.brake = self.apply_brake - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py deleted file mode 100644 index a1129c59c847abe..000000000000000 --- a/selfdrive/car/gm/carstate.py +++ /dev/null @@ -1,180 +0,0 @@ -import copy -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import mean -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.gm.values import DBC, AccState, CanBus, STEER_THRESHOLD - -TransmissionType = car.CarParams.TransmissionType -NetworkLocation = car.CarParams.NetworkLocation -STANDSTILL_THRESHOLD = 10 * 0.0311 * CV.KPH_TO_MS - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] - self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. - self.cluster_min_speed = CV.KPH_TO_MS / 2. - - self.loopback_lka_steering_cmd_updated = False - self.loopback_lka_steering_cmd_ts_nanos = 0 - self.pt_lka_steering_cmd_counter = 0 - self.cam_lka_steering_cmd_counter = 0 - self.buttons_counter = 0 - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, pt_cp, cam_cp, loopback_cp): - ret = car.CarState.new_message() - - self.prev_cruise_buttons = self.cruise_buttons - self.prev_distance_button = self.distance_button - self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] - self.distance_button = pt_cp.vl["ASCMSteeringButton"]["DistanceButton"] - self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] - self.pscm_status = copy.copy(pt_cp.vl["PSCMStatus"]) - # This is to avoid a fault where you engage while still moving backwards after shifting to D. - # An Equinox has been seen with an unsupported status (3), so only check if either wheel is in reverse (2) - self.moving_backward = (pt_cp.vl["EBCMWheelSpdRear"]["RLWheelDir"] == 2) or (pt_cp.vl["EBCMWheelSpdRear"]["RRWheelDir"] == 2) - - # Variables used for avoiding LKAS faults - self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]["RollingCounter"]) > 0 - if self.loopback_lka_steering_cmd_updated: - self.loopback_lka_steering_cmd_ts_nanos = loopback_cp.ts_nanos["ASCMLKASteeringCmd"]["RollingCounter"] - if self.CP.networkLocation == NetworkLocation.fwdCamera: - self.pt_lka_steering_cmd_counter = pt_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] - self.cam_lka_steering_cmd_counter = cam_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] - - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"], - pt_cp.vl["EBCMWheelSpdFront"]["FRWheelSpd"], - pt_cp.vl["EBCMWheelSpdRear"]["RLWheelSpd"], - pt_cp.vl["EBCMWheelSpdRear"]["RRWheelSpd"], - ) - ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]) - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - # sample rear wheel speeds, standstill=True if ECM allows engagement with brake - ret.standstill = ret.wheelSpeeds.rl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - if pt_cp.vl["ECMPRDNL2"]["ManualMode"] == 1: - ret.gearShifter = self.parse_gear_shifter("T") - else: - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL2"]["PRNDL2"], None)) - - ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] - if self.CP.networkLocation == NetworkLocation.fwdCamera: - ret.brakePressed = pt_cp.vl["ECMEngineStatus"]["BrakePressed"] != 0 - else: - # Some Volt 2016-17 have loose brake pedal push rod retainers which causes the ECM to believe - # that the brake is being intermittently pressed without user interaction. - # To avoid a cruise fault we need to use a conservative brake position threshold - # https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf - ret.brakePressed = ret.brake >= 8 - - # Regen braking is braking - if self.CP.transmissionType == TransmissionType.direct: - ret.regenBraking = pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0 - - ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254. - ret.gasPressed = ret.gas > 1e-5 - - ret.steeringAngleDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelAngle"] - ret.steeringRateDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelRate"] - ret.steeringTorque = pt_cp.vl["PSCMStatus"]["LKADriverAppldTrq"] - ret.steeringTorqueEps = pt_cp.vl["PSCMStatus"]["LKATorqueDelivered"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - - # 0 inactive, 1 active, 2 temporarily limited, 3 failed - self.lkas_status = pt_cp.vl["PSCMStatus"]["LKATorqueDeliveredStatus"] - ret.steerFaultTemporary = self.lkas_status == 2 - ret.steerFaultPermanent = self.lkas_status == 3 - - # 1 - open, 0 - closed - ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]["FrontLeftDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["FrontRightDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["RearLeftDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["RearRightDoor"] == 1) - - # 1 - latched - ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]["LeftSeatBelt"] == 0 - ret.leftBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 1 - ret.rightBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 2 - - ret.parkingBrake = pt_cp.vl["BCMGeneralPlatformStatus"]["ParkBrakeSwActive"] == 1 - ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0 - ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1 - ret.accFaulted = (pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED or - pt_cp.vl["EBCMFrictionBrakeStatus"]["FrictionBrakeUnavailable"] == 1) - - ret.cruiseState.enabled = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] != AccState.OFF - ret.cruiseState.standstill = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.STANDSTILL - if self.CP.networkLocation == NetworkLocation.fwdCamera: - ret.cruiseState.speed = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCSpeedSetpoint"] * CV.KPH_TO_MS - ret.stockAeb = cam_cp.vl["AEBCmd"]["AEBCmdActive"] != 0 - # openpilot controls nonAdaptive when not pcmCruise - if self.CP.pcmCruise: - ret.cruiseState.nonAdaptive = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCCruiseState"] not in (2, 3) - - if self.CP.enableBsm: - ret.leftBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["LeftBSM"] == 1 - ret.rightBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["RightBSM"] == 1 - - return ret - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - ("AEBCmd", 10), - ("ASCMLKASteeringCmd", 10), - ("ASCMActiveCruiseControlStatus", 25), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.CAMERA) - - @staticmethod - def get_can_parser(CP): - messages = [ - ("BCMTurnSignals", 1), - ("ECMPRDNL2", 10), - ("PSCMStatus", 10), - ("ESPStatus", 10), - ("BCMDoorBeltStatus", 10), - ("BCMGeneralPlatformStatus", 10), - ("EBCMWheelSpdFront", 20), - ("EBCMWheelSpdRear", 20), - ("EBCMFrictionBrakeStatus", 20), - ("AcceleratorPedal2", 33), - ("ASCMSteeringButton", 33), - ("ECMEngineStatus", 100), - ("PSCMSteeringAngle", 100), - ("ECMAcceleratorPos", 80), - ] - - if CP.enableBsm: - messages.append(("BCMBlindSpotMonitor", 10)) - - # Used to read back last counter sent to PT by camera - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - ("ASCMLKASteeringCmd", 0), - ] - - if CP.transmissionType == TransmissionType.direct: - messages.append(("EBCMRegenPaddle", 50)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.POWERTRAIN) - - @staticmethod - def get_loopback_can_parser(CP): - messages = [ - ("ASCMLKASteeringCmd", 0), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.LOOPBACK) diff --git a/selfdrive/car/gm/fingerprints.py b/selfdrive/car/gm/fingerprints.py deleted file mode 100644 index 3752fbb8d320290..000000000000000 --- a/selfdrive/car/gm/fingerprints.py +++ /dev/null @@ -1,63 +0,0 @@ -# ruff: noqa: E501 -from openpilot.selfdrive.car.gm.values import CAR - -# Trailblazer also matches as a SILVERADO, TODO: split with fw versions -# FIXME: There are Equinox users with different message lengths, specifically 304 and 320 - - -FINGERPRINTS = { - CAR.HOLDEN_ASTRA: [{ - 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 715: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7 - }], - CAR.CHEVROLET_VOLT: [{ - 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 715: 8, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 - }, - { - 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 578: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1516: 8, 1601: 8, 1618: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2018: 8, 2020: 8, 2024: 8, 2028: 8 - }, - { - 170: 8, 171: 8, 189: 7, 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 209: 7, 211: 2, 241: 6, 288: 5, 289: 1, 290: 1, 298: 2, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 368: 8, 381: 2, 384: 8, 386: 5, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 458: 8, 479: 3, 481: 7, 485: 8, 489: 5, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 3, 508: 8, 512: 3, 528: 4, 530: 8, 532: 6, 537: 5, 539: 8, 542: 7, 546: 7, 550: 8, 554: 3, 558: 8, 560: 6, 562: 4, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 821: 4, 823: 7, 832: 8, 840: 5, 842: 5, 844: 8, 853: 8, 866: 4, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 5, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7 - }], - CAR.BUICK_LACROSSE: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 353: 3, 381: 6, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 503: 1, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 5, 707: 8, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 872: 1, 882: 8, 890: 1, 892: 2, 893: 1, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1022: 1, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1243: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1913: 7, 1914: 7, 1916: 7, 1918: 7, 1919: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 - }], - CAR.BUICK_REGAL: [{ - 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 8, 419: 8, 422: 4, 426: 8, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 463: 3, 479: 8, 481: 7, 485: 8, 487: 8, 489: 8, 495: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 578: 8, 579: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 884: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 8, 969: 8, 977: 8, 979: 8, 985: 8, 1001: 8, 1005: 6, 1009: 8, 1011: 8, 1013: 3, 1017: 8, 1020: 8, 1024: 8, 1025: 8, 1026: 8, 1027: 8, 1028: 8, 1029: 8, 1030: 8, 1031: 8, 1032: 2, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 8, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 8, 1263: 8, 1265: 8, 1267: 8, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1602: 8, 1603: 7, 1611: 8, 1618: 8, 1906: 8, 1907: 7, 1912: 7, 1914: 7, 1916: 7, 1919: 7, 1930: 7, 2016: 8, 2018: 8, 2019: 8, 2024: 8, 2026: 8 - }], - CAR.CADILLAC_ATS: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.CHEVROLET_MALIBU: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.GMC_ACADIA: [{ - 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 1, 290: 1, 298: 8, 304: 8, 309: 8, 313: 8, 320: 8, 322: 7, 328: 1, 352: 7, 368: 8, 381: 8, 384: 8, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 458: 8, 460: 4, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 5, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 512: 3, 530: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 568: 2, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 801: 8, 803: 8, 804: 3, 805: 8, 832: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7 - }, - { - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.CADILLAC_ESCALADE: [{ - 170: 8, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 4, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 - }], - CAR.CADILLAC_ESCALADE_ESV: [{ - 309: 1, 848: 8, 849: 8, 850: 8, 851: 8, 852: 8, 853: 8, 854: 3, 1056: 6, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1061: 8, 1062: 8, 1063: 8, 1064: 8, 1065: 8, 1066: 8, 1067: 8, 1068: 8, 1120: 8, 1121: 8, 1122: 8, 1123: 8, 1124: 8, 1125: 8, 1126: 8, 1127: 8, 1128: 8, 1129: 8, 1130: 8, 1131: 8, 1132: 8, 1133: 8, 1134: 8, 1135: 8, 1136: 8, 1137: 8, 1138: 8, 1139: 8, 1140: 8, 1141: 8, 1142: 8, 1143: 8, 1146: 8, 1147: 8, 1148: 8, 1149: 8, 1150: 8, 1151: 8, 1216: 8, 1217: 8, 1218: 8, 1219: 8, 1220: 8, 1221: 8, 1222: 8, 1223: 8, 1224: 8, 1225: 8, 1226: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1240: 8, 1241: 8, 1242: 8, 1787: 8, 1788: 8 - }], - CAR.CADILLAC_ESCALADE_ESV_2019: [{ - 715: 8, 840: 5, 717: 5, 869: 4, 880: 6, 289: 8, 454: 8, 842: 5, 460: 5, 463: 3, 801: 8, 170: 8, 190: 6, 241: 6, 201: 8, 417: 7, 211: 2, 419: 1, 398: 8, 426: 7, 487: 8, 442: 8, 451: 8, 452: 8, 453: 6, 479: 3, 311: 8, 500: 6, 647: 6, 193: 8, 707: 8, 197: 8, 209: 7, 199: 4, 455: 7, 313: 8, 481: 7, 485: 8, 489: 8, 249: 8, 393: 7, 407: 7, 413: 8, 422: 4, 431: 8, 501: 8, 499: 3, 810: 8, 508: 8, 381: 8, 462: 4, 532: 6, 562: 8, 386: 8, 761: 7, 573: 1, 554: 3, 719: 5, 560: 8, 1279: 4, 388: 8, 288: 5, 1005: 6, 497: 8, 844: 8, 961: 8, 967: 4, 977: 8, 979: 8, 985: 5, 1001: 8, 1017: 8, 1019: 2, 1020: 8, 1217: 8, 510: 8, 866: 4, 304: 1, 969: 8, 384: 4, 1033: 7, 1009: 8, 1034: 7, 1296: 4, 1930: 7, 1105: 5, 1013: 5, 1225: 7, 1919: 7, 320: 3, 534: 2, 352: 5, 298: 8, 1223: 2, 1233: 8, 608: 8, 1265: 8, 609: 6, 1267: 1, 1417: 8, 610: 6, 1906: 7, 611: 6, 612: 8, 613: 8, 208: 8, 564: 5, 309: 8, 1221: 5, 1280: 4, 1249: 8, 1907: 7, 1257: 6, 1300: 8, 1920: 7, 563: 5, 1322: 6, 1323: 4, 1328: 4, 1917: 7, 328: 1, 1912: 7, 1914: 7, 804: 3, 1918: 7 - }], - CAR.CHEVROLET_BOLT_EUV: [{ - 189: 7, 190: 7, 193: 8, 197: 8, 201: 8, 209: 7, 211: 3, 241: 6, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 451: 8, 452: 8, 453: 6, 458: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 566: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1265: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - CAR.CHEVROLET_SILVERADO: [{ - 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - CAR.CHEVROLET_EQUINOX: [{ - 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }, - { - 190: 6, 201: 8, 211: 2, 717: 5, 241: 6, 451: 8, 298: 8, 452: 8, 453: 6, 479: 3, 485: 8, 249: 8, 500: 6, 587: 8, 1611: 8, 289: 8, 481: 7, 193: 8, 197: 8, 209: 7, 455: 7, 489: 8, 309: 8, 413: 8, 501: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 311: 8, 510: 8, 528: 5, 532: 6, 715: 8, 560: 8, 562: 8, 707: 8, 789: 5, 869: 4, 880: 6, 761: 7, 840: 5, 842: 5, 844: 8, 313: 8, 381: 8, 386: 8, 810: 8, 322: 7, 384: 4, 800: 6, 1033: 7, 1034: 7, 1296: 4, 753: 5, 388: 8, 288: 5, 497: 8, 463: 3, 304: 3, 977: 8, 1001: 8, 1280: 4, 320: 4, 352: 5, 563: 5, 565: 5, 1221: 5, 1011: 6, 1017: 8, 1020: 8, 1249: 8, 1300: 8, 328: 1, 1217: 8, 1233: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1930: 7, 1271: 8 - }], -} - -FW_VERSIONS: dict[str, dict[tuple, list[bytes]]] = { -} diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py deleted file mode 100755 index 358bc9e5ba32bbe..000000000000000 --- a/selfdrive/car/gm/interface.py +++ /dev/null @@ -1,239 +0,0 @@ -#!/usr/bin/env python3 -import os -from cereal import car -from math import fabs, exp -from panda import Panda - -from openpilot.common.basedir import BASEDIR -from openpilot.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, LatControlInputs, NanoFFModel -from openpilot.selfdrive.controls.lib.drive_helpers import get_friction - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -GearShifter = car.CarState.GearShifter -TransmissionType = car.CarParams.TransmissionType -NetworkLocation = car.CarParams.NetworkLocation -BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, - CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} - - -NON_LINEAR_TORQUE_PARAMS = { - CAR.CHEVROLET_BOLT_EUV: [2.6531724862969748, 1.0, 0.1919764879840985, 0.009054123646805178], - CAR.GMC_ACADIA: [4.78003305, 1.0, 0.3122, 0.05591772], - CAR.CHEVROLET_SILVERADO: [3.29974374, 1.0, 0.25571356, 0.0465122] -} - -NEURAL_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/neural_ff_weights.json') - - -class CarInterface(CarInterfaceBase): - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX - - # Determined by iteratively plotting and minimizing error for f(angle, speed) = steer. - @staticmethod - def get_steer_feedforward_volt(desired_angle, v_ego): - desired_angle *= 0.02904609 - sigmoid = desired_angle / (1 + fabs(desired_angle)) - return 0.10006696 * sigmoid * (v_ego + 3.12485927) - - def get_steer_feedforward_function(self): - if self.CP.carFingerprint == CAR.CHEVROLET_VOLT: - return self.get_steer_feedforward_volt - else: - return CarInterfaceBase.get_steer_feedforward_default - - def torque_from_lateral_accel_siglin(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, - lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: - friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - - def sig(val): - return 1 / (1 + exp(-val)) - 0.5 - - # The "lat_accel vs torque" relationship is assumed to be the sum of "sigmoid + linear" curves - # An important thing to consider is that the slope at 0 should be > 0 (ideally >1) - # This has big effect on the stability about 0 (noise when going straight) - # ToDo: To generalize to other GMs, explore tanh function as the nonlinear - non_linear_torque_params = NON_LINEAR_TORQUE_PARAMS.get(self.CP.carFingerprint) - assert non_linear_torque_params, "The params are not defined" - a, b, c, _ = non_linear_torque_params - steer_torque = (sig(latcontrol_inputs.lateral_acceleration * a) * b) + (latcontrol_inputs.lateral_acceleration * c) - return float(steer_torque) + friction - - def torque_from_lateral_accel_neural(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, - lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: - friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - inputs = list(latcontrol_inputs) - if gravity_adjusted: - inputs[0] += inputs[1] - return float(self.neural_ff_model.predict(inputs)) + friction - - def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: - if self.CP.carFingerprint == CAR.CHEVROLET_BOLT_EUV: - self.neural_ff_model = NanoFFModel(NEURAL_PARAMS_PATH, self.CP.carFingerprint) - return self.torque_from_lateral_accel_neural - elif self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: - return self.torque_from_lateral_accel_siglin - else: - return self.torque_from_lateral_accel_linear - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "gm" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] - ret.autoResumeSng = False - ret.enableBsm = 0x142 in fingerprint[CanBus.POWERTRAIN] - - if candidate in EV_CAR: - ret.transmissionType = TransmissionType.direct - else: - ret.transmissionType = TransmissionType.automatic - - ret.longitudinalTuning.deadzoneBP = [0.] - ret.longitudinalTuning.deadzoneV = [0.15] - - ret.longitudinalTuning.kpBP = [5., 35.] - ret.longitudinalTuning.kiBP = [0.] - - if candidate in CAMERA_ACC_CAR: - ret.experimentalLongitudinalAvailable = True - ret.networkLocation = NetworkLocation.fwdCamera - ret.radarUnavailable = True # no radar - ret.pcmCruise = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM - ret.minEnableSpeed = 5 * CV.KPH_TO_MS - ret.minSteerSpeed = 10 * CV.KPH_TO_MS - - # Tuning for experimental long - ret.longitudinalTuning.kpV = [2.0, 1.5] - ret.longitudinalTuning.kiV = [0.72] - ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling - ret.vEgoStopping = 0.25 - ret.vEgoStarting = 0.25 - - if experimental_long: - ret.pcmCruise = False - ret.openpilotLongitudinalControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM_LONG - - else: # ASCM, OBD-II harness - ret.openpilotLongitudinalControl = True - ret.networkLocation = NetworkLocation.gateway - ret.radarUnavailable = RADAR_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and not docs - ret.pcmCruise = False # stock non-adaptive cruise control is kept off - # supports stop and go, but initial engage must (conservatively) be above 18mph - ret.minEnableSpeed = 18 * CV.MPH_TO_MS - ret.minSteerSpeed = 7 * CV.MPH_TO_MS - - # Tuning - ret.longitudinalTuning.kpV = [2.4, 1.5] - ret.longitudinalTuning.kiV = [0.36] - - # These cars have been put into dashcam only due to both a lack of users and test coverage. - # These cars likely still work fine. Once a user confirms each car works and a test route is - # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.CHEVROLET_MALIBU, CAR.BUICK_REGAL} or \ - (ret.networkLocation == NetworkLocation.gateway and ret.radarUnavailable) - - # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] - ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 - ret.steerActuatorDelay = 0.1 # Default delay, not measured yet - - ret.steerLimitTimer = 0.4 - ret.radarTimeStep = 0.0667 # GM radar runs at 15Hz instead of standard 20Hz - ret.longitudinalActuatorDelayUpperBound = 0.5 # large delay to initially start braking - - if candidate == CAR.CHEVROLET_VOLT: - ret.lateralTuning.pid.kpBP = [0., 40.] - ret.lateralTuning.pid.kpV = [0., 0.17] - ret.lateralTuning.pid.kiBP = [0.] - ret.lateralTuning.pid.kiV = [0.] - ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_volt() - ret.steerActuatorDelay = 0.2 - - elif candidate == CAR.GMC_ACADIA: - ret.minEnableSpeed = -1. # engage speed is decided by pcm - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.BUICK_LACROSSE: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CADILLAC_ESCALADE: - ret.minEnableSpeed = -1. # engage speed is decided by pcm - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate in (CAR.CADILLAC_ESCALADE_ESV, CAR.CADILLAC_ESCALADE_ESV_2019): - ret.minEnableSpeed = -1. # engage speed is decided by pcm - - if candidate == CAR.CADILLAC_ESCALADE_ESV: - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[10., 41.0], [10., 41.0]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.13, 0.24], [0.01, 0.02]] - ret.lateralTuning.pid.kf = 0.000045 - else: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_BOLT_EUV: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_SILVERADO: - # On the Bolt, the ECM and camera independently check that you are either above 5 kph or at a stop - # with foot on brake to allow engagement, but this platform only has that check in the camera. - # TODO: check if this is split by EV/ICE with more platforms in the future - if ret.openpilotLongitudinalControl: - ret.minEnableSpeed = -1. - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_EQUINOX: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_TRAILBLAZER: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_loopback) - - # Don't add event if transitioning from INIT, unless it's to an actual button - if self.CS.cruise_buttons != CruiseButtons.UNPRESS or self.CS.prev_cruise_buttons != CruiseButtons.INIT: - ret.buttonEvents = [ - *create_button_events(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT, - unpressed_btn=CruiseButtons.UNPRESS), - *create_button_events(self.CS.distance_button, self.CS.prev_distance_button, - {1: ButtonType.gapAdjustCruise}) - ] - - # The ECM allows enabling on falling edge of set, but only rising edge of resume - events = self.create_common_events(ret, extra_gears=[GearShifter.sport, GearShifter.low, - GearShifter.eco, GearShifter.manumatic], - pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,)) - if not self.CP.pcmCruise: - if any(b.type == ButtonType.accelCruise and b.pressed for b in ret.buttonEvents): - events.add(EventName.buttonEnable) - - # Enabling at a standstill with brake is allowed - # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs - below_min_enable_speed = ret.vEgo < self.CP.minEnableSpeed or self.CS.moving_backward - if below_min_enable_speed and not (ret.standstill and ret.brake >= 20 and - self.CP.networkLocation == NetworkLocation.fwdCamera): - events.add(EventName.belowEngageSpeed) - if ret.cruiseState.standstill: - events.add(EventName.resumeRequired) - if ret.vEgo < self.CP.minSteerSpeed: - events.add(EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py deleted file mode 100755 index b893babd3193969..000000000000000 --- a/selfdrive/car/gm/radar_interface.py +++ /dev/null @@ -1,101 +0,0 @@ -#!/usr/bin/env python3 -import math -from cereal import car -from openpilot.common.conversions import Conversions as CV -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.gm.values import DBC, CanBus -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -RADAR_HEADER_MSG = 1120 -SLOT_1_MSG = RADAR_HEADER_MSG + 1 -NUM_SLOTS = 20 - -# Actually it's 0x47f, but can parser only reports -# messages that are present in DBC -LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS - - -def create_radar_can_parser(car_fingerprint): - # C1A-ARS3-A by Continental - radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)) - signals = list(zip(['FLRRNumValidTargets', - 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', - 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', - 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + - ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + - ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + - ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, - [RADAR_HEADER_MSG] * 7 + radar_targets * 6, strict=True)) - - messages = list({(s[1], 14) for s in signals}) - - return CANParser(DBC[car_fingerprint]['radar'], messages, CanBus.OBSTACLE) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - - self.rcp = None if CP.radarUnavailable else create_radar_can_parser(CP.carFingerprint) - - self.trigger_msg = LAST_RADAR_MSG - self.updated_messages = set() - self.radar_ts = CP.radarTimeStep - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - header = self.rcp.vl[RADAR_HEADER_MSG] - fault = header['FLRRSnsrBlckd'] or header['FLRRSnstvFltPrsntInt'] or \ - header['FLRRYawRtPlsblityFlt'] or header['FLRRHWFltPrsntInt'] or \ - header['FLRRAntTngFltPrsnt'] or header['FLRRAlgnFltPrsnt'] - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - if fault: - errors.append("fault") - ret.errors = errors - - currentTargets = set() - num_targets = header['FLRRNumValidTargets'] - - # Not all radar messages describe targets, - # no need to monitor all of the self.rcp.msgs_upd - for ii in self.updated_messages: - if ii == RADAR_HEADER_MSG: - continue - - if num_targets == 0: - break - - cpt = self.rcp.vl[ii] - # Zero distance means it's an empty target slot - if cpt['TrkRange'] > 0.0: - targetId = cpt['TrkObjectID'] - currentTargets.add(targetId) - if targetId not in self.pts: - self.pts[targetId] = car.RadarData.RadarPoint.new_message() - self.pts[targetId].trackId = targetId - distance = cpt['TrkRange'] - self.pts[targetId].dRel = distance # from front of car - # From driver's pov, left is positive - self.pts[targetId].yRel = math.sin(cpt['TrkAzimuth'] * CV.DEG_TO_RAD) * distance - self.pts[targetId].vRel = cpt['TrkRangeRate'] - self.pts[targetId].aRel = float('nan') - self.pts[targetId].yvRel = float('nan') - - for oldTarget in list(self.pts.keys()): - if oldTarget not in currentTargets: - del self.pts[oldTarget] - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py deleted file mode 100644 index 53a4621d27fe89f..000000000000000 --- a/selfdrive/car/gm/values.py +++ /dev/null @@ -1,234 +0,0 @@ -from dataclasses import dataclass, field - -from cereal import car -from openpilot.selfdrive.car import dbc_dict, PlatformConfig, DbcDict, Platforms, CarSpecs -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output - STEER_STEP = 3 # Active control frames per command (~33hz) - INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz) - STEER_DELTA_UP = 10 # Delta rates require review due to observed EPS weakness - STEER_DELTA_DOWN = 15 - STEER_DRIVER_ALLOWANCE = 65 - STEER_DRIVER_MULTIPLIER = 4 - STEER_DRIVER_FACTOR = 100 - NEAR_STOP_BRAKE_PHASE = 0.5 # m/s - - # Heartbeat for dash "Service Adaptive Cruise" and "Service Front Camera" - ADAS_KEEPALIVE_STEP = 100 - CAMERA_KEEPALIVE_STEP = 100 - - # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we - # perform the closed loop control, and might need some - # to apply some more braking if we're on a downhill slope. - # Our controller should still keep the 2 second average above - # -3.5 m/s^2 as per planner limits - ACCEL_MAX = 2. # m/s^2 - ACCEL_MIN = -4. # m/s^2 - - def __init__(self, CP): - # Gas/brake lookups - self.ZERO_GAS = 2048 # Coasting - self.MAX_BRAKE = 400 # ~ -4.0 m/s^2 with regen - - if CP.carFingerprint in CAMERA_ACC_CAR: - self.MAX_GAS = 3400 - self.MAX_ACC_REGEN = 1514 - self.INACTIVE_REGEN = 1554 - # Camera ACC vehicles have no regen while enabled. - # Camera transitions to MAX_ACC_REGEN from ZERO_GAS and uses friction brakes instantly - max_regen_acceleration = 0. - - else: - self.MAX_GAS = 3072 # Safety limit, not ACC max. Stock ACC >4096 from standstill. - self.MAX_ACC_REGEN = 1404 # Max ACC regen is slightly less than max paddle regen - self.INACTIVE_REGEN = 1404 - # ICE has much less engine braking force compared to regen in EVs, - # lower threshold removes some braking deadzone - max_regen_acceleration = -1. if CP.carFingerprint in EV_CAR else -0.1 - - self.GAS_LOOKUP_BP = [max_regen_acceleration, 0., self.ACCEL_MAX] - self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, self.ZERO_GAS, self.MAX_GAS] - - self.BRAKE_LOOKUP_BP = [self.ACCEL_MIN, max_regen_acceleration] - self.BRAKE_LOOKUP_V = [self.MAX_BRAKE, 0.] - - -@dataclass -class GMCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC)" - - def init_make(self, CP: car.CarParams): - if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera: - self.car_parts = CarParts.common([CarHarness.gm]) - else: - self.car_parts = CarParts.common([CarHarness.obd_ii]) - - -@dataclass(frozen=True, kw_only=True) -class GMCarSpecs(CarSpecs): - tireStiffnessFactor: float = 0.444 # not optimized yet - - -@dataclass -class GMPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) - - -@dataclass -class GMASCMPlatformConfig(GMPlatformConfig): - def init(self): - # ASCM is supported, but due to a janky install and hardware configuration, we are not showing in the car docs - self.car_docs = [] - - -class CAR(Platforms): - HOLDEN_ASTRA = GMASCMPlatformConfig( - [GMCarDocs("Holden Astra 2017")], - GMCarSpecs(mass=1363, wheelbase=2.662, steerRatio=15.7, centerToFrontRatio=0.4), - ) - CHEVROLET_VOLT = GMASCMPlatformConfig( - [GMCarDocs("Chevrolet Volt 2017-18", min_enable_speed=0, video_link="https://youtu.be/QeMCN_4TFfQ")], - GMCarSpecs(mass=1607, wheelbase=2.69, steerRatio=17.7, centerToFrontRatio=0.45, tireStiffnessFactor=0.469), - ) - CADILLAC_ATS = GMASCMPlatformConfig( - [GMCarDocs("Cadillac ATS Premium Performance 2018")], - GMCarSpecs(mass=1601, wheelbase=2.78, steerRatio=15.3), - ) - CHEVROLET_MALIBU = GMASCMPlatformConfig( - [GMCarDocs("Chevrolet Malibu Premier 2017")], - GMCarSpecs(mass=1496, wheelbase=2.83, steerRatio=15.8, centerToFrontRatio=0.4), - ) - GMC_ACADIA = GMASCMPlatformConfig( - [GMCarDocs("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo")], - GMCarSpecs(mass=1975, wheelbase=2.86, steerRatio=14.4, centerToFrontRatio=0.4), - ) - BUICK_LACROSSE = GMASCMPlatformConfig( - [GMCarDocs("Buick LaCrosse 2017-19", "Driver Confidence Package 2")], - GMCarSpecs(mass=1712, wheelbase=2.91, steerRatio=15.8, centerToFrontRatio=0.4), - ) - BUICK_REGAL = GMASCMPlatformConfig( - [GMCarDocs("Buick Regal Essence 2018")], - GMCarSpecs(mass=1714, wheelbase=2.83, steerRatio=14.4, centerToFrontRatio=0.4), - ) - CADILLAC_ESCALADE = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade 2017", "Driver Assist Package")], - GMCarSpecs(mass=2564, wheelbase=2.95, steerRatio=17.3), - ) - CADILLAC_ESCALADE_ESV = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS")], - GMCarSpecs(mass=2739, wheelbase=3.302, steerRatio=17.3, tireStiffnessFactor=1.0), - ) - CADILLAC_ESCALADE_ESV_2019 = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade ESV 2019", "Adaptive Cruise Control (ACC) & LKAS")], - CADILLAC_ESCALADE_ESV.specs, - ) - CHEVROLET_BOLT_EUV = GMPlatformConfig( - [ - GMCarDocs("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210"), - GMCarDocs("Chevrolet Bolt EV 2022-23", "2LT Trim with Adaptive Cruise Control Package"), - ], - GMCarSpecs(mass=1669, wheelbase=2.63779, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), - ) - CHEVROLET_SILVERADO = GMPlatformConfig( - [ - GMCarDocs("Chevrolet Silverado 1500 2020-21", "Safety Package II"), - GMCarDocs("GMC Sierra 1500 2020-21", "Driver Alert Package II", video_link="https://youtu.be/5HbNoBLzRwE"), - ], - GMCarSpecs(mass=2450, wheelbase=3.75, steerRatio=16.3, tireStiffnessFactor=1.0), - ) - CHEVROLET_EQUINOX = GMPlatformConfig( - [GMCarDocs("Chevrolet Equinox 2019-22")], - GMCarSpecs(mass=1588, wheelbase=2.72, steerRatio=14.4, centerToFrontRatio=0.4), - ) - CHEVROLET_TRAILBLAZER = GMPlatformConfig( - [GMCarDocs("Chevrolet Trailblazer 2021-22")], - GMCarSpecs(mass=1345, wheelbase=2.64, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), - ) - - -class CruiseButtons: - INIT = 0 - UNPRESS = 1 - RES_ACCEL = 2 - DECEL_SET = 3 - MAIN = 5 - CANCEL = 6 - -class AccState: - OFF = 0 - ACTIVE = 1 - FAULTED = 3 - STANDSTILL = 4 - -class CanBus: - POWERTRAIN = 0 - OBSTACLE = 1 - CAMERA = 2 - CHASSIS = 2 - LOOPBACK = 128 - DROPPED = 192 - - -# In a Data Module, an identifier is a string used to recognize an object, -# either by itself or together with the identifiers of parent objects. -# Each returns a 4 byte hex representation of the decimal part number. `b"\x02\x8c\xf0'"` -> 42790951 -GM_BOOT_SOFTWARE_PART_NUMER_REQUEST = b'\x1a\xc0' # likely does not contain anything useful -GM_SOFTWARE_MODULE_1_REQUEST = b'\x1a\xc1' -GM_SOFTWARE_MODULE_2_REQUEST = b'\x1a\xc2' -GM_SOFTWARE_MODULE_3_REQUEST = b'\x1a\xc3' - -# Part number of XML data file that is used to configure ECU -GM_XML_DATA_FILE_PART_NUMBER = b'\x1a\x9c' -GM_XML_CONFIG_COMPAT_ID = b'\x1a\x9b' # used to know if XML file is compatible with the ECU software/hardware - -# This DID is for identifying the part number that reflects the mix of hardware, -# software, and calibrations in the ECU when it first arrives at the vehicle assembly plant. -# If there's an Alpha Code, it's associated with this part number and stored in the DID $DB. -GM_END_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcb' -GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdb' -GM_BASE_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcc' -GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdc' -GM_FW_RESPONSE = b'\x5a' - -GM_FW_REQUESTS = [ - GM_BOOT_SOFTWARE_PART_NUMER_REQUEST, - GM_SOFTWARE_MODULE_1_REQUEST, - GM_SOFTWARE_MODULE_2_REQUEST, - GM_SOFTWARE_MODULE_3_REQUEST, - GM_XML_DATA_FILE_PART_NUMBER, - GM_XML_CONFIG_COMPAT_ID, - GM_END_MODEL_PART_NUMBER_REQUEST, - GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, - GM_BASE_MODEL_PART_NUMBER_REQUEST, - GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, -] - -GM_RX_OFFSET = 0x400 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for req in GM_FW_REQUESTS for request in [ - Request( - [StdQueries.SHORT_TESTER_PRESENT_REQUEST, req], - [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, GM_FW_RESPONSE + bytes([req[-1]])], - rx_offset=GM_RX_OFFSET, - bus=0, - logging=True, - ), - ]], - extra_ecus=[(Ecu.fwdCamera, 0x24b, None)], -) - -EV_CAR = {CAR.CHEVROLET_VOLT, CAR.CHEVROLET_BOLT_EUV} - -# We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) -CAMERA_ACC_CAR = {CAR.CHEVROLET_BOLT_EUV, CAR.CHEVROLET_SILVERADO, CAR.CHEVROLET_EQUINOX, CAR.CHEVROLET_TRAILBLAZER} - -STEER_THRESHOLD = 1.0 - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py deleted file mode 100644 index fe023ea17d714ea..000000000000000 --- a/selfdrive/car/honda/carcontroller.py +++ /dev/null @@ -1,256 +0,0 @@ -from collections import namedtuple - -from cereal import car -from openpilot.common.numpy_fast import clip, interp -from openpilot.common.realtime import DT_CTRL -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car.honda import hondacan -from openpilot.selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.controls.lib.drive_helpers import rate_limit - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - - -def compute_gb_honda_bosch(accel, speed): - # TODO returns 0s, is unused - return 0.0, 0.0 - - -def compute_gb_honda_nidec(accel, speed): - creep_brake = 0.0 - creep_speed = 2.3 - creep_brake_value = 0.15 - if speed < creep_speed: - creep_brake = (creep_speed - speed) / creep_speed * creep_brake_value - gb = float(accel) / 4.8 - creep_brake - return clip(gb, 0.0, 1.0), clip(-gb, 0.0, 1.0) - - -def compute_gas_brake(accel, speed, fingerprint): - if fingerprint in HONDA_BOSCH: - return compute_gb_honda_bosch(accel, speed) - else: - return compute_gb_honda_nidec(accel, speed) - - -# TODO not clear this does anything useful -def actuator_hysteresis(brake, braking, brake_steady, v_ego, car_fingerprint): - # hyst params - brake_hyst_on = 0.02 # to activate brakes exceed this value - brake_hyst_off = 0.005 # to deactivate brakes below this value - brake_hyst_gap = 0.01 # don't change brake command for small oscillations within this value - - # *** hysteresis logic to avoid brake blinking. go above 0.1 to trigger - if (brake < brake_hyst_on and not braking) or brake < brake_hyst_off: - brake = 0. - braking = brake > 0. - - # for small brake oscillations within brake_hyst_gap, don't change the brake command - if brake == 0.: - brake_steady = 0. - elif brake > brake_steady + brake_hyst_gap: - brake_steady = brake - brake_hyst_gap - elif brake < brake_steady - brake_hyst_gap: - brake_steady = brake + brake_hyst_gap - brake = brake_steady - - return brake, braking, brake_steady - - -def brake_pump_hysteresis(apply_brake, apply_brake_last, last_pump_ts, ts): - pump_on = False - - # reset pump timer if: - # - there is an increment in brake request - # - we are applying steady state brakes and we haven't been running the pump - # for more than 20s (to prevent pressure bleeding) - if apply_brake > apply_brake_last or (ts - last_pump_ts > 20. and apply_brake > 0): - last_pump_ts = ts - - # once the pump is on, run it for at least 0.2s - if ts - last_pump_ts < 0.2 and apply_brake > 0: - pump_on = True - - return pump_on, last_pump_ts - - -def process_hud_alert(hud_alert): - # initialize to no alert - fcw_display = 0 - steer_required = 0 - acc_alert = 0 - - # priority is: FCW, steer required, all others - if hud_alert == VisualAlert.fcw: - fcw_display = VISUAL_HUD[hud_alert.raw] - elif hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw): - steer_required = VISUAL_HUD[hud_alert.raw] - else: - acc_alert = VISUAL_HUD[hud_alert.raw] - - return fcw_display, steer_required, acc_alert - - -HUDData = namedtuple("HUDData", - ["pcm_accel", "v_cruise", "lead_visible", - "lanes_visible", "fcw", "acc_alert", "steer_required", "lead_distance_bars"]) - - -def rate_limit_steer(new_steer, last_steer): - # TODO just hardcoded ramp to min/max in 0.33s for all Honda - MAX_DELTA = 3 * DT_CTRL - return clip(new_steer, last_steer - MAX_DELTA, last_steer + MAX_DELTA) - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.packer = CANPacker(dbc_name) - self.params = CarControllerParams(CP) - self.CAN = hondacan.CanBus(CP) - self.frame = 0 - - self.braking = False - self.brake_steady = 0. - self.brake_last = 0. - self.apply_brake_last = 0 - self.last_pump_ts = 0. - self.stopping_counter = 0 - - self.accel = 0.0 - self.speed = 0.0 - self.gas = 0.0 - self.brake = 0.0 - self.last_steer = 0.0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - conversion = hondacan.get_cruise_speed_conversion(self.CP.carFingerprint, CS.is_metric) - hud_v_cruise = hud_control.setSpeed / conversion if hud_control.speedVisible else 255 - pcm_cancel_cmd = CC.cruiseControl.cancel - - if CC.longActive: - accel = actuators.accel - gas, brake = compute_gas_brake(actuators.accel, CS.out.vEgo, self.CP.carFingerprint) - else: - accel = 0.0 - gas, brake = 0.0, 0.0 - - # *** rate limit steer *** - limited_steer = rate_limit_steer(actuators.steer, self.last_steer) - self.last_steer = limited_steer - - # *** apply brake hysteresis *** - pre_limit_brake, self.braking, self.brake_steady = actuator_hysteresis(brake, self.braking, self.brake_steady, - CS.out.vEgo, self.CP.carFingerprint) - - # *** rate limit after the enable check *** - self.brake_last = rate_limit(pre_limit_brake, self.brake_last, -2., DT_CTRL) - - # vehicle hud display, wait for one update from 10Hz 0x304 msg - fcw_display, steer_required, acc_alert = process_hud_alert(hud_control.visualAlert) - - # **** process the car messages **** - - # steer torque is converted back to CAN reference (positive when steering right) - apply_steer = int(interp(-limited_steer * self.params.STEER_MAX, - self.params.STEER_LOOKUP_BP, self.params.STEER_LOOKUP_V)) - - # Send CAN commands - can_sends = [] - - # tester present - w/ no response (keeps radar disabled) - if self.CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and self.CP.openpilotLongitudinalControl: - if self.frame % 10 == 0: - can_sends.append((0x18DAB0F1, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", 1)) - - # Send steering command. - can_sends.append(hondacan.create_steering_control(self.packer, self.CAN, apply_steer, CC.latActive, self.CP.carFingerprint, - CS.CP.openpilotLongitudinalControl)) - - # wind brake from air resistance decel at high speed - wind_brake = interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15]) - # all of this is only relevant for HONDA NIDEC - max_accel = interp(CS.out.vEgo, self.params.NIDEC_MAX_ACCEL_BP, self.params.NIDEC_MAX_ACCEL_V) - # TODO this 1.44 is just to maintain previous behavior - pcm_speed_BP = [-wind_brake, - -wind_brake * (3 / 4), - 0.0, - 0.5] - # The Honda ODYSSEY seems to have different PCM_ACCEL - # msgs, is it other cars too? - if not CC.longActive: - pcm_speed = 0.0 - pcm_accel = int(0.0) - elif self.CP.carFingerprint in HONDA_NIDEC_ALT_PCM_ACCEL: - pcm_speed_V = [0.0, - clip(CS.out.vEgo - 3.0, 0.0, 100.0), - clip(CS.out.vEgo + 0.0, 0.0, 100.0), - clip(CS.out.vEgo + 5.0, 0.0, 100.0)] - pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) - pcm_accel = int(1.0 * self.params.NIDEC_GAS_MAX) - else: - pcm_speed_V = [0.0, - clip(CS.out.vEgo - 2.0, 0.0, 100.0), - clip(CS.out.vEgo + 2.0, 0.0, 100.0), - clip(CS.out.vEgo + 5.0, 0.0, 100.0)] - pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) - pcm_accel = int(clip((accel / 1.44) / max_accel, 0.0, 1.0) * self.params.NIDEC_GAS_MAX) - - if not self.CP.openpilotLongitudinalControl: - if self.frame % 2 == 0 and self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: # radarless cars don't have supplemental message - can_sends.append(hondacan.create_bosch_supplemental_1(self.packer, self.CAN, self.CP.carFingerprint)) - # If using stock ACC, spam cancel command to kill gas when OP disengages. - if pcm_cancel_cmd: - can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.CANCEL, self.CP.carFingerprint)) - elif CC.cruiseControl.resume: - can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.RES_ACCEL, self.CP.carFingerprint)) - - else: - # Send gas and brake commands. - if self.frame % 2 == 0: - ts = self.frame * DT_CTRL - - if self.CP.carFingerprint in HONDA_BOSCH: - self.accel = clip(accel, self.params.BOSCH_ACCEL_MIN, self.params.BOSCH_ACCEL_MAX) - self.gas = interp(accel, self.params.BOSCH_GAS_LOOKUP_BP, self.params.BOSCH_GAS_LOOKUP_V) - - stopping = actuators.longControlState == LongCtrlState.stopping - self.stopping_counter = self.stopping_counter + 1 if stopping else 0 - can_sends.extend(hondacan.create_acc_commands(self.packer, self.CAN, CC.enabled, CC.longActive, self.accel, self.gas, - self.stopping_counter, self.CP.carFingerprint)) - else: - apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0) - apply_brake = int(clip(apply_brake * self.params.NIDEC_BRAKE_MAX, 0, self.params.NIDEC_BRAKE_MAX - 1)) - pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) - - pcm_override = True - can_sends.append(hondacan.create_brake_command(self.packer, self.CAN, apply_brake, pump_on, - pcm_override, pcm_cancel_cmd, fcw_display, - self.CP.carFingerprint, CS.stock_brake)) - self.apply_brake_last = apply_brake - self.brake = apply_brake / self.params.NIDEC_BRAKE_MAX - - # Send dashboard UI commands. - if self.frame % 10 == 0: - hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_control.leadVisible, - hud_control.lanesVisible, fcw_display, acc_alert, steer_required, hud_control.leadDistanceBars) - can_sends.extend(hondacan.create_ui_commands(self.packer, self.CAN, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, CS.acc_hud, CS.lkas_hud)) - - if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint not in HONDA_BOSCH: - self.speed = pcm_speed - self.gas = pcm_accel / self.params.NIDEC_GAS_MAX - - new_actuators = actuators.as_builder() - new_actuators.speed = self.speed - new_actuators.accel = self.accel - new_actuators.gas = self.gas - new_actuators.brake = self.brake - new_actuators.steer = self.last_steer - new_actuators.steerOutputCan = apply_steer - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py deleted file mode 100644 index c98d1a72d3cc153..000000000000000 --- a/selfdrive/car/honda/carstate.py +++ /dev/null @@ -1,297 +0,0 @@ -from collections import defaultdict - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import interp -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.honda.hondacan import CanBus, get_cruise_speed_conversion -from openpilot.selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, \ - HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS, \ - HondaFlags -from openpilot.selfdrive.car.interfaces import CarStateBase - -TransmissionType = car.CarParams.TransmissionType - - -def get_can_messages(CP, gearbox_msg): - messages = [ - ("ENGINE_DATA", 100), - ("WHEEL_SPEEDS", 50), - ("STEERING_SENSORS", 100), - ("SEATBELT_STATUS", 10), - ("CRUISE", 10), - ("POWERTRAIN_DATA", 100), - ("CAR_SPEED", 10), - ("VSA_STATUS", 50), - ("STEER_STATUS", 100), - ("STEER_MOTOR_TORQUE", 0), # TODO: not on every car - ] - - if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: - messages += [ - ("SCM_FEEDBACK", 25), - ("SCM_BUTTONS", 50), - ] - else: - messages += [ - ("SCM_FEEDBACK", 10), - ("SCM_BUTTONS", 25), - ] - - if CP.carFingerprint in (CAR.HONDA_CRV_HYBRID, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E): - messages.append((gearbox_msg, 50)) - else: - messages.append((gearbox_msg, 100)) - - if CP.flags & HondaFlags.BOSCH_ALT_BRAKE: - messages.append(("BRAKE_MODULE", 50)) - - if CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): - messages.append(("EPB_STATUS", 50)) - - if CP.carFingerprint in HONDA_BOSCH: - # these messages are on camera bus on radarless cars - if not CP.openpilotLongitudinalControl and CP.carFingerprint not in HONDA_BOSCH_RADARLESS: - messages += [ - ("ACC_HUD", 10), - ("ACC_CONTROL", 50), - ] - else: # Nidec signals - if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: - messages.append(("CRUISE_PARAMS", 10)) - else: - messages.append(("CRUISE_PARAMS", 50)) - - # TODO: clean this up - if CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, - CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): - pass - elif CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): - pass - else: - messages.append(("DOORS_STATUS", 3)) - - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - messages.append(("CRUISE_FAULT_STATUS", 50)) - elif CP.openpilotLongitudinalControl: - messages.append(("STANDSTILL", 50)) - - return messages - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.gearbox_msg = "GEARBOX" - if CP.carFingerprint == CAR.HONDA_ACCORD and CP.transmissionType == TransmissionType.cvt: - self.gearbox_msg = "GEARBOX_15T" - - self.main_on_sig_msg = "SCM_FEEDBACK" - if CP.carFingerprint in HONDA_NIDEC_ALT_SCM_MESSAGES: - self.main_on_sig_msg = "SCM_BUTTONS" - - self.shifter_values = can_define.dv[self.gearbox_msg]["GEAR_SHIFTER"] - self.steer_status_values = defaultdict(lambda: "UNKNOWN", can_define.dv["STEER_STATUS"]["STEER_STATUS"]) - - self.brake_switch_prev = False - self.brake_switch_active = False - self.cruise_setting = 0 - self.v_cruise_pcm_prev = 0 - - # When available we use cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] to populate vEgoCluster - # However, on cars without a digital speedometer this is not always present (HRV, FIT, CRV 2016, ILX and RDX) - self.dash_speed_seen = False - - def update(self, cp, cp_cam, cp_body): - ret = car.CarState.new_message() - - # car params - v_weight_v = [0., 1.] # don't trust smooth speed at low values to avoid premature zero snapping - v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero - - # update prevs, update must run once per loop - self.prev_cruise_buttons = self.cruise_buttons - self.prev_cruise_setting = self.cruise_setting - self.cruise_setting = cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] - self.cruise_buttons = cp.vl["SCM_BUTTONS"]["CRUISE_BUTTONS"] - - # used for car hud message - self.is_metric = not cp.vl["CAR_SPEED"]["IMPERIAL_UNIT"] - - # ******************* parse out can ******************* - # STANDSTILL->WHEELS_MOVING bit can be noisy around zero, so use XMISSION_SPEED - # panda checks if the signal is non-zero - ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 1e-5 - # TODO: find a common signal across all cars - if self.CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, - CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): - ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) - elif self.CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): - ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"]) - else: - ret.doorOpen = any([cp.vl["DOORS_STATUS"]["DOOR_OPEN_FL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_FR"], - cp.vl["DOORS_STATUS"]["DOOR_OPEN_RL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = bool(cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LAMP"] or not cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LATCHED"]) - - steer_status = self.steer_status_values[cp.vl["STEER_STATUS"]["STEER_STATUS"]] - ret.steerFaultPermanent = steer_status not in ("NORMAL", "NO_TORQUE_ALERT_1", "NO_TORQUE_ALERT_2", "LOW_SPEED_LOCKOUT", "TMP_FAULT") - # LOW_SPEED_LOCKOUT is not worth a warning - # NO_TORQUE_ALERT_2 can be caused by bump or steering nudge from driver - ret.steerFaultTemporary = steer_status not in ("NORMAL", "LOW_SPEED_LOCKOUT", "NO_TORQUE_ALERT_2") - - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - ret.accFaulted = bool(cp.vl["CRUISE_FAULT_STATUS"]["CRUISE_FAULT"]) - else: - # On some cars, these two signals are always 1, this flag is masking a bug in release - # FIXME: find and set the ACC faulted signals on more platforms - if self.CP.openpilotLongitudinalControl: - ret.accFaulted = bool(cp.vl["STANDSTILL"]["BRAKE_ERROR_1"] or cp.vl["STANDSTILL"]["BRAKE_ERROR_2"]) - - # Log non-critical stock ACC/LKAS faults if Nidec (camera) - if self.CP.carFingerprint not in HONDA_BOSCH: - ret.carFaultedNonCritical = bool(cp_cam.vl["ACC_HUD"]["ACC_PROBLEM"] or cp_cam.vl["LKAS_HUD"]["LKAS_PROBLEM"]) - - ret.espDisabled = cp.vl["VSA_STATUS"]["ESP_DISABLED"] != 0 - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], - ) - v_wheel = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.0 - - # blend in transmission speed at low speed, since it has more low speed accuracy - v_weight = interp(v_wheel, v_weight_bp, v_weight_v) - ret.vEgoRaw = (1. - v_weight) * cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] * CV.KPH_TO_MS * self.CP.wheelSpeedFactor + v_weight * v_wheel - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - - self.dash_speed_seen = self.dash_speed_seen or cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] > 1e-3 - if self.dash_speed_seen: - conversion = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - ret.vEgoCluster = cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] * conversion - - ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE"] - ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE_RATE"] - - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk( - 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) - ret.brakeHoldActive = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] == 1 - - # TODO: set for all cars - if self.CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): - ret.parkingBrake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0 - - gear = int(cp.vl[self.gearbox_msg]["GEAR_SHIFTER"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear, None)) - - ret.gas = cp.vl["POWERTRAIN_DATA"]["PEDAL_GAS"] - ret.gasPressed = ret.gas > 1e-5 - - ret.steeringTorque = cp.vl["STEER_STATUS"]["STEER_TORQUE_SENSOR"] - ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]["MOTOR_TORQUE"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD.get(self.CP.carFingerprint, 1200) - - if self.CP.carFingerprint in HONDA_BOSCH: - # The PCM always manages its own cruise control state, but doesn't publish it - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - ret.cruiseState.nonAdaptive = cp_cam.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"] != 0 - - if not self.CP.openpilotLongitudinalControl: - # ACC_HUD is on camera bus on radarless cars - acc_hud = cp_cam.vl["ACC_HUD"] if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS else cp.vl["ACC_HUD"] - ret.cruiseState.nonAdaptive = acc_hud["CRUISE_CONTROL_LABEL"] != 0 - ret.cruiseState.standstill = acc_hud["CRUISE_SPEED"] == 252. - - conversion = get_cruise_speed_conversion(self.CP.carFingerprint, self.is_metric) - # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. - ret.cruiseState.speed = self.v_cruise_pcm_prev if acc_hud["CRUISE_SPEED"] > 160.0 else acc_hud["CRUISE_SPEED"] * conversion - self.v_cruise_pcm_prev = ret.cruiseState.speed - else: - ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS - - if self.CP.flags & HondaFlags.BOSCH_ALT_BRAKE: - ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 - else: - # brake switch has shown some single time step noise, so only considered when - # switch is on for at least 2 consecutive CAN samples - # brake switch rises earlier than brake pressed but is never 1 when in park - brake_switch_vals = cp.vl_all["POWERTRAIN_DATA"]["BRAKE_SWITCH"] - if len(brake_switch_vals): - brake_switch = cp.vl["POWERTRAIN_DATA"]["BRAKE_SWITCH"] != 0 - if len(brake_switch_vals) > 1: - self.brake_switch_prev = brake_switch_vals[-2] != 0 - self.brake_switch_active = brake_switch and self.brake_switch_prev - self.brake_switch_prev = brake_switch - ret.brakePressed = (cp.vl["POWERTRAIN_DATA"]["BRAKE_PRESSED"] != 0) or self.brake_switch_active - - ret.brake = cp.vl["VSA_STATUS"]["USER_BRAKE"] - ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0 - ret.cruiseState.available = bool(cp.vl[self.main_on_sig_msg]["MAIN_ON"]) - - # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models - if self.CP.carFingerprint in (CAR.HONDA_PILOT, CAR.HONDA_RIDGELINE): - if ret.brake > 0.1: - ret.brakePressed = True - - if self.CP.carFingerprint in HONDA_BOSCH: - # TODO: find the radarless AEB_STATUS bit and make sure ACCEL_COMMAND is correct to enable AEB alerts - if self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: - ret.stockAeb = (not self.CP.openpilotLongitudinalControl) and bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) - else: - ret.stockAeb = bool(cp_cam.vl["BRAKE_COMMAND"]["AEB_REQ_1"] and cp_cam.vl["BRAKE_COMMAND"]["COMPUTER_BRAKE"] > 1e-5) - - self.acc_hud = False - self.lkas_hud = False - if self.CP.carFingerprint not in HONDA_BOSCH: - ret.stockFcw = cp_cam.vl["BRAKE_COMMAND"]["FCW"] != 0 - self.acc_hud = cp_cam.vl["ACC_HUD"] - self.stock_brake = cp_cam.vl["BRAKE_COMMAND"] - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - self.lkas_hud = cp_cam.vl["LKAS_HUD"] - - if self.CP.enableBsm: - # BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0 - # more info here: https://github.com/commaai/openpilot/pull/1867 - ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]["BSM_ALERT"] == 1 - ret.rightBlindspot = cp_body.vl["BSM_STATUS_RIGHT"]["BSM_ALERT"] == 1 - - return ret - - def get_can_parser(self, CP): - messages = get_can_messages(CP, self.gearbox_msg) - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).pt) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - ("STEERING_CONTROL", 100), - ] - - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - messages += [ - ("ACC_HUD", 10), - ("LKAS_HUD", 10), - ] - - elif CP.carFingerprint not in HONDA_BOSCH: - messages += [ - ("ACC_HUD", 10), - ("LKAS_HUD", 10), - ("BRAKE_COMMAND", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) - - @staticmethod - def get_body_can_parser(CP): - if CP.enableBsm: - messages = [ - ("BSM_STATUS_LEFT", 3), - ("BSM_STATUS_RIGHT", 3), - ] - bus_body = CanBus(CP).radar # B-CAN is forwarded to ACC-CAN radar side (CAN 0 on fake ethernet port) - return CANParser(DBC[CP.carFingerprint]["body"], messages, bus_body) - return None diff --git a/selfdrive/car/honda/fingerprints.py b/selfdrive/car/honda/fingerprints.py deleted file mode 100644 index 8a5b79b41e39d96..000000000000000 --- a/selfdrive/car/honda/fingerprints.py +++ /dev/null @@ -1,895 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.honda.values import CAR - -Ecu = car.CarParams.Ecu - -# Modified FW can be identified by the second dash being replaced by a comma -# For example: `b'39990-TVA,A150\x00\x00'` -# -# TODO: vsa is "essential" for fpv2 but doesn't appear on some CAR.FREED models - - -FW_VERSIONS = { - CAR.HONDA_ACCORD: { - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TVC-A910\x00\x00', - b'54008-TWA-A910\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-6A7-A220\x00\x00', - b'28101-6A7-A230\x00\x00', - b'28101-6A7-A320\x00\x00', - b'28101-6A7-A330\x00\x00', - b'28101-6A7-A410\x00\x00', - b'28101-6A7-A510\x00\x00', - b'28101-6A7-A610\x00\x00', - b'28101-6A7-A710\x00\x00', - b'28101-6A9-H140\x00\x00', - b'28101-6A9-H420\x00\x00', - b'28102-6B8-A560\x00\x00', - b'28102-6B8-A570\x00\x00', - b'28102-6B8-A700\x00\x00', - b'28102-6B8-A800\x00\x00', - b'28102-6B8-C560\x00\x00', - b'28102-6B8-C570\x00\x00', - b'28102-6B8-M520\x00\x00', - b'28102-6B8-R700\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TVA-A050\x00\x00', - b'46114-TVA-A060\x00\x00', - b'46114-TVA-A080\x00\x00', - b'46114-TVA-A120\x00\x00', - b'46114-TVA-A320\x00\x00', - b'46114-TVE-H550\x00\x00', - b'46114-TVE-H560\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TVA-B040\x00\x00', - b'57114-TVA-B050\x00\x00', - b'57114-TVA-B060\x00\x00', - b'57114-TVA-B530\x00\x00', - b'57114-TVA-C040\x00\x00', - b'57114-TVA-C050\x00\x00', - b'57114-TVA-C060\x00\x00', - b'57114-TVA-C530\x00\x00', - b'57114-TVA-E520\x00\x00', - b'57114-TVE-H250\x00\x00', - b'57114-TWA-A040\x00\x00', - b'57114-TWA-A050\x00\x00', - b'57114-TWA-A530\x00\x00', - b'57114-TWA-B520\x00\x00', - b'57114-TWA-C510\x00\x00', - b'57114-TWB-H030\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBX-H120\x00\x00', - b'39990-TVA,A150\x00\x00', - b'39990-TVA-A140\x00\x00', - b'39990-TVA-A150\x00\x00', - b'39990-TVA-A160\x00\x00', - b'39990-TVA-A340\x00\x00', - b'39990-TVA-X030\x00\x00', - b'39990-TVA-X040\x00\x00', - b'39990-TVE-H130\x00\x00', - b'39990-TWB-H120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBX-H230\x00\x00', - b'77959-TVA-A460\x00\x00', - b'77959-TVA-F330\x00\x00', - b'77959-TVA-H230\x00\x00', - b'77959-TVA-L420\x00\x00', - b'77959-TVA-X330\x00\x00', - b'77959-TWA-A440\x00\x00', - b'77959-TWA-L420\x00\x00', - b'77959-TWB-H220\x00\x00', - ], - (Ecu.hud, 0x18da61f1, None): [ - b'78209-TVA-A010\x00\x00', - b'78209-TVA-A110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TBX-H140\x00\x00', - b'36802-TVA-A150\x00\x00', - b'36802-TVA-A160\x00\x00', - b'36802-TVA-A170\x00\x00', - b'36802-TVA-A180\x00\x00', - b'36802-TVA-A330\x00\x00', - b'36802-TVC-A330\x00\x00', - b'36802-TVE-H070\x00\x00', - b'36802-TWA-A070\x00\x00', - b'36802-TWA-A080\x00\x00', - b'36802-TWA-A210\x00\x00', - b'36802-TWA-A330\x00\x00', - b'36802-TWB-H060\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TBX-H130\x00\x00', - b'36161-TVA-A060\x00\x00', - b'36161-TVA-A330\x00\x00', - b'36161-TVC-A330\x00\x00', - b'36161-TVE-H050\x00\x00', - b'36161-TWA-A070\x00\x00', - b'36161-TWA-A330\x00\x00', - b'36161-TWB-H040\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TVA-A010\x00\x00', - b'38897-TVA-A020\x00\x00', - b'38897-TVA-A230\x00\x00', - b'38897-TVA-A240\x00\x00', - b'38897-TWA-A120\x00\x00', - b'38897-TWD-J020\x00\x00', - ], - }, - CAR.HONDA_CIVIC: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5CG-A040\x00\x00', - b'28101-5CG-A050\x00\x00', - b'28101-5CG-A070\x00\x00', - b'28101-5CG-A080\x00\x00', - b'28101-5CG-A320\x00\x00', - b'28101-5CG-A810\x00\x00', - b'28101-5CG-A820\x00\x00', - b'28101-5DJ-A040\x00\x00', - b'28101-5DJ-A060\x00\x00', - b'28101-5DJ-A510\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TBA-A540\x00\x00', - b'57114-TBA-A550\x00\x00', - b'57114-TBA-A560\x00\x00', - b'57114-TBA-A570\x00\x00', - b'57114-TEA-Q220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBA,A030\x00\x00', - b'39990-TBA-A030\x00\x00', - b'39990-TBG-A030\x00\x00', - b'39990-TEA-T020\x00\x00', - b'39990-TEG-A010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBA-A030\x00\x00', - b'77959-TBA-A040\x00\x00', - b'77959-TBG-A020\x00\x00', - b'77959-TBG-A030\x00\x00', - b'77959-TEA-Q820\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TBA-A020\x00\x00', - b'36161-TBA-A030\x00\x00', - b'36161-TBA-A040\x00\x00', - b'36161-TBC-A020\x00\x00', - b'36161-TBC-A030\x00\x00', - b'36161-TED-Q320\x00\x00', - b'36161-TEG-A010\x00\x00', - b'36161-TEG-A020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A010\x00\x00', - b'38897-TBA-A020\x00\x00', - ], - }, - CAR.HONDA_CIVIC_BOSCH: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5CG-A920\x00\x00', - b'28101-5CG-AB10\x00\x00', - b'28101-5CG-C110\x00\x00', - b'28101-5CG-C220\x00\x00', - b'28101-5CG-C320\x00\x00', - b'28101-5CG-G020\x00\x00', - b'28101-5CG-L020\x00\x00', - b'28101-5CK-A130\x00\x00', - b'28101-5CK-A140\x00\x00', - b'28101-5CK-A150\x00\x00', - b'28101-5CK-C130\x00\x00', - b'28101-5CK-C140\x00\x00', - b'28101-5CK-C150\x00\x00', - b'28101-5CK-G210\x00\x00', - b'28101-5CK-J710\x00\x00', - b'28101-5CK-Q610\x00\x00', - b'28101-5DJ-A610\x00\x00', - b'28101-5DJ-A710\x00\x00', - b'28101-5DV-E330\x00\x00', - b'28101-5DV-E610\x00\x00', - b'28101-5DV-E820\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TBG-A330\x00\x00', - b'57114-TBG-A340\x00\x00', - b'57114-TBG-A350\x00\x00', - b'57114-TGG-A340\x00\x00', - b'57114-TGG-C320\x00\x00', - b'57114-TGG-G320\x00\x00', - b'57114-TGG-L320\x00\x00', - b'57114-TGG-L330\x00\x00', - b'57114-TGH-L130\x00\x00', - b'57114-TGK-T320\x00\x00', - b'57114-TGL-G330\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBA-C020\x00\x00', - b'39990-TBA-C120\x00\x00', - b'39990-TEA-T820\x00\x00', - b'39990-TEZ-T020\x00\x00', - b'39990-TGG,A020\x00\x00', - b'39990-TGG,A120\x00\x00', - b'39990-TGG-A020\x00\x00', - b'39990-TGG-A120\x00\x00', - b'39990-TGG-J510\x00\x00', - b'39990-TGH-J530\x00\x00', - b'39990-TGL-E130\x00\x00', - b'39990-TGN-E120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBA-A060\x00\x00', - b'77959-TBG-A050\x00\x00', - b'77959-TEA-G020\x00\x00', - b'77959-TGG-A020\x00\x00', - b'77959-TGG-A030\x00\x00', - b'77959-TGG-E010\x00\x00', - b'77959-TGG-G010\x00\x00', - b'77959-TGG-G110\x00\x00', - b'77959-TGG-J320\x00\x00', - b'77959-TGG-Z820\x00\x00', - b'77959-TGH-J110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TBA-A150\x00\x00', - b'36802-TBA-A160\x00\x00', - b'36802-TFJ-G060\x00\x00', - b'36802-TGG-A050\x00\x00', - b'36802-TGG-A060\x00\x00', - b'36802-TGG-A070\x00\x00', - b'36802-TGG-A130\x00\x00', - b'36802-TGG-G040\x00\x00', - b'36802-TGG-G130\x00\x00', - b'36802-TGH-A140\x00\x00', - b'36802-TGK-Q120\x00\x00', - b'36802-TGL-G040\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TBA-A130\x00\x00', - b'36161-TBA-A140\x00\x00', - b'36161-TFJ-G070\x00\x00', - b'36161-TGG-A060\x00\x00', - b'36161-TGG-A080\x00\x00', - b'36161-TGG-A120\x00\x00', - b'36161-TGG-G050\x00\x00', - b'36161-TGG-G070\x00\x00', - b'36161-TGG-G130\x00\x00', - b'36161-TGG-G140\x00\x00', - b'36161-TGH-A140\x00\x00', - b'36161-TGK-Q120\x00\x00', - b'36161-TGL-G050\x00\x00', - b'36161-TGL-G070\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A020\x00\x00', - b'38897-TBA-A110\x00\x00', - b'38897-TGH-A010\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'39494-TGL-G030\x00\x00', - ], - }, - CAR.HONDA_CIVIC_BOSCH_DIESEL: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-59Y-G220\x00\x00', - b'28101-59Y-G620\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TGN-E320\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TFK-G020\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TFK-G210\x00\x00', - b'77959-TGN-G220\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TFK-G130\x00\x00', - b'36802-TGN-G130\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TGN-E010\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TFK-G130\x00\x00', - b'36161-TGN-G130\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A020\x00\x00', - ], - }, - CAR.HONDA_CRV: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T1W-A230\x00\x00', - b'57114-T1W-A240\x00\x00', - b'57114-TFF-A940\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T0A-A230\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T1W-A830\x00\x00', - b'36161-T1W-C830\x00\x00', - b'36161-T1X-A830\x00\x00', - ], - }, - CAR.HONDA_CRV_5G: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5RG-A020\x00\x00', - b'28101-5RG-A030\x00\x00', - b'28101-5RG-A040\x00\x00', - b'28101-5RG-A120\x00\x00', - b'28101-5RG-A220\x00\x00', - b'28101-5RH-A020\x00\x00', - b'28101-5RH-A030\x00\x00', - b'28101-5RH-A040\x00\x00', - b'28101-5RH-A120\x00\x00', - b'28101-5RH-A220\x00\x00', - b'28101-5RL-Q010\x00\x00', - b'28101-5RM-F010\x00\x00', - b'28101-5RM-K010\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TLA-A040\x00\x00', - b'57114-TLA-A050\x00\x00', - b'57114-TLA-A060\x00\x00', - b'57114-TLB-A830\x00\x00', - b'57114-TMC-Z040\x00\x00', - b'57114-TMC-Z050\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TLA,A040\x00\x00', - b'39990-TLA-A040\x00\x00', - b'39990-TLA-A110\x00\x00', - b'39990-TLA-A220\x00\x00', - b'39990-TME-T030\x00\x00', - b'39990-TME-T120\x00\x00', - b'39990-TMT-T010\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TLA-A040\x00\x00', - b'46114-TLA-A050\x00\x00', - b'46114-TLA-A930\x00\x00', - b'46114-TMC-U020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TLA-A010\x00\x00', - b'38897-TLA-A110\x00\x00', - b'38897-TNY-G010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TLA-A040\x00\x00', - b'36802-TLA-A050\x00\x00', - b'36802-TLA-A060\x00\x00', - b'36802-TLA-A070\x00\x00', - b'36802-TMC-Q040\x00\x00', - b'36802-TMC-Q070\x00\x00', - b'36802-TNY-A030\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TLA-A060\x00\x00', - b'36161-TLA-A070\x00\x00', - b'36161-TLA-A080\x00\x00', - b'36161-TMC-Q020\x00\x00', - b'36161-TMC-Q030\x00\x00', - b'36161-TMC-Q040\x00\x00', - b'36161-TNY-A020\x00\x00', - b'36161-TNY-A030\x00\x00', - b'36161-TNY-A040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TLA-A240\x00\x00', - b'77959-TLA-A250\x00\x00', - b'77959-TLA-A320\x00\x00', - b'77959-TLA-A410\x00\x00', - b'77959-TLA-A420\x00\x00', - b'77959-TLA-Q040\x00\x00', - b'77959-TLA-Z040\x00\x00', - b'77959-TMM-F040\x00\x00', - ], - }, - CAR.HONDA_CRV_EU: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T1V-G920\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T1V-G520\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-T1V-G010\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5LH-E120\x00\x00', - b'28103-5LH-E100\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T1G-G940\x00\x00', - ], - }, - CAR.HONDA_CRV_HYBRID: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TMB-H030\x00\x00', - b'57114-TPA-G020\x00\x00', - b'57114-TPG-A020\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TMA-H020\x00\x00', - b'39990-TPA-G030\x00\x00', - b'39990-TPG-A020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TMA-H110\x00\x00', - b'38897-TPG-A110\x00\x00', - b'38897-TPG-A210\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TMB-H510\x00\x00', - b'54008-TMB-H610\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TMB-H040\x00\x00', - b'36161-TPA-E050\x00\x00', - b'36161-TPG-A030\x00\x00', - b'36161-TPG-A040\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TMB-H040\x00\x00', - b'36802-TPA-E040\x00\x00', - b'36802-TPG-A020\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TLA-C320\x00\x00', - b'77959-TLA-C410\x00\x00', - b'77959-TLA-C420\x00\x00', - b'77959-TLA-G220\x00\x00', - b'77959-TLA-H240\x00\x00', - ], - }, - CAR.HONDA_FIT: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T5R-L020\x00\x00', - b'57114-T5R-L220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T5R-C020\x00\x00', - b'39990-T5R-C030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T5A-J010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T5R-A040\x00\x00', - b'36161-T5R-A240\x00\x00', - b'36161-T5R-A520\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T5R-A230\x00\x00', - ], - }, - CAR.HONDA_FREED: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TDK-J010\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TDK-J050\x00\x00', - b'39990-TDK-N020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TDK-J120\x00\x00', - b'57114-TDK-J330\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TDK-J070\x00\x00', - b'36161-TDK-J080\x00\x00', - b'36161-TDK-J530\x00\x00', - ], - }, - CAR.HONDA_ODYSSEY: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-THR-A010\x00\x00', - b'38897-THR-A020\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-THR-A020\x00\x00', - b'39990-THR-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-THR-A010\x00\x00', - b'77959-THR-A110\x00\x00', - b'77959-THR-X010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-THR-A020\x00\x00', - b'36161-THR-A030\x00\x00', - b'36161-THR-A110\x00\x00', - b'36161-THR-A720\x00\x00', - b'36161-THR-A730\x00\x00', - b'36161-THR-A810\x00\x00', - b'36161-THR-A910\x00\x00', - b'36161-THR-C010\x00\x00', - b'36161-THR-D110\x00\x00', - b'36161-THR-K020\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5NZ-A110\x00\x00', - b'28101-5NZ-A310\x00\x00', - b'28101-5NZ-C310\x00\x00', - b'28102-5MX-A001\x00\x00', - b'28102-5MX-A600\x00\x00', - b'28102-5MX-A610\x00\x00', - b'28102-5MX-A700\x00\x00', - b'28102-5MX-A710\x00\x00', - b'28102-5MX-A900\x00\x00', - b'28102-5MX-A910\x00\x00', - b'28102-5MX-C001\x00\x00', - b'28102-5MX-C910\x00\x00', - b'28102-5MX-D001\x00\x00', - b'28102-5MX-D710\x00\x00', - b'28102-5MX-K610\x00\x00', - b'28103-5NZ-A100\x00\x00', - b'28103-5NZ-A300\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-THR-A040\x00\x00', - b'57114-THR-A110\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-THR-A020\x00\x00', - ], - }, - CAR.HONDA_ODYSSEY_CHN: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T6D-H220\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T6A-J010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T6A-P040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T6A-P110\x00\x00', - ], - }, - CAR.HONDA_PILOT: { - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TG7-A520\x00\x00', - b'54008-TG7-A530\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5EY-A040\x00\x00', - b'28101-5EY-A050\x00\x00', - b'28101-5EY-A100\x00\x00', - b'28101-5EY-A430\x00\x00', - b'28101-5EY-A500\x00\x00', - b'28101-5EZ-A050\x00\x00', - b'28101-5EZ-A060\x00\x00', - b'28101-5EZ-A100\x00\x00', - b'28101-5EZ-A210\x00\x00', - b'28101-5EZ-A330\x00\x00', - b'28101-5EZ-A430\x00\x00', - b'28101-5EZ-A500\x00\x00', - b'28101-5EZ-A600\x00\x00', - b'28101-5EZ-A700\x00\x00', - b'28103-5EY-A110\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TG7-A030\x00\x00', - b'38897-TG7-A040\x00\x00', - b'38897-TG7-A110\x00\x00', - b'38897-TG7-A210\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TG7-A030\x00\x00', - b'39990-TG7-A040\x00\x00', - b'39990-TG7-A060\x00\x00', - b'39990-TG7-A070\x00\x00', - b'39990-TGS-A230\x00\x00', - b'39990-TGS-A320\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TG7-A310\x00\x00', - b'36161-TG7-A520\x00\x00', - b'36161-TG7-A630\x00\x00', - b'36161-TG7-A720\x00\x00', - b'36161-TG7-A820\x00\x00', - b'36161-TG7-A930\x00\x00', - b'36161-TG7-C520\x00\x00', - b'36161-TG7-D520\x00\x00', - b'36161-TG7-D630\x00\x00', - b'36161-TG7-Y630\x00\x00', - b'36161-TG8-A410\x00\x00', - b'36161-TG8-A520\x00\x00', - b'36161-TG8-A630\x00\x00', - b'36161-TG8-A720\x00\x00', - b'36161-TG8-A830\x00\x00', - b'36161-TGS-A030\x00\x00', - b'36161-TGS-A130\x00\x00', - b'36161-TGS-A220\x00\x00', - b'36161-TGS-A320\x00\x00', - b'36161-TGT-A030\x00\x00', - b'36161-TGT-A130\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TG7-A020\x00\x00', - b'77959-TG7-A110\x00\x00', - b'77959-TG7-A210\x00\x00', - b'77959-TG7-Y210\x00\x00', - b'77959-TGS-A010\x00\x00', - b'77959-TGS-A110\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TG7-A130\x00\x00', - b'57114-TG7-A140\x00\x00', - b'57114-TG7-A230\x00\x00', - b'57114-TG7-A240\x00\x00', - b'57114-TG7-A630\x00\x00', - b'57114-TG7-A730\x00\x00', - b'57114-TG8-A140\x00\x00', - b'57114-TG8-A230\x00\x00', - b'57114-TG8-A240\x00\x00', - b'57114-TG8-A630\x00\x00', - b'57114-TG8-A730\x00\x00', - b'57114-TGS-A530\x00\x00', - b'57114-TGT-A530\x00\x00', - ], - }, - CAR.ACURA_RDX: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TX4-A220\x00\x00', - b'57114-TX5-A220\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TX4-A030\x00\x00', - b'36161-TX5-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TX4-B010\x00\x00', - b'77959-TX4-C010\x00\x00', - b'77959-TX4-C020\x00\x00', - ], - }, - CAR.ACURA_RDX_3G: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TJB-A030\x00\x00', - b'57114-TJB-A040\x00\x00', - b'57114-TJB-A120\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TJB-A040\x00\x00', - b'36802-TJB-A050\x00\x00', - b'36802-TJB-A540\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TJB-A040\x00\x00', - b'36161-TJB-A530\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TJB-A520\x00\x00', - b'54008-TJB-A530\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28102-5YK-A610\x00\x00', - b'28102-5YK-A620\x00\x00', - b'28102-5YK-A630\x00\x00', - b'28102-5YK-A700\x00\x00', - b'28102-5YK-A711\x00\x00', - b'28102-5YK-A800\x00\x00', - b'28102-5YL-A620\x00\x00', - b'28102-5YL-A700\x00\x00', - b'28102-5YL-A711\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TJB-A040\x00\x00', - b'77959-TJB-A120\x00\x00', - b'77959-TJB-A210\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TJB-A040\x00\x00', - b'46114-TJB-A050\x00\x00', - b'46114-TJB-A060\x00\x00', - b'46114-TJB-A120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TJB-A040\x00\x00', - b'38897-TJB-A110\x00\x00', - b'38897-TJB-A120\x00\x00', - b'38897-TJB-A220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TJB-A030\x00\x00', - b'39990-TJB-A040\x00\x00', - b'39990-TJB-A070\x00\x00', - b'39990-TJB-A130\x00\x00', - ], - }, - CAR.HONDA_RIDGELINE: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T6Z-A020\x00\x00', - b'39990-T6Z-A030\x00\x00', - b'39990-T6Z-A050\x00\x00', - b'39990-T6Z-A110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T6Z-A020\x00\x00', - b'36161-T6Z-A310\x00\x00', - b'36161-T6Z-A420\x00\x00', - b'36161-T6Z-A520\x00\x00', - b'36161-T6Z-A620\x00\x00', - b'36161-T6Z-A720\x00\x00', - b'36161-TJZ-A120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T6Z-A010\x00\x00', - b'38897-T6Z-A110\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T6Z-A020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T6Z-A120\x00\x00', - b'57114-T6Z-A130\x00\x00', - b'57114-T6Z-A520\x00\x00', - b'57114-T6Z-A610\x00\x00', - b'57114-TJZ-A520\x00\x00', - ], - }, - CAR.HONDA_INSIGHT: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TXM-A040\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TXM-A070\x00\x00', - b'36802-TXM-A080\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TXM-A050\x00\x00', - b'36161-TXM-A060\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TXM-A230\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TXM-A030\x00\x00', - b'57114-TXM-A040\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TWA-A910\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TXM-A020\x00\x00', - ], - }, - CAR.HONDA_HRV: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T7A-A010\x00\x00', - b'38897-T7A-A110\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-THX-A020\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T7A-A040\x00\x00', - b'36161-T7A-A140\x00\x00', - b'36161-T7A-A240\x00\x00', - b'36161-T7A-C440\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T7A-A230\x00\x00', - ], - }, - CAR.HONDA_HRV_3G: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-3M0-G110\x00\x00', - b'39990-3W0-A030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-3M0-M110\x00\x00', - b'38897-3W1-A010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-3M0-K840\x00\x00', - b'77959-3V0-A820\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'8S102-3M6-P030\x00\x00', - b'8S102-3W0-A060\x00\x00', - b'8S102-3W0-AB10\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-3M6-M010\x00\x00', - b'57114-3W0-A040\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-6EH-A010\x00\x00', - b'28101-6JC-M310\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-3W0-A020\x00\x00', - ], - }, - CAR.ACURA_ILX: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TX6-A010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TV9-A140\x00\x00', - b'36161-TX6-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TX6-A230\x00\x00', - b'77959-TX6-C210\x00\x00', - ], - }, - CAR.HONDA_E: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TYF-N030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TYF-E140\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TYF-E010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TYF-G430\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TYF-E030\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TYF-E020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TYF-E030\x00\x00', - ], - }, - CAR.HONDA_CIVIC_2022: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T24-T120\x00\x00', - b'39990-T39-A130\x00\x00', - b'39990-T43-J020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T20-A020\x00\x00', - b'38897-T20-A210\x00\x00', - b'38897-T20-A310\x00\x00', - b'38897-T20-A510\x00\x00', - b'38897-T21-A010\x00\x00', - b'38897-T24-Z120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T20-A970\x00\x00', - b'77959-T20-A980\x00\x00', - b'77959-T20-M820\x00\x00', - b'77959-T47-A940\x00\x00', - b'77959-T47-A950\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T20-A060\x00\x00', - b'36161-T20-A070\x00\x00', - b'36161-T20-A080\x00\x00', - b'36161-T24-T070\x00\x00', - b'36161-T47-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', - ], - }, -} diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py deleted file mode 100755 index 2026c385c24a7c1..000000000000000 --- a/selfdrive/car/honda/interface.py +++ /dev/null @@ -1,259 +0,0 @@ -#!/usr/bin/env python3 -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 CanBus -from openpilot.selfdrive.car.honda.values import CarControllerParams, CruiseButtons, CruiseSettings, HondaFlags, CAR, HONDA_BOSCH, \ - HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.disable_ecu import disable_ecu - - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -TransmissionType = car.CarParams.TransmissionType -BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, - CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} -SETTINGS_BUTTONS_DICT = {CruiseSettings.DISTANCE: ButtonType.gapAdjustCruise, CruiseSettings.LKAS: ButtonType.altButton1} - - -class CarInterface(CarInterfaceBase): - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - if CP.carFingerprint in HONDA_BOSCH: - return CarControllerParams.BOSCH_ACCEL_MIN, CarControllerParams.BOSCH_ACCEL_MAX - else: - # NIDECs don't allow acceleration near cruise_speed, - # so limit limits of pid to prevent windup - ACCEL_MAX_VALS = [CarControllerParams.NIDEC_ACCEL_MAX, 0.2] - ACCEL_MAX_BP = [cruise_speed - 2., cruise_speed - .2] - return CarControllerParams.NIDEC_ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "honda" - - CAN = CanBus(ret, fingerprint) - - if candidate in HONDA_BOSCH: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaBosch)] - ret.radarUnavailable = True - # Disable the radar and let openpilot control longitudinal - # WARNING: THIS DISABLES AEB! - # If Bosch radarless, this blocks ACC messages from the camera - ret.experimentalLongitudinalAvailable = True - ret.openpilotLongitudinalControl = experimental_long - ret.pcmCruise = not ret.openpilotLongitudinalControl - else: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaNidec)] - ret.openpilotLongitudinalControl = True - - ret.pcmCruise = True - - if candidate == CAR.HONDA_CRV_5G: - ret.enableBsm = 0x12f8bfa7 in fingerprint[CAN.radar] - - # Detect Bosch cars with new HUD msgs - if any(0x33DA in f for f in fingerprint.values()): - ret.flags |= HondaFlags.BOSCH_EXT_HUD.value - - # Accord ICE 1.5T CVT has different gearbox message - if candidate == CAR.HONDA_ACCORD and 0x191 in fingerprint[CAN.pt]: - ret.transmissionType = TransmissionType.cvt - - # Certain Hondas have an extra steering sensor at the bottom of the steering rack, - # which improves controls quality as it removes the steering column torsion from feedback. - # Tire stiffness factor fictitiously lower if it includes the steering column torsion effect. - # For modeling details, see p.198-200 in "The Science of Vehicle Dynamics (2014), M. Guiggiani" - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0], [0]] - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward - - if candidate in HONDA_BOSCH: - ret.longitudinalTuning.kpV = [0.25] - ret.longitudinalTuning.kiV = [0.05] - ret.longitudinalActuatorDelayUpperBound = 0.5 # s - if candidate in HONDA_BOSCH_RADARLESS: - ret.stopAccel = CarControllerParams.BOSCH_ACCEL_MIN # stock uses -4.0 m/s^2 once stopped but limited by safety model - else: - # default longitudinal tuning for all hondas - ret.longitudinalTuning.kpBP = [0., 5., 35.] - ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5] - ret.longitudinalTuning.kiBP = [0., 35.] - ret.longitudinalTuning.kiV = [0.18, 0.12] - - eps_modified = False - for fw in car_fw: - if fw.ecu == "eps" and b"," in fw.fwVersion: - eps_modified = True - - if candidate == CAR.HONDA_CIVIC: - if eps_modified: - # stock request input values: 0x0000, 0x00DE, 0x014D, 0x01EF, 0x0290, 0x0377, 0x0454, 0x0610, 0x06EE - # stock request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x1680, 0x1680 - # modified request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x2880, 0x3180 - # stock filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108 - # modified filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0400, 0x0480 - # note: max request allowed is 4096, but request is capped at 3840 in firmware, so modifications result in 2x max - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 8000], [0, 2560, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.1]] - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] - - elif candidate in (CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CIVIC_2022): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate == CAR.HONDA_ACCORD: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - - if eps_modified: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] - else: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - - elif candidate == CAR.ACURA_ILX: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate in (CAR.HONDA_CRV, CAR.HONDA_CRV_EU): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_CRV_5G: - if eps_modified: - # stock request input values: 0x0000, 0x00DB, 0x01BB, 0x0296, 0x0377, 0x0454, 0x0532, 0x0610, 0x067F - # stock request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x129A, 0x134D, 0x1400 - # modified request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x1ACD, 0x239A, 0x2800 - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 10000], [0, 2560, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_CRV_HYBRID: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_FIT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] - - elif candidate == CAR.HONDA_FREED: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] - - elif candidate in (CAR.HONDA_HRV, CAR.HONDA_HRV_3G): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] - if candidate == CAR.HONDA_HRV: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.025]] - ret.wheelSpeedFactor = 1.025 - else: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] # TODO: can probably use some tuning - - elif candidate == CAR.ACURA_RDX: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate == CAR.ACURA_RDX_3G: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] - - elif candidate in (CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN): - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] - if candidate == CAR.HONDA_ODYSSEY_CHN: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - - elif candidate == CAR.HONDA_PILOT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - - elif candidate == CAR.HONDA_RIDGELINE: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - - elif candidate == CAR.HONDA_INSIGHT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - - elif candidate == CAR.HONDA_E: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] # TODO: can probably use some tuning - - else: - raise ValueError(f"unsupported car {candidate}") - - # These cars use alternate user brake msg (0x1BE) - # TODO: Only detect feature for Accord/Accord Hybrid, not all Bosch DBCs have BRAKE_MODULE - if 0x1BE in fingerprint[CAN.pt] and candidate in (CAR.HONDA_ACCORD, CAR.HONDA_HRV_3G): - ret.flags |= HondaFlags.BOSCH_ALT_BRAKE.value - - if ret.flags & HondaFlags.BOSCH_ALT_BRAKE: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_ALT_BRAKE - - # These cars use alternate SCM messages (SCM_FEEDBACK AND SCM_BUTTON) - if candidate in HONDA_NIDEC_ALT_SCM_MESSAGES: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_NIDEC_ALT - - if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_BOSCH_LONG - - if candidate in HONDA_BOSCH_RADARLESS: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_RADARLESS - - # min speed to enable ACC. if car can do stop and go, then set enabling speed - # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not - # conflict with PCM acc - ret.autoResumeSng = candidate in (HONDA_BOSCH | {CAR.HONDA_CIVIC}) - ret.minEnableSpeed = -1. if ret.autoResumeSng else 25.5 * CV.MPH_TO_MS - - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.8 - - return ret - - @staticmethod - def init(CP, logcan, sendcan): - if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl: - disable_ecu(logcan, sendcan, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03') - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) - - ret.buttonEvents = [ - *create_button_events(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT), - *create_button_events(self.CS.cruise_setting, self.CS.prev_cruise_setting, SETTINGS_BUTTONS_DICT), - ] - - # events - events = self.create_common_events(ret, pcm_enable=False) - if self.CP.pcmCruise and ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.belowEngageSpeed) - - if self.CP.pcmCruise: - # we engage when pcm is active (rising edge) - if ret.cruiseState.enabled and not self.CS.out.cruiseState.enabled: - events.add(EventName.pcmEnable) - elif not ret.cruiseState.enabled and (c.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl): - # it can happen that car cruise disables while comma system is enabled: need to - # keep braking if needed or if the speed is very low - if ret.vEgo < self.CP.minEnableSpeed + 2.: - # non loud alert if cruise disables below 25mph as expected (+ a little margin) - events.add(EventName.speedTooLow) - else: - events.add(EventName.cruiseDisabled) - if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: - events.add(EventName.manualRestart) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py deleted file mode 100755 index 8090f8e03e77351..000000000000000 --- a/selfdrive/car/honda/radar_interface.py +++ /dev/null @@ -1,84 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.honda.values import DBC - - -def _create_nidec_can_parser(car_fingerprint): - radar_messages = [0x400] + list(range(0x430, 0x43A)) + list(range(0x440, 0x446)) - messages = [(m, 20) for m in radar_messages] - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.track_id = 0 - self.radar_fault = False - self.radar_wrong_config = False - self.radar_off_can = CP.radarUnavailable - self.radar_ts = CP.radarTimeStep - - self.delay = int(round(0.1 / CP.radarTimeStep)) # 0.1s delay of radar - - # Nidec - if self.radar_off_can: - self.rcp = None - else: - self.rcp = _create_nidec_can_parser(CP.carFingerprint) - self.trigger_msg = 0x445 - self.updated_messages = set() - - def update(self, can_strings): - # in Bosch radar and we are only steering for now, so sleep 0.05s to keep - # radard at 20Hz and return no points - if self.radar_off_can: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - - for ii in sorted(updated_messages): - cpt = self.rcp.vl[ii] - if ii == 0x400: - # check for radar faults - self.radar_fault = cpt['RADAR_STATE'] != 0x79 - self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 - elif cpt['LONG_DIST'] < 255: - if ii not in self.pts or cpt['NEW_TRACK']: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = True - else: - if ii in self.pts: - del self.pts[ii] - - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - if self.radar_fault: - errors.append("fault") - if self.radar_wrong_config: - errors.append("wrongConfig") - ret.errors = errors - - ret.points = list(self.pts.values()) - - return ret diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py deleted file mode 100644 index c3005c667c822ee..000000000000000 --- a/selfdrive/car/honda/values.py +++ /dev/null @@ -1,331 +0,0 @@ -from dataclasses import dataclass -from enum import Enum, IntFlag - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarControllerParams: - # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we - # perform the closed loop control, and might need some - # to apply some more braking if we're on a downhill slope. - # Our controller should still keep the 2 second average above - # -3.5 m/s^2 as per planner limits - NIDEC_ACCEL_MIN = -4.0 # m/s^2 - NIDEC_ACCEL_MAX = 1.6 # m/s^2, lower than 2.0 m/s^2 for tuning reasons - - NIDEC_ACCEL_LOOKUP_BP = [-1., 0., .6] - NIDEC_ACCEL_LOOKUP_V = [-4.8, 0., 2.0] - - NIDEC_MAX_ACCEL_V = [0.5, 2.4, 1.4, 0.6] - NIDEC_MAX_ACCEL_BP = [0.0, 4.0, 10., 20.] - - NIDEC_GAS_MAX = 198 # 0xc6 - NIDEC_BRAKE_MAX = 1024 // 4 - - BOSCH_ACCEL_MIN = -3.5 # m/s^2 - BOSCH_ACCEL_MAX = 2.0 # m/s^2 - - BOSCH_GAS_LOOKUP_BP = [-0.2, 2.0] # 2m/s^2 - BOSCH_GAS_LOOKUP_V = [0, 1600] - - def __init__(self, CP): - self.STEER_MAX = CP.lateralParams.torqueBP[-1] - # mirror of list (assuming first item is zero) for interp of signed request values - assert(CP.lateralParams.torqueBP[0] == 0) - assert(CP.lateralParams.torqueBP[0] == 0) - self.STEER_LOOKUP_BP = [v * -1 for v in CP.lateralParams.torqueBP][1:][::-1] + list(CP.lateralParams.torqueBP) - self.STEER_LOOKUP_V = [v * -1 for v in CP.lateralParams.torqueV][1:][::-1] + list(CP.lateralParams.torqueV) - - -class HondaFlags(IntFlag): - # Detected flags - # Bosch models with alternate set of LKAS_HUD messages - BOSCH_EXT_HUD = 1 - BOSCH_ALT_BRAKE = 2 - - # Static flags - BOSCH = 4 - BOSCH_RADARLESS = 8 - - NIDEC = 16 - NIDEC_ALT_PCM_ACCEL = 32 - NIDEC_ALT_SCM_MESSAGES = 64 - - -# Car button codes -class CruiseButtons: - RES_ACCEL = 4 - DECEL_SET = 3 - CANCEL = 2 - MAIN = 1 - - -class CruiseSettings: - DISTANCE = 3 - LKAS = 1 - - -# See dbc files for info on values -VISUAL_HUD = { - VisualAlert.none: 0, - VisualAlert.fcw: 1, - VisualAlert.steerRequired: 1, - VisualAlert.ldw: 1, - VisualAlert.brakePressed: 10, - VisualAlert.wrongGear: 6, - VisualAlert.seatbeltUnbuckled: 5, - VisualAlert.speedTooHigh: 8 -} - - -@dataclass -class HondaCarDocs(CarDocs): - package: str = "Honda Sensing" - - def init_make(self, CP: car.CarParams): - if CP.flags & HondaFlags.BOSCH: - self.car_parts = CarParts.common([CarHarness.bosch_b]) if CP.flags & HondaFlags.BOSCH_RADARLESS else CarParts.common([CarHarness.bosch_a]) - else: - self.car_parts = CarParts.common([CarHarness.nidec]) - - -class Footnote(Enum): - CIVIC_DIESEL = CarFootnote( - "2019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.", - Column.FSR_STEERING) - - -class HondaBoschPlatformConfig(PlatformConfig): - def init(self): - self.flags |= HondaFlags.BOSCH - - -class HondaNidecPlatformConfig(PlatformConfig): - def init(self): - self.flags |= HondaFlags.NIDEC - - -class CAR(Platforms): - # Bosch Cars - HONDA_ACCORD = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), - HondaCarDocs("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), - HondaCarDocs("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), - ], - # steerRatio: 11.82 is spec end-to-end - CarSpecs(mass=3279 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=16.33, centerToFrontRatio=0.39, tireStiffnessFactor=0.8467), - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_CIVIC_BOSCH = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Civic 2019-21", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", - footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), - HondaCarDocs("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS), - ], - CarSpecs(mass=1326, wheelbase=2.7, steerRatio=15.38, centerToFrontRatio=0.4), # steerRatio: 10.93 is end-to-end spec - dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), - ) - HONDA_CIVIC_BOSCH_DIESEL = HondaBoschPlatformConfig( - [], # don't show in docs - HONDA_CIVIC_BOSCH.specs, - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_CIVIC_2022 = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Civic 2022-23", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), - HondaCarDocs("Honda Civic Hatchback 2022-23", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), - ], - HONDA_CIVIC_BOSCH.specs, - dbc_dict('honda_civic_ex_2022_can_generated', None), - flags=HondaFlags.BOSCH_RADARLESS, - ) - HONDA_CRV_5G = HondaBoschPlatformConfig( - [HondaCarDocs("Honda CR-V 2017-22", min_steer_speed=12. * CV.MPH_TO_MS)], - # steerRatio: 12.3 is spec end-to-end - CarSpecs(mass=3410 * CV.LB_TO_KG, wheelbase=2.66, steerRatio=16.0, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), - dbc_dict('honda_crv_ex_2017_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), - flags=HondaFlags.BOSCH_ALT_BRAKE, - ) - HONDA_CRV_HYBRID = HondaBoschPlatformConfig( - [HondaCarDocs("Honda CR-V Hybrid 2017-21", min_steer_speed=12. * CV.MPH_TO_MS)], - # mass: mean of 4 models in kg, steerRatio: 12.3 is spec end-to-end - CarSpecs(mass=1667, wheelbase=2.66, steerRatio=16, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_HRV_3G = HondaBoschPlatformConfig( - [HondaCarDocs("Honda HR-V 2023", "All")], - CarSpecs(mass=3125 * CV.LB_TO_KG, wheelbase=2.61, steerRatio=15.2, centerToFrontRatio=0.41, tireStiffnessFactor=0.5), - dbc_dict('honda_civic_ex_2022_can_generated', None), - flags=HondaFlags.BOSCH_RADARLESS, - ) - ACURA_RDX_3G = HondaBoschPlatformConfig( - [HondaCarDocs("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=4068 * CV.LB_TO_KG, wheelbase=2.75, steerRatio=11.95, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), # as spec - dbc_dict('acura_rdx_2020_can_generated', None), - flags=HondaFlags.BOSCH_ALT_BRAKE, - ) - HONDA_INSIGHT = HondaBoschPlatformConfig( - [HondaCarDocs("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=2987 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.0, centerToFrontRatio=0.39, tireStiffnessFactor=0.82), # as spec - dbc_dict('honda_insight_ex_2019_can_generated', None), - ) - HONDA_E = HondaBoschPlatformConfig( - [HondaCarDocs("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=3338.8 * CV.LB_TO_KG, wheelbase=2.5, centerToFrontRatio=0.5, steerRatio=16.71, tireStiffnessFactor=0.82), - dbc_dict('acura_rdx_2020_can_generated', None), - ) - - # Nidec Cars - ACURA_ILX = HondaNidecPlatformConfig( - [HondaCarDocs("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS)], - CarSpecs(mass=3095 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=18.61, centerToFrontRatio=0.37, tireStiffnessFactor=0.72), # 15.3 is spec end-to-end - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CRV = HondaNidecPlatformConfig( - [HondaCarDocs("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3572 * CV.LB_TO_KG, wheelbase=2.62, steerRatio=16.89, centerToFrontRatio=0.41, tireStiffnessFactor=0.444), # as spec - dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CRV_EU = HondaNidecPlatformConfig( - [], # Euro version of CRV Touring, don't show in docs - HONDA_CRV.specs, - dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_FIT = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Fit 2018-20", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=2644 * CV.LB_TO_KG, wheelbase=2.53, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_FREED = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Freed 2020", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3086. * CV.LB_TO_KG, wheelbase=2.74, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), # mostly copied from FIT - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_HRV = HondaNidecPlatformConfig( - [HondaCarDocs("Honda HR-V 2019-22", min_steer_speed=12. * CV.MPH_TO_MS)], - HONDA_HRV_3G.specs, - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_ODYSSEY = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Odyssey 2018-20")], - CarSpecs(mass=1900, wheelbase=3.0, steerRatio=14.35, centerToFrontRatio=0.41, tireStiffnessFactor=0.82), - dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_PCM_ACCEL, - ) - HONDA_ODYSSEY_CHN = HondaNidecPlatformConfig( - [], # Chinese version of Odyssey, don't show in docs - HONDA_ODYSSEY.specs, - dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - ACURA_RDX = HondaNidecPlatformConfig( - [HondaCarDocs("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3925 * CV.LB_TO_KG, wheelbase=2.68, steerRatio=15.0, centerToFrontRatio=0.38, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_PILOT = HondaNidecPlatformConfig( - [ - HondaCarDocs("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS), - HondaCarDocs("Honda Passport 2019-23", "All", min_steer_speed=12. * CV.MPH_TO_MS), - ], - CarSpecs(mass=4278 * CV.LB_TO_KG, wheelbase=2.86, centerToFrontRatio=0.428, steerRatio=16.0, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_RIDGELINE = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Ridgeline 2017-24", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=4515 * CV.LB_TO_KG, wheelbase=3.18, centerToFrontRatio=0.41, steerRatio=15.59, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CIVIC = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video_link="https://youtu.be/-IkImTe1NYE")], - CarSpecs(mass=1326, wheelbase=2.70, centerToFrontRatio=0.4, steerRatio=15.38), # 10.93 is end-to-end spec - dbc_dict('honda_civic_touring_2016_can_generated', 'acura_ilx_2016_nidec'), - ) - - -HONDA_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xF112) -HONDA_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xF112) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # Currently used to fingerprint - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=1, - ), - - # Data collection requests: - # Log manufacturer-specific identifier for current ECUs - Request( - [HONDA_ALT_VERSION_REQUEST], - [HONDA_ALT_VERSION_RESPONSE], - bus=1, - logging=True, - ), - # Nidec PT bus - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=0, - ), - # Bosch PT bus - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=1, - obd_multiplexing=False, - ), - ], - # We lose these ECUs without the comma power on these cars. - # Note that we still attempt to match with them when they are present - # This is or'd with (ALL_ECUS - ESSENTIAL_ECUS) from fw_versions.py - non_essential_ecus={ - Ecu.eps: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_2022, CAR.HONDA_E, CAR.HONDA_HRV_3G], - Ecu.vsa: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_2022, CAR.HONDA_CRV_5G, CAR.HONDA_CRV_HYBRID, - CAR.HONDA_E, CAR.HONDA_HRV_3G, CAR.HONDA_INSIGHT], - }, - extra_ecus=[ - (Ecu.combinationMeter, 0x18da60f1, None), - (Ecu.programmedFuelInjection, 0x18da10f1, None), - # The only other ECU on PT bus accessible by camera on radarless Civic - # This is likely a manufacturer-specific sub-address implementation: the camera responds to this and 0x18dab0f1 - # Unclear what the part number refers to: 8S103 is 'Camera Set Mono', while 36160 is 'Camera Monocular - Honda' - # TODO: add query back, camera does not support querying both in parallel and 0x18dab0f1 often fails to respond - # (Ecu.unknown, 0x18DAB3F1, None), - ], -) - -STEER_THRESHOLD = { - # default is 1200, overrides go here - CAR.ACURA_RDX: 400, - CAR.HONDA_CRV_EU: 400, -} - -HONDA_NIDEC_ALT_PCM_ACCEL = CAR.with_flags(HondaFlags.NIDEC_ALT_PCM_ACCEL) -HONDA_NIDEC_ALT_SCM_MESSAGES = CAR.with_flags(HondaFlags.NIDEC_ALT_SCM_MESSAGES) -HONDA_BOSCH = CAR.with_flags(HondaFlags.BOSCH) -HONDA_BOSCH_RADARLESS = CAR.with_flags(HondaFlags.BOSCH_RADARLESS) - - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py deleted file mode 100644 index 4038ddcca9088b1..000000000000000 --- a/selfdrive/car/hyundai/carcontroller.py +++ /dev/null @@ -1,208 +0,0 @@ -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import clip -from openpilot.common.realtime import DT_CTRL -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance -from openpilot.selfdrive.car.hyundai import hyundaicanfd, hyundaican -from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR -from openpilot.selfdrive.car.interfaces import CarControllerBase - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - -# EPS faults if you apply torque while the steering angle is above 90 degrees for more than 1 second -# All slightly below EPS thresholds to avoid fault -MAX_ANGLE = 85 -MAX_ANGLE_FRAMES = 89 -MAX_ANGLE_CONSECUTIVE_FRAMES = 2 - - -def process_hud_alert(enabled, fingerprint, hud_control): - sys_warning = (hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)) - - # initialize to no line visible - # TODO: this is not accurate for all cars - sys_state = 1 - if hud_control.leftLaneVisible and hud_control.rightLaneVisible or sys_warning: # HUD alert only display when LKAS status is active - sys_state = 3 if enabled or sys_warning else 4 - elif hud_control.leftLaneVisible: - sys_state = 5 - elif hud_control.rightLaneVisible: - sys_state = 6 - - # initialize to no warnings - left_lane_warning = 0 - right_lane_warning = 0 - if hud_control.leftLaneDepart: - left_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 - if hud_control.rightLaneDepart: - right_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 - - return sys_warning, sys_state, left_lane_warning, right_lane_warning - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.CAN = CanBus(CP) - self.params = CarControllerParams(CP) - self.packer = CANPacker(dbc_name) - self.angle_limit_counter = 0 - self.frame = 0 - - self.accel_last = 0 - self.apply_steer_last = 0 - self.car_fingerprint = CP.carFingerprint - self.last_button_frame = 0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - - # steering torque - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) - - # >90 degree steering fault prevention - self.angle_limit_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringAngleDeg) >= MAX_ANGLE, CC.latActive, - self.angle_limit_counter, MAX_ANGLE_FRAMES, - MAX_ANGLE_CONSECUTIVE_FRAMES) - - if not CC.latActive: - apply_steer = 0 - - # Hold torque with induced temporary fault when cutting the actuation bit - torque_fault = CC.latActive and not apply_steer_req - - self.apply_steer_last = apply_steer - - # accel + longitudinal - accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) - stopping = actuators.longControlState == LongCtrlState.stopping - set_speed_in_units = hud_control.setSpeed * (CV.MS_TO_KPH if CS.is_metric else CV.MS_TO_MPH) - - # HUD messages - sys_warning, sys_state, left_lane_warning, right_lane_warning = process_hud_alert(CC.enabled, self.car_fingerprint, - hud_control) - - can_sends = [] - - # *** common hyundai stuff *** - - # tester present - w/ no response (keeps relevant ECU disabled) - if self.frame % 100 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and self.CP.openpilotLongitudinalControl: - # for longitudinal control, either radar or ADAS driving ECU - addr, bus = 0x7d0, 0 - if self.CP.flags & HyundaiFlags.CANFD_HDA2.value: - addr, bus = 0x730, self.CAN.ECAN - can_sends.append([addr, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", bus]) - - # for blinkers - if self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: - can_sends.append([0x7b1, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", self.CAN.ECAN]) - - # CAN-FD platforms - if self.CP.carFingerprint in CANFD_CAR: - hda2 = self.CP.flags & HyundaiFlags.CANFD_HDA2 - hda2_long = hda2 and self.CP.openpilotLongitudinalControl - - # steering control - can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.enabled, apply_steer_req, apply_steer)) - - # prevent LFA from activating on HDA2 by sending "no lane lines detected" to ADAS ECU - if self.frame % 5 == 0 and hda2: - can_sends.append(hyundaicanfd.create_suppress_lfa(self.packer, self.CAN, CS.hda2_lfa_block_msg, - self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING)) - - # LFA and HDA icons - if self.frame % 5 == 0 and (not hda2 or hda2_long): - can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CAN, CC.enabled)) - - # blinkers - if hda2 and self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: - can_sends.extend(hyundaicanfd.create_spas_messages(self.packer, self.CAN, self.frame, CC.leftBlinker, CC.rightBlinker)) - - if self.CP.openpilotLongitudinalControl: - if hda2: - can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.CAN, self.frame)) - if self.frame % 2 == 0: - can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CAN, CC.enabled, self.accel_last, accel, stopping, CC.cruiseControl.override, - set_speed_in_units, hud_control)) - self.accel_last = accel - else: - # button presses - can_sends.extend(self.create_button_messages(CC, CS, use_clu11=False)) - else: - can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.CP, apply_steer, apply_steer_req, - torque_fault, CS.lkas11, sys_warning, sys_state, CC.enabled, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, - left_lane_warning, right_lane_warning)) - - if not self.CP.openpilotLongitudinalControl: - can_sends.extend(self.create_button_messages(CC, CS, use_clu11=True)) - - if self.frame % 2 == 0 and self.CP.openpilotLongitudinalControl: - # TODO: unclear if this is needed - jerk = 3.0 if actuators.longControlState == LongCtrlState.pid else 1.0 - use_fca = self.CP.flags & HyundaiFlags.USE_FCA.value - can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2), - hud_control, set_speed_in_units, stopping, - CC.cruiseControl.override, use_fca)) - - # 20 Hz LFA MFA message - if self.frame % 5 == 0 and self.CP.flags & HyundaiFlags.SEND_LFA.value: - can_sends.append(hyundaican.create_lfahda_mfc(self.packer, CC.enabled)) - - # 5 Hz ACC options - if self.frame % 20 == 0 and self.CP.openpilotLongitudinalControl: - can_sends.extend(hyundaican.create_acc_opt(self.packer)) - - # 2 Hz front radar options - if self.frame % 50 == 0 and self.CP.openpilotLongitudinalControl: - can_sends.append(hyundaican.create_frt_radar_opt(self.packer)) - - new_actuators = actuators.as_builder() - new_actuators.steer = apply_steer / self.params.STEER_MAX - new_actuators.steerOutputCan = apply_steer - new_actuators.accel = accel - - self.frame += 1 - return new_actuators, can_sends - - def create_button_messages(self, CC: car.CarControl, CS: car.CarState, use_clu11: bool): - can_sends = [] - if use_clu11: - if CC.cruiseControl.cancel: - can_sends.append(hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.CANCEL, self.CP)) - elif CC.cruiseControl.resume: - # send resume at a max freq of 10Hz - if (self.frame - self.last_button_frame) * DT_CTRL > 0.1: - # send 25 messages at a time to increases the likelihood of resume being accepted - can_sends.extend([hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.RES_ACCEL, self.CP)] * 25) - if (self.frame - self.last_button_frame) * DT_CTRL >= 0.15: - self.last_button_frame = self.frame - else: - if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: - # cruise cancel - if CC.cruiseControl.cancel: - if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - can_sends.append(hyundaicanfd.create_acc_cancel(self.packer, self.CP, self.CAN, CS.cruise_info)) - self.last_button_frame = self.frame - else: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.CANCEL)) - self.last_button_frame = self.frame - - # cruise standstill resume - elif CC.cruiseControl.resume: - if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - # TODO: resume for alt button cars - pass - else: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.RES_ACCEL)) - self.last_button_frame = self.frame - - return can_sends diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py deleted file mode 100644 index 92c489cf34e2573..000000000000000 --- a/selfdrive/car/hyundai/carstate.py +++ /dev/null @@ -1,368 +0,0 @@ -from collections import deque -import copy -import math - -from cereal import car -from openpilot.common.conversions import Conversions as CV -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, Buttons, CarControllerParams -from openpilot.selfdrive.car.interfaces import CarStateBase - -PREV_BUTTON_SAMPLES = 8 -CLUSTER_SAMPLE_RATE = 20 # frames -STANDSTILL_THRESHOLD = 12 * 0.03125 * CV.KPH_TO_MS - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.cruise_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) - self.main_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) - - self.gear_msg_canfd = "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \ - "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \ - "GEAR_SHIFTER" - if CP.carFingerprint in CANFD_CAR: - self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"] - elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] - elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - self.shifter_values = can_define.dv["TCU12"]["CUR_GR"] - else: # preferred and elect gear methods use same definition - self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] - - self.accelerator_msg_canfd = "ACCELERATOR" if CP.flags & HyundaiFlags.EV else \ - "ACCELERATOR_ALT" if CP.flags & HyundaiFlags.HYBRID else \ - "ACCELERATOR_BRAKE_ALT" - self.cruise_btns_msg_canfd = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else \ - "CRUISE_BUTTONS" - self.is_metric = False - self.buttons_counter = 0 - - self.cruise_info = {} - - # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz - self.cluster_speed = 0 - self.cluster_speed_counter = CLUSTER_SAMPLE_RATE - - self.params = CarControllerParams(CP) - - def update(self, cp, cp_cam): - if self.CP.carFingerprint in CANFD_CAR: - return self.update_canfd(cp, cp_cam) - - ret = car.CarState.new_message() - cp_cruise = cp_cam if self.CP.carFingerprint in CAMERA_SCC_CAR else cp - self.is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0 - speed_conv = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - - ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"], - cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]]) - - ret.seatbeltUnlatched = cp.vl["CGW1"]["CF_Gway_DrvSeatBeltSw"] == 0 - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHL_SPD11"]["WHL_SPD_FL"], - cp.vl["WHL_SPD11"]["WHL_SPD_FR"], - cp.vl["WHL_SPD11"]["WHL_SPD_RL"], - cp.vl["WHL_SPD11"]["WHL_SPD_RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - self.cluster_speed_counter += 1 - if self.cluster_speed_counter > CLUSTER_SAMPLE_RATE: - self.cluster_speed = cp.vl["CLU15"]["CF_Clu_VehicleSpeed"] - self.cluster_speed_counter = 0 - - # Mimic how dash converts to imperial. - # Sorento is the only platform where CF_Clu_VehicleSpeed is already imperial when not is_metric - # TODO: CGW_USM1->CF_Gway_DrLockSoundRValue may describe this - if not self.is_metric and self.CP.carFingerprint not in (CAR.KIA_SORENTO,): - self.cluster_speed = math.floor(self.cluster_speed * CV.KPH_TO_MPH + CV.KPH_TO_MPH) - - ret.vEgoCluster = self.cluster_speed * speed_conv - - ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"] - ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"] - ret.yawRate = cp.vl["ESP12"]["YAW_RATE"] - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp( - 50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) - ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"] - ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) - ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0 - - # cruise state - if self.CP.openpilotLongitudinalControl: - # These are not used for engage/disengage since openpilot keeps track of state using the buttons - ret.cruiseState.available = cp.vl["TCS13"]["ACCEnable"] == 0 - ret.cruiseState.enabled = cp.vl["TCS13"]["ACC_REQ"] == 1 - ret.cruiseState.standstill = False - ret.cruiseState.nonAdaptive = False - else: - ret.cruiseState.available = cp_cruise.vl["SCC11"]["MainMode_ACC"] == 1 - ret.cruiseState.enabled = cp_cruise.vl["SCC12"]["ACCMode"] != 0 - ret.cruiseState.standstill = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 4. - ret.cruiseState.nonAdaptive = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 2. # Shows 'Cruise Control' on dash - ret.cruiseState.speed = cp_cruise.vl["SCC11"]["VSetDis"] * speed_conv - - # TODO: Find brake pressure - ret.brake = 0 - ret.brakePressed = cp.vl["TCS13"]["DriverOverride"] == 2 # 2 includes regen braking by user on HEV/EV - ret.brakeHoldActive = cp.vl["TCS15"]["AVH_LAMP"] == 2 # 0 OFF, 1 ERROR, 2 ACTIVE, 3 READY - ret.parkingBrake = cp.vl["TCS13"]["PBRAKE_ACT"] == 1 - ret.espDisabled = cp.vl["TCS11"]["TCS_PAS"] == 1 - ret.accFaulted = cp.vl["TCS13"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED - - if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - if self.CP.flags & HyundaiFlags.HYBRID: - ret.gas = cp.vl["E_EMS11"]["CR_Vcu_AccPedDep_Pos"] / 254. - else: - ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 254. - ret.gasPressed = ret.gas > 0 - else: - ret.gas = cp.vl["EMS12"]["PV_AV_CAN"] / 100. - ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) - - # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, - # as this seems to be standard over all cars, but is not the preferred method. - if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] - elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - gear = cp.vl["CLU15"]["CF_Clu_Gear"] - elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - gear = cp.vl["TCU12"]["CUR_GR"] - else: - gear = cp.vl["LVR12"]["CF_Lvr_Gear"] - - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) - - if not self.CP.openpilotLongitudinalControl: - aeb_src = "FCA11" if self.CP.flags & HyundaiFlags.USE_FCA.value else "SCC12" - aeb_sig = "FCA_CmdAct" if self.CP.flags & HyundaiFlags.USE_FCA.value else "AEB_CmdAct" - aeb_warning = cp_cruise.vl[aeb_src]["CF_VSM_Warn"] != 0 - scc_warning = cp_cruise.vl["SCC12"]["TakeOverReq"] == 1 # sometimes only SCC system shows an FCW - aeb_braking = cp_cruise.vl[aeb_src]["CF_VSM_DecCmdAct"] != 0 or cp_cruise.vl[aeb_src][aeb_sig] != 0 - ret.stockFcw = (aeb_warning or scc_warning) and not aeb_braking - ret.stockAeb = aeb_warning and aeb_braking - - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 - ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 - - # save the entire LKAS11 and CLU11 - self.lkas11 = copy.copy(cp_cam.vl["LKAS11"]) - self.clu11 = copy.copy(cp.vl["CLU11"]) - self.steer_state = cp.vl["MDPS12"]["CF_Mdps_ToiActive"] # 0 NOT ACTIVE, 1 ACTIVE - self.prev_cruise_buttons = self.cruise_buttons[-1] - self.cruise_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwState"]) - self.main_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwMain"]) - - return ret - - def update_canfd(self, cp, cp_cam): - ret = car.CarState.new_message() - - self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1 - speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - - if self.CP.flags & (HyundaiFlags.EV | HyundaiFlags.HYBRID): - offset = 255. if self.CP.flags & HyundaiFlags.EV else 1023. - ret.gas = cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL"] / offset - ret.gasPressed = ret.gas > 1e-5 - else: - ret.gasPressed = bool(cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL_PRESSED"]) - - ret.brakePressed = cp.vl["TCS"]["DriverBraking"] == 1 - - ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR"] == 1 - ret.seatbeltUnlatched = cp.vl["DOORS_SEATBELTS"]["DRIVER_SEATBELT"] == 0 - - gear = cp.vl[self.gear_msg_canfd]["GEAR"] - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) - - # TODO: figure out positions - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_1"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_2"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_3"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_4"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEERING_RATE"] - ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEERING_ANGLE"] * -1 - ret.steeringTorque = cp.vl["MDPS"]["STEERING_COL_TORQUE"] - ret.steeringTorqueEps = cp.vl["MDPS"]["STEERING_OUT_TORQUE"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) - ret.steerFaultTemporary = cp.vl["MDPS"]["LKA_FAULT"] != 0 - - # TODO: alt signal usage may be described by cp.vl['BLINKERS']['USE_ALT_LAMP'] - left_blinker_sig, right_blinker_sig = "LEFT_LAMP", "RIGHT_LAMP" - if self.CP.carFingerprint == CAR.HYUNDAI_KONA_EV_2ND_GEN: - left_blinker_sig, right_blinker_sig = "LEFT_LAMP_ALT", "RIGHT_LAMP_ALT" - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"][left_blinker_sig], - cp.vl["BLINKERS"][right_blinker_sig]) - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0 - ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0 - - # cruise state - # CAN FD cars enable on main button press, set available if no TCS faults preventing engagement - ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0 - if self.CP.openpilotLongitudinalControl: - # These are not used for engage/disengage since openpilot keeps track of state using the buttons - ret.cruiseState.enabled = cp.vl["TCS"]["ACC_REQ"] == 1 - ret.cruiseState.standstill = False - else: - cp_cruise_info = cp_cam if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp - ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2) - ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1 - ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor - self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"]) - - # Manual Speed Limit Assist is a feature that replaces non-adaptive cruise control on EV CAN FD platforms. - # It limits the vehicle speed, overridable by pressing the accelerator past a certain point. - # The car will brake, but does not respect positive acceleration commands in this mode - # TODO: find this message on ICE & HYBRID cars + cruise control signals (if exists) - if self.CP.flags & HyundaiFlags.EV: - ret.cruiseState.nonAdaptive = cp.vl["MANUAL_SPEED_LIMIT_ASSIST"]["MSLA_ENABLED"] == 1 - - self.prev_cruise_buttons = self.cruise_buttons[-1] - self.cruise_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["CRUISE_BUTTONS"]) - self.main_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["ADAPTIVE_CRUISE_MAIN_BTN"]) - self.buttons_counter = cp.vl[self.cruise_btns_msg_canfd]["COUNTER"] - ret.accFaulted = cp.vl["TCS"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED - - if self.CP.flags & HyundaiFlags.CANFD_HDA2: - self.hda2_lfa_block_msg = copy.copy(cp_cam.vl["CAM_0x362"] if self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING - else cp_cam.vl["CAM_0x2a4"]) - - return ret - - def get_can_parser(self, CP): - if CP.carFingerprint in CANFD_CAR: - return self.get_can_parser_canfd(CP) - - messages = [ - # address, frequency - ("MDPS12", 50), - ("TCS11", 100), - ("TCS13", 50), - ("TCS15", 10), - ("CLU11", 50), - ("CLU15", 5), - ("ESP12", 100), - ("CGW1", 10), - ("CGW2", 5), - ("CGW4", 5), - ("WHL_SPD11", 50), - ("SAS11", 100), - ] - - if not CP.openpilotLongitudinalControl and CP.carFingerprint not in CAMERA_SCC_CAR: - messages += [ - ("SCC11", 50), - ("SCC12", 50), - ] - if CP.flags & HyundaiFlags.USE_FCA.value: - messages.append(("FCA11", 50)) - - if CP.enableBsm: - messages.append(("LCA11", 50)) - - if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - messages.append(("E_EMS11", 50)) - else: - messages += [ - ("EMS12", 100), - ("EMS16", 100), - ] - - if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - messages.append(("ELECT_GEAR", 20)) - elif CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - pass - elif CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - messages.append(("TCU12", 100)) - else: - messages.append(("LVR12", 100)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - if CP.carFingerprint in CANFD_CAR: - return CarState.get_cam_can_parser_canfd(CP) - - messages = [ - ("LKAS11", 100) - ] - - if not CP.openpilotLongitudinalControl and CP.carFingerprint in CAMERA_SCC_CAR: - messages += [ - ("SCC11", 50), - ("SCC12", 50), - ] - - if CP.flags & HyundaiFlags.USE_FCA.value: - messages.append(("FCA11", 50)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) - - def get_can_parser_canfd(self, CP): - messages = [ - (self.gear_msg_canfd, 100), - (self.accelerator_msg_canfd, 100), - ("WHEEL_SPEEDS", 100), - ("STEERING_SENSORS", 100), - ("MDPS", 100), - ("TCS", 50), - ("CRUISE_BUTTONS_ALT", 50), - ("BLINKERS", 4), - ("DOORS_SEATBELTS", 4), - ] - - if CP.flags & HyundaiFlags.EV: - messages += [ - ("MANUAL_SPEED_LIMIT_ASSIST", 10), - ] - - if not (CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): - messages += [ - ("CRUISE_BUTTONS", 50) - ] - - if CP.enableBsm: - messages += [ - ("BLINDSPOTS_REAR_CORNERS", 20), - ] - - if not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and not CP.openpilotLongitudinalControl: - messages += [ - ("SCC_CONTROL", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).ECAN) - - @staticmethod - def get_cam_can_parser_canfd(CP): - messages = [] - if CP.flags & HyundaiFlags.CANFD_HDA2: - block_lfa_msg = "CAM_0x362" if CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING else "CAM_0x2a4" - messages += [(block_lfa_msg, 20)] - elif CP.flags & HyundaiFlags.CANFD_CAMERA_SCC: - messages += [ - ("SCC_CONTROL", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).CAM) diff --git a/selfdrive/car/hyundai/fingerprints.py b/selfdrive/car/hyundai/fingerprints.py deleted file mode 100644 index d115283dd5c90db..000000000000000 --- a/selfdrive/car/hyundai/fingerprints.py +++ /dev/null @@ -1,1160 +0,0 @@ -# ruff: noqa: E501 -from cereal import car -from openpilot.selfdrive.car.hyundai.values import CAR - -Ecu = car.CarParams.Ecu - -FINGERPRINTS = { - CAR.HYUNDAI_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.HYUNDAI_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.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_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.HYUNDAI_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.HYUNDAI_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 - }], -} - -FW_VERSIONS = { - CAR.HYUNDAI_AZERA_6TH_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IG__ SCC F-CU- 1.00 1.00 99110-G8100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IG MDPS C 1.00 1.02 56310G8510\x00 4IGSC103', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IG MFC AT MES LHD 1.00 1.04 99211-G8100 200511', - ], - }, - CAR.HYUNDAI_AZERA_HEV_6TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.00 99211-G8000 180903', - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.01 99211-G8000 181109', - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.02 99211-G8100 191029', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IG MDPS C 1.00 1.00 56310M9600\x00 4IHSC100', - b'\xf1\x00IG MDPS C 1.00 1.01 56310M9350\x00 4IH8C101', - b'\xf1\x00IG MDPS C 1.00 1.02 56310M9350\x00 4IH8C102', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IGhe SCC FHCUP 1.00 1.00 99110-M9100 ', - b'\xf1\x00IGhe SCC FHCUP 1.00 1.01 99110-M9000 ', - b'\xf1\x00IGhe SCC FHCUP 1.00 1.02 99110-M9000 ', - ], - }, - CAR.HYUNDAI_GENESIS: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DH LKAS 1.1 -150210', - b'\xf1\x00DH LKAS 1.4 -140110', - b'\xf1\x00DH LKAS 1.5 -140425', - ], - }, - CAR.HYUNDAI_IONIQ: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.05 56310/G2501 4AEHC105', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_PHEV_2019: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2551 4AEHC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEP MFC AT AUS RHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_PHEV: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2200 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.02 99110-G2100 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.02 99110-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2210 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2310 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2510 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2560 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEP MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEP MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2700 201027', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819', - ], - }, - CAR.HYUNDAI_IONIQ_EV_2020: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7200 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7500 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7000 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7100 ', - b'\xf1\x00AEev SCC FHCUP 1.00 1.01 99110-G7100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7310 4APEC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7510 4APEC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7560 4APEC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2600 190730', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2700 201027', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.03 95740-G2500 190516', - b'\xf1\x00AEE MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEE MFC AT USA LHD 1.00 1.01 95740-G2600 190819', - ], - }, - CAR.HYUNDAI_IONIQ_EV_LTD: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7000 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.02 56310G7300\x00 4AEEC102', - b'\xf1\x00AE MDPS C 1.00 1.03 56310/G7300 4AEEC103', - b'\xf1\x00AE MDPS C 1.00 1.03 56310G7300\x00 4AEEC103', - b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7301 4AEEC104', - b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7501 4AEEC104', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2300 170703', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', - b'\xf1\x00AEE MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_HEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2700 201027', - ], - }, - CAR.HYUNDAI_SONATA: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DN8_ SCC F-CU- 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC F-CUP 1.00 1.02 99110-L1000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.02 99110-L1000 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', - b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', - b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', - b'\xf1\x00DN ESC \x06 107 \x07\x03 58910-L1300', - b'\xf1\x00DN ESC \x06 107"\x08\x07 58910-L0100', - b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', - b'\xf1\x00DN ESC \x07 107"\x08\x07 58910-L0100', - b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1010 4DNDC103', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1030 4DNDC103', - b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', - b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', - b'\xf1\x00DN8 MDPS R 1.00 1.02 57700-L1000 4DNDP105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', - b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.04 99211-L1000 191016', - b'\xf1\x00DN8 MFC AT RUS LHD 1.00 1.03 99211-L1000 190705', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223', - ], - }, - CAR.HYUNDAI_SONATA_LF: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', - b'\xf1\x00LF ESC \x0c 11 \x17\x01\x13 58920-C2610', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51', - b'\xf1\x00LFF LKAS AT USA LHD 1.01 1.02 95740-C1000 E52', - ], - }, - CAR.HYUNDAI_TUCSON: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TL__ FCA F-CUP 1.00 1.01 99110-D3500 ', - b'\xf1\x00TL__ FCA F-CUP 1.00 1.02 99110-D3510 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TL MFC AT KOR LHD 1.00 1.02 95895-D3800 180719', - b'\xf1\x00TL MFC AT USA LHD 1.00 1.06 95895-D3800 190107', - ], - }, - CAR.HYUNDAI_SANTA_FE: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1210 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S2000 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600', - b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600', - b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600', - b'\xf1\x00TM ESC \x02 104\x19\x07\x07 58910-S2600', - b'\xf1\x00TM ESC \x03 103\x18\x11\x07 58910-S2600', - b'\xf1\x00TM ESC \x0c 103\x18\x11\x08 58910-S2650', - b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', - b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', - b'\xf1\x00TM ESC \r 104\x19\x07\x08 58910-S2650', - b'\xf1\x00TM ESC \r 105\x19\x05# 58910-S1500', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409', - b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8A12', - b'\xf1\x00TM MDPS C 1.00 1.01 56340-S2000 9129', - b'\xf1\x00TM MDPS R 1.00 1.02 57700-S1100 4TMDP102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TM MFC AT EUR LHD 1.00 1.01 99211-S1010 181207', - b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409', - ], - }, - CAR.HYUNDAI_SANTA_FE_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S1500 ', - b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', - b'\xf1\x00TM__ SCC FHCUP 1.00 1.01 99110-S1500 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00TM ESC \x01 102!\x04\x03 58910-S2DA0', - b'\xf1\x00TM ESC \x01 104"\x10\x07 58910-S2DA0', - b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', - b'\xf1\x00TM ESC \x02 103"\x07\x08 58910-S2GA0', - b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', - b'\xf1\x00TM ESC \x03 102!\x04\x03 58910-S2DA0', - b'\xf1\x00TM ESC \x04 101 \x08\x04 58910-S2GA0', - b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', - b'\xf1\x00TM ESC \x04 103"\x07\x08 58910-S2GA0', - b'\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', - b'\xf1\x00TM ESC 103!\x030 58910-S1MA0', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', - b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1EB0 4TSDC101', - b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TM MFC AT MES LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMA MFC AT MEX LHD 1.00 1.01 99211-S2500 210205', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.00 99211-S2500 200720', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.01 99211-S2500 210205', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', - ], - }, - CAR.HYUNDAI_SANTA_FE_HEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100', - b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105', - b'\xf1\x00TM MDPS R 1.00 1.06 57700-CL000 4TSHP106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', - b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727', - b'\xf1\x00TMH MFC AT KOR LHD 1.00 1.06 99211-S1500 220727', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.06 99211-S1500 220727', - ], - }, - CAR.HYUNDAI_SANTA_FE_PHEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TMhe SCC F-CUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310CLEC0\x00 4TSHC102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.06 99211-S1500 220727', - ], - }, - CAR.HYUNDAI_CUSTIN_1ST_GEN: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00KU ESC \x01 101!\x02\x03 58910-O3200', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00KU__ SCC F-CUP 1.00 1.01 99110-O3000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00KU MDPS C 1.00 1.01 56310/O3100 4KUCC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00KU2 MFC AT CHN LHD 1.00 1.02 99211-O3000 220923', - ], - }, - CAR.KIA_STINGER: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104', - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5220 4C2VL104', - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104', - b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106', - b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106', - b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.04 95740-J5000 180504', - ], - }, - CAR.KIA_STINGER_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5500 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5600 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.01 99110-J5100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5300 4C2CL503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5320 4C2VL503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5520 4C4VL503', - b'\xf1\x00CK MDPS R 1.00 5.04 57700-J5520 4C4VL504', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT KOR LHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 99211-J5000 201209', - ], - }, - CAR.HYUNDAI_PALISADE: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC F-CUP 1.00 1.05 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCU- 1.00 1.05 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.00 99110-S8110 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.03 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.00 99110-S9110 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.01 99110-S9110 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.03 99110-S9100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x01 104 \x10\x15 58910-S8350', - b'\xf1\x00LX ESC \x01 104 \x10\x16 58910-S8360', - b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', - b'\xf1\x00LX ESC \x0b 101\x19\x03 58910-S8360', - b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', - b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', - b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', - b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', - b'\xf1\x00ON ESC \x01 101\x19\t\x08 58910-S9360', - b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360', - b'\xf1\x00ON ESC \x0b 101\x19\t\x05 58910-S9320', - b'\xf1\x00ON ESC \x0b 101\x19\t\x08 58910-S9360', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00LX2 MDPS C 1,00 1,03 56310-S8020 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8000 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-XX000 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8020 4LXDC104', - b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8420 4LXDC104', - b'\xf1\x00LX2 MDPS R 1.00 1.02 56370-S8300 9318', - b'\xf1\x00ON MDPS C 1.00 1.00 56340-S9000 8B13', - b'\xf1\x00ON MDPS C 1.00 1.01 56340-S9000 9201', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00LX2 MFC AT KOR LHD 1.00 1.08 99211-S8100 200903', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.00 99211-S8110 210226', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.05 99211-S8100 190909', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 200422', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 200903', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 181105', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 200720', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.04 99211-S9100 211227', - ], - }, - CAR.HYUNDAI_VELOSTER: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', - b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JS LKAS AT KOR LHD 1.00 1.03 95740-J3000 K33', - b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', - ], - }, - CAR.GENESIS_G70: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', - ], - }, - CAR.GENESIS_G70_2020: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9220 4I2VL106', - b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9220 4I2VL107', - b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9420 4I4VL107', - b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9200 4I2CL108', - b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9420 4I4VL108', - b'\xf1\x00IK MDPS R 1.00 5.09 57700-G9520 4I4VL509', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 \xf1\xa01.02', - b'\xf1\x00IK__ SCC FHCUP 1.00 1.00 99110-G9300 ', - b'\xf1\x00IK__ SCC FHCUP 1.00 1.02 96400-G9000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IK MFC AT KOR LHD 1.00 1.01 95740-G9000 170920', - b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', - b'\xf1\x00IK MFC AT USA LHD 1.00 1.04 99211-G9000 220401', - ], - }, - CAR.GENESIS_G80: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DH__ SCC F-CUP 1.00 1.01 96400-B1120 ', - b'\xf1\x00DH__ SCC F-CUP 1.00 1.02 96400-B1120 ', - b'\xf1\x00DH__ SCC FHCUP 1.00 1.01 96400-B1110 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.01 95895-B1500 161014', - b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.02 95895-B1500 170810', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.01 95895-B1500 161014', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.02 95895-B1500 170810', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.03 95895-B1500 180713', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.04 95895-B1500 181213', - ], - }, - CAR.GENESIS_G90: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00HI__ SCC F-CUP 1.00 1.01 96400-D2100 ', - b'\xf1\x00HI__ SCC FHCUP 1.00 1.02 99110-D2100 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2020 160302', - b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2030 170208', - b'\xf1\x00HI MFC AT USA LHD 1.00 1.03 99211-D2000 190831', - ], - }, - CAR.HYUNDAI_KONA: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', - ], - }, - CAR.KIA_CEED: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CD__ SCC F-CUP 1.00 1.02 99110-J7000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CD MDPS C 1.00 1.06 56310-XX000 4CDEC106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CD LKAS AT EUR LHD 1.00 1.01 99211-J7000 B40', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00CD ESC \x03 102\x18\x08\x05 58920-J7350', - ], - }, - CAR.KIA_FORTE: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00BD MDPS C 1.00 1.02 56310-XX000 4BD2C102', - b'\xf1\x00BD MDPS C 1.00 1.08 56310/M6300 4BDDC108', - b'\xf1\x00BD MDPS C 1.00 1.08 56310M6300\x00 4BDDC108', - b'\xf1\x00BDm MDPS C A.01 1.01 56310M7800\x00 4BPMC101', - b'\xf1\x00BDm MDPS C A.01 1.03 56310M7800\x00 4BPMC103', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00BD LKAS AT USA LHD 1.00 1.04 95740-M6000 J33', - b'\xf1\x00BDP LKAS AT USA LHD 1.00 1.05 99211-M6500 744', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00BDPE_SCC FHCUPC 1.00 1.04 99110-M6500\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x00BD__ SCC H-CUP 1.00 1.02 99110-M6000 ', - ], - }, - CAR.KIA_K5_2021: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.04 99110-L2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3110 4DLAC101', - b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L2220 4DLDC102', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310L3220\x00 4DLAC102', - b'\xf1\x00DL3 MDPS R 1.00 1.02 57700-L3000 4DLAP102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DL3 MFC AT KOR LHD 1.00 1.04 99210-L2000 210527', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.05 99210-L3000 211222', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00DL ESC \x01 104 \x07\x12 58910-L2200', - b'\xf1\x00DL ESC \x03 100 \x08\x02 58910-L3600', - b'\xf1\x00DL ESC \x06 101 \x04\x02 58910-L3200', - b'\xf1\x00DL ESC \x06 103"\x08\x06 58910-L3200', - b'\xf1\x00DL ESC \t 100 \x06\x02 58910-L3800', - b'\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', - b'\xf1\x00DL ESC \t 102"\x08\x10 58910-L3800', - ], - }, - CAR.KIA_K5_HEV_2020: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DLhe SCC FHCUP 1.00 1.02 99110-L7000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7000 4DLHC102', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7220 4DLHC102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.02 99210-L2000 200309', - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.04 99210-L2000 210527', - ], - }, - CAR.HYUNDAI_KONA_EV: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \x02 210 \x02\x14 58520-K4000', - b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \x03 210 \x02\x14 58520-K4000', - b'\xf1\x00OS IEB \x03 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OE2 LKAS AT EUR LHD 1.00 1.00 95740-K4200 200', - b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4300 W50', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103', - b'\xf1\x00OS MDPS C 1.00 1.04 56310-XX000 4OEDC104', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4000 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4100 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 ', - b'\xf1\x00OSev SCC FNCUP 1.00 1.01 99110-K4000 ', - ], - }, - CAR.HYUNDAI_KONA_EV_2022: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x02 102"\x05\x16 58520-K4010', - b'\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', - b'\xf1\x00OS IEB \x03 102"\x05\x16 58520-K4010', - b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802', - b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.02 99211-J9110 802', - b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT USA LHD 1.00 1.04 99211-J9200 904', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OSP MDPS C 1.00 1.02 56310-K4271 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4261\x00 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4971\x00 4OEPC102', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00', - ], - }, - CAR.HYUNDAI_KONA_EV_2ND_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SXev RDR ----- 1.00 1.00 99110-BF000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SX2EMFC AT KOR LHD 1.00 1.00 99211-BF000 230410', - ], - }, - CAR.KIA_NIRO_EV: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4600 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4000 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', - b'\xf1\x00DEev SCC FHCUP 1.00 1.00 99110-Q4600 ', - b'\xf1\x00DEev SCC FHCUP 1.00 1.03 96400-Q4000 ', - b'\xf1\x00DEev SCC FNCUP 1.00 1.00 99110-Q4600 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.04 56310Q4100\x00 4DEEC104', - b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105', - b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4100\x00 4DEEC105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4000 191211', - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.00 99211-Q4000 191211', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', - ], - }, - CAR.KIA_NIRO_EV_2ND_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', - b'\xf1\x00SG2EMFC AT USA LHD 1.01 1.09 99211-AT000 220801', - ], - }, - CAR.KIA_NIRO_PHEV: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 95740-G5010 170117', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 95740-G5010 170117', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.05 99211-G5000 190826', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC F-CUP 1.00 1.02 99110-G5100 ', - b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', - ], - }, - CAR.KIA_NIRO_PHEV_2022: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 99211-G5500 210428', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.06 99211-G5000 201028', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC F-CUP 1.00 1.00 99110-G5600 ', - b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', - ], - }, - CAR.KIA_NIRO_HEV_2021: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEH MFC AT KOR LHD 1.00 1.04 99211-G5000 190516', - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 99211-G5500 210428', - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.07 99211-G5000 201221', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', - b'\xf1\x00DEhe SCC FHCUP 1.00 1.01 99110-G5000 ', - ], - }, - CAR.KIA_SELTOS: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00SP ESC \x07 101\x19\t\x05 58910-Q5450', - b'\xf1\x00SP ESC \t 101\x19\t\x05 58910-Q5450', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00SP2 MDPS C 1.00 1.04 56300Q5200 ', - b'\xf1\x00SP2 MDPS C 1.01 1.05 56300Q5200 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114', - b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.05 99210-Q5000 201012', - ], - }, - CAR.KIA_OPTIMA_G4: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00JF ESC \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', - ], - }, - CAR.KIA_OPTIMA_G4_FL: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', - ], - (Ecu.abs, 0x7d1, None): [ - b"\xf1\x00JF ESC \t 11 \x18\x03' 58920-D5260", - b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5001 h32', - b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5100 h32', - ], - }, - CAR.KIA_OPTIMA_H: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JFhe SCC FNCUP 1.00 1.00 96400-A8000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFP LKAS AT EUR LHD 1.00 1.03 95895-A8100 160711', - ], - }, - CAR.KIA_OPTIMA_H_G4_FL: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JFhe SCC FHCUP 1.00 1.01 99110-A8500 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFH MFC AT KOR LHD 1.00 1.01 95895-A8200 180323', - ], - }, - CAR.HYUNDAI_ELANTRA: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AD LKAS AT USA LHD 1.01 1.01 95895-F2000 251', - b'\xf1\x00ADP LKAS AT USA LHD 1.00 1.03 99211-F2000 X31', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00AD ESC \x11 11 \x18\x05\x06 58910-F2840', - b'\xf1\x00AD ESC \x11 12 \x15\t\t 58920-F2810', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AD__ SCC H-CUP 1.00 1.00 99110-F2100 ', - b'\xf1\x00AD__ SCC H-CUP 1.00 1.01 96400-F2100 ', - ], - }, - CAR.HYUNDAI_ELANTRA_GT_I30: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00PD LKAS AT KOR LHD 1.00 1.02 95740-G3000 A51', - b'\xf1\x00PD LKAS AT USA LHD 1.00 1.02 95740-G3000 A51', - b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00PD MDPS C 1.00 1.00 56310G3300\x00 4PDDC100', - b'\xf1\x00PD MDPS C 1.00 1.03 56310/G3300 4PDDC103', - b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00PD ESC \t 104\x18\t\x03 58920-G3350', - b'\xf1\x00PD ESC \x0b 103\x17\x110 58920-G3350', - b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', - b'\xf1\x00PD__ SCC F-CUP 1.01 1.00 96400-G3100 ', - b'\xf1\x00PD__ SCC FNCUP 1.01 1.00 96400-G3000 ', - ], - }, - CAR.HYUNDAI_ELANTRA_2021: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', - b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', - b'\xf1\x00CN7_ SCC FNCUP 1.00 1.01 99110-AA000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA050 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA070 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.07 56310AA050\x00 4CNDC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.02 99210-AB000 220111', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AB000 220426', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.07 99210-AA000 220426', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.08 99210-AA000 220728', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', - b'\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', - b'\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800', - ], - }, - CAR.HYUNDAI_ELANTRA_HEV_2021: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.05 99210-AA000 210930', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.07 99210-AA000 220426', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.08 99210-AA000 220728', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.09 99210-AA000 221108', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310/BY050 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY050\x00 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY0500 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.04 56310BY050\x00 4CNHC104', - ], - }, - CAR.HYUNDAI_KONA_HEV: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OShe SCC FNCUP 1.00 1.01 99110-CM000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.00 56310CM030\x00 4OHDC100', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OSH LKAS AT KOR LHD 1.00 1.01 95740-CM000 l31', - ], - }, - CAR.HYUNDAI_SONATA_HYBRID: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', - b'\xf1\x00DNhe SCC FHCUP 1.00 1.00 99110-L5000 ', - b'\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L5000 4DNHC101', - b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', - b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L5450 4DNHC103', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DN8HMFC AT KOR LHD 1.00 1.03 99211-L1000 190705', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.05 99211-L1000 201109', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.06 99211-L1000 210325', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.07 99211-L1000 211223', - ], - }, - CAR.KIA_SORENTO: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00UMP LKAS AT KOR LHD 1.00 1.00 95740-C5550 S30', - b'\xf1\x00UMP LKAS AT USA LHD 1.00 1.00 95740-C6550 d00', - b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00UM ESC \x02 12 \x18\x05\x05 58910-C6300', - b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330', - b'\xf1\x00UM ESC \x13 12 \x17\x07\x05 58910-C5320', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C5500 ', - b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C6500 ', - ], - }, - CAR.KIA_EV6: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328', - b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.04 99210-CV000 210823', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.06 99210-CV000 220328', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV200 230510', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328', - ], - }, - CAR.HYUNDAI_IONIQ_5: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI010 230110', - b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', - b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.00 99211-GI020 230719', - b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.00 99211-GI020 230719', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.06 99211-GI010 230110', - ], - }, - CAR.HYUNDAI_IONIQ_6: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CE__ RDR ----- 1.00 1.01 99110-KL000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CE MFC AT CAN LHD 1.00 1.04 99211-KL000 221213', - b'\xf1\x00CE MFC AT EUR LHD 1.00 1.03 99211-KL000 221011', - b'\xf1\x00CE MFC AT EUR LHD 1.00 1.04 99211-KL000 221213', - b'\xf1\x00CE MFC AT USA LHD 1.00 1.04 99211-KL000 221213', - ], - }, - CAR.HYUNDAI_TUCSON_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.00 99211-N9260 14Y', - b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.01 99211-N9100 14A', - b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 1.00 99211-N9220 14K', - b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 2.02 99211-N9000 14E', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9250 14W', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9260 14Y', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9100 14A', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', - b'\xf1\x00NX4__ 1.00 1.01 99110-N9000 ', - b'\xf1\x00NX4__ 1.00 1.02 99110-N9000 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ', - ], - }, - CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW020 14Z', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-K5000 ', - ], - }, - CAR.KIA_SPORTAGE_5TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NQ5 FR_CMR AT AUS RHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT EUR LHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT GEN LHD 1.00 1.00 99211-P1060 665', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1030 662', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1060 665', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1070 690', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NQ5__ 1.00 1.02 99110-P1000 ', - b'\xf1\x00NQ5__ 1.00 1.03 99110-CH000 ', - b'\xf1\x00NQ5__ 1.00 1.03 99110-P1000 ', - b'\xf1\x00NQ5__ 1.01 1.03 99110-CH000 ', - b'\xf1\x00NQ5__ 1.01 1.03 99110-P1000 ', - ], - }, - CAR.GENESIS_GV70_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125', - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR300 220125', - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ', - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR300 ', - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ', - ], - }, - CAR.GENESIS_GV60_EV_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU000 211215', - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU100 211215', - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.03 99211-CU000 221118', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ', - ], - }, - CAR.KIA_SORENTO_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.00 99210-R5100 221019', - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.03 99210-R5000 200903', - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQ4_ SCC F-CUP 1.00 1.06 99110-P2000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.00 99110-R5000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.08 99110-P2000 ', - ], - }, - CAR.KIA_SORENTO_HEV_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.04 99210-P2000 200330', - b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.12 99210-P2000 230331', - b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.10 99210-P2000 210406', - b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.11 99210-P2000 211217', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQhe SCC FHCUP 1.00 1.04 99110-P4000 ', - b'\xf1\x00MQhe SCC FHCUP 1.00 1.06 99110-P4000 ', - b'\xf1\x00MQhe SCC FHCUP 1.00 1.07 99110-P4000 ', - ], - }, - CAR.KIA_NIRO_HEV_2ND_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.08 99211-AT000 220531', - b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.09 99211-AT000 220801', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', - ], - }, - CAR.GENESIS_GV80: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JX1 MFC AT USA LHD 1.00 1.02 99211-T6110 220513', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JX1_ SCC FHCUP 1.00 1.01 99110-T6100 ', - ], - }, - CAR.KIA_CARNIVAL_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00KA4 MFC AT EUR LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4 MFC AT KOR LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.00 99210-R0100 230105', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.01 99210-R0100 230710', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.05 99210-R0000 201221', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4CMFC AT CHN LHD 1.00 1.01 99211-I4000 210525', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00KA4_ SCC F-CUP 1.00 1.03 99110-R0000 ', - b'\xf1\x00KA4_ SCC FHCUP 1.00 1.00 99110-R0100 ', - b'\xf1\x00KA4_ SCC FHCUP 1.00 1.03 99110-R0000 ', - b'\xf1\x00KA4c SCC FHCUP 1.00 1.01 99110-I4000 ', - ], - }, - CAR.KIA_K8_HEV_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.03 99211-L8000 210907', - b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.04 99211-L8000 230207', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00GL3_ RDR ----- 1.00 1.02 99110-L8000 ', - ], - }, - CAR.HYUNDAI_STARIA_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00US4 MFC AT KOR LHD 1.00 1.06 99211-CG000 230524', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00US4_ RDR ----- 1.00 1.00 99110-CG000 ', - ], - }, -} diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py deleted file mode 100644 index 22c54bce6b51799..000000000000000 --- a/selfdrive/car/hyundai/interface.py +++ /dev/null @@ -1,180 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, CANFD_RADAR_SCC_CAR, \ - CANFD_UNSUPPORTED_LONGITUDINAL_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, \ - UNSUPPORTED_LONGITUDINAL_CAR, Buttons -from openpilot.selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.disable_ecu import disable_ecu - -Ecu = car.CarParams.Ecu -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -ENABLE_BUTTONS = (Buttons.RES_ACCEL, Buttons.SET_DECEL, Buttons.CANCEL) -BUTTONS_DICT = {Buttons.RES_ACCEL: ButtonType.accelCruise, Buttons.SET_DECEL: ButtonType.decelCruise, - Buttons.GAP_DIST: ButtonType.gapAdjustCruise, Buttons.CANCEL: ButtonType.cancel} - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "hyundai" - ret.radarUnavailable = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None - - # These cars have been put into dashcam only due to both a lack of users and test coverage. - # These cars likely still work fine. Once a user confirms each car works and a test route is - # added to selfdrive/car/tests/routes.py, we can remove it from this list. - # FIXME: the Optima Hybrid 2017 uses a different SCC12 checksum - ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, } - - hda2 = Ecu.adas in [fw.ecu for fw in car_fw] - CAN = CanBus(None, hda2, fingerprint) - - if candidate in CANFD_CAR: - # detect if car is hybrid - if 0x105 in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.HYBRID.value - elif candidate in EV_CAR: - ret.flags |= HyundaiFlags.EV.value - - # detect HDA2 with ADAS Driving ECU - if hda2: - ret.flags |= HyundaiFlags.CANFD_HDA2.value - if 0x110 in fingerprint[CAN.CAM]: - ret.flags |= HyundaiFlags.CANFD_HDA2_ALT_STEERING.value - else: - # non-HDA2 - if 0x1cf not in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value - # ICE cars do not have 0x130; GEARS message on 0x40 or 0x70 instead - if 0x130 not in fingerprint[CAN.ECAN]: - if 0x40 not in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.CANFD_ALT_GEARS_2.value - else: - ret.flags |= HyundaiFlags.CANFD_ALT_GEARS.value - if candidate not in CANFD_RADAR_SCC_CAR: - ret.flags |= HyundaiFlags.CANFD_CAMERA_SCC.value - else: - # TODO: detect EV and hybrid - if candidate in HYBRID_CAR: - ret.flags |= HyundaiFlags.HYBRID.value - elif candidate in EV_CAR: - ret.flags |= HyundaiFlags.EV.value - - # Send LFA message on cars with HDA - if 0x485 in fingerprint[2]: - ret.flags |= HyundaiFlags.SEND_LFA.value - - # These cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - if 0x38d in fingerprint[0] or 0x38d in fingerprint[2]: - ret.flags |= HyundaiFlags.USE_FCA.value - - ret.steerActuatorDelay = 0.1 # Default delay - ret.steerLimitTimer = 0.4 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate == CAR.KIA_OPTIMA_G4_FL: - ret.steerActuatorDelay = 0.2 - - # *** longitudinal control *** - if candidate in CANFD_CAR: - ret.longitudinalTuning.kpV = [0.1] - ret.longitudinalTuning.kiV = [0.0] - ret.experimentalLongitudinalAvailable = candidate not in (CANFD_UNSUPPORTED_LONGITUDINAL_CAR | CANFD_RADAR_SCC_CAR) - else: - ret.longitudinalTuning.kpV = [0.5] - ret.longitudinalTuning.kiV = [0.0] - ret.experimentalLongitudinalAvailable = candidate not in (UNSUPPORTED_LONGITUDINAL_CAR | CAMERA_SCC_CAR) - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable - ret.pcmCruise = not ret.openpilotLongitudinalControl - - ret.stoppingControl = True - ret.startingState = True - ret.vEgoStarting = 0.1 - ret.startAccel = 1.0 - ret.longitudinalActuatorDelayLowerBound = 0.5 - ret.longitudinalActuatorDelayUpperBound = 0.5 - - # *** feature detection *** - if candidate in CANFD_CAR: - ret.enableBsm = 0x1e5 in fingerprint[CAN.ECAN] - else: - ret.enableBsm = 0x58b in fingerprint[0] - - # *** panda safety config *** - if candidate in CANFD_CAR: - cfgs = [get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd), ] - if CAN.ECAN >= 4: - cfgs.insert(0, get_safety_config(car.CarParams.SafetyModel.noOutput)) - ret.safetyConfigs = cfgs - - if ret.flags & HyundaiFlags.CANFD_HDA2: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 - if ret.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2_ALT_STEERING - if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS - if ret.flags & HyundaiFlags.CANFD_CAMERA_SCC: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC - else: - if candidate in LEGACY_SAFETY_MODE_CAR: - # these cars require a special panda safety mode due to missing counters and checksums in the messages - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundaiLegacy)] - else: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundai, 0)] - - if candidate in CAMERA_SCC_CAR: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC - - if ret.openpilotLongitudinalControl: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_LONG - if ret.flags & HyundaiFlags.HYBRID: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_HYBRID_GAS - elif ret.flags & HyundaiFlags.EV: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_EV_GAS - - if candidate in (CAR.HYUNDAI_KONA, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_KONA_HEV, CAR.HYUNDAI_KONA_EV_2022): - ret.flags |= HyundaiFlags.ALT_LIMITS.value - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_ALT_LIMITS - - ret.centerToFront = ret.wheelbase * 0.4 - - return ret - - @staticmethod - def init(CP, logcan, sendcan): - if CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value): - addr, bus = 0x7d0, 0 - if CP.flags & HyundaiFlags.CANFD_HDA2.value: - addr, bus = 0x730, CanBus(CP).ECAN - disable_ecu(logcan, sendcan, bus=bus, addr=addr, com_cont_req=b'\x28\x83\x01') - - # for blinkers - if CP.flags & HyundaiFlags.ENABLE_BLINKERS: - disable_ecu(logcan, sendcan, bus=CanBus(CP).ECAN, addr=0x7B1, com_cont_req=b'\x28\x83\x01') - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - if self.CS.CP.openpilotLongitudinalControl: - ret.buttonEvents = create_button_events(self.CS.cruise_buttons[-1], self.CS.prev_cruise_buttons, BUTTONS_DICT) - - # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state - # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons - # Main button also can trigger an engagement on these cars - allow_enable = any(btn in ENABLE_BUTTONS for btn in self.CS.cruise_buttons) or any(self.CS.main_buttons) - events = self.create_common_events(ret, pcm_enable=self.CS.CP.pcmCruise, allow_enable=allow_enable) - - # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) - if ret.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: - self.low_speed_alert = True - if ret.vEgo > (self.CP.minSteerSpeed + 4.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(car.CarEvent.EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py deleted file mode 100644 index 52600509860f5aa..000000000000000 --- a/selfdrive/car/hyundai/radar_interface.py +++ /dev/null @@ -1,79 +0,0 @@ -import math - -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.hyundai.values import DBC - -RADAR_START_ADDR = 0x500 -RADAR_MSG_COUNT = 32 - -# POC for parsing corner radars: https://github.com/commaai/openpilot/pull/24221/ - -def get_radar_can_parser(CP): - if DBC[CP.carFingerprint]['radar'] is None: - return None - - messages = [(f"RADAR_TRACK_{addr:x}", 50) for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT)] - return CANParser(DBC[CP.carFingerprint]['radar'], messages, 1) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.updated_messages = set() - self.trigger_msg = RADAR_START_ADDR + RADAR_MSG_COUNT - 1 - self.track_id = 0 - - self.radar_off_can = CP.radarUnavailable - self.rcp = get_radar_can_parser(CP) - - def update(self, can_strings): - if self.radar_off_can or (self.rcp is None): - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - if self.rcp is None: - return ret - - errors = [] - - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT): - msg = self.rcp.vl[f"RADAR_TRACK_{addr:x}"] - - if addr not in self.pts: - self.pts[addr] = car.RadarData.RadarPoint.new_message() - self.pts[addr].trackId = self.track_id - self.track_id += 1 - - valid = msg['STATE'] in (3, 4) - if valid: - azimuth = math.radians(msg['AZIMUTH']) - self.pts[addr].measured = True - self.pts[addr].dRel = math.cos(azimuth) * msg['LONG_DIST'] - self.pts[addr].yRel = 0.5 * -math.sin(azimuth) * msg['LONG_DIST'] - self.pts[addr].vRel = msg['REL_SPEED'] - self.pts[addr].aRel = msg['REL_ACCEL'] - self.pts[addr].yvRel = float('nan') - - else: - del self.pts[addr] - - ret.points = list(self.pts.values()) - return ret diff --git a/selfdrive/car/hyundai/tests/print_platform_codes.py b/selfdrive/car/hyundai/tests/print_platform_codes.py deleted file mode 100755 index f641535678c22f1..000000000000000 --- a/selfdrive/car/hyundai/tests/print_platform_codes.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from openpilot.selfdrive.car.hyundai.values import PLATFORM_CODE_ECUS, get_platform_codes -from openpilot.selfdrive.car.hyundai.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -if __name__ == "__main__": - for car_model, ecus in FW_VERSIONS.items(): - print() - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - platform_codes = get_platform_codes(ecus[ecu]) - codes = {code for code, _ in platform_codes} - dates = {date for _, date in platform_codes if date is not None} - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {codes}') - print(f' Dates: {dates}') diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py deleted file mode 100644 index c489ea0042717a4..000000000000000 --- a/selfdrive/car/hyundai/values.py +++ /dev/null @@ -1,751 +0,0 @@ -import re -from dataclasses import dataclass, field -from enum import Enum, IntFlag - -from cereal import car -from panda.python import uds -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - ACCEL_MIN = -3.5 # m/s - ACCEL_MAX = 2.0 # m/s - - def __init__(self, CP): - self.STEER_DELTA_UP = 3 - self.STEER_DELTA_DOWN = 7 - self.STEER_DRIVER_ALLOWANCE = 50 - self.STEER_DRIVER_MULTIPLIER = 2 - self.STEER_DRIVER_FACTOR = 1 - self.STEER_THRESHOLD = 150 - self.STEER_STEP = 1 # 100 Hz - - if CP.carFingerprint in CANFD_CAR: - self.STEER_MAX = 270 - self.STEER_DRIVER_ALLOWANCE = 250 - self.STEER_DRIVER_MULTIPLIER = 2 - self.STEER_THRESHOLD = 250 - self.STEER_DELTA_UP = 2 - self.STEER_DELTA_DOWN = 3 - - # To determine the limit for your car, find the maximum value that the stock LKAS will request. - # If the max stock LKAS request is <384, add your car to this list. - elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.HYUNDAI_ELANTRA, CAR.HYUNDAI_ELANTRA_GT_I30, CAR.HYUNDAI_IONIQ, - CAR.HYUNDAI_IONIQ_EV_LTD, CAR.HYUNDAI_SANTA_FE_PHEV_2022, CAR.HYUNDAI_SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV, - CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA_H_G4_FL, CAR.KIA_SORENTO): - self.STEER_MAX = 255 - - # these cars have significantly more torque than most HKG; limit to 70% of max - elif CP.flags & HyundaiFlags.ALT_LIMITS: - self.STEER_MAX = 270 - self.STEER_DELTA_UP = 2 - self.STEER_DELTA_DOWN = 3 - - # Default for most HKG - else: - self.STEER_MAX = 384 - - -class HyundaiFlags(IntFlag): - # Dynamic Flags - CANFD_HDA2 = 1 - CANFD_ALT_BUTTONS = 2 - CANFD_ALT_GEARS = 2 ** 2 - CANFD_CAMERA_SCC = 2 ** 3 - - ALT_LIMITS = 2 ** 4 - ENABLE_BLINKERS = 2 ** 5 - CANFD_ALT_GEARS_2 = 2 ** 6 - SEND_LFA = 2 ** 7 - USE_FCA = 2 ** 8 - CANFD_HDA2_ALT_STEERING = 2 ** 9 - - # these cars use a different gas signal - HYBRID = 2 ** 10 - EV = 2 ** 11 - - # Static flags - - # If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points. - # If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py - MANDO_RADAR = 2 ** 12 - CANFD = 2 ** 13 - - # The radar does SCC on these cars when HDA I, rather than the camera - RADAR_SCC = 2 ** 14 - CAMERA_SCC = 2 ** 15 - CHECKSUM_CRC8 = 2 ** 16 - CHECKSUM_6B = 2 ** 17 - - # these cars require a special panda safety mode due to missing counters and checksums in the messages - LEGACY = 2 ** 18 - - # these cars have not been verified to work with longitudinal yet - radar disable, sending correct messages, etc. - UNSUPPORTED_LONGITUDINAL = 2 ** 19 - - CANFD_NO_RADAR_DISABLE = 2 ** 20 - - CLUSTER_GEARS = 2 ** 21 - TCU_GEARS = 2 ** 22 - - MIN_STEER_32_MPH = 2 ** 23 - - -class Footnote(Enum): - CANFD = CarFootnote( - "Requires a CAN FD panda kit if not using " + - "comma 3X for this CAN FD car.", - Column.MODEL, shop_footnote=False) - - -@dataclass -class HyundaiCarDocs(CarDocs): - package: str = "Smart Cruise Control (SCC)" - - def init_make(self, CP: car.CarParams): - if CP.flags & HyundaiFlags.CANFD: - self.footnotes.insert(0, Footnote.CANFD) - - -@dataclass -class HyundaiPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_kia_generic", None)) - - def init(self): - if self.flags & HyundaiFlags.MANDO_RADAR: - self.dbc_dict = dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated') - - if self.flags & HyundaiFlags.MIN_STEER_32_MPH: - self.specs = self.specs.override(minSteerSpeed=32 * CV.MPH_TO_MS) - - -@dataclass -class HyundaiCanFDPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_canfd", None)) - - def init(self): - self.flags |= HyundaiFlags.CANFD - - -class CAR(Platforms): - # Hyundai - HYUNDAI_AZERA_6TH_GEN = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Azera 2022", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=1600, wheelbase=2.885, steerRatio=14.5), - ) - HYUNDAI_AZERA_HEV_6TH_GEN = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Azera Hybrid 2019", "All", car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Hyundai Azera Hybrid 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), - ], - CarSpecs(mass=1675, wheelbase=2.885, steerRatio=14.5), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_ELANTRA = HyundaiPlatformConfig( - [ - # TODO: 2017-18 could be Hyundai G - HyundaiCarDocs("Hyundai Elantra 2017-18", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b])), - HyundaiCarDocs("Hyundai Elantra 2019", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), - ], - # steerRatio: 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535, stiffnessFactor settled on 1.0081302973865127 - CarSpecs(mass=1275, wheelbase=2.7, steerRatio=15.4, tireStiffnessFactor=0.385), - flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_ELANTRA_GT_I30 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Elantra GT 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), - HyundaiCarDocs("Hyundai i30 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - HYUNDAI_ELANTRA.specs, - flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_ELANTRA_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Elantra 2021-23", video_link="https://youtu.be/_EdYQtV52-c", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=2800 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_ELANTRA_HEV_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", - car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=3017 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_GENESIS = HyundaiPlatformConfig( - [ - # TODO: check 2015 packages - HyundaiCarDocs("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), - HyundaiCarDocs("Genesis G80 2017", "All", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), - ], - CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5, minSteerSpeed=60 * CV.KPH_TO_MS), - flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.LEGACY, - ) - HYUNDAI_IONIQ = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Hybrid 2017-19", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_HEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_h]))], # TODO: confirm 2020-21 harness, - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, - ) - HYUNDAI_IONIQ_EV_LTD = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Electric 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV | HyundaiFlags.LEGACY | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_EV_2020 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Electric 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV, - ) - HYUNDAI_IONIQ_PHEV_2019 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_PHEV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_KONA = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona 2020", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b]))], - CarSpecs(mass=1275, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.CLUSTER_GEARS, - ) - HYUNDAI_KONA_EV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric 2018-21", car_parts=CarParts.common([CarHarness.hyundai_g]))], - CarSpecs(mass=1685, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV, - ) - HYUNDAI_KONA_EV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric 2022-23", car_parts=CarParts.common([CarHarness.hyundai_o]))], - CarSpecs(mass=1743, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.CAMERA_SCC | HyundaiFlags.EV, - ) - HYUNDAI_KONA_EV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric (with HDA II, Korea only) 2023", video_link="https://www.youtube.com/watch?v=U2fOCmcQ8hw", - car_parts=CarParts.common([CarHarness.hyundai_r]))], - CarSpecs(mass=1740, wheelbase=2.66, steerRatio=13.6, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, - ) - HYUNDAI_KONA_HEV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_i]))], # TODO: check packages, - CarSpecs(mass=1425, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_SANTA_FE = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe 2019-20", "All", video_link="https://youtu.be/bjDR0YjM__s", - car_parts=CarParts.common([CarHarness.hyundai_d]))], - CarSpecs(mass=3982 * CV.LB_TO_KG, wheelbase=2.766, steerRatio=16.55, tireStiffnessFactor=0.82), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SANTA_FE_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe 2021-23", "All", video_link="https://youtu.be/VnHzSTygTS4", - car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SANTA_FE_HEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_SANTA_FE_PHEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_SONATA = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata 2020-23", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", - car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=1513, wheelbase=2.84, steerRatio=13.27 * 1.15, tireStiffnessFactor=0.65), # 15% higher at the center seems reasonable - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SONATA_LF = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata 2018-19", car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=1536, wheelbase=2.804, steerRatio=13.27 * 1.15), # 15% higher at the center seems reasonable - - flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_STARIA_4TH_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Staria 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=2205, wheelbase=3.273, steerRatio=11.94), # https://www.hyundai.com/content/dam/hyundai/au/en/models/staria-load/premium-pip-update-2023/spec-sheet/STARIA_Load_Spec-Table_March_2023_v3.1.pdf - ) - HYUNDAI_TUCSON = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Hyundai Tucson Diesel 2019", car_parts=CarParts.common([CarHarness.hyundai_l])), - ], - CarSpecs(mass=3520 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=16.1, tireStiffnessFactor=0.385), - flags=HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_PALISADE = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Palisade 2020-22", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456", car_parts=CarParts.common([CarHarness.hyundai_h])), - HyundaiCarDocs("Kia Telluride 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h])), - ], - CarSpecs(mass=1999, wheelbase=2.9, steerRatio=15.6 * 1.15, tireStiffnessFactor=0.63), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_VELOSTER = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=2917 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75 * 1.15, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_SONATA_HYBRID = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata Hybrid 2020-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], - HYUNDAI_SONATA.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_IONIQ_5 = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Hyundai Ioniq 5 (Southeast Asia only) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_q])), - HyundaiCarDocs("Hyundai Ioniq 5 (without HDA II) 2022-23", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_k])), - HyundaiCarDocs("Hyundai Ioniq 5 (with HDA II) 2022-23", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q])), - ], - CarSpecs(mass=1948, wheelbase=2.97, steerRatio=14.26, tireStiffnessFactor=0.65), - flags=HyundaiFlags.EV, - ) - HYUNDAI_IONIQ_6 = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq 6 (with HDA II) 2023-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p]))], - HYUNDAI_IONIQ_5.specs, - flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, - ) - HYUNDAI_TUCSON_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Hyundai Tucson 2022", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson 2023-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson Hybrid 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson Plug-in Hybrid 2024", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - ], - CarSpecs(mass=1630, wheelbase=2.756, steerRatio=13.7, tireStiffnessFactor=0.385), - ) - HYUNDAI_SANTA_CRUZ_1ST_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Cruz 2022-24", car_parts=CarParts.common([CarHarness.hyundai_n]))], - # weight from Limited trim - the only supported trim, steering ratio according to Hyundai News https://www.hyundainews.com/assets/documents/original/48035-2022SantaCruzProductGuideSpecsv2081521.pdf - CarSpecs(mass=1870, wheelbase=3, steerRatio=14.2), - ) - HYUNDAI_CUSTIN_1ST_GEN = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Custin 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=1690, wheelbase=3.055, steerRatio=17), # mass: from https://www.hyundai-motor.com.tw/clicktobuy/custin#spec_0, steerRatio: from learner - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - - # Kia - KIA_FORTE = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Forte 2019-21", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), - HyundaiCarDocs("Kia Forte 2022-23", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - CarSpecs(mass=2878 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5) - ) - KIA_K5_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia K5 2021-24", car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=3381 * CV.LB_TO_KG, wheelbase=2.85, steerRatio=13.27, tireStiffnessFactor=0.5), # 2021 Kia K5 Steering Ratio (all trims) - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - KIA_K5_HEV_2020 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia K5 Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_K5_2021.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - KIA_K8_HEV_1ST_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia K8 Hybrid (with HDA II) 2023", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q]))], - # mass: https://carprices.ae/brands/kia/2023/k8/1.6-turbo-hybrid, steerRatio: guesstimate from K5 platform - CarSpecs(mass=1630, wheelbase=2.895, steerRatio=13.27) - ) - KIA_NIRO_EV = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), - HyundaiCarDocs("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_f])), - HyundaiCarDocs("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), - ], - CarSpecs(mass=3543 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=13.6, tireStiffnessFactor=0.385), # average of all the cars - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV, - ) - KIA_NIRO_EV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Niro EV 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.EV, - ) - KIA_NIRO_PHEV = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Hybrid 2018", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_d])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.MIN_STEER_32_MPH, - ) - KIA_NIRO_PHEV_2022 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.HYBRID | HyundaiFlags.MANDO_RADAR, - ) - KIA_NIRO_HEV_2021 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), - HyundaiCarDocs("Kia Niro Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.HYBRID, - ) - KIA_NIRO_HEV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Niro Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_NIRO_EV.specs, - ) - KIA_OPTIMA_G4 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima 2017", "Advanced Smart Cruise Control", - car_parts=CarParts.common([CarHarness.hyundai_b]))], # TODO: may support 2016, 2018 - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - KIA_OPTIMA_G4_FL = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima 2019-20", car_parts=CarParts.common([CarHarness.hyundai_g]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, - ) - # TODO: may support adjacent years. may have a non-zero minimum steering speed - KIA_OPTIMA_H = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, - ) - KIA_OPTIMA_H_G4_FL = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, - ) - KIA_SELTOS = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Seltos 2021", car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=1337, wheelbase=2.63, steerRatio=14.56), - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - KIA_SPORTAGE_5TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Sportage 2023-24", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Kia Sportage Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), - ], - # weight from SX and above trims, average of FWD and AWD version, steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sportage/2023/specifications - CarSpecs(mass=1725, wheelbase=2.756, steerRatio=13.6), - ) - KIA_SORENTO = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Sorento 2018", "Advanced Smart Cruise Control & LKAS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", - car_parts=CarParts.common([CarHarness.hyundai_e])), - HyundaiCarDocs("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - CarSpecs(mass=1985, wheelbase=2.78, steerRatio=14.4 * 1.1), # 10% higher at the center seems reasonable - flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, - ) - KIA_SORENTO_4TH_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Sorento 2021-23", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=3957 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms - flags=HyundaiFlags.RADAR_SCC, - ) - KIA_SORENTO_HEV_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Sorento Hybrid 2021-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Kia Sorento Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - ], - CarSpecs(mass=4395 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms - flags=HyundaiFlags.RADAR_SCC, - ) - KIA_STINGER = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", - car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1825, wheelbase=2.78, steerRatio=14.4 * 1.15) # 15% higher at the center seems reasonable - ) - KIA_STINGER_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Stinger 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - KIA_STINGER.specs, - ) - KIA_CEED = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Ceed 2019", car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=1450, wheelbase=2.65, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY, - ) - KIA_EV6 = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia EV6 (Southeast Asia only) 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_p])), - HyundaiCarDocs("Kia EV6 (without HDA II) 2022-24", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Kia EV6 (with HDA II) 2022-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p])) - ], - CarSpecs(mass=2055, wheelbase=2.9, steerRatio=16, tireStiffnessFactor=0.65), - flags=HyundaiFlags.EV, - ) - KIA_CARNIVAL_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Carnival 2022-24", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Kia Carnival (China only) 2023", car_parts=CarParts.common([CarHarness.hyundai_k])) - ], - CarSpecs(mass=2087, wheelbase=3.09, steerRatio=14.23), - flags=HyundaiFlags.RADAR_SCC, - ) - - # Genesis - GENESIS_GV60_EV_1ST_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Genesis GV60 (Advanced Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Genesis GV60 (Performance Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), - ], - CarSpecs(mass=2205, wheelbase=2.9, steerRatio=12.6), # steerRatio: https://www.motor1.com/reviews/586376/2023-genesis-gv60-first-drive/#:~:text=Relative%20to%20the%20related%20Ioniq,5%2FEV6%27s%2014.3%3A1. - flags=HyundaiFlags.EV, - ) - GENESIS_G70 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G70 2018", "All", car_parts=CarParts.common([CarHarness.hyundai_f]))], - CarSpecs(mass=1640, wheelbase=2.84, steerRatio=13.56), - flags=HyundaiFlags.LEGACY, - ) - GENESIS_G70_2020 = HyundaiPlatformConfig( - [ - # TODO: 2021 MY harness is unknown - HyundaiCarDocs("Genesis G70 2019-21", "All", car_parts=CarParts.common([CarHarness.hyundai_f])), - # TODO: From 3.3T Sport Advanced 2022 & Prestige 2023 Trim, 2.0T is unknown - HyundaiCarDocs("Genesis G70 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), - ], - GENESIS_G70.specs, - flags=HyundaiFlags.MANDO_RADAR, - ) - GENESIS_GV70_1ST_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Genesis GV70 (2.5T Trim) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Genesis GV70 (3.5T Trim) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_m])), - ], - CarSpecs(mass=1950, wheelbase=2.87, steerRatio=14.6), - flags=HyundaiFlags.RADAR_SCC, - ) - GENESIS_G80 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G80 2018-19", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5), - flags=HyundaiFlags.LEGACY, - ) - GENESIS_G90 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G90 2017-20", "All", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=2200, wheelbase=3.15, steerRatio=12.069), - ) - GENESIS_GV80 = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Genesis GV80 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_m]))], - CarSpecs(mass=2258, wheelbase=2.95, steerRatio=14.14), - flags=HyundaiFlags.RADAR_SCC, - ) - - -class Buttons: - NONE = 0 - RES_ACCEL = 1 - SET_DECEL = 2 - GAP_DIST = 3 - CANCEL = 4 # on newer models, this is a pause/resume button - - -def get_platform_codes(fw_versions: list[bytes]) -> set[tuple[bytes, bytes | None]]: - # Returns unique, platform-specific identification codes for a set of versions - codes = set() # (code-Optional[part], date) - for fw in fw_versions: - code_match = PLATFORM_CODE_FW_PATTERN.search(fw) - part_match = PART_NUMBER_FW_PATTERN.search(fw) - date_match = DATE_FW_PATTERN.search(fw) - if code_match is not None: - code: bytes = code_match.group() - part = part_match.group() if part_match else None - date = date_match.group() if date_match else None - if part is not None: - # part number starts with generic ECU part type, add what is specific to platform - code += b"-" + part[-5:] - - codes.add((code, date)) - return codes - - -def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: - # Non-electric CAN FD platforms often do not have platform code specifiers needed - # to distinguish between hybrid and ICE. All EVs so far are either exclusively - # electric or specify electric in the platform code. - fuzzy_platform_blacklist = {str(c) for c in (CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST)} - candidates: set[str] = set() - - for candidate, fws in offline_fw_versions.items(): - # Keep track of ECUs which pass all checks (platform codes, within date range) - valid_found_ecus = set() - valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} - for ecu, expected_versions in fws.items(): - addr = ecu[1:] - # Only check ECUs expected to have platform codes - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Expected platform codes & dates - codes = get_platform_codes(expected_versions) - expected_platform_codes = {code for code, _ in codes} - expected_dates = {date for _, date in codes if date is not None} - - # Found platform codes & dates - codes = get_platform_codes(live_fw_versions.get(addr, set())) - found_platform_codes = {code for code, _ in codes} - found_dates = {date for _, date in codes if date is not None} - - # Check platform code + part number matches for any found versions - if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): - break - - if ecu[0] in DATE_FW_ECUS: - # If ECU can have a FW date, require it to exist - # (this excludes candidates in the database without dates) - if not len(expected_dates) or not len(found_dates): - break - - # Check any date within range in the database, format is %y%m%d - if not any(min(expected_dates) <= found_date <= max(expected_dates) for found_date in found_dates): - break - - valid_found_ecus.add(addr) - - # If all live ECUs pass all checks for candidate, add it as a match - if valid_expected_ecus.issubset(valid_found_ecus): - candidates.add(candidate) - - return candidates - fuzzy_platform_blacklist - - -HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) # Long description - -HYUNDAI_VERSION_REQUEST_ALT = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf110) # Alt long description - -HYUNDAI_ECU_MANUFACTURING_DATE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.ECU_MANUFACTURING_DATE) - -HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) - -# Regex patterns for parsing platform code, FW date, and part number from FW versions -PLATFORM_CODE_FW_PATTERN = re.compile(b'((?<=' + HYUNDAI_VERSION_REQUEST_LONG[1:] + - b')[A-Z]{2}[A-Za-z0-9]{0,2})') -DATE_FW_PATTERN = re.compile(b'(?<=[ -])([0-9]{6}$)') -PART_NUMBER_FW_PATTERN = re.compile(b'(?<=[0-9][.,][0-9]{2} )([0-9]{5}[-/]?[A-Z][A-Z0-9]{3}[0-9])') - -# We've seen both ICE and hybrid for these platforms, and they have hybrid descriptors (e.g. MQ4 vs MQ4H) -CANFD_FUZZY_WHITELIST = {CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KIA_K8_HEV_1ST_GEN, - # TODO: the hybrid variant is not out yet - CAR.KIA_CARNIVAL_4TH_GEN} - -# List of ECUs expected to have platform codes, camera and radar should exist on all cars -# TODO: use abs, it has the platform code and part number on many platforms -PLATFORM_CODE_ECUS = [Ecu.fwdRadar, Ecu.fwdCamera, Ecu.eps] -# So far we've only seen dates in fwdCamera -# TODO: there are date codes in the ABS firmware versions in hex -DATE_FW_ECUS = [Ecu.fwdCamera] - -# Note: an ECU on CAN FD cars may sometimes send 0x30080aaaaaaaaaaa (flow control continue) while we -# are attempting to query ECUs. This currently does not seem to affect fingerprinting from the camera -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # TODO: add back whitelists - # CAN queries (OBD-II port) - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - ), - - # CAN & CAN-FD queries (from camera) - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - ), - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - bus=1, - auxiliary=True, - obd_multiplexing=False, - ), - - # CAN & CAN FD query to understand the three digit date code - # HDA2 cars usually use 6 digit date codes, so skip bus 1 - Request( - [HYUNDAI_ECU_MANUFACTURING_DATE], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - logging=True, - ), - - # CAN-FD alt request logging queries for hvac and parkingAdas - Request( - [HYUNDAI_VERSION_REQUEST_ALT], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - logging=True, - ), - Request( - [HYUNDAI_VERSION_REQUEST_ALT], - [HYUNDAI_VERSION_RESPONSE], - bus=1, - auxiliary=True, - logging=True, - obd_multiplexing=False, - ), - ], - # We lose these ECUs without the comma power on these cars. - # Note that we still attempt to match with them when they are present - non_essential_ecus={ - Ecu.abs: [CAR.HYUNDAI_PALISADE, CAR.HYUNDAI_SONATA, CAR.HYUNDAI_SANTA_FE_2022, CAR.KIA_K5_2021, CAR.HYUNDAI_ELANTRA_2021, - CAR.HYUNDAI_SANTA_FE, CAR.HYUNDAI_KONA_EV_2022, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_CUSTIN_1ST_GEN, CAR.KIA_SORENTO, - CAR.KIA_CEED, CAR.KIA_SELTOS], - }, - extra_ecus=[ - (Ecu.adas, 0x730, None), # ADAS Driving ECU on HDA2 platforms - (Ecu.parkingAdas, 0x7b1, None), # ADAS Parking ECU (may exist on all platforms) - (Ecu.hvac, 0x7b3, None), # HVAC Control Assembly - (Ecu.cornerRadar, 0x7b7, None), - (Ecu.combinationMeter, 0x7c6, None), # CAN FD Instrument cluster - ], - # Custom fuzzy fingerprinting function using platform codes, part numbers + FW dates: - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -CHECKSUM = { - "crc8": CAR.with_flags(HyundaiFlags.CHECKSUM_CRC8), - "6B": CAR.with_flags(HyundaiFlags.CHECKSUM_6B), -} - -CAN_GEARS = { - # which message has the gear. hybrid and EV use ELECT_GEAR - "use_cluster_gears": CAR.with_flags(HyundaiFlags.CLUSTER_GEARS), - "use_tcu_gears": CAR.with_flags(HyundaiFlags.TCU_GEARS), -} - -CANFD_CAR = CAR.with_flags(HyundaiFlags.CANFD) -CANFD_RADAR_SCC_CAR = CAR.with_flags(HyundaiFlags.RADAR_SCC) - -# These CAN FD cars do not accept communication control to disable the ADAS ECU, -# responds with 0x7F2822 - 'conditions not correct' -CANFD_UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.CANFD_NO_RADAR_DISABLE) - -# The camera does SCC on these cars, rather than the radar -CAMERA_SCC_CAR = CAR.with_flags(HyundaiFlags.CAMERA_SCC) - -HYBRID_CAR = CAR.with_flags(HyundaiFlags.HYBRID) - -EV_CAR = CAR.with_flags(HyundaiFlags.EV) - -LEGACY_SAFETY_MODE_CAR = CAR.with_flags(HyundaiFlags.LEGACY) - -UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.LEGACY) | CAR.with_flags(HyundaiFlags.UNSUPPORTED_LONGITUDINAL) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py deleted file mode 100644 index a3572238bab5af6..000000000000000 --- a/selfdrive/car/interfaces.py +++ /dev/null @@ -1,540 +0,0 @@ -import json -import os -import numpy as np -import tomllib -from abc import abstractmethod, ABC -from enum import StrEnum -from typing import Any, NamedTuple -from collections.abc import Callable -from functools import cache - -from cereal import car -from openpilot.common.basedir import BASEDIR -from openpilot.common.conversions import Conversions as CV -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 -from openpilot.selfdrive.car.values import PLATFORMS -from openpilot.selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, get_friction -from openpilot.selfdrive.controls.lib.events import Events -from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel - -ButtonType = car.CarState.ButtonEvent.Type -GearShifter = car.CarState.GearShifter -EventName = car.CarEvent.EventName - -MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS -ACCEL_MAX = 2.0 -ACCEL_MIN = -3.5 -FRICTION_THRESHOLD = 0.3 - -TORQUE_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/params.toml') -TORQUE_OVERRIDE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/override.toml') -TORQUE_SUBSTITUTE_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/substitute.toml') - -GEAR_SHIFTER_MAP: dict[str, car.CarState.GearShifter] = { - 'P': GearShifter.park, 'PARK': GearShifter.park, - 'R': GearShifter.reverse, 'REVERSE': GearShifter.reverse, - 'N': GearShifter.neutral, 'NEUTRAL': GearShifter.neutral, - 'E': GearShifter.eco, 'ECO': GearShifter.eco, - 'T': GearShifter.manumatic, 'MANUAL': GearShifter.manumatic, - 'D': GearShifter.drive, 'DRIVE': GearShifter.drive, - 'S': GearShifter.sport, 'SPORT': GearShifter.sport, - 'L': GearShifter.low, 'LOW': GearShifter.low, - 'B': GearShifter.brake, 'BRAKE': GearShifter.brake, -} - - -class LatControlInputs(NamedTuple): - lateral_acceleration: float - roll_compensation: float - vego: float - aego: float - - -TorqueFromLateralAccelCallbackType = Callable[[LatControlInputs, car.CarParams.LateralTorqueTuning, float, float, bool, bool], float] - - -@cache -def get_torque_params(): - with open(TORQUE_SUBSTITUTE_PATH, 'rb') as f: - sub = tomllib.load(f) - with open(TORQUE_PARAMS_PATH, 'rb') as f: - params = tomllib.load(f) - with open(TORQUE_OVERRIDE_PATH, 'rb') as f: - override = tomllib.load(f) - - torque_params = {} - for candidate in (sub.keys() | params.keys() | override.keys()) - {'legend'}: - if sum([candidate in x for x in [sub, params, override]]) > 1: - raise RuntimeError(f'{candidate} is defined twice in torque config') - - sub_candidate = sub.get(candidate, candidate) - - if sub_candidate in override: - out = override[sub_candidate] - elif sub_candidate in params: - out = params[sub_candidate] - else: - raise NotImplementedError(f"Did not find torque params for {sub_candidate}") - - torque_params[sub_candidate] = {key: out[i] for i, key in enumerate(params['legend'])} - if candidate in sub: - torque_params[candidate] = torque_params[sub_candidate] - - return torque_params - -# generic car and radar interfaces - -class CarInterfaceBase(ABC): - def __init__(self, CP, CarController, CarState): - self.CP = CP - self.VM = VehicleModel(CP) - - self.frame = 0 - self.steering_unpressed = 0 - self.low_speed_alert = False - self.no_steer_warning = False - self.silent_steer_warning = True - self.v_ego_cluster_seen = False - - self.CS = CarState(CP) - self.cp = self.CS.get_can_parser(CP) - self.cp_cam = self.CS.get_cam_can_parser(CP) - self.cp_adas = self.CS.get_adas_can_parser(CP) - self.cp_body = self.CS.get_body_can_parser(CP) - self.cp_loopback = self.CS.get_loopback_can_parser(CP) - self.can_parsers = [self.cp, self.cp_cam, self.cp_adas, self.cp_body, self.cp_loopback] - - dbc_name = "" if self.cp is None else self.cp.dbc_name - self.CC: CarControllerBase = CarController(dbc_name, CP, self.VM) - - def apply(self, c: car.CarControl, now_nanos: int) -> tuple[car.CarControl.Actuators, list[tuple[int, int, bytes, int]]]: - return self.CC.update(c, self.CS, now_nanos) - - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - return ACCEL_MIN, ACCEL_MAX - - @classmethod - def get_non_essential_params(cls, candidate: str): - """ - Parameters essential to controlling the car may be incomplete or wrong without FW versions or fingerprints. - """ - return cls.get_params(candidate, gen_empty_fingerprint(), list(), False, False) - - @classmethod - def get_params(cls, candidate: str, fingerprint: dict[int, dict[int, int]], car_fw: list[car.CarParams.CarFw], experimental_long: bool, docs: bool): - ret = CarInterfaceBase.get_std_params(candidate) - - platform = PLATFORMS[candidate] - ret.mass = platform.config.specs.mass - ret.wheelbase = platform.config.specs.wheelbase - ret.steerRatio = platform.config.specs.steerRatio - ret.centerToFront = ret.wheelbase * platform.config.specs.centerToFrontRatio - ret.minEnableSpeed = platform.config.specs.minEnableSpeed - ret.minSteerSpeed = platform.config.specs.minSteerSpeed - ret.tireStiffnessFactor = platform.config.specs.tireStiffnessFactor - ret.flags |= int(platform.config.flags) - - ret = cls._get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs) - - # Vehicle mass is published curb weight plus assumed payload such as a human driver; notCars have no assumed payload - if not ret.notCar: - ret.mass = ret.mass + STD_CARGO_KG - - # Set params dependent on values set by the car interface - ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) - ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront, ret.tireStiffnessFactor) - - return ret - - @staticmethod - @abstractmethod - def _get_params(ret: car.CarParams, candidate, fingerprint: dict[int, dict[int, int]], - car_fw: list[car.CarParams.CarFw], experimental_long: bool, docs: bool): - raise NotImplementedError - - @staticmethod - def init(CP, logcan, sendcan): - pass - - @staticmethod - def get_steer_feedforward_default(desired_angle, v_ego): - # Proportional to realigning tire momentum: lateral acceleration. - return desired_angle * (v_ego**2) - - def get_steer_feedforward_function(self): - return self.get_steer_feedforward_default - - def torque_from_lateral_accel_linear(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, - lateral_accel_error: float, lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: - # The default is a linear relationship between torque and lateral acceleration (accounting for road roll and steering friction) - friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - return (latcontrol_inputs.lateral_acceleration / float(torque_params.latAccelFactor)) + friction - - def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: - return self.torque_from_lateral_accel_linear - - # returns a set of default params to avoid repetition in car specific params - @staticmethod - def get_std_params(candidate): - ret = car.CarParams.new_message() - ret.carFingerprint = candidate - - # Car docs fields - ret.maxLateralAccel = get_torque_params()[candidate]['MAX_LAT_ACCEL_MEASURED'] - ret.autoResumeSng = True # describes whether car can resume from a stop automatically - - # standard ALC params - ret.tireStiffnessFactor = 1.0 - ret.steerControlType = car.CarParams.SteerControlType.torque - ret.minSteerSpeed = 0. - ret.wheelSpeedFactor = 1.0 - - ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars - ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this - ret.steerRatioRear = 0. # no rear steering, at least on the listed cars aboveA - ret.openpilotLongitudinalControl = False - ret.stopAccel = -2.0 - ret.stoppingDecelRate = 0.8 # brake_travel/s while trying to stop - ret.vEgoStopping = 0.5 - ret.vEgoStarting = 0.5 - ret.stoppingControl = True - ret.longitudinalTuning.deadzoneBP = [0.] - ret.longitudinalTuning.deadzoneV = [0.] - ret.longitudinalTuning.kf = 1. - ret.longitudinalTuning.kpBP = [0.] - ret.longitudinalTuning.kpV = [1.] - ret.longitudinalTuning.kiBP = [0.] - ret.longitudinalTuning.kiV = [1.] - # TODO estimate car specific lag, use .15s for now - ret.longitudinalActuatorDelayLowerBound = 0.15 - ret.longitudinalActuatorDelayUpperBound = 0.15 - ret.steerLimitTimer = 1.0 - return ret - - @staticmethod - def configure_torque_tune(candidate, tune, steering_angle_deadzone_deg=0.0, use_steering_angle=True): - params = get_torque_params()[candidate] - - tune.init('torque') - tune.torque.useSteeringAngle = use_steering_angle - tune.torque.kp = 1.0 - tune.torque.kf = 1.0 - tune.torque.ki = 0.1 - tune.torque.friction = params['FRICTION'] - tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR'] - tune.torque.latAccelOffset = 0.0 - tune.torque.steeringAngleDeadzoneDeg = steering_angle_deadzone_deg - - @abstractmethod - def _update(self, c: car.CarControl) -> car.CarState: - pass - - def update(self, c: car.CarControl, can_strings: list[bytes]) -> car.CarState: - # parse can - for cp in self.can_parsers: - if cp is not None: - cp.update_strings(can_strings) - - # get CarState - ret = self._update(c) - - ret.canValid = all(cp.can_valid for cp in self.can_parsers if cp is not None) - ret.canTimeout = any(cp.bus_timeout for cp in self.can_parsers if cp is not None) - - if ret.vEgoCluster == 0.0 and not self.v_ego_cluster_seen: - ret.vEgoCluster = ret.vEgo - else: - self.v_ego_cluster_seen = True - - # Many cars apply hysteresis to the ego dash speed - if self.CS is not None: - ret.vEgoCluster = apply_hysteresis(ret.vEgoCluster, self.CS.out.vEgoCluster, self.CS.cluster_speed_hyst_gap) - if abs(ret.vEgo) < self.CS.cluster_min_speed: - ret.vEgoCluster = 0.0 - - if ret.cruiseState.speedCluster == 0: - ret.cruiseState.speedCluster = ret.cruiseState.speed - - # copy back for next iteration - if self.CS is not None: - self.CS.out = ret.as_reader() - - return ret - - - def create_common_events(self, cs_out, extra_gears=None, pcm_enable=True, allow_enable=True, - enable_buttons=(ButtonType.accelCruise, ButtonType.decelCruise)): - events = Events() - - if cs_out.doorOpen: - events.add(EventName.doorOpen) - if cs_out.seatbeltUnlatched: - events.add(EventName.seatbeltNotLatched) - if cs_out.gearShifter != GearShifter.drive and (extra_gears is None or - cs_out.gearShifter not in extra_gears): - events.add(EventName.wrongGear) - if cs_out.gearShifter == GearShifter.reverse: - events.add(EventName.reverseGear) - if not cs_out.cruiseState.available: - events.add(EventName.wrongCarMode) - if cs_out.espDisabled: - events.add(EventName.espDisabled) - if cs_out.stockFcw: - events.add(EventName.stockFcw) - if cs_out.stockAeb: - events.add(EventName.stockAeb) - if cs_out.vEgo > MAX_CTRL_SPEED: - events.add(EventName.speedTooHigh) - if cs_out.cruiseState.nonAdaptive: - events.add(EventName.wrongCruiseMode) - if cs_out.brakeHoldActive and self.CP.openpilotLongitudinalControl: - events.add(EventName.brakeHold) - if cs_out.parkingBrake: - events.add(EventName.parkBrake) - if cs_out.accFaulted: - events.add(EventName.accFaulted) - if cs_out.steeringPressed: - events.add(EventName.steerOverride) - if cs_out.brakePressed and cs_out.standstill: - events.add(EventName.preEnableStandstill) - if cs_out.gasPressed: - events.add(EventName.gasPressedOverride) - - # Handle button presses - for b in cs_out.buttonEvents: - # Enable OP long on falling edge of enable buttons (defaults to accelCruise and decelCruise, overridable per-port) - if not self.CP.pcmCruise and (b.type in enable_buttons and not b.pressed): - events.add(EventName.buttonEnable) - # Disable on rising and falling edge of cancel for both stock and OP long - if b.type == ButtonType.cancel: - events.add(EventName.buttonCancel) - - # Handle permanent and temporary steering faults - self.steering_unpressed = 0 if cs_out.steeringPressed else self.steering_unpressed + 1 - if cs_out.steerFaultTemporary: - if cs_out.steeringPressed and (not self.CS.out.steerFaultTemporary or self.no_steer_warning): - self.no_steer_warning = True - else: - self.no_steer_warning = False - - # if the user overrode recently, show a less harsh alert - if self.silent_steer_warning or cs_out.standstill or self.steering_unpressed < int(1.5 / DT_CTRL): - self.silent_steer_warning = True - events.add(EventName.steerTempUnavailableSilent) - else: - events.add(EventName.steerTempUnavailable) - else: - self.no_steer_warning = False - self.silent_steer_warning = False - if cs_out.steerFaultPermanent: - events.add(EventName.steerUnavailable) - - # we engage when pcm is active (rising edge) - # enabling can optionally be blocked by the car interface - if pcm_enable: - if cs_out.cruiseState.enabled and not self.CS.out.cruiseState.enabled and allow_enable: - events.add(EventName.pcmEnable) - elif not cs_out.cruiseState.enabled: - events.add(EventName.pcmDisable) - - return events - - -class RadarInterfaceBase(ABC): - def __init__(self, CP): - self.rcp = None - self.pts = {} - self.delay = 0 - self.radar_ts = CP.radarTimeStep - self.frame = 0 - - def update(self, can_strings): - self.frame += 1 - if (self.frame % int(100 * self.radar_ts)) == 0: - return car.RadarData.new_message() - return None - - -class CarStateBase(ABC): - def __init__(self, CP): - self.CP = CP - self.car_fingerprint = CP.carFingerprint - self.out = car.CarState.new_message() - - self.cruise_buttons = 0 - self.left_blinker_cnt = 0 - self.right_blinker_cnt = 0 - self.steering_pressed_cnt = 0 - self.left_blinker_prev = False - self.right_blinker_prev = False - self.cluster_speed_hyst_gap = 0.0 - self.cluster_min_speed = 0.0 # min speed before dropping to 0 - - Q = [[0.0, 0.0], [0.0, 100.0]] - R = 0.3 - A = [[1.0, DT_CTRL], [0.0, 1.0]] - C = [[1.0, 0.0]] - x0=[[0.0], [0.0]] - K = get_kalman_gain(DT_CTRL, np.array(A), np.array(C), np.array(Q), R) - self.v_ego_kf = KF1D(x0=x0, A=A, C=C[0], K=K) - - def update_speed_kf(self, v_ego_raw): - if abs(v_ego_raw - self.v_ego_kf.x[0][0]) > 2.0: # Prevent large accelerations when car starts at non zero speed - self.v_ego_kf.set_x([[v_ego_raw], [0.0]]) - - v_ego_x = self.v_ego_kf.update(v_ego_raw) - return float(v_ego_x[0]), float(v_ego_x[1]) - - def get_wheel_speeds(self, fl, fr, rl, rr, unit=CV.KPH_TO_MS): - factor = unit * self.CP.wheelSpeedFactor - - wheelSpeeds = car.CarState.WheelSpeeds.new_message() - wheelSpeeds.fl = fl * factor - wheelSpeeds.fr = fr * factor - wheelSpeeds.rl = rl * factor - wheelSpeeds.rr = rr * factor - return wheelSpeeds - - def update_blinker_from_lamp(self, blinker_time: int, left_blinker_lamp: bool, right_blinker_lamp: bool): - """Update blinkers from lights. Enable output when light was seen within the last `blinker_time` - iterations""" - # TODO: Handle case when switching direction. Now both blinkers can be on at the same time - self.left_blinker_cnt = blinker_time if left_blinker_lamp else max(self.left_blinker_cnt - 1, 0) - self.right_blinker_cnt = blinker_time if right_blinker_lamp else max(self.right_blinker_cnt - 1, 0) - return self.left_blinker_cnt > 0, self.right_blinker_cnt > 0 - - def update_steering_pressed(self, steering_pressed, steering_pressed_min_count): - """Applies filtering on steering pressed for noisy driver torque signals.""" - self.steering_pressed_cnt += 1 if steering_pressed else -1 - self.steering_pressed_cnt = clip(self.steering_pressed_cnt, 0, steering_pressed_min_count * 2) - return self.steering_pressed_cnt > steering_pressed_min_count - - def update_blinker_from_stalk(self, blinker_time: int, left_blinker_stalk: bool, right_blinker_stalk: bool): - """Update blinkers from stalk position. When stalk is seen the blinker will be on for at least blinker_time, - or until the stalk is turned off, whichever is longer. If the opposite stalk direction is seen the blinker - is forced to the other side. On a rising edge of the stalk the timeout is reset.""" - - if left_blinker_stalk: - self.right_blinker_cnt = 0 - if not self.left_blinker_prev: - self.left_blinker_cnt = blinker_time - - if right_blinker_stalk: - self.left_blinker_cnt = 0 - if not self.right_blinker_prev: - self.right_blinker_cnt = blinker_time - - self.left_blinker_cnt = max(self.left_blinker_cnt - 1, 0) - self.right_blinker_cnt = max(self.right_blinker_cnt - 1, 0) - - self.left_blinker_prev = left_blinker_stalk - self.right_blinker_prev = right_blinker_stalk - - return bool(left_blinker_stalk or self.left_blinker_cnt > 0), bool(right_blinker_stalk or self.right_blinker_cnt > 0) - - @staticmethod - def parse_gear_shifter(gear: str | None) -> car.CarState.GearShifter: - if gear is None: - return GearShifter.unknown - return GEAR_SHIFTER_MAP.get(gear.upper(), GearShifter.unknown) - - @staticmethod - def get_can_parser(CP): - return None - - @staticmethod - def get_cam_can_parser(CP): - return None - - @staticmethod - def get_adas_can_parser(CP): - return None - - @staticmethod - def get_body_can_parser(CP): - return None - - @staticmethod - def get_loopback_can_parser(CP): - return None - - -SendCan = tuple[int, int, bytes, int] - - -class CarControllerBase(ABC): - def __init__(self, dbc_name: str, CP, VM): - pass - - @abstractmethod - def update(self, CC: car.CarControl.Actuators, CS: car.CarState, now_nanos: int) -> tuple[car.CarControl.Actuators, list[SendCan]]: - pass - - -INTERFACE_ATTR_FILE = { - "FINGERPRINTS": "fingerprints", - "FW_VERSIONS": "fingerprints", -} - -# interface-specific helpers - -def get_interface_attr(attr: str, combine_brands: bool = False, ignore_none: bool = False) -> dict[str | StrEnum, Any]: - # read all the folders in selfdrive/car and return a dict where: - # - keys are all the car models or brand names - # - values are attr values from all car folders - result = {} - for car_folder in sorted([x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]): - try: - brand_name = car_folder.split('/')[-1] - brand_values = __import__(f'openpilot.selfdrive.car.{brand_name}.{INTERFACE_ATTR_FILE.get(attr, "values")}', fromlist=[attr]) - if hasattr(brand_values, attr) or not ignore_none: - attr_data = getattr(brand_values, attr, None) - else: - continue - - if combine_brands: - if isinstance(attr_data, dict): - for f, v in attr_data.items(): - result[f] = v - else: - result[brand_name] = attr_data - except (ImportError, OSError): - pass - - return result - - -class NanoFFModel: - def __init__(self, weights_loc: str, platform: str): - self.weights_loc = weights_loc - self.platform = platform - self.load_weights(platform) - - def load_weights(self, platform: str): - with open(self.weights_loc) as fob: - self.weights = {k: np.array(v) for k, v in json.load(fob)[platform].items()} - - def relu(self, x: np.ndarray): - return np.maximum(0.0, x) - - def forward(self, x: np.ndarray): - assert x.ndim == 1 - x = (x - self.weights['input_norm_mat'][:, 0]) / (self.weights['input_norm_mat'][:, 1] - self.weights['input_norm_mat'][:, 0]) - x = self.relu(np.dot(x, self.weights['w_1']) + self.weights['b_1']) - x = self.relu(np.dot(x, self.weights['w_2']) + self.weights['b_2']) - x = self.relu(np.dot(x, self.weights['w_3']) + self.weights['b_3']) - x = np.dot(x, self.weights['w_4']) + self.weights['b_4'] - return x - - def predict(self, x: list[float], do_sample: bool = False): - x = self.forward(np.array(x)) - if do_sample: - pred = np.random.laplace(x[0], np.exp(x[1]) / self.weights['temperature']) - else: - pred = x[0] - pred = pred * (self.weights['output_norm_mat'][1] - self.weights['output_norm_mat'][0]) + self.weights['output_norm_mat'][0] - return pred diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py deleted file mode 100644 index 447c7093c5b4fc8..000000000000000 --- a/selfdrive/car/isotp_parallel_query.py +++ /dev/null @@ -1,173 +0,0 @@ -import time -from collections import defaultdict -from functools import partial - -import cereal.messaging as messaging -from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.pandad 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: 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, debug: bool = False, response_pending_timeout: float = 10) -> None: - self.sendcan = sendcan - self.logcan = logcan - self.bus = bus - self.request = request - self.response = response - self.functional_addrs = functional_addrs or [] - self.debug = debug - self.response_pending_timeout = response_pending_timeout - - real_addrs = [a if isinstance(a, tuple) else (a, None) for a in addrs] - for tx_addr, _ in real_addrs: - assert tx_addr not in FUNCTIONAL_ADDRS, f"Functional address should be defined in functional_addrs: {hex(tx_addr)}" - - self.msg_addrs = {tx_addr: get_rx_addr_for_tx_addr(tx_addr[0], rx_offset=response_offset) for tx_addr in real_addrs} - self.msg_buffer: dict[int, list[tuple[int, int, bytes, int]]] = defaultdict(list) - - def rx(self): - """Drain can socket and sort messages into buffers based on address""" - can_packets = messaging.drain_sock(self.logcan, wait_for_one=True) - - for packet in can_packets: - for msg in packet.can: - if msg.src == self.bus and msg.address in self.msg_addrs.values(): - self.msg_buffer[msg.address].append((msg.address, msg.busTime, msg.dat, msg.src)) - - def _can_tx(self, tx_addr, dat, bus): - """Helper function to send single message""" - msg = [tx_addr, 0, dat, bus] - self.sendcan.send(can_list_to_can_capnp([msg], msgtype='sendcan')) - - def _can_rx(self, addr, sub_addr=None): - """Helper function to retrieve message with specified address and subadress from buffer""" - keep_msgs = [] - - if sub_addr is None: - msgs = self.msg_buffer[addr] - else: - # Filter based on subadress - msgs = [] - for m in self.msg_buffer[addr]: - first_byte = m[2][0] - if first_byte == sub_addr: - msgs.append(m) - else: - keep_msgs.append(m) - - self.msg_buffer[addr] = keep_msgs - return msgs - - def _drain_rx(self): - messaging.drain_sock_raw(self.logcan) - self.msg_buffer = defaultdict(list) - - def _create_isotp_msg(self, tx_addr: int, sub_addr: int | None, rx_addr: int): - can_client = CanClient(self._can_tx, partial(self._can_rx, rx_addr, sub_addr=sub_addr), tx_addr, rx_addr, - self.bus, sub_addr=sub_addr, debug=self.debug) - - max_len = 8 if sub_addr is None else 7 - # uses iso-tp frame separation time of 10 ms - # TODO: use single_frame_mode so ECUs can send as fast as they want, - # as well as reduces chances we process messages from previous queries - return IsoTpMessage(can_client, timeout=0, separation_time=0.01, debug=self.debug, max_len=max_len) - - def get_data(self, timeout: float, total_timeout: float = 60.) -> dict[AddrType, bytes]: - self._drain_rx() - - # Create message objects - msgs = {} - request_counter = {} - request_done = {} - for tx_addr, rx_addr in self.msg_addrs.items(): - msgs[tx_addr] = self._create_isotp_msg(*tx_addr, rx_addr) - request_counter[tx_addr] = 0 - request_done[tx_addr] = False - - # Send first request to functional addrs, subsequent responses are handled on physical addrs - if len(self.functional_addrs): - for addr in self.functional_addrs: - self._create_isotp_msg(addr, None, -1).send(self.request[0]) - - # Send first frame (single or first) to all addresses and receive asynchronously in the loop below. - # If querying functional addrs, only set up physical IsoTpMessages to send consecutive frames - for msg in msgs.values(): - msg.send(self.request[0], setup_only=len(self.functional_addrs) > 0) - - results = {} - start_time = time.monotonic() - addrs_responded = set() # track addresses that have ever sent a valid iso-tp frame for timeout logging - response_timeouts = {tx_addr: start_time + timeout for tx_addr in self.msg_addrs} - while True: - self.rx() - - for tx_addr, msg in msgs.items(): - try: - dat, rx_in_progress = msg.recv() - except Exception: - cloudlog.exception(f"Error processing UDS response: {tx_addr}") - request_done[tx_addr] = True - continue - - # Extend timeout for each consecutive ISO-TP frame to avoid timing out on long responses - if rx_in_progress: - addrs_responded.add(tx_addr) - response_timeouts[tx_addr] = time.monotonic() + timeout - - if dat is None: - continue - - # Log unexpected empty responses - if len(dat) == 0: - cloudlog.error(f"iso-tp query empty response: {tx_addr}") - request_done[tx_addr] = True - continue - - counter = request_counter[tx_addr] - expected_response = self.response[counter] - response_valid = dat.startswith(expected_response) - - if response_valid: - if counter + 1 < len(self.request): - response_timeouts[tx_addr] = time.monotonic() + timeout - msg.send(self.request[counter + 1]) - request_counter[tx_addr] += 1 - else: - results[tx_addr] = dat[len(expected_response):] - request_done[tx_addr] = True - else: - error_code = dat[2] if len(dat) > 2 else -1 - if error_code == 0x78: - response_timeouts[tx_addr] = time.monotonic() + self.response_pending_timeout - cloudlog.error(f"iso-tp query response pending: {tx_addr}") - else: - request_done[tx_addr] = True - cloudlog.error(f"iso-tp query bad response: {tx_addr} - 0x{dat.hex()}") - - # Mark request done if address timed out - cur_time = time.monotonic() - for tx_addr in response_timeouts: - if cur_time - response_timeouts[tx_addr] > 0: - if not request_done[tx_addr]: - if request_counter[tx_addr] > 0: - cloudlog.error(f"iso-tp query timeout after receiving partial response: {tx_addr}") - elif tx_addr in addrs_responded: - cloudlog.error(f"iso-tp query timeout while receiving response: {tx_addr}") - # TODO: handle functional addresses - # else: - # cloudlog.error(f"iso-tp query timeout with no response: {tx_addr}") - request_done[tx_addr] = True - - # Break if all requests are done (finished or timed out) - if all(request_done.values()): - break - - if cur_time - start_time > total_timeout: - cloudlog.error("iso-tp query timeout while receiving data") - break - - return results diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py deleted file mode 100644 index 3d41634879051ac..000000000000000 --- a/selfdrive/car/mazda/carcontroller.py +++ /dev/null @@ -1,66 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.mazda import mazdacan -from openpilot.selfdrive.car.mazda.values import CarControllerParams, Buttons - -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.apply_steer_last = 0 - self.packer = CANPacker(dbc_name) - self.brake_counter = 0 - self.frame = 0 - - def update(self, CC, CS, now_nanos): - can_sends = [] - - apply_steer = 0 - - if CC.latActive: - # calculate steer and also set limits due to driver torque - new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, - CS.out.steeringTorque, CarControllerParams) - - if CC.cruiseControl.cancel: - # If brake is pressed, let us wait >70ms before trying to disable crz to avoid - # a race condition with the stock system, where the second cancel from openpilot - # will disable the crz 'main on'. crz ctrl msg runs at 50hz. 70ms allows us to - # read 3 messages and most likely sync state before we attempt cancel. - self.brake_counter = self.brake_counter + 1 - if self.frame % 10 == 0 and not (CS.out.brakePressed and self.brake_counter < 7): - # Cancel Stock ACC if it's enabled while OP is disengaged - # Send at a rate of 10hz until we sync with stock ACC state - can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.CANCEL)) - else: - self.brake_counter = 0 - if CC.cruiseControl.resume and self.frame % 5 == 0: - # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds - # Send Resume button when planner wants car to move - can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.RESUME)) - - self.apply_steer_last = apply_steer - - # send HUD alerts - if self.frame % 50 == 0: - ldw = CC.hudControl.visualAlert == VisualAlert.ldw - steer_required = CC.hudControl.visualAlert == VisualAlert.steerRequired - # TODO: find a way to silence audible warnings so we can add more hud alerts - steer_required = steer_required and CS.lkas_allowed_speed - can_sends.append(mazdacan.create_alert_command(self.packer, CS.cam_laneinfo, ldw, steer_required)) - - # send steering command - can_sends.append(mazdacan.create_steering_control(self.packer, self.CP, - self.frame, apply_steer, CS.cam_lkas)) - - new_actuators = CC.actuators.as_builder() - new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX - new_actuators.steerOutputCan = apply_steer - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py deleted file mode 100644 index 83b238fb6831ed5..000000000000000 --- a/selfdrive/car/mazda/carstate.py +++ /dev/null @@ -1,153 +0,0 @@ -from cereal import car -from openpilot.common.conversions import Conversions as CV -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.mazda.values import DBC, LKAS_LIMITS, MazdaFlags - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["GEAR"]["GEAR"] - - self.crz_btns_counter = 0 - self.acc_active_last = False - self.low_speed_alert = False - self.lkas_allowed_speed = False - self.lkas_disabled = False - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRZ_BTNS"]["DISTANCE_LESS"] - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["FL"], - cp.vl["WHEEL_SPEEDS"]["FR"], - cp.vl["WHEEL_SPEEDS"]["RL"], - cp.vl["WHEEL_SPEEDS"]["RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - - # Match panda speed reading - speed_kph = cp.vl["ENGINE_DATA"]["SPEED"] - ret.standstill = speed_kph <= .1 - - can_gear = int(cp.vl["GEAR"]["GEAR"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - ret.genericToggle = bool(cp.vl["BLINK_INFO"]["HIGH_BEAMS"]) - ret.leftBlindspot = cp.vl["BSM"]["LEFT_BS_STATUS"] != 0 - ret.rightBlindspot = cp.vl["BSM"]["RIGHT_BS_STATUS"] != 0 - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(40, cp.vl["BLINK_INFO"]["LEFT_BLINK"] == 1, - cp.vl["BLINK_INFO"]["RIGHT_BLINK"] == 1) - - ret.steeringAngleDeg = cp.vl["STEER"]["STEER_ANGLE"] - ret.steeringTorque = cp.vl["STEER_TORQUE"]["STEER_TORQUE_SENSOR"] - ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD - - ret.steeringTorqueEps = cp.vl["STEER_TORQUE"]["STEER_TORQUE_MOTOR"] - ret.steeringRateDeg = cp.vl["STEER_RATE"]["STEER_ANGLE_RATE"] - - # TODO: this should be from 0 - 1. - ret.brakePressed = cp.vl["PEDALS"]["BRAKE_ON"] == 1 - ret.brake = cp.vl["BRAKE"]["BRAKE_PRESSURE"] - - ret.seatbeltUnlatched = cp.vl["SEATBELT"]["DRIVER_SEATBELT"] == 0 - ret.doorOpen = any([cp.vl["DOORS"]["FL"], cp.vl["DOORS"]["FR"], - cp.vl["DOORS"]["BL"], cp.vl["DOORS"]["BR"]]) - - # TODO: this should be from 0 - 1. - ret.gas = cp.vl["ENGINE_DATA"]["PEDAL_GAS"] - ret.gasPressed = ret.gas > 0 - - # Either due to low speed or hands off - lkas_blocked = cp.vl["STEER_RATE"]["LKAS_BLOCK"] == 1 - - if self.CP.minSteerSpeed > 0: - # LKAS is enabled at 52kph going up and disabled at 45kph going down - # wait for LKAS_BLOCK signal to clear when going up since it lags behind the speed sometimes - if speed_kph > LKAS_LIMITS.ENABLE_SPEED and not lkas_blocked: - self.lkas_allowed_speed = True - elif speed_kph < LKAS_LIMITS.DISABLE_SPEED: - self.lkas_allowed_speed = False - else: - self.lkas_allowed_speed = True - - # TODO: the signal used for available seems to be the adaptive cruise signal, instead of the main on - # it should be used for carState.cruiseState.nonAdaptive instead - ret.cruiseState.available = cp.vl["CRZ_CTRL"]["CRZ_AVAILABLE"] == 1 - ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]["CRZ_ACTIVE"] == 1 - ret.cruiseState.standstill = cp.vl["PEDALS"]["STANDSTILL"] == 1 - ret.cruiseState.speed = cp.vl["CRZ_EVENTS"]["CRZ_SPEED"] * CV.KPH_TO_MS - - if ret.cruiseState.enabled: - if not self.lkas_allowed_speed and self.acc_active_last: - self.low_speed_alert = True - else: - self.low_speed_alert = False - - # Check if LKAS is disabled due to lack of driver torque when all other states indicate - # it should be enabled (steer lockout). Don't warn until we actually get lkas active - # and lose it again, i.e, after initial lkas activation - ret.steerFaultTemporary = self.lkas_allowed_speed and lkas_blocked - - self.acc_active_last = ret.cruiseState.enabled - - self.crz_btns_counter = cp.vl["CRZ_BTNS"]["CTR"] - - # camera signals - self.lkas_disabled = cp_cam.vl["CAM_LANEINFO"]["LANE_LINES"] == 0 - self.cam_lkas = cp_cam.vl["CAM_LKAS"] - self.cam_laneinfo = cp_cam.vl["CAM_LANEINFO"] - ret.steerFaultPermanent = cp_cam.vl["CAM_LKAS"]["ERR_BIT_1"] == 1 - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("BLINK_INFO", 10), - ("STEER", 67), - ("STEER_RATE", 83), - ("STEER_TORQUE", 83), - ("WHEEL_SPEEDS", 100), - ] - - if CP.flags & MazdaFlags.GEN1: - messages += [ - ("ENGINE_DATA", 100), - ("CRZ_CTRL", 50), - ("CRZ_EVENTS", 50), - ("CRZ_BTNS", 10), - ("PEDALS", 50), - ("BRAKE", 50), - ("SEATBELT", 10), - ("DOORS", 10), - ("GEAR", 20), - ("BSM", 10), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - - if CP.flags & MazdaFlags.GEN1: - messages += [ - # sig_address, frequency - ("CAM_LANEINFO", 2), - ("CAM_LKAS", 16), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/mazda/fingerprints.py b/selfdrive/car/mazda/fingerprints.py deleted file mode 100644 index f460fe9950b0c83..000000000000000 --- a/selfdrive/car/mazda/fingerprints.py +++ /dev/null @@ -1,265 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.mazda.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.MAZDA_CX5_2022: { - (Ecu.eps, 0x730, None): [ - b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PEW5-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PW67-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2D-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'KGWD-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PG69-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PW66-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYJ3-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX5: { - (Ecu.eps, 0x730, None): [ - b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KCB8-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PA53-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PAR4-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2E-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2F-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2K-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFA-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SHKT-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PA66-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX39-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX9: { - (Ecu.eps, 0x730, None): [ - b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXN8-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PXM4-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD6-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_3: { - (Ecu.eps, 0x730, None): [ - b'BHN1-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYJW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-Q\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PY2S-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKA-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_6: { - (Ecu.eps, 0x730, None): [ - b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GBEF-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GFBC-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PA34-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX4F-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GBVH-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GDDM-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PA28-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH3-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX9_2021: { - (Ecu.eps, 0x730, None): [ - b'TC3M-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PXGW-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXGW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, -} diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py deleted file mode 100755 index 6992d49ffe58a64..000000000000000 --- a/selfdrive/car/mazda/interface.py +++ /dev/null @@ -1,50 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.mazda.values import CAR, LKAS_LIMITS -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "mazda" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.mazda)] - ret.radarUnavailable = True - - ret.dashcamOnly = candidate not in (CAR.MAZDA_CX5_2022, CAR.MAZDA_CX9_2021) - - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.8 - - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate not in (CAR.MAZDA_CX5_2022, ): - ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS - - ret.centerToFront = ret.wheelbase * 0.41 - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - # TODO: add button types for inc and dec - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - # events - events = self.create_common_events(ret) - - if self.CS.lkas_disabled: - events.add(EventName.lkasDisabled) - elif self.CS.low_speed_alert: - events.add(EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/mazda/radar_interface.py b/selfdrive/car/mazda/radar_interface.py deleted file mode 100755 index b461fcd5f84062a..000000000000000 --- a/selfdrive/car/mazda/radar_interface.py +++ /dev/null @@ -1,5 +0,0 @@ -#!/usr/bin/env python3 -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py deleted file mode 100644 index a8c808d5824e22d..000000000000000 --- a/selfdrive/car/mazda/values.py +++ /dev/null @@ -1,104 +0,0 @@ -from dataclasses import dataclass, field -from enum import IntFlag - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -# Steer torque limits - -class CarControllerParams: - STEER_MAX = 800 # theoretical max_steer 2047 - STEER_DELTA_UP = 10 # torque increase per refresh - STEER_DELTA_DOWN = 25 # torque decrease per refresh - STEER_DRIVER_ALLOWANCE = 15 # allowed driver torque before start limiting - STEER_DRIVER_MULTIPLIER = 1 # weight driver torque - STEER_DRIVER_FACTOR = 1 # from dbc - STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor - STEER_STEP = 1 # 100 Hz - - def __init__(self, CP): - pass - - -@dataclass -class MazdaCarDocs(CarDocs): - package: str = "All" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.mazda])) - - -@dataclass(frozen=True, kw_only=True) -class MazdaCarSpecs(CarSpecs): - tireStiffnessFactor: float = 0.7 # not optimized yet - - -class MazdaFlags(IntFlag): - # Static flags - # Gen 1 hardware: same CAN messages and same camera - GEN1 = 1 - - -@dataclass -class MazdaPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('mazda_2017', None)) - flags: int = MazdaFlags.GEN1 - - -class CAR(Platforms): - MAZDA_CX5 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-5 2017-21")], - MazdaCarSpecs(mass=3655 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.5) - ) - MAZDA_CX9 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-9 2016-20")], - MazdaCarSpecs(mass=4217 * CV.LB_TO_KG, wheelbase=3.1, steerRatio=17.6) - ) - MAZDA_3 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda 3 2017-18")], - MazdaCarSpecs(mass=2875 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=14.0) - ) - MAZDA_6 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda 6 2017-20")], - MazdaCarSpecs(mass=3443 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=15.5) - ) - MAZDA_CX9_2021 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-9 2021-23", video_link="https://youtu.be/dA3duO4a0O4")], - MAZDA_CX9.specs - ) - MAZDA_CX5_2022 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-5 2022-24")], - MAZDA_CX5.specs, - ) - - -class LKAS_LIMITS: - STEER_THRESHOLD = 15 - DISABLE_SPEED = 45 # kph - ENABLE_SPEED = 52 # kph - - -class Buttons: - NONE = 0 - SET_PLUS = 1 - SET_MINUS = 2 - RESUME = 3 - CANCEL = 4 - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # TODO: check data to ensure ABS does not skip ISO-TP frames on bus 0 - Request( - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - bus=0, - ), - ], -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/mock/carcontroller.py b/selfdrive/car/mock/carcontroller.py deleted file mode 100644 index 0cd37c03695d53e..000000000000000 --- a/selfdrive/car/mock/carcontroller.py +++ /dev/null @@ -1,5 +0,0 @@ -from openpilot.selfdrive.car.interfaces import CarControllerBase - -class CarController(CarControllerBase): - def update(self, CC, CS, now_nanos): - return CC.actuators.as_builder(), [] diff --git a/selfdrive/car/mock/carstate.py b/selfdrive/car/mock/carstate.py deleted file mode 100644 index ece908b51c522f5..000000000000000 --- a/selfdrive/car/mock/carstate.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import CarStateBase - -class CarState(CarStateBase): - pass diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py deleted file mode 100755 index 7506bab053601f0..000000000000000 --- a/selfdrive/car/mock/interface.py +++ /dev/null @@ -1,32 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -import cereal.messaging as messaging -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -# mocked car interface for dashcam mode -class CarInterface(CarInterfaceBase): - def __init__(self, CP, CarController, CarState): - super().__init__(CP, CarController, CarState) - - self.speed = 0. - self.sm = messaging.SubMaster(['gpsLocation', 'gpsLocationExternal']) - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "mock" - ret.mass = 1700. - ret.wheelbase = 2.70 - ret.centerToFront = ret.wheelbase * 0.5 - ret.steerRatio = 13. - ret.dashcamOnly = True - return ret - - def _update(self, c): - self.sm.update(0) - gps_sock = 'gpsLocationExternal' if self.sm.recv_frame['gpsLocationExternal'] > 1 else 'gpsLocation' - - ret = car.CarState.new_message() - ret.vEgo = self.sm[gps_sock].speed - ret.vEgoRaw = self.sm[gps_sock].speed - - return ret diff --git a/selfdrive/car/mock/radar_interface.py b/selfdrive/car/mock/radar_interface.py deleted file mode 100644 index e654bd61fd4afdc..000000000000000 --- a/selfdrive/car/mock/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/mock/values.py b/selfdrive/car/mock/values.py deleted file mode 100644 index f98aac2ee3c0edd..000000000000000 --- a/selfdrive/car/mock/values.py +++ /dev/null @@ -1,9 +0,0 @@ -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms - - -class CAR(Platforms): - MOCK = PlatformConfig( - [], - CarSpecs(mass=1700, wheelbase=2.7, steerRatio=13), - {} - ) diff --git a/selfdrive/car/nissan/carcontroller.py b/selfdrive/car/nissan/carcontroller.py deleted file mode 100644 index c7bd231398bcef7..000000000000000 --- a/selfdrive/car/nissan/carcontroller.py +++ /dev/null @@ -1,82 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.nissan import nissancan -from openpilot.selfdrive.car.nissan.values import CAR, CarControllerParams - -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.car_fingerprint = CP.carFingerprint - self.frame = 0 - - self.lkas_max_torque = 0 - self.apply_angle_last = 0 - - self.packer = CANPacker(dbc_name) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - ### STEER ### - steer_hud_alert = 1 if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) else 0 - - if CC.latActive: - # windup slower - apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgoRaw, CarControllerParams) - - # Max torque from driver before EPS will give up and not apply torque - if not bool(CS.out.steeringPressed): - self.lkas_max_torque = CarControllerParams.LKAS_MAX_TORQUE - else: - # Scale max torque based on how much torque the driver is applying to the wheel - self.lkas_max_torque = max( - # Scale max torque down to half LKAX_MAX_TORQUE as a minimum - CarControllerParams.LKAS_MAX_TORQUE * 0.5, - # Start scaling torque at STEER_THRESHOLD - CarControllerParams.LKAS_MAX_TORQUE - 0.6 * max(0, abs(CS.out.steeringTorque) - CarControllerParams.STEER_THRESHOLD) - ) - - else: - apply_angle = CS.out.steeringAngleDeg - self.lkas_max_torque = 0 - - self.apply_angle_last = apply_angle - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA) and pcm_cancel_cmd: - can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, self.car_fingerprint, CS.cruise_throttle_msg)) - - # TODO: Find better way to cancel! - # For some reason spamming the cancel button is unreliable on the Leaf - # We now cancel by making propilot think the seatbelt is unlatched, - # this generates a beep and a warning message every time you disengage - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC) and self.frame % 2 == 0: - can_sends.append(nissancan.create_cancel_msg(self.packer, CS.cancel_msg, pcm_cancel_cmd)) - - can_sends.append(nissancan.create_steering_control( - self.packer, apply_angle, self.frame, CC.latActive, self.lkas_max_torque)) - - # Below are the HUD messages. We copy the stock message and modify - if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: - if self.frame % 2 == 0: - can_sends.append(nissancan.create_lkas_hud_msg(self.packer, CS.lkas_hud_msg, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible, - hud_control.leftLaneDepart, hud_control.rightLaneDepart)) - - if self.frame % 50 == 0: - can_sends.append(nissancan.create_lkas_hud_info_msg( - self.packer, CS.lkas_hud_info_msg, steer_hud_alert - )) - - new_actuators = actuators.as_builder() - new_actuators.steeringAngleDeg = apply_angle - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py deleted file mode 100644 index 57146b49c49c6b9..000000000000000 --- a/selfdrive/car/nissan/carstate.py +++ /dev/null @@ -1,197 +0,0 @@ -import copy -from collections import deque -from cereal import car -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.common.conversions import Conversions as CV -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.nissan.values import CAR, DBC, CarControllerParams - -TORQUE_SAMPLES = 12 - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.lkas_hud_msg = {} - self.lkas_hud_info_msg = {} - - self.steeringTorqueSamples = deque(TORQUE_SAMPLES*[0], TORQUE_SAMPLES) - self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"] - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_adas, cp_cam): - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRUISE_THROTTLE"]["FOLLOW_DISTANCE_BUTTON"] - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"] - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - ret.gas = cp.vl["CRUISE_THROTTLE"]["GAS_PEDAL"] - - ret.gasPressed = bool(ret.gas > 3) - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - ret.brakePressed = bool(cp.vl["DOORS_LIGHTS"]["USER_BRAKE_PRESSED"]) - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - ret.brakePressed = bool(cp.vl["CRUISE_THROTTLE"]["USER_BRAKE_PRESSED"]) - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"] == 0.0 and cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"] == 0.0 - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.cruiseState.enabled = bool(cp.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) - else: - ret.cruiseState.enabled = bool(cp_adas.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): - ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 - ret.cruiseState.available = bool(cp_cam.vl["PRO_PILOT"]["CRUISE_ON"]) - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - if self.CP.carFingerprint == CAR.NISSAN_LEAF: - ret.seatbeltUnlatched = cp.vl["SEATBELT"]["SEATBELT_DRIVER_LATCHED"] == 0 - elif self.CP.carFingerprint == CAR.NISSAN_LEAF_IC: - ret.seatbeltUnlatched = cp.vl["CANCEL_MSG"]["CANCEL_SEATBELT"] == 1 - ret.cruiseState.available = bool(cp.vl["CRUISE_THROTTLE"]["CRUISE_AVAILABLE"]) - elif self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 - ret.cruiseState.available = bool(cp_adas.vl["PRO_PILOT"]["CRUISE_ON"]) - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - speed = cp.vl["PROPILOT_HUD"]["SET_SPEED"] - else: - speed = cp_adas.vl["PROPILOT_HUD"]["SET_SPEED"] - - if speed != 255: - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - conversion = CV.MPH_TO_MS if cp.vl["HUD_SETTINGS"]["SPEED_MPH"] else CV.KPH_TO_MS - else: - conversion = CV.MPH_TO_MS if cp.vl["HUD"]["SPEED_MPH"] else CV.KPH_TO_MS - ret.cruiseState.speed = speed * conversion - ret.cruiseState.speedCluster = (speed - 1) * conversion # Speed on HUD is always 1 lower than actually sent on can bus - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.steeringTorque = cp_cam.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - else: - ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - - self.steeringTorqueSamples.append(ret.steeringTorque) - # Filtering driver torque to prevent steeringPressed false positives - ret.steeringPressed = bool(abs(sum(self.steeringTorqueSamples) / TORQUE_SAMPLES) > CarControllerParams.STEER_THRESHOLD) - - ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] - - ret.leftBlinker = bool(cp.vl["LIGHTS"]["LEFT_BLINKER"]) - ret.rightBlinker = bool(cp.vl["LIGHTS"]["RIGHT_BLINKER"]) - - ret.doorOpen = any([cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RR"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RL"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FR"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FL"]]) - - ret.espDisabled = bool(cp.vl["ESP"]["ESP_DISABLED"]) - - can_gear = int(cp.vl["GEARBOX"]["GEAR_SHIFTER"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - self.lkas_enabled = bool(cp.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) - else: - self.lkas_enabled = bool(cp_adas.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) - - self.cruise_throttle_msg = copy.copy(cp.vl["CRUISE_THROTTLE"]) - - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - self.cancel_msg = copy.copy(cp.vl["CANCEL_MSG"]) - - if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: - self.lkas_hud_msg = copy.copy(cp_adas.vl["PROPILOT_HUD"]) - self.lkas_hud_info_msg = copy.copy(cp_adas.vl["PROPILOT_HUD_INFO_MSG"]) - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("STEER_ANGLE_SENSOR", 100), - ("WHEEL_SPEEDS_REAR", 50), - ("WHEEL_SPEEDS_FRONT", 50), - ("ESP", 25), - ("GEARBOX", 25), - ("DOORS_LIGHTS", 10), - ("LIGHTS", 10), - ] - - if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - messages += [ - ("GAS_PEDAL", 100), - ("CRUISE_THROTTLE", 50), - ("HUD", 25), - ] - - elif CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - messages += [ - ("BRAKE_PEDAL", 100), - ("CRUISE_THROTTLE", 50), - ("CANCEL_MSG", 50), - ("HUD_SETTINGS", 25), - ("SEATBELT", 10), - ] - - if CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages += [ - ("CRUISE_STATE", 10), - ("LKAS_SETTINGS", 10), - ("PROPILOT_HUD", 50), - ] - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) - - messages.append(("STEER_TORQUE_SENSOR", 100)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_adas_can_parser(CP): - # this function generates lists for signal, messages and initial values - - if CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages = [ - ("LKAS", 100), - ("PRO_PILOT", 100), - ] - else: - messages = [ - ("PROPILOT_HUD_INFO_MSG", 2), - ("LKAS_SETTINGS", 10), - ("CRUISE_STATE", 50), - ("PROPILOT_HUD", 50), - ("LKAS", 100), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - - if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): - messages.append(("PRO_PILOT", 100)) - elif CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages.append(("STEER_TORQUE_SENSOR", 100)) - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) diff --git a/selfdrive/car/nissan/fingerprints.py b/selfdrive/car/nissan/fingerprints.py deleted file mode 100644 index 743feeace9c6f37..000000000000000 --- a/selfdrive/car/nissan/fingerprints.py +++ /dev/null @@ -1,119 +0,0 @@ -# ruff: noqa: E501 -from cereal import car -from openpilot.selfdrive.car.nissan.values import CAR - -Ecu = car.CarParams.Ecu - -FINGERPRINTS = { - CAR.NISSAN_XTRAIL: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837: 8, 2015: 8, 2016: 8, 2024: 8 - }, - { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3, 1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 - }], - CAR.NISSAN_LEAF: [{ - 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8, 643: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8 - }, - { - 2: 5, 42: 8, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 976: 6, 1008: 7, 1009: 8, 1010: 8, 1011: 7, 1012: 8, 1013: 8, 1019: 8, 1020: 8, 1021: 8, 1022: 8, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1402: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8 - }], - CAR.NISSAN_LEAF_IC: [{ - 2: 5, 42: 6, 264: 3, 282: 8, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 756: 5, 758: 3, 761: 2, 783: 3, 830: 2, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 1001: 6, 1057: 3, 1227: 8, 1228: 8, 1229: 8, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1514: 6, 1549: 8, 1573: 6, 1792: 8, 1821: 8, 1822: 8, 1837: 8, 1838: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8 - }], - CAR.NISSAN_ROGUE: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 634: 7, 643: 5, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1042: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1534: 7, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1839: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], - CAR.NISSAN_ALTIMA: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], -} - -FW_VERSIONS = { - CAR.NISSAN_ALTIMA: { - (Ecu.fwdCamera, 0x707, None): [ - b'284N86CA1D', - ], - (Ecu.eps, 0x742, None): [ - b'6CA2B\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', - ], - (Ecu.engine, 0x7e0, None): [ - b'237109HE2B', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U29HE0A', - ], - }, - CAR.NISSAN_LEAF: { - (Ecu.abs, 0x740, None): [ - b'476605SA1C', - b'476605SA7D', - b'476605SC2D', - b'476606WK7B', - b'476606WK9B', - ], - (Ecu.eps, 0x742, None): [ - b'5SA2A\x99A\x05\x02N123F\x15b\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SA2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SN2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SN2A\xb7A\x05\x02N126F\x15\xb2\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.fwdCamera, 0x707, None): [ - b'5SA0ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', - b'5SA2ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', - b'6WK2ADB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', - b'6WK2BDB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', - b'6WK2CDB\x04\x18\x00\x00\x00\x00\x00R=1\x18\x99\x10\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U25SA3C', - b'284U25SP0C', - b'284U25SP1C', - b'284U26WK0A', - b'284U26WK0C', - ], - }, - CAR.NISSAN_LEAF_IC: { - (Ecu.fwdCamera, 0x707, None): [ - b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', - b'5SH4BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', - b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', - ], - (Ecu.abs, 0x740, None): [ - b'476605SD2E', - b'476605SH1D', - b'476605SK2A', - ], - (Ecu.eps, 0x742, None): [ - b'5SH2A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SH2C\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SK3A\x99A\x05\x02N123F\x15u\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U25SF0C', - b'284U25SH3A', - b'284U25SK2D', - ], - }, - CAR.NISSAN_XTRAIL: { - (Ecu.fwdCamera, 0x707, None): [ - b'284N86FR2A', - ], - (Ecu.abs, 0x740, None): [ - b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', - b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', - ], - (Ecu.eps, 0x742, None): [ - b'6FP2A\x99A\x05\x02N123F\x18\x02\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.combinationMeter, 0x743, None): [ - b'6FR2A\x18B\x05\x17\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.engine, 0x7e0, None): [ - b'6FR9A\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - b'6FU9B\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U26FR0E', - ], - }, -} diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py deleted file mode 100644 index 2e9a990610a279a..000000000000000 --- a/selfdrive/car/nissan/interface.py +++ /dev/null @@ -1,44 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.nissan.values import CAR - -ButtonType = car.CarState.ButtonEvent.Type - - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "nissan" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.nissan)] - ret.autoResumeSng = False - - ret.steerLimitTimer = 1.0 - - ret.steerActuatorDelay = 0.1 - - ret.steerControlType = car.CarParams.SteerControlType.angle - ret.radarUnavailable = True - - if candidate == CAR.NISSAN_ALTIMA: - # Altima has EPS on C-CAN unlike the others that have it on V-CAN - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_NISSAN_ALT_EPS_BUS - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_adas, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.brake]) - - if self.CS.lkas_enabled: - events.add(car.CarEvent.EventName.invalidLkasSetting) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/nissan/radar_interface.py b/selfdrive/car/nissan/radar_interface.py deleted file mode 100644 index e654bd61fd4afdc..000000000000000 --- a/selfdrive/car/nissan/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py deleted file mode 100644 index eecffb21bcc0d14..000000000000000 --- a/selfdrive/car/nissan/values.py +++ /dev/null @@ -1,107 +0,0 @@ -from dataclasses import dataclass, field - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs, CarHarness, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., .8, .15]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., 3.5, 0.4]) - LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower - STEER_THRESHOLD = 1.0 - - def __init__(self, CP): - pass - - -@dataclass -class NissanCarDocs(CarDocs): - package: str = "ProPILOT Assist" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.nissan_a])) - - -@dataclass(frozen=True) -class NissanCarSpecs(CarSpecs): - centerToFrontRatio: float = 0.44 - steerRatio: float = 17. - - -@dataclass -class NissanPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('nissan_x_trail_2017_generated', None)) - - -class CAR(Platforms): - NISSAN_XTRAIL = NissanPlatformConfig( - [NissanCarDocs("Nissan X-Trail 2017")], - NissanCarSpecs(mass=1610, wheelbase=2.705) - ) - NISSAN_LEAF = NissanPlatformConfig( - [NissanCarDocs("Nissan Leaf 2018-23", video_link="https://youtu.be/vaMbtAh_0cY")], - NissanCarSpecs(mass=1610, wheelbase=2.705), - dbc_dict('nissan_leaf_2018_generated', None), - ) - # Leaf with ADAS ECU found behind instrument cluster instead of glovebox - # Currently the only known difference between them is the inverted seatbelt signal. - NISSAN_LEAF_IC = NISSAN_LEAF.override(car_docs=[]) - NISSAN_ROGUE = NissanPlatformConfig( - [NissanCarDocs("Nissan Rogue 2018-20")], - NissanCarSpecs(mass=1610, wheelbase=2.705) - ) - NISSAN_ALTIMA = NissanPlatformConfig( - [NissanCarDocs("Nissan Altima 2019-20", car_parts=CarParts.common([CarHarness.nissan_b]))], - NissanCarSpecs(mass=1492, wheelbase=2.824) - ) - - -DBC = CAR.create_dbc_map() - -# Default diagnostic session -NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0x81]) -NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0x81]) - -# Manufacturer specific -NISSAN_DIAGNOSTIC_REQUEST_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xda]) -NISSAN_DIAGNOSTIC_RESPONSE_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xda]) - -NISSAN_VERSION_REQUEST_KWP = b'\x21\x83' -NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' - -NISSAN_RX_OFFSET = 0x20 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for bus, logging in ((0, False), (1, True)) for request in [ - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], - bus=bus, - logging=logging, - ), - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], - rx_offset=NISSAN_RX_OFFSET, - bus=bus, - logging=logging, - ), - # Rogue's engine solely responds to this - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP_2, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP_2, NISSAN_VERSION_RESPONSE_KWP], - bus=bus, - logging=logging, - ), - Request( - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - rx_offset=NISSAN_RX_OFFSET, - bus=bus, - logging=logging, - ), - ]], -) diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py deleted file mode 100644 index d89ae8c6397157f..000000000000000 --- a/selfdrive/car/subaru/carcontroller.py +++ /dev/null @@ -1,144 +0,0 @@ -from openpilot.common.numpy_fast import clip, interp -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.subaru import subarucan -from openpilot.selfdrive.car.subaru.values import DBC, GLOBAL_ES_ADDR, CanBus, CarControllerParams, SubaruFlags - -# FIXME: These limits aren't exact. The real limit is more than likely over a larger time period and -# involves the total steering angle change rather than rate, but these limits work well for now -MAX_STEER_RATE = 25 # deg/s -MAX_STEER_RATE_FRAMES = 7 # tx control frames needed before torque can be cut - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.apply_steer_last = 0 - self.frame = 0 - - self.cruise_button_prev = 0 - self.steer_rate_counter = 0 - - self.p = CarControllerParams(CP) - self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - # *** steering *** - if (self.frame % self.p.STEER_STEP) == 0: - apply_steer = int(round(actuators.steer * self.p.STEER_MAX)) - - # limits due to driver torque - - new_steer = int(round(apply_steer)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) - - if not CC.latActive: - apply_steer = 0 - - if self.CP.flags & SubaruFlags.PREGLOBAL: - can_sends.append(subarucan.create_preglobal_steering_control(self.packer, self.frame // self.p.STEER_STEP, apply_steer, CC.latActive)) - else: - apply_steer_req = CC.latActive - - if self.CP.flags & SubaruFlags.STEER_RATE_LIMITED: - # Steering rate fault prevention - self.steer_rate_counter, apply_steer_req = \ - common_fault_avoidance(abs(CS.out.steeringRateDeg) > MAX_STEER_RATE, apply_steer_req, - self.steer_rate_counter, MAX_STEER_RATE_FRAMES) - - can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, apply_steer_req)) - - self.apply_steer_last = apply_steer - - # *** longitudinal *** - - if CC.longActive: - apply_throttle = int(round(interp(actuators.accel, CarControllerParams.THROTTLE_LOOKUP_BP, CarControllerParams.THROTTLE_LOOKUP_V))) - apply_rpm = int(round(interp(actuators.accel, CarControllerParams.RPM_LOOKUP_BP, CarControllerParams.RPM_LOOKUP_V))) - apply_brake = int(round(interp(actuators.accel, CarControllerParams.BRAKE_LOOKUP_BP, CarControllerParams.BRAKE_LOOKUP_V))) - - # limit min and max values - cruise_throttle = clip(apply_throttle, CarControllerParams.THROTTLE_MIN, CarControllerParams.THROTTLE_MAX) - cruise_rpm = clip(apply_rpm, CarControllerParams.RPM_MIN, CarControllerParams.RPM_MAX) - cruise_brake = clip(apply_brake, CarControllerParams.BRAKE_MIN, CarControllerParams.BRAKE_MAX) - else: - cruise_throttle = CarControllerParams.THROTTLE_INACTIVE - cruise_rpm = CarControllerParams.RPM_MIN - cruise_brake = CarControllerParams.BRAKE_MIN - - # *** alerts and pcm cancel *** - if self.CP.flags & SubaruFlags.PREGLOBAL: - if self.frame % 5 == 0: - # 1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 = resume deep - # disengage ACC when OP is disengaged - if pcm_cancel_cmd: - cruise_button = 1 - # turn main on if off and past start-up state - elif not CS.out.cruiseState.available and CS.ready: - cruise_button = 1 - else: - cruise_button = CS.cruise_button - - # unstick previous mocked button press - if cruise_button == 1 and self.cruise_button_prev == 1: - cruise_button = 0 - self.cruise_button_prev = cruise_button - - can_sends.append(subarucan.create_preglobal_es_distance(self.packer, cruise_button, CS.es_distance_msg)) - - else: - if self.frame % 10 == 0: - can_sends.append(subarucan.create_es_dashstatus(self.packer, self.frame // 10, CS.es_dashstatus_msg, CC.enabled, - self.CP.openpilotLongitudinalControl, CC.longActive, hud_control.leadVisible)) - - can_sends.append(subarucan.create_es_lkas_state(self.packer, self.frame // 10, CS.es_lkas_state_msg, CC.enabled, hud_control.visualAlert, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, - hud_control.leftLaneDepart, hud_control.rightLaneDepart)) - - if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: - can_sends.append(subarucan.create_es_infotainment(self.packer, self.frame // 10, CS.es_infotainment_msg, hud_control.visualAlert)) - - if self.CP.openpilotLongitudinalControl: - if self.frame % 5 == 0: - can_sends.append(subarucan.create_es_status(self.packer, self.frame // 5, CS.es_status_msg, - self.CP.openpilotLongitudinalControl, CC.longActive, cruise_rpm)) - - can_sends.append(subarucan.create_es_brake(self.packer, self.frame // 5, CS.es_brake_msg, - self.CP.openpilotLongitudinalControl, CC.longActive, cruise_brake)) - - can_sends.append(subarucan.create_es_distance(self.packer, self.frame // 5, CS.es_distance_msg, 0, pcm_cancel_cmd, - self.CP.openpilotLongitudinalControl, cruise_brake > 0, cruise_throttle)) - else: - if pcm_cancel_cmd: - if not (self.CP.flags & SubaruFlags.HYBRID): - bus = CanBus.alt if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else CanBus.main - can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg["COUNTER"] + 1, CS.es_distance_msg, bus, pcm_cancel_cmd)) - - if self.CP.flags & SubaruFlags.DISABLE_EYESIGHT: - # Tester present (keeps eyesight disabled) - if self.frame % 100 == 0: - can_sends.append([GLOBAL_ES_ADDR, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", CanBus.camera]) - - # Create all of the other eyesight messages to keep the rest of the car happy when eyesight is disabled - if self.frame % 5 == 0: - can_sends.append(subarucan.create_es_highbeamassist(self.packer)) - - if self.frame % 10 == 0: - can_sends.append(subarucan.create_es_static_1(self.packer)) - - if self.frame % 2 == 0: - can_sends.append(subarucan.create_es_static_2(self.packer)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.p.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py deleted file mode 100644 index 821ff2c151f586a..000000000000000 --- a/selfdrive/car/subaru/carstate.py +++ /dev/null @@ -1,229 +0,0 @@ -import copy -from cereal import car -from opendbc.can.can_define import CANDefine -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.interfaces import CarStateBase -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.subaru.values import DBC, CanBus, SubaruFlags -from openpilot.selfdrive.car import CanSignalRateCalculator - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["Transmission"]["Gear"] - - self.angle_rate_calulator = CanSignalRateCalculator(50) - - def update(self, cp, cp_cam, cp_body): - ret = car.CarState.new_message() - - throttle_msg = cp.vl["Throttle"] if not (self.CP.flags & SubaruFlags.HYBRID) else cp_body.vl["Throttle_Hybrid"] - ret.gas = throttle_msg["Throttle_Pedal"] / 255. - - ret.gasPressed = ret.gas > 1e-5 - if self.CP.flags & SubaruFlags.PREGLOBAL: - ret.brakePressed = cp.vl["Brake_Pedal"]["Brake_Pedal"] > 0 - else: - cp_brakes = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - ret.brakePressed = cp_brakes.vl["Brake_Status"]["Brake"] == 1 - - cp_es_distance = cp_body if self.CP.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.HYBRID) else cp_cam - if not (self.CP.flags & SubaruFlags.HYBRID): - eyesight_fault = bool(cp_es_distance.vl["ES_Distance"]["Cruise_Fault"]) - - # if openpilot is controlling long, an eyesight fault is a non-critical fault. otherwise it's an ACC fault - if self.CP.openpilotLongitudinalControl: - ret.carFaultedNonCritical = eyesight_fault - else: - ret.accFaulted = eyesight_fault - - cp_wheels = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - ret.wheelSpeeds = self.get_wheel_speeds( - cp_wheels.vl["Wheel_Speeds"]["FL"], - cp_wheels.vl["Wheel_Speeds"]["FR"], - cp_wheels.vl["Wheel_Speeds"]["RL"], - cp_wheels.vl["Wheel_Speeds"]["RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw == 0 - - # continuous blinker signals for assisted lane change - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["Dashlights"]["LEFT_BLINKER"], - cp.vl["Dashlights"]["RIGHT_BLINKER"]) - - if self.CP.enableBsm: - ret.leftBlindspot = (cp.vl["BSD_RCTA"]["L_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["L_APPROACHING"] == 1) - ret.rightBlindspot = (cp.vl["BSD_RCTA"]["R_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["R_APPROACHING"] == 1) - - cp_transmission = cp_body if self.CP.flags & SubaruFlags.HYBRID else cp - can_gear = int(cp_transmission.vl["Transmission"]["Gear"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"] - - if not (self.CP.flags & SubaruFlags.PREGLOBAL): - # ideally we get this from the car, but unclear if it exists. diagnostic software doesn't even have it - ret.steeringRateDeg = self.angle_rate_calulator.update(ret.steeringAngleDeg, cp.vl["Steering_Torque"]["COUNTER"]) - - ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"] - ret.steeringTorqueEps = cp.vl["Steering_Torque"]["Steer_Torque_Output"] - - steer_threshold = 75 if self.CP.flags & SubaruFlags.PREGLOBAL else 80 - ret.steeringPressed = abs(ret.steeringTorque) > steer_threshold - - cp_cruise = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - if self.CP.flags & SubaruFlags.HYBRID: - ret.cruiseState.enabled = cp_cam.vl["ES_DashStatus"]['Cruise_Activated'] != 0 - ret.cruiseState.available = cp_cam.vl["ES_DashStatus"]['Cruise_On'] != 0 - else: - ret.cruiseState.enabled = cp_cruise.vl["CruiseControl"]["Cruise_Activated"] != 0 - ret.cruiseState.available = cp_cruise.vl["CruiseControl"]["Cruise_On"] != 0 - ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.KPH_TO_MS - - if (self.CP.flags & SubaruFlags.PREGLOBAL and cp.vl["Dash_State2"]["UNITS"] == 1) or \ - (not (self.CP.flags & SubaruFlags.PREGLOBAL) and cp.vl["Dashlights"]["UNITS"] == 1): - ret.cruiseState.speed *= CV.MPH_TO_KPH - - ret.seatbeltUnlatched = cp.vl["Dashlights"]["SEATBELT_FL"] == 1 - ret.doorOpen = any([cp.vl["BodyInfo"]["DOOR_OPEN_RR"], - cp.vl["BodyInfo"]["DOOR_OPEN_RL"], - cp.vl["BodyInfo"]["DOOR_OPEN_FR"], - cp.vl["BodyInfo"]["DOOR_OPEN_FL"]]) - ret.steerFaultPermanent = cp.vl["Steering_Torque"]["Steer_Error_1"] == 1 - - if self.CP.flags & SubaruFlags.PREGLOBAL: - self.cruise_button = cp_cam.vl["ES_Distance"]["Cruise_Button"] - self.ready = not cp_cam.vl["ES_DashStatus"]["Not_Ready_Startup"] - else: - ret.steerFaultTemporary = cp.vl["Steering_Torque"]["Steer_Warning"] == 1 - ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]["Conventional_Cruise"] == 1 - ret.cruiseState.standstill = cp_cam.vl["ES_DashStatus"]["Cruise_State"] == 3 - ret.stockFcw = (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 1) or \ - (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 2) - - self.es_lkas_state_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) - cp_es_brake = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam - self.es_brake_msg = copy.copy(cp_es_brake.vl["ES_Brake"]) - cp_es_status = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam - - # TODO: Hybrid cars don't have ES_Distance, need a replacement - if not (self.CP.flags & SubaruFlags.HYBRID): - # 8 is known AEB, there are a few other values related to AEB we ignore - ret.stockAeb = (cp_es_distance.vl["ES_Brake"]["AEB_Status"] == 8) and \ - (cp_es_distance.vl["ES_Brake"]["Brake_Pressure"] != 0) - - self.es_status_msg = copy.copy(cp_es_status.vl["ES_Status"]) - self.cruise_control_msg = copy.copy(cp_cruise.vl["CruiseControl"]) - - if not (self.CP.flags & SubaruFlags.HYBRID): - self.es_distance_msg = copy.copy(cp_es_distance.vl["ES_Distance"]) - - self.es_dashstatus_msg = copy.copy(cp_cam.vl["ES_DashStatus"]) - if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: - self.es_infotainment_msg = copy.copy(cp_cam.vl["ES_Infotainment"]) - - return ret - - @staticmethod - def get_common_global_body_messages(CP): - messages = [ - ("Wheel_Speeds", 50), - ("Brake_Status", 50), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages.append(("CruiseControl", 20)) - - return messages - - @staticmethod - def get_common_global_es_messages(CP): - messages = [ - ("ES_Brake", 20), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages += [ - ("ES_Distance", 20), - ("ES_Status", 20) - ] - - return messages - - @staticmethod - def get_common_preglobal_body_messages(): - messages = [ - ("CruiseControl", 50), - ("Wheel_Speeds", 50), - ("Dash_State2", 1), - ] - - return messages - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("Dashlights", 10), - ("Steering_Torque", 50), - ("BodyInfo", 1), - ("Brake_Pedal", 50), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages += [ - ("Throttle", 100), - ("Transmission", 100) - ] - - if CP.enableBsm: - messages.append(("BSD_RCTA", 17)) - - if not (CP.flags & SubaruFlags.PREGLOBAL): - if not (CP.flags & SubaruFlags.GLOBAL_GEN2): - messages += CarState.get_common_global_body_messages(CP) - else: - messages += CarState.get_common_preglobal_body_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.main) - - @staticmethod - def get_cam_can_parser(CP): - if CP.flags & SubaruFlags.PREGLOBAL: - messages = [ - ("ES_DashStatus", 20), - ("ES_Distance", 20), - ] - else: - messages = [ - ("ES_DashStatus", 10), - ("ES_LKAS_State", 10), - ] - - if not (CP.flags & SubaruFlags.GLOBAL_GEN2): - messages += CarState.get_common_global_es_messages(CP) - - if CP.flags & SubaruFlags.SEND_INFOTAINMENT: - messages.append(("ES_Infotainment", 10)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.camera) - - @staticmethod - def get_body_can_parser(CP): - messages = [] - - if CP.flags & SubaruFlags.GLOBAL_GEN2: - messages += CarState.get_common_global_body_messages(CP) - messages += CarState.get_common_global_es_messages(CP) - - if CP.flags & SubaruFlags.HYBRID: - messages += [ - ("Throttle_Hybrid", 40), - ("Transmission", 100) - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.alt) - diff --git a/selfdrive/car/subaru/fingerprints.py b/selfdrive/car/subaru/fingerprints.py deleted file mode 100644 index 7f3ae73163e418c..000000000000000 --- a/selfdrive/car/subaru/fingerprints.py +++ /dev/null @@ -1,563 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.SUBARU_ASCENT: { - (Ecu.abs, 0x7b0, None): [ - b'\xa5 \x19\x02\x00', - b'\xa5 !\x02\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x05\xc0\xd0\x00', - b'\x85\xc0\xd0\x00', - b'\x95\xc0\xd0\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00d\xb9\x00\x00\x00\x00', - b'\x00\x00d\xb9\x1f@ \x10', - b'\x00\x00e@\x00\x00\x00\x00', - b'\x00\x00e@\x1f@ $', - b"\x00\x00e~\x1f@ '", - ], - (Ecu.engine, 0x7e0, None): [ - b'\xbb,\xa0t\x07', - b'\xd1,\xa0q\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x00>\xf0\x00\x00', - b'\x00\xfe\xf7\x00\x00', - b'\x01\xfe\xf7\x00\x00', - b'\x01\xfe\xf9\x00\x00', - b'\x01\xfe\xfa\x00\x00', - ], - }, - CAR.SUBARU_ASCENT_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\xa5 #\x03\x00', - ], - (Ecu.eps, 0x746, None): [ - b'%\xc0\xd0\x11', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x05!\x08\x1dK\x05!\x08\x01/', - ], - (Ecu.engine, 0x7a2, None): [ - b'\xe5,\xa0P\x07', - ], - (Ecu.transmission, 0x7a3, None): [ - b'\x04\xfe\xf3\x00\x00', - ], - }, - CAR.SUBARU_LEGACY: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 \x02\x01', - b'\xa1 \x02\x02', - b'\xa1 \x03\x03', - b'\xa1 \x04\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x9b\xc0\x11\x00', - b'\x9b\xc0\x11\x02', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00e\x80\x00\x1f@ \x19\x00', - b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xde"a0\x07', - b'\xde,\xa0@\x07', - b'\xe2"aq\x07', - b'\xe2,\xa0@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xa5\xf6\x05@\x00', - b'\xa5\xfe\xc7@\x00', - b'\xa7\xf6\x04@\x00', - b'\xa7\xfe\xc4@\x00', - ], - }, - CAR.SUBARU_IMPREZA: { - (Ecu.abs, 0x7b0, None): [ - b'z\x84\x19\x90\x00', - b'z\x94\x08\x90\x00', - b'z\x94\x08\x90\x01', - b'z\x94\x0c\x90\x00', - b'z\x94\x0c\x90\x01', - b'z\x94.\x90\x00', - b'z\x94?\x90\x00', - b'z\x9c\x19\x80\x01', - b'\xa2 \x185\x00', - b'\xa2 \x193\x00', - b'\xa2 \x194\x00', - b'\xa2 \x19`\x00', - ], - (Ecu.eps, 0x746, None): [ - b'z\xc0\x00\x00', - b'z\xc0\x04\x00', - b'z\xc0\x08\x00', - b'z\xc0\n\x00', - b'z\xc0\x0c\x00', - b'\x8a\xc0\x00\x00', - b'\x8a\xc0\x10\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\xf4\x00\x00\x00\x00', - b'\x00\x00c\xf4\x1f@ \x07', - b'\x00\x00d)\x00\x00\x00\x00', - b'\x00\x00d)\x1f@ \x07', - b'\x00\x00dd\x00\x00\x00\x00', - b'\x00\x00dd\x1f@ \x0e', - b'\x00\x00d\xb5\x1f@ \x0e', - b'\x00\x00d\xdc\x00\x00\x00\x00', - b'\x00\x00d\xdc\x1f@ \x0e', - b'\x00\x00e\x02\x1f@ \x14', - b'\x00\x00e\x1c\x00\x00\x00\x00', - b'\x00\x00e\x1c\x1f@ \x14', - b'\x00\x00e+\x00\x00\x00\x00', - b'\x00\x00e+\x1f@ \x14', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xaa\x00Bu\x07', - b'\xaa\x01bt\x07', - b'\xaa!`u\x07', - b'\xaa!au\x07', - b'\xaa!av\x07', - b'\xaa!aw\x07', - b'\xaa!dq\x07', - b'\xaa!ds\x07', - b'\xaa!dt\x07', - b'\xaaafs\x07', - b'\xbe!as\x07', - b'\xbe!at\x07', - b'\xbeacr\x07', - b'\xc5!`r\x07', - b'\xc5!`s\x07', - b'\xc5!ap\x07', - b'\xc5!ar\x07', - b'\xc5!as\x07', - b'\xc5!dr\x07', - b'\xc5!ds\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xe3\xd0\x081\x00', - b'\xe3\xd5\x161\x00', - b'\xe3\xe5F1\x00', - b'\xe3\xf5\x06\x00\x00', - b'\xe3\xf5\x07\x00\x00', - b'\xe3\xf5C\x00\x00', - b'\xe3\xf5F\x00\x00', - b'\xe3\xf5G\x00\x00', - b'\xe4\xe5\x021\x00', - b'\xe4\xe5\x061\x00', - b'\xe4\xf5\x02\x00\x00', - b'\xe4\xf5\x07\x00\x00', - b'\xe5\xf5\x04\x00\x00', - b'\xe5\xf5$\x00\x00', - b'\xe5\xf5B\x00\x00', - ], - }, - CAR.SUBARU_IMPREZA_2020: { - (Ecu.abs, 0x7b0, None): [ - b'\xa2 \x193\x00', - b'\xa2 \x194\x00', - b'\xa2 `\x00', - b'\xa2 !3\x00', - b'\xa2 !6\x00', - b'\xa2 !`\x00', - b'\xa2 !i\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\n\xc0\x04\x00', - b'\n\xc0\x04\x01', - b'\x9a\xc0\x00\x00', - b'\x9a\xc0\x04\x00', - b'\x9a\xc0\n\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eb\x1f@ "', - b'\x00\x00eq\x00\x00\x00\x00', - b'\x00\x00eq\x1f@ "', - b'\x00\x00e\x8f\x00\x00\x00\x00', - b'\x00\x00e\x8f\x1f@ )', - b'\x00\x00e\x92\x00\x00\x00\x00', - b'\x00\x00e\xa4\x00\x00\x00\x00', - b'\x00\x00e\xa4\x1f@ (', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xca!`0\x07', - b'\xca!`p\x07', - b'\xca!ap\x07', - b'\xca!f@\x07', - b'\xca!fp\x07', - b'\xcaacp\x07', - b'\xcc!`p\x07', - b'\xcc!fp\x07', - b'\xcc"f0\x07', - b'\xe6!`@\x07', - b'\xe6!fp\x07', - b'\xe6"f0\x07', - b'\xe6"fp\x07', - b'\xf3"f@\x07', - b'\xf3"fp\x07', - b'\xf3"fr\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xe6\x15\x042\x00', - b'\xe6\xf5\x04\x00\x00', - b'\xe6\xf5$\x00\x00', - b'\xe6\xf5D0\x00', - b'\xe7\xf5\x04\x00\x00', - b'\xe7\xf5D0\x00', - b'\xe7\xf6B0\x00', - b'\xe9\xf5"\x00\x00', - b'\xe9\xf5B0\x00', - b'\xe9\xf6B0\x00', - b'\xe9\xf6F0\x00', - ], - }, - CAR.SUBARU_CROSSTREK_HYBRID: { - (Ecu.abs, 0x7b0, None): [ - b'\xa2 \x19e\x01', - b'\xa2 !e\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\n\xc2\x01\x00', - b'\x9a\xc2\x01\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00el\x1f@ #', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd7!`@\x07', - b'\xd7!`p\x07', - b'\xf4!`0\x07', - ], - }, - CAR.SUBARU_FORESTER: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 \x18\x14\x00', - b'\xa3 \x18&\x00', - b'\xa3 \x19\x14\x00', - b'\xa3 \x19&\x00', - b'\xa3 \x19h\x00', - b'\xa3 \x14\x00', - b'\xa3 \x14\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x8d\xc0\x00\x00', - b'\x8d\xc0\x04\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00e!\x00\x00\x00\x00', - b'\x00\x00e!\x1f@ \x11', - b'\x00\x00e^\x00\x00\x00\x00', - b'\x00\x00e^\x1f@ !', - b'\x00\x00e`\x00\x00\x00\x00', - b'\x00\x00e`\x1f@ ', - b'\x00\x00e\x97\x00\x00\x00\x00', - b'\x00\x00e\x97\x1f@ 0', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb6"`A\x07', - b'\xb6\xa2`A\x07', - b'\xcb"`@\x07', - b'\xcb"`p\x07', - b'\xcf"`0\x07', - b'\xcf"`p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1a\xe6B1\x00', - b'\x1a\xe6F1\x00', - b'\x1a\xf6B0\x00', - b'\x1a\xf6B`\x00', - b'\x1a\xf6F`\x00', - b'\x1a\xf6b0\x00', - b'\x1a\xf6b`\x00', - b'\x1a\xf6f`\x00', - ], - }, - CAR.SUBARU_FORESTER_HYBRID: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 \x19T\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x8d\xc2\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eY\x1f@ !', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd2\xa1`r\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1b\xa7@a\x00', - ], - }, - CAR.SUBARU_FORESTER_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'm\x97\x14@', - b'}\x97\x14@', - ], - (Ecu.eps, 0x746, None): [ - b'm\xc0\x10\x00', - b'}\xc0\x10\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\xe9\x00\x00\x00\x00', - b'\x00\x00c\xe9\x1f@ \x03', - b'\x00\x00d5\x1f@ \t', - b'\x00\x00d\xd3\x1f@ \t', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa7"@0\x07', - b'\xa7"@p\x07', - b'\xa7)\xa0q\x07', - b'\xba"@@\x07', - b'\xba"@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1a\xf6F`\x00', - b'\xda\xf2`p\x00', - b'\xda\xf2`\x80\x00', - b'\xda\xfd\xe0\x80\x00', - b'\xdc\xf2@`\x00', - b'\xdc\xf2``\x00', - b'\xdc\xf2`\x80\x00', - b'\xdc\xf2`\x81\x00', - ], - }, - CAR.SUBARU_LEGACY_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'[\x97D\x00', - b'[\xba\xc4\x03', - b'k\x97D\x00', - b'k\x9aD\x00', - b'{\x97D\x00', - ], - (Ecu.eps, 0x746, None): [ - b'K\xb0\x00\x01', - b'[\xb0\x00\x01', - b'k\xb0\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\x94\x1f@\x10\x08', - b'\x00\x00c\xb7\x1f@\x10\x16', - b'\x00\x00c\xec\x1f@ \x04', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa0"@q\x07', - b'\xa0+@p\x07', - b'\xab*@r\x07', - b'\xab+@p\x07', - b'\xb4"@0\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbd\xf2\x00`\x00', - b'\xbe\xf2\x00p\x00', - b'\xbe\xfb\xc0p\x00', - b'\xbf\xf2\x00\x80\x00', - b'\xbf\xfb\xc0\x80\x00', - ], - }, - CAR.SUBARU_OUTBACK_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'[\xba\xac\x03', - b'[\xf7\xac\x00', - b'[\xf7\xac\x03', - b'[\xf7\xbc\x03', - b'k\x97\xac\x00', - b'k\x9a\xac\x00', - b'{\x97\xac\x00', - b'{\x9a\xac\x00', - ], - (Ecu.eps, 0x746, None): [ - b'K\xb0\x00\x00', - b'K\xb0\x00\x02', - b'[\xb0\x00\x00', - b'k\xb0\x00\x00', - b'{\xb0\x00\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\x90\x1f@\x10\x0e', - b'\x00\x00c\x94\x00\x00\x00\x00', - b'\x00\x00c\x94\x1f@\x10\x08', - b'\x00\x00c\xb7\x1f@\x10\x16', - b'\x00\x00c\xd1\x1f@\x10\x17', - b'\x00\x00c\xec\x1f@ \x04', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa0"@\x80\x07', - b'\xa0*@q\x07', - b'\xa0*@u\x07', - b'\xa0+@@\x07', - b'\xa0bAq\x07', - b'\xab"@@\x07', - b'\xab"@s\x07', - b'\xab*@@\x07', - b'\xab+@@\x07', - b'\xb4"@0\x07', - b'\xb4"@p\x07', - b'\xb4"@r\x07', - b'\xb4+@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbd\xf2@`\x00', - b'\xbd\xf2@\x81\x00', - b'\xbd\xfb\xe0\x80\x00', - b'\xbe\xf2@p\x00', - b'\xbe\xf2@\x80\x00', - b'\xbe\xfb\xe0p\x00', - b'\xbf\xe2@\x80\x00', - b'\xbf\xf2@\x80\x00', - b'\xbf\xfb\xe0b\x00', - ], - }, - CAR.SUBARU_OUTBACK_PREGLOBAL_2018: { - (Ecu.abs, 0x7b0, None): [ - b'\x8b\x97\xac\x00', - b'\x8b\x97\xbc\x00', - b'\x8b\x99\xac\x00', - b'\x8b\x9a\xac\x00', - b'\x9b\x97\xac\x00', - b'\x9b\x97\xbe\x10', - b'\x9b\x9a\xac\x00', - ], - (Ecu.eps, 0x746, None): [ - b'{\xb0\x00\x00', - b'{\xb0\x00\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00df\x1f@ \n', - b'\x00\x00d\x95\x00\x00\x00\x00', - b'\x00\x00d\x95\x1f@ \x0f', - b'\x00\x00d\xfe\x00\x00\x00\x00', - b'\x00\x00d\xfe\x1f@ \x15', - b'\x00\x00e\x19\x1f@ \x15', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb5"@P\x07', - b'\xb5"@p\x07', - b'\xb5+@@\x07', - b'\xb5b@1\x07', - b'\xb5q\xe0@\x07', - b'\xc4"@0\x07', - b'\xc4+@0\x07', - b'\xc4b@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbb\xf2@`\x00', - b'\xbb\xfb\xe0`\x00', - b'\xbc\xaf\xe0`\x00', - b'\xbc\xe2@\x80\x00', - b'\xbc\xf2@\x80\x00', - b'\xbc\xf2@\x81\x00', - b'\xbc\xfb\xe0`\x00', - b'\xbc\xfb\xe0\x80\x00', - ], - }, - CAR.SUBARU_OUTBACK: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 \x06\x00', - b'\xa1 \x06\x01', - b'\xa1 \x06\x02', - b'\xa1 \x07\x00', - b'\xa1 \x07\x02', - b'\xa1 \x07\x03', - b'\xa1 \x08\x00', - b'\xa1 \x08\x01', - b'\xa1 \x08\x02', - b'\xa1 "\t\x00', - b'\xa1 "\t\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x1b\xc0\x10\x00', - b'\x9b\xc0\x10\x00', - b'\x9b\xc0\x10\x02', - b'\x9b\xc0 \x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eJ\x00\x00\x00\x00\x00\x00', - b'\x00\x00eJ\x00\x1f@ \x19\x00', - b'\x00\x00e\x80\x00\x1f@ \x19\x00', - b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', - b'\x00\x00e\x9a\x00\x1f@ 1\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xbc"`@\x07', - b'\xbc"`q\x07', - b'\xbc,\xa0q\x07', - b'\xbc,\xa0u\x07', - b'\xde"`0\x07', - b'\xde,\xa0@\x07', - b'\xe2"`0\x07', - b'\xe2"`p\x07', - b'\xe2"`q\x07', - b'\xe3,\xa0@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xa5\xf6D@\x00', - b'\xa5\xfe\xf6@\x00', - b'\xa5\xfe\xf7@\x00', - b'\xa5\xfe\xf8@\x00', - b'\xa7\x8e\xf40\x00', - b'\xa7\xf6D@\x00', - b'\xa7\xfe\xf4@\x00', - ], - }, - CAR.SUBARU_FORESTER_2022: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 !v\x00', - b'\xa3 !x\x00', - b'\xa3 "v\x00', - b'\xa3 "x\x00', - ], - (Ecu.eps, 0x746, None): [ - b'-\xc0\x040', - b'-\xc0%0', - b'=\xc0%\x02', - b'=\xc04\x02', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x04!\x01\x1eD\x07!\x00\x04,', - b'\x04!\x08\x01.\x07!\x08\x022', - b'\r!\x08\x017\n!\x08\x003', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd5"`0\x07', - b'\xd5"a0\x07', - b'\xf1"`q\x07', - b'\xf1"aq\x07', - b'\xfa"ap\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1d\x86B0\x00', - b'\x1d\xf6B0\x00', - b'\x1e\x86B0\x00', - b'\x1e\x86F0\x00', - b'\x1e\xf6D0\x00', - ], - }, - CAR.SUBARU_OUTBACK_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 #\x14\x00', - b'\xa1 #\x17\x00', - ], - (Ecu.eps, 0x746, None): [ - b'+\xc0\x10\x11\x00', - b'+\xc0\x12\x11\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\t!\x08\x046\x05!\x08\x01/', - ], - (Ecu.engine, 0x7a2, None): [ - b'\xed,\xa0q\x07', - b'\xed,\xa2q\x07', - ], - (Ecu.transmission, 0x7a3, None): [ - b'\xa8\x8e\xf41\x00', - b'\xa8\xfe\xf41\x00', - ], - }, -} diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py deleted file mode 100644 index 1aa4bd95eaad4fb..000000000000000 --- a/selfdrive/car/subaru/interface.py +++ /dev/null @@ -1,116 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.disable_ecu import disable_ecu -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.subaru.values import CAR, GLOBAL_ES_ADDR, SubaruFlags - - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate: CAR, fingerprint, car_fw, experimental_long, docs): - ret.carName = "subaru" - ret.radarUnavailable = True - # for HYBRID CARS to be upstreamed, we need: - # - replacement for ES_Distance so we can cancel the cruise control - # - to find the Cruise_Activated bit from the car - # - proper panda safety setup (use the correct cruise_activated bit, throttle from Throttle_Hybrid, etc) - ret.dashcamOnly = bool(ret.flags & (SubaruFlags.PREGLOBAL | SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) - ret.autoResumeSng = False - - # Detect infotainment message sent from the camera - if not (ret.flags & SubaruFlags.PREGLOBAL) and 0x323 in fingerprint[2]: - ret.flags |= SubaruFlags.SEND_INFOTAINMENT.value - - if ret.flags & SubaruFlags.PREGLOBAL: - ret.enableBsm = 0x25c in fingerprint[0] - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.subaruPreglobal)] - else: - ret.enableBsm = 0x228 in fingerprint[0] - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.subaru)] - if ret.flags & SubaruFlags.GLOBAL_GEN2: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_GEN2 - - ret.steerLimitTimer = 0.4 - ret.steerActuatorDelay = 0.1 - - if ret.flags & SubaruFlags.LKAS_ANGLE: - ret.steerControlType = car.CarParams.SteerControlType.angle - else: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate in (CAR.SUBARU_ASCENT, CAR.SUBARU_ASCENT_2023): - ret.steerActuatorDelay = 0.3 # end-to-end angle controller - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00003 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.0025, 0.1], [0.00025, 0.01]] - - elif candidate == CAR.SUBARU_IMPREZA: - ret.steerActuatorDelay = 0.4 # end-to-end angle controller - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00005 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.3], [0.02, 0.03]] - - elif candidate == CAR.SUBARU_IMPREZA_2020: - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00005 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] - - elif candidate == CAR.SUBARU_CROSSTREK_HYBRID: - ret.steerActuatorDelay = 0.1 - - elif candidate in (CAR.SUBARU_FORESTER, CAR.SUBARU_FORESTER_2022, CAR.SUBARU_FORESTER_HYBRID): - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.000038 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] - - elif candidate in (CAR.SUBARU_OUTBACK, CAR.SUBARU_LEGACY, CAR.SUBARU_OUTBACK_2023): - ret.steerActuatorDelay = 0.1 - - elif candidate in (CAR.SUBARU_FORESTER_PREGLOBAL, CAR.SUBARU_OUTBACK_PREGLOBAL_2018): - ret.safetyConfigs[0].safetyParam = Panda.FLAG_SUBARU_PREGLOBAL_REVERSED_DRIVER_TORQUE # Outback 2018-2019 and Forester have reversed driver torque signal - - elif candidate == CAR.SUBARU_LEGACY_PREGLOBAL: - ret.steerActuatorDelay = 0.15 - - elif candidate == CAR.SUBARU_OUTBACK_PREGLOBAL: - pass - else: - raise ValueError(f"unknown car: {candidate}") - - ret.experimentalLongitudinalAvailable = not (ret.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.PREGLOBAL | - SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable - - if ret.flags & SubaruFlags.GLOBAL_GEN2 and ret.openpilotLongitudinalControl: - ret.flags |= SubaruFlags.DISABLE_EYESIGHT.value - - if ret.openpilotLongitudinalControl: - ret.longitudinalTuning.kpBP = [0., 5., 35.] - ret.longitudinalTuning.kpV = [0.8, 1.0, 1.5] - ret.longitudinalTuning.kiBP = [0., 35.] - ret.longitudinalTuning.kiV = [0.54, 0.36] - - ret.stoppingControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_LONG - - return ret - - # returns a car.CarState - def _update(self, c): - - ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) - - ret.events = self.create_common_events(ret).to_msg() - - return ret - - @staticmethod - def init(CP, logcan, sendcan): - if CP.flags & SubaruFlags.DISABLE_EYESIGHT: - disable_ecu(logcan, sendcan, bus=2, addr=GLOBAL_ES_ADDR, com_cont_req=b'\x28\x03\x01') diff --git a/selfdrive/car/subaru/radar_interface.py b/selfdrive/car/subaru/radar_interface.py deleted file mode 100644 index e654bd61fd4afdc..000000000000000 --- a/selfdrive/car/subaru/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/subaru/tests/test_subaru.py b/selfdrive/car/subaru/tests/test_subaru.py deleted file mode 100644 index 33040442b69778d..000000000000000 --- a/selfdrive/car/subaru/tests/test_subaru.py +++ /dev/null @@ -1,16 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu - -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -class TestSubaruFingerprint: - def test_fw_version_format(self): - for platform, fws_per_ecu in FW_VERSIONS.items(): - for (ecu, _, _), fws in fws_per_ecu.items(): - fw_size = len(fws[0]) - for fw in fws: - assert len(fw) == fw_size, f"{platform} {ecu}: {len(fw)} {fw_size}" - diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py deleted file mode 100644 index dcbea1979fd227e..000000000000000 --- a/selfdrive/car/subaru/values.py +++ /dev/null @@ -1,275 +0,0 @@ -from dataclasses import dataclass, field -from enum import Enum, IntFlag - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Tool, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - def __init__(self, CP): - self.STEER_STEP = 2 # how often we update the steer cmd - self.STEER_DELTA_UP = 50 # torque increase per refresh, 0.8s to max - self.STEER_DELTA_DOWN = 70 # torque decrease per refresh - self.STEER_DRIVER_ALLOWANCE = 60 # allowed driver torque before start limiting - self.STEER_DRIVER_MULTIPLIER = 50 # weight driver torque heavily - self.STEER_DRIVER_FACTOR = 1 # from dbc - - if CP.flags & SubaruFlags.GLOBAL_GEN2: - self.STEER_MAX = 1000 - self.STEER_DELTA_UP = 40 - self.STEER_DELTA_DOWN = 40 - elif CP.carFingerprint == CAR.SUBARU_IMPREZA_2020: - self.STEER_MAX = 1439 - else: - self.STEER_MAX = 2047 - - THROTTLE_MIN = 808 - THROTTLE_MAX = 3400 - - THROTTLE_INACTIVE = 1818 # corresponds to zero acceleration - THROTTLE_ENGINE_BRAKE = 808 # while braking, eyesight sets throttle to this, probably for engine braking - - BRAKE_MIN = 0 - BRAKE_MAX = 600 # about -3.5m/s2 from testing - - RPM_MIN = 0 - RPM_MAX = 3600 - - RPM_INACTIVE = 600 # a good base rpm for zero acceleration - - THROTTLE_LOOKUP_BP = [0, 2] - THROTTLE_LOOKUP_V = [THROTTLE_INACTIVE, THROTTLE_MAX] - - RPM_LOOKUP_BP = [0, 2] - RPM_LOOKUP_V = [RPM_INACTIVE, RPM_MAX] - - BRAKE_LOOKUP_BP = [-3.5, 0] - BRAKE_LOOKUP_V = [BRAKE_MAX, BRAKE_MIN] - - -class SubaruFlags(IntFlag): - # Detected flags - SEND_INFOTAINMENT = 1 - DISABLE_EYESIGHT = 2 - - # Static flags - GLOBAL_GEN2 = 4 - - # Cars that temporarily fault when steering angle rate is greater than some threshold. - # Appears to be all torque-based cars produced around 2019 - present - STEER_RATE_LIMITED = 8 - PREGLOBAL = 16 - HYBRID = 32 - LKAS_ANGLE = 64 - - -GLOBAL_ES_ADDR = 0x787 -GEN2_ES_BUTTONS_DID = b'\x11\x30' - - -class CanBus: - main = 0 - alt = 1 - camera = 2 - - -class Footnote(Enum): - GLOBAL = CarFootnote( - "In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.", - Column.PACKAGE) - EXP_LONG = CarFootnote( - "Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.", - Column.LONGITUDINAL) - - -@dataclass -class SubaruCarDocs(CarDocs): - package: str = "EyeSight Driver Assistance" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.subaru_a])) - footnotes: list[Enum] = field(default_factory=lambda: [Footnote.GLOBAL]) - - def init_make(self, CP: car.CarParams): - self.car_parts.parts.extend([Tool.socket_8mm_deep, Tool.pry_tool]) - - if CP.experimentalLongitudinalAvailable: - self.footnotes.append(Footnote.EXP_LONG) - - -@dataclass -class SubaruPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('subaru_global_2017_generated', None)) - - def init(self): - if self.flags & SubaruFlags.HYBRID: - self.dbc_dict = dbc_dict('subaru_global_2020_hybrid_generated', None) - - -@dataclass -class SubaruGen2PlatformConfig(SubaruPlatformConfig): - def init(self): - super().init() - self.flags |= SubaruFlags.GLOBAL_GEN2 - if not (self.flags & SubaruFlags.LKAS_ANGLE): - self.flags |= SubaruFlags.STEER_RATE_LIMITED - - -class CAR(Platforms): - # Global platform - SUBARU_ASCENT = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Ascent 2019-21", "All")], - CarSpecs(mass=2031, wheelbase=2.89, steerRatio=13.5), - ) - SUBARU_OUTBACK = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Outback 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), - ) - SUBARU_LEGACY = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Legacy 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], - SUBARU_OUTBACK.specs, - ) - SUBARU_IMPREZA = SubaruPlatformConfig( - [ - SubaruCarDocs("Subaru Impreza 2017-19"), - SubaruCarDocs("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), - SubaruCarDocs("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), - ], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=15), - ) - SUBARU_IMPREZA_2020 = SubaruPlatformConfig( - [ - SubaruCarDocs("Subaru Impreza 2020-22"), - SubaruCarDocs("Subaru Crosstrek 2020-23"), - SubaruCarDocs("Subaru XV 2020-21"), - ], - CarSpecs(mass=1480, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.STEER_RATE_LIMITED, - ) - # TODO: is there an XV and Impreza too? - SUBARU_CROSSTREK_HYBRID = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Crosstrek Hybrid 2020", car_parts=CarParts.common([CarHarness.subaru_b]))], - CarSpecs(mass=1668, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.HYBRID, - ) - SUBARU_FORESTER = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2019-21", "All")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.STEER_RATE_LIMITED, - ) - SUBARU_FORESTER_HYBRID = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester Hybrid 2020")], - SUBARU_FORESTER.specs, - flags=SubaruFlags.HYBRID, - ) - # Pre-global - SUBARU_FORESTER_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2017-18")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=20), - dbc_dict('subaru_forester_2017_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_LEGACY_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Legacy 2015-18")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=12.5), - dbc_dict('subaru_outback_2015_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_OUTBACK_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Outback 2015-17")], - SUBARU_FORESTER_PREGLOBAL.specs, - dbc_dict('subaru_outback_2015_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_OUTBACK_PREGLOBAL_2018 = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Outback 2018-19")], - SUBARU_FORESTER_PREGLOBAL.specs, - dbc_dict('subaru_outback_2019_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - # Angle LKAS - SUBARU_FORESTER_2022 = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2022-24", "All", car_parts=CarParts.common([CarHarness.subaru_c]))], - SUBARU_FORESTER.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - SUBARU_OUTBACK_2023 = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Outback 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], - SUBARU_OUTBACK.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - SUBARU_ASCENT_2023 = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Ascent 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], - SUBARU_ASCENT.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - - -SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) -SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) - -# The EyeSight ECU takes 10s to respond to SUBARU_VERSION_REQUEST properly, -# log this alternate manufacturer-specific query -SUBARU_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) -SUBARU_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xf100) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - logging=True, - ), - # Non-OBD requests - # Some Eyesight modules fail on TESTER_PRESENT_REQUEST - # TODO: check if this resolves the fingerprinting issue for the 2023 Ascent and other new Subaru cars - Request( - [SUBARU_VERSION_REQUEST], - [SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - ), - Request( - [SUBARU_ALT_VERSION_REQUEST], - [SUBARU_ALT_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - logging=True, - ), - Request( - [StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - logging=True, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - bus=0, - ), - # GEN2 powertrain bus query - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - bus=1, - obd_multiplexing=False, - ), - ], - # We don't get the EPS from non-OBD queries on GEN2 cars. Note that we still attempt to match when it exists - non_essential_ecus={ - Ecu.eps: list(CAR.with_flags(SubaruFlags.GLOBAL_GEN2)), - } -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/tesla/carcontroller.py b/selfdrive/car/tesla/carcontroller.py deleted file mode 100644 index e460111e32cab05..000000000000000 --- a/selfdrive/car/tesla/carcontroller.py +++ /dev/null @@ -1,67 +0,0 @@ -from openpilot.common.numpy_fast import clip -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.tesla.teslacan import TeslaCAN -from openpilot.selfdrive.car.tesla.values import DBC, CANBUS, CarControllerParams - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.frame = 0 - self.apply_angle_last = 0 - self.packer = CANPacker(dbc_name) - self.pt_packer = CANPacker(DBC[CP.carFingerprint]['pt']) - self.tesla_can = TeslaCAN(self.packer, self.pt_packer) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - # Temp disable steering on a hands_on_fault, and allow for user override - hands_on_fault = CS.steer_warning == "EAC_ERROR_HANDS_ON" and CS.hands_on_level >= 3 - lkas_enabled = CC.latActive and not hands_on_fault - - if self.frame % 2 == 0: - if lkas_enabled: - # Angular rate limit based on speed - apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo, CarControllerParams) - - # To not fault the EPS - apply_angle = clip(apply_angle, CS.out.steeringAngleDeg - 20, CS.out.steeringAngleDeg + 20) - else: - apply_angle = CS.out.steeringAngleDeg - - self.apply_angle_last = apply_angle - can_sends.append(self.tesla_can.create_steering_control(apply_angle, lkas_enabled, (self.frame // 2) % 16)) - - # Longitudinal control (in sync with stock message, about 40Hz) - if self.CP.openpilotLongitudinalControl: - target_accel = actuators.accel - target_speed = max(CS.out.vEgo + (target_accel * CarControllerParams.ACCEL_TO_SPEED_MULTIPLIER), 0) - max_accel = 0 if target_accel < 0 else target_accel - min_accel = 0 if target_accel > 0 else target_accel - - while len(CS.das_control_counters) > 0: - can_sends.extend(self.tesla_can.create_longitudinal_commands(CS.acc_state, target_speed, min_accel, max_accel, CS.das_control_counters.popleft())) - - # Cancel on user steering override, since there is no steering torque blending - if hands_on_fault: - pcm_cancel_cmd = True - - if self.frame % 10 == 0 and pcm_cancel_cmd: - # Spam every possible counter value, otherwise it might not be accepted - for counter in range(16): - can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, pcm_cancel_cmd, CANBUS.chassis, counter)) - can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, pcm_cancel_cmd, CANBUS.autopilot_chassis, counter)) - - # TODO: HUD control - - new_actuators = actuators.as_builder() - new_actuators.steeringAngleDeg = self.apply_angle_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/tesla/carstate.py b/selfdrive/car/tesla/carstate.py deleted file mode 100644 index 645ea46014c1279..000000000000000 --- a/selfdrive/car/tesla/carstate.py +++ /dev/null @@ -1,139 +0,0 @@ -import copy -from collections import deque -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.tesla.values import CAR, DBC, CANBUS, GEAR_MAP, DOORS, BUTTONS -from openpilot.selfdrive.car.interfaces import CarStateBase -from opendbc.can.parser import CANParser -from opendbc.can.can_define import CANDefine - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.button_states = {button.event_type: False for button in BUTTONS} - self.can_define = CANDefine(DBC[CP.carFingerprint]['chassis']) - - # Needed by carcontroller - self.msg_stw_actn_req = None - self.hands_on_level = 0 - self.steer_warning = None - self.acc_state = 0 - self.das_control_counters = deque(maxlen=32) - - def update(self, cp, cp_cam): - ret = car.CarState.new_message() - - # Vehicle speed - ret.vEgoRaw = cp.vl["ESP_B"]["ESP_vehicleSpeed"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = (ret.vEgo < 0.1) - - # Gas pedal - ret.gas = cp.vl["DI_torque1"]["DI_pedalPos"] / 100.0 - ret.gasPressed = (ret.gas > 0) - - # Brake pedal - ret.brake = 0 - ret.brakePressed = bool(cp.vl["BrakeMessage"]["driverBrakeStatus"] != 1) - - # Steering wheel - epas_status = cp_cam.vl["EPAS3P_sysStatus"] if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN else cp.vl["EPAS_sysStatus"] - - self.hands_on_level = epas_status["EPAS_handsOnLevel"] - self.steer_warning = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacErrorCode"].get(int(epas_status["EPAS_eacErrorCode"]), None) - steer_status = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacStatus"].get(int(epas_status["EPAS_eacStatus"]), None) - - ret.steeringAngleDeg = -epas_status["EPAS_internalSAS"] - ret.steeringRateDeg = -cp.vl["STW_ANGLHP_STAT"]["StW_AnglHP_Spd"] # This is from a different angle sensor, and at different rate - ret.steeringTorque = -epas_status["EPAS_torsionBarTorque"] - ret.steeringPressed = (self.hands_on_level > 0) - ret.steerFaultPermanent = steer_status == "EAC_FAULT" - ret.steerFaultTemporary = (self.steer_warning not in ("EAC_ERROR_IDLE", "EAC_ERROR_HANDS_ON")) - - # Cruise state - cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp.vl["DI_state"]["DI_cruiseState"]), None) - speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp.vl["DI_state"]["DI_speedUnits"]), None) - - acc_enabled = (cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL")) - - ret.cruiseState.enabled = acc_enabled - if speed_units == "KPH": - ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.KPH_TO_MS - elif speed_units == "MPH": - ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.MPH_TO_MS - ret.cruiseState.available = ((cruise_state == "STANDBY") or ret.cruiseState.enabled) - ret.cruiseState.standstill = False # This needs to be false, since we can resume from stop without sending anything special - - # Gear - ret.gearShifter = GEAR_MAP[self.can_define.dv["DI_torque2"]["DI_gear"].get(int(cp.vl["DI_torque2"]["DI_gear"]), "DI_GEAR_INVALID")] - - # Buttons - buttonEvents = [] - for button in BUTTONS: - state = (cp.vl[button.can_addr][button.can_msg] in button.values) - if self.button_states[button.event_type] != state: - event = car.CarState.ButtonEvent.new_message() - event.type = button.event_type - event.pressed = state - buttonEvents.append(event) - self.button_states[button.event_type] = state - ret.buttonEvents = buttonEvents - - # Doors - ret.doorOpen = any((self.can_define.dv["GTW_carState"][door].get(int(cp.vl["GTW_carState"][door]), "OPEN") == "OPEN") for door in DOORS) - - # Blinkers - ret.leftBlinker = (cp.vl["GTW_carState"]["BC_indicatorLStatus"] == 1) - ret.rightBlinker = (cp.vl["GTW_carState"]["BC_indicatorRStatus"] == 1) - - # Seatbelt - if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - ret.seatbeltUnlatched = (cp.vl["DriverSeat"]["buckleStatus"] != 1) - else: - ret.seatbeltUnlatched = (cp.vl["SDM1"]["SDM_bcklDrivStatus"] != 1) - - # TODO: blindspot - - # AEB - ret.stockAeb = (cp_cam.vl["DAS_control"]["DAS_aebEvent"] == 1) - - # Messages needed by carcontroller - self.msg_stw_actn_req = copy.copy(cp.vl["STW_ACTN_RQ"]) - self.acc_state = cp_cam.vl["DAS_control"]["DAS_accState"] - self.das_control_counters.extend(cp_cam.vl_all["DAS_control"]["DAS_controlCounter"]) - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("ESP_B", 50), - ("DI_torque1", 100), - ("DI_torque2", 100), - ("STW_ANGLHP_STAT", 100), - ("EPAS_sysStatus", 25), - ("DI_state", 10), - ("STW_ACTN_RQ", 10), - ("GTW_carState", 10), - ("BrakeMessage", 50), - ] - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages.append(("DriverSeat", 20)) - else: - messages.append(("SDM1", 10)) - - return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.chassis) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - # sig_address, frequency - ("DAS_control", 40), - ] - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages.append(("EPAS3P_sysStatus", 100)) - - return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.autopilot_chassis) diff --git a/selfdrive/car/tesla/fingerprints.py b/selfdrive/car/tesla/fingerprints.py deleted file mode 100644 index 68c50a62ed05fcc..000000000000000 --- a/selfdrive/car/tesla/fingerprints.py +++ /dev/null @@ -1,32 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.tesla.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.TESLA_AP2_MODELS: { - (Ecu.adas, 0x649, None): [ - b'\x01\x00\x8b\x07\x01\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x11', - ], - (Ecu.electricBrakeBooster, 0x64d, None): [ - b'1037123-00-A', - ], - (Ecu.fwdRadar, 0x671, None): [ - b'\x01\x00W\x00\x00\x00\x07\x00\x00\x00\x00\x08\x01\x00\x00\x00\x07\xff\xfe', - ], - (Ecu.eps, 0x730, None): [ - b'\x10#\x01', - ], - }, - CAR.TESLA_MODELS_RAVEN: { - (Ecu.electricBrakeBooster, 0x64d, None): [ - b'1037123-00-A', - ], - (Ecu.fwdRadar, 0x671, None): [ - b'\x01\x00\x99\x02\x01\x00\x10\x00\x00AP8.3.03\x00\x10', - ], - (Ecu.eps, 0x730, None): [ - b'SX_0.0.0 (99),SR013.7', - ], - }, -} diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py deleted file mode 100755 index e039859263f59f7..000000000000000 --- a/selfdrive/car/tesla/interface.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from panda import Panda -from openpilot.selfdrive.car.tesla.values import CANBUS, CAR -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "tesla" - - # There is no safe way to do steer blending with user torque, - # so the steering behaves like autopilot. This is not - # how openpilot should be, hence dashcamOnly - ret.dashcamOnly = True - - ret.steerControlType = car.CarParams.SteerControlType.angle - - # Set kP and kI to 0 over the whole speed range to have the planner accel as actuator command - ret.longitudinalTuning.kpBP = [0] - ret.longitudinalTuning.kpV = [0] - ret.longitudinalTuning.kiBP = [0] - ret.longitudinalTuning.kiV = [0] - ret.longitudinalActuatorDelayUpperBound = 0.5 # s - ret.radarTimeStep = (1.0 / 8) # 8Hz - - # Check if we have messages on an auxiliary panda, and that 0x2bf (DAS_control) is present on the AP powertrain bus - # If so, we assume that it is connected to the longitudinal harness. - flags = (Panda.FLAG_TESLA_RAVEN if candidate == CAR.TESLA_MODELS_RAVEN else 0) - if (CANBUS.autopilot_powertrain in fingerprint.keys()) and (0x2bf in fingerprint[CANBUS.autopilot_powertrain].keys()): - ret.openpilotLongitudinalControl = True - flags |= Panda.FLAG_TESLA_LONG_CONTROL - ret.safetyConfigs = [ - get_safety_config(car.CarParams.SafetyModel.tesla, flags), - get_safety_config(car.CarParams.SafetyModel.tesla, flags | Panda.FLAG_TESLA_POWERTRAIN), - ] - else: - ret.openpilotLongitudinalControl = False - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.tesla, flags)] - - ret.steerLimitTimer = 1.0 - ret.steerActuatorDelay = 0.25 - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.events = self.create_common_events(ret).to_msg() - - return ret diff --git a/selfdrive/car/tesla/radar_interface.py b/selfdrive/car/tesla/radar_interface.py deleted file mode 100755 index ae5077824bc6f28..000000000000000 --- a/selfdrive/car/tesla/radar_interface.py +++ /dev/null @@ -1,91 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.tesla.values import CAR, DBC, CANBUS -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.CP = CP - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages = [('RadarStatus', 16)] - self.num_points = 40 - self.trigger_msg = 1119 - else: - messages = [('TeslaRadarSguInfo', 10)] - self.num_points = 32 - self.trigger_msg = 878 - - for i in range(self.num_points): - messages.extend([ - (f'RadarPoint{i}_A', 16), - (f'RadarPoint{i}_B', 16), - ]) - - self.rcp = CANParser(DBC[CP.carFingerprint]['radar'], messages, CANBUS.radar) - self.updated_messages = set() - self.track_id = 0 - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - values = self.rcp.update_strings(can_strings) - self.updated_messages.update(values) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - - # Errors - errors = [] - if not self.rcp.can_valid: - errors.append('canError') - - if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - radar_status = self.rcp.vl['RadarStatus'] - if radar_status['sensorBlocked'] or radar_status['shortTermUnavailable'] or radar_status['vehDynamicsError']: - errors.append('fault') - else: - radar_status = self.rcp.vl['TeslaRadarSguInfo'] - if radar_status['RADC_HWFail'] or radar_status['RADC_SGUFail'] or radar_status['RADC_SensorDirty']: - errors.append('fault') - - ret.errors = errors - - # Radar tracks - for i in range(self.num_points): - msg_a = self.rcp.vl[f'RadarPoint{i}_A'] - msg_b = self.rcp.vl[f'RadarPoint{i}_B'] - - # Make sure msg A and B are together - if msg_a['Index'] != msg_b['Index2']: - continue - - # Check if it's a valid track - if not msg_a['Tracked']: - if i in self.pts: - del self.pts[i] - continue - - # New track! - if i not in self.pts: - self.pts[i] = car.RadarData.RadarPoint.new_message() - self.pts[i].trackId = self.track_id - self.track_id += 1 - - # Parse track data - self.pts[i].dRel = msg_a['LongDist'] - self.pts[i].yRel = msg_a['LatDist'] - self.pts[i].vRel = msg_a['LongSpeed'] - self.pts[i].aRel = msg_a['LongAccel'] - self.pts[i].yvRel = msg_b['LatSpeed'] - self.pts[i].measured = bool(msg_a['Meas']) - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret diff --git a/selfdrive/car/tesla/teslacan.py b/selfdrive/car/tesla/teslacan.py deleted file mode 100644 index 6bb27b995f79d54..000000000000000 --- a/selfdrive/car/tesla/teslacan.py +++ /dev/null @@ -1,94 +0,0 @@ -import crcmod - -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.tesla.values import CANBUS, CarControllerParams - - -class TeslaCAN: - def __init__(self, packer, pt_packer): - self.packer = packer - self.pt_packer = pt_packer - self.crc = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) - - @staticmethod - def checksum(msg_id, dat): - # TODO: get message ID from name instead - ret = (msg_id & 0xFF) + ((msg_id >> 8) & 0xFF) - ret += sum(dat) - return ret & 0xFF - - def create_steering_control(self, angle, enabled, counter): - values = { - "DAS_steeringAngleRequest": -angle, - "DAS_steeringHapticRequest": 0, - "DAS_steeringControlType": 1 if enabled else 0, - "DAS_steeringControlCounter": counter, - } - - data = self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values)[2] - values["DAS_steeringControlChecksum"] = self.checksum(0x488, data[:3]) - return self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values) - - def create_action_request(self, msg_stw_actn_req, cancel, bus, counter): - # We copy this whole message when spamming cancel - values = {s: msg_stw_actn_req[s] for s in [ - "SpdCtrlLvr_Stat", - "VSL_Enbl_Rq", - "SpdCtrlLvrStat_Inv", - "DTR_Dist_Rq", - "TurnIndLvr_Stat", - "HiBmLvr_Stat", - "WprWashSw_Psd", - "WprWash_R_Sw_Posn_V2", - "StW_Lvr_Stat", - "StW_Cond_Flt", - "StW_Cond_Psd", - "HrnSw_Psd", - "StW_Sw00_Psd", - "StW_Sw01_Psd", - "StW_Sw02_Psd", - "StW_Sw03_Psd", - "StW_Sw04_Psd", - "StW_Sw05_Psd", - "StW_Sw06_Psd", - "StW_Sw07_Psd", - "StW_Sw08_Psd", - "StW_Sw09_Psd", - "StW_Sw10_Psd", - "StW_Sw11_Psd", - "StW_Sw12_Psd", - "StW_Sw13_Psd", - "StW_Sw14_Psd", - "StW_Sw15_Psd", - "WprSw6Posn", - "MC_STW_ACTN_RQ", - "CRC_STW_ACTN_RQ", - ]} - - if cancel: - values["SpdCtrlLvr_Stat"] = 1 - values["MC_STW_ACTN_RQ"] = counter - - data = self.packer.make_can_msg("STW_ACTN_RQ", bus, values)[2] - values["CRC_STW_ACTN_RQ"] = self.crc(data[:7]) - return self.packer.make_can_msg("STW_ACTN_RQ", bus, values) - - def create_longitudinal_commands(self, acc_state, speed, min_accel, max_accel, cnt): - messages = [] - values = { - "DAS_setSpeed": speed * CV.MS_TO_KPH, - "DAS_accState": acc_state, - "DAS_aebEvent": 0, - "DAS_jerkMin": CarControllerParams.JERK_LIMIT_MIN, - "DAS_jerkMax": CarControllerParams.JERK_LIMIT_MAX, - "DAS_accelMin": min_accel, - "DAS_accelMax": max_accel, - "DAS_controlCounter": cnt, - "DAS_controlChecksum": 0, - } - - for packer, bus in [(self.packer, CANBUS.chassis), (self.pt_packer, CANBUS.powertrain)]: - data = packer.make_can_msg("DAS_control", bus, values)[2] - values["DAS_controlChecksum"] = self.checksum(0x2b9, data[:7]) - messages.append(packer.make_can_msg("DAS_control", bus, values)) - return messages diff --git a/selfdrive/car/tesla/values.py b/selfdrive/car/tesla/values.py deleted file mode 100644 index 0f9cd00f63edeb2..000000000000000 --- a/selfdrive/car/tesla/values.py +++ /dev/null @@ -1,98 +0,0 @@ -from collections import namedtuple - -from cereal import car -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - -Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) - -class CAR(Platforms): - TESLA_AP1_MODELS = PlatformConfig( - [CarDocs("Tesla AP1 Model S", "All")], - CarSpecs(mass=2100., wheelbase=2.959, steerRatio=15.0), - dbc_dict('tesla_powertrain', 'tesla_radar_bosch_generated', chassis_dbc='tesla_can') - ) - TESLA_AP2_MODELS = PlatformConfig( - [CarDocs("Tesla AP2 Model S", "All")], - TESLA_AP1_MODELS.specs, - TESLA_AP1_MODELS.dbc_dict - ) - TESLA_MODELS_RAVEN = PlatformConfig( - [CarDocs("Tesla Model S Raven", "All")], - TESLA_AP1_MODELS.specs, - dbc_dict('tesla_powertrain', 'tesla_radar_continental_generated', chassis_dbc='tesla_can') - ) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - whitelist_ecus=[Ecu.eps], - rx_offset=0x08, - bus=0, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.SUPPLIER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.SUPPLIER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.eps], - rx_offset=0x08, - bus=0, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - whitelist_ecus=[Ecu.adas, Ecu.electricBrakeBooster, Ecu.fwdRadar], - rx_offset=0x10, - bus=0, - ), - ] -) - -class CANBUS: - # Lateral harness - chassis = 0 - radar = 1 - autopilot_chassis = 2 - - # Longitudinal harness - powertrain = 4 - private = 5 - autopilot_powertrain = 6 - -GEAR_MAP = { - "DI_GEAR_INVALID": car.CarState.GearShifter.unknown, - "DI_GEAR_P": car.CarState.GearShifter.park, - "DI_GEAR_R": car.CarState.GearShifter.reverse, - "DI_GEAR_N": car.CarState.GearShifter.neutral, - "DI_GEAR_D": car.CarState.GearShifter.drive, - "DI_GEAR_SNA": car.CarState.GearShifter.unknown, -} - -DOORS = ["DOOR_STATE_FL", "DOOR_STATE_FR", "DOOR_STATE_RL", "DOOR_STATE_RR", "DOOR_STATE_FrontTrunk", "BOOT_STATE"] - -# Make sure the message and addr is also in the CAN parser! -BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.leftBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [1]), - Button(car.CarState.ButtonEvent.Type.rightBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [2]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [4, 16]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [8, 32]), - Button(car.CarState.ButtonEvent.Type.cancel, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [2]), -] - -class CarControllerParams: - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 1.6, .3]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 7.0, 0.8]) - JERK_LIMIT_MAX = 8 - JERK_LIMIT_MIN = -8 - ACCEL_TO_SPEED_MULTIPLIER = 3 - - def __init__(self, CP): - pass - - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/tests/big_cars_test.sh b/selfdrive/car/tests/big_cars_test.sh index af45c9cd1488ad2..863b8bead0457e0 100755 --- a/selfdrive/car/tests/big_cars_test.sh +++ b/selfdrive/car/tests/big_cars_test.sh @@ -1,12 +1,12 @@ -#!/bin/bash +#!/usr/bin/env bash SCRIPT_DIR=$(dirname "$0") BASEDIR=$(realpath "$SCRIPT_DIR/../../../") cd $BASEDIR -MAX_EXAMPLES=300 -INTERNAL_SEG_CNT=300 -FILEREADER_CACHE=1 -INTERNAL_SEG_LIST=selfdrive/car/tests/test_models_segs.txt +export MAX_EXAMPLES=300 +export INTERNAL_SEG_CNT=300 +export FILEREADER_CACHE=1 +export INTERNAL_SEG_LIST=selfdrive/car/tests/test_models_segs.txt -cd selfdrive/car/tests && pytest test_models.py test_car_interfaces.py \ No newline at end of file +cd selfdrive/car/tests && pytest test_models.py test_car_interfaces.py diff --git a/selfdrive/car/tests/test_can_fingerprint.py b/selfdrive/car/tests/test_can_fingerprint.py deleted file mode 100644 index f236986d8e58b39..000000000000000 --- a/selfdrive/car/tests/test_can_fingerprint.py +++ /dev/null @@ -1,61 +0,0 @@ -from parameterized import parameterized - -from cereal import log, messaging -from openpilot.selfdrive.car.car_helpers import FRAME_FINGERPRINT, can_fingerprint -from openpilot.selfdrive.car.fingerprints import _FINGERPRINTS as FINGERPRINTS - - -class TestCanFingerprint: - @parameterized.expand(list(FINGERPRINTS.items())) - def test_can_fingerprint(self, car_model, fingerprints): - """Tests online fingerprinting function on offline fingerprints""" - - for fingerprint in fingerprints: # can have multiple fingerprints for each platform - can = messaging.new_message('can', 1) - can.can = [log.CanData(address=address, dat=b'\x00' * length, src=src) - for address, length in fingerprint.items() for src in (0, 1)] - - fingerprint_iter = iter([can]) - empty_can = messaging.new_message('can', 0) - car_fingerprint, finger = can_fingerprint(lambda: next(fingerprint_iter, empty_can)) # noqa: B023 - - assert car_fingerprint == car_model - assert finger[0] == fingerprint - assert finger[1] == fingerprint - assert finger[2] == {} - - def test_timing(self, subtests): - # just pick any CAN fingerprinting car - car_model = "CHEVROLET_BOLT_EUV" - fingerprint = FINGERPRINTS[car_model][0] - - cases = [] - - # case 1 - one match, make sure we keep going for 100 frames - can = messaging.new_message('can', 1) - can.can = [log.CanData(address=address, dat=b'\x00' * length, src=src) - for address, length in fingerprint.items() for src in (0, 1)] - cases.append((FRAME_FINGERPRINT, car_model, can)) - - # case 2 - no matches, make sure we keep going for 100 frames - can = messaging.new_message('can', 1) - can.can = [log.CanData(address=1, dat=b'\x00' * 1, src=src) for src in (0, 1)] # uncommon address - cases.append((FRAME_FINGERPRINT, None, can)) - - # case 3 - multiple matches, make sure we keep going for 200 frames to try to eliminate some - can = messaging.new_message('can', 1) - can.can = [log.CanData(address=2016, dat=b'\x00' * 8, src=src) for src in (0, 1)] # common address - cases.append((FRAME_FINGERPRINT * 2, None, can)) - - for expected_frames, car_model, can in cases: - with subtests.test(expected_frames=expected_frames, car_model=car_model): - frames = 0 - - def test(): - nonlocal frames - frames += 1 - return can # noqa: B023 - - car_fingerprint, _ = can_fingerprint(test) - assert car_fingerprint == car_model - assert frames == expected_frames + 2# TODO: fix extra frames diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 19096c23e5505dc..4370ea141ba7d51 100644 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -2,66 +2,45 @@ import math import hypothesis.strategies as st from hypothesis import Phase, given, settings -import importlib from parameterized import parameterized -from cereal import car, messaging -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car import gen_empty_fingerprint -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.fingerprints import all_known_cars -from openpilot.selfdrive.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS -from openpilot.selfdrive.car.interfaces import get_interface_attr +from cereal import car +from opendbc.car import DT_CTRL +from opendbc.car.car_helpers import interfaces +from opendbc.car.structs import CarParams +from opendbc.car.tests.test_car_interfaces import get_fuzzy_car_interface_args +from opendbc.car.fingerprints import all_known_cars +from opendbc.car.fw_versions import FW_VERSIONS, FW_QUERY_CONFIGS +from opendbc.car.mock.values import CAR as MOCK 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 +from openpilot.selfdrive.test.fuzzy_generation import FuzzyGenerator ALL_ECUS = {ecu for ecus in FW_VERSIONS.values() for ecu in ecus.keys()} ALL_ECUS |= {ecu for config in FW_QUERY_CONFIGS.values() for ecu in config.extra_ecus} ALL_REQUESTS = {tuple(r.request) for config in FW_QUERY_CONFIGS.values() for r in config.requests} -MAX_EXAMPLES = int(os.environ.get('MAX_EXAMPLES', '40')) - - -def get_fuzzy_car_interface_args(draw: DrawType) -> dict: - # Fuzzy CAN fingerprints and FW versions to test more states of the CarInterface - fingerprint_strategy = st.fixed_dictionaries({key: st.dictionaries(st.integers(min_value=0, max_value=0x800), - st.integers(min_value=0, max_value=64)) for key in - gen_empty_fingerprint()}) - - # only pick from possible ecus to reduce search space - car_fw_strategy = st.lists(st.sampled_from(sorted(ALL_ECUS))) - - params_strategy = st.fixed_dictionaries({ - 'fingerprints': fingerprint_strategy, - 'car_fw': car_fw_strategy, - 'experimental_long': st.booleans(), - }) - - params: dict = draw(params_strategy) - params['car_fw'] = [car.CarParams.CarFw(ecu=fw[0], address=fw[1], subAddress=fw[2] or 0, - request=draw(st.sampled_from(sorted(ALL_REQUESTS)))) - for fw in params['car_fw']] - return params +MAX_EXAMPLES = int(os.environ.get('MAX_EXAMPLES', '60')) class TestCarInterfaces: # FIXME: Due to the lists used in carParams, Phase.target is very slow and will cause # many generated examples to overrun when max_examples > ~20, don't use it - @parameterized.expand([(car,) for car in sorted(all_known_cars())]) + @parameterized.expand([(car,) for car in sorted(all_known_cars())] + [MOCK.MOCK]) @settings(max_examples=MAX_EXAMPLES, deadline=None, phases=(Phase.reuse, Phase.generate, Phase.shrink)) @given(data=st.data()) def test_car_interfaces(self, car_name, data): - CarInterface, CarController, CarState = interfaces[car_name] + CarInterface, CarController, CarState, RadarInterface = interfaces[car_name] args = get_fuzzy_car_interface_args(data.draw) car_params = CarInterface.get_params(car_name, args['fingerprints'], args['car_fw'], experimental_long=args['experimental_long'], docs=False) + car_params = car_params.as_reader() car_interface = CarInterface(car_params, CarController, CarState) assert car_params assert car_interface @@ -75,15 +54,15 @@ def test_car_interfaces(self, car_name, data): # Longitudinal sanity checks assert len(car_params.longitudinalTuning.kpV) == len(car_params.longitudinalTuning.kpBP) assert len(car_params.longitudinalTuning.kiV) == len(car_params.longitudinalTuning.kiBP) - assert len(car_params.longitudinalTuning.deadzoneV) == len(car_params.longitudinalTuning.deadzoneBP) # Lateral sanity checks - if car_params.steerControlType != car.CarParams.SteerControlType.angle: + if car_params.steerControlType != CarParams.SteerControlType.angle: tune = car_params.lateralTuning if tune.which() == 'pid': - assert not math.isnan(tune.pid.kf) and tune.pid.kf > 0 - assert len(tune.pid.kpV) > 0 and len(tune.pid.kpV) == len(tune.pid.kpBP) - assert len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP) + if car_name != MOCK.MOCK: + assert not math.isnan(tune.pid.kf) and tune.pid.kf > 0 + assert len(tune.pid.kpV) > 0 and len(tune.pid.kpV) == len(tune.pid.kpBP) + assert len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP) elif tune.which() == 'torque': assert not math.isnan(tune.torque.kf) and tune.torque.kf > 0 @@ -93,67 +72,27 @@ def test_car_interfaces(self, car_name, data): # Run car interface now_nanos = 0 CC = car.CarControl.new_message(**cc_msg) + CC = CC.as_reader() for _ in range(10): - car_interface.update(CC, []) - car_interface.apply(CC.as_reader(), now_nanos) + car_interface.update([]) + car_interface.apply(CC, now_nanos) now_nanos += DT_CTRL * 1e9 # 10 ms CC = car.CarControl.new_message(**cc_msg) CC.enabled = True + CC = CC.as_reader() for _ in range(10): - car_interface.update(CC, []) - car_interface.apply(CC.as_reader(), now_nanos) + car_interface.update([]) + car_interface.apply(CC, now_nanos) now_nanos += DT_CTRL * 1e9 # 10ms # Test controller initialization # TODO: wait until card refactor is merged to run controller a few times, # hypothesis also slows down significantly with just one more message draw LongControl(car_params) - if car_params.steerControlType == car.CarParams.SteerControlType.angle: + if car_params.steerControlType == 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) - assert radar_interface - - # Run radar interface once - radar_interface.update([]) - if not car_params.radarUnavailable and radar_interface.rcp is not None and \ - hasattr(radar_interface, '_update') and hasattr(radar_interface, 'trigger_msg'): - radar_interface._update([radar_interface.trigger_msg]) - - # Test radar fault - if not car_params.radarUnavailable and radar_interface.rcp is not None: - cans = [messaging.new_message('can', 1).to_bytes() for _ in range(5)] - rr = radar_interface.update(cans) - assert rr is None or len(rr.errors) > 0 - - def test_interface_attrs(self): - """Asserts basic behavior of interface attribute getter""" - num_brands = len(get_interface_attr('CAR')) - assert num_brands >= 13 - - # Should return value for all brands when not combining, even if attribute doesn't exist - ret = get_interface_attr('FAKE_ATTR') - assert len(ret) == num_brands - - # Make sure we can combine dicts - ret = get_interface_attr('DBC', combine_brands=True) - assert len(ret) >= 160 - - # We don't support combining non-dicts - ret = get_interface_attr('CAR', combine_brands=True) - assert len(ret) == 0 - - # If brand has None value, it shouldn't return when ignore_none=True is specified - none_brands = {b for b, v in get_interface_attr('FINGERPRINTS').items() if v is None} - assert len(none_brands) >= 1 - - ret = get_interface_attr('FINGERPRINTS', ignore_none=True) - none_brands_in_ret = none_brands.intersection(ret) - assert len(none_brands_in_ret) == 0, f'Brands with None values in ignore_none=True result: {none_brands_in_ret}' diff --git a/selfdrive/controls/tests/test_cruise_speed.py b/selfdrive/car/tests/test_cruise_speed.py similarity index 97% rename from selfdrive/controls/tests/test_cruise_speed.py rename to selfdrive/car/tests/test_cruise_speed.py index 8f451a49bc1d26a..7bda3a24eb31ac4 100644 --- a/selfdrive/controls/tests/test_cruise_speed.py +++ b/selfdrive/car/tests/test_cruise_speed.py @@ -4,7 +4,7 @@ from parameterized import parameterized_class from cereal import log -from openpilot.selfdrive.controls.lib.drive_helpers import VCruiseHelper, V_CRUISE_MIN, V_CRUISE_MAX, V_CRUISE_INITIAL, IMPERIAL_INCREMENT +from openpilot.selfdrive.car.cruise import VCruiseHelper, V_CRUISE_MIN, V_CRUISE_MAX, V_CRUISE_INITIAL, IMPERIAL_INCREMENT from cereal import car from openpilot.common.conversions import Conversions as CV from openpilot.selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver diff --git a/selfdrive/car/tests/test_docs.py b/selfdrive/car/tests/test_docs.py index 40ad07b28376444..a203b2feff6d45b 100644 --- a/selfdrive/car/tests/test_docs.py +++ b/selfdrive/car/tests/test_docs.py @@ -1,16 +1,10 @@ -from collections import defaultdict import os -import pytest -import re from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.docs import CARS_MD_OUT, CARS_MD_TEMPLATE, generate_cars_md, get_all_car_docs -from openpilot.selfdrive.car.docs_definitions import Cable, Column, PartType, Star -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.values import PLATFORMS +from opendbc.car.docs import generate_cars_md, get_all_car_docs from openpilot.selfdrive.debug.dump_car_docs import dump_car_docs from openpilot.selfdrive.debug.print_docs_diff import print_car_docs_diff +from openpilot.selfdrive.car.docs import CARS_MD_OUT, CARS_MD_TEMPLATE class TestCarDocs: @@ -23,69 +17,10 @@ def test_generator(self): with open(CARS_MD_OUT) as f: current_cars_md = f.read() - assert generated_cars_md == current_cars_md, "Run selfdrive/car/docs.py to update the compatibility documentation" + assert generated_cars_md == current_cars_md, "Run selfdrive/opcar/docs.py to update the compatibility documentation" def test_docs_diff(self): dump_path = os.path.join(BASEDIR, "selfdrive", "car", "tests", "cars_dump") dump_car_docs(dump_path) print_car_docs_diff(dump_path) os.remove(dump_path) - - def test_duplicate_years(self, subtests): - make_model_years = defaultdict(list) - for car in self.all_cars: - with subtests.test(car_docs_name=car.name): - make_model = (car.make, car.model) - for year in car.year_list: - assert year not in make_model_years[make_model], f"{car.name}: Duplicate model year" - make_model_years[make_model].append(year) - - def test_missing_car_docs(self, subtests): - all_car_docs_platforms = [name for name, config in PLATFORMS.items()] - for platform in sorted(interfaces.keys()): - with subtests.test(platform=platform): - assert platform in all_car_docs_platforms, f"Platform: {platform} doesn't have a CarDocs entry" - - def test_naming_conventions(self, subtests): - # Asserts market-standard car naming conventions by brand - for car in self.all_cars: - with subtests.test(car=car.name): - tokens = car.model.lower().split(" ") - if car.car_name == "hyundai": - assert "phev" not in tokens, "Use `Plug-in Hybrid`" - assert "hev" not in tokens, "Use `Hybrid`" - if "plug-in hybrid" in car.model.lower(): - assert "Plug-in Hybrid" in car.model, "Use correct capitalization" - if car.make != "Kia": - assert "ev" not in tokens, "Use `Electric`" - elif car.car_name == "toyota": - if "rav4" in tokens: - assert "RAV4" in car.model, "Use correct capitalization" - - def test_torque_star(self, subtests): - # Asserts brand-specific assumptions around steering torque star - for car in self.all_cars: - with subtests.test(car=car.name): - # honda sanity check, it's the definition of a no torque star - if car.car_fingerprint in (HONDA.HONDA_ACCORD, HONDA.HONDA_CIVIC, HONDA.HONDA_CRV, HONDA.HONDA_ODYSSEY, HONDA.HONDA_PILOT): - assert car.row[Column.STEERING_TORQUE] == Star.EMPTY, f"{car.name} has full torque star" - elif car.car_name in ("toyota", "hyundai"): - assert car.row[Column.STEERING_TORQUE] != Star.EMPTY, f"{car.name} has no torque star" - - def test_year_format(self, subtests): - for car in self.all_cars: - with subtests.test(car=car.name): - assert re.search(r"\d{4}-\d{4}", car.name) is None, f"Format years correctly: {car.name}" - - def test_harnesses(self, subtests): - for car in self.all_cars: - with subtests.test(car=car.name): - if car.name == "comma body": - pytest.skip() - - car_part_type = [p.part_type for p in car.car_parts.all_parts()] - car_parts = list(car.car_parts.all_parts()) - assert len(car_parts) > 0, f"Need to specify car parts: {car.name}" - assert car_part_type.count(PartType.connector) == 1, f"Need to specify one harness connector: {car.name}" - assert car_part_type.count(PartType.mount) == 1, f"Need to specify one mount: {car.name}" - assert Cable.right_angle_obd_c_cable_1_5ft in car_parts, f"Need to specify a right angle OBD-C cable (1.5ft): {car.name}" diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py deleted file mode 100644 index f9b7a478e0baec0..000000000000000 --- a/selfdrive/car/toyota/carcontroller.py +++ /dev/null @@ -1,179 +0,0 @@ -from cereal import car -from openpilot.common.numpy_fast import clip -from openpilot.selfdrive.car import apply_meas_steer_torque_limits, apply_std_steer_angle_limits, common_fault_avoidance, make_can_msg -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.toyota import toyotacan -from openpilot.selfdrive.car.toyota.values import CAR, STATIC_DSU_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \ - CarControllerParams, ToyotaFlags, \ - UNSUPPORTED_DSU_CAR -from opendbc.can.packer import CANPacker - -SteerControlType = car.CarParams.SteerControlType -VisualAlert = car.CarControl.HUDControl.VisualAlert - -# LKA limits -# EPS faults if you apply torque while the steering rate is above 100 deg/s for too long -MAX_STEER_RATE = 100 # deg/s -MAX_STEER_RATE_FRAMES = 18 # tx control frames needed before torque can be cut - -# EPS allows user torque above threshold for 50 frames before permanently faulting -MAX_USER_TORQUE = 500 - -# LTA limits -# EPS ignores commands above this angle and causes PCS to fault -MAX_LTA_ANGLE = 94.9461 # deg -MAX_LTA_DRIVER_TORQUE_ALLOWANCE = 150 # slightly above steering pressed allows some resistance when changing lanes - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.params = CarControllerParams(self.CP) - self.frame = 0 - self.last_steer = 0 - self.last_angle = 0 - self.alert_active = False - self.last_standstill = False - self.standstill_req = False - self.steer_rate_counter = 0 - self.distance_button = 0 - - self.packer = CANPacker(dbc_name) - self.gas = 0 - self.accel = 0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - pcm_cancel_cmd = CC.cruiseControl.cancel - lat_active = CC.latActive and abs(CS.out.steeringTorque) < MAX_USER_TORQUE - - # *** control msgs *** - can_sends = [] - - # *** steer torque *** - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - 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, lat_active, - self.steer_rate_counter, MAX_STEER_RATE_FRAMES) - - if not lat_active: - apply_steer = 0 - - # *** steer angle *** - if self.CP.steerControlType == SteerControlType.angle: - # If using LTA control, disable LKA and set steering angle command - apply_steer = 0 - apply_steer_req = False - if self.frame % 2 == 0: - # EPS uses the torque sensor angle to control with, offset to compensate - 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.vEgoRaw, self.params) - - if not lat_active: - apply_angle = CS.out.steeringAngleDeg + CS.out.steeringAngleOffsetDeg - - self.last_angle = clip(apply_angle, -MAX_LTA_ANGLE, MAX_LTA_ANGLE) - - self.last_steer = apply_steer - - # 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_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 *** - pcm_accel_cmd = clip(actuators.accel, self.params.ACCEL_MIN, self.params.ACCEL_MAX) - - # on entering standstill, send standstill request - if CS.out.standstill and not self.last_standstill and (self.CP.carFingerprint not in NO_STOP_TIMER_CAR): - self.standstill_req = True - if CS.pcm_acc_status != 8: - # pcm entered standstill or it's disabled - self.standstill_req = False - - self.last_standstill = CS.out.standstill - - # handle UI messages - fcw_alert = hud_control.visualAlert == VisualAlert.fcw - steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) - - # we can spam can to cancel the system even if we are using lat only control - if (self.frame % 3 == 0 and self.CP.openpilotLongitudinalControl) or pcm_cancel_cmd: - lead = hud_control.leadVisible or CS.out.vEgo < 12. # at low speed we always assume the lead is present so ACC can be engaged - - # Press distance button until we are at the correct bar length. Only change while enabled to avoid skipping startup popup - if self.frame % 6 == 0 and self.CP.openpilotLongitudinalControl: - desired_distance = 4 - hud_control.leadDistanceBars - if CS.out.cruiseState.enabled and CS.pcm_follow_distance != desired_distance: - self.distance_button = not self.distance_button - else: - self.distance_button = 0 - - # Lexus IS uses a different cancellation message - if pcm_cancel_cmd and self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: - can_sends.append(toyotacan.create_acc_cancel_command(self.packer)) - elif self.CP.openpilotLongitudinalControl: - can_sends.append(toyotacan.create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead, CS.acc_type, fcw_alert, - self.distance_button)) - self.accel = pcm_accel_cmd - else: - can_sends.append(toyotacan.create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead, CS.acc_type, False, self.distance_button)) - - # *** hud ui *** - if self.CP.carFingerprint != CAR.TOYOTA_PRIUS_V: - # ui mesg is at 1Hz but we send asap if: - # - there is something to display - # - there is something to stop displaying - send_ui = False - if ((fcw_alert or steer_alert) and not self.alert_active) or \ - (not (fcw_alert or steer_alert) and self.alert_active): - send_ui = True - self.alert_active = not self.alert_active - elif pcm_cancel_cmd: - # forcing the pcm to disengage causes a bad fault sound so play a good sound instead - send_ui = True - - if self.frame % 20 == 0 or send_ui: - can_sends.append(toyotacan.create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, - hud_control.rightLaneVisible, hud_control.leftLaneDepart, - hud_control.rightLaneDepart, CC.enabled, CS.lkas_hud)) - - if (self.frame % 100 == 0 or send_ui) and (self.CP.enableDsu or self.CP.flags & ToyotaFlags.DISABLE_RADAR.value): - can_sends.append(toyotacan.create_fcw_command(self.packer, fcw_alert)) - - # *** static msgs *** - for addr, cars, bus, fr_step, vl in STATIC_DSU_MSGS: - if self.frame % fr_step == 0 and self.CP.enableDsu and self.CP.carFingerprint in cars: - can_sends.append(make_can_msg(addr, vl, bus)) - - # keep radar disabled - if self.frame % 20 == 0 and self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: - can_sends.append([0x750, 0, b"\x0F\x02\x3E\x00\x00\x00\x00\x00", 0]) - - new_actuators = actuators.as_builder() - new_actuators.steer = apply_steer / self.params.STEER_MAX - new_actuators.steerOutputCan = apply_steer - new_actuators.steeringAngleDeg = self.last_angle - new_actuators.accel = self.accel - new_actuators.gas = self.gas - - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py deleted file mode 100644 index 8315f24ae48d8b9..000000000000000 --- a/selfdrive/car/toyota/carstate.py +++ /dev/null @@ -1,247 +0,0 @@ -import copy - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import mean -from openpilot.common.filter_simple import FirstOrderFilter -from openpilot.common.realtime import DT_CTRL -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, \ - TSS2_CAR, RADAR_ACC_CAR, EPS_SCALE, UNSUPPORTED_DSU_CAR - -SteerControlType = car.CarParams.SteerControlType - -# These steering fault definitions seem to be common across LKA (torque) and LTA (angle): -# - high steer rate fault: goes to 21 or 25 for 1 frame, then 9 for 2 seconds -# - lka/lta msg drop out: goes to 9 then 11 for a combined total of 2 seconds, then 3. -# if using the other control command, goes directly to 3 after 1.5 seconds -# - initializing: LTA can report 0 as long as STEER_TORQUE_SENSOR->STEER_ANGLE_INITIALIZING is 1, -# and is a catch-all for LKA -TEMP_STEER_FAULTS = (0, 9, 11, 21, 25) -# - lka/lta msg drop out: 3 (recoverable) -# - prolonged high driver torque: 17 (permanent) -PERM_STEER_FAULTS = (3, 17) - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["GEAR_PACKET"]["GEAR"] - self.eps_torque_scale = EPS_SCALE[CP.carFingerprint] / 100. - self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. - self.cluster_min_speed = CV.KPH_TO_MS / 2. - - # On cars with cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] - # the signal is zeroed to where the steering angle is at start. - # Need to apply an offset as soon as the steering angle measurements are both received - self.accurate_steer_angle_seen = False - self.angle_offset = FirstOrderFilter(None, 60.0, DT_CTRL, initialized=False) - - self.prev_distance_button = 0 - self.distance_button = 0 - - self.pcm_follow_distance = 0 - - self.low_speed_lockout = False - self.acc_type = 1 - self.lkas_hud = {} - - def update(self, cp, cp_cam): - ret = car.CarState.new_message() - - ret.doorOpen = any([cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FR"], - cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = cp.vl["BODY_CONTROL_STATE"]["SEATBELT_DRIVER_UNLATCHED"] != 0 - ret.parkingBrake = cp.vl["BODY_CONTROL_STATE"]["PARKING_BRAKE"] == 1 - - ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 - ret.brakeHoldActive = cp.vl["ESP_CONTROL"]["BRAKE_HOLD_ACTIVE"] == 1 - - ret.gasPressed = cp.vl["PCM_CRUISE"]["GAS_RELEASED"] == 0 - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], - ) - ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]) - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.vEgoCluster = ret.vEgo * 1.015 # minimum of all the cars - - 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"] - torque_sensor_angle_deg = cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] - - # On some cars, the angle measurement is non-zero while initializing - if abs(torque_sensor_angle_deg) > 1e-3 and not bool(cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE_INITIALIZING"]): - self.accurate_steer_angle_seen = True - - if self.accurate_steer_angle_seen: - # Offset seems to be invalid for large steering angles and high angle rates - if abs(ret.steeringAngleDeg) < 90 and abs(ret.steeringRateDeg) < 100 and cp.can_valid: - self.angle_offset.update(torque_sensor_angle_deg - ret.steeringAngleDeg) - - if self.angle_offset.initialized: - ret.steeringAngleOffsetDeg = self.angle_offset.x - ret.steeringAngleDeg = torque_sensor_angle_deg - self.angle_offset.x - - can_gear = int(cp.vl["GEAR_PACKET"]["GEAR"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - ret.leftBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 1 - ret.rightBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 2 - - if self.CP.carFingerprint != CAR.TOYOTA_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 - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - - # Check EPS LKA/LTA fault status - ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] in TEMP_STEER_FAULTS - ret.steerFaultPermanent = cp.vl["EPS_STATUS"]["LKA_STATE"] in PERM_STEER_FAULTS - - if self.CP.steerControlType == SteerControlType.angle: - ret.steerFaultTemporary = ret.steerFaultTemporary or cp.vl["EPS_STATUS"]["LTA_STATE"] in TEMP_STEER_FAULTS - ret.steerFaultPermanent = ret.steerFaultPermanent or cp.vl["EPS_STATUS"]["LTA_STATE"] in PERM_STEER_FAULTS - - if self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: - # TODO: find the bit likely in DSU_CRUISE that describes an ACC fault. one may also exist in CLUTCH - ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 - ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS - cluster_set_speed = cp.vl["PCM_CRUISE_ALT"]["UI_SET_SPEED"] - else: - ret.accFaulted = cp.vl["PCM_CRUISE_2"]["ACC_FAULTED"] != 0 - ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 - ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS - cluster_set_speed = cp.vl["PCM_CRUISE_SM"]["UI_SET_SPEED"] - - # UI_SET_SPEED is always non-zero when main is on, hide until first enable - if ret.cruiseState.speed != 0: - is_metric = cp.vl["BODY_CONTROL_STATE_2"]["UNITS"] in (1, 2) - conversion_factor = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS - ret.cruiseState.speedCluster = cluster_set_speed * conversion_factor - - cp_acc = cp_cam if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) else cp - - if self.CP.carFingerprint in TSS2_CAR and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: - if not (self.CP.flags & ToyotaFlags.SMART_DSU.value): - self.acc_type = cp_acc.vl["ACC_CONTROL"]["ACC_TYPE"] - ret.stockFcw = bool(cp_acc.vl["PCS_HUD"]["FCW"]) - - # some TSS2 cars have low speed lockout permanently set, so ignore on those cars - # these cars are identified by an ACC_TYPE value of 2. - # TODO: it is possible to avoid the lockout and gain stop and go if you - # send your own ACC_CONTROL msg on startup with ACC_TYPE set to 1 - if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR) or \ - (self.CP.carFingerprint in TSS2_CAR and self.acc_type == 1): - self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]["LOW_SPEED_LOCKOUT"] == 2 - - self.pcm_acc_status = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] - if self.CP.carFingerprint not in (NO_STOP_TIMER_CAR - TSS2_CAR): - # ignore standstill state in certain vehicles, since pcm allows to restart with just an acceleration request - ret.cruiseState.standstill = self.pcm_acc_status == 7 - ret.cruiseState.enabled = bool(cp.vl["PCM_CRUISE"]["CRUISE_ACTIVE"]) - ret.cruiseState.nonAdaptive = self.pcm_acc_status in (1, 2, 3, 4, 5, 6) - - ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"]) - ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 - - if not self.CP.enableDsu and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: - ret.stockAeb = bool(cp_acc.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_acc.vl["PRE_COLLISION"]["FORCE"] < -1e-5) - - if self.CP.enableBsm: - ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1) - ret.rightBlindspot = (cp.vl["BSM"]["R_ADJACENT"] == 1) or (cp.vl["BSM"]["R_APPROACHING"] == 1) - - if self.CP.carFingerprint != CAR.TOYOTA_PRIUS_V: - self.lkas_hud = copy.copy(cp_cam.vl["LKAS_HUD"]) - - if self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR: - self.pcm_follow_distance = cp.vl["PCM_CRUISE_2"]["PCM_FOLLOW_DISTANCE"] - - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) or (self.CP.flags & ToyotaFlags.SMART_DSU and not self.CP.flags & ToyotaFlags.RADAR_CAN_FILTER): - # distance button is wired to the ACC module (camera or radar) - self.prev_distance_button = self.distance_button - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): - self.distance_button = cp_acc.vl["ACC_CONTROL"]["DISTANCE"] - else: - self.distance_button = cp.vl["SDSU"]["FD_BUTTON"] - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - ("GEAR_PACKET", 1), - ("LIGHT_STALK", 1), - ("BLINKERS_STATE", 0.15), - ("BODY_CONTROL_STATE", 3), - ("BODY_CONTROL_STATE_2", 2), - ("ESP_CONTROL", 3), - ("EPS_STATUS", 25), - ("BRAKE_MODULE", 40), - ("WHEEL_SPEEDS", 80), - ("STEER_ANGLE_SENSOR", 80), - ("PCM_CRUISE", 33), - ("PCM_CRUISE_SM", 1), - ("STEER_TORQUE_SENSOR", 50), - ] - - if CP.carFingerprint != CAR.TOYOTA_MIRAI: - messages.append(("ENGINE_RPM", 42)) - - if CP.carFingerprint in UNSUPPORTED_DSU_CAR: - messages.append(("DSU_CRUISE", 5)) - messages.append(("PCM_CRUISE_ALT", 1)) - else: - messages.append(("PCM_CRUISE_2", 33)) - - if CP.enableBsm: - messages.append(("BSM", 1)) - - if CP.carFingerprint in RADAR_ACC_CAR and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: - if not CP.flags & ToyotaFlags.SMART_DSU.value: - messages += [ - ("ACC_CONTROL", 33), - ] - messages += [ - ("PCS_HUD", 1), - ] - - if CP.carFingerprint not in (TSS2_CAR - RADAR_ACC_CAR) and not CP.enableDsu and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: - messages += [ - ("PRE_COLLISION", 33), - ] - - if CP.flags & ToyotaFlags.SMART_DSU and not CP.flags & ToyotaFlags.RADAR_CAN_FILTER: - messages += [ - ("SDSU", 100), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - - if CP.carFingerprint != CAR.TOYOTA_PRIUS_V: - messages += [ - ("LKAS_HUD", 1), - ] - - if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): - messages += [ - ("PRE_COLLISION", 33), - ("ACC_CONTROL", 33), - ("PCS_HUD", 1), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/toyota/fingerprints.py b/selfdrive/car/toyota/fingerprints.py deleted file mode 100644 index 0866a4d43ca8639..000000000000000 --- a/selfdrive/car/toyota/fingerprints.py +++ /dev/null @@ -1,1681 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.toyota.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.TOYOTA_AVALON: { - (Ecu.abs, 0x7b0, None): [ - b'F152607060\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510701300\x00\x00\x00\x00', - b'881510705100\x00\x00\x00\x00', - b'881510705200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41051\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0701100\x00\x00\x00\x00', - b'8646F0703000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_AVALON_2019: { - (Ecu.abs, 0x7b0, None): [ - b'F152607110\x00\x00\x00\x00\x00\x00', - b'F152607140\x00\x00\x00\x00\x00\x00', - b'F152607171\x00\x00\x00\x00\x00\x00', - b'F152607180\x00\x00\x00\x00\x00\x00', - b'F152641040\x00\x00\x00\x00\x00\x00', - b'F152641050\x00\x00\x00\x00\x00\x00', - b'F152641060\x00\x00\x00\x00\x00\x00', - b'F152641061\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510703200\x00\x00\x00\x00', - b'881510704200\x00\x00\x00\x00', - b'881514107100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B07010\x00\x00\x00\x00\x00\x00', - b'8965B41070\x00\x00\x00\x00\x00\x00', - b'8965B41080\x00\x00\x00\x00\x00\x00', - b'8965B41090\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630725100\x00\x00\x00\x00', - b'\x01896630725200\x00\x00\x00\x00', - b'\x01896630725300\x00\x00\x00\x00', - b'\x01896630725400\x00\x00\x00\x00', - b'\x01896630735100\x00\x00\x00\x00', - b'\x01896630738000\x00\x00\x00\x00', - b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x02896630728000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x02896630734000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x02896630737000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0702100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_AVALON_TSS2: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F152607240\x00\x00\x00\x00\x00\x00', - b'\x01F152607250\x00\x00\x00\x00\x00\x00', - b'\x01F152607280\x00\x00\x00\x00\x00\x00', - b'F152641080\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41110\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x01896630742000\x00\x00\x00\x00', - b'\x01896630743000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_CAMRY: { - (Ecu.engine, 0x700, None): [ - b'\x018966306L3100\x00\x00\x00\x00', - b'\x018966306L4200\x00\x00\x00\x00', - b'\x018966306L5200\x00\x00\x00\x00', - b'\x018966306L9000\x00\x00\x00\x00', - b'\x018966306P8000\x00\x00\x00\x00', - b'\x018966306Q3100\x00\x00\x00\x00', - b'\x018966306Q4000\x00\x00\x00\x00', - b'\x018966306Q4100\x00\x00\x00\x00', - b'\x018966306Q4200\x00\x00\x00\x00', - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x018966333N1100\x00\x00\x00\x00', - b'\x018966333N4300\x00\x00\x00\x00', - b'\x018966333P3100\x00\x00\x00\x00', - b'\x018966333P3200\x00\x00\x00\x00', - b'\x018966333P4200\x00\x00\x00\x00', - b'\x018966333P4300\x00\x00\x00\x00', - b'\x018966333P4400\x00\x00\x00\x00', - b'\x018966333P4500\x00\x00\x00\x00', - b'\x018966333P4700\x00\x00\x00\x00', - b'\x018966333P4900\x00\x00\x00\x00', - b'\x018966333Q6000\x00\x00\x00\x00', - b'\x018966333Q6200\x00\x00\x00\x00', - b'\x018966333Q6300\x00\x00\x00\x00', - b'\x018966333Q6500\x00\x00\x00\x00', - b'\x018966333Q9200\x00\x00\x00\x00', - b'\x018966333W6000\x00\x00\x00\x00', - b'\x018966333X0000\x00\x00\x00\x00', - b'\x018966333X4000\x00\x00\x00\x00', - b'\x01896633T16000\x00\x00\x00\x00', - b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306B2500\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8200\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8400\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R5000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R6000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S0000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02333P1100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'8821F0601200 ', - b'8821F0601300 ', - b'8821F0601400 ', - b'8821F0601500 ', - b'8821F0602000 ', - b'8821F0603300 ', - b'8821F0603400 ', - b'8821F0604000 ', - b'8821F0604100 ', - b'8821F0604200 ', - b'8821F0605200 ', - b'8821F0606200 ', - b'8821F0607200 ', - b'8821F0608000 ', - b'8821F0608200 ', - b'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'8646F0604000 ', - b'8646F0604100 ', - b'8646F0605000 ', - b'8646F0606000 ', - b'8646F0606100 ', - b'8646F0607000 ', - b'8646F0607100 ', - ], - }, - CAR.TOYOTA_CAMRY_TSS2: { - (Ecu.eps, 0x7a1, None): [ - b'8965B33630\x00\x00\x00\x00\x00\x00', - b'8965B33640\x00\x00\x00\x00\x00\x00', - b'8965B33650\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152606370\x00\x00\x00\x00\x00\x00', - b'\x01F152606390\x00\x00\x00\x00\x00\x00', - b'\x01F152606400\x00\x00\x00\x00\x00\x00', - b'\x01F152606431\x00\x00\x00\x00\x00\x00', - b'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.TOYOTA_CHR: { - (Ecu.engine, 0x700, None): [ - b'\x01896631017100\x00\x00\x00\x00', - b'\x01896631017200\x00\x00\x00\x00', - b'\x01896631021100\x00\x00\x00\x00', - b'\x0189663F413100\x00\x00\x00\x00', - b'\x0189663F414100\x00\x00\x00\x00', - b'\x0189663F438000\x00\x00\x00\x00', - b'\x02896631013200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F405000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F405100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F418000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'8821F0W01000 ', - b'8821F0W01100 ', - b'8821FF401600 ', - b'8821FF402300 ', - b'8821FF402400 ', - b'8821FF404000 ', - b'8821FF404100 ', - b'8821FF405000 ', - b'8821FF405100 ', - b'8821FF406000 ', - b'8821FF407100 ', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152610012\x00\x00\x00\x00\x00\x00', - b'F152610013\x00\x00\x00\x00\x00\x00', - b'F152610014\x00\x00\x00\x00\x00\x00', - b'F152610020\x00\x00\x00\x00\x00\x00', - b'F152610040\x00\x00\x00\x00\x00\x00', - b'F152610153\x00\x00\x00\x00\x00\x00', - b'F152610190\x00\x00\x00\x00\x00\x00', - b'F152610200\x00\x00\x00\x00\x00\x00', - b'F152610210\x00\x00\x00\x00\x00\x00', - b'F152610220\x00\x00\x00\x00\x00\x00', - b'F152610230\x00\x00\x00\x00\x00\x00', - b'F1526F4034\x00\x00\x00\x00\x00\x00', - b'F1526F4044\x00\x00\x00\x00\x00\x00', - b'F1526F4073\x00\x00\x00\x00\x00\x00', - b'F1526F4121\x00\x00\x00\x00\x00\x00', - b'F1526F4122\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B10011\x00\x00\x00\x00\x00\x00', - b'8965B10020\x00\x00\x00\x00\x00\x00', - b'8965B10040\x00\x00\x00\x00\x00\x00', - b'8965B10050\x00\x00\x00\x00\x00\x00', - b'8965B10070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x0331036000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x033F401100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203102\x00\x00\x00\x00', - b'\x033F401200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F0W01000 ', - b'8821F0W01100 ', - b'8821FF401600 ', - b'8821FF402300 ', - b'8821FF402400 ', - b'8821FF404000 ', - b'8821FF404100 ', - b'8821FF405000 ', - b'8821FF405100 ', - b'8821FF406000 ', - b'8821FF407100 ', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646FF401700 ', - b'8646FF401800 ', - b'8646FF402100 ', - b'8646FF404000 ', - b'8646FF406000 ', - b'8646FF407000 ', - b'8646FF407100 ', - ], - }, - CAR.TOYOTA_CHR_TSS2: { - (Ecu.abs, 0x7b0, None): [ - b'F152610041\x00\x00\x00\x00\x00\x00', - b'F152610260\x00\x00\x00\x00\x00\x00', - b'F1526F4270\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B10091\x00\x00\x00\x00\x00\x00', - b'8965B10092\x00\x00\x00\x00\x00\x00', - b'8965B10110\x00\x00\x00\x00\x00\x00', - b'8965B10111\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x0189663F438000\x00\x00\x00\x00', - b'\x0189663F459000\x00\x00\x00\x00', - b'\x02896631025000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F453000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0331014000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821FF410200\x00\x00\x00\x00', - b'\x018821FF410300\x00\x00\x00\x00', - b'\x018821FF410400\x00\x00\x00\x00', - b'\x018821FF410500\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00', - b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00', - b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_COROLLA: { - (Ecu.engine, 0x7e0, None): [ - b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0330ZC1200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510201100\x00\x00\x00\x00', - b'881510201200\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152602190\x00\x00\x00\x00\x00\x00', - b'F152602191\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B02181\x00\x00\x00\x00\x00\x00', - b'8965B02191\x00\x00\x00\x00\x00\x00', - b'8965B48150\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0201101\x00\x00\x00\x00', - b'8646F0201200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_COROLLA_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630A22000\x00\x00\x00\x00', - b'\x01896630ZG2000\x00\x00\x00\x00', - b'\x01896630ZG5000\x00\x00\x00\x00', - b'\x01896630ZG5100\x00\x00\x00\x00', - b'\x01896630ZG5200\x00\x00\x00\x00', - b'\x01896630ZG5300\x00\x00\x00\x00', - b'\x01896630ZJ1000\x00\x00\x00\x00', - b'\x01896630ZP1000\x00\x00\x00\x00', - b'\x01896630ZP2000\x00\x00\x00\x00', - b'\x01896630ZQ5000\x00\x00\x00\x00', - b'\x01896630ZU8000\x00\x00\x00\x00', - b'\x01896630ZU9000\x00\x00\x00\x00', - b'\x01896630ZX4000\x00\x00\x00\x00', - b'\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'\x01F152602281\x00\x00\x00\x00\x00\x00', - b'\x01F152602470\x00\x00\x00\x00\x00\x00', - b'\x01F152602560\x00\x00\x00\x00\x00\x00', - b'\x01F152602590\x00\x00\x00\x00\x00\x00', - b'\x01F152602650\x00\x00\x00\x00\x00\x00', - b'\x01F15260A010\x00\x00\x00\x00\x00\x00', - b'\x01F15260A050\x00\x00\x00\x00\x00\x00', - b'\x01F15260A070\x00\x00\x00\x00\x00\x00', - b'\x01F152612641\x00\x00\x00\x00\x00\x00', - b'\x01F152612651\x00\x00\x00\x00\x00\x00', - b'\x01F152612862\x00\x00\x00\x00\x00\x00', - b'\x01F152612B10\x00\x00\x00\x00\x00\x00', - b'\x01F152612B51\x00\x00\x00\x00\x00\x00', - b'\x01F152612B60\x00\x00\x00\x00\x00\x00', - b'\x01F152612B61\x00\x00\x00\x00\x00\x00', - b'\x01F152612B62\x00\x00\x00\x00\x00\x00', - b'\x01F152612B70\x00\x00\x00\x00\x00\x00', - b'\x01F152612B71\x00\x00\x00\x00\x00\x00', - b'\x01F152612B81\x00\x00\x00\x00\x00\x00', - b'\x01F152612B90\x00\x00\x00\x00\x00\x00', - b'\x01F152612B91\x00\x00\x00\x00\x00\x00', - b'\x01F152612C00\x00\x00\x00\x00\x00\x00', - b'\x01F152676250\x00\x00\x00\x00\x00\x00', - b'F152612590\x00\x00\x00\x00\x00\x00', - b'F152612691\x00\x00\x00\x00\x00\x00', - b'F152612692\x00\x00\x00\x00\x00\x00', - b'F152612700\x00\x00\x00\x00\x00\x00', - b'F152612710\x00\x00\x00\x00\x00\x00', - b'F152612790\x00\x00\x00\x00\x00\x00', - b'F152612800\x00\x00\x00\x00\x00\x00', - b'F152612820\x00\x00\x00\x00\x00\x00', - b'F152612840\x00\x00\x00\x00\x00\x00', - b'F152612842\x00\x00\x00\x00\x00\x00', - b'F152612890\x00\x00\x00\x00\x00\x00', - b'F152612A00\x00\x00\x00\x00\x00\x00', - b'F152612A10\x00\x00\x00\x00\x00\x00', - b'F152612D00\x00\x00\x00\x00\x00\x00', - b'F152616011\x00\x00\x00\x00\x00\x00', - b'F152616030\x00\x00\x00\x00\x00\x00', - b'F152616060\x00\x00\x00\x00\x00\x00', - b'F152642540\x00\x00\x00\x00\x00\x00', - b'F152676293\x00\x00\x00\x00\x00\x00', - b'F152676303\x00\x00\x00\x00\x00\x00', - b'F152676304\x00\x00\x00\x00\x00\x00', - b'F152676371\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F12010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1201400\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1206000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F7603300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F7605100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_HIGHLANDER: { - (Ecu.engine, 0x700, None): [ - b'\x01896630E09000\x00\x00\x00\x00', - b'\x01896630E43000\x00\x00\x00\x00', - b'\x01896630E43100\x00\x00\x00\x00', - b'\x01896630E43200\x00\x00\x00\x00', - b'\x01896630E44200\x00\x00\x00\x00', - b'\x01896630E44400\x00\x00\x00\x00', - b'\x01896630E45000\x00\x00\x00\x00', - b'\x01896630E45100\x00\x00\x00\x00', - b'\x01896630E45200\x00\x00\x00\x00', - b'\x01896630E46000\x00\x00\x00\x00', - b'\x01896630E46200\x00\x00\x00\x00', - b'\x01896630E74000\x00\x00\x00\x00', - b'\x01896630E75000\x00\x00\x00\x00', - b'\x01896630E76000\x00\x00\x00\x00', - b'\x01896630E77000\x00\x00\x00\x00', - b'\x01896630E83000\x00\x00\x00\x00', - b'\x01896630E84000\x00\x00\x00\x00', - b'\x01896630E85000\x00\x00\x00\x00', - b'\x01896630E86000\x00\x00\x00\x00', - b'\x01896630E88000\x00\x00\x00\x00', - b'\x01896630EA0000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230E40100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230E51000\x00\x00\x00\x00\x00\x00\x00\x0050E17000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230EA2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230EA2100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B48140\x00\x00\x00\x00\x00\x00', - b'8965B48150\x00\x00\x00\x00\x00\x00', - b'8965B48160\x00\x00\x00\x00\x00\x00', - b'8965B48210\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F15260E011\x00\x00\x00\x00\x00\x00', - b'F152648541\x00\x00\x00\x00\x00\x00', - b'F152648542\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510E01100\x00\x00\x00\x00', - b'881510E01200\x00\x00\x00\x00', - b'881510E02200\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0E01200\x00\x00\x00\x00', - b'8646F0E01300\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_HIGHLANDER_TSS2: { - (Ecu.eps, 0x7a1, None): [ - b'8965B48241\x00\x00\x00\x00\x00\x00', - b'8965B48310\x00\x00\x00\x00\x00\x00', - b'8965B48320\x00\x00\x00\x00\x00\x00', - b'8965B48400\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260E051\x00\x00\x00\x00\x00\x00', - b'\x01F15260E05300\x00\x00\x00\x00', - b'\x01F15260E061\x00\x00\x00\x00\x00\x00', - b'\x01F15260E110\x00\x00\x00\x00\x00\x00', - b'\x01F15260E170\x00\x00\x00\x00\x00\x00', - b'\x01F15264872300\x00\x00\x00\x00', - b'\x01F15264872400\x00\x00\x00\x00', - b'\x01F15264872500\x00\x00\x00\x00', - b'\x01F15264872600\x00\x00\x00\x00', - b'\x01F15264872700\x00\x00\x00\x00', - b'\x01F15264873500\x00\x00\x00\x00', - b'\x01F152648C6300\x00\x00\x00\x00', - b'\x01F152648J4000\x00\x00\x00\x00', - b'\x01F152648J5000\x00\x00\x00\x00', - b'\x01F152648J6000\x00\x00\x00\x00', - b'\x01F152648J7000\x00\x00\x00\x00', - b'\x01F152648L5000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630E62100\x00\x00\x00\x00', - b'\x01896630E62200\x00\x00\x00\x00', - b'\x01896630E64100\x00\x00\x00\x00', - b'\x01896630E64200\x00\x00\x00\x00', - b'\x01896630E64400\x00\x00\x00\x00', - b'\x01896630E67000\x00\x00\x00\x00', - b'\x01896630EA1000\x00\x00\x00\x00', - b'\x01896630EB1000\x00\x00\x00\x00', - b'\x01896630EB1100\x00\x00\x00\x00', - b'\x01896630EB1200\x00\x00\x00\x00', - b'\x01896630EB1300\x00\x00\x00\x00', - b'\x01896630EB2000\x00\x00\x00\x00', - b'\x01896630EB2100\x00\x00\x00\x00', - b'\x01896630EB2200\x00\x00\x00\x00', - b'\x01896630EC4000\x00\x00\x00\x00', - b'\x01896630ED9000\x00\x00\x00\x00', - b'\x01896630ED9100\x00\x00\x00\x00', - b'\x01896630EE1000\x00\x00\x00\x00', - b'\x01896630EE1100\x00\x00\x00\x00', - b'\x01896630EE4000\x00\x00\x00\x00', - b'\x01896630EE4100\x00\x00\x00\x00', - b'\x01896630EE5000\x00\x00\x00\x00', - b'\x01896630EE6000\x00\x00\x00\x00', - b'\x01896630EE7000\x00\x00\x00\x00', - b'\x01896630EF8000\x00\x00\x00\x00', - b'\x01896630EG3000\x00\x00\x00\x00', - b'\x01896630EG5000\x00\x00\x00\x00', - b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630EB3100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_IS: { - (Ecu.engine, 0x700, None): [ - b'\x018966353M7000\x00\x00\x00\x00', - b'\x018966353M7100\x00\x00\x00\x00', - b'\x018966353Q2000\x00\x00\x00\x00', - b'\x018966353Q2100\x00\x00\x00\x00', - b'\x018966353Q2300\x00\x00\x00\x00', - b'\x018966353Q4000\x00\x00\x00\x00', - b'\x018966353R1100\x00\x00\x00\x00', - b'\x018966353R7100\x00\x00\x00\x00', - b'\x018966353R8000\x00\x00\x00\x00', - b'\x018966353R8100\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0232480000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152653300\x00\x00\x00\x00\x00\x00', - b'F152653301\x00\x00\x00\x00\x00\x00', - b'F152653310\x00\x00\x00\x00\x00\x00', - b'F152653330\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881515306200\x00\x00\x00\x00', - b'881515306400\x00\x00\x00\x00', - b'881515306500\x00\x00\x00\x00', - b'881515307400\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B53270\x00\x00\x00\x00\x00\x00', - b'8965B53271\x00\x00\x00\x00\x00\x00', - b'8965B53280\x00\x00\x00\x00\x00\x00', - b'8965B53281\x00\x00\x00\x00\x00\x00', - b'8965B53311\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F5301101\x00\x00\x00\x00', - b'8646F5301200\x00\x00\x00\x00', - b'8646F5301300\x00\x00\x00\x00', - b'8646F5301400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_IS_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966353S1000\x00\x00\x00\x00', - b'\x018966353S2000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02353U0000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15265337200\x00\x00\x00\x00', - b'\x01F15265342000\x00\x00\x00\x00', - b'\x01F15265343000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B53450\x00\x00\x00\x00\x00\x00', - b'8965B53800\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F5303300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F5303400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS: { - (Ecu.engine, 0x700, None): [ - b'\x02896634761000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634761100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634761200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634762000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634762100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634763000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634763100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634765000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634770000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634770100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634782000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347B0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701002\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703001\x00\x00\x00\x00', - b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x03896634768100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', - b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', - b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', - b'\x038966347B6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B47021\x00\x00\x00\x00\x00\x00', - b'8965B47022\x00\x00\x00\x00\x00\x00', - b'8965B47023\x00\x00\x00\x00\x00\x00', - b'8965B47050\x00\x00\x00\x00\x00\x00', - b'8965B47060\x00\x00\x00\x00\x00\x00', - b'8965B47070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152647290\x00\x00\x00\x00\x00\x00', - b'F152647300\x00\x00\x00\x00\x00\x00', - b'F152647310\x00\x00\x00\x00\x00\x00', - b'F152647414\x00\x00\x00\x00\x00\x00', - b'F152647415\x00\x00\x00\x00\x00\x00', - b'F152647416\x00\x00\x00\x00\x00\x00', - b'F152647417\x00\x00\x00\x00\x00\x00', - b'F152647470\x00\x00\x00\x00\x00\x00', - b'F152647490\x00\x00\x00\x00\x00\x00', - b'F152647682\x00\x00\x00\x00\x00\x00', - b'F152647683\x00\x00\x00\x00\x00\x00', - b'F152647684\x00\x00\x00\x00\x00\x00', - b'F152647862\x00\x00\x00\x00\x00\x00', - b'F152647863\x00\x00\x00\x00\x00\x00', - b'F152647864\x00\x00\x00\x00\x00\x00', - b'F152647865\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514702300\x00\x00\x00\x00', - b'881514702400\x00\x00\x00\x00', - b'881514703100\x00\x00\x00\x00', - b'881514704100\x00\x00\x00\x00', - b'881514706000\x00\x00\x00\x00', - b'881514706100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4701300\x00\x00\x00\x00', - b'8646F4702001\x00\x00\x00\x00', - b'8646F4702100\x00\x00\x00\x00', - b'8646F4702200\x00\x00\x00\x00', - b'8646F4705000\x00\x00\x00\x00', - b'8646F4705200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS_V: { - (Ecu.abs, 0x7b0, None): [ - b'F152647280\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0234781000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514705100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4703300\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4: { - (Ecu.engine, 0x7e0, None): [ - b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1100\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1200\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1300\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2000\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2100\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2200\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q4000\x00\x00\x00\x00\x00\x00\x00\x0054215000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42063\x00\x00\x00\x00\x00\x00', - b'8965B42073\x00\x00\x00\x00\x00\x00', - b'8965B42082\x00\x00\x00\x00\x00\x00', - b'8965B42083\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F15260R102\x00\x00\x00\x00\x00\x00', - b'F15260R103\x00\x00\x00\x00\x00\x00', - b'F152642492\x00\x00\x00\x00\x00\x00', - b'F152642493\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514201200\x00\x00\x00\x00', - b'881514201300\x00\x00\x00\x00', - b'881514201400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4201100\x00\x00\x00\x00', - b'8646F4201200\x00\x00\x00\x00', - b'8646F4202001\x00\x00\x00\x00', - b'8646F4202100\x00\x00\x00\x00', - b'8646F4204000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4H: { - (Ecu.engine, 0x7e0, None): [ - b'\x02342N9000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342N9100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342P0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42102\x00\x00\x00\x00\x00\x00', - b'8965B42103\x00\x00\x00\x00\x00\x00', - b'8965B42112\x00\x00\x00\x00\x00\x00', - b'8965B42162\x00\x00\x00\x00\x00\x00', - b'8965B42163\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152642090\x00\x00\x00\x00\x00\x00', - b'F152642110\x00\x00\x00\x00\x00\x00', - b'F152642120\x00\x00\x00\x00\x00\x00', - b'F152642400\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514202200\x00\x00\x00\x00', - b'881514202300\x00\x00\x00\x00', - b'881514202400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4201100\x00\x00\x00\x00', - b'8646F4201200\x00\x00\x00\x00', - b'8646F4202001\x00\x00\x00\x00', - b'8646F4202100\x00\x00\x00\x00', - b'8646F4204000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630R58000\x00\x00\x00\x00', - b'\x01896630R58100\x00\x00\x00\x00', - b'\x018966342E2000\x00\x00\x00\x00', - b'\x018966342M5000\x00\x00\x00\x00', - b'\x018966342M8000\x00\x00\x00\x00', - b'\x018966342S9000\x00\x00\x00\x00', - b'\x018966342T1000\x00\x00\x00\x00', - b'\x018966342T6000\x00\x00\x00\x00', - b'\x018966342T9000\x00\x00\x00\x00', - b'\x018966342U4000\x00\x00\x00\x00', - b'\x018966342U4100\x00\x00\x00\x00', - b'\x018966342U5100\x00\x00\x00\x00', - b'\x018966342V0000\x00\x00\x00\x00', - b'\x018966342V3000\x00\x00\x00\x00', - b'\x018966342V3100\x00\x00\x00\x00', - b'\x018966342V3200\x00\x00\x00\x00', - b'\x018966342W5000\x00\x00\x00\x00', - b'\x018966342W7000\x00\x00\x00\x00', - b'\x018966342W8000\x00\x00\x00\x00', - b'\x018966342X5000\x00\x00\x00\x00', - b'\x018966342X6000\x00\x00\x00\x00', - b'\x01896634A05000\x00\x00\x00\x00', - b'\x01896634A15000\x00\x00\x00\x00', - b'\x01896634A19000\x00\x00\x00\x00', - b'\x01896634A19100\x00\x00\x00\x00', - b'\x01896634A20000\x00\x00\x00\x00', - b'\x01896634A20100\x00\x00\x00\x00', - b'\x01896634A22000\x00\x00\x00\x00', - b'\x01896634A22100\x00\x00\x00\x00', - b'\x01896634A25000\x00\x00\x00\x00', - b'\x01896634A30000\x00\x00\x00\x00', - b'\x01896634A44000\x00\x00\x00\x00', - b'\x01896634A45000\x00\x00\x00\x00', - b'\x01896634A46000\x00\x00\x00\x00', - b'\x028966342M7000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342T0000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342V1000\x00\x00\x00\x00897CF1202001\x00\x00\x00\x00', - b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A13000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02896634A13001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A13101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A13201\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF0R01000\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A23000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A23101\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', - b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R210\x00\x00\x00\x00\x00\x00', - b'\x01F15260R220\x00\x00\x00\x00\x00\x00', - b'\x01F15260R290\x00\x00\x00\x00\x00\x00', - b'\x01F15260R292\x00\x00\x00\x00\x00\x00', - b'\x01F15260R300\x00\x00\x00\x00\x00\x00', - b'\x01F15260R302\x00\x00\x00\x00\x00\x00', - b'\x01F152642551\x00\x00\x00\x00\x00\x00', - b'\x01F152642561\x00\x00\x00\x00\x00\x00', - b'\x01F152642601\x00\x00\x00\x00\x00\x00', - b'\x01F152642700\x00\x00\x00\x00\x00\x00', - b'\x01F152642701\x00\x00\x00\x00\x00\x00', - b'\x01F152642710\x00\x00\x00\x00\x00\x00', - b'\x01F152642711\x00\x00\x00\x00\x00\x00', - b'\x01F152642750\x00\x00\x00\x00\x00\x00', - b'\x01F152642751\x00\x00\x00\x00\x00\x00', - b'F152642290\x00\x00\x00\x00\x00\x00', - b'F152642291\x00\x00\x00\x00\x00\x00', - b'F152642322\x00\x00\x00\x00\x00\x00', - b'F152642330\x00\x00\x00\x00\x00\x00', - b'F152642331\x00\x00\x00\x00\x00\x00', - b'F152642520\x00\x00\x00\x00\x00\x00', - b'F152642521\x00\x00\x00\x00\x00\x00', - b'F152642531\x00\x00\x00\x00\x00\x00', - b'F152642532\x00\x00\x00\x00\x00\x00', - b'F152642540\x00\x00\x00\x00\x00\x00', - b'F152642541\x00\x00\x00\x00\x00\x00', - b'F152642542\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', - b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', - b'\x028965B0R01400\x00\x00\x00\x008965B0R02400\x00\x00\x00\x00', - b'8965B42170\x00\x00\x00\x00\x00\x00', - b'8965B42171\x00\x00\x00\x00\x00\x00', - b'8965B42180\x00\x00\x00\x00\x00\x00', - b'8965B42181\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4203200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2_2022: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R350\x00\x00\x00\x00\x00\x00', - b'\x01F15260R361\x00\x00\x00\x00\x00\x00', - b'\x01F15264283100\x00\x00\x00\x00', - b'\x01F15264283200\x00\x00\x00\x00', - b'\x01F15264286100\x00\x00\x00\x00', - b'\x01F15264286200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', - b'8965B42172\x00\x00\x00\x00\x00\x00', - b'8965B42182\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896634A02001\x00\x00\x00\x00', - b'\x01896634A03000\x00\x00\x00\x00', - b'\x01896634A08000\x00\x00\x00\x00', - b'\x01896634A61000\x00\x00\x00\x00', - b'\x01896634A62000\x00\x00\x00\x00', - b'\x01896634A62100\x00\x00\x00\x00', - b'\x01896634A63000\x00\x00\x00\x00', - b'\x01896634A88000\x00\x00\x00\x00', - b'\x01896634A89000\x00\x00\x00\x00', - b'\x01896634A89100\x00\x00\x00\x00', - b'\x01896634AA0000\x00\x00\x00\x00', - b'\x01896634AA0100\x00\x00\x00\x00', - b'\x01896634AA1000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F0R01100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0R02100\x00\x00\x00\x008646G0R01100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R450\x00\x00\x00\x00\x00\x00', - b'\x01F15260R50000\x00\x00\x00\x00', - b'\x01F15260R51000\x00\x00\x00\x00', - b'\x01F15264283200\x00\x00\x00\x00', - b'\x01F15264283300\x00\x00\x00\x00', - b'\x01F152642F1000\x00\x00\x00\x00', - b'\x01F152642F8000\x00\x00\x00\x00', - b'\x01F152642F8100\x00\x00\x00\x00', - b'\x01F152642F9000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R11000\x00\x00\x00\x008965B0R12000\x00\x00\x00\x00', - b'8965B42371\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896634A61000\x00\x00\x00\x00', - b'\x01896634A88100\x00\x00\x00\x00', - b'\x01896634A89100\x00\x00\x00\x00', - b'\x01896634AE1001\x00\x00\x00\x00', - b'\x01896634AF0000\x00\x00\x00\x00', - b'\x01896634AJ2000\x00\x00\x00\x00', - b'\x01896634AL5000\x00\x00\x00\x00', - b'\x01896634AL6000\x00\x00\x00\x00', - b'\x01896634AL8000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F0R03100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0R05100\x00\x00\x00\x008646G0R02100\x00\x00\x00\x00', - b'\x028646F0R05200\x00\x00\x00\x008646G0R02200\x00\x00\x00\x00', - b'\x028646F0R11000\x00\x00\x00\x008646G0R04000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_SIENNA: { - (Ecu.engine, 0x700, None): [ - b'\x01896630832100\x00\x00\x00\x00', - b'\x01896630832200\x00\x00\x00\x00', - b'\x01896630838000\x00\x00\x00\x00', - b'\x01896630838100\x00\x00\x00\x00', - b'\x01896630842000\x00\x00\x00\x00', - b'\x01896630843000\x00\x00\x00\x00', - b'\x01896630851000\x00\x00\x00\x00', - b'\x01896630851100\x00\x00\x00\x00', - b'\x01896630851200\x00\x00\x00\x00', - b'\x01896630852000\x00\x00\x00\x00', - b'\x01896630852100\x00\x00\x00\x00', - b'\x01896630859000\x00\x00\x00\x00', - b'\x01896630860000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B45070\x00\x00\x00\x00\x00\x00', - b'8965B45080\x00\x00\x00\x00\x00\x00', - b'8965B45082\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152608130\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510801100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702200\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0801100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_CTH: { - (Ecu.dsu, 0x791, None): [ - b'881517601100\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152676144\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237635000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F7601100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ES_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966306U6000\x00\x00\x00\x00', - b'\x018966333T5000\x00\x00\x00\x00', - b'\x018966333T5100\x00\x00\x00\x00', - b'\x018966333X6000\x00\x00\x00\x00', - b'\x01896633T07000\x00\x00\x00\x00', - b'\x01896633T38000\x00\x00\x00\x00', - b'\x01896633T58000\x00\x00\x00\x00', - b'\x028966333S8000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966333S8000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333W1000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', - b'\x02896633T10000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152606281\x00\x00\x00\x00\x00\x00', - b'\x01F152606340\x00\x00\x00\x00\x00\x00', - b'\x01F152606461\x00\x00\x00\x00\x00\x00', - b'\x01F15260646200\x00\x00\x00\x00', - b'F152633423\x00\x00\x00\x00\x00\x00', - b'F152633680\x00\x00\x00\x00\x00\x00', - b'F152633681\x00\x00\x00\x00\x00\x00', - b'F152633F50\x00\x00\x00\x00\x00\x00', - b'F152633F51\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33252\x00\x00\x00\x00\x00\x00', - b'8965B33590\x00\x00\x00\x00\x00\x00', - b'8965B33690\x00\x00\x00\x00\x00\x00', - b'8965B33721\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0610000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3303100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3303200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F3304200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F3304300\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F3309100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3309100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ES: { - (Ecu.engine, 0x7e0, None): [ - b'\x02333M4100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02333R0000\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152606202\x00\x00\x00\x00\x00\x00', - b'F152633171\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513309400\x00\x00\x00\x00', - b'881513309500\x00\x00\x00\x00', - b'881513310400\x00\x00\x00\x00', - b'881513310500\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33502\x00\x00\x00\x00\x00\x00', - b'8965B33512\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701100\x00\x00\x00\x00', - b'8821F4701200\x00\x00\x00\x00', - b'8821F4701300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3302001\x00\x00\x00\x00', - b'8646F3302100\x00\x00\x00\x00', - b'8646F3302200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_GS_F: { - (Ecu.engine, 0x7e0, None): [ - b'\x0233075200\x00\x00\x00\x00\x00\x00\x00\x00530B9000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152630700\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513016200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B30551\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3002100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_NX: { - (Ecu.engine, 0x700, None): [ - b'\x01896637850000\x00\x00\x00\x00', - b'\x01896637851000\x00\x00\x00\x00', - b'\x01896637852000\x00\x00\x00\x00', - b'\x01896637854000\x00\x00\x00\x00', - b'\x01896637873000\x00\x00\x00\x00', - b'\x01896637878000\x00\x00\x00\x00', - b'\x01896637878100\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237842000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237880000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152678130\x00\x00\x00\x00\x00\x00', - b'F152678140\x00\x00\x00\x00\x00\x00', - b'F152678160\x00\x00\x00\x00\x00\x00', - b'F152678170\x00\x00\x00\x00\x00\x00', - b'F152678171\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881517803100\x00\x00\x00\x00', - b'881517803300\x00\x00\x00\x00', - b'881517804100\x00\x00\x00\x00', - b'881517804300\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B78060\x00\x00\x00\x00\x00\x00', - b'8965B78080\x00\x00\x00\x00\x00\x00', - b'8965B78100\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F7801100\x00\x00\x00\x00', - b'8646F7801300\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_NX_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966378B2000\x00\x00\x00\x00', - b'\x018966378B2100\x00\x00\x00\x00', - b'\x018966378B3000\x00\x00\x00\x00', - b'\x018966378B3100\x00\x00\x00\x00', - b'\x018966378B4100\x00\x00\x00\x00', - b'\x018966378G2000\x00\x00\x00\x00', - b'\x018966378G3000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237881000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02378A0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02378F4000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152678221\x00\x00\x00\x00\x00\x00', - b'F152678200\x00\x00\x00\x00\x00\x00', - b'F152678210\x00\x00\x00\x00\x00\x00', - b'F152678211\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B78110\x00\x00\x00\x00\x00\x00', - b'8965B78120\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F78030A0\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F7803100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_LC_TSS2: { - (Ecu.engine, 0x7e0, None): [ - b'\x0131130000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152611390\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B11091\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F1104200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F1105200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RC: { - (Ecu.engine, 0x700, None): [ - b'\x01896632461100\x00\x00\x00\x00', - b'\x01896632478100\x00\x00\x00\x00', - b'\x01896632478200\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152624150\x00\x00\x00\x00\x00\x00', - b'F152624221\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881512404100\x00\x00\x00\x00', - b'881512407000\x00\x00\x00\x00', - b'881512409100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B24081\x00\x00\x00\x00\x00\x00', - b'8965B24240\x00\x00\x00\x00\x00\x00', - b'8965B24320\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F2401100\x00\x00\x00\x00', - b'8646F2401200\x00\x00\x00\x00', - b'8646F2402200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RX: { - (Ecu.engine, 0x700, None): [ - b'\x01896630E36100\x00\x00\x00\x00', - b'\x01896630E36200\x00\x00\x00\x00', - b'\x01896630E36300\x00\x00\x00\x00', - b'\x01896630E37100\x00\x00\x00\x00', - b'\x01896630E37200\x00\x00\x00\x00', - b'\x01896630E37300\x00\x00\x00\x00', - b'\x01896630E41000\x00\x00\x00\x00', - b'\x01896630E41100\x00\x00\x00\x00', - b'\x01896630E41200\x00\x00\x00\x00', - b'\x01896630E41500\x00\x00\x00\x00', - b'\x01896630EA3100\x00\x00\x00\x00', - b'\x01896630EA3300\x00\x00\x00\x00', - b'\x01896630EA3400\x00\x00\x00\x00', - b'\x01896630EA4100\x00\x00\x00\x00', - b'\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'\x01896634D11000\x00\x00\x00\x00', - b'\x01896634D12000\x00\x00\x00\x00', - b'\x01896634D12100\x00\x00\x00\x00', - b'\x01896634D43000\x00\x00\x00\x00', - b'\x01896634D44000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02348U2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X5000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Y3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0234D14000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260E031\x00\x00\x00\x00\x00\x00', - b'\x01F15260E041\x00\x00\x00\x00\x00\x00', - b'\x01F152648781\x00\x00\x00\x00\x00\x00', - b'\x01F152648801\x00\x00\x00\x00\x00\x00', - b'F152648493\x00\x00\x00\x00\x00\x00', - b'F152648811\x00\x00\x00\x00\x00\x00', - b'F152648831\x00\x00\x00\x00\x00\x00', - b'F152648891\x00\x00\x00\x00\x00\x00', - b'F152648C80\x00\x00\x00\x00\x00\x00', - b'F152648D00\x00\x00\x00\x00\x00\x00', - b'F152648D60\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B48261\x00\x00\x00\x00\x00\x00', - b'8965B48271\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4810400\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', - b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', - b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', - b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152647500\x00\x00\x00\x00\x00\x00', - b'F152647510\x00\x00\x00\x00\x00\x00', - b'F152647520\x00\x00\x00\x00\x00\x00', - b'F152647521\x00\x00\x00\x00\x00\x00', - b'F152647531\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B47070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4707000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4710000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F4712000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_MIRAI: { - (Ecu.abs, 0x7d1, None): [ - b'\x01898A36203000\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15266203200\x00\x00\x00\x00', - b'\x01F15266203500\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B6204100\x00\x00\x00\x008965B6203100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_ALPHARD_TSS2: { - (Ecu.engine, 0x7e0, None): [ - b'\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B58040\x00\x00\x00\x00\x00\x00', - b'8965B58052\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152658320\x00\x00\x00\x00\x00\x00', - b'F152658341\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F58010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646FV201000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, -} diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py deleted file mode 100644 index 3ea05f9fef57b9e..000000000000000 --- a/selfdrive/car/toyota/interface.py +++ /dev/null @@ -1,202 +0,0 @@ -from cereal import car -from panda import Panda -from panda.python import uds -from openpilot.selfdrive.car.toyota.values import Ecu, CAR, DBC, ToyotaFlags, CarControllerParams, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, \ - MIN_ACC_SPEED, EPS_SCALE, UNSUPPORTED_DSU_CAR, NO_STOP_TIMER_CAR, ANGLE_CONTROL_CAR -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.disable_ecu import disable_ecu -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -SteerControlType = car.CarParams.SteerControlType - - -class CarInterface(CarInterfaceBase): - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "toyota" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.toyota)] - ret.safetyConfigs[0].safetyParam = EPS_SCALE[candidate] - - # BRAKE_MODULE is on a different address for these cars - if DBC[candidate]["pt"] == "toyota_new_mc_pt_generated": - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_ALT_BRAKE - - if candidate in ANGLE_CONTROL_CAR: - 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.18 - ret.steerLimitTimer = 0.8 - else: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay - ret.steerLimitTimer = 0.4 - - ret.stoppingControl = False # Toyota starts braking more when it thinks you want to stop - - stop_and_go = candidate in TSS2_CAR - - # Detect smartDSU, which intercepts ACC_CMD from the DSU (or radar) allowing openpilot to send it - # 0x2AA is sent by a similar device which intercepts the radar instead of DSU on NO_DSU_CARs - if 0x2FF in fingerprint[0] or (0x2AA in fingerprint[0] and candidate in NO_DSU_CAR): - ret.flags |= ToyotaFlags.SMART_DSU.value - - if 0x2AA in fingerprint[0] and candidate in NO_DSU_CAR: - ret.flags |= ToyotaFlags.RADAR_CAN_FILTER.value - - # In TSS2 cars, the camera does long control - 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) - - if candidate == CAR.TOYOTA_PRIUS: - stop_and_go = True - # Only give steer angle deadzone to for bad angle sensor prius - for fw in car_fw: - if fw.ecu == "eps" and not fw.fwVersion == b'8965B47060\x00\x00\x00\x00\x00\x00': - ret.steerActuatorDelay = 0.25 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg=0.2) - - elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RX_TSS2): - stop_and_go = True - ret.wheelSpeedFactor = 1.035 - - elif candidate in (CAR.TOYOTA_AVALON, CAR.TOYOTA_AVALON_2019, CAR.TOYOTA_AVALON_TSS2): - # starting from 2019, all Avalon variants have stop and go - # https://engage.toyota.com/static/images/toyota_safety_sense/TSS_Applicability_Chart.pdf - stop_and_go = candidate != CAR.TOYOTA_AVALON - - elif candidate in (CAR.TOYOTA_RAV4_TSS2, CAR.TOYOTA_RAV4_TSS2_2022, CAR.TOYOTA_RAV4_TSS2_2023): - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kiBP = [0.0] - ret.lateralTuning.pid.kpBP = [0.0] - ret.lateralTuning.pid.kpV = [0.6] - ret.lateralTuning.pid.kiV = [0.1] - ret.lateralTuning.pid.kf = 0.00007818594 - - # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. - # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 - for fw in car_fw: - if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']): - ret.lateralTuning.pid.kpV = [0.15] - ret.lateralTuning.pid.kiV = [0.05] - ret.lateralTuning.pid.kf = 0.00004 - break - - elif candidate in (CAR.TOYOTA_CHR, CAR.TOYOTA_CAMRY, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_NX): - # TODO: Some of these platforms are not advertised to have full range ACC, are they similar to SNG_WITHOUT_DSU cars? - stop_and_go = True - - # TODO: these models can do stop and go, but unclear if it requires sDSU or unplugging DSU. - # For now, don't list stop and go functionality in the docs - if ret.flags & ToyotaFlags.SNG_WITHOUT_DSU: - stop_and_go = stop_and_go or bool(ret.flags & ToyotaFlags.SMART_DSU.value) or (ret.enableDsu and not docs) - - ret.centerToFront = ret.wheelbase * 0.44 - - # TODO: Some TSS-P platforms have BSM, but are flipped based on region or driving direction. - # Detect flipped signals and enable for C-HR and others - ret.enableBsm = 0x3F6 in fingerprint[0] and candidate in TSS2_CAR - - # No radar dbc for cars without DSU which are not TSS 2.0 - # TODO: make an adas dbc file for dsu-less models - ret.radarUnavailable = DBC[candidate]['radar'] is None or candidate in (NO_DSU_CAR - TSS2_CAR) - - # 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 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: - ret.flags |= ToyotaFlags.DISABLE_RADAR.value - else: - use_sdsu = use_sdsu and experimental_long - - # openpilot longitudinal enabled by default: - # - non-(TSS2 radar ACC cars) w/ smartDSU installed - # - cars w/ DSU disconnected - # - TSS2 cars with camera sending ACC_CONTROL where we can block it - # openpilot longitudinal behind experimental long toggle: - # - TSS2 radar ACC cars w/ smartDSU installed - # - TSS2 radar ACC cars w/o smartDSU installed (disables radar) - # - 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 - - if not ret.openpilotLongitudinalControl: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL - - # 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 else MIN_ACC_SPEED - - tune = ret.longitudinalTuning - tune.deadzoneBP = [0., 9.] - tune.deadzoneV = [.0, .15] - if candidate in TSS2_CAR: - tune.kpBP = [0., 5., 20.] - tune.kpV = [1.3, 1.0, 0.7] - tune.kiBP = [0., 5., 12., 20., 27.] - tune.kiV = [.35, .23, .20, .17, .1] - if candidate in TSS2_CAR: - ret.vEgoStopping = 0.25 - ret.vEgoStarting = 0.25 - ret.stoppingDecelRate = 0.3 # reach stopping target smoothly - else: - tune.kpBP = [0., 5., 35.] - tune.kiBP = [0., 35.] - tune.kpV = [3.6, 2.4, 1.5] - tune.kiV = [0.54, 0.36] - - return ret - - @staticmethod - def init(CP, logcan, sendcan): - # disable radar if alpha longitudinal toggled on radar-ACC car without CAN filter/smartDSU - if CP.flags & ToyotaFlags.DISABLE_RADAR.value: - communication_control = bytes([uds.SERVICE_TYPE.COMMUNICATION_CONTROL, uds.CONTROL_TYPE.ENABLE_RX_DISABLE_TX, uds.MESSAGE_TYPE.NORMAL]) - disable_ecu(logcan, sendcan, bus=0, addr=0x750, sub_addr=0xf, com_cont_req=communication_control) - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) or (self.CP.flags & ToyotaFlags.SMART_DSU and not self.CP.flags & ToyotaFlags.RADAR_CAN_FILTER): - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - # events - events = self.create_common_events(ret) - - # Lane Tracing Assist control is unavailable (EPS_STATUS->LTA_STATE=0) until - # the more accurate angle sensor signal is initialized - if self.CP.steerControlType == SteerControlType.angle and not self.CS.accurate_steer_angle_seen: - events.add(EventName.vehicleSensorsInvalid) - - if self.CP.openpilotLongitudinalControl: - if ret.cruiseState.standstill and not ret.brakePressed: - events.add(EventName.resumeRequired) - if self.CS.low_speed_lockout: - events.add(EventName.lowSpeedLockout) - if ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.belowEngageSpeed) - if c.actuators.accel > 0.3: - # some margin on the actuator to not false trigger cancellation while stopping - events.add(EventName.speedTooLow) - if ret.vEgo < 0.001: - # while in standstill, send a user alert - events.add(EventName.manualRestart) - - ret.events = events.to_msg() - - return ret diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py deleted file mode 100755 index fae6eecaf634e26..000000000000000 --- a/selfdrive/car/toyota/radar_interface.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python3 -from opendbc.can.parser import CANParser -from cereal import car -from openpilot.selfdrive.car.toyota.values import DBC, TSS2_CAR -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - - -def _create_radar_can_parser(car_fingerprint): - if car_fingerprint in TSS2_CAR: - RADAR_A_MSGS = list(range(0x180, 0x190)) - RADAR_B_MSGS = list(range(0x190, 0x1a0)) - else: - RADAR_A_MSGS = list(range(0x210, 0x220)) - RADAR_B_MSGS = list(range(0x220, 0x230)) - - msg_a_n = len(RADAR_A_MSGS) - msg_b_n = len(RADAR_B_MSGS) - messages = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20] * (msg_a_n + msg_b_n), strict=True)) - - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.track_id = 0 - self.radar_ts = CP.radarTimeStep - - if CP.carFingerprint in TSS2_CAR: - self.RADAR_A_MSGS = list(range(0x180, 0x190)) - self.RADAR_B_MSGS = list(range(0x190, 0x1a0)) - else: - self.RADAR_A_MSGS = list(range(0x210, 0x220)) - self.RADAR_B_MSGS = list(range(0x220, 0x230)) - - self.valid_cnt = {key: 0 for key in self.RADAR_A_MSGS} - - self.rcp = None if CP.radarUnavailable else _create_radar_can_parser(CP.carFingerprint) - self.trigger_msg = self.RADAR_B_MSGS[-1] - self.updated_messages = set() - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for ii in sorted(updated_messages): - if ii in self.RADAR_A_MSGS: - cpt = self.rcp.vl[ii] - - if cpt['LONG_DIST'] >= 255 or cpt['NEW_TRACK']: - self.valid_cnt[ii] = 0 # reset counter - if cpt['VALID'] and cpt['LONG_DIST'] < 255: - self.valid_cnt[ii] += 1 - else: - self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) - - score = self.rcp.vl[ii+16]['SCORE'] - # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] - - # radar point only valid if it's a valid measurement and score is above 50 - if cpt['VALID'] or (score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): - if ii not in self.pts or cpt['NEW_TRACK']: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = bool(cpt['VALID']) - else: - if ii in self.pts: - del self.pts[ii] - - ret.points = list(self.pts.values()) - return ret diff --git a/selfdrive/car/toyota/tests/print_platform_codes.py b/selfdrive/car/toyota/tests/print_platform_codes.py deleted file mode 100755 index 9ec7a14cd3eed06..000000000000000 --- a/selfdrive/car/toyota/tests/print_platform_codes.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/bin/env python3 -from collections import defaultdict -from cereal import car -from openpilot.selfdrive.car.toyota.values import PLATFORM_CODE_ECUS, get_platform_codes -from openpilot.selfdrive.car.toyota.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -if __name__ == "__main__": - parts_for_ecu: dict = defaultdict(set) - cars_for_code: dict = defaultdict(lambda: defaultdict(set)) - for car_model, ecus in FW_VERSIONS.items(): - print() - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - platform_codes = get_platform_codes(ecus[ecu]) - parts_for_ecu[ecu] |= {code.split(b'-')[0] for code in platform_codes if code.count(b'-') > 1} - for code in platform_codes: - cars_for_code[ecu][b'-'.join(code.split(b'-')[:2])] |= {car_model} - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {platform_codes}') - - print('\nECU parts:') - for ecu, parts in parts_for_ecu.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}): {parts}') - - print('\nCar models vs. platform codes (no major versions):') - for ecu, codes in cars_for_code.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - for code, cars in codes.items(): - print(f' {code!r}: {sorted(cars)}') diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py deleted file mode 100644 index 1cc99b41b578733..000000000000000 --- a/selfdrive/car/toyota/toyotacan.py +++ /dev/null @@ -1,118 +0,0 @@ -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.""" - - values = { - "STEER_REQUEST": steer_req, - "STEER_TORQUE_CMD": steer, - "SET_ME_1": 1, - } - return packer.make_can_msg("STEERING_LKA", 0, values) - - -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, # 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, - "TORQUE_WIND_DOWN": torque_wind_down, - "ANGLE": 0, - "STEER_ANGLE_CMD": steer_angle, - "STEER_REQUEST": steer_req, - "STEER_REQUEST_2": steer_req, - "CLEAR_HOLD_STEERING_ALERT": 0, - } - return packer.make_can_msg("STEERING_LTA", 0, values) - - -def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead, acc_type, fcw_alert, distance): - # TODO: find the exact canceling bit that does not create a chime - values = { - "ACCEL_CMD": accel, - "ACC_TYPE": acc_type, - "DISTANCE": distance, - "MINI_CAR": lead, - "PERMIT_BRAKING": 1, - "RELEASE_STANDSTILL": not standstill_req, - "CANCEL_REQ": pcm_cancel, - "ALLOW_LONG_PRESS": 1, - "ACC_CUT_IN": fcw_alert, # only shown when ACC enabled - } - return packer.make_can_msg("ACC_CONTROL", 0, values) - - -def create_acc_cancel_command(packer): - values = { - "GAS_RELEASED": 0, - "CRUISE_ACTIVE": 0, - "ACC_BRAKING": 0, - "ACCEL_NET": 0, - "CRUISE_STATE": 0, - "CANCEL_REQ": 1, - } - return packer.make_can_msg("PCM_CRUISE", 0, values) - - -def create_fcw_command(packer, fcw): - values = { - "PCS_INDICATOR": 1, # PCS turned off - "FCW": fcw, - "SET_ME_X20": 0x20, - "SET_ME_X10": 0x10, - "PCS_OFF": 1, - "PCS_SENSITIVITY": 0, - } - return packer.make_can_msg("PCS_HUD", 0, values) - - -def create_ui_command(packer, steer, chime, left_line, right_line, left_lane_depart, right_lane_depart, enabled, stock_lkas_hud): - values = { - "TWO_BEEPS": chime, - "LDA_ALERT": steer, - "RIGHT_LINE": 3 if right_lane_depart else 1 if right_line else 2, - "LEFT_LINE": 3 if left_lane_depart else 1 if left_line else 2, - "BARRIERS": 1 if enabled else 0, - - # static signals - "SET_ME_X02": 2, - "SET_ME_X01": 1, - "LKAS_STATUS": 1, - "REPEATED_BEEPS": 0, - "LANE_SWAY_FLD": 7, - "LANE_SWAY_BUZZER": 0, - "LANE_SWAY_WARNING": 0, - "LDA_FRONT_CAMERA_BLOCKED": 0, - "TAKE_CONTROL": 0, - "LANE_SWAY_SENSITIVITY": 2, - "LANE_SWAY_TOGGLE": 1, - "LDA_ON_MESSAGE": 0, - "LDA_MESSAGES": 0, - "LDA_SA_TOGGLE": 1, - "LDA_SENSITIVITY": 2, - "LDA_UNAVAILABLE": 0, - "LDA_MALFUNCTION": 0, - "LDA_UNAVAILABLE_QUIET": 0, - "ADJUSTING_CAMERA": 0, - "LDW_EXIST": 1, - } - - # lane sway functionality - # not all cars have LKAS_HUD — update with camera values if available - if len(stock_lkas_hud): - values.update({s: stock_lkas_hud[s] for s in [ - "LANE_SWAY_FLD", - "LANE_SWAY_BUZZER", - "LANE_SWAY_WARNING", - "LANE_SWAY_SENSITIVITY", - "LANE_SWAY_TOGGLE", - ]}) - - return packer.make_can_msg("LKAS_HUD", 0, values) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py deleted file mode 100644 index 2e781ad0aa58270..000000000000000 --- a/selfdrive/car/toyota/values.py +++ /dev/null @@ -1,575 +0,0 @@ -import re -from collections import defaultdict -from dataclasses import dataclass, field -from enum import Enum, IntFlag - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms -from openpilot.selfdrive.car import AngleRateLimit, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarDocs, Column, CarParts, CarHarness -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu -MIN_ACC_SPEED = 19. * CV.MPH_TO_MS -PEDAL_TRANSITION = 10. * CV.MPH_TO_MS - - -class CarControllerParams: - ACCEL_MAX = 1.5 # m/s2, lower than allowed 2.0 m/s2 for tuning reasons - ACCEL_MIN = -3.5 # m/s2 - - STEER_STEP = 1 - STEER_MAX = 1500 - STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor - - # Lane Tracing Assist (LTA) control limits - # 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: - # 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]) - - def __init__(self, CP): - if CP.lateralTuning.which == 'torque': - self.STEER_DELTA_UP = 15 # 1.0s time to peak torque - self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) - else: - self.STEER_DELTA_UP = 10 # 1.5s time to peak torque - self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) - - -class ToyotaFlags(IntFlag): - # Detected flags - HYBRID = 1 - SMART_DSU = 2 - DISABLE_RADAR = 4 - RADAR_CAN_FILTER = 1024 - - # Static flags - TSS2 = 8 - NO_DSU = 16 - UNSUPPORTED_DSU = 32 - RADAR_ACC = 64 - # these cars use the Lane Tracing Assist (LTA) message for lateral control - ANGLE_CONTROL = 128 - NO_STOP_TIMER = 256 - # these cars are speculated to allow stop and go when the DSU is unplugged or disabled with sDSU - SNG_WITHOUT_DSU = 512 - - -class Footnote(Enum): - CAMRY = CarFootnote( - "openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.", - Column.FSR_LONGITUDINAL) - - -@dataclass -class ToyotaCarDocs(CarDocs): - package: str = "All" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.toyota_a])) - - -@dataclass -class ToyotaTSS2PlatformConfig(PlatformConfig): - dbc_dict: dict = field(default_factory=lambda: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas')) - - def init(self): - self.flags |= ToyotaFlags.TSS2 | ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.NO_DSU - - if self.flags & ToyotaFlags.RADAR_ACC: - self.dbc_dict = dbc_dict('toyota_nodsu_pt_generated', None) - - -class CAR(Platforms): - # Toyota - TOYOTA_ALPHARD_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota Alphard 2019-20"), - ToyotaCarDocs("Toyota Alphard Hybrid 2021"), - ], - CarSpecs(mass=4305. * CV.LB_TO_KG, wheelbase=3.0, steerRatio=14.2, tireStiffnessFactor=0.444), - ) - TOYOTA_AVALON = PlatformConfig( - [ - ToyotaCarDocs("Toyota Avalon 2016", "Toyota Safety Sense P"), - ToyotaCarDocs("Toyota Avalon 2017-18"), - ], - CarSpecs(mass=3505. * CV.LB_TO_KG, wheelbase=2.82, steerRatio=14.8, tireStiffnessFactor=0.7983), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - ) - TOYOTA_AVALON_2019 = PlatformConfig( - [ - ToyotaCarDocs("Toyota Avalon 2019-21"), - ToyotaCarDocs("Toyota Avalon Hybrid 2019-21"), - ], - TOYOTA_AVALON.specs, - dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - ) - TOYOTA_AVALON_TSS2 = ToyotaTSS2PlatformConfig( # TSS 2.5 - [ - ToyotaCarDocs("Toyota Avalon 2022"), - ToyotaCarDocs("Toyota Avalon Hybrid 2022"), - ], - TOYOTA_AVALON.specs, - ) - TOYOTA_CAMRY = PlatformConfig( - [ - ToyotaCarDocs("Toyota Camry 2018-20", video_link="https://www.youtube.com/watch?v=fkcjviZY9CM", footnotes=[Footnote.CAMRY]), - ToyotaCarDocs("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk"), - ], - CarSpecs(mass=3400. * CV.LB_TO_KG, wheelbase=2.82448, steerRatio=13.7, tireStiffnessFactor=0.7933), - dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_DSU, - ) - TOYOTA_CAMRY_TSS2 = ToyotaTSS2PlatformConfig( # TSS 2.5 - [ - ToyotaCarDocs("Toyota Camry 2021-24", footnotes=[Footnote.CAMRY]), - ToyotaCarDocs("Toyota Camry Hybrid 2021-24"), - ], - TOYOTA_CAMRY.specs, - ) - TOYOTA_CHR = PlatformConfig( - [ - ToyotaCarDocs("Toyota C-HR 2017-20"), - ToyotaCarDocs("Toyota C-HR Hybrid 2017-20"), - ], - CarSpecs(mass=3300. * CV.LB_TO_KG, wheelbase=2.63906, steerRatio=13.6, tireStiffnessFactor=0.7933), - dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_DSU, - ) - TOYOTA_CHR_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota C-HR 2021"), - ToyotaCarDocs("Toyota C-HR Hybrid 2021-22"), - ], - TOYOTA_CHR.specs, - flags=ToyotaFlags.RADAR_ACC, - ) - TOYOTA_COROLLA = PlatformConfig( - [ToyotaCarDocs("Toyota Corolla 2017-19")], - CarSpecs(mass=2860. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=18.27, tireStiffnessFactor=0.444), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - ) - # LSS2 Lexus UX Hybrid is same as a TSS2 Corolla Hybrid - TOYOTA_COROLLA_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), - ToyotaCarDocs("Toyota Corolla Cross (Non-US only) 2020-23", min_enable_speed=7.5), - ToyotaCarDocs("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), - # Hybrid platforms - ToyotaCarDocs("Toyota Corolla Hybrid 2020-22"), - ToyotaCarDocs("Toyota Corolla Hybrid (South America only) 2020-23", min_enable_speed=7.5), - ToyotaCarDocs("Toyota Corolla Cross Hybrid (Non-US only) 2020-22", min_enable_speed=7.5), - ToyotaCarDocs("Lexus UX Hybrid 2019-23"), - ], - CarSpecs(mass=3060. * CV.LB_TO_KG, wheelbase=2.67, steerRatio=13.9, tireStiffnessFactor=0.444), - ) - TOYOTA_HIGHLANDER = PlatformConfig( - [ - ToyotaCarDocs("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"), - ToyotaCarDocs("Toyota Highlander Hybrid 2017-19"), - ], - CarSpecs(mass=4516. * CV.LB_TO_KG, wheelbase=2.8194, steerRatio=16.0, tireStiffnessFactor=0.8), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, - ) - TOYOTA_HIGHLANDER_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota Highlander 2020-23"), - ToyotaCarDocs("Toyota Highlander Hybrid 2020-23"), - ], - TOYOTA_HIGHLANDER.specs, - ) - TOYOTA_PRIUS = PlatformConfig( - [ - ToyotaCarDocs("Toyota Prius 2016", "Toyota Safety Sense P", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), - ToyotaCarDocs("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), - ToyotaCarDocs("Toyota Prius Prime 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), - ], - CarSpecs(mass=3045. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.74, tireStiffnessFactor=0.6371), - dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - ) - TOYOTA_PRIUS_V = PlatformConfig( - [ToyotaCarDocs("Toyota Prius v 2017", "Toyota Safety Sense P", min_enable_speed=MIN_ACC_SPEED)], - CarSpecs(mass=3340. * CV.LB_TO_KG, wheelbase=2.78, steerRatio=17.4, tireStiffnessFactor=0.5533), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, - ) - TOYOTA_PRIUS_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota Prius 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), - ToyotaCarDocs("Toyota Prius Prime 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), - ], - CarSpecs(mass=3115. * CV.LB_TO_KG, wheelbase=2.70002, steerRatio=13.4, tireStiffnessFactor=0.6371), - ) - TOYOTA_RAV4 = PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 2016", "Toyota Safety Sense P"), - ToyotaCarDocs("Toyota RAV4 2017-18") - ], - CarSpecs(mass=3650. * CV.LB_TO_KG, wheelbase=2.65, steerRatio=16.88, tireStiffnessFactor=0.5533), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - ) - TOYOTA_RAV4H = PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 Hybrid 2016", "Toyota Safety Sense P", video_link="https://youtu.be/LhT5VzJVfNI?t=26"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2017-18", video_link="https://youtu.be/LhT5VzJVfNI?t=26") - ], - TOYOTA_RAV4.specs, - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - # Note that the ICE RAV4 does not respect positive acceleration commands under 19 mph - flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, - ) - TOYOTA_RAV4_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 2019-21", video_link="https://www.youtube.com/watch?v=wJxjDd42gGA"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2019-21"), - ], - CarSpecs(mass=3585. * CV.LB_TO_KG, wheelbase=2.68986, steerRatio=14.3, tireStiffnessFactor=0.7933), - ) - TOYOTA_RAV4_TSS2_2022 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 2022"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2022", video_link="https://youtu.be/U0nH9cnrFB0"), - ], - TOYOTA_RAV4_TSS2.specs, - flags=ToyotaFlags.RADAR_ACC, - ) - TOYOTA_RAV4_TSS2_2023 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 2023-24"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2023-24"), - ], - TOYOTA_RAV4_TSS2.specs, - flags=ToyotaFlags.RADAR_ACC | ToyotaFlags.ANGLE_CONTROL, - ) - TOYOTA_MIRAI = ToyotaTSS2PlatformConfig( # TSS 2.5 - [ToyotaCarDocs("Toyota Mirai 2021")], - CarSpecs(mass=4300. * CV.LB_TO_KG, wheelbase=2.91, steerRatio=14.8, tireStiffnessFactor=0.8), - ) - TOYOTA_SIENNA = PlatformConfig( - [ToyotaCarDocs("Toyota Sienna 2018-20", video_link="https://www.youtube.com/watch?v=q1UPOo4Sh68", min_enable_speed=MIN_ACC_SPEED)], - CarSpecs(mass=4590. * CV.LB_TO_KG, wheelbase=3.03, steerRatio=15.5, tireStiffnessFactor=0.444), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_STOP_TIMER, - ) - - # Lexus - LEXUS_CTH = PlatformConfig( - [ToyotaCarDocs("Lexus CT Hybrid 2017-18", "Lexus Safety System+")], - CarSpecs(mass=3108. * CV.LB_TO_KG, wheelbase=2.6, steerRatio=18.6, tireStiffnessFactor=0.517), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - ) - LEXUS_ES = PlatformConfig( - [ - ToyotaCarDocs("Lexus ES 2017-18"), - ToyotaCarDocs("Lexus ES Hybrid 2017-18"), - ], - CarSpecs(mass=3677. * CV.LB_TO_KG, wheelbase=2.8702, steerRatio=16.0, tireStiffnessFactor=0.444), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - ) - LEXUS_ES_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Lexus ES 2019-24"), - ToyotaCarDocs("Lexus ES Hybrid 2019-24", video_link="https://youtu.be/BZ29osRVJeg?t=12"), - ], - LEXUS_ES.specs, - ) - LEXUS_IS = PlatformConfig( - [ToyotaCarDocs("Lexus IS 2017-19")], - CarSpecs(mass=3736.8 * CV.LB_TO_KG, wheelbase=2.79908, steerRatio=13.3, tireStiffnessFactor=0.444), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.UNSUPPORTED_DSU, - ) - LEXUS_IS_TSS2 = ToyotaTSS2PlatformConfig( - [ToyotaCarDocs("Lexus IS 2022-23")], - LEXUS_IS.specs, - ) - LEXUS_NX = PlatformConfig( - [ - ToyotaCarDocs("Lexus NX 2018-19"), - ToyotaCarDocs("Lexus NX Hybrid 2018-19"), - ], - CarSpecs(mass=4070. * CV.LB_TO_KG, wheelbase=2.66, steerRatio=14.7, tireStiffnessFactor=0.444), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - ) - LEXUS_NX_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Lexus NX 2020-21"), - ToyotaCarDocs("Lexus NX Hybrid 2020-21"), - ], - LEXUS_NX.specs, - ) - LEXUS_LC_TSS2 = ToyotaTSS2PlatformConfig( - [ToyotaCarDocs("Lexus LC 2024")], - CarSpecs(mass=4500. * CV.LB_TO_KG, wheelbase=2.87, steerRatio=13.0, tireStiffnessFactor=0.444), - ) - LEXUS_RC = PlatformConfig( - [ToyotaCarDocs("Lexus RC 2018-20")], - LEXUS_IS.specs, - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.UNSUPPORTED_DSU, - ) - LEXUS_RX = PlatformConfig( - [ - ToyotaCarDocs("Lexus RX 2016", "Lexus Safety System+"), - ToyotaCarDocs("Lexus RX 2017-19"), - # Hybrid platforms - ToyotaCarDocs("Lexus RX Hybrid 2016", "Lexus Safety System+"), - ToyotaCarDocs("Lexus RX Hybrid 2017-19"), - ], - CarSpecs(mass=4481. * CV.LB_TO_KG, wheelbase=2.79, steerRatio=16., tireStiffnessFactor=0.5533), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - ) - LEXUS_RX_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Lexus RX 2020-22"), - ToyotaCarDocs("Lexus RX Hybrid 2020-22"), - ], - LEXUS_RX.specs, - ) - LEXUS_GS_F = PlatformConfig( - [ToyotaCarDocs("Lexus GS F 2016")], - CarSpecs(mass=4034. * CV.LB_TO_KG, wheelbase=2.84988, steerRatio=13.3, tireStiffnessFactor=0.444), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.UNSUPPORTED_DSU, - ) - - -# (addr, cars, bus, 1/freq*100, vl) -STATIC_DSU_MSGS = [ - (0x128, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON), \ - 1, 3, b'\xf4\x01\x90\x83\x00\x37'), - (0x128, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 3, b'\x03\x00\x20\x00\x00\x52'), - (0x141, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 2, b'\x00\x00\x00\x46'), - (0x160, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), - (0x161, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_PRIUS_V), - 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), - (0X161, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), - (0x283, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), - (0x2E6, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), - (0x2E7, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), - (0x33E, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), - (0x344, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), - (0x365, (CAR.TOYOTA_PRIUS, CAR.LEXUS_NX, CAR.TOYOTA_HIGHLANDER), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), - (0x365, (CAR.TOYOTA_RAV4, CAR.TOYOTA_RAV4H, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_RX, - CAR.TOYOTA_PRIUS_V), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), - (0x366, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_HIGHLANDER), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), - (0x366, (CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), - 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), - (0x470, (CAR.TOYOTA_PRIUS, CAR.LEXUS_RX), 1, 100, b'\x00\x00\x02\x7a'), - (0x470, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_RAV4H, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 100, b'\x00\x00\x01\x79'), - (0x4CB, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), -] - - -def get_platform_codes(fw_versions: list[bytes]) -> dict[bytes, set[bytes]]: - # Returns sub versions in a dict so comparisons can be made within part-platform-major_version combos - codes = defaultdict(set) # Optional[part]-platform-major_version: set of sub_version - for fw in fw_versions: - # FW versions returned from UDS queries can return multiple fields/chunks of data (different ECU calibrations, different data?) - # and are prefixed with a byte that describes how many chunks of data there are. - # But FW returned from KWP requires querying of each sub-data id and does not have a length prefix. - - length_code = 1 - length_code_match = FW_LEN_CODE.search(fw) - if length_code_match is not None: - length_code = length_code_match.group()[0] - fw = fw[1:] - - # fw length should be multiple of 16 bytes (per chunk, even if no length code), skip parsing if unexpected length - if length_code * FW_CHUNK_LEN != len(fw): - continue - - chunks = [fw[FW_CHUNK_LEN * i:FW_CHUNK_LEN * i + FW_CHUNK_LEN].strip(b'\x00 ') for i in range(length_code)] - - # only first is considered for now since second is commonly shared (TODO: understand that) - first_chunk = chunks[0] - if len(first_chunk) == 8: - # TODO: no part number, but some short chunks have it in subsequent chunks - fw_match = SHORT_FW_PATTERN.search(first_chunk) - if fw_match is not None: - platform, major_version, sub_version = fw_match.groups() - codes[b'-'.join((platform, major_version))].add(sub_version) - - elif len(first_chunk) == 10: - fw_match = MEDIUM_FW_PATTERN.search(first_chunk) - if fw_match is not None: - part, platform, major_version, sub_version = fw_match.groups() - codes[b'-'.join((part, platform, major_version))].add(sub_version) - - elif len(first_chunk) == 12: - fw_match = LONG_FW_PATTERN.search(first_chunk) - if fw_match is not None: - part, platform, major_version, sub_version = fw_match.groups() - codes[b'-'.join((part, platform, major_version))].add(sub_version) - - return dict(codes) - - -def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: - candidates = set() - - 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} - for ecu, expected_versions in fws.items(): - addr = ecu[1:] - # Only check ECUs expected to have platform codes - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Expected platform codes & versions - expected_platform_codes = get_platform_codes(expected_versions) - - # Found platform codes & versions - found_platform_codes = get_platform_codes(live_fw_versions.get(addr, set())) - - # Check part number + platform code + major version matches for any found versions - # Platform codes and major versions change for different physical parts, generation, API, etc. - # Sub-versions are incremented for minor recalls, do not need to be checked. - if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): - break - - valid_found_ecus.add(addr) - - # If all live ECUs pass all checks for candidate, add it as a match - if valid_expected_ecus.issubset(valid_found_ecus): - candidates.add(candidate) - - return {str(c) for c in (candidates - FUZZY_EXCLUDED_PLATFORMS)} - - -# Regex patterns for parsing more general platform-specific identifiers from FW versions. -# - Part number: Toyota part number (usually last character needs to be ignored to find a match). -# Each ECU address has just one part number. -# - Platform: usually multiple codes per an openpilot platform, however this is the least variable and -# is usually shared across ECUs and model years signifying this describes something about the specific platform. -# This describes more generational changes (TSS-P vs TSS2), or manufacture region. -# - Major version: second least variable part of the FW version. Seen splitting cars by model year/API such as -# RAV4 2022/2023 and Avalon. Used to differentiate cars where API has changed slightly, but is not a generational change. -# It is important to note that these aren't always consecutive, for example: -# Avalon 2016-18's fwdCamera has these major versions: 01, 03 while 2019 has: 02 -# - Sub version: exclusive to major version, but shared with other cars. Should only be used for further filtering. -# Seen bumped in TSB FW updates, and describes other minor differences. -SHORT_FW_PATTERN = re.compile(b'[A-Z0-9](?P[A-Z0-9]{2})(?P[A-Z0-9]{2})(?P[A-Z0-9]{3})') -MEDIUM_FW_PATTERN = re.compile(b'(?P[A-Z0-9]{5})(?P[A-Z0-9]{2})(?P[A-Z0-9]{1})(?P[A-Z0-9]{2})') -LONG_FW_PATTERN = re.compile(b'(?P[A-Z0-9]{5})(?P[A-Z0-9]{2})(?P[A-Z0-9]{2})(?P[A-Z0-9]{3})') -FW_LEN_CODE = re.compile(b'^[\x01-\x03]') # highest seen is 3 chunks, 16 bytes each -FW_CHUNK_LEN = 16 - -# List of ECUs that are most unique across openpilot platforms -# - 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. -# 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.fwdRadar, Ecu.eps) - -# These platforms have at least one platform code for all ECUs shared with another platform. -FUZZY_EXCLUDED_PLATFORMS: set[CAR] = set() - -# Some ECUs that use KWP2000 have their FW versions on non-standard data identifiers. -# Toyota diagnostic software first gets the supported data ids, then queries them one by one. -# For example, sends: 0x1a8800, receives: 0x1a8800010203, queries: 0x1a8801, 0x1a8802, 0x1a8803 -TOYOTA_VERSION_REQUEST_KWP = b'\x1a\x88\x01' -TOYOTA_VERSION_RESPONSE_KWP = b'\x5a\x88\x01' - -FW_QUERY_CONFIG = FwQueryConfig( - # TODO: look at data to whitelist new ECUs effectively - requests=[ - Request( - [StdQueries.SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST_KWP], - [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE_KWP], - whitelist_ecus=[Ecu.fwdCamera, Ecu.fwdRadar, Ecu.dsu, Ecu.abs, Ecu.eps, Ecu.srs, Ecu.transmission, Ecu.hvac], - bus=0, - ), - Request( - [StdQueries.SHORT_TESTER_PRESENT_REQUEST, StdQueries.OBD_VERSION_REQUEST], - [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, StdQueries.OBD_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.hybrid, Ecu.srs, Ecu.transmission, Ecu.hvac], - bus=0, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.EXTENDED_DIAGNOSTIC_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.EXTENDED_DIAGNOSTIC_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.abs, Ecu.eps, - Ecu.hybrid, Ecu.srs, Ecu.transmission, Ecu.hvac], - bus=0, - ), - ], - non_essential_ecus={ - # FIXME: On some models, abs can sometimes be missing - Ecu.abs: [CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_IS, CAR.TOYOTA_ALPHARD_TSS2], - # On some models, the engine can show on two different addresses - Ecu.engine: [CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_CAMRY, CAR.TOYOTA_COROLLA_TSS2, CAR.TOYOTA_CHR, CAR.TOYOTA_CHR_TSS2, CAR.LEXUS_IS, - CAR.LEXUS_IS_TSS2, 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: - # Responds to UDS: - # - Combination Meter (0x7c0) - # - HV Battery (0x713, 0x747) - # - Motor Generator (0x716, 0x724) - # - 2nd ABS "Brake/EPB" (0x730) - # - Electronic Parking Brake ((0x750, 0x2c)) - # - Telematics ((0x750, 0xc7)) - # Responds to KWP (0x1a8801): - # - Steering Angle Sensor (0x7b3) - # - EPS/EMPS (0x7a0, 0x7a1) - # - 2nd SRS Airbag (0x784) - # - Central Gateway ((0x750, 0x5f)) - # - Telematics ((0x750, 0xc7)) - # Responds to KWP (0x1a8881): - # - Body Control Module ((0x750, 0x40)) - # - Telematics ((0x750, 0xc7)) - - # Hybrid control computer can be on 0x7e2 (KWP) or 0x7d2 (UDS) depending on platform - (Ecu.hybrid, 0x7e2, None), # Hybrid Control Assembly & Computer - (Ecu.srs, 0x780, None), # SRS Airbag - # Transmission is combined with engine on some platforms, such as TSS-P RAV4 - (Ecu.transmission, 0x701, None), - # A few platforms have a tester present response on this address, add to log - (Ecu.transmission, 0x7e1, None), - (Ecu.hvac, 0x7c4, None), - ], - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - - -STEER_THRESHOLD = 100 - -# These cars have non-standard EPS torque scale factors. All others are 73 -EPS_SCALE = defaultdict(lambda: 73, - {CAR.TOYOTA_PRIUS: 66, CAR.TOYOTA_COROLLA: 88, CAR.LEXUS_IS: 77, CAR.LEXUS_RC: 77, CAR.LEXUS_CTH: 100, CAR.TOYOTA_PRIUS_V: 100}) - -# Toyota/Lexus Safety Sense 2.0 and 2.5 -TSS2_CAR = CAR.with_flags(ToyotaFlags.TSS2) - -NO_DSU_CAR = CAR.with_flags(ToyotaFlags.NO_DSU) - -# the DSU uses the AEB message for longitudinal on these cars -UNSUPPORTED_DSU_CAR = CAR.with_flags(ToyotaFlags.UNSUPPORTED_DSU) - -# these cars have a radar which sends ACC messages instead of the camera -RADAR_ACC_CAR = CAR.with_flags(ToyotaFlags.RADAR_ACC) - -ANGLE_CONTROL_CAR = CAR.with_flags(ToyotaFlags.ANGLE_CONTROL) - -# no resume button press required -NO_STOP_TIMER_CAR = CAR.with_flags(ToyotaFlags.NO_STOP_TIMER) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/car/values.py b/selfdrive/car/values.py deleted file mode 100644 index bf5d378ab4f58cb..000000000000000 --- a/selfdrive/car/values.py +++ /dev/null @@ -1,19 +0,0 @@ -from typing import get_args -from openpilot.selfdrive.car.body.values import CAR as BODY -from openpilot.selfdrive.car.chrysler.values import CAR as CHRYSLER -from openpilot.selfdrive.car.ford.values import CAR as FORD -from openpilot.selfdrive.car.gm.values import CAR as GM -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.hyundai.values import CAR as HYUNDAI -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA -from openpilot.selfdrive.car.mock.values import CAR as MOCK -from openpilot.selfdrive.car.nissan.values import CAR as NISSAN -from openpilot.selfdrive.car.subaru.values import CAR as SUBARU -from openpilot.selfdrive.car.tesla.values import CAR as TESLA -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.volkswagen.values import CAR as VOLKSWAGEN - -Platform = BODY | CHRYSLER | FORD | GM | HONDA | HYUNDAI | MAZDA | MOCK | NISSAN | SUBARU | TESLA | TOYOTA | VOLKSWAGEN -BRANDS = get_args(Platform) - -PLATFORMS: dict[str, Platform] = {str(platform): platform for brand in BRANDS for platform in brand} diff --git a/selfdrive/car/vin.py b/selfdrive/car/vin.py deleted file mode 100755 index e8c9c5804298aa7..000000000000000 --- a/selfdrive/car/vin.py +++ /dev/null @@ -1,79 +0,0 @@ -#!/usr/bin/env python3 -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 STANDARD_VIN_ADDRS, StdQueries -from openpilot.common.swaglog import cloudlog - -VIN_UNKNOWN = "0" * 17 -VIN_RE = "[A-HJ-NPR-Z0-9]{17}" - - -def is_valid_vin(vin: str): - return re.fullmatch(VIN_RE, vin) is not None - - -def get_vin(logcan, sendcan, buses, timeout=0.1, retry=2, debug=False): - for i in range(retry): - for bus in buses: - for request, response, valid_buses, vin_addrs, functional_addrs, rx_offset in ( - (StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE, (0, 1), STANDARD_VIN_ADDRS, FUNCTIONAL_ADDRS, 0x8), - (StdQueries.OBD_VIN_REQUEST, StdQueries.OBD_VIN_RESPONSE, (0, 1), STANDARD_VIN_ADDRS, FUNCTIONAL_ADDRS, 0x8), - (StdQueries.GM_VIN_REQUEST, StdQueries.GM_VIN_RESPONSE, (0,), [0x24b], None, 0x400), # Bolt fwdCamera - (StdQueries.KWP_VIN_REQUEST, StdQueries.KWP_VIN_RESPONSE, (0,), [0x797], None, 0x3), # Nissan Leaf VCM - (StdQueries.UDS_VIN_REQUEST, StdQueries.UDS_VIN_RESPONSE, (0,), [0x74f], None, 0x6a), # Volkswagen fwdCamera - ): - if bus not in valid_buses: - continue - - # When querying functional addresses, ideally we respond to everything that sends a first frame to avoid leaving the - # ECU in a temporary bad state. Note that we may not cover all ECUs and response offsets. TODO: query physical addrs - tx_addrs = vin_addrs - if functional_addrs is not None: - tx_addrs = [a for a in range(0x700, 0x800) if a != 0x7DF] + list(range(0x18DA00F1, 0x18DB00F1, 0x100)) - - try: - query = IsoTpParallelQuery(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__": - import argparse - import time - - parser = argparse.ArgumentParser(description='Get VIN of the car') - parser.add_argument('--debug', action='store_true') - parser.add_argument('--bus', type=int, default=1) - parser.add_argument('--timeout', type=float, default=0.1) - parser.add_argument('--retry', type=int, default=5) - args = parser.parse_args() - - sendcan = messaging.pub_sock('sendcan') - logcan = messaging.sub_sock('can') - time.sleep(1) - - vin_rx_addr, vin_rx_bus, vin = get_vin(logcan, sendcan, (args.bus,), args.timeout, args.retry, debug=args.debug) - print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py deleted file mode 100644 index a4e0c8946ae10fe..000000000000000 --- a/selfdrive/car/volkswagen/carcontroller.py +++ /dev/null @@ -1,121 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.common.numpy_fast import clip -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.interfaces import CarControllerBase -from openpilot.selfdrive.car.volkswagen import mqbcan, pqcan -from openpilot.selfdrive.car.volkswagen.values import CANBUS, CarControllerParams, VolkswagenFlags - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.CCP = CarControllerParams(CP) - self.CCS = pqcan if CP.flags & VolkswagenFlags.PQ else mqbcan - self.packer_pt = CANPacker(dbc_name) - self.ext_bus = CANBUS.pt if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera else CANBUS.cam - - self.apply_steer_last = 0 - self.gra_acc_counter_last = None - self.frame = 0 - self.eps_timer_soft_disable_alert = False - self.hca_frame_timer_running = 0 - self.hca_frame_same_torque = 0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - can_sends = [] - - # **** Steering Controls ************************************************ # - - if self.frame % self.CCP.STEER_STEP == 0: - # Logic to avoid HCA state 4 "refused": - # * Don't steer unless HCA is in state 3 "ready" or 5 "active" - # * Don't steer at standstill - # * Don't send > 3.00 Newton-meters torque - # * Don't send the same torque for > 6 seconds - # * Don't send uninterrupted steering for > 360 seconds - # MQB racks reset the uninterrupted steering timer after a single frame - # of HCA disabled; this is done whenever output happens to be zero. - - if CC.latActive: - new_steer = int(round(actuators.steer * self.CCP.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP) - self.hca_frame_timer_running += self.CCP.STEER_STEP - if self.apply_steer_last == apply_steer: - self.hca_frame_same_torque += self.CCP.STEER_STEP - if self.hca_frame_same_torque > self.CCP.STEER_TIME_STUCK_TORQUE / DT_CTRL: - apply_steer -= (1, -1)[apply_steer < 0] - self.hca_frame_same_torque = 0 - else: - self.hca_frame_same_torque = 0 - hca_enabled = abs(apply_steer) > 0 - else: - hca_enabled = False - apply_steer = 0 - - if not hca_enabled: - self.hca_frame_timer_running = 0 - - self.eps_timer_soft_disable_alert = self.hca_frame_timer_running > self.CCP.STEER_TIME_ALERT / DT_CTRL - self.apply_steer_last = apply_steer - can_sends.append(self.CCS.create_steering_control(self.packer_pt, CANBUS.pt, apply_steer, hca_enabled)) - - if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - # Pacify VW Emergency Assist driver inactivity detection by changing its view of driver steering input torque - # to the greatest of actual driver input or 2x openpilot's output (1x openpilot output is not enough to - # consistently reset inactivity detection on straight level roads). See commaai/openpilot#23274 for background. - ea_simulated_torque = clip(apply_steer * 2, -self.CCP.STEER_MAX, self.CCP.STEER_MAX) - if abs(CS.out.steeringTorque) > abs(ea_simulated_torque): - ea_simulated_torque = CS.out.steeringTorque - can_sends.append(self.CCS.create_eps_update(self.packer_pt, CANBUS.cam, CS.eps_stock_values, ea_simulated_torque)) - - # **** Acceleration Controls ******************************************** # - - if self.frame % self.CCP.ACC_CONTROL_STEP == 0 and self.CP.openpilotLongitudinalControl: - acc_control = self.CCS.acc_control_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) - accel = clip(actuators.accel, self.CCP.ACCEL_MIN, self.CCP.ACCEL_MAX) if CC.longActive else 0 - stopping = actuators.longControlState == LongCtrlState.stopping - starting = actuators.longControlState == LongCtrlState.pid and (CS.esp_hold_confirmation or CS.out.vEgo < self.CP.vEgoStopping) - can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, CS.acc_type, CC.longActive, accel, - acc_control, stopping, starting, CS.esp_hold_confirmation)) - - # **** HUD Controls ***************************************************** # - - if self.frame % self.CCP.LDW_STEP == 0: - hud_alert = 0 - if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw): - hud_alert = self.CCP.LDW_MESSAGES["laneAssistTakeOver"] - can_sends.append(self.CCS.create_lka_hud_control(self.packer_pt, CANBUS.pt, CS.ldw_stock_values, CC.latActive, - CS.out.steeringPressed, hud_alert, hud_control)) - - if self.frame % self.CCP.ACC_HUD_STEP == 0 and self.CP.openpilotLongitudinalControl: - lead_distance = 0 - if hud_control.leadVisible and self.frame * DT_CTRL > 1.0: # Don't display lead until we know the scaling factor - lead_distance = 512 if CS.upscale_lead_car_signal else 8 - acc_hud_status = self.CCS.acc_hud_status_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) - # FIXME: follow the recent displayed-speed updates, also use mph_kmh toggle to fix display rounding problem? - set_speed = hud_control.setSpeed * CV.MS_TO_KPH - can_sends.append(self.CCS.create_acc_hud_control(self.packer_pt, CANBUS.pt, acc_hud_status, set_speed, - lead_distance, hud_control.leadDistanceBars)) - - # **** Stock ACC Button Controls **************************************** # - - gra_send_ready = self.CP.pcmCruise and CS.gra_stock_values["COUNTER"] != self.gra_acc_counter_last - if gra_send_ready and (CC.cruiseControl.cancel or CC.cruiseControl.resume): - can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, self.ext_bus, CS.gra_stock_values, - cancel=CC.cruiseControl.cancel, resume=CC.cruiseControl.resume)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.CCP.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - self.gra_acc_counter_last = CS.gra_stock_values["COUNTER"] - self.frame += 1 - return new_actuators, can_sends diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py deleted file mode 100644 index ec6403496f70519..000000000000000 --- a/selfdrive/car/volkswagen/carstate.py +++ /dev/null @@ -1,398 +0,0 @@ -import numpy as np -from cereal import car -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, NetworkLocation, TransmissionType, GearShifter, \ - CarControllerParams, VolkswagenFlags - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.frame = 0 - self.eps_init_complete = False - self.CCP = CarControllerParams(CP) - self.button_states = {button.event_type: False for button in self.CCP.BUTTONS} - self.esp_hold_confirmation = False - self.upscale_lead_car_signal = False - self.eps_stock_values = False - - def create_button_events(self, pt_cp, buttons): - button_events = [] - - for button in buttons: - state = pt_cp.vl[button.can_addr][button.can_msg] in button.values - if self.button_states[button.event_type] != state: - event = car.CarState.ButtonEvent.new_message() - event.type = button.event_type - event.pressed = state - button_events.append(event) - self.button_states[button.event_type] = state - - return button_events - - def update(self, pt_cp, cam_cp, ext_cp, trans_type): - if self.CP.flags & VolkswagenFlags.PQ: - return self.update_pq(pt_cp, cam_cp, ext_cp, trans_type) - - ret = car.CarState.new_message() - # Update vehicle speed and acceleration from ABS wheel speeds. - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["ESP_19"]["ESP_VL_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_VR_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_HL_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_HR_Radgeschw_02"], - ) - - ret.vEgoRaw = float(np.mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr])) - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw == 0 - - # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. - ret.steeringAngleDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradwinkel"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradwinkel"])] - ret.steeringRateDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradw_Geschw"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradw_Geschw"])] - ret.steeringTorque = pt_cp.vl["LH_EPS_03"]["EPS_Lenkmoment"] * (1, -1)[int(pt_cp.vl["LH_EPS_03"]["EPS_VZ_Lenkmoment"])] - ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE - ret.yawRate = pt_cp.vl["ESP_02"]["ESP_Gierrate"] * (1, -1)[int(pt_cp.vl["ESP_02"]["ESP_VZ_Gierrate"])] * CV.DEG_TO_RAD - hca_status = self.CCP.hca_status_values.get(pt_cp.vl["LH_EPS_03"]["EPS_HCA_Status"]) - ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) - - # VW Emergency Assist status tracking and mitigation - self.eps_stock_values = pt_cp.vl["LH_EPS_03"] - if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - ret.carFaultedNonCritical = bool(cam_cp.vl["HCA_01"]["EA_Ruckfreigabe"]) or cam_cp.vl["HCA_01"]["EA_ACC_Sollstatus"] > 0 - - # Update gas, brakes, and gearshift. - ret.gas = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] / 100.0 - ret.gasPressed = ret.gas > 0 - ret.brake = pt_cp.vl["ESP_05"]["ESP_Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects - brake_pedal_pressed = bool(pt_cp.vl["Motor_14"]["MO_Fahrer_bremst"]) - brake_pressure_detected = bool(pt_cp.vl["ESP_05"]["ESP_Fahrer_bremst"]) - ret.brakePressed = brake_pedal_pressed or brake_pressure_detected - ret.parkingBrake = bool(pt_cp.vl["Kombi_01"]["KBI_Handbremse"]) # FIXME: need to include an EPB check as well - - # Update gear and/or clutch position data. - if trans_type == TransmissionType.automatic: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_11"]["GE_Fahrstufe"], None)) - elif trans_type == TransmissionType.direct: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["EV_Gearshift"]["GearPosition"], None)) - elif trans_type == TransmissionType.manual: - ret.clutchPressed = not pt_cp.vl["Motor_14"]["MO_Kuppl_schalter"] - if bool(pt_cp.vl["Gateway_72"]["BCM1_Rueckfahrlicht_Schalter"]): - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # Update door and trunk/hatch lid open status. - ret.doorOpen = any([pt_cp.vl["Gateway_72"]["ZV_FT_offen"], - pt_cp.vl["Gateway_72"]["ZV_BT_offen"], - pt_cp.vl["Gateway_72"]["ZV_HFS_offen"], - pt_cp.vl["Gateway_72"]["ZV_HBFS_offen"], - pt_cp.vl["Gateway_72"]["ZV_HD_offen"]]) - - # Update seatbelt fastened status. - ret.seatbeltUnlatched = pt_cp.vl["Airbag_02"]["AB_Gurtschloss_FA"] != 3 - - # Consume blind-spot monitoring info/warning LED states, if available. - # Infostufe: BSM LED on, Warnung: BSM LED flashing - if self.CP.enableBsm: - ret.leftBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_li"]) - ret.rightBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_re"]) - - # Consume factory LDW data relevant for factory SWA (Lane Change Assist) - # and capture it for forwarding to the blind spot radar controller - self.ldw_stock_values = cam_cp.vl["LDW_02"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} - - # Stock FCW is considered active if the release bit for brake-jerk warning - # is set. Stock AEB considered active if the partial braking or target - # braking release bits are set. - # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance - # Systems, chapter on Front Assist with Braking: Golf Family for all MQB - ret.stockFcw = bool(ext_cp.vl["ACC_10"]["AWV2_Freigabe"]) - ret.stockAeb = bool(ext_cp.vl["ACC_10"]["ANB_Teilbremsung_Freigabe"]) or bool(ext_cp.vl["ACC_10"]["ANB_Zielbremsung_Freigabe"]) - - # Update ACC radar status. - self.acc_type = ext_cp.vl["ACC_06"]["ACC_Typ"] - - # ACC okay but disabled (1), ACC ready (2), a radar visibility or other fault/disruption (6 or 7) - # currently regulating speed (3), driver accel override (4), brake only (5) - ret.cruiseState.available = pt_cp.vl["TSK_06"]["TSK_Status"] in (2, 3, 4, 5) - ret.cruiseState.enabled = pt_cp.vl["TSK_06"]["TSK_Status"] in (3, 4, 5) - - if self.CP.pcmCruise: - # Cruise Control mode; check for distance UI setting from the radar. - # ECM does not manage this, so do not need to check for openpilot longitudinal - ret.cruiseState.nonAdaptive = ext_cp.vl["ACC_02"]["ACC_Gesetzte_Zeitluecke"] == 0 - else: - # Speed limiter mode; ECM faults if we command ACC while not pcmCruise - ret.cruiseState.nonAdaptive = bool(pt_cp.vl["TSK_06"]["TSK_Limiter_ausgewaehlt"]) - - ret.accFaulted = pt_cp.vl["TSK_06"]["TSK_Status"] in (6, 7) - - self.esp_hold_confirmation = bool(pt_cp.vl["ESP_21"]["ESP_Haltebestaetigung"]) - ret.cruiseState.standstill = self.CP.pcmCruise and self.esp_hold_confirmation - - # Update ACC setpoint. When the setpoint is zero or there's an error, the - # radar sends a set-speed of ~90.69 m/s / 203mph. - if self.CP.pcmCruise: - ret.cruiseState.speed = ext_cp.vl["ACC_02"]["ACC_Wunschgeschw_02"] * CV.KPH_TO_MS - if ret.cruiseState.speed > 90: - ret.cruiseState.speed = 0 - - # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough - ret.leftBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Left"]) - ret.rightBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Right"]) - ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) - self.gra_stock_values = pt_cp.vl["GRA_ACC_01"] - - # Additional safety checks performed in CarInterface. - ret.espDisabled = pt_cp.vl["ESP_21"]["ESP_Tastung_passiv"] != 0 - - # Digital instrument clusters expect the ACC HUD lead car distance to be scaled differently - self.upscale_lead_car_signal = bool(pt_cp.vl["Kombi_03"]["KBI_Variante"]) - - self.frame += 1 - return ret - - def update_pq(self, pt_cp, cam_cp, ext_cp, trans_type): - ret = car.CarState.new_message() - # Update vehicle speed and acceleration from ABS wheel speeds. - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["Bremse_3"]["Radgeschw__VL_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__VR_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__HL_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__HR_4_1"], - ) - - # vEgo obtained from Bremse_1 vehicle speed rather than Bremse_3 wheel speeds because Bremse_3 isn't present on NSF - ret.vEgoRaw = pt_cp.vl["Bremse_1"]["Geschwindigkeit_neu__Bremse_1_"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw == 0 - - # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. - ret.steeringAngleDeg = pt_cp.vl["Lenkhilfe_3"]["LH3_BLW"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_BLWSign"])] - ret.steeringRateDeg = pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit"] * (1, -1)[int(pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit_S"])] - ret.steeringTorque = pt_cp.vl["Lenkhilfe_3"]["LH3_LM"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_LMSign"])] - ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE - ret.yawRate = pt_cp.vl["Bremse_5"]["Giergeschwindigkeit"] * (1, -1)[int(pt_cp.vl["Bremse_5"]["Vorzeichen_der_Giergeschwindigk"])] * CV.DEG_TO_RAD - hca_status = self.CCP.hca_status_values.get(pt_cp.vl["Lenkhilfe_2"]["LH2_Sta_HCA"]) - ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) - - # Update gas, brakes, and gearshift. - ret.gas = pt_cp.vl["Motor_3"]["Fahrpedal_Rohsignal"] / 100.0 - ret.gasPressed = ret.gas > 0 - ret.brake = pt_cp.vl["Bremse_5"]["Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects - ret.brakePressed = bool(pt_cp.vl["Motor_2"]["Bremslichtschalter"]) - ret.parkingBrake = bool(pt_cp.vl["Kombi_1"]["Bremsinfo"]) - - # Update gear and/or clutch position data. - if trans_type == TransmissionType.automatic: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"], None)) - elif trans_type == TransmissionType.manual: - ret.clutchPressed = not pt_cp.vl["Motor_1"]["Kupplungsschalter"] - reverse_light = bool(pt_cp.vl["Gate_Komf_1"]["GK1_Rueckfahr"]) - if reverse_light: - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # Update door and trunk/hatch lid open status. - ret.doorOpen = any([pt_cp.vl["Gate_Komf_1"]["GK1_Fa_Tuerkont"], - pt_cp.vl["Gate_Komf_1"]["BSK_BT_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HL_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HR_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HD_Hauptraste"]]) - - # Update seatbelt fastened status. - ret.seatbeltUnlatched = not bool(pt_cp.vl["Airbag_1"]["Gurtschalter_Fahrer"]) - - # Consume blind-spot monitoring info/warning LED states, if available. - # Infostufe: BSM LED on, Warnung: BSM LED flashing - if self.CP.enableBsm: - ret.leftBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_li"]) - ret.rightBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_re"]) - - # Consume factory LDW data relevant for factory SWA (Lane Change Assist) - # and capture it for forwarding to the blind spot radar controller - self.ldw_stock_values = cam_cp.vl["LDW_Status"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} - - # Stock FCW is considered active if the release bit for brake-jerk warning - # is set. Stock AEB considered active if the partial braking or target - # braking release bits are set. - # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance - # Systems, chapters on Front Assist with Braking and City Emergency - # Braking for the 2016 Passat NMS - # TODO: deferred until we can collect data on pre-MY2016 behavior, AWV message may be shorter with fewer signals - ret.stockFcw = False - ret.stockAeb = False - - # Update ACC radar status. - self.acc_type = ext_cp.vl["ACC_System"]["ACS_Typ_ACC"] - ret.cruiseState.available = bool(pt_cp.vl["Motor_5"]["GRA_Hauptschalter"]) - ret.cruiseState.enabled = pt_cp.vl["Motor_2"]["GRA_Status"] in (1, 2) - if self.CP.pcmCruise: - ret.accFaulted = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_StaACC"] in (6, 7) - else: - ret.accFaulted = pt_cp.vl["Motor_2"]["GRA_Status"] == 3 - - # Update ACC setpoint. When the setpoint reads as 255, the driver has not - # yet established an ACC setpoint, so treat it as zero. - ret.cruiseState.speed = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_V_Wunsch"] * CV.KPH_TO_MS - if ret.cruiseState.speed > 70: # 255 kph in m/s == no current setpoint - ret.cruiseState.speed = 0 - - # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(300, pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_li"], - pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_re"]) - ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) - self.gra_stock_values = pt_cp.vl["GRA_Neu"] - - # Additional safety checks performed in CarInterface. - ret.espDisabled = bool(pt_cp.vl["Bremse_1"]["ESP_Passiv_getastet"]) - - self.frame += 1 - return ret - - def update_hca_state(self, hca_status): - # Treat INITIALIZING and FAULT as temporary for worst likely EPS recovery time, for cars without factory Lane Assist - # DISABLED means the EPS hasn't been configured to support Lane Assist - self.eps_init_complete = self.eps_init_complete or (hca_status in ("DISABLED", "READY", "ACTIVE") or self.frame > 600) - perm_fault = hca_status == "DISABLED" or (self.eps_init_complete and hca_status in ("INITIALIZING", "FAULT")) - temp_fault = hca_status in ("REJECTED", "PREEMPTED") or not self.eps_init_complete - return temp_fault, perm_fault - - @staticmethod - def get_can_parser(CP): - if CP.flags & VolkswagenFlags.PQ: - return CarState.get_can_parser_pq(CP) - - messages = [ - # sig_address, frequency - ("LWI_01", 100), # From J500 Steering Assist with integrated sensors - ("LH_EPS_03", 100), # From J500 Steering Assist with integrated sensors - ("ESP_19", 100), # From J104 ABS/ESP controller - ("ESP_05", 50), # From J104 ABS/ESP controller - ("ESP_21", 50), # From J104 ABS/ESP controller - ("Motor_20", 50), # From J623 Engine control module - ("TSK_06", 50), # From J623 Engine control module - ("ESP_02", 50), # From J104 ABS/ESP controller - ("GRA_ACC_01", 33), # From J533 CAN gateway (via LIN from steering wheel controls) - ("Gateway_72", 10), # From J533 CAN gateway (aggregated data) - ("Motor_14", 10), # From J623 Engine control module - ("Airbag_02", 5), # From J234 Airbag control module - ("Kombi_01", 2), # From J285 Instrument cluster - ("Blinkmodi_02", 1), # From J519 BCM (sent at 1Hz when no lights active, 50Hz when active) - ("Kombi_03", 0), # From J285 instrument cluster (not present on older cars, 1Hz when present) - ] - - if CP.transmissionType == TransmissionType.automatic: - messages.append(("Getriebe_11", 20)) # From J743 Auto transmission control module - elif CP.transmissionType == TransmissionType.direct: - messages.append(("EV_Gearshift", 10)) # From J??? unknown EV control module - - if CP.networkLocation == NetworkLocation.fwdCamera: - # Radars are here on CANBUS.pt - messages += MqbExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += MqbExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) - - @staticmethod - def get_cam_can_parser(CP): - if CP.flags & VolkswagenFlags.PQ: - return CarState.get_cam_can_parser_pq(CP) - - messages = [] - - if CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - messages += [ - ("HCA_01", 1), # From R242 Driver assistance camera, 50Hz if steering/1Hz if not - ] - - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - # sig_address, frequency - ("LDW_02", 10) # From R242 Driver assistance camera - ] - else: - # Radars are here on CANBUS.cam - messages += MqbExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += MqbExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) - - @staticmethod - def get_can_parser_pq(CP): - messages = [ - # sig_address, frequency - ("Bremse_1", 100), # From J104 ABS/ESP controller - ("Bremse_3", 100), # From J104 ABS/ESP controller - ("Lenkhilfe_3", 100), # From J500 Steering Assist with integrated sensors - ("Lenkwinkel_1", 100), # From J500 Steering Assist with integrated sensors - ("Motor_3", 100), # From J623 Engine control module - ("Airbag_1", 50), # From J234 Airbag control module - ("Bremse_5", 50), # From J104 ABS/ESP controller - ("GRA_Neu", 50), # From J??? steering wheel control buttons - ("Kombi_1", 50), # From J285 Instrument cluster - ("Motor_2", 50), # From J623 Engine control module - ("Motor_5", 50), # From J623 Engine control module - ("Lenkhilfe_2", 20), # From J500 Steering Assist with integrated sensors - ("Gate_Komf_1", 10), # From J533 CAN gateway - ] - - if CP.transmissionType == TransmissionType.automatic: - messages += [("Getriebe_1", 100)] # From J743 Auto transmission control module - elif CP.transmissionType == TransmissionType.manual: - messages += [("Motor_1", 100)] # From J623 Engine control module - - if CP.networkLocation == NetworkLocation.fwdCamera: - # Extended CAN devices other than the camera are here on CANBUS.pt - messages += PqExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += PqExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) - - @staticmethod - def get_cam_can_parser_pq(CP): - - messages = [] - - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - # sig_address, frequency - ("LDW_Status", 10) # From R242 Driver assistance camera - ] - - if CP.networkLocation == NetworkLocation.gateway: - # Radars are here on CANBUS.cam - messages += PqExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += PqExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) - - -class MqbExtraSignals: - # Additional signal and message lists for optional or bus-portable controllers - fwd_radar_messages = [ - ("ACC_06", 50), # From J428 ACC radar control module - ("ACC_10", 50), # From J428 ACC radar control module - ("ACC_02", 17), # From J428 ACC radar control module - ] - bsm_radar_messages = [ - ("SWA_01", 20), # From J1086 Lane Change Assist - ] - -class PqExtraSignals: - # Additional signal and message lists for optional or bus-portable controllers - fwd_radar_messages = [ - ("ACC_System", 50), # From J428 ACC radar control module - ("ACC_GRA_Anzeige", 25), # From J428 ACC radar control module - ] - bsm_radar_messages = [ - ("SWA_1", 20), # From J1086 Lane Change Assist - ] diff --git a/selfdrive/car/volkswagen/fingerprints.py b/selfdrive/car/volkswagen/fingerprints.py deleted file mode 100644 index fea530b29bdd8c0..000000000000000 --- a/selfdrive/car/volkswagen/fingerprints.py +++ /dev/null @@ -1,1204 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.volkswagen.values import CAR - -Ecu = car.CarParams.Ecu - -# TODO: Sharan Mk2 EPS and DQ250 auto trans both require KWP2000 support for fingerprinting - - -FW_VERSIONS = { - CAR.VOLKSWAGEN_ARTEON_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x873G0906259AH\xf1\x890001', - b'\xf1\x873G0906259F \xf1\x890004', - b'\xf1\x873G0906259G \xf1\x890004', - b'\xf1\x873G0906259G \xf1\x890005', - b'\xf1\x873G0906259M \xf1\x890003', - b'\xf1\x873G0906259N \xf1\x890004', - b'\xf1\x873G0906259P \xf1\x890001', - b'\xf1\x875NA907115H \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158L \xf1\x893611', - b'\xf1\x870DL300014C \xf1\x893704', - b'\xf1\x870GC300011L \xf1\x891401', - b'\xf1\x870GC300014M \xf1\x892802', - b'\xf1\x870GC300019G \xf1\x892804', - b'\xf1\x870GC300040P \xf1\x891401', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121157161111572900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', - b'\xf1\x873Q0959655CK\xf1\x890711\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DA\xf1\x890720\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\x0e1812141812171105141123052J00', - b'\xf1\x875QF959655AP\xf1\x890755\xf1\x82\x1311110011111311111100110200--1611125F49', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571B41815A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571B00817A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020800', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002MB4092M7N', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002NB4202N7N', - b'\xf1\x875WA907145Q \xf1\x891063\xf1\x82\x002KB4092KOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_ATLAS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703H906026AA\xf1\x899970', - b'\xf1\x8703H906026AG\xf1\x899973', - b'\xf1\x8703H906026AJ\xf1\x890638', - b'\xf1\x8703H906026AJ\xf1\x891017', - b'\xf1\x8703H906026AT\xf1\x891922', - b'\xf1\x8703H906026BC\xf1\x892664', - b'\xf1\x8703H906026F \xf1\x896696', - b'\xf1\x8703H906026F \xf1\x899970', - b'\xf1\x8703H906026J \xf1\x896026', - b'\xf1\x8703H906026J \xf1\x899970', - b'\xf1\x8703H906026J \xf1\x899971', - b'\xf1\x8703H906026S \xf1\x896693', - b'\xf1\x8703H906026S \xf1\x899970', - b'\xf1\x873CN906259 \xf1\x890005', - b'\xf1\x873CN906259F \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158A \xf1\x893387', - b'\xf1\x8709G927158DR\xf1\x893536', - b'\xf1\x8709G927158DR\xf1\x893742', - b'\xf1\x8709G927158EN\xf1\x893691', - b'\xf1\x8709G927158F \xf1\x893489', - b'\xf1\x8709G927158FT\xf1\x893835', - b'\xf1\x8709G927158GL\xf1\x893939', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\x0e1914151912001103111122031200', - b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\x0e2214152212001105141122052900', - b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e1114151112001105111122052900', - b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e2214152212001105141122052900', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105111122052J00', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B60924A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6G920A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6M921A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6N920A1', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6080105', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_CADDY_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027T \xf1\x892363', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872K5959655E \xf1\x890018\xf1\x82\x05000P037605', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0155', - ], - }, - CAR.VOLKSWAGEN_CRAFTER_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906056BP\xf1\x894729', - b'\xf1\x8704L906056EK\xf1\x896391', - b'\xf1\x8705L906023BC\xf1\x892688', - b'\xf1\x8705L906023MH\xf1\x892588', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AL\xf1\x890505\xf1\x82\x0e1411001413001203151311031100', - b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900', - b'\xf1\x875QF959655AS\xf1\x890755\xf1\x82\x1315140015150011111100050200--1311120749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872N0909143D\x00\xf1\x897010\xf1\x82\x05183AZ306A2', - b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2', - b'\xf1\x872N0909143H \xf1\x897045\xf1\x82\x05263AZ309A2', - b'\xf1\x872N0909144K \xf1\x897045\xf1\x82\x05233AZ810A2', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572J \xf1\x890156', - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.VOLKSWAGEN_GOLF_MK7: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906016A \xf1\x897697', - b'\xf1\x8704E906016AD\xf1\x895758', - b'\xf1\x8704E906016CE\xf1\x899096', - b'\xf1\x8704E906016CH\xf1\x899226', - b'\xf1\x8704E906016N \xf1\x899105', - b'\xf1\x8704E906023AG\xf1\x891726', - b'\xf1\x8704E906023BN\xf1\x894518', - b'\xf1\x8704E906024K \xf1\x896811', - b'\xf1\x8704E906024K \xf1\x899970', - b'\xf1\x8704E906027GR\xf1\x892394', - b'\xf1\x8704E906027HD\xf1\x892603', - b'\xf1\x8704E906027HD\xf1\x893742', - b'\xf1\x8704E906027MA\xf1\x894958', - b'\xf1\x8704L906021DT\xf1\x895520', - b'\xf1\x8704L906021DT\xf1\x898127', - b'\xf1\x8704L906021N \xf1\x895518', - b'\xf1\x8704L906021N \xf1\x898138', - b'\xf1\x8704L906026BN\xf1\x891197', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906026NF\xf1\x899528', - b'\xf1\x8704L906056CL\xf1\x893823', - b'\xf1\x8704L906056CR\xf1\x895813', - b'\xf1\x8704L906056HE\xf1\x893758', - b'\xf1\x8704L906056HN\xf1\x896590', - b'\xf1\x8704L906056HT\xf1\x896591', - b'\xf1\x8704L997022N \xf1\x899459', - b'\xf1\x870EA906016A \xf1\x898343', - b'\xf1\x870EA906016E \xf1\x894219', - b'\xf1\x870EA906016F \xf1\x894238', - b'\xf1\x870EA906016F \xf1\x895002', - b'\xf1\x870EA906016Q \xf1\x895993', - b'\xf1\x870EA906016S \xf1\x897207', - b'\xf1\x875G0906259 \xf1\x890007', - b'\xf1\x875G0906259D \xf1\x890002', - b'\xf1\x875G0906259J \xf1\x890002', - b'\xf1\x875G0906259L \xf1\x890002', - b'\xf1\x875G0906259N \xf1\x890003', - b'\xf1\x875G0906259Q \xf1\x890002', - b'\xf1\x875G0906259Q \xf1\x892313', - b'\xf1\x875G0906259T \xf1\x890003', - b'\xf1\x878V0906259H \xf1\x890002', - b'\xf1\x878V0906259J \xf1\x890003', - b'\xf1\x878V0906259J \xf1\x890103', - b'\xf1\x878V0906259K \xf1\x890001', - b'\xf1\x878V0906259K \xf1\x890003', - b'\xf1\x878V0906259P \xf1\x890001', - b'\xf1\x878V0906259Q \xf1\x890002', - b'\xf1\x878V0906259R \xf1\x890002', - b'\xf1\x878V0906264F \xf1\x890003', - b'\xf1\x878V0906264L \xf1\x890002', - b'\xf1\x878V0906264M \xf1\x890001', - b'\xf1\x878V09C0BB01 \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927749AP\xf1\x892943', - b'\xf1\x8709S927158A \xf1\x893585', - b'\xf1\x870CW300040H \xf1\x890606', - b'\xf1\x870CW300041D \xf1\x891004', - b'\xf1\x870CW300041H \xf1\x891010', - b'\xf1\x870CW300042F \xf1\x891604', - b'\xf1\x870CW300043B \xf1\x891601', - b'\xf1\x870CW300043E \xf1\x891603', - b'\xf1\x870CW300044S \xf1\x894530', - b'\xf1\x870CW300044T \xf1\x895245', - b'\xf1\x870CW300045 \xf1\x894531', - b'\xf1\x870CW300047D \xf1\x895261', - b'\xf1\x870CW300047E \xf1\x895261', - b'\xf1\x870CW300048J \xf1\x890611', - b'\xf1\x870CW300049H \xf1\x890905', - b'\xf1\x870CW300050G \xf1\x891905', - b'\xf1\x870D9300012 \xf1\x894904', - b'\xf1\x870D9300012 \xf1\x894913', - b'\xf1\x870D9300012 \xf1\x894937', - b'\xf1\x870D9300012 \xf1\x895045', - b'\xf1\x870D9300012 \xf1\x895046', - b'\xf1\x870D9300014M \xf1\x895004', - b'\xf1\x870D9300014Q \xf1\x895006', - b'\xf1\x870D9300018 \xf1\x895201', - b'\xf1\x870D9300020J \xf1\x894902', - b'\xf1\x870D9300020Q \xf1\x895201', - b'\xf1\x870D9300020S \xf1\x895201', - b'\xf1\x870D9300040A \xf1\x893613', - b'\xf1\x870D9300040S \xf1\x894311', - b'\xf1\x870D9300041H \xf1\x895220', - b'\xf1\x870D9300041N \xf1\x894512', - b'\xf1\x870D9300041P \xf1\x894507', - b'\xf1\x870DD300045K \xf1\x891120', - b'\xf1\x870DD300046F \xf1\x891601', - b'\xf1\x870GC300012A \xf1\x891401', - b'\xf1\x870GC300012A \xf1\x891403', - b'\xf1\x870GC300012A \xf1\x891422', - b'\xf1\x870GC300012M \xf1\x892301', - b'\xf1\x870GC300014B \xf1\x892401', - b'\xf1\x870GC300014B \xf1\x892403', - b'\xf1\x870GC300014B \xf1\x892405', - b'\xf1\x870GC300020G \xf1\x892401', - b'\xf1\x870GC300020G \xf1\x892403', - b'\xf1\x870GC300020G \xf1\x892404', - b'\xf1\x870GC300020N \xf1\x892804', - b'\xf1\x870GC300043T \xf1\x899999', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120043114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120053114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114417121411149113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113', - b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x13141500111233003142114A2131219333313100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333423100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x13141600111233003142115A2232229333463100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2251229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100', - b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', - b'\xf1\x875Q0959655D \xf1\x890388\xf1\x82\x111413001113120006110417121A101A9113', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13271112111312--071104171825102591131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271112111312--071104171825102591131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271212111312--071104171838103891131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13272512111312--07110417182C102C91131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13341512112212--071104172328102891131211', - b'\xf1\x875Q0959655M \xf1\x890361\xf1\x82\x111413001112120041114115121611169112', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200061104171717101791132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200621143171717111791132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200061104171724102491132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200621143171724112491132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200631143171724122491132111', - b'\xf1\x875Q0959655T \xf1\x890825\xf1\x82\x13271200111312--071104171837103791132111', - b'\xf1\x875Q0959655T \xf1\x890830\xf1\x82\x13271100111312--071104171826102691131211', - b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111413001113120006110417121D101D9112', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561A01612A0', - b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566A0J612A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A00514A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01613A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A0J712A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571A0J714A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A01A18A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A02A16A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A0JA16A1', - b'\xf1\x873QM909144 \xf1\x895072\xf1\x82\x0571A01714A1', - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820519A9040203', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00441A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00608A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00641A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00442A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00642A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A07B05A1', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00502A0', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00602A0', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0522A00402A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511A00403A0', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00404A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00504A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A07A02A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00407A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00507A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A07B04A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A20B03A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A2000400', - b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1', - b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00442A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00642A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A16A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A18A1', - b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A01A18A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567G \xf1\x890390\xf1\x82\x0101', - b'\xf1\x875Q0907567J \xf1\x890396\xf1\x82\x0101', - b'\xf1\x875Q0907567L \xf1\x890098\xf1\x82\x0101', - b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\x0101', - b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', - b'\xf1\x875Q0907572C \xf1\x890210\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572E \xf1\x89X310\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572G \xf1\x890571', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890653', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_JETTA_MK7: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906024AK\xf1\x899937', - b'\xf1\x8704E906024AS\xf1\x899912', - b'\xf1\x8704E906024B \xf1\x895594', - b'\xf1\x8704E906024BC\xf1\x899971', - b'\xf1\x8704E906024BG\xf1\x891057', - b'\xf1\x8704E906024C \xf1\x899970', - b'\xf1\x8704E906024C \xf1\x899971', - b'\xf1\x8704E906024L \xf1\x895595', - b'\xf1\x8704E906024L \xf1\x899970', - b'\xf1\x8704E906027MS\xf1\x896223', - b'\xf1\x8705E906013DB\xf1\x893361', - b'\xf1\x875G0906259T \xf1\x890003', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158BQ\xf1\x893545', - b'\xf1\x8709S927158BS\xf1\x893642', - b'\xf1\x8709S927158BS\xf1\x893694', - b'\xf1\x8709S927158CK\xf1\x893770', - b'\xf1\x8709S927158JC\xf1\x894113', - b'\xf1\x8709S927158R \xf1\x893552', - b'\xf1\x8709S927158R \xf1\x893587', - b'\xf1\x870GC300020N \xf1\x892803', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1314171231313500314611011630169333463100', - b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1314171231313500314611011630169333463100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314642011650169333463100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314643011650169333463100', - b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1311170031313300314240011150119333433100', - b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1319170031313300314240011550159333463100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314642021650169333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314643021650169333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1317171231313500314642023050309333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A10A11A1', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x000_A1080_OM', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A10A01A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521B00404A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A00642A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A10A01A1', - b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A10A11A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x875Q0907572N \xf1\x890681', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_PASSAT_MK8: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703N906026E \xf1\x892114', - b'\xf1\x8704E906023AH\xf1\x893379', - b'\xf1\x8704E906023BM\xf1\x894522', - b'\xf1\x8704L906026DP\xf1\x891538', - b'\xf1\x8704L906026ET\xf1\x891990', - b'\xf1\x8704L906026FP\xf1\x892012', - b'\xf1\x8704L906026GA\xf1\x892013', - b'\xf1\x8704L906026GK\xf1\x899971', - b'\xf1\x8704L906026KD\xf1\x894798', - b'\xf1\x8705L906022A \xf1\x890827', - b'\xf1\x873G0906259 \xf1\x890004', - b'\xf1\x873G0906259B \xf1\x890002', - b'\xf1\x873G0906264 \xf1\x890004', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041E \xf1\x891006', - b'\xf1\x870CW300042H \xf1\x891601', - b'\xf1\x870CW300042H \xf1\x891607', - b'\xf1\x870CW300043H \xf1\x891601', - b'\xf1\x870CW300048R \xf1\x890610', - b'\xf1\x870D9300013A \xf1\x894905', - b'\xf1\x870D9300014L \xf1\x895002', - b'\xf1\x870D9300018C \xf1\x895297', - b'\xf1\x870D9300041A \xf1\x894801', - b'\xf1\x870D9300042H \xf1\x894901', - b'\xf1\x870DD300045T \xf1\x891601', - b'\xf1\x870DD300046H \xf1\x891601', - b'\xf1\x870DL300011H \xf1\x895201', - b'\xf1\x870GC300042H \xf1\x891404', - b'\xf1\x870GC300043 \xf1\x892301', - b'\xf1\x870GC300046P \xf1\x892805', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111', - b'\xf1\x873Q0959655AF\xf1\x890195\xf1\x82\r56140056130012026612120211', - b'\xf1\x873Q0959655AN\xf1\x890305\xf1\x82\r58160058140013036914110311', - b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', - b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012416612124111', - b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111', - b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', - b'\xf1\x873Q0959655BG\xf1\x890712\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001344701311442900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001354701311542900', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011111200631145171716121691132111', - b'\xf1\x875QF959655S \xf1\x890639\xf1\x82\x13131100131300111111000120----2211114A48', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1', - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514B0060703', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526B0060905', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521B00606A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516B00501A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00603A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00703A1', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563B0000600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572A \xf1\x890126', - b'\xf1\x873Q0907572A \xf1\x890130', - b'\xf1\x873Q0907572B \xf1\x890192', - b'\xf1\x873Q0907572B \xf1\x890194', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x873Q0907572C \xf1\x890196', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_PASSAT_NMS: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8706K906016C \xf1\x899609', - b'\xf1\x8706K906016E \xf1\x899830', - b'\xf1\x8706K906016G \xf1\x891124', - b'\xf1\x8706K906071BJ\xf1\x894891', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158AB\xf1\x893318', - b'\xf1\x8709G927158BD\xf1\x893121', - b'\xf1\x8709G927158DK\xf1\x893594', - b'\xf1\x8709G927158FQ\xf1\x893745', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x87561959655 \xf1\x890210\xf1\x82\x1212121111113000102011--121012--101312', - b'\xf1\x87561959655C \xf1\x890508\xf1\x82\x1215141111121100314919--153015--304831', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x87561907567A \xf1\x890132', - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0152', - ], - }, - CAR.VOLKSWAGEN_POLO_MK6: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025H \xf1\x895177', - b'\xf1\x8705C906032J \xf1\x891702', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300042D \xf1\x891612', - b'\xf1\x870CW300050D \xf1\x891908', - b'\xf1\x870CW300051G \xf1\x891909', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AG\xf1\x890248\xf1\x82\x1218130411110411--04040404231811152H14', - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1248130411110416--04040404784811152H14', - b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1384830511110516041405820599841215391471', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - b'\xf1\x872Q2909144AB\xf1\x896050', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - ], - }, - CAR.VOLKSWAGEN_SHARAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906016HE\xf1\x894635', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x877N0959655D \xf1\x890016\xf1\x82\x0801100705----10--', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0153', - ], - }, - CAR.VOLKSWAGEN_TAOS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906025CK\xf1\x892228', - b'\xf1\x8704E906027NJ\xf1\x891445', - b'\xf1\x8704E906027NP\xf1\x891286', - b'\xf1\x8705E906013BD\xf1\x892496', - b'\xf1\x8705E906013E \xf1\x891624', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158EM\xf1\x893812', - b'\xf1\x8709S927158BL\xf1\x893791', - b'\xf1\x8709S927158CR\xf1\x893924', - b'\xf1\x8709S927158DN\xf1\x893946', - b'\xf1\x8709S927158FF\xf1\x893876', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1311111111333500314646021450149333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1312111111333500314646021550159333613100', - b'\xf1\x875Q0959655CE\xf1\x890421\xf1\x82\x1311110011333300314240021350139333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x001O06081OOM', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060405A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060605A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.VOLKSWAGEN_TCROSS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025AK\xf1\x897053', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300050E \xf1\x891903', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1212130411110411--04041104141311152H14', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.VOLKSWAGEN_TIGUAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703N906026D \xf1\x893680', - b'\xf1\x8704E906024AP\xf1\x891461', - b'\xf1\x8704E906027NB\xf1\x899504', - b'\xf1\x8704L906026EJ\xf1\x893661', - b'\xf1\x8704L906027G \xf1\x899893', - b'\xf1\x8705E906018BS\xf1\x890914', - b'\xf1\x875N0906259 \xf1\x890002', - b'\xf1\x875NA906259H \xf1\x890002', - b'\xf1\x875NA907115E \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890005', - b'\xf1\x875NA907115J \xf1\x890002', - b'\xf1\x875NA907115K \xf1\x890004', - b'\xf1\x8783A907115 \xf1\x890007', - b'\xf1\x8783A907115B \xf1\x890005', - b'\xf1\x8783A907115F \xf1\x890002', - b'\xf1\x8783A907115G \xf1\x890001', - b'\xf1\x8783A907115K \xf1\x890001', - b'\xf1\x8783A907115K \xf1\x890002', - b'\xf1\x8783A907115Q \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158DS\xf1\x893699', - b'\xf1\x8709G927158DT\xf1\x893698', - b'\xf1\x8709G927158FM\xf1\x893757', - b'\xf1\x8709G927158GC\xf1\x893821', - b'\xf1\x8709G927158GD\xf1\x893820', - b'\xf1\x8709G927158GM\xf1\x893936', - b'\xf1\x8709G927158GN\xf1\x893938', - b'\xf1\x8709G927158HB\xf1\x894069', - b'\xf1\x8709G927158HC\xf1\x894070', - b'\xf1\x870D9300043 \xf1\x895202', - b'\xf1\x870DD300046K \xf1\x892302', - b'\xf1\x870DL300011N \xf1\x892001', - b'\xf1\x870DL300011N \xf1\x892012', - b'\xf1\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.VOLKSWAGEN_TOURAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906025BE\xf1\x890720', - b'\xf1\x8704E906027HQ\xf1\x893746', - b'\xf1\x8704L906026HM\xf1\x893017', - b'\xf1\x8705E906018CQ\xf1\x890808', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020A \xf1\x891936', - b'\xf1\x870CW300041E \xf1\x891005', - b'\xf1\x870CW300041Q \xf1\x891606', - b'\xf1\x870CW300051M \xf1\x891926', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x1336350021353335314132014730479333313100', - b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x13363500213533353141324C4732479333313100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1336350021353336314740025250529333613100', - b'\xf1\x875QD959655AJ\xf1\x890421\xf1\x82\x1336350021313300314240023330339333663100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A8090400', - b'\xf1\x875QD909144F \xf1\x891082\xf1\x82\x0521A00642A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_TRANSPORTER_T61: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906056AG\xf1\x899970', - b'\xf1\x8704L906056AL\xf1\x899970', - b'\xf1\x8704L906057AP\xf1\x891186', - b'\xf1\x8704L906057N \xf1\x890413', - b'\xf1\x8705L906023E \xf1\x891352', - b'\xf1\x8705L906023MR\xf1\x892582', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870BT300012E \xf1\x893105', - b'\xf1\x870BT300012G \xf1\x893102', - b'\xf1\x870BT300046R \xf1\x893102', - b'\xf1\x870DV300012B \xf1\x893701', - b'\xf1\x870DV300012B \xf1\x893702', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704161611152S1411', - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704171711152S1411', - b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', - b'\xf1\x872Q0959655AQ\xf1\x890511\xf1\x82\x1316170411110411--0404170426261215391421', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x0532380518A2', - b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x05323A5519A2', - b'\xf1\x877LA909144G \xf1\x897160\xf1\x82\x05333A5519A2', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - ], - }, - CAR.VOLKSWAGEN_TROC_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018AT\xf1\x899640', - b'\xf1\x8705E906018CK\xf1\x890863', - b'\xf1\x8705E906018P \xf1\x896020', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041S \xf1\x891615', - b'\xf1\x870CW300050J \xf1\x891911', - b'\xf1\x870CW300051M \xf1\x891925', - b'\xf1\x870CW300051M \xf1\x891928', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1111001111001105111111052900', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1311110012333300314240681152119333463100', - b'\xf1\x875Q0959655CF\xf1\x890421\xf1\x82\x1311110012333300314240021150119333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1152119333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1154119333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521060403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521060405A1', - b'\xf1\x875WA907144M \xf1\x891051\xf1\x82\x001T06081T7N', - b'\xf1\x875WA907144Q \xf1\x891063\xf1\x82\x001O06081OOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.AUDI_A3_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906023AN\xf1\x893695', - b'\xf1\x8704E906023AR\xf1\x893440', - b'\xf1\x8704E906023BL\xf1\x895190', - b'\xf1\x8704E906027CJ\xf1\x897798', - b'\xf1\x8704L997022N \xf1\x899459', - b'\xf1\x875G0906259A \xf1\x890004', - b'\xf1\x875G0906259D \xf1\x890002', - b'\xf1\x875G0906259L \xf1\x890002', - b'\xf1\x875G0906259Q \xf1\x890002', - b'\xf1\x878V0906259E \xf1\x890001', - b'\xf1\x878V0906259F \xf1\x890002', - b'\xf1\x878V0906259H \xf1\x890002', - b'\xf1\x878V0906259J \xf1\x890002', - b'\xf1\x878V0906259K \xf1\x890001', - b'\xf1\x878V0906264B \xf1\x890003', - b'\xf1\x878V0907115B \xf1\x890007', - b'\xf1\x878V0907404A \xf1\x890005', - b'\xf1\x878V0907404G \xf1\x890005', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300044T \xf1\x895245', - b'\xf1\x870CW300048 \xf1\x895201', - b'\xf1\x870D9300012 \xf1\x894912', - b'\xf1\x870D9300012 \xf1\x894931', - b'\xf1\x870D9300012K \xf1\x894513', - b'\xf1\x870D9300012L \xf1\x894521', - b'\xf1\x870D9300013B \xf1\x894902', - b'\xf1\x870D9300013B \xf1\x894931', - b'\xf1\x870D9300041N \xf1\x894512', - b'\xf1\x870D9300043T \xf1\x899699', - b'\xf1\x870DD300046 \xf1\x891604', - b'\xf1\x870DD300046A \xf1\x891602', - b'\xf1\x870DD300046F \xf1\x891602', - b'\xf1\x870DD300046G \xf1\x891601', - b'\xf1\x870DL300012E \xf1\x892012', - b'\xf1\x870DL300012H \xf1\x892112', - b'\xf1\x870GC300011 \xf1\x890403', - b'\xf1\x870GC300013M \xf1\x892402', - b'\xf1\x870GC300042J \xf1\x891402', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\x111111001111111206110412111321139114', - b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', - b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', - b'\xf1\x875Q0959655AR\xf1\x890315\xf1\x82\x1311110011131115311211012331239321212100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--171115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13111112111111--241115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111211--261117141112231291163221', - b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112110004110411111421149114', - b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112111104110411111521159114', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561G01A13A0', - b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566G0HA14A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0JA13A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521G0G809A1', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00303A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00803A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G0G803A0', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516G00804A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516G00804A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521G00807A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567M \xf1\x890398\xf1\x82\x0101', - b'\xf1\x875Q0907567N \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572G \xf1\x890571', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572P \xf1\x890682', - ], - }, - CAR.AUDI_Q2_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027JT\xf1\x894145', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041F \xf1\x891006', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BD\xf1\x890336\xf1\x82\x1311111111111100311211011231129321312111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571F60511A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.AUDI_Q3_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018N \xf1\x899970', - b'\xf1\x8705L906022M \xf1\x890901', - b'\xf1\x8783A906259 \xf1\x890001', - b'\xf1\x8783A906259 \xf1\x890005', - b'\xf1\x8783A906259C \xf1\x890002', - b'\xf1\x8783A906259D \xf1\x890001', - b'\xf1\x8783A906259F \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158CN\xf1\x893608', - b'\xf1\x8709G927158FL\xf1\x893758', - b'\xf1\x8709G927158GG\xf1\x893825', - b'\xf1\x8709G927158GP\xf1\x893937', - b'\xf1\x870GC300045D \xf1\x892802', - b'\xf1\x870GC300046F \xf1\x892701', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111', - b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218A219321532111', - b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218C219321532111', - b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111224118A119321532111', - b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60533A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60733A1', - b'\xf1\x875TA907145D \xf1\x891051\xf1\x82\x001PG60A1P7N', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SEAT_ATECA_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027KA\xf1\x893749', - b'\xf1\x8704L906021EL\xf1\x897542', - b'\xf1\x8704L906026BP\xf1\x891198', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906056CR\xf1\x892181', - b'\xf1\x8704L906056CR\xf1\x892797', - b'\xf1\x8705E906018AS\xf1\x899596', - b'\xf1\x8781A906259B \xf1\x890003', - b'\xf1\x878V0906264H \xf1\x890005', - b'\xf1\x878V0907115E \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041D \xf1\x891004', - b'\xf1\x870CW300041G \xf1\x891003', - b'\xf1\x870CW300050J \xf1\x891908', - b'\xf1\x870D9300014S \xf1\x895202', - b'\xf1\x870D9300042M \xf1\x895016', - b'\xf1\x870GC300014P \xf1\x892801', - b'\xf1\x870GC300043A \xf1\x892304', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11110011110011021511110200', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1212001211001305121211052900', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1113121149', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571N60511A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521N01842A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521N01342A1', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511N01805A0', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N05808A1', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x0013N619137N', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.SKODA_FABIA_MK4: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018CF\xf1\x891905', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300051M \xf1\x891936', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1111120749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144S \xf1\x896042', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - ], - }, - CAR.SKODA_KAMIQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025AK\xf1\x897053', - b'\xf1\x8705C906032M \xf1\x891333', - b'\xf1\x8705C906032M \xf1\x892365', - b'\xf1\x8705E906013CK\xf1\x892540', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020 \xf1\x891906', - b'\xf1\x870CW300020 \xf1\x891907', - b'\xf1\x870CW300020T \xf1\x892204', - b'\xf1\x870CW300050 \xf1\x891709', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14', - b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x12111104111104112104040404111111112H14', - b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x122221042111042121040404042E2711152H14', - b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1311150411110411210404040417151215391413', - b'\xf1\x872Q0959655BJ\xf1\x890412\xf1\x82\x132223042111042121040404042B251215391423', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144AB\xf1\x896050', - b'\xf1\x872Q1909144M \xf1\x896041', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_KAROQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906013CL\xf1\x892541', - b'\xf1\x8705E906013H \xf1\x892407', - b'\xf1\x8705E906018P \xf1\x895472', - b'\xf1\x8705E906018P \xf1\x896020', - b'\xf1\x8705L906022BS\xf1\x890913', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020T \xf1\x892202', - b'\xf1\x870CW300041S \xf1\x891615', - b'\xf1\x870GC300014L \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001101131112012100', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1213001211001101131122012100', - b'\xf1\x873Q0959655DE\xf1\x890731\xf1\x82\x0e1213001211001101131121012J00', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1312110012120011111100010200--2521210749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563T6090500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100700', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_KODIAQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027DD\xf1\x893123', - b'\xf1\x8704E906027LD\xf1\x893433', - b'\xf1\x8704E906027NB\xf1\x896517', - b'\xf1\x8704E906027NB\xf1\x899504', - b'\xf1\x8704L906026DE\xf1\x895418', - b'\xf1\x8704L906026EJ\xf1\x893661', - b'\xf1\x8704L906026HT\xf1\x893617', - b'\xf1\x8705E906018DJ\xf1\x890915', - b'\xf1\x8705E906018DJ\xf1\x891903', - b'\xf1\x8705L906022GM\xf1\x893411', - b'\xf1\x875NA906259E \xf1\x890003', - b'\xf1\x875NA907115D \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890005', - b'\xf1\x8783A907115E \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870D9300014S \xf1\x895201', - b'\xf1\x870D9300043 \xf1\x895202', - b'\xf1\x870DL300011N \xf1\x892014', - b'\xf1\x870DL300012G \xf1\x892006', - b'\xf1\x870DL300012M \xf1\x892107', - b'\xf1\x870DL300012N \xf1\x892110', - b'\xf1\x870DL300013G \xf1\x892119', - b'\xf1\x870GC300014N \xf1\x892801', - b'\xf1\x870GC300018S \xf1\x892803', - b'\xf1\x870GC300019H \xf1\x892806', - b'\xf1\x870GC300046Q \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r11110011110011031111310311', - b'\xf1\x873Q0959655AP\xf1\x890306\xf1\x82\r11110011110011421111314211', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', - b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1213001211001244212111442100', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', - b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', - b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121240749', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121246149', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6060405', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', - b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x0025T6BA25OM', - b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002LT61A2LOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572Q \xf1\x890342', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_OCTAVIA_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025L \xf1\x896198', - b'\xf1\x8704E906016ER\xf1\x895823', - b'\xf1\x8704E906027HD\xf1\x893742', - b'\xf1\x8704E906027MH\xf1\x894786', - b'\xf1\x8704L906021DT\xf1\x898127', - b'\xf1\x8704L906021ER\xf1\x898361', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906026BS\xf1\x891541', - b'\xf1\x8704L906026BT\xf1\x897612', - b'\xf1\x875G0906259C \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041L \xf1\x891601', - b'\xf1\x870CW300041N \xf1\x891605', - b'\xf1\x870CW300043B \xf1\x891601', - b'\xf1\x870CW300043P \xf1\x891605', - b'\xf1\x870D9300012H \xf1\x894518', - b'\xf1\x870D9300014T \xf1\x895221', - b'\xf1\x870D9300041C \xf1\x894936', - b'\xf1\x870D9300041H \xf1\x895220', - b'\xf1\x870D9300041J \xf1\x894902', - b'\xf1\x870D9300041P \xf1\x894507', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', - b'\xf1\x873Q0959655AK\xf1\x890306\xf1\x82\r31210031210021033733310331', - b'\xf1\x873Q0959655AP\xf1\x890305\xf1\x82\r11110011110011213331312131', - b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01513A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521T00403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00603A1', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521T00601A1', - b'\xf1\x875QD909144E \xf1\x891081\xf1\x82\x0521T00503A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567P \xf1\x890100\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.SKODA_SUPERB_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027BS\xf1\x892887', - b'\xf1\x8704E906027BT\xf1\x899042', - b'\xf1\x8704L906026ET\xf1\x891343', - b'\xf1\x8704L906026ET\xf1\x891990', - b'\xf1\x8704L906026FP\xf1\x891196', - b'\xf1\x8704L906026KA\xf1\x896014', - b'\xf1\x8704L906026KB\xf1\x894071', - b'\xf1\x8704L906026KD\xf1\x894798', - b'\xf1\x8704L906026MT\xf1\x893076', - b'\xf1\x8705L906022BK\xf1\x899971', - b'\xf1\x873G0906259 \xf1\x890004', - b'\xf1\x873G0906259B \xf1\x890002', - b'\xf1\x873G0906259L \xf1\x890003', - b'\xf1\x873G0906264A \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300042H \xf1\x891601', - b'\xf1\x870CW300043B \xf1\x891603', - b'\xf1\x870CW300049Q \xf1\x890906', - b'\xf1\x870D9300011T \xf1\x894801', - b'\xf1\x870D9300012 \xf1\x894940', - b'\xf1\x870D9300013A \xf1\x894905', - b'\xf1\x870D9300014K \xf1\x895006', - b'\xf1\x870D9300041H \xf1\x894905', - b'\xf1\x870D9300042M \xf1\x895013', - b'\xf1\x870D9300043F \xf1\x895202', - b'\xf1\x870GC300013K \xf1\x892403', - b'\xf1\x870GC300014M \xf1\x892801', - b'\xf1\x870GC300019G \xf1\x892803', - b'\xf1\x870GC300043 \xf1\x892301', - b'\xf1\x870GC300046D \xf1\x892402', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', - b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121118112231292221111', - b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', - b'\xf1\x875Q0959655AS\xf1\x890317\xf1\x82\x1331310031313100313131823133319331313100', - b'\xf1\x875Q0959655AT\xf1\x890317\xf1\x82\x1331310031313100313131013131319331313100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', - b'\xf1\x875Q0959655BK\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1333310031313100313152015351539331423100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151013141319331423100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151823143319331423100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152025350539331463100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152855372539331463100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ050303', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ060505', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ070505', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060700', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070700', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572B \xf1\x890192', - b'\xf1\x873Q0907572B \xf1\x890194', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, -} diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py deleted file mode 100644 index 91cd300e9220b21..000000000000000 --- a/selfdrive/car/volkswagen/interface.py +++ /dev/null @@ -1,133 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.volkswagen.values import CAR, CANBUS, CarControllerParams, NetworkLocation, TransmissionType, GearShifter, VolkswagenFlags - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName - - -class CarInterface(CarInterfaceBase): - def __init__(self, CP, CarController, CarState): - super().__init__(CP, CarController, CarState) - - if CP.networkLocation == NetworkLocation.fwdCamera: - self.ext_bus = CANBUS.pt - self.cp_ext = self.cp - else: - self.ext_bus = CANBUS.cam - self.cp_ext = self.cp_cam - - @staticmethod - def _get_params(ret, candidate: CAR, fingerprint, car_fw, experimental_long, docs): - ret.carName = "volkswagen" - ret.radarUnavailable = True - - if ret.flags & VolkswagenFlags.PQ: - # Set global PQ35/PQ46/NMS parameters - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagenPq)] - ret.enableBsm = 0x3BA in fingerprint[0] # SWA_1 - - if 0x440 in fingerprint[0] or docs: # Getriebe_1 - ret.transmissionType = TransmissionType.automatic - else: - ret.transmissionType = TransmissionType.manual - - if any(msg in fingerprint[1] for msg in (0x1A0, 0xC2)): # Bremse_1, Lenkwinkel_1 - ret.networkLocation = NetworkLocation.gateway - else: - ret.networkLocation = NetworkLocation.fwdCamera - - # The PQ port is in dashcam-only mode due to a fixed six-minute maximum timer on HCA steering. An unsupported - # EPS flash update to work around this timer, and enable steering down to zero, is available from: - # https://github.com/pd0wm/pq-flasher - # It is documented in a four-part blog series: - # https://blog.willemmelching.nl/carhacking/2022/01/02/vw-part1/ - # Panda ALLOW_DEBUG firmware required. - ret.dashcamOnly = True - - else: - # Set global MQB parameters - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagen)] - ret.enableBsm = 0x30F in fingerprint[0] # SWA_01 - - if 0xAD in fingerprint[0] or docs: # Getriebe_11 - ret.transmissionType = TransmissionType.automatic - elif 0x187 in fingerprint[0]: # EV_Gearshift - ret.transmissionType = TransmissionType.direct - else: - ret.transmissionType = TransmissionType.manual - - if any(msg in fingerprint[1] for msg in (0x40, 0x86, 0xB2, 0xFD)): # Airbag_01, LWI_01, ESP_19, ESP_21 - ret.networkLocation = NetworkLocation.gateway - else: - ret.networkLocation = NetworkLocation.fwdCamera - - if 0x126 in fingerprint[2]: # HCA_01 - ret.flags |= VolkswagenFlags.STOCK_HCA_PRESENT.value - - # Global lateral tuning defaults, can be overridden per-vehicle - - ret.steerLimitTimer = 0.4 - if ret.flags & VolkswagenFlags.PQ: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - else: - ret.steerActuatorDelay = 0.1 - ret.lateralTuning.pid.kpBP = [0.] - ret.lateralTuning.pid.kiBP = [0.] - ret.lateralTuning.pid.kf = 0.00006 - ret.lateralTuning.pid.kpV = [0.6] - ret.lateralTuning.pid.kiV = [0.2] - - # Global longitudinal tuning defaults, can be overridden per-vehicle - - ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or docs - if experimental_long: - # Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required. - ret.openpilotLongitudinalControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL - if ret.transmissionType == TransmissionType.manual: - ret.minEnableSpeed = 4.5 - - ret.pcmCruise = not ret.openpilotLongitudinalControl - ret.stoppingControl = True - ret.stopAccel = -0.55 - ret.vEgoStarting = 0.1 - ret.vEgoStopping = 0.5 - ret.longitudinalTuning.kpV = [0.1] - ret.longitudinalTuning.kiV = [0.0] - ret.autoResumeSng = ret.minEnableSpeed == -1 - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_ext, self.CP.transmissionType) - - events = self.create_common_events(ret, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], - pcm_enable=not self.CS.CP.openpilotLongitudinalControl, - enable_buttons=(ButtonType.setCruise, ButtonType.resumeCruise)) - - # Low speed steer alert hysteresis logic - if (self.CP.minSteerSpeed - 1e-3) > CarControllerParams.DEFAULT_MIN_STEER_SPEED and ret.vEgo < (self.CP.minSteerSpeed + 1.): - self.low_speed_alert = True - elif ret.vEgo > (self.CP.minSteerSpeed + 2.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(EventName.belowSteerSpeed) - - if self.CS.CP.openpilotLongitudinalControl: - if ret.vEgo < self.CP.minEnableSpeed + 0.5: - events.add(EventName.belowEngageSpeed) - if c.enabled and ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.speedTooLow) - - if self.CC.eps_timer_soft_disable_alert: - events.add(EventName.steerTimeLimit) - - ret.events = events.to_msg() - - return ret - diff --git a/selfdrive/car/volkswagen/radar_interface.py b/selfdrive/car/volkswagen/radar_interface.py deleted file mode 100644 index e654bd61fd4afdc..000000000000000 --- a/selfdrive/car/volkswagen/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py deleted file mode 100644 index 8b58769b3fd87aa..000000000000000 --- a/selfdrive/car/volkswagen/values.py +++ /dev/null @@ -1,516 +0,0 @@ -from collections import defaultdict, namedtuple -from dataclasses import dataclass, field -from enum import Enum, IntFlag, StrEnum - -from cereal import car -from panda.python import uds -from opendbc.can.can_define import CANDefine -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import dbc_dict, CarSpecs, DbcDict, PlatformConfig, Platforms -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ - Device -from openpilot.selfdrive.car.fw_query_definitions import EcuAddrSubAddr, FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu -NetworkLocation = car.CarParams.NetworkLocation -TransmissionType = car.CarParams.TransmissionType -GearShifter = car.CarState.GearShifter -Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) - - -class CarControllerParams: - STEER_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz - ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz - - # Documented lateral limits: 3.00 Nm max, rate of change 5.00 Nm/sec. - # MQB vs PQ maximums are shared, but rate-of-change limited differently - # based on safety requirements driven by lateral accel testing. - - STEER_MAX = 300 # Max heading control assist torque 3.00 Nm - STEER_DRIVER_MULTIPLIER = 3 # weight driver torque heavily - STEER_DRIVER_FACTOR = 1 # from dbc - - STEER_TIME_MAX = 360 # Max time that EPS allows uninterrupted HCA steering control - STEER_TIME_ALERT = STEER_TIME_MAX - 10 # If mitigation fails, time to soft disengage before EPS timer expires - STEER_TIME_STUCK_TORQUE = 1.9 # EPS limits same torque to 6 seconds, reset timer 3x within that period - - DEFAULT_MIN_STEER_SPEED = 0.4 # m/s, newer EPS racks fault below this speed, don't show a low speed alert - - ACCEL_MAX = 2.0 # 2.0 m/s max acceleration - ACCEL_MIN = -3.5 # 3.5 m/s max deceleration - - def __init__(self, CP): - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - if CP.flags & VolkswagenFlags.PQ: - self.LDW_STEP = 5 # LDW_1 message frequency 20Hz - self.ACC_HUD_STEP = 4 # ACC_GRA_Anzeige frequency 25Hz - self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm - self.STEER_DELTA_UP = 6 # Max HCA reached in 1.00s (STEER_MAX / (50Hz * 1.00)) - self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) - - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"] - self.hca_status_values = can_define.dv["Lenkhilfe_2"]["LH2_Sta_HCA"] - - self.BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_Neu", "GRA_Neu_Setzen", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_Neu", "GRA_Recall", [1]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_Neu", "GRA_Up_kurz", [1]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_Neu", "GRA_Down_kurz", [1]), - Button(car.CarState.ButtonEvent.Type.cancel, "GRA_Neu", "GRA_Abbrechen", [1]), - Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_Neu", "GRA_Zeitluecke", [1]), - ] - - self.LDW_MESSAGES = { - "none": 0, # Nothing to display - "laneAssistUnavail": 1, # "Lane Assist currently not available." - "laneAssistUnavailSysError": 2, # "Lane Assist system error" - "laneAssistUnavailNoSensorView": 3, # "Lane Assist not available. No sensor view." - "laneAssistTakeOver": 4, # "Lane Assist: Please Take Over Steering" - "laneAssistDeactivTrailer": 5, # "Lane Assist: no function with trailer" - } - - else: - self.LDW_STEP = 10 # LDW_02 message frequency 10Hz - self.ACC_HUD_STEP = 6 # ACC_02 message frequency 16Hz - self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm - self.STEER_DELTA_UP = 4 # Max HCA reached in 1.50s (STEER_MAX / (50Hz * 1.50)) - self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) - - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["Getriebe_11"]["GE_Fahrstufe"] - elif CP.transmissionType == TransmissionType.direct: - self.shifter_values = can_define.dv["EV_Gearshift"]["GearPosition"] - self.hca_status_values = can_define.dv["LH_EPS_03"]["EPS_HCA_Status"] - - self.BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_ACC_01", "GRA_Tip_Setzen", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_ACC_01", "GRA_Tip_Wiederaufnahme", [1]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_ACC_01", "GRA_Tip_Hoch", [1]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_ACC_01", "GRA_Tip_Runter", [1]), - Button(car.CarState.ButtonEvent.Type.cancel, "GRA_ACC_01", "GRA_Abbrechen", [1]), - Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_ACC_01", "GRA_Verstellung_Zeitluecke", [1]), - ] - - self.LDW_MESSAGES = { - "none": 0, # Nothing to display - "laneAssistUnavailChime": 1, # "Lane Assist currently not available." with chime - "laneAssistUnavailNoSensorChime": 3, # "Lane Assist not available. No sensor view." with chime - "laneAssistTakeOverUrgent": 4, # "Lane Assist: Please Take Over Steering" with urgent beep - "emergencyAssistUrgent": 6, # "Emergency Assist: Please Take Over Steering" with urgent beep - "laneAssistTakeOverChime": 7, # "Lane Assist: Please Take Over Steering" with chime - "laneAssistTakeOver": 8, # "Lane Assist: Please Take Over Steering" silent - "emergencyAssistChangingLanes": 9, # "Emergency Assist: Changing lanes..." with urgent beep - "laneAssistDeactivated": 10, # "Lane Assist deactivated." silent with persistent icon afterward - } - - -class CANBUS: - pt = 0 - cam = 2 - - -class WMI(StrEnum): - VOLKSWAGEN_USA_SUV = "1V2" - VOLKSWAGEN_USA_CAR = "1VW" - VOLKSWAGEN_MEXICO_SUV = "3VV" - VOLKSWAGEN_MEXICO_CAR = "3VW" - VOLKSWAGEN_ARGENTINA = "8AW" - VOLKSWAGEN_BRASIL = "9BW" - SAIC_VOLKSWAGEN = "LSV" - SKODA = "TMB" - SEAT = "VSS" - AUDI_EUROPE_MPV = "WA1" - AUDI_GERMANY_CAR = "WAU" - MAN = "WMA" - AUDI_SPORT = "WUA" - VOLKSWAGEN_COMMERCIAL = "WV1" - VOLKSWAGEN_COMMERCIAL_BUS_VAN = "WV2" - VOLKSWAGEN_EUROPE_SUV = "WVG" - VOLKSWAGEN_EUROPE_CAR = "WVW" - VOLKSWAGEN_GROUP_RUS = "XW8" - - -class VolkswagenFlags(IntFlag): - # Detected flags - STOCK_HCA_PRESENT = 1 - - # Static flags - PQ = 2 - - -@dataclass -class VolkswagenMQBPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_mqb_2010', None)) - # Volkswagen uses the VIN WMI and chassis code to match in the absence of the comma power - # on camera-integrated cars, as we lose too many ECUs to reliably identify the vehicle - chassis_codes: set[str] = field(default_factory=set) - wmis: set[WMI] = field(default_factory=set) - - -@dataclass -class VolkswagenPQPlatformConfig(VolkswagenMQBPlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_golf_mk4', None)) - - def init(self): - self.flags |= VolkswagenFlags.PQ - - -@dataclass(frozen=True, kw_only=True) -class VolkswagenCarSpecs(CarSpecs): - centerToFrontRatio: float = 0.45 - steerRatio: float = 15.6 - minSteerSpeed: float = CarControllerParams.DEFAULT_MIN_STEER_SPEED - - -class Footnote(Enum): - KAMIQ = CarFootnote( - "Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.", - Column.MODEL) - PASSAT = CarFootnote( - "Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.", - Column.MODEL) - SKODA_HEATED_WINDSHIELD = CarFootnote( - "Some Škoda vehicles are equipped with heated windshields, which are known " + - "to block GPS signal needed for some comma 3X functionality.", - Column.MODEL) - VW_EXP_LONG = CarFootnote( - "Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness " + - "are limited to using stock ACC.", - Column.LONGITUDINAL) - VW_MQB_A0 = CarFootnote( - "Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot " + - "in software, but doesn't yet have a harness available from the comma store.", - Column.HARDWARE) - - -@dataclass -class VWCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC) & Lane Assist" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.j533])) - - def init_make(self, CP: car.CarParams): - self.footnotes.append(Footnote.VW_EXP_LONG) - if "SKODA" in CP.carFingerprint: - self.footnotes.append(Footnote.SKODA_HEATED_WINDSHIELD) - - if CP.carFingerprint in (CAR.VOLKSWAGEN_CRAFTER_MK2, CAR.VOLKSWAGEN_TRANSPORTER_T61): - self.car_parts = CarParts([Device.threex_angled_mount, CarHarness.j533]) - - if abs(CP.minSteerSpeed - CarControllerParams.DEFAULT_MIN_STEER_SPEED) < 1e-3: - self.min_steer_speed = 0 - - -# Check the 7th and 8th characters of the VIN before adding a new CAR. If the -# chassis code is already listed below, don't add a new CAR, just add to the -# FW_VERSIONS for that existing CAR. - -class CAR(Platforms): - config: VolkswagenMQBPlatformConfig | VolkswagenPQPlatformConfig - - VOLKSWAGEN_ARTEON_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Arteon 2018-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon R 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon eHybrid 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon Shooting Brake 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen CC 2018-22", video_link="https://youtu.be/FAomFKPFlDA"), - ], - VolkswagenCarSpecs(mass=1733, wheelbase=2.84), - chassis_codes={"AN", "3H"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_ATLAS_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Atlas 2018-23"), - VWCarDocs("Volkswagen Atlas Cross Sport 2020-22"), - VWCarDocs("Volkswagen Teramont 2018-22"), - VWCarDocs("Volkswagen Teramont Cross Sport 2021-22"), - VWCarDocs("Volkswagen Teramont X 2021-22"), - ], - VolkswagenCarSpecs(mass=2011, wheelbase=2.98), - chassis_codes={"CA"}, - wmis={WMI.VOLKSWAGEN_USA_SUV, WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_CADDY_MK3 = VolkswagenPQPlatformConfig( - [ - VWCarDocs("Volkswagen Caddy 2019"), - VWCarDocs("Volkswagen Caddy Maxi 2019"), - ], - VolkswagenCarSpecs(mass=1613, wheelbase=2.6, minSteerSpeed=21 * CV.KPH_TO_MS), - chassis_codes={"2K"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, - ) - VOLKSWAGEN_CRAFTER_MK2 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Crafter 2017-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("Volkswagen e-Crafter 2018-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("Volkswagen Grand California 2019-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("MAN TGE 2017-24", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("MAN eTGE 2020-24", video_link="https://youtu.be/4100gLeabmo"), - ], - VolkswagenCarSpecs(mass=2100, wheelbase=3.64, minSteerSpeed=50 * CV.KPH_TO_MS), - chassis_codes={"SY", "SZ", "UY", "UZ"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL, WMI.MAN}, - ) - VOLKSWAGEN_GOLF_MK7 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen e-Golf 2014-20"), - VWCarDocs("Volkswagen Golf 2015-20", auto_resume=False), - VWCarDocs("Volkswagen Golf Alltrack 2015-19", auto_resume=False), - VWCarDocs("Volkswagen Golf GTD 2015-20"), - VWCarDocs("Volkswagen Golf GTE 2015-20"), - VWCarDocs("Volkswagen Golf GTI 2015-21", auto_resume=False), - VWCarDocs("Volkswagen Golf R 2015-19"), - VWCarDocs("Volkswagen Golf SportsVan 2015-20"), - ], - VolkswagenCarSpecs(mass=1397, wheelbase=2.62), - chassis_codes={"5G", "AU", "BA", "BE"}, - wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_JETTA_MK7 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Jetta 2018-24"), - VWCarDocs("Volkswagen Jetta GLI 2021-24"), - ], - VolkswagenCarSpecs(mass=1328, wheelbase=2.71), - chassis_codes={"BU"}, - wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_PASSAT_MK8 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Passat 2015-22", footnotes=[Footnote.PASSAT]), - VWCarDocs("Volkswagen Passat Alltrack 2015-22"), - VWCarDocs("Volkswagen Passat GTE 2015-22"), - ], - VolkswagenCarSpecs(mass=1551, wheelbase=2.79), - chassis_codes={"3C", "3G"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_PASSAT_NMS = VolkswagenPQPlatformConfig( - [VWCarDocs("Volkswagen Passat NMS 2017-22")], - VolkswagenCarSpecs(mass=1503, wheelbase=2.80, minSteerSpeed=50 * CV.KPH_TO_MS, minEnableSpeed=20 * CV.KPH_TO_MS), - chassis_codes={"A3"}, - wmis={WMI.VOLKSWAGEN_USA_CAR}, - ) - VOLKSWAGEN_POLO_MK6 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Polo 2018-23", footnotes=[Footnote.VW_MQB_A0]), - VWCarDocs("Volkswagen Polo GTI 2018-23", footnotes=[Footnote.VW_MQB_A0]), - ], - VolkswagenCarSpecs(mass=1230, wheelbase=2.55), - chassis_codes={"AW"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_SHARAN_MK2 = VolkswagenPQPlatformConfig( - [ - VWCarDocs("Volkswagen Sharan 2018-22"), - VWCarDocs("SEAT Alhambra 2018-20"), - ], - VolkswagenCarSpecs(mass=1639, wheelbase=2.92, minSteerSpeed=50 * CV.KPH_TO_MS), - chassis_codes={"7N"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_TAOS_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen Taos 2022-23")], - VolkswagenCarSpecs(mass=1498, wheelbase=2.69), - chassis_codes={"B2"}, - wmis={WMI.VOLKSWAGEN_MEXICO_SUV, WMI.VOLKSWAGEN_ARGENTINA}, - ) - VOLKSWAGEN_TCROSS_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_MQB_A0])], - VolkswagenCarSpecs(mass=1150, wheelbase=2.60), - chassis_codes={"C1"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_TIGUAN_MK2 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Tiguan 2018-24"), - VWCarDocs("Volkswagen Tiguan eHybrid 2021-23"), - ], - VolkswagenCarSpecs(mass=1715, wheelbase=2.74), - chassis_codes={"5N", "AD", "AX", "BW"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV, WMI.VOLKSWAGEN_MEXICO_SUV}, - ) - VOLKSWAGEN_TOURAN_MK2 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen Touran 2016-23")], - VolkswagenCarSpecs(mass=1516, wheelbase=2.79), - chassis_codes={"1T"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_TRANSPORTER_T61 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Caravelle 2020"), - VWCarDocs("Volkswagen California 2021-23"), - ], - VolkswagenCarSpecs(mass=1926, wheelbase=3.00, minSteerSpeed=14.0), - chassis_codes={"7H", "7L"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, - ) - VOLKSWAGEN_TROC_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen T-Roc 2018-23")], - VolkswagenCarSpecs(mass=1413, wheelbase=2.63), - chassis_codes={"A1"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - AUDI_A3_MK3 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Audi A3 2014-19"), - VWCarDocs("Audi A3 Sportback e-tron 2017-18"), - VWCarDocs("Audi RS3 2018"), - VWCarDocs("Audi S3 2015-17"), - ], - VolkswagenCarSpecs(mass=1335, wheelbase=2.61), - chassis_codes={"8V", "FF"}, - wmis={WMI.AUDI_GERMANY_CAR, WMI.AUDI_SPORT}, - ) - AUDI_Q2_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Audi Q2 2018")], - VolkswagenCarSpecs(mass=1205, wheelbase=2.61), - chassis_codes={"GA"}, - wmis={WMI.AUDI_GERMANY_CAR}, - ) - AUDI_Q3_MK2 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Audi Q3 2019-23")], - VolkswagenCarSpecs(mass=1623, wheelbase=2.68), - chassis_codes={"8U", "F3", "FS"}, - wmis={WMI.AUDI_EUROPE_MPV, WMI.AUDI_GERMANY_CAR}, - ) - SEAT_ATECA_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("CUPRA Ateca 2018-23"), - VWCarDocs("SEAT Ateca 2016-23"), - VWCarDocs("SEAT Leon 2014-20"), - ], - VolkswagenCarSpecs(mass=1300, wheelbase=2.64), - chassis_codes={"5F"}, - wmis={WMI.SEAT}, - ) - SKODA_FABIA_MK4 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Fabia 2022-23", footnotes=[Footnote.VW_MQB_A0])], - VolkswagenCarSpecs(mass=1266, wheelbase=2.56), - chassis_codes={"PJ"}, - wmis={WMI.SKODA}, - ) - SKODA_KAMIQ_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Škoda Kamiq 2021-23", footnotes=[Footnote.VW_MQB_A0, Footnote.KAMIQ]), - VWCarDocs("Škoda Scala 2020-23", footnotes=[Footnote.VW_MQB_A0]), - ], - VolkswagenCarSpecs(mass=1230, wheelbase=2.66), - chassis_codes={"NW"}, - wmis={WMI.SKODA}, - ) - SKODA_KAROQ_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Karoq 2019-23")], - VolkswagenCarSpecs(mass=1278, wheelbase=2.66), - chassis_codes={"NU"}, - wmis={WMI.SKODA}, - ) - SKODA_KODIAQ_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Kodiaq 2017-23")], - VolkswagenCarSpecs(mass=1569, wheelbase=2.79), - chassis_codes={"NS"}, - wmis={WMI.SKODA, WMI.VOLKSWAGEN_GROUP_RUS}, - ) - SKODA_OCTAVIA_MK3 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Škoda Octavia 2015-19"), - VWCarDocs("Škoda Octavia RS 2016"), - VWCarDocs("Škoda Octavia Scout 2017-19"), - ], - VolkswagenCarSpecs(mass=1388, wheelbase=2.68), - chassis_codes={"NE"}, - wmis={WMI.SKODA}, - ) - SKODA_SUPERB_MK3 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Superb 2015-22")], - VolkswagenCarSpecs(mass=1505, wheelbase=2.84), - chassis_codes={"3V", "NP"}, - wmis={WMI.SKODA}, - ) - - -def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: - candidates = set() - - # Compile all FW versions for each ECU - all_ecu_versions: dict[EcuAddrSubAddr, set[str]] = defaultdict(set) - for ecus in offline_fw_versions.values(): - for ecu, versions in ecus.items(): - all_ecu_versions[ecu] |= set(versions) - - # Check the WMI and chassis code to determine the platform - wmi = vin[:3] - chassis_code = vin[6:8] - - for platform in CAR: - valid_ecus = set() - for ecu in offline_fw_versions[platform]: - addr = ecu[1:] - if ecu[0] not in CHECK_FUZZY_ECUS: - continue - - # Sanity check that live FW is in the superset of all FW, Volkswagen ECU part numbers are commonly shared - found_versions = live_fw_versions.get(addr, []) - expected_versions = all_ecu_versions[ecu] - if not any(found_version in expected_versions for found_version in found_versions): - break - - valid_ecus.add(ecu[0]) - - if valid_ecus != CHECK_FUZZY_ECUS: - continue - - if wmi in platform.config.wmis and chassis_code in platform.config.chassis_codes: - candidates.add(platform) - - return {str(c) for c in candidates} - - -# These ECUs are required to match to gain a VIN match -# TODO: do we want to check camera when we add its FW? -CHECK_FUZZY_ECUS = {Ecu.fwdRadar} - -# All supported cars should return FW from the engine, srs, eps, and fwdRadar. Cars -# with a manual trans won't return transmission firmware, but all other cars will. -# -# The 0xF187 SW part number query should return in the form of N[NX][NX] NNN NNN [X[X]], -# where N=number, X=letter, and the trailing two letters are optional. Performance -# tuners sometimes tamper with that field (e.g. 8V0 9C0 BB0 1 from COBB/EQT). Tampered -# ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have -# them repaired by the tuner before including them in openpilot. - -VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) -VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) - -VOLKSWAGEN_RX_OFFSET = 0x6a - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for bus, obd_multiplexing in [(1, True), (1, False), (0, False)] for request in [ - Request( - [VOLKSWAGEN_VERSION_REQUEST_MULTI], - [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar, Ecu.fwdCamera], - rx_offset=VOLKSWAGEN_RX_OFFSET, - bus=bus, - obd_multiplexing=obd_multiplexing, - ), - Request( - [VOLKSWAGEN_VERSION_REQUEST_MULTI], - [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], - bus=bus, - obd_multiplexing=obd_multiplexing, - ), - ]], - non_essential_ecus={Ecu.eps: list(CAR)}, - extra_ecus=[(Ecu.fwdCamera, 0x74f, None)], - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -DBC = CAR.create_dbc_map() diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 4f5bd194056ba7b..64be43408162624 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -1,130 +1,53 @@ #!/usr/bin/env python3 -import os import math -import time -import threading from typing import SupportsFloat -import cereal.messaging as messaging - from cereal import car, log -from msgq.visionipc import VisionIpcClient, VisionStreamType - - +import cereal.messaging as messaging from openpilot.common.conversions import Conversions as CV -from openpilot.common.git import get_short_branch -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.realtime import config_realtime_process, Priority, Ratekeeper from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.car.car_helpers import get_car_interface, get_startup_event -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 opendbc.car.car_helpers import get_car_interface +from openpilot.selfdrive.controls.lib.drive_helpers import clip_curvature from openpilot.selfdrive.controls.lib.latcontrol import LatControl, MIN_LATERAL_CONTROL_SPEED 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.longcontrol import LongControl from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel +from openpilot.selfdrive.locationd.helpers import PoseCalibrator, Pose -from openpilot.system.hardware import HARDWARE - -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 -TESTING_CLOSET = "TESTING_CLOSET" in os.environ -IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} - -ThermalStatus = log.DeviceState.ThermalStatus -State = log.ControlsState.OpenpilotState -PandaType = log.PandaState.PandaType -Desire = log.Desire +State = log.SelfdriveState.OpenpilotState LaneChangeState = log.LaneChangeState LaneChangeDirection = log.LaneChangeDirection -EventName = car.CarEvent.EventName -ButtonType = car.CarState.ButtonEvent.Type -SafetyModel = car.CarParams.SafetyModel -IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) -CSID_MAP = {"1": EventName.roadCameraError, "2": EventName.wideRoadCameraError, "0": EventName.driverCameraError} ACTUATOR_FIELDS = tuple(car.CarControl.Actuators.schema.fields.keys()) -ACTIVE_STATES = (State.enabled, State.softDisabling, State.overriding) -ENABLED_STATES = (State.preEnabled, *ACTIVE_STATES) - class Controls: - def __init__(self, CI=None): + def __init__(self) -> None: self.params = Params() + cloudlog.info("controlsd is waiting for CarParams") + self.CP = messaging.log_from_bytes(self.params.get("CarParams", block=True), car.CarParams) + cloudlog.info("controlsd got CarParams") - if CI is None: - cloudlog.info("controlsd is waiting for CarParams") - with car.CarParams.from_bytes(self.params.get("CarParams", block=True)) as msg: - # TODO: this shouldn't need to be a builder - self.CP = msg.as_builder() - cloudlog.info("controlsd got CarParams") - - # Uses car interface helper functions, altering state won't be considered by card for actuation - self.CI = get_car_interface(self.CP) - else: - self.CI, self.CP = CI, CI.CP - - # Ensure the current branch is cached, otherwise the first iteration of controlsd lags - self.branch = get_short_branch() - - # Setup sockets - self.pm = messaging.PubMaster(['controlsState', 'carControl', 'onroadEvents']) - - self.sensor_packets = ["accelerometer", "gyroscope"] - self.camera_packets = ["roadCameraState", "driverCameraState", "wideRoadCameraState"] - - self.log_sock = messaging.sub_sock('androidLog') - - # TODO: de-couple controlsd with card/conflate on carState without introducing controls mismatches - self.car_state_sock = messaging.sub_sock('carState', timeout=20) - - ignore = self.sensor_packets + ['testJoystick'] - if SIMULATION: - ignore += ['driverCameraState', 'managerState'] - if REPLAY: - # no vipc in replay will make them ignored anyways - ignore += ['roadCameraState', 'wideRoadCameraState'] - self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', - 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'liveLocationKalman', - 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', - 'testJoystick'] + self.camera_packets + self.sensor_packets, - ignore_alive=ignore, ignore_avg_freq=ignore+['radarState', 'testJoystick'], ignore_valid=['testJoystick', ], - frequency=int(1/DT_CTRL)) + self.CI = get_car_interface(self.CP) - self.joystick_mode = self.params.get_bool("JoystickDebugMode") + self.sm = messaging.SubMaster(['liveParameters', 'liveTorqueParameters', 'modelV2', 'selfdriveState', + 'liveCalibration', 'livePose', 'longitudinalPlan', 'carState', 'carOutput', + 'driverMonitoringState', 'onroadEvents', 'driverAssistance'], poll='selfdriveState') + self.pm = messaging.PubMaster(['carControl', 'controlsState']) - # read params - self.is_metric = self.params.get_bool("IsMetric") - self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") - - # detect sound card presence and ensure successful init - sounds_available = HARDWARE.get_sound_card_online() - - car_recognized = self.CP.carName != 'mock' - - # cleanup old params - if not self.CP.experimentalLongitudinalAvailable: - self.params.remove("ExperimentalLongitudinalEnabled") - if not self.CP.openpilotLongitudinalControl: - self.params.remove("ExperimentalMode") + self.steer_limited = False + self.desired_curvature = 0.0 - self.CS_prev = car.CarState.new_message() - self.AM = AlertManager() - self.events = Events() + self.pose_calibrator = PoseCalibrator() + self.calibrated_pose: Pose|None = None self.LoC = LongControl(self.CP) self.VM = VehicleModel(self.CP) - self.LaC: LatControl if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.LaC = LatControlAngle(self.CP, self.CI) @@ -133,394 +56,16 @@ def __init__(self, CI=None): elif self.CP.lateralTuning.which() == 'torque': self.LaC = LatControlTorque(self.CP, self.CI) - self.initialized = False - self.state = State.disabled - self.enabled = False - self.active = False - self.soft_disable_timer = 0 - self.mismatch_counter = 0 - self.cruise_mismatch_counter = 0 - self.last_blinker_frame = 0 - self.last_steering_pressed_frame = 0 - self.distance_traveled = 0 - self.last_functional_fan_frame = 0 - self.events_prev = [] - self.current_alert_types = [ET.PERMANENT] - self.logged_comm_issue = None - self.not_running_prev = None - self.steer_limited = False - self.desired_curvature = 0.0 - self.experimental_mode = False - self.personality = self.read_personality_param() - self.v_cruise_helper = VCruiseHelper(self.CP) - self.recalibrating_seen = False - - self.can_log_mono_time = 0 - - self.startup_event = get_startup_event(car_recognized, not self.CP.passive, len(self.CP.carFw) > 0) - - if not sounds_available: - self.events.add(EventName.soundsUnavailable, static=True) - if not car_recognized: - self.events.add(EventName.carUnrecognized, static=True) - if len(self.CP.carFw) > 0: - set_offroad_alert("Offroad_CarUnrecognized", True) - else: - set_offroad_alert("Offroad_NoFirmware", True) - elif self.CP.passive: - self.events.add(EventName.dashcamMode, static=True) - - # controlsd is driven by carState, expected at 100Hz - self.rk = Ratekeeper(100, print_delay_threshold=None) - - def set_initial_state(self): - if REPLAY: - controls_state = self.params.get("ReplayControlsState") - if controls_state is not None: - with log.ControlsState.from_bytes(controls_state) as controls_state: - self.v_cruise_helper.v_cruise_kph = controls_state.vCruise - - if any(ps.controlsAllowed for ps in self.sm['pandaStates']): - self.state = State.enabled - - def update_events(self, CS): - """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) - self.startup_event = None - - # Don't add any more events if not initialized - if not self.initialized: - self.events.add(EventName.controlsInitializing) - return - - # no more events while in dashcam mode - if self.CP.passive: - return - - # Block resume if cruise never previously enabled - resume_pressed = any(be.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for be in CS.buttonEvents) - if not self.CP.pcmCruise and not self.v_cruise_helper.v_cruise_initialized and resume_pressed: - self.events.add(EventName.resumeBlocked) - - if not self.CP.notCar: - self.events.add_from_msg(self.sm['driverMonitoringState'].events) - - # Add car events, ignore if CAN isn't valid - if CS.canValid: - self.events.add_from_msg(CS.events) - - # Create events for temperature, disk space, and memory - if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: - self.events.add(EventName.overheat) - if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: - # under 7% of space free no enable allowed - self.events.add(EventName.outOfSpace) - if self.sm['deviceState'].memoryUsagePercent > 90 and not SIMULATION: - self.events.add(EventName.lowMemory) - - # TODO: enable this once loggerd CPU usage is more reasonable - #cpus = list(self.sm['deviceState'].cpuUsagePercent) - #if max(cpus, default=0) > 95 and not SIMULATION: - # self.events.add(EventName.highCpuUsage) - - # Alert if fan isn't spinning for 5 seconds - if self.sm['peripheralState'].pandaType != log.PandaState.PandaType.unknown: - if self.sm['peripheralState'].fanSpeedRpm < 500 and self.sm['deviceState'].fanSpeedPercentDesired > 50: - # allow enough time for the fan controller in the panda to recover from stalls - if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 15.0: - self.events.add(EventName.fanMalfunction) - else: - self.last_functional_fan_frame = self.sm.frame - - # Handle calibration status - cal_status = self.sm['liveCalibration'].calStatus - if cal_status != log.LiveCalibrationData.Status.calibrated: - if cal_status == log.LiveCalibrationData.Status.uncalibrated: - self.events.add(EventName.calibrationIncomplete) - elif cal_status == log.LiveCalibrationData.Status.recalibrating: - if not self.recalibrating_seen: - set_offroad_alert("Offroad_Recalibration", True) - self.recalibrating_seen = True - self.events.add(EventName.calibrationRecalibrating) - else: - self.events.add(EventName.calibrationInvalid) - - # Handle lane change - 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) - else: - if direction == LaneChangeDirection.left: - self.events.add(EventName.preLaneChangeLeft) - else: - self.events.add(EventName.preLaneChangeRight) - elif self.sm['modelV2'].meta.laneChangeState in (LaneChangeState.laneChangeStarting, - LaneChangeState.laneChangeFinishing): - self.events.add(EventName.laneChange) - - for i, pandaState in enumerate(self.sm['pandaStates']): - # All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput - if i < len(self.CP.safetyConfigs): - safety_mismatch = pandaState.safetyModel != self.CP.safetyConfigs[i].safetyModel or \ - pandaState.safetyParam != self.CP.safetyConfigs[i].safetyParam or \ - pandaState.alternativeExperience != self.CP.alternativeExperience - else: - safety_mismatch = pandaState.safetyModel not in IGNORED_SAFETY_MODES - - # safety mismatch allows some time for pandad 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: - self.events.add(EventName.relayMalfunction) - - # Handle HW and system malfunctions - # Order is very intentional here. Be careful when modifying this. - # All events here should at least have NO_ENTRY and SOFT_DISABLE. - 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.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) - self.not_running_prev = not_running - else: - if not SIMULATION and not self.rk.lagging: - if not self.sm.all_alive(self.camera_packets): - self.events.add(EventName.cameraMalfunction) - elif not self.sm.all_freq_ok(self.camera_packets): - self.events.add(EventName.cameraFrameRate) - if not REPLAY and self.rk.lagging: - self.events.add(EventName.controlsdLagging) - if len(self.sm['radarState'].radarErrors) or ((not self.rk.lagging or REPLAY) and not self.sm.all_checks(['radarState'])): - self.events.add(EventName.radarFault) - if not self.sm.valid['pandaStates']: - self.events.add(EventName.usbError) - if CS.canTimeout: - self.events.add(EventName.canBusMissing) - elif not CS.canValid: - self.events.add(EventName.canError) - - # generic catch-all. ideally, a more specific event should be added above instead - 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() and no_system_errors: - if not self.sm.all_alive(): - self.events.add(EventName.commIssue) - elif not self.sm.all_freq_ok(): - self.events.add(EventName.commIssueAvgFreq) - else: - self.events.add(EventName.commIssue) - - logs = { - '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], - } - if logs != self.logged_comm_issue: - cloudlog.event("commIssue", error=True, **logs) - self.logged_comm_issue = logs - else: - self.logged_comm_issue = None - - 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.recv_frame[s])*DT_CTRL > 10. for s in self.sensor_packets): - self.events.add(EventName.sensorDataInvalid) - - if not REPLAY: - # Check for mismatch between openpilot and car's PCM - cruise_mismatch = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) - self.cruise_mismatch_counter = self.cruise_mismatch_counter + 1 if cruise_mismatch else 0 - if self.cruise_mismatch_counter > int(6. / DT_CTRL): - self.events.add(EventName.cruiseMismatch) - - # Check for FCW - stock_long_is_braking = self.enabled and not self.CP.openpilotLongitudinalControl and CS.aEgo < -1.25 - model_fcw = self.sm['modelV2'].meta.hardBrakePredicted and not CS.brakePressed and not stock_long_is_braking - planner_fcw = self.sm['longitudinalPlan'].fcw and self.enabled - if (planner_fcw or model_fcw) and not (self.CP.notCar and self.joystick_mode): - self.events.add(EventName.fcw) - - for m in messaging.drain_sock(self.log_sock, wait_for_one=False): - try: - msg = m.androidLog.message - if any(err in msg for err in ("ERROR_CRC", "ERROR_ECC", "ERROR_STREAM_UNDERFLOW", "APPLY FAILED")): - csid = msg.split("CSID:")[-1].split(" ")[0] - evt = CSID_MAP.get(csid, None) - if evt is not None: - self.events.add(evt) - except UnicodeDecodeError: - pass - - # TODO: fix simulator - if not SIMULATION or REPLAY: - # Not show in first 1 km to allow for driving out of garage. This event shows after 5 minutes - if not self.sm['liveLocationKalman'].gpsOK and self.sm['liveLocationKalman'].inputsOK and (self.distance_traveled > 1500): - 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) - - def data_sample(self): - """Receive data from sockets""" - - car_state = messaging.recv_one(self.car_state_sock) - CS = car_state.carState if car_state else self.CS_prev - - 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 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: - self.sm.ignore_alive.append('roadCameraState') - if VisionStreamType.VISION_STREAM_WIDE_ROAD not in available_streams: - self.sm.ignore_alive.append('wideRoadCameraState') - - self.initialized = True - self.set_initial_state() - - 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 - # another socket other than the CAN messages and one can arrive earlier than the other. - # Therefore we allow a mismatch for two samples, then we trigger the disengagement. - if not self.enabled: - self.mismatch_counter = 0 - - # All pandas not in silent mode must have controlsAllowed when openpilot is enabled - if self.enabled and any(not ps.controlsAllowed for ps in self.sm['pandaStates'] - if ps.safetyModel not in IGNORED_SAFETY_MODES): - self.mismatch_counter += 1 - - return CS - - def state_transition(self, CS): - """Compute conditional state transitions and execute actions on state transitions""" - - self.v_cruise_helper.update_v_cruise(CS, self.enabled, self.is_metric) - - # decrement the soft disable timer at every step, as it's reset on - # entrance in SOFT_DISABLING state - self.soft_disable_timer = max(0, self.soft_disable_timer - 1) - - self.current_alert_types = [ET.PERMANENT] - - # ENABLED, SOFT DISABLING, PRE ENABLING, OVERRIDING - if self.state != State.disabled: - # user and immediate disable always have priority in a non-disabled state - if self.events.contains(ET.USER_DISABLE): - self.state = State.disabled - self.current_alert_types.append(ET.USER_DISABLE) - - elif self.events.contains(ET.IMMEDIATE_DISABLE): - self.state = State.disabled - self.current_alert_types.append(ET.IMMEDIATE_DISABLE) + def update(self): + self.sm.update(15) + if self.sm.updated["liveCalibration"]: + self.pose_calibrator.feed_live_calib(self.sm['liveCalibration']) + if self.sm.updated["livePose"]: + device_pose = Pose.from_live_pose(self.sm['livePose']) + self.calibrated_pose = self.pose_calibrator.build_calibrated_pose(device_pose) - else: - # ENABLED - if self.state == State.enabled: - if self.events.contains(ET.SOFT_DISABLE): - self.state = State.softDisabling - self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) - self.current_alert_types.append(ET.SOFT_DISABLE) - - elif self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL): - self.state = State.overriding - self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] - - # SOFT DISABLING - elif self.state == State.softDisabling: - if not self.events.contains(ET.SOFT_DISABLE): - # no more soft disabling condition, so go back to ENABLED - self.state = State.enabled - - elif self.soft_disable_timer > 0: - self.current_alert_types.append(ET.SOFT_DISABLE) - - elif self.soft_disable_timer <= 0: - self.state = State.disabled - - # PRE ENABLING - elif self.state == State.preEnabled: - if not self.events.contains(ET.PRE_ENABLE): - self.state = State.enabled - else: - self.current_alert_types.append(ET.PRE_ENABLE) - - # OVERRIDING - elif self.state == State.overriding: - if self.events.contains(ET.SOFT_DISABLE): - self.state = State.softDisabling - self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) - self.current_alert_types.append(ET.SOFT_DISABLE) - elif not (self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL)): - self.state = State.enabled - else: - self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] - - # DISABLED - elif self.state == State.disabled: - if self.events.contains(ET.ENABLE): - if self.events.contains(ET.NO_ENTRY): - self.current_alert_types.append(ET.NO_ENTRY) - - else: - if self.events.contains(ET.PRE_ENABLE): - self.state = State.preEnabled - elif self.events.contains(ET.OVERRIDE_LATERAL) or self.events.contains(ET.OVERRIDE_LONGITUDINAL): - self.state = State.overriding - else: - self.state = State.enabled - self.current_alert_types.append(ET.ENABLE) - self.v_cruise_helper.initialize_v_cruise(CS, self.experimental_mode) - - # Check if openpilot is engaged and actuators are enabled - self.enabled = self.state in ENABLED_STATES - self.active = self.state in ACTIVE_STATES - if self.active: - self.current_alert_types.append(ET.WARNING) - - def state_control(self, CS): - """Given the state, this function returns a CarControl packet""" + def state_control(self): + CS = self.sm['carState'] # Update VehicleModel lp = self.sm['liveParameters'] @@ -539,13 +84,12 @@ def state_control(self, CS): model_v2 = self.sm['modelV2'] CC = car.CarControl.new_message() - CC.enabled = self.enabled + CC.enabled = self.sm['selfdriveState'].enabled # Check which actuators can be enabled - standstill = CS.vEgo <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill - CC.latActive = self.active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and \ - (not standstill or self.joystick_mode) - CC.longActive = self.enabled and not self.events.contains(ET.OVERRIDE_LONGITUDINAL) and self.CP.openpilotLongitudinalControl + standstill = abs(CS.vEgo) <= max(self.CP.minSteerSpeed, MIN_LATERAL_CONTROL_SPEED) or CS.standstill + CC.latActive = self.sm['selfdriveState'].active and not CS.steerFaultTemporary and not CS.steerFaultPermanent and not standstill + CC.longActive = CC.enabled and not any(e.overrideLongitudinal for e in self.sm['onroadEvents']) and self.CP.openpilotLongitudinalControl actuators = CC.actuators actuators.longControlState = self.LoC.long_control_state @@ -555,80 +99,21 @@ def state_control(self, CS): 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 - - # State specific actions - if not CC.latActive: self.LaC.reset() if not CC.longActive: - self.LoC.reset(v_pid=CS.vEgo) - - 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.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 = 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.recv_frame['testJoystick'] > 0: - # reset joystick if it hasn't been received in a while - 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: - joystick_axes = [0.0, 0.0] - - if CC.longActive: - actuators.accel = 4.0*clip(joystick_axes[0], -1, 1) - - 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 * 90., steer * -0.02 - - lac_log.active = self.active - lac_log.steeringAngleDeg = CS.steeringAngleDeg - lac_log.output = actuators.steer - lac_log.saturated = abs(actuators.steer) >= 0.9 - - if CS.steeringPressed: - self.last_steering_pressed_frame = self.sm.frame - recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0 - - # Send a "steering required alert" if saturation count has reached the limit - if lac_log.active and not recent_steer_pressed and not self.CP.notCar: - if self.CP.lateralTuning.which() == 'torque' and not self.joystick_mode: - undershooting = abs(lac_log.desiredLateralAccel) / abs(1e-3 + lac_log.actualLateralAccel) > 1.2 - turning = abs(lac_log.desiredLateralAccel) > 1.0 - good_speed = CS.vEgo > 5 - max_torque = abs(self.sm['carOutput'].actuatorsOutput.steer) > 0.99 - if undershooting and turning and good_speed and max_torque: - lac_log.active and self.events.add(EventName.steerSaturated) - elif lac_log.saturated: - # 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 - if self.CP.steerControlType == car.CarParams.SteerControlType.angle: - steering_value = actuators.steeringAngleDeg - else: - steering_value = actuators.steer - - left_deviation = steering_value > 0 and dpath_points[0] < -0.20 - right_deviation = steering_value < 0 and dpath_points[0] > 0.20 - - if left_deviation or right_deviation: - self.events.add(EventName.steerSaturated) + self.LoC.reset() + + # accel PID loop + pid_accel_limits = self.CI.get_pid_accel_limits(self.CP, CS.vEgo, CS.vCruise * CV.KPH_TO_MS) + actuators.accel = self.LoC.update(CC.longActive, CS, long_plan.aTarget, long_plan.shouldStop, pid_accel_limits) + + # Steering PID loop and lateral MPC + 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.calibrated_pose) # TODO what if not available # Ensure no NaNs/Infs for p in ACTUATOR_FIELDS: @@ -640,80 +125,39 @@ def state_control(self, CS): cloudlog.error(f"actuators.{p} not finite {actuators.to_dict()}") setattr(actuators, p, 0.0) - # decrement personality on distance button press - if self.CP.openpilotLongitudinalControl: - if any(not be.pressed and be.type == ButtonType.gapAdjustCruise for be in CS.buttonEvents): - self.personality = (self.personality - 1) % 3 - self.params.put_nonblocking('LongitudinalPersonality', str(self.personality)) - return CC, lac_log - def publish_logs(self, CS, start_time, CC, lac_log): - """Send actuators and hud commands to the car, send controlsstate and MPC logging""" + def publish(self, CC, lac_log): + CS = self.sm['carState'] # Orientation and angle rates can be useful for carcontroller # Only calibrated (car) frame is relevant for the carcontroller - orientation_value = list(self.sm['liveLocationKalman'].calibratedOrientationNED.value) - if len(orientation_value) > 2: - CC.orientationNED = orientation_value - angular_rate_value = list(self.sm['liveLocationKalman'].angularVelocityCalibrated.value) - if len(angular_rate_value) > 2: - CC.angularVelocity = angular_rate_value - - 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.recv_frame['testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: - CC.cruiseControl.cancel = True + if self.calibrated_pose is not None: + CC.orientationNED = self.calibrated_pose.orientation.xyz.tolist() + CC.angularVelocity = self.calibrated_pose.angular_velocity.xyz.tolist() + + CC.cruiseControl.override = CC.enabled and not CC.longActive and self.CP.openpilotLongitudinalControl + CC.cruiseControl.cancel = CS.cruiseState.enabled and (not CC.enabled or not self.CP.pcmCruise) speeds = self.sm['longitudinalPlan'].speeds if len(speeds): - CC.cruiseControl.resume = self.enabled and CS.cruiseState.standstill and speeds[-1] > 0.1 + CC.cruiseControl.resume = CC.enabled and CS.cruiseState.standstill and speeds[-1] > 0.1 hudControl = CC.hudControl - hudControl.setSpeed = float(self.v_cruise_helper.v_cruise_cluster_kph * CV.KPH_TO_MS) - hudControl.speedVisible = self.enabled - hudControl.lanesVisible = self.enabled + hudControl.setSpeed = float(CS.vCruiseCluster * CV.KPH_TO_MS) + hudControl.speedVisible = CC.enabled + hudControl.lanesVisible = CC.enabled hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead - hudControl.leadDistanceBars = self.personality + 1 + hudControl.leadDistanceBars = self.sm['selfdriveState'].personality.raw + 1 + hudControl.visualAlert = self.sm['selfdriveState'].alertHudVisual hudControl.rightLaneVisible = True hudControl.leftLaneVisible = True + if self.sm.valid['driverAssistance']: + hudControl.leftLaneDepart = self.sm['driverAssistance'].leftLaneDeparture + hudControl.rightLaneDepart = self.sm['driverAssistance'].rightLaneDeparture - recent_blinker = (self.sm.frame - self.last_blinker_frame) * DT_CTRL < 5.0 # 5s blinker cooldown - ldw_allowed = self.is_ldw_enabled and CS.vEgo > LDW_MIN_SPEED and not recent_blinker \ - and not CC.latActive and self.sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.calibrated - - model_v2 = self.sm['modelV2'] - desire_prediction = model_v2.meta.desirePrediction - if len(desire_prediction) and ldw_allowed: - right_lane_visible = model_v2.laneLineProbs[2] > 0.5 - left_lane_visible = model_v2.laneLineProbs[1] > 0.5 - l_lane_change_prob = desire_prediction[Desire.laneChangeLeft] - r_lane_change_prob = desire_prediction[Desire.laneChangeRight] - - lane_lines = model_v2.laneLines - l_lane_close = left_lane_visible and (lane_lines[1].y[0] > -(1.08 + CAMERA_OFFSET)) - r_lane_close = right_lane_visible and (lane_lines[2].y[0] < (1.08 - CAMERA_OFFSET)) - - hudControl.leftLaneDepart = bool(l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) - hudControl.rightLaneDepart = bool(r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) - - if hudControl.rightLaneDepart or hudControl.leftLaneDepart: - self.events.add(EventName.ldw) - - clear_event_types = set() - if ET.WARNING not in self.current_alert_types: - clear_event_types.add(ET.WARNING) - if self.enabled: - clear_event_types.add(ET.NO_ENTRY) - - alerts = self.events.create_alerts(self.current_alert_types, [self.CP, CS, self.sm, self.is_metric, self.soft_disable_timer]) - self.AM.add_many(self.sm.frame, alerts) - current_alert = self.AM.process_alerts(self.sm.frame, clear_event_types) - if current_alert: - hudControl.visualAlert = current_alert.visual_alert - - if not self.CP.passive and self.initialized: + if self.sm['selfdriveState'].active: CO = self.sm['carOutput'] if self.CP.steerControlType == car.CarParams.SteerControlType.angle: self.steer_limited = abs(CC.actuators.steeringAngleDeg - CO.actuatorsOutput.steeringAngleDeg) > \ @@ -721,129 +165,56 @@ def publish_logs(self, CS, start_time, CC, lac_log): else: self.steer_limited = abs(CC.actuators.steer - CO.actuatorsOutput.steer) > 1e-2 - force_decel = (self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ - (self.state == State.softDisabling) - - # Curvature & Steering angle - lp = self.sm['liveParameters'] - - steer_angle_without_offset = math.radians(CS.steeringAngleDeg - lp.angleOffsetDeg) - curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, lp.roll) + # TODO: both controlsState and carControl valids should be set by + # sm.all_checks(), but this creates a circular dependency # controlsState dat = messaging.new_message('controlsState') dat.valid = CS.canValid - controlsState = dat.controlsState - if current_alert: - controlsState.alertText1 = current_alert.alert_text_1 - controlsState.alertText2 = current_alert.alert_text_2 - controlsState.alertSize = current_alert.alert_size - controlsState.alertStatus = current_alert.alert_status - controlsState.alertBlinkingRate = current_alert.alert_rate - controlsState.alertType = current_alert.alert_type - controlsState.alertSound = current_alert.audible_alert - - controlsState.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan'] - controlsState.lateralPlanMonoTime = self.sm.logMonoTime['modelV2'] - controlsState.enabled = self.enabled - controlsState.active = self.active - controlsState.curvature = curvature - controlsState.desiredCurvature = self.desired_curvature - controlsState.state = self.state - controlsState.engageable = not self.events.contains(ET.NO_ENTRY) - controlsState.longControlState = self.LoC.long_control_state - controlsState.vPid = float(self.LoC.v_pid) - controlsState.vCruise = float(self.v_cruise_helper.v_cruise_kph) - controlsState.vCruiseCluster = float(self.v_cruise_helper.v_cruise_cluster_kph) - controlsState.upAccelCmd = float(self.LoC.pid.p) - controlsState.uiAccelCmd = float(self.LoC.pid.i) - controlsState.ufAccelCmd = float(self.LoC.pid.f) - controlsState.cumLagMs = -self.rk.remaining * 1000. - controlsState.startMonoTime = int(start_time * 1e9) - controlsState.forceDecel = bool(force_decel) - controlsState.experimentalMode = self.experimental_mode - controlsState.personality = self.personality + cs = dat.controlsState + + lp = self.sm['liveParameters'] + steer_angle_without_offset = math.radians(CS.steeringAngleDeg - lp.angleOffsetDeg) + cs.curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, lp.roll) + + cs.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan'] + cs.lateralPlanMonoTime = self.sm.logMonoTime['modelV2'] + cs.desiredCurvature = self.desired_curvature + cs.longControlState = self.LoC.long_control_state + cs.upAccelCmd = float(self.LoC.pid.p) + cs.uiAccelCmd = float(self.LoC.pid.i) + cs.ufAccelCmd = float(self.LoC.pid.f) + cs.forceDecel = bool((self.sm['driverMonitoringState'].awarenessStatus < 0.) or + (self.sm['selfdriveState'].state == State.softDisabling)) lat_tuning = self.CP.lateralTuning.which() - if self.joystick_mode: - controlsState.lateralControlState.debugState = lac_log - elif self.CP.steerControlType == car.CarParams.SteerControlType.angle: - controlsState.lateralControlState.angleState = lac_log + if self.CP.steerControlType == car.CarParams.SteerControlType.angle: + cs.lateralControlState.angleState = lac_log elif lat_tuning == 'pid': - controlsState.lateralControlState.pidState = lac_log + cs.lateralControlState.pidState = lac_log elif lat_tuning == 'torque': - controlsState.lateralControlState.torqueState = lac_log + cs.lateralControlState.torqueState = lac_log self.pm.send('controlsState', dat) - # 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('onroadEvents', len(self.events)) - ce_send.valid = True - ce_send.onroadEvents = self.events.to_msg() - self.pm.send('onroadEvents', ce_send) - self.events_prev = self.events.names.copy() - # carControl cc_send = messaging.new_message('carControl') cc_send.valid = CS.canValid cc_send.carControl = CC self.pm.send('carControl', cc_send) - def step(self): - start_time = time.monotonic() - - # Sample data from sockets and get a carState - CS = self.data_sample() - cloudlog.timestamp("Data sampled") - - self.update_events(CS) - cloudlog.timestamp("Events updated") - - if not self.CP.passive and self.initialized: - # Update control state - self.state_transition(CS) - - # Compute actuators (runs PID loops and lateral MPC) - CC, lac_log = self.state_control(CS) - - # Publish data - self.publish_logs(CS, start_time, CC, lac_log) - - self.CS_prev = CS - - def read_personality_param(self): - try: - return int(self.params.get('LongitudinalPersonality')) - except (ValueError, TypeError): - return log.LongitudinalPersonality.standard - - 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 - self.personality = self.read_personality_param() - if self.CP.notCar: - self.joystick_mode = self.params.get_bool("JoystickDebugMode") - time.sleep(0.1) - - def controlsd_thread(self): - 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 run(self): + rk = Ratekeeper(100, print_delay_threshold=None) + while True: + self.update() + CC, lac_log = self.state_control() + self.publish(CC, lac_log) + rk.monitor_time() def main(): config_realtime_process(4, Priority.CTRL_HIGH) controls = Controls() - controls.controlsd_thread() + controls.run() if __name__ == "__main__": diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py deleted file mode 100644 index f67e269fa978546..000000000000000 --- a/selfdrive/controls/lib/alertmanager.py +++ /dev/null @@ -1,61 +0,0 @@ -import copy -import os -import json -from collections import defaultdict -from dataclasses import dataclass - -from openpilot.common.basedir import BASEDIR -from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.events import Alert - - -with open(os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json")) as f: - OFFROAD_ALERTS = json.load(f) - - -def set_offroad_alert(alert: str, show_alert: bool, extra_text: str = None) -> None: - if show_alert: - a = copy.copy(OFFROAD_ALERTS[alert]) - a['extra'] = extra_text or '' - Params().put(alert, json.dumps(a)) - else: - Params().remove(alert) - - -@dataclass -class AlertEntry: - alert: Alert | None = None - start_frame: int = -1 - end_frame: int = -1 - - def active(self, frame: int) -> bool: - return frame <= self.end_frame - -class AlertManager: - def __init__(self): - self.alerts: dict[str, AlertEntry] = defaultdict(AlertEntry) - - def add_many(self, frame: int, alerts: list[Alert]) -> None: - for alert in alerts: - entry = self.alerts[alert.alert_type] - entry.alert = alert - if not entry.active(frame): - entry.start_frame = frame - min_end_frame = entry.start_frame + alert.duration - entry.end_frame = max(frame + 1, min_end_frame) - - def process_alerts(self, frame: int, clear_event_types: set) -> Alert | None: - current_alert = AlertEntry() - for v in self.alerts.values(): - if not v.alert: - continue - - if v.alert.event_type in clear_event_types: - v.end_frame = -1 - - # sort by priority first and then by start_frame - greater = current_alert.alert is None or (v.alert.priority, v.start_frame) > (current_alert.alert.priority, current_alert.start_frame) - if v.active(frame) and greater: - current_alert = v - - return current_alert.alert diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index 6a5b22f6868726a..64cbf473d63d299 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -1,20 +1,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 cereal import log +from openpilot.common.numpy_fast import clip 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 -# V_CRUISE's are in kph -V_CRUISE_MIN = 8 -V_CRUISE_MAX = 145 -V_CRUISE_UNSET = 255 -V_CRUISE_INITIAL = 40 -V_CRUISE_INITIAL_EXPERIMENTAL_MODE = 105 -IMPERIAL_INCREMENT = 1.6 # should be CV.MPH_TO_KPH, but this causes rounding errors - MIN_SPEED = 1.0 CONTROL_N = 17 CAR_ROTATION_RADIUS = 0.0 @@ -23,144 +10,6 @@ MAX_LATERAL_JERK = 5.0 MAX_VEL_ERR = 5.0 -ButtonEvent = car.CarState.ButtonEvent -ButtonType = car.CarState.ButtonEvent.Type -CRUISE_LONG_PRESS = 50 -CRUISE_NEAREST_FUNC = { - ButtonType.accelCruise: math.ceil, - ButtonType.decelCruise: math.floor, -} -CRUISE_INTERVAL_SIGN = { - ButtonType.accelCruise: +1, - ButtonType.decelCruise: -1, -} - - -class VCruiseHelper: - def __init__(self, CP): - self.CP = CP - self.v_cruise_kph = V_CRUISE_UNSET - self.v_cruise_cluster_kph = V_CRUISE_UNSET - self.v_cruise_kph_last = 0 - self.button_timers = {ButtonType.decelCruise: 0, ButtonType.accelCruise: 0} - self.button_change_states = {btn: {"standstill": False, "enabled": False} for btn in self.button_timers} - - @property - def v_cruise_initialized(self): - return self.v_cruise_kph != V_CRUISE_UNSET - - def update_v_cruise(self, CS, enabled, is_metric): - self.v_cruise_kph_last = self.v_cruise_kph - - if CS.cruiseState.available: - if not self.CP.pcmCruise: - # if stock cruise is completely disabled, then we can use our own set speed logic - self._update_v_cruise_non_pcm(CS, enabled, is_metric) - self.v_cruise_cluster_kph = self.v_cruise_kph - self.update_button_timers(CS, enabled) - else: - self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH - self.v_cruise_cluster_kph = CS.cruiseState.speedCluster * CV.MS_TO_KPH - else: - self.v_cruise_kph = V_CRUISE_UNSET - self.v_cruise_cluster_kph = V_CRUISE_UNSET - - def _update_v_cruise_non_pcm(self, CS, enabled, is_metric): - # handle button presses. TODO: this should be in state_control, but a decelCruise press - # would have the effect of both enabling and changing speed is checked after the state transition - if not enabled: - return - - long_press = False - button_type = None - - v_cruise_delta = 1. if is_metric else IMPERIAL_INCREMENT - - for b in CS.buttonEvents: - if b.type.raw in self.button_timers and not b.pressed: - if self.button_timers[b.type.raw] > CRUISE_LONG_PRESS: - return # end long press - button_type = b.type.raw - break - else: - for k in self.button_timers.keys(): - if self.button_timers[k] and self.button_timers[k] % CRUISE_LONG_PRESS == 0: - button_type = k - long_press = True - break - - if button_type is None: - return - - # Don't adjust speed when pressing resume to exit standstill - cruise_standstill = self.button_change_states[button_type]["standstill"] or CS.cruiseState.standstill - if button_type == ButtonType.accelCruise and cruise_standstill: - return - - # Don't adjust speed if we've enabled since the button was depressed (some ports enable on rising edge) - if not self.button_change_states[button_type]["enabled"]: - return - - v_cruise_delta = v_cruise_delta * (5 if long_press else 1) - if long_press and self.v_cruise_kph % v_cruise_delta != 0: # partial interval - self.v_cruise_kph = CRUISE_NEAREST_FUNC[button_type](self.v_cruise_kph / v_cruise_delta) * v_cruise_delta - else: - self.v_cruise_kph += v_cruise_delta * CRUISE_INTERVAL_SIGN[button_type] - - # If set is pressed while overriding, clip cruise speed to minimum of vEgo - if CS.gasPressed and button_type in (ButtonType.decelCruise, ButtonType.setCruise): - self.v_cruise_kph = max(self.v_cruise_kph, CS.vEgo * CV.MS_TO_KPH) - - self.v_cruise_kph = clip(round(self.v_cruise_kph, 1), V_CRUISE_MIN, V_CRUISE_MAX) - - def update_button_timers(self, CS, enabled): - # increment timer for buttons still pressed - for k in self.button_timers: - if self.button_timers[k] > 0: - self.button_timers[k] += 1 - - for b in CS.buttonEvents: - if b.type.raw in self.button_timers: - # Start/end timer and store current state on change of button pressed - self.button_timers[b.type.raw] = 1 if b.pressed else 0 - self.button_change_states[b.type.raw] = {"standstill": CS.cruiseState.standstill, "enabled": enabled} - - def initialize_v_cruise(self, CS, experimental_mode: bool) -> None: - # initializing is handled by the PCM - if self.CP.pcmCruise: - return - - initial = V_CRUISE_INITIAL_EXPERIMENTAL_MODE if experimental_mode else V_CRUISE_INITIAL - - # 250kph or above probably means we never had a set speed - if any(b.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for b in CS.buttonEvents) and self.v_cruise_kph_last < 250: - self.v_cruise_kph = self.v_cruise_kph_last - else: - self.v_cruise_kph = int(round(clip(CS.vEgo * CV.MS_TO_KPH, initial, V_CRUISE_MAX))) - - self.v_cruise_cluster_kph = self.v_cruise_kph - - -def apply_deadzone(error, deadzone): - if error > deadzone: - error -= deadzone - elif error < - deadzone: - error += deadzone - else: - error = 0. - return error - - -def apply_center_deadzone(error, deadzone): - if (error > - deadzone) and (error < deadzone): - error = 0. - return error - - -def rate_limit(new_value, last_value, dw_step, up_step): - return clip(new_value, last_value + dw_step, last_value + up_step) - - def clip_curvature(v_ego, prev_curvature, new_curvature): v_ego = max(MIN_SPEED, v_ego) max_curvature_rate = MAX_LATERAL_JERK / (v_ego**2) # inexact calculation, check https://github.com/commaai/openpilot/pull/24755 @@ -171,17 +20,6 @@ def clip_curvature(v_ego, prev_curvature, new_curvature): return safe_desired_curvature -def get_friction(lateral_accel_error: float, lateral_accel_deadzone: float, friction_threshold: float, - torque_params: car.CarParams.LateralTorqueTuning, friction_compensation: bool) -> float: - friction_interp = interp( - apply_center_deadzone(lateral_accel_error, lateral_accel_deadzone), - [-friction_threshold, friction_threshold], - [-torque_params.friction, torque_params.friction] - ) - friction = float(friction_interp) if friction_compensation else 0.0 - return friction - - def get_speed_error(modelV2: log.ModelDataV2, v_ego: float) -> float: # ToDo: Try relative error, and absolute speed if len(modelV2.temporalPose.trans): diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py index fddb331ccb9c7d2..0e4a27da61725fa 100644 --- a/selfdrive/controls/lib/latcontrol.py +++ b/selfdrive/controls/lib/latcontrol.py @@ -17,7 +17,7 @@ def __init__(self, CP, CI): self.steer_max = 1.0 @abstractmethod - def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose): pass def reset(self): diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py index 329c486eb9a2e56..d3da656daa16dff 100644 --- a/selfdrive/controls/lib/latcontrol_angle.py +++ b/selfdrive/controls/lib/latcontrol_angle.py @@ -11,7 +11,7 @@ def __init__(self, CP, CI): super().__init__(CP, CI) self.sat_check_min_speed = 5. - def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose): angle_log = log.ControlsState.LateralAngleState.new_message() if not active: diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py index 9e6160838b20670..d7edd39f8a4103b 100644 --- a/selfdrive/controls/lib/latcontrol_pid.py +++ b/selfdrive/controls/lib/latcontrol_pid.py @@ -2,7 +2,7 @@ from cereal import log from openpilot.selfdrive.controls.lib.latcontrol import LatControl -from openpilot.selfdrive.controls.lib.pid import PIDController +from openpilot.common.pid import PIDController class LatControlPID(LatControl): @@ -17,7 +17,7 @@ def reset(self): super().reset() self.pid.reset() - def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose): pid_log = log.ControlsState.LateralPIDState.new_message() pid_log.steeringAngleDeg = float(CS.steeringAngleDeg) pid_log.steeringRateDeg = float(CS.steeringRateDeg) diff --git a/selfdrive/controls/lib/latcontrol_torque.py b/selfdrive/controls/lib/latcontrol_torque.py index 34b0d4712417507..55a37c1f4bd5ad0 100644 --- a/selfdrive/controls/lib/latcontrol_torque.py +++ b/selfdrive/controls/lib/latcontrol_torque.py @@ -1,10 +1,10 @@ import math from cereal import log +from opendbc.car.interfaces import LatControlInputs from openpilot.common.numpy_fast import interp -from openpilot.selfdrive.car.interfaces import LatControlInputs from openpilot.selfdrive.controls.lib.latcontrol import LatControl -from openpilot.selfdrive.controls.lib.pid import PIDController +from openpilot.common.pid import PIDController from openpilot.selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY # At higher speeds (25+mph) we can assume: @@ -25,7 +25,7 @@ class LatControlTorque(LatControl): def __init__(self, CP, CI): super().__init__(CP, CI) - self.torque_params = CP.lateralTuning.torque + self.torque_params = CP.lateralTuning.torque.as_builder() self.pid = PIDController(self.torque_params.kp, self.torque_params.ki, k_f=self.torque_params.kf, pos_limit=self.steer_max, neg_limit=-self.steer_max) self.torque_from_lateral_accel = CI.torque_from_lateral_accel() @@ -37,7 +37,7 @@ def update_live_torque_params(self, latAccelFactor, latAccelOffset, friction): self.torque_params.latAccelOffset = latAccelOffset self.torque_params.friction = friction - def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): + def update(self, active, CS, VM, params, steer_limited, desired_curvature, calibrated_pose): pid_log = log.ControlsState.LateralTorqueState.new_message() if not active: output_torque = 0.0 @@ -49,8 +49,9 @@ def update(self, active, CS, VM, params, steer_limited, desired_curvature, llk): actual_curvature = actual_curvature_vm curvature_deadzone = abs(VM.calc_curvature(math.radians(self.steering_angle_deadzone_deg), CS.vEgo, 0.0)) else: - actual_curvature_llk = llk.angularVelocityCalibrated.value[2] / CS.vEgo - actual_curvature = interp(CS.vEgo, [2.0, 5.0], [actual_curvature_vm, actual_curvature_llk]) + assert calibrated_pose is not None + actual_curvature_pose = calibrated_pose.angular_velocity.yaw / CS.vEgo + actual_curvature = interp(CS.vEgo, [2.0, 5.0], [actual_curvature_vm, actual_curvature_pose]) curvature_deadzone = 0.0 desired_lateral_accel = desired_curvature * CS.vEgo ** 2 diff --git a/selfdrive/controls/lib/lateral_mpc_lib/SConscript b/selfdrive/controls/lib/lateral_mpc_lib/SConscript index 73242cb8f9cf360..2c03da06a626dfd 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/SConscript +++ b/selfdrive/controls/lib/lateral_mpc_lib/SConscript @@ -1,4 +1,4 @@ -Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'opendbc_python') +Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'opendbc_python', 'np_version') gen = "c_generated_code" @@ -88,3 +88,4 @@ lenv2.Command(libacados_ocp_solver_c, f' {acados_ocp_solver_pyx.get_labspath()}') lib_cython = lenv2.Program(f'{gen}/acados_ocp_solver_pyx.so', [libacados_ocp_solver_c]) lenv2.Depends(lib_cython, lib_solver) +lenv2.Depends(libacados_ocp_solver_c, np_version) diff --git a/selfdrive/controls/lib/ldw.py b/selfdrive/controls/lib/ldw.py new file mode 100644 index 000000000000000..caf03fec7327fc7 --- /dev/null +++ b/selfdrive/controls/lib/ldw.py @@ -0,0 +1,41 @@ +from cereal import log +from openpilot.common.realtime import DT_CTRL +from openpilot.common.conversions import Conversions as CV + + +CAMERA_OFFSET = 0.04 +LDW_MIN_SPEED = 31 * CV.MPH_TO_MS +LANE_DEPARTURE_THRESHOLD = 0.1 + +class LaneDepartureWarning: + def __init__(self): + self.left = False + self.right = False + self.last_blinker_frame = 0 + + def update(self, frame, modelV2, CS, CC): + if CS.leftBlinker or CS.rightBlinker: + self.last_blinker_frame = frame + + recent_blinker = (frame - self.last_blinker_frame) * DT_CTRL < 5.0 # 5s blinker cooldown + ldw_allowed = CS.vEgo > LDW_MIN_SPEED and not recent_blinker and not CC.latActive + + desire_prediction = modelV2.meta.desirePrediction + if len(desire_prediction) and ldw_allowed: + right_lane_visible = modelV2.laneLineProbs[2] > 0.5 + left_lane_visible = modelV2.laneLineProbs[1] > 0.5 + l_lane_change_prob = desire_prediction[log.Desire.laneChangeLeft] + r_lane_change_prob = desire_prediction[log.Desire.laneChangeRight] + + lane_lines = modelV2.laneLines + l_lane_close = left_lane_visible and (lane_lines[1].y[0] > -(1.08 + CAMERA_OFFSET)) + r_lane_close = right_lane_visible and (lane_lines[2].y[0] < (1.08 - CAMERA_OFFSET)) + + self.left = bool(l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) + self.right = bool(r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) + else: + self.left, self.right = False, False + + @property + def warning(self) -> bool: + return bool(self.left or self.right) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index d08ee05035215f5..e18ee0c279024b7 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -1,8 +1,8 @@ from cereal import car -from openpilot.common.numpy_fast import clip, interp +from openpilot.common.numpy_fast import clip from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, apply_deadzone -from openpilot.selfdrive.controls.lib.pid import PIDController +from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N +from openpilot.common.pid import PIDController from openpilot.selfdrive.modeld.constants import ModelConstants CONTROL_N_T_IDX = ModelConstants.T_IDXS[:CONTROL_N] @@ -10,18 +10,10 @@ LongCtrlState = car.CarControl.Actuators.LongControlState -def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, - v_target_1sec, brake_pressed, cruise_standstill): - accelerating = v_target_1sec > v_target - planned_stop = (v_target < CP.vEgoStopping and - v_target_1sec < CP.vEgoStopping and - not accelerating) - stay_stopped = (v_ego < CP.vEgoStopping and - (brake_pressed or cruise_standstill)) - stopping_condition = planned_stop or stay_stopped - - starting_condition = (v_target_1sec > CP.vEgoStarting and - accelerating and +def long_control_state_trans(CP, active, long_control_state, v_ego, + should_stop, brake_pressed, cruise_standstill): + stopping_condition = should_stop + starting_condition = (not should_stop and not cruise_standstill and not brake_pressed) started_condition = v_ego > CP.vEgoStarting @@ -30,10 +22,14 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, long_control_state = LongCtrlState.off else: - if long_control_state in (LongCtrlState.off, LongCtrlState.pid): - long_control_state = LongCtrlState.pid - if stopping_condition: + if long_control_state == LongCtrlState.off: + if not starting_condition: long_control_state = LongCtrlState.stopping + else: + if starting_condition and CP.startingState: + long_control_state = LongCtrlState.starting + else: + long_control_state = LongCtrlState.pid elif long_control_state == LongCtrlState.stopping: if starting_condition and CP.startingState: @@ -41,92 +37,52 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target, elif starting_condition: long_control_state = LongCtrlState.pid - elif long_control_state == LongCtrlState.starting: + elif long_control_state in [LongCtrlState.starting, LongCtrlState.pid]: if stopping_condition: long_control_state = LongCtrlState.stopping elif started_condition: long_control_state = LongCtrlState.pid - return long_control_state - class LongControl: def __init__(self, CP): self.CP = CP - self.long_control_state = LongCtrlState.off # initialized to off + self.long_control_state = LongCtrlState.off self.pid = PIDController((CP.longitudinalTuning.kpBP, CP.longitudinalTuning.kpV), (CP.longitudinalTuning.kiBP, CP.longitudinalTuning.kiV), k_f=CP.longitudinalTuning.kf, rate=1 / DT_CTRL) - self.v_pid = 0.0 self.last_output_accel = 0.0 - def reset(self, v_pid): - """Reset PID controller and change setpoint""" + def reset(self): self.pid.reset() - self.v_pid = v_pid - def update(self, active, CS, long_plan, accel_limits, t_since_plan): + def update(self, active, CS, a_target, should_stop, accel_limits): """Update longitudinal control. This updates the state machine and runs a PID loop""" - # Interp control trajectory - speeds = long_plan.speeds - if len(speeds) == CONTROL_N: - v_target_now = interp(t_since_plan, CONTROL_N_T_IDX, speeds) - a_target_now = interp(t_since_plan, CONTROL_N_T_IDX, long_plan.accels) - - v_target_lower = interp(self.CP.longitudinalActuatorDelayLowerBound + t_since_plan, CONTROL_N_T_IDX, speeds) - a_target_lower = 2 * (v_target_lower - v_target_now) / self.CP.longitudinalActuatorDelayLowerBound - a_target_now - - v_target_upper = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan, CONTROL_N_T_IDX, speeds) - a_target_upper = 2 * (v_target_upper - v_target_now) / self.CP.longitudinalActuatorDelayUpperBound - a_target_now - - v_target = min(v_target_lower, v_target_upper) - a_target = min(a_target_lower, a_target_upper) - - v_target_1sec = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan + 1.0, CONTROL_N_T_IDX, speeds) - else: - v_target = 0.0 - v_target_now = 0.0 - v_target_1sec = 0.0 - a_target = 0.0 - self.pid.neg_limit = accel_limits[0] self.pid.pos_limit = accel_limits[1] - output_accel = self.last_output_accel self.long_control_state = long_control_state_trans(self.CP, active, self.long_control_state, CS.vEgo, - v_target, v_target_1sec, CS.brakePressed, + should_stop, CS.brakePressed, CS.cruiseState.standstill) - if self.long_control_state == LongCtrlState.off: - self.reset(CS.vEgo) + self.reset() output_accel = 0. elif self.long_control_state == LongCtrlState.stopping: + output_accel = self.last_output_accel if output_accel > self.CP.stopAccel: output_accel = min(output_accel, 0.0) output_accel -= self.CP.stoppingDecelRate * DT_CTRL - self.reset(CS.vEgo) + self.reset() elif self.long_control_state == LongCtrlState.starting: output_accel = self.CP.startAccel - self.reset(CS.vEgo) + self.reset() - elif self.long_control_state == LongCtrlState.pid: - self.v_pid = v_target_now - - # Toyota starts braking more when it thinks you want to stop - # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration - # TODO too complex, needs to be simplified and tested on toyotas - prevent_overshoot = not self.CP.stoppingControl and CS.vEgo < 1.5 and v_target_1sec < 0.7 and v_target_1sec < self.v_pid - deadzone = interp(CS.vEgo, self.CP.longitudinalTuning.deadzoneBP, self.CP.longitudinalTuning.deadzoneV) - freeze_integrator = prevent_overshoot - - error = self.v_pid - CS.vEgo - error_deadzone = apply_deadzone(error, deadzone) - output_accel = self.pid.update(error_deadzone, speed=CS.vEgo, - feedforward=a_target, - freeze_integrator=freeze_integrator) + else: # LongCtrlState.pid + error = a_target - CS.aEgo + output_accel = self.pid.update(error, speed=CS.vEgo, + feedforward=a_target) self.last_output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) - return self.last_output_accel diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript index 592c1c2c2da8ec0..2a155717c014704 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript @@ -1,4 +1,4 @@ -Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'opendbc_python') +Import('env', 'envCython', 'arch', 'msgq_python', 'common_python', 'opendbc_python', 'pandad_python', 'np_version') gen = "c_generated_code" @@ -66,13 +66,15 @@ lenv.Clean(generated_files, Dir(gen)) generated_long = lenv.Command(generated_files, source_list, f"cd {Dir('.').abspath} && python3 long_mpc.py") -lenv.Depends(generated_long, [msgq_python, common_python, opendbc_python]) +lenv.Depends(generated_long, [msgq_python, common_python, opendbc_python, pandad_python]) lenv["CFLAGS"].append("-DACADOS_WITH_QPOASES") lenv["CXXFLAGS"].append("-DACADOS_WITH_QPOASES") lenv["CCFLAGS"].append("-Wno-unused") if arch != "Darwin": lenv["LINKFLAGS"].append("-Wl,--disable-new-dtags") +else: + lenv["LINKFLAGS"].append("-Wl,-install_name,@loader_path/libacados_ocp_solver_long.dylib") lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_long", build_files, LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e']) @@ -94,3 +96,4 @@ lenv2.Command(libacados_ocp_solver_c, f' {acados_ocp_solver_pyx.get_labspath()}') lib_cython = lenv2.Program(f'{gen}/acados_ocp_solver_pyx.so', [libacados_ocp_solver_c]) lenv2.Depends(lib_cython, lib_solver) +lenv2.Depends(libacados_ocp_solver_c, np_version) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index bad37add63aab3e..65e1421d7792472 100755 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -3,12 +3,12 @@ import time import numpy as np from cereal import log +from opendbc.car.interfaces import ACCEL_MIN from openpilot.common.numpy_fast import clip from openpilot.common.realtime import DT_MDL from openpilot.common.swaglog import cloudlog # WARNING: imports outside of constants will not trigger a rebuild from openpilot.selfdrive.modeld.constants import index_function -from openpilot.selfdrive.car.interfaces import ACCEL_MIN from openpilot.selfdrive.controls.radard import _LEAD_ACCEL_TAU if __name__ == '__main__': # generating code @@ -347,7 +347,8 @@ def update(self, radarstate, v_cruise, x, v, a, j, personality=log.LongitudinalP lead_1_obstacle = lead_xv_1[:,0] + get_stopped_equivalence_factor(lead_xv_1[:,1]) self.params[:,0] = ACCEL_MIN - self.params[:,1] = self.max_a + # negative accel constraint causes problems because negative speed is not allowed + self.params[:,1] = max(0.0, self.max_a) # Update in ACC mode or ACC/e2e blend if self.mode == 'acc': @@ -356,6 +357,7 @@ def update(self, radarstate, v_cruise, x, v, a, j, personality=log.LongitudinalP # Fake an obstacle for cruise, this ensures smooth acceleration to set speed # when the leads are no factor. v_lower = v_ego + (T_IDXS * self.cruise_min_a * 1.05) + # TODO does this make sense when max_a is negative? v_upper = v_ego + (T_IDXS * self.max_a * 1.05) v_cruise_clipped = np.clip(v_cruise * np.ones(N+1), v_lower, diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index ff5f901b52433f6..f1637d960cf58ec 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -4,21 +4,25 @@ from openpilot.common.numpy_fast import clip, interp import cereal.messaging as messaging +from opendbc.car.interfaces import ACCEL_MIN, ACCEL_MAX from openpilot.common.conversions import Conversions as CV from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.realtime import DT_MDL from openpilot.selfdrive.modeld.constants import ModelConstants -from openpilot.selfdrive.car.interfaces import ACCEL_MIN, ACCEL_MAX from openpilot.selfdrive.controls.lib.longcontrol import LongCtrlState from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import LongitudinalMpc from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import T_IDXS as T_IDXS_MPC -from openpilot.selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX, CONTROL_N, get_speed_error +from openpilot.selfdrive.controls.lib.drive_helpers import CONTROL_N, get_speed_error +from openpilot.selfdrive.car.cruise import V_CRUISE_MAX, V_CRUISE_UNSET from openpilot.common.swaglog import cloudlog LON_MPC_STEP = 0.2 # first step is 0.2s A_CRUISE_MIN = -1.2 A_CRUISE_MAX_VALS = [1.6, 1.2, 0.8, 0.6] A_CRUISE_MAX_BP = [0., 10.0, 25., 40.] +CONTROL_N_T_IDX = ModelConstants.T_IDXS[:CONTROL_N] +ALLOW_THROTTLE_THRESHOLD = 0.5 +MIN_ALLOW_THROTTLE_SPEED = 2.5 # Lookup table for turns _A_TOTAL_MAX_V = [1.7, 3.2] @@ -28,13 +32,15 @@ def get_max_accel(v_ego): return interp(v_ego, A_CRUISE_MAX_BP, A_CRUISE_MAX_VALS) +def get_coast_accel(pitch): + return np.sin(pitch) * -5.65 - 0.3 # fitted from data using xx/projects/allow_throttle/compute_coast_accel.py + def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): """ This function returns a limited long acceleration allowed, depending on the existing lateral acceleration this should avoid accelerating when losing the target in turns """ - # FIXME: This function to calculate lateral accel is incorrect and should use the VehicleModel # The lookup table for turns should also be updated if we do this a_total_max = interp(v_ego, _A_TOTAL_MAX_BP, _A_TOTAL_MAX_V) @@ -44,12 +50,34 @@ def limit_accel_in_turns(v_ego, angle_steers, a_target, CP): return [a_target[0], min(a_target[1], a_x_allowed)] +def get_accel_from_plan(CP, speeds, accels): + if len(speeds) == CONTROL_N: + v_target_now = interp(DT_MDL, CONTROL_N_T_IDX, speeds) + a_target_now = interp(DT_MDL, CONTROL_N_T_IDX, accels) + + v_target = interp(CP.longitudinalActuatorDelay + DT_MDL, CONTROL_N_T_IDX, speeds) + if v_target != v_target_now: + a_target = 2 * (v_target - v_target_now) / CP.longitudinalActuatorDelay - a_target_now + else: + a_target = a_target_now + + v_target_1sec = interp(CP.longitudinalActuatorDelay + DT_MDL + 1.0, CONTROL_N_T_IDX, speeds) + else: + v_target = 0.0 + v_target_1sec = 0.0 + a_target = 0.0 + should_stop = (v_target < CP.vEgoStopping and + v_target_1sec < CP.vEgoStopping) + return a_target, should_stop + + class LongitudinalPlanner: def __init__(self, CP, init_v=0.0, init_a=0.0, dt=DT_MDL): self.CP = CP self.mpc = LongitudinalMpc(dt=dt) self.fcw = False self.dt = dt + self.allow_throttle = True self.a_desired = init_a self.v_desired_filter = FirstOrderFilter(init_v, 2.0, self.dt) @@ -63,8 +91,8 @@ def __init__(self, CP, init_v=0.0, init_a=0.0, dt=DT_MDL): @staticmethod def parse_model(model_msg, model_error): if (len(model_msg.position.x) == ModelConstants.IDX_N and - len(model_msg.velocity.x) == ModelConstants.IDX_N and - len(model_msg.acceleration.x) == ModelConstants.IDX_N): + len(model_msg.velocity.x) == ModelConstants.IDX_N and + len(model_msg.acceleration.x) == ModelConstants.IDX_N): x = np.interp(T_IDXS_MPC, ModelConstants.T_IDXS, model_msg.position.x) - model_error * T_IDXS_MPC v = np.interp(T_IDXS_MPC, ModelConstants.T_IDXS, model_msg.velocity.x) - model_error a = np.interp(T_IDXS_MPC, ModelConstants.T_IDXS, model_msg.acceleration.x) @@ -74,27 +102,40 @@ def parse_model(model_msg, model_error): v = np.zeros(len(T_IDXS_MPC)) a = np.zeros(len(T_IDXS_MPC)) j = np.zeros(len(T_IDXS_MPC)) - return x, v, a, j + if len(model_msg.meta.disengagePredictions.gasPressProbs) > 1: + throttle_prob = model_msg.meta.disengagePredictions.gasPressProbs[1] + else: + throttle_prob = 1.0 + return x, v, a, j, throttle_prob def update(self, sm): - self.mpc.mode = 'blended' if sm['controlsState'].experimentalMode else 'acc' + self.mpc.mode = 'blended' if sm['selfdriveState'].experimentalMode else 'acc' + + if len(sm['carControl'].orientationNED) == 3: + accel_coast = get_coast_accel(sm['carControl'].orientationNED[1]) + else: + accel_coast = ACCEL_MAX v_ego = sm['carState'].vEgo - v_cruise_kph = min(sm['controlsState'].vCruise, V_CRUISE_MAX) + v_cruise_kph = min(sm['carState'].vCruise, V_CRUISE_MAX) v_cruise = v_cruise_kph * CV.KPH_TO_MS + v_cruise_initialized = sm['carState'].vCruise != V_CRUISE_UNSET long_control_off = sm['controlsState'].longControlState == LongCtrlState.off force_slow_decel = sm['controlsState'].forceDecel # Reset current state when not engaged, or user is controlling the speed - reset_state = long_control_off if self.CP.openpilotLongitudinalControl else not sm['controlsState'].enabled + reset_state = long_control_off if self.CP.openpilotLongitudinalControl else not sm['selfdriveState'].enabled + # PCM cruise speed may be updated a few cycles later, check if initialized + reset_state = reset_state or not v_cruise_initialized # No change cost when user is controlling the speed, or when standstill prev_accel_constraint = not (reset_state or sm['carState'].standstill) if self.mpc.mode == 'acc': accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)] - accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP) + steer_angle_without_offset = sm['carState'].steeringAngleDeg - sm['liveParameters'].angleOffsetDeg + accel_limits_turns = limit_accel_in_turns(v_ego, steer_angle_without_offset, accel_limits, self.CP) else: accel_limits = [ACCEL_MIN, ACCEL_MAX] accel_limits_turns = [ACCEL_MIN, ACCEL_MAX] @@ -108,6 +149,14 @@ def update(self, sm): self.v_desired_filter.x = max(0.0, self.v_desired_filter.update(v_ego)) # Compute model v_ego error self.v_model_error = get_speed_error(sm['modelV2'], v_ego) + x, v, a, j, throttle_prob = self.parse_model(sm['modelV2'], self.v_model_error) + # Don't clip at low speeds since throttle_prob doesn't account for creep + self.allow_throttle = throttle_prob > ALLOW_THROTTLE_THRESHOLD or v_ego <= MIN_ALLOW_THROTTLE_SPEED + + if not self.allow_throttle: + clipped_accel_coast = max(accel_coast, accel_limits_turns[0]) + clipped_accel_coast_interp = interp(v_ego, [MIN_ALLOW_THROTTLE_SPEED, MIN_ALLOW_THROTTLE_SPEED*2], [accel_limits_turns[1], clipped_accel_coast]) + accel_limits_turns[1] = min(accel_limits_turns[1], clipped_accel_coast_interp) if force_slow_decel: v_cruise = 0.0 @@ -115,17 +164,14 @@ def update(self, sm): accel_limits_turns[0] = min(accel_limits_turns[0], self.a_desired + 0.05) accel_limits_turns[1] = max(accel_limits_turns[1], self.a_desired - 0.05) - self.mpc.set_weights(prev_accel_constraint, personality=sm['controlsState'].personality) + self.mpc.set_weights(prev_accel_constraint, personality=sm['selfdriveState'].personality) self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1]) self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired) - x, v, a, j = self.parse_model(sm['modelV2'], self.v_model_error) - self.mpc.update(sm['radarState'], v_cruise, x, v, a, j, personality=sm['controlsState'].personality) + self.mpc.update(sm['radarState'], v_cruise, x, v, a, j, personality=sm['selfdriveState'].personality) - self.v_desired_trajectory_full = np.interp(ModelConstants.T_IDXS, T_IDXS_MPC, self.mpc.v_solution) - self.a_desired_trajectory_full = np.interp(ModelConstants.T_IDXS, T_IDXS_MPC, self.mpc.a_solution) - self.v_desired_trajectory = self.v_desired_trajectory_full[:CONTROL_N] - self.a_desired_trajectory = self.a_desired_trajectory_full[:CONTROL_N] - self.j_desired_trajectory = np.interp(ModelConstants.T_IDXS[:CONTROL_N], T_IDXS_MPC[:-1], self.mpc.j_solution) + self.v_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.v_solution) + self.a_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC, self.mpc.a_solution) + self.j_desired_trajectory = np.interp(CONTROL_N_T_IDX, T_IDXS_MPC[:-1], self.mpc.j_solution) # TODO counter is only needed because radar is glitchy, remove once radar is gone self.fcw = self.mpc.crash_cnt > 2 and not sm['carState'].standstill @@ -134,17 +180,18 @@ def update(self, sm): # Interpolate 0.05 seconds and save as starting point for next iteration a_prev = self.a_desired - self.a_desired = float(interp(self.dt, ModelConstants.T_IDXS[:CONTROL_N], self.a_desired_trajectory)) + self.a_desired = float(interp(self.dt, CONTROL_N_T_IDX, 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') - plan_send.valid = sm.all_checks(service_list=['carState', 'controlsState']) + plan_send.valid = sm.all_checks(service_list=['carState', 'controlsState', 'selfdriveState']) longitudinalPlan = plan_send.longitudinalPlan longitudinalPlan.modelMonoTime = sm.logMonoTime['modelV2'] longitudinalPlan.processingDelay = (plan_send.logMonoTime / 1e9) - sm.logMonoTime['modelV2'] + longitudinalPlan.solverExecutionTime = self.mpc.solve_time longitudinalPlan.speeds = self.v_desired_trajectory.tolist() longitudinalPlan.accels = self.a_desired_trajectory.tolist() @@ -154,6 +201,10 @@ def publish(self, sm, pm): longitudinalPlan.longitudinalPlanSource = self.mpc.source longitudinalPlan.fcw = self.fcw - longitudinalPlan.solverExecutionTime = self.mpc.solve_time + a_target, should_stop = get_accel_from_plan(self.CP, longitudinalPlan.speeds, longitudinalPlan.accels) + longitudinalPlan.aTarget = a_target + longitudinalPlan.shouldStop = should_stop + longitudinalPlan.allowBrake = True + longitudinalPlan.allowThrottle = self.allow_throttle pm.send('longitudinalPlan', plan_send) diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py deleted file mode 100644 index 29c4d8bd469c072..000000000000000 --- a/selfdrive/controls/lib/pid.py +++ /dev/null @@ -1,75 +0,0 @@ -import numpy as np -from numbers import Number - -from openpilot.common.numpy_fast import clip, interp - - -class PIDController: - def __init__(self, k_p, k_i, k_f=0., k_d=0., pos_limit=1e308, neg_limit=-1e308, rate=100): - self._k_p = k_p - self._k_i = k_i - self._k_d = k_d - self.k_f = k_f # feedforward gain - if isinstance(self._k_p, Number): - self._k_p = [[0], [self._k_p]] - if isinstance(self._k_i, Number): - self._k_i = [[0], [self._k_i]] - if isinstance(self._k_d, Number): - self._k_d = [[0], [self._k_d]] - - self.pos_limit = pos_limit - self.neg_limit = neg_limit - - self.i_unwind_rate = 0.3 / rate - self.i_rate = 1.0 / rate - self.speed = 0.0 - - self.reset() - - @property - def k_p(self): - return interp(self.speed, self._k_p[0], self._k_p[1]) - - @property - def k_i(self): - return interp(self.speed, self._k_i[0], self._k_i[1]) - - @property - def k_d(self): - return interp(self.speed, self._k_d[0], self._k_d[1]) - - @property - def error_integral(self): - return self.i/self.k_i - - def reset(self): - self.p = 0.0 - self.i = 0.0 - self.d = 0.0 - self.f = 0.0 - self.control = 0 - - def update(self, error, error_rate=0.0, speed=0.0, override=False, feedforward=0., freeze_integrator=False): - self.speed = speed - - self.p = float(error) * self.k_p - self.f = feedforward * self.k_f - self.d = error_rate * self.k_d - - if override: - self.i -= self.i_unwind_rate * float(np.sign(self.i)) - else: - i = self.i + error * self.k_i * self.i_rate - control = self.p + i + self.d + self.f - - # Update when changing i will move the control away from the limits - # or when i will move towards the sign of the error - if ((error >= 0 and (control <= self.pos_limit or i < 0.0)) or - (error <= 0 and (control >= self.neg_limit or i > 0.0))) and \ - not freeze_integrator: - self.i = i - - control = self.p + self.i + self.d + self.f - - self.control = clip(control, self.neg_limit, self.pos_limit) - return self.control diff --git a/selfdrive/controls/lib/tests/test_alertmanager.py b/selfdrive/controls/lib/tests/test_alertmanager.py deleted file mode 100644 index 8b9c18a9d48206a..000000000000000 --- a/selfdrive/controls/lib/tests/test_alertmanager.py +++ /dev/null @@ -1,39 +0,0 @@ -import random - -from openpilot.selfdrive.controls.lib.events import Alert, EVENTS -from openpilot.selfdrive.controls.lib.alertmanager import AlertManager - - -class TestAlertManager: - - def test_duration(self): - """ - Enforce that an alert lasts for max(alert duration, duration the alert is added) - """ - for duration in range(1, 100): - alert = None - while not isinstance(alert, Alert): - event = random.choice([e for e in EVENTS.values() if len(e)]) - alert = random.choice(list(event.values())) - - alert.duration = duration - - # check two cases: - # - alert is added to AM for <= the alert's duration - # - alert is added to AM for > alert's duration - for greater in (True, False): - if greater: - add_duration = duration + random.randint(1, 10) - else: - add_duration = random.randint(1, duration) - show_duration = max(duration, add_duration) - - AM = AlertManager() - for frame in range(duration+10): - if frame < add_duration: - AM.add_many(frame, [alert, ]) - current_alert = AM.process_alerts(frame, {}) - - shown = current_alert is not None - should_show = frame <= show_duration - assert shown == should_show, f"{frame=} {add_duration=} {duration=}" diff --git a/selfdrive/controls/lib/tests/test_latcontrol.py b/selfdrive/controls/lib/tests/test_latcontrol.py index 81411edec1c3d6e..ba4bd0faeceb4a5 100644 --- a/selfdrive/controls/lib/tests/test_latcontrol.py +++ b/selfdrive/controls/lib/tests/test_latcontrol.py @@ -1,27 +1,28 @@ from parameterized import parameterized from cereal import car, log -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.nissan.values import CAR as NISSAN +from opendbc.car.car_helpers import interfaces +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.nissan.values import CAR as NISSAN from openpilot.selfdrive.controls.lib.latcontrol_pid import LatControlPID from openpilot.selfdrive.controls.lib.latcontrol_torque import LatControlTorque from openpilot.selfdrive.controls.lib.latcontrol_angle import LatControlAngle from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel -from openpilot.common.mock.generators import generate_liveLocationKalman +from openpilot.selfdrive.locationd.helpers import Pose +from openpilot.common.mock.generators import generate_livePose class TestLatControl: @parameterized.expand([(HONDA.HONDA_CIVIC, LatControlPID), (TOYOTA.TOYOTA_RAV4, LatControlTorque), (NISSAN.NISSAN_LEAF, LatControlAngle)]) def test_saturation(self, car_name, controller): - CarInterface, CarController, CarState = interfaces[car_name] + CarInterface, CarController, CarState, RadarInterface = interfaces[car_name] CP = CarInterface.get_non_essential_params(car_name) CI = CarInterface(CP, CarController, CarState) VM = VehicleModel(CP) - controller = controller(CP, CI) + controller = controller(CP.as_reader(), CI) CS = car.CarState.new_message() CS.vEgo = 30 @@ -29,8 +30,10 @@ def test_saturation(self, car_name, controller): params = log.LiveParametersData.new_message() - llk = generate_liveLocationKalman() + lp = generate_livePose() + pose = Pose.from_live_pose(lp.livePose) + for _ in range(1000): - _, _, lac_log = controller.update(True, CS, VM, params, False, 1, llk) + _, _, lac_log = controller.update(True, CS, VM, params, False, 1, pose) assert lac_log.saturated diff --git a/selfdrive/controls/lib/tests/test_vehicle_model.py b/selfdrive/controls/lib/tests/test_vehicle_model.py index 4d0e41805d09333..d15519a8667d4ef 100644 --- a/selfdrive/controls/lib/tests/test_vehicle_model.py +++ b/selfdrive/controls/lib/tests/test_vehicle_model.py @@ -2,10 +2,9 @@ import math import numpy as np -from control import StateSpace -from openpilot.selfdrive.car.honda.interface import CarInterface -from openpilot.selfdrive.car.honda.values import CAR +from opendbc.car.honda.interface import CarInterface +from opendbc.car.honda.values import CAR from openpilot.selfdrive.controls.lib.vehicle_model import VehicleModel, dyn_ss_sol, create_dyn_state_matrices @@ -47,8 +46,12 @@ def test_syn_ss_sol_simulate(self): A, B = create_dyn_state_matrices(u, self.VM) # Convert to discrete time system - ss = StateSpace(A, B, np.eye(2), np.zeros((2, 2))) - ss = ss.sample(0.01) + dt = 0.01 + top = np.hstack((A, B)) + full = np.vstack((top, np.zeros_like(top))) * dt + Md = sum([np.linalg.matrix_power(full, k) / math.factorial(k) for k in range(25)]) + Ad = Md[:A.shape[0], :A.shape[1]] + Bd = Md[:A.shape[0], A.shape[1]:] for sa in np.linspace(math.radians(-20), math.radians(20), num=11): inp = np.array([[sa], [roll]]) @@ -56,7 +59,7 @@ def test_syn_ss_sol_simulate(self): # Simulate for 1 second x1 = np.zeros((2, 1)) for _ in range(100): - x1 = ss.A @ x1 + ss.B @ inp + x1 = Ad @ x1 + Bd @ inp # Compute steady state solution directly x2 = dyn_ss_sol(sa, u, roll, self.VM) diff --git a/selfdrive/controls/plannerd.py b/selfdrive/controls/plannerd.py index eeeeda050ebc51e..bcfc4d0c14809b5 100755 --- a/selfdrive/controls/plannerd.py +++ b/selfdrive/controls/plannerd.py @@ -3,32 +3,23 @@ from openpilot.common.params import Params from openpilot.common.realtime import Priority, config_realtime_process from openpilot.common.swaglog import cloudlog +from openpilot.selfdrive.controls.lib.ldw import LaneDepartureWarning from openpilot.selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner import cereal.messaging as messaging -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 = 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) - -def plannerd_thread(): + +def main(): config_realtime_process(5, Priority.CTRL_LOW) cloudlog.info("plannerd is waiting for CarParams") params = Params() - with car.CarParams.from_bytes(params.get("CarParams", block=True)) as msg: - CP = msg + CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) cloudlog.info("plannerd got CarParams: %s", CP.carName) + ldw = LaneDepartureWarning() longitudinal_planner = LongitudinalPlanner(CP) - pm = messaging.PubMaster(['longitudinalPlan', 'uiPlan']) - sm = messaging.SubMaster(['carControl', 'carState', 'controlsState', 'radarState', 'modelV2'], + pm = messaging.PubMaster(['longitudinalPlan', 'driverAssistance']) + sm = messaging.SubMaster(['carControl', 'carState', 'controlsState', 'liveParameters', 'radarState', 'modelV2', 'selfdriveState'], poll='modelV2', ignore_avg_freq=['radarState']) while True: @@ -36,10 +27,13 @@ def plannerd_thread(): if sm.updated['modelV2']: longitudinal_planner.update(sm) longitudinal_planner.publish(sm, pm) - publish_ui_plan(sm, pm, longitudinal_planner) -def main(): - plannerd_thread() + ldw.update(sm.frame, sm['modelV2'], sm['carState'], sm['carControl']) + msg = messaging.new_message('driverAssistance') + msg.valid = sm.all_checks(['carState', 'carControl', 'modelV2', 'liveParameters']) + msg.driverAssistance.leftLaneDeparture = ldw.left + msg.driverAssistance.rightLaneDeparture = ldw.right + pm.send('driverAssistance', msg) if __name__ == "__main__": diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 7420f666f7a3c2a..fb69fb736fdedc5 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 -import importlib import math from collections import deque from typing import Any @@ -8,9 +7,8 @@ from cereal import messaging, log, car from openpilot.common.numpy_fast import interp from openpilot.common.params import Params -from openpilot.common.realtime import DT_CTRL, Ratekeeper, Priority, config_realtime_process +from openpilot.common.realtime import DT_MDL, Priority, config_realtime_process from openpilot.common.swaglog import cloudlog - from openpilot.common.simple_kalman import KF1D @@ -37,7 +35,7 @@ def __init__(self, dt: float): #Q = np.matrix([[10., 0.0], [0.0, 100.]]) #R = 1e3 #K = np.matrix([[ 0.05705578], [ 0.03073241]]) - dts = [dt * 0.01 for dt in range(1, 21)] + dts = [i * 0.01 for i in range(1, 21)] K0 = [0.12287673, 0.14556536, 0.16522756, 0.18281627, 0.1988689, 0.21372394, 0.22761098, 0.24069424, 0.253096, 0.26491023, 0.27621103, 0.28705801, 0.29750003, 0.30757767, 0.31732515, 0.32677158, 0.33594201, 0.34485814, @@ -82,10 +80,6 @@ def update(self, d_rel: float, y_rel: float, v_rel: float, v_lead: float, measur self.cnt += 1 - def get_key_for_cluster(self): - # Weigh y higher since radar is inaccurate in this dimension - return [self.dRel, self.yRel*2, self.vRel] - def reset_a_lead(self, aLeadK: float, aLeadTau: float): self.kf = KF1D([[self.vLead], [aLeadK]], self.K_A, self.K_C, self.K_K) self.aLeadK = aLeadK @@ -193,14 +187,14 @@ def get_lead(v_ego: float, ready: bool, tracks: dict[int, Track], lead_msg: capn class RadarD: - def __init__(self, radar_ts: float, delay: int = 0): + def __init__(self, delay: float = 0.0): self.current_time = 0.0 self.tracks: dict[int, Track] = {} - self.kalman_params = KalmanParams(radar_ts) + self.kalman_params = KalmanParams(DT_MDL) self.v_ego = 0.0 - self.v_ego_hist = deque([0.0], maxlen=delay+1) + self.v_ego_hist = deque([0.0], maxlen=int(round(delay / DT_MDL))+1) self.last_v_ego_frame = -1 self.radar_state: capnp._DynamicStructBuilder | None = None @@ -208,23 +202,17 @@ def __init__(self, radar_ts: float, delay: int = 0): self.ready = False - def update(self, sm: messaging.SubMaster, rr): + def update(self, sm: messaging.SubMaster, rr: car.RadarData): self.ready = sm.seen['modelV2'] self.current_time = 1e-9*max(sm.logMonoTime.values()) - radar_points = [] - radar_errors = [] - if rr is not None: - radar_points = rr.points - radar_errors = rr.errors - if sm.recv_frame['carState'] != self.last_v_ego_frame: self.v_ego = sm['carState'].vEgo self.v_ego_hist.append(self.v_ego) self.last_v_ego_frame = sm.recv_frame['carState'] ar_pts = {} - for pt in radar_points: + for pt in rr.points: ar_pts[pt.trackId] = [pt.dRel, pt.yRel, pt.vRel, pt.measured] # *** remove missing points from meta data *** @@ -245,14 +233,14 @@ def update(self, sm: messaging.SubMaster, rr): self.tracks[ids].update(rpt[0], rpt[1], rpt[2], v_lead, rpt[3]) # *** publish radarState *** - self.radar_state_valid = sm.all_checks() and len(radar_errors) == 0 + self.radar_state_valid = sm.all_checks() and len(rr.errors) == 0 self.radar_state = log.RadarState.new_message() self.radar_state.mdMonoTime = sm.logMonoTime['modelV2'] - self.radar_state.radarErrors = list(radar_errors) + self.radar_state.radarErrors = list(rr.errors) self.radar_state.carStateMonoTime = sm.logMonoTime['carState'] - if len(sm['modelV2'].temporalPose.trans): - model_v_ego = sm['modelV2'].temporalPose.trans[0] + if len(sm['modelV2'].velocity.x): + model_v_ego = sm['modelV2'].velocity.x[0] else: model_v_ego = self.v_ego leads_v3 = sm['modelV2'].leadsV3 @@ -260,63 +248,35 @@ def update(self, sm: messaging.SubMaster, rr): self.radar_state.leadOne = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[0], model_v_ego, low_speed_override=True) self.radar_state.leadTwo = get_lead(self.v_ego, self.ready, self.tracks, leads_v3[1], model_v_ego, low_speed_override=False) - def publish(self, pm: messaging.PubMaster, lag_ms: float): + def publish(self, pm: messaging.PubMaster): assert self.radar_state is not None radar_msg = messaging.new_message("radarState") radar_msg.valid = self.radar_state_valid radar_msg.radarState = self.radar_state - radar_msg.radarState.cumLagMs = lag_ms pm.send("radarState", radar_msg) - # 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, - "dRel": float(self.tracks[tid].dRel), - "yRel": float(self.tracks[tid].yRel), - "vRel": float(self.tracks[tid].vRel), - } - pm.send('liveTracks', tracks_msg) - # fuses camera and radar data for best lead detection -def main(): +def main() -> None: config_realtime_process(5, Priority.CTRL_LOW) # wait for stats about the car to come in from controls cloudlog.info("radard is waiting for CarParams") - with car.CarParams.from_bytes(Params().get("CarParams", block=True)) as msg: - CP = msg + CP = messaging.log_from_bytes(Params().get("CarParams", block=True), car.CarParams) cloudlog.info("radard got CarParams") - # import the radar from the fingerprint - cloudlog.info("radard is importing %s", CP.carName) - RadarInterface = importlib.import_module(f'selfdrive.car.{CP.carName}.radar_interface').RadarInterface - # *** setup messaging - can_sock = messaging.sub_sock('can') - sm = messaging.SubMaster(['modelV2', 'carState'], frequency=int(1./DT_CTRL)) - pm = messaging.PubMaster(['radarState', 'liveTracks']) - - RI = RadarInterface(CP) + sm = messaging.SubMaster(['modelV2', 'carState', 'liveTracks'], poll='modelV2') + pm = messaging.PubMaster(['radarState']) - rk = Ratekeeper(1.0 / CP.radarTimeStep, print_delay_threshold=None) - RD = RadarD(CP.radarTimeStep, RI.delay) + RD = RadarD(CP.radarDelay) 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 - - RD.update(sm, rr) - RD.publish(pm, -rk.remaining*1000.0) + sm.update() - rk.monitor_time() + RD.update(sm, sm['liveTracks']) + RD.publish(pm) if __name__ == "__main__": diff --git a/selfdrive/controls/tests/test_leads.py b/selfdrive/controls/tests/test_leads.py index f1f4449afdc4b96..89582d1e647f8b0 100644 --- a/selfdrive/controls/tests/test_leads.py +++ b/selfdrive/controls/tests/test_leads.py @@ -1,7 +1,7 @@ import cereal.messaging as messaging +from opendbc.car.toyota.values import CAR as TOYOTA from openpilot.selfdrive.test.process_replay import replay_process_with_name -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA class TestLeads: @@ -11,19 +11,21 @@ def test_radar_fault(self): def single_iter_pkg(): # single iter package, with meaningless cans and empty carState/modelV2 msgs = [] - for _ in range(5): + for _ in range(500): can = messaging.new_message("can", 1) cs = messaging.new_message("carState") + cp = messaging.new_message("carParams") msgs.append(can.as_reader()) msgs.append(cs.as_reader()) + msgs.append(cp.as_reader()) model = messaging.new_message("modelV2") msgs.append(model.as_reader()) return msgs msgs = [m for _ in range(3) for m in single_iter_pkg()] - out = replay_process_with_name("radard", msgs, fingerprint=TOYOTA.TOYOTA_COROLLA_TSS2) - states = [m for m in out if m.which() == "radarState"] - failures = [not state.valid and len(state.radarState.radarErrors) for state in states] + out = replay_process_with_name("card", msgs, fingerprint=TOYOTA.TOYOTA_COROLLA_TSS2) + states = [m for m in out if m.which() == "liveTracks"] + failures = [not state.valid and len(state.liveTracks.errors) for state in states] assert len(states) == 0 or all(failures) diff --git a/selfdrive/controls/tests/test_longcontrol.py b/selfdrive/controls/tests/test_longcontrol.py new file mode 100644 index 000000000000000..ab50810d894f61d --- /dev/null +++ b/selfdrive/controls/tests/test_longcontrol.py @@ -0,0 +1,56 @@ +from cereal import car +from openpilot.selfdrive.controls.lib.longcontrol import LongCtrlState, long_control_state_trans + + + + +class TestLongControlStateTransition: + + def test_stay_stopped(self): + CP = car.CarParams.new_message() + active = True + current_state = LongCtrlState.stopping + next_state = long_control_state_trans(CP, active, current_state, v_ego=0.1, + should_stop=True, brake_pressed=False, cruise_standstill=False) + assert next_state == LongCtrlState.stopping + next_state = long_control_state_trans(CP, active, current_state, v_ego=0.1, + should_stop=False, brake_pressed=True, cruise_standstill=False) + assert next_state == LongCtrlState.stopping + next_state = long_control_state_trans(CP, active, current_state, v_ego=0.1, + should_stop=False, brake_pressed=False, cruise_standstill=True) + assert next_state == LongCtrlState.stopping + next_state = long_control_state_trans(CP, active, current_state, v_ego=1.0, + should_stop=False, brake_pressed=False, cruise_standstill=False) + assert next_state == LongCtrlState.pid + active = False + next_state = long_control_state_trans(CP, active, current_state, v_ego=1.0, + should_stop=False, brake_pressed=False, cruise_standstill=False) + assert next_state == LongCtrlState.off + +def test_engage(): + CP = car.CarParams.new_message() + active = True + current_state = LongCtrlState.off + next_state = long_control_state_trans(CP, active, current_state, v_ego=0.1, + should_stop=True, brake_pressed=False, cruise_standstill=False) + assert next_state == LongCtrlState.stopping + next_state = long_control_state_trans(CP, active, current_state, v_ego=0.1, + should_stop=False, brake_pressed=True, cruise_standstill=False) + assert next_state == LongCtrlState.stopping + next_state = long_control_state_trans(CP, active, current_state, v_ego=0.1, + should_stop=False, brake_pressed=False, cruise_standstill=True) + assert next_state == LongCtrlState.stopping + next_state = long_control_state_trans(CP, active, current_state, v_ego=0.1, + should_stop=False, brake_pressed=False, cruise_standstill=False) + assert next_state == LongCtrlState.pid + +def test_starting(): + CP = car.CarParams.new_message(startingState=True, vEgoStarting=0.5) + active = True + current_state = LongCtrlState.starting + next_state = long_control_state_trans(CP, active, current_state, v_ego=0.1, + should_stop=False, brake_pressed=False, cruise_standstill=False) + assert next_state == LongCtrlState.starting + next_state = long_control_state_trans(CP, active, current_state, v_ego=1.0, + should_stop=False, brake_pressed=False, cruise_standstill=False) + assert next_state == LongCtrlState.pid diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py deleted file mode 100644 index 14b0788a3d594c4..000000000000000 --- a/selfdrive/controls/tests/test_startup.py +++ /dev/null @@ -1,121 +0,0 @@ -import os -from parameterized import parameterized - -from cereal import log, car -import cereal.messaging as messaging -from openpilot.common.params import Params -from openpilot.selfdrive.pandad.pandad_api_impl import can_list_to_can_capnp -from openpilot.selfdrive.car.fingerprints import _FINGERPRINTS -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA -from openpilot.selfdrive.controls.lib.events import EVENT_NAME -from openpilot.system.manager.process_config import managed_processes - -EventName = car.CarEvent.EventName -Ecu = car.CarParams.Ecu - -COROLLA_FW_VERSIONS = [ - (Ecu.engine, 0x7e0, None, b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.abs, 0x7b0, None, b'F152602190\x00\x00\x00\x00\x00\x00'), - (Ecu.eps, 0x7a1, None, b'8965B02181\x00\x00\x00\x00\x00\x00'), - (Ecu.fwdRadar, 0x750, 0xf, b'8821F4702100\x00\x00\x00\x00'), - (Ecu.fwdCamera, 0x750, 0x6d, b'8646F0201101\x00\x00\x00\x00'), - (Ecu.dsu, 0x791, None, b'881510201100\x00\x00\x00\x00'), -] -COROLLA_FW_VERSIONS_FUZZY = COROLLA_FW_VERSIONS[:-1] + [(Ecu.dsu, 0x791, None, b'xxxxxx')] -COROLLA_FW_VERSIONS_NO_DSU = COROLLA_FW_VERSIONS[:-1] - -CX5_FW_VERSIONS = [ - (Ecu.engine, 0x7e0, None, b'PYNF-188K2-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'), - (Ecu.eps, 0x730, None, b'KJ01-3210X-G-00\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'), - (Ecu.fwdCamera, 0x706, None, b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.transmission, 0x7e1, None, b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), -] - - -@parameterized.expand([ - # TODO: test EventName.startup for release branches - - # officially supported car - (EventName.startupMaster, TOYOTA.TOYOTA_COROLLA, COROLLA_FW_VERSIONS, "toyota"), - (EventName.startupMaster, TOYOTA.TOYOTA_COROLLA, COROLLA_FW_VERSIONS, "toyota"), - - # dashcamOnly car - (EventName.startupNoControl, MAZDA.MAZDA_CX5, CX5_FW_VERSIONS, "mazda"), - (EventName.startupNoControl, MAZDA.MAZDA_CX5, CX5_FW_VERSIONS, "mazda"), - - # unrecognized car with no fw - (EventName.startupNoFw, None, None, ""), - (EventName.startupNoFw, None, None, ""), - - # unrecognized car - (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1], "toyota"), - (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1], "toyota"), - - # fuzzy match - (EventName.startupMaster, TOYOTA.TOYOTA_COROLLA, COROLLA_FW_VERSIONS_FUZZY, "toyota"), - (EventName.startupMaster, TOYOTA.TOYOTA_COROLLA, COROLLA_FW_VERSIONS_FUZZY, "toyota"), -]) -def test_startup_alert(expected_event, car_model, fw_versions, brand): - controls_sock = messaging.sub_sock("controlsState") - pm = messaging.PubMaster(['can', 'pandaStates']) - - params = Params() - params.put_bool("OpenpilotEnabledToggle", True) - - # Build capnn version of FW array - if fw_versions is not None: - car_fw = [] - cp = car.CarParams.new_message() - for ecu, addr, subaddress, version in fw_versions: - f = car.CarParams.CarFw.new_message() - f.ecu = ecu - f.address = addr - f.fwVersion = version - f.brand = brand - - if subaddress is not None: - f.subAddress = subaddress - - car_fw.append(f) - cp.carVin = "1" * 17 - cp.carFw = car_fw - params.put("CarParamsCache", cp.to_bytes()) - else: - os.environ['SKIP_FW_QUERY'] = '1' - - managed_processes['controlsd'].start() - managed_processes['card'].start() - - assert pm.wait_for_readers_to_update('can', 5) - pm.send('can', can_list_to_can_capnp([[0, 0, b"", 0]])) - - assert pm.wait_for_readers_to_update('pandaStates', 5) - msg = messaging.new_message('pandaStates', 1) - msg.pandaStates[0].pandaType = log.PandaState.PandaType.uno - pm.send('pandaStates', msg) - - # fingerprint - if (car_model is None) or (fw_versions is not None): - finger = {addr: 1 for addr in range(1, 100)} - else: - finger = _FINGERPRINTS[car_model][0] - - msgs = [[addr, 0, b'\x00'*length, 0] for addr, length in finger.items()] - for _ in range(1000): - # card waits for pandad to echo back that it has changed the multiplexing mode - if not params.get_bool("ObdMultiplexingChanged"): - params.put_bool("ObdMultiplexingChanged", True) - - pm.send('can', can_list_to_can_capnp(msgs)) - assert pm.wait_for_readers_to_update('can', 5, dt=0.001), f"step: {_}" - - ctrls = messaging.drain_sock(controls_sock) - if len(ctrls): - event_name = ctrls[0].controlsState.alertType.split("/")[0] - assert EVENT_NAME[expected_event] == event_name, f"expected {EVENT_NAME[expected_event]} for '{car_model}', got {event_name}" - break - else: - raise Exception(f"failed to fingerprint {car_model}") diff --git a/selfdrive/controls/tests/test_state_machine.py b/selfdrive/controls/tests/test_state_machine.py deleted file mode 100644 index b6ec512dc4ab0a3..000000000000000 --- a/selfdrive/controls/tests/test_state_machine.py +++ /dev/null @@ -1,102 +0,0 @@ -from cereal import car, log -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.controls.controlsd import Controls, SOFT_DISABLE_TIME -from openpilot.selfdrive.controls.lib.events import Events, ET, Alert, Priority, AlertSize, AlertStatus, VisualAlert, \ - AudibleAlert, EVENTS -from openpilot.selfdrive.car.mock.values import CAR as MOCK - -State = log.ControlsState.OpenpilotState - -# The event types that maintain the current state -MAINTAIN_STATES = {State.enabled: (None,), State.disabled: (None,), State.softDisabling: (ET.SOFT_DISABLE,), - State.preEnabled: (ET.PRE_ENABLE,), State.overriding: (ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL)} -ALL_STATES = tuple(State.schema.enumerants.values()) -# The event types checked in DISABLED section of state machine -ENABLE_EVENT_TYPES = (ET.ENABLE, ET.PRE_ENABLE, ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL) - - -def make_event(event_types): - event = {} - for ev in event_types: - event[ev] = Alert("", "", AlertStatus.normal, AlertSize.small, Priority.LOW, - VisualAlert.none, AudibleAlert.none, 1.) - EVENTS[0] = event - return 0 - - -class TestStateMachine: - - def setup_method(self): - CarInterface, CarController, CarState = interfaces[MOCK.MOCK] - CP = CarInterface.get_non_essential_params(MOCK.MOCK) - CI = CarInterface(CP, CarController, CarState) - - self.controlsd = Controls(CI=CI) - self.controlsd.events = Events() - self.controlsd.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) - self.CS = car.CarState() - - def test_immediate_disable(self): - for state in ALL_STATES: - for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.IMMEDIATE_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - assert State.disabled == self.controlsd.state - self.controlsd.events.clear() - - def test_user_disable(self): - for state in ALL_STATES: - for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.USER_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - assert State.disabled == self.controlsd.state - self.controlsd.events.clear() - - def test_soft_disable(self): - for state in ALL_STATES: - if state == State.preEnabled: # preEnabled considers NO_ENTRY instead - continue - for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.SOFT_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - assert self.controlsd.state == State.disabled if state == State.disabled else State.softDisabling - self.controlsd.events.clear() - - def test_soft_disable_timer(self): - self.controlsd.state = State.enabled - self.controlsd.events.add(make_event([ET.SOFT_DISABLE])) - self.controlsd.state_transition(self.CS) - for _ in range(int(SOFT_DISABLE_TIME / DT_CTRL)): - assert self.controlsd.state == State.softDisabling - self.controlsd.state_transition(self.CS) - - assert self.controlsd.state == State.disabled - - def test_no_entry(self): - # Make sure noEntry keeps us disabled - for et in ENABLE_EVENT_TYPES: - self.controlsd.events.add(make_event([ET.NO_ENTRY, et])) - self.controlsd.state_transition(self.CS) - assert self.controlsd.state == State.disabled - self.controlsd.events.clear() - - def test_no_entry_pre_enable(self): - # preEnabled with noEntry event - self.controlsd.state = State.preEnabled - self.controlsd.events.add(make_event([ET.NO_ENTRY, ET.PRE_ENABLE])) - self.controlsd.state_transition(self.CS) - assert self.controlsd.state == State.preEnabled - - def test_maintain_states(self): - # Given current state's event type, we should maintain state - for state in ALL_STATES: - for et in MAINTAIN_STATES[state]: - self.controlsd.state = state - self.controlsd.events.add(make_event([et])) - self.controlsd.state_transition(self.CS) - assert self.controlsd.state == state - self.controlsd.events.clear() diff --git a/selfdrive/debug/adb.sh b/selfdrive/debug/adb.sh index 919a82fefc726bc..8fa267fd4d0d417 100755 --- a/selfdrive/debug/adb.sh +++ b/selfdrive/debug/adb.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e PORT=5555 diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py index 220008979d10299..b93e48ba73ee112 100755 --- a/selfdrive/debug/can_printer.py +++ b/selfdrive/debug/can_printer.py @@ -23,12 +23,12 @@ def can_printer(bus, max_msg, addr, ascii_decode): if time.monotonic() - lp > 0.1: dd = chr(27) + "[2J" dd += f"{time.monotonic() - start:5.2f}\n" - for addr in sorted(msgs.keys()): - a = f"\"{msgs[addr][-1].decode('ascii', 'backslashreplace')}\"" if ascii_decode else "" - x = binascii.hexlify(msgs[addr][-1]).decode('ascii') - freq = len(msgs[addr]) / (time.monotonic() - start) - if max_msg is None or addr < max_msg: - dd += "%04X(%4d)(%6d)(%3dHz) %s %s\n" % (addr, addr, len(msgs[addr]), freq, x.ljust(20), a) + for _addr in sorted(msgs.keys()): + a = f"\"{msgs[_addr][-1].decode('ascii', 'backslashreplace')}\"" if ascii_decode else "" + x = binascii.hexlify(msgs[_addr][-1]).decode('ascii') + freq = len(msgs[_addr]) / (time.monotonic() - start) + if max_msg is None or _addr < max_msg: + dd += "%04X(%4d)(%6d)(%3dHz) %s %s\n" % (_addr, _addr, len(msgs[_addr]), freq, x.ljust(20), a) print(dd) lp = time.monotonic() diff --git a/selfdrive/debug/car/disable_ecu.py b/selfdrive/debug/car/disable_ecu.py new file mode 100755 index 000000000000000..185139324d610fa --- /dev/null +++ b/selfdrive/debug/car/disable_ecu.py @@ -0,0 +1,15 @@ +#!/usr/bin/env python3 +import time +import cereal.messaging as messaging +from opendbc.car.disable_ecu import disable_ecu +from openpilot.selfdrive.car.card import can_comm_callbacks + +if __name__ == "__main__": + sendcan = messaging.pub_sock('sendcan') + logcan = messaging.sub_sock('can') + can_callbacks = can_comm_callbacks(logcan, sendcan) + time.sleep(1) + + # honda bosch radar disable + disabled = disable_ecu(*can_callbacks, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03', timeout=0.5, debug=False) + print(f"disabled: {disabled}") diff --git a/selfdrive/debug/car/ecu_addrs.py b/selfdrive/debug/car/ecu_addrs.py new file mode 100755 index 000000000000000..58781222dc4be8e --- /dev/null +++ b/selfdrive/debug/car/ecu_addrs.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python3 +import argparse +import time +import cereal.messaging as messaging +from opendbc.car.ecu_addrs import get_all_ecu_addrs +from openpilot.common.params import Params +from openpilot.selfdrive.car.card import can_comm_callbacks, obd_callback + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Get addresses of all ECUs') + parser.add_argument('--debug', action='store_true') + parser.add_argument('--bus', type=int, default=1) + parser.add_argument('--no-obd', action='store_true') + parser.add_argument('--timeout', type=float, default=1.0) + args = parser.parse_args() + + logcan = messaging.sub_sock('can') + sendcan = messaging.pub_sock('sendcan') + can_callbacks = can_comm_callbacks(logcan, sendcan) + + # Set up params for pandad + params = Params() + params.remove("FirmwareQueryDone") + params.put_bool("IsOnroad", False) + time.sleep(0.2) # thread is 10 Hz + params.put_bool("IsOnroad", True) + + obd_callback(params)(not args.no_obd) + + print("Getting ECU addresses ...") + ecu_addrs = get_all_ecu_addrs(*can_callbacks, args.bus, args.timeout, debug=args.debug) + + print() + print("Found ECUs on rx addresses:") + for addr, subaddr, _ in ecu_addrs: + msg = f" {hex(addr)}" + if subaddr is not None: + msg += f" (sub-address: {hex(subaddr)})" + print(msg) diff --git a/selfdrive/debug/car/fw_versions.py b/selfdrive/debug/car/fw_versions.py new file mode 100755 index 000000000000000..18a287b38e09ed0 --- /dev/null +++ b/selfdrive/debug/car/fw_versions.py @@ -0,0 +1,70 @@ +#!/usr/bin/env python3 +import time +import argparse +import cereal.messaging as messaging +from cereal import car +from opendbc.car.fw_versions import get_fw_versions, match_fw_to_car +from opendbc.car.vin import get_vin +from openpilot.common.params import Params +from openpilot.selfdrive.car.card import can_comm_callbacks, obd_callback +from typing import Any + +Ecu = car.CarParams.Ecu + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Get firmware version of ECUs') + parser.add_argument('--scan', action='store_true') + parser.add_argument('--debug', action='store_true') + parser.add_argument('--brand', help='Only query addresses/with requests for this brand') + args = parser.parse_args() + + logcan = messaging.sub_sock('can') + pandaStates_sock = messaging.sub_sock('pandaStates') + sendcan = messaging.pub_sock('sendcan') + can_callbacks = can_comm_callbacks(logcan, sendcan) + + # Set up params for pandad + params = Params() + params.remove("FirmwareQueryDone") + params.put_bool("IsOnroad", False) + time.sleep(0.2) # thread is 10 Hz + params.put_bool("IsOnroad", True) + set_obd_multiplexing = obd_callback(params) + + extra: Any = None + if args.scan: + extra = {} + # Honda + for i in range(256): + extra[(Ecu.unknown, 0x18da00f1 + (i << 8), None)] = [] + extra[(Ecu.unknown, 0x700 + i, None)] = [] + extra[(Ecu.unknown, 0x750, i)] = [] + extra = {"any": {"debug": extra}} + + num_pandas = len(messaging.recv_one_retry(pandaStates_sock).pandaStates) + + t = time.time() + print("Getting vin...") + set_obd_multiplexing(True) + vin_rx_addr, vin_rx_bus, vin = get_vin(*can_callbacks, (0, 1), debug=args.debug) + print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') + print(f"Getting VIN took {time.time() - t:.3f} s") + print() + + t = time.time() + fw_vers = get_fw_versions(*can_callbacks, set_obd_multiplexing, query_brand=args.brand, extra=extra, num_pandas=num_pandas, debug=args.debug, progress=True) + _, candidates = match_fw_to_car(fw_vers, vin) + + print() + print("Found FW versions") + print("{") + padding = max([len(fw.brand) for fw in fw_vers] or [0]) + for version in fw_vers: + subaddr = None if version.subAddress == 0 else hex(version.subAddress) + print(f" Brand: {version.brand:{padding}}, bus: {version.bus}, OBD: {version.obdMultiplexing} - " + + f"(Ecu.{version.ecu}, {hex(version.address)}, {subaddr}): [{version.fwVersion!r}]") + print("}") + + print() + print("Possible matches:", candidates) + print(f"Getting fw took {time.time() - t:.3f} s") diff --git a/selfdrive/debug/car/vin.py b/selfdrive/debug/car/vin.py new file mode 100755 index 000000000000000..7946b429e45af64 --- /dev/null +++ b/selfdrive/debug/car/vin.py @@ -0,0 +1,22 @@ +#!/usr/bin/env python3 +import argparse +import time +import cereal.messaging as messaging +from opendbc.car.vin import get_vin +from openpilot.selfdrive.car.card import can_comm_callbacks + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description='Get VIN of the car') + parser.add_argument('--debug', action='store_true') + parser.add_argument('--bus', type=int, default=1) + parser.add_argument('--timeout', type=float, default=0.1) + parser.add_argument('--retry', type=int, default=5) + args = parser.parse_args() + + sendcan = messaging.pub_sock('sendcan') + logcan = messaging.sub_sock('can') + can_callbacks = can_comm_callbacks(logcan, sendcan) + time.sleep(1) + + vin_rx_addr, vin_rx_bus, vin = get_vin(*can_callbacks, (args.bus,), args.timeout, args.retry, debug=args.debug) + print(f'RX: {hex(vin_rx_addr)}, BUS: {vin_rx_bus}, VIN: {vin}') diff --git a/selfdrive/debug/check_can_parser_performance.py b/selfdrive/debug/check_can_parser_performance.py index 604a1df1248e862..7a0db1926bfb17b 100755 --- a/selfdrive/debug/check_can_parser_performance.py +++ b/selfdrive/debug/check_can_parser_performance.py @@ -4,8 +4,9 @@ from tqdm import tqdm from cereal import car -from openpilot.selfdrive.car.tests.routes import CarTestRoute +from opendbc.car.tests.routes import CarTestRoute from openpilot.selfdrive.car.tests.test_models import TestCarModelBase +from openpilot.selfdrive.pandad import can_capnp_to_list from openpilot.tools.plotjuggler.juggle import DEMO_ROUTE N_RUNS = 10 @@ -13,7 +14,6 @@ class CarModelTestCase(TestCarModelBase): test_route = CarTestRoute(DEMO_ROUTE, None) - ci = False if __name__ == '__main__': @@ -25,12 +25,13 @@ class CarModelTestCase(TestCarModelBase): CC = car.CarControl.new_message() ets = [] for _ in tqdm(range(N_RUNS)): - msgs = [(m.as_builder().to_bytes(),) for m in tm.can_msgs] + msgs = [m.as_builder().to_bytes() for m in tm.can_msgs] start_t = time.process_time_ns() for msg in msgs: + can_list = can_capnp_to_list([msg]) for cp in tm.CI.can_parsers: if cp is not None: - cp.update_strings(msg) + cp.update_strings(can_list) ets.append((time.process_time_ns() - start_t) * 1e-6) print(f'{len(tm.can_msgs)} CAN packets, {N_RUNS} runs') diff --git a/selfdrive/debug/count_events.py b/selfdrive/debug/count_events.py index 59420547570b0e2..4095ae3fc1694ee 100755 --- a/selfdrive/debug/count_events.py +++ b/selfdrive/debug/count_events.py @@ -33,8 +33,8 @@ if len(events) == 0 or ae != events[-1][1]: events.append((t, ae)) - elif msg.which() == 'controlsState': - at = msg.controlsState.alertType + elif msg.which() == 'selfdriveState': + at = msg.selfdriveState.alertType if "/override" not in at or "lanechange" in at.lower(): if len(alerts) == 0 or alerts[-1][1] != at: alerts.append((t, at)) diff --git a/selfdrive/debug/cycle_alerts.py b/selfdrive/debug/cycle_alerts.py index 93b0430c1e0c0f7..11e75a7a8e3be3e 100755 --- a/selfdrive/debug/cycle_alerts.py +++ b/selfdrive/debug/cycle_alerts.py @@ -4,13 +4,13 @@ from cereal import car, log import cereal.messaging as messaging +from opendbc.car.honda.interface import CarInterface from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car.honda.interface import CarInterface -from openpilot.selfdrive.controls.lib.events import ET, Events -from openpilot.selfdrive.controls.lib.alertmanager import AlertManager +from openpilot.selfdrive.selfdrived.events import ET, Events +from openpilot.selfdrive.selfdrived.alertmanager import AlertManager from openpilot.system.manager.process_config import managed_processes -EventName = car.CarEvent.EventName +EventName = log.OnroadEvent.EventName def randperc() -> float: return 100. * random.random() @@ -54,10 +54,10 @@ def cycle_alerts(duration=200, is_metric=False): CS = car.CarState.new_message() CP = CarInterface.get_non_essential_params("HONDA_CIVIC") sm = messaging.SubMaster(['deviceState', 'pandaStates', 'roadCameraState', 'modelV2', 'liveCalibration', - 'driverMonitoringState', 'longitudinalPlan', 'liveLocationKalman', + 'driverMonitoringState', 'longitudinalPlan', 'livePose', 'managerState'] + cameras) - pm = messaging.PubMaster(['controlsState', 'pandaStates', 'deviceState']) + pm = messaging.PubMaster(['selfdriveState', 'pandaStates', 'deviceState']) events = Events() AM = AlertManager() @@ -100,18 +100,17 @@ def cycle_alerts(duration=200, is_metric=False): print(alert) for _ in range(duration): dat = messaging.new_message() - dat.init('controlsState') - dat.controlsState.enabled = False + dat.init('selfdriveState') + dat.selfdriveState.enabled = False if alert: - dat.controlsState.alertText1 = alert.alert_text_1 - dat.controlsState.alertText2 = alert.alert_text_2 - dat.controlsState.alertSize = alert.alert_size - dat.controlsState.alertStatus = alert.alert_status - dat.controlsState.alertBlinkingRate = alert.alert_rate - dat.controlsState.alertType = alert.alert_type - dat.controlsState.alertSound = alert.audible_alert - pm.send('controlsState', dat) + dat.selfdriveState.alertText1 = alert.alert_text_1 + dat.selfdriveState.alertText2 = alert.alert_text_2 + dat.selfdriveState.alertSize = alert.alert_size + dat.selfdriveState.alertStatus = alert.alert_status + dat.selfdriveState.alertType = alert.alert_type + dat.selfdriveState.alertSound = alert.audible_alert + pm.send('selfdriveState', dat) dat = messaging.new_message() dat.init('deviceState') diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index 787e9bc738b09d2..78cf51e3db5fb00 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -4,7 +4,6 @@ import json import codecs -from hexdump import hexdump from cereal import log from cereal.services import SERVICE_LIST from openpilot.tools.lib.live_logreader import raw_live_logreader @@ -12,6 +11,18 @@ codecs.register_error("strict", codecs.backslashreplace_errors) +def hexdump(msg): + m = str.upper(msg.hex()) + m = [m[i:i+2] for i in range(0,len(m),2)] + m = [m[i:i+16] for i in range(0,len(m),16)] + for row,dump in enumerate(m): + addr = '%08X:' % (row*16) + raw = ' '.join(dump[:8]) + ' ' + ' '.join(dump[8:]) + space = ' ' * (48 - len(raw)) + asci = ''.join(chr(int(x,16)) if 0x20 <= int(x,16) <= 0x7E else '.' for x in dump) + print(f'{addr} {raw} {space} {asci}') + + if __name__ == "__main__": parser = argparse.ArgumentParser(description='Dump communication sockets. See cereal/services.py for a complete list of available sockets.') diff --git a/selfdrive/debug/dump_car_docs.py b/selfdrive/debug/dump_car_docs.py index f09c602cffa5a33..f0e99cda24ad6f2 100755 --- a/selfdrive/debug/dump_car_docs.py +++ b/selfdrive/debug/dump_car_docs.py @@ -2,7 +2,7 @@ import argparse import pickle -from openpilot.selfdrive.car.docs import get_all_car_docs +from opendbc.car.docs import get_all_car_docs def dump_car_docs(path): diff --git a/selfdrive/debug/fingerprint_from_route.py b/selfdrive/debug/fingerprint_from_route.py index 68308bb62782d5b..9da388999b2c14d 100755 --- a/selfdrive/debug/fingerprint_from_route.py +++ b/selfdrive/debug/fingerprint_from_route.py @@ -8,10 +8,12 @@ def get_fingerprint(lr): # TODO: make this a nice tool for car ports. should also work with qlogs for FW fw = None + vin = None msgs = {} for msg in lr: if msg.which() == 'carParams': fw = msg.carParams.carFw + vin = msg.carParams.carVin elif msg.which() == 'can': for c in msg.can: # read also msgs sent by EON on CAN bus 0x80 and filter out the @@ -32,6 +34,7 @@ def get_fingerprint(lr): print(f" {f.fwVersion},") print(" ],") print() + print(f"VIN: {vin}") if __name__ == "__main__": diff --git a/selfdrive/debug/format_fingerprints.py b/selfdrive/debug/format_fingerprints.py index 2a5e4e60802e5ac..7207bd1ef1abb9c 100755 --- a/selfdrive/debug/format_fingerprints.py +++ b/selfdrive/debug/format_fingerprints.py @@ -4,7 +4,7 @@ from cereal import car from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car.interfaces import get_interface_attr +from opendbc.car.interfaces import get_interface_attr Ecu = car.CarParams.Ecu @@ -18,12 +18,12 @@ # ruff: noqa: E501 {% endif %} {% if FW_VERSIONS[brand] %} -from cereal import car +from opendbc.car.structs import CarParams {% endif %} -from openpilot.selfdrive.car.{{brand}}.values import CAR +from opendbc.car.{{brand}}.values import CAR {% if FW_VERSIONS[brand] %} -Ecu = car.CarParams.Ecu +Ecu = CarParams.Ecu {% endif %} {% if comments +%} {{ comments | join() }} @@ -66,7 +66,7 @@ def format_brand_fw_versions(brand, extra_fw_versions: None | dict[str, dict[tuple, list[bytes]]] = None): extra_fw_versions = extra_fw_versions or {} - fingerprints_file = os.path.join(BASEDIR, f"selfdrive/car/{brand}/fingerprints.py") + fingerprints_file = os.path.join(BASEDIR, f"opendbc/car/{brand}/fingerprints.py") with open(fingerprints_file) as f: comments = [line for line in f.readlines() if line.startswith("#") and "noqa" not in line] diff --git a/selfdrive/debug/internal/fuzz_fw_fingerprint.py b/selfdrive/debug/internal/fuzz_fw_fingerprint.py index aedb3ada1dcdd4d..fa99e6bfbe8e9eb 100755 --- a/selfdrive/debug/internal/fuzz_fw_fingerprint.py +++ b/selfdrive/debug/internal/fuzz_fw_fingerprint.py @@ -5,11 +5,11 @@ from tqdm import tqdm -from openpilot.selfdrive.car.fw_versions import match_fw_to_car_fuzzy -from openpilot.selfdrive.car.toyota.values import FW_VERSIONS as TOYOTA_FW_VERSIONS -from openpilot.selfdrive.car.honda.values import FW_VERSIONS as HONDA_FW_VERSIONS -from openpilot.selfdrive.car.hyundai.values import FW_VERSIONS as HYUNDAI_FW_VERSIONS -from openpilot.selfdrive.car.volkswagen.values import FW_VERSIONS as VW_FW_VERSIONS +from opendbc.car.fw_versions import match_fw_to_car_fuzzy +from opendbc.car.toyota.values import FW_VERSIONS as TOYOTA_FW_VERSIONS +from opendbc.car.honda.values import FW_VERSIONS as HONDA_FW_VERSIONS +from opendbc.car.hyundai.values import FW_VERSIONS as HYUNDAI_FW_VERSIONS +from opendbc.car.volkswagen.values import FW_VERSIONS as VW_FW_VERSIONS FWS = {} diff --git a/selfdrive/debug/internal/measure_torque_time_to_max.py b/selfdrive/debug/internal/measure_torque_time_to_max.py index ef3152b50ca379d..7052dccf7de2833 100755 --- a/selfdrive/debug/internal/measure_torque_time_to_max.py +++ b/selfdrive/debug/internal/measure_torque_time_to_max.py @@ -18,7 +18,7 @@ if args.addr != "127.0.0.1": os.environ["ZMQ"] = "1" - messaging.context = messaging.Context() + messaging.reset_context() poller = messaging.Poller() messaging.sub_sock('can', poller, addr=args.addr) diff --git a/selfdrive/debug/internal/qlog_size.py b/selfdrive/debug/internal/qlog_size.py index b51cb3af2fc1458..11606c758919f20 100755 --- a/selfdrive/debug/internal/qlog_size.py +++ b/selfdrive/debug/internal/qlog_size.py @@ -1,28 +1,41 @@ #!/usr/bin/env python3 import argparse -import bz2 +import zstandard as zstd from collections import defaultdict import matplotlib.pyplot as plt from cereal.services import SERVICE_LIST +from openpilot.system.loggerd.uploader import LOG_COMPRESSION_LEVEL from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.route import Route +from tqdm import tqdm MIN_SIZE = 0.5 # Percent size of total to show as separate entry def make_pie(msgs, typ): - compressed_length_by_type = {k: len(bz2.compress(b"".join(v))) for k, v in msgs.items()} + msgs_by_type = defaultdict(list) + for m in msgs: + msgs_by_type[m.which()].append(m.as_builder().to_bytes()) + + total = len(zstd.compress(b"".join([m.as_builder().to_bytes() for m in msgs]), LOG_COMPRESSION_LEVEL)) + uncompressed_total = len(b"".join([m.as_builder().to_bytes() for m in msgs])) - total = sum(compressed_length_by_type.values()) + length_by_type = {k: len(b"".join(v)) for k, v in msgs_by_type.items()} + # calculate compressed size by calculating diff when removed from the segment + compressed_length_by_type = {} + for k in tqdm(msgs_by_type.keys(), desc="Compressing"): + compressed_length_by_type[k] = total - len(zstd.compress(b"".join([m.as_builder().to_bytes() for m in msgs if m.which() != k]), LOG_COMPRESSION_LEVEL)) sizes = sorted(compressed_length_by_type.items(), key=lambda kv: kv[1]) - print(f"{typ} - Total {total / 1024:.2f} kB") + print("name - comp. size (uncomp. size)") for (name, sz) in sizes: - print(f"{name} - {sz / 1024:.2f} kB") + print(f"{name:<22} - {sz / 1024:.2f} kB ({length_by_type[name] / 1024:.2f} kB)") print() + print(f"{typ} - Real total {total / 1024:.2f} kB") + print(f"{typ} - Breakdown total {sum(compressed_length_by_type.values()) / 1024:.2f} kB") + print(f"{typ} - Uncompressed total {uncompressed_total / 1024 / 1024:.2f} MB") sizes_large = [(k, sz) for (k, sz) in sizes if sz >= total * MIN_SIZE / 100] sizes_large += [('other', sum(sz for (_, sz) in sizes if sz < total * MIN_SIZE / 100))] @@ -35,28 +48,31 @@ def make_pie(msgs, typ): if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Check qlog size based on a rlog') + parser = argparse.ArgumentParser(description='View log size breakdown by message type') parser.add_argument('route', help='route to use') - parser.add_argument('segment', type=int, help='segment number to use') + parser.add_argument('--as-qlog', action='store_true', help='decimate rlog using latest decimation factors') args = parser.parse_args() - r = Route(args.route) - rlog = r.log_paths()[args.segment] - msgs = list(LogReader(rlog)) + msgs = list(LogReader(args.route)) - msgs_by_type = defaultdict(list) - for m in msgs: - msgs_by_type[m.which()].append(m.as_builder().to_bytes()) + if args.as_qlog: + new_msgs = [] + msg_cnts: dict[str, int] = defaultdict(int) + for msg in msgs: + msg_which = msg.which() + if msg.which() in ("initData", "sentinel"): + new_msgs.append(msg) + continue + + if msg_which not in SERVICE_LIST: + continue - qlog_by_type = defaultdict(list) - for name, service in SERVICE_LIST.items(): - if service.decimation is None: - continue + decimation = SERVICE_LIST[msg_which].decimation + if decimation is not None and msg_cnts[msg_which] % decimation == 0: + new_msgs.append(msg) + msg_cnts[msg_which] += 1 - for i, msg in enumerate(msgs_by_type[name]): - if i % service.decimation == 0: - qlog_by_type[name].append(msg) + msgs = new_msgs - make_pie(msgs_by_type, 'rlog') - make_pie(qlog_by_type, 'qlog') + make_pie(msgs, 'qlog') plt.show() diff --git a/selfdrive/debug/print_docs_diff.py b/selfdrive/debug/print_docs_diff.py index 7ef89a6ecae72ca..388acf3af580209 100755 --- a/selfdrive/debug/print_docs_diff.py +++ b/selfdrive/debug/print_docs_diff.py @@ -4,8 +4,8 @@ import difflib import pickle -from openpilot.selfdrive.car.docs import get_all_car_docs -from openpilot.selfdrive.car.docs_definitions import Column +from opendbc.car.docs import get_all_car_docs +from opendbc.car.docs_definitions import Column FOOTNOTE_TAG = "{}" STAR_ICON = ' bool: 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: + def add_point(self, x: float, y: float) -> None: raise NotImplementedError def get_points(self, num_points: int = None) -> Any: @@ -62,3 +71,69 @@ def handle_log(self, t: int, which: str, msg: log.Event) -> None: def get_msg(self, valid: bool, with_points: bool) -> log.Event: raise NotImplementedError + + +class Measurement: + x, y, z = (property(lambda self: self.xyz[0]), property(lambda self: self.xyz[1]), property(lambda self: self.xyz[2])) + x_std, y_std, z_std = (property(lambda self: self.xyz_std[0]), property(lambda self: self.xyz_std[1]), property(lambda self: self.xyz_std[2])) + roll, pitch, yaw = x, y, z + roll_std, pitch_std, yaw_std = x_std, y_std, z_std + + def __init__(self, xyz: np.ndarray, xyz_std: np.ndarray): + self.xyz: np.ndarray = xyz + self.xyz_std: np.ndarray = xyz_std + + @classmethod + def from_measurement_xyz(cls, measurement: log.LivePose.XYZMeasurement) -> 'Measurement': + return cls( + xyz=np.array([measurement.x, measurement.y, measurement.z]), + xyz_std=np.array([measurement.xStd, measurement.yStd, measurement.zStd]) + ) + + +class Pose: + def __init__(self, orientation: Measurement, velocity: Measurement, acceleration: Measurement, angular_velocity: Measurement): + self.orientation = orientation + self.velocity = velocity + self.acceleration = acceleration + self.angular_velocity = angular_velocity + + @classmethod + def from_live_pose(cls, live_pose: log.LivePose) -> 'Pose': + return Pose( + orientation=Measurement.from_measurement_xyz(live_pose.orientationNED), + velocity=Measurement.from_measurement_xyz(live_pose.velocityDevice), + acceleration=Measurement.from_measurement_xyz(live_pose.accelerationDevice), + angular_velocity=Measurement.from_measurement_xyz(live_pose.angularVelocityDevice) + ) + + +class PoseCalibrator: + def __init__(self): + self.calib_valid = False + self.calib_from_device = np.eye(3) + + def _transform_calib_from_device(self, meas: Measurement): + new_xyz = self.calib_from_device @ meas.xyz + new_xyz_std = rotate_std(self.calib_from_device, meas.xyz_std) + return Measurement(new_xyz, new_xyz_std) + + def _ned_from_calib(self, orientation: Measurement): + ned_from_device = rot_from_euler(orientation.xyz) + ned_from_calib = ned_from_device @ self.calib_from_device.T + ned_from_calib_euler_meas = Measurement(euler_from_rot(ned_from_calib), np.full(3, np.nan)) + return ned_from_calib_euler_meas + + def build_calibrated_pose(self, pose: Pose) -> Pose: + ned_from_calib_euler = self._ned_from_calib(pose.orientation) + angular_velocity_calib = self._transform_calib_from_device(pose.angular_velocity) + acceleration_calib = self._transform_calib_from_device(pose.acceleration) + velocity_calib = self._transform_calib_from_device(pose.angular_velocity) + + return Pose(ned_from_calib_euler, velocity_calib, acceleration_calib, angular_velocity_calib) + + def feed_live_calib(self, live_calib: log.LiveCalibrationData): + calib_rpy = np.array(live_calib.rpyCalib) + device_from_calib = rot_from_euler(calib_rpy) + self.calib_from_device = device_from_calib.T + self.calib_valid = live_calib.calStatus == log.LiveCalibrationData.Status.calibrated diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc deleted file mode 100644 index 2ac392a77893b30..000000000000000 --- a/selfdrive/locationd/locationd.cc +++ /dev/null @@ -1,750 +0,0 @@ -#include "selfdrive/locationd/locationd.h" - -#include -#include - -#include -#include -#include - -using namespace EKFS; -using namespace Eigen; - -ExitHandler do_exit; -const double ACCEL_SANITY_CHECK = 100.0; // m/s^2 -const double ROTATION_SANITY_CHECK = 10.0; // rad/s -const double TRANS_SANITY_CHECK = 200.0; // m/s -const double CALIB_RPY_SANITY_CHECK = 0.5; // rad (+- 30 deg) -const double ALTITUDE_SANITY_CHECK = 10000; // m -const double MIN_STD_SANITY_CHECK = 1e-5; // m or rad -const double VALID_TIME_SINCE_RESET = 1.0; // s -const double VALID_POS_STD = 50.0; // m -const double MAX_RESET_TRACKER = 5.0; -const double SANE_GPS_UNCERTAINTY = 1500.0; // m -const double INPUT_INVALID_THRESHOLD = 0.5; // same as reset tracker -const double RESET_TRACKER_DECAY = 0.99995; -const double DECAY = 0.9993; // ~10 secs to resume after a bad input -const double MAX_FILTER_REWIND_TIME = 0.8; // s -const double YAWRATE_CROSS_ERR_CHECK_FACTOR = 30; - -// TODO: GPS sensor time offsets are empirically calculated -// They should be replaced with synced time from a real clock -const double GPS_QUECTEL_SENSOR_TIME_OFFSET = 0.630; // s -const double GPS_UBLOX_SENSOR_TIME_OFFSET = 0.095; // s -const float GPS_POS_STD_THRESHOLD = 50.0; -const float GPS_VEL_STD_THRESHOLD = 5.0; -const float GPS_POS_ERROR_RESET_THRESHOLD = 300.0; -const float GPS_POS_STD_RESET_THRESHOLD = 2.0; -const float GPS_VEL_STD_RESET_THRESHOLD = 0.5; -const float GPS_ORIENTATION_ERROR_RESET_THRESHOLD = 1.0; -const int GPS_ORIENTATION_ERROR_RESET_CNT = 3; - -const bool DEBUG = getenv("DEBUG") != nullptr && std::string(getenv("DEBUG")) != "0"; - -static VectorXd floatlist2vector(const capnp::List::Reader& floatlist) { - VectorXd res(floatlist.size()); - for (int i = 0; i < floatlist.size(); i++) { - res[i] = floatlist[i]; - } - return res; -} - -static Vector4d quat2vector(const Quaterniond& quat) { - return Vector4d(quat.w(), quat.x(), quat.y(), quat.z()); -} - -static Quaterniond vector2quat(const VectorXd& vec) { - return Quaterniond(vec(0), vec(1), vec(2), vec(3)); -} - -static void init_measurement(cereal::LiveLocationKalman::Measurement::Builder meas, const VectorXd& val, const VectorXd& std, bool valid) { - meas.setValue(kj::arrayPtr(val.data(), val.size())); - meas.setStd(kj::arrayPtr(std.data(), std.size())); - meas.setValid(valid); -} - - -static MatrixXdr rotate_cov(const MatrixXdr& rot_matrix, const MatrixXdr& cov_in) { - // To rotate a covariance matrix, the cov matrix needs to multiplied left and right by the transform matrix - return ((rot_matrix * cov_in) * rot_matrix.transpose()); -} - -static VectorXd rotate_std(const MatrixXdr& rot_matrix, const VectorXd& std_in) { - // Stds cannot be rotated like values, only covariances can be rotated - return rotate_cov(rot_matrix, std_in.array().square().matrix().asDiagonal()).diagonal().array().sqrt(); -} - -Localizer::Localizer(LocalizerGnssSource gnss_source) { - this->kf = std::make_unique(); - this->reset_kalman(); - - this->calib = Vector3d(0.0, 0.0, 0.0); - this->device_from_calib = MatrixXdr::Identity(3, 3); - this->calib_from_device = MatrixXdr::Identity(3, 3); - - for (int i = 0; i < POSENET_STD_HIST_HALF * 2; i++) { - this->posenet_stds.push_back(10.0); - } - - VectorXd ecef_pos = this->kf->get_x().segment(STATE_ECEF_POS_START); - this->converter = std::make_unique((ECEF) { .x = ecef_pos[0], .y = ecef_pos[1], .z = ecef_pos[2] }); - this->configure_gnss_source(gnss_source); -} - -void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { - VectorXd predicted_state = this->kf->get_x(); - MatrixXdr predicted_cov = this->kf->get_P(); - VectorXd predicted_std = predicted_cov.diagonal().array().sqrt(); - - VectorXd fix_ecef = predicted_state.segment(STATE_ECEF_POS_START); - ECEF fix_ecef_ecef = { .x = fix_ecef(0), .y = fix_ecef(1), .z = fix_ecef(2) }; - VectorXd fix_ecef_std = predicted_std.segment(STATE_ECEF_POS_ERR_START); - VectorXd vel_ecef = predicted_state.segment(STATE_ECEF_VELOCITY_START); - VectorXd vel_ecef_std = predicted_std.segment(STATE_ECEF_VELOCITY_ERR_START); - VectorXd fix_pos_geo_vec = this->get_position_geodetic(); - VectorXd orientation_ecef = quat2euler(vector2quat(predicted_state.segment(STATE_ECEF_ORIENTATION_START))); - VectorXd orientation_ecef_std = predicted_std.segment(STATE_ECEF_ORIENTATION_ERR_START); - MatrixXdr orientation_ecef_cov = predicted_cov.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_ORIENTATION_ERR_START); - MatrixXdr device_from_ecef = euler2rot(orientation_ecef).transpose(); - VectorXd calibrated_orientation_ecef = rot2euler((this->calib_from_device * device_from_ecef).transpose()); - - VectorXd acc_calib = this->calib_from_device * predicted_state.segment(STATE_ACCELERATION_START); - MatrixXdr acc_calib_cov = predicted_cov.block(STATE_ACCELERATION_ERR_START, STATE_ACCELERATION_ERR_START); - VectorXd acc_calib_std = rotate_cov(this->calib_from_device, acc_calib_cov).diagonal().array().sqrt(); - VectorXd ang_vel_calib = this->calib_from_device * predicted_state.segment(STATE_ANGULAR_VELOCITY_START); - - MatrixXdr vel_angular_cov = predicted_cov.block(STATE_ANGULAR_VELOCITY_ERR_START, STATE_ANGULAR_VELOCITY_ERR_START); - VectorXd ang_vel_calib_std = rotate_cov(this->calib_from_device, vel_angular_cov).diagonal().array().sqrt(); - - VectorXd vel_device = device_from_ecef * vel_ecef; - VectorXd device_from_ecef_eul = quat2euler(vector2quat(predicted_state.segment(STATE_ECEF_ORIENTATION_START))).transpose(); - MatrixXdr condensed_cov(STATE_ECEF_ORIENTATION_ERR_LEN + STATE_ECEF_VELOCITY_ERR_LEN, STATE_ECEF_ORIENTATION_ERR_LEN + STATE_ECEF_VELOCITY_ERR_LEN); - condensed_cov.topLeftCorner() = - predicted_cov.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_ORIENTATION_ERR_START); - condensed_cov.topRightCorner() = - predicted_cov.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_VELOCITY_ERR_START); - condensed_cov.bottomRightCorner() = - predicted_cov.block(STATE_ECEF_VELOCITY_ERR_START, STATE_ECEF_VELOCITY_ERR_START); - condensed_cov.bottomLeftCorner() = - predicted_cov.block(STATE_ECEF_VELOCITY_ERR_START, STATE_ECEF_ORIENTATION_ERR_START); - VectorXd H_input(device_from_ecef_eul.size() + vel_ecef.size()); - H_input << device_from_ecef_eul, vel_ecef; - MatrixXdr HH = this->kf->H(H_input); - MatrixXdr vel_device_cov = (HH * condensed_cov) * HH.transpose(); - VectorXd vel_device_std = vel_device_cov.diagonal().array().sqrt(); - - VectorXd vel_calib = this->calib_from_device * vel_device; - VectorXd vel_calib_std = rotate_cov(this->calib_from_device, vel_device_cov).diagonal().array().sqrt(); - - VectorXd orientation_ned = ned_euler_from_ecef(fix_ecef_ecef, orientation_ecef); - VectorXd orientation_ned_std = rotate_cov(this->converter->ecef2ned_matrix, orientation_ecef_cov).diagonal().array().sqrt(); - VectorXd calibrated_orientation_ned = ned_euler_from_ecef(fix_ecef_ecef, calibrated_orientation_ecef); - VectorXd nextfix_ecef = fix_ecef + vel_ecef; - VectorXd ned_vel = this->converter->ecef2ned((ECEF) { .x = nextfix_ecef(0), .y = nextfix_ecef(1), .z = nextfix_ecef(2) }).to_vector() - converter->ecef2ned(fix_ecef_ecef).to_vector(); - - VectorXd accDevice = predicted_state.segment(STATE_ACCELERATION_START); - VectorXd accDeviceErr = predicted_std.segment(STATE_ACCELERATION_ERR_START); - - VectorXd angVelocityDevice = predicted_state.segment(STATE_ANGULAR_VELOCITY_START); - VectorXd angVelocityDeviceErr = predicted_std.segment(STATE_ANGULAR_VELOCITY_ERR_START); - - Vector3d nans = Vector3d(NAN, NAN, NAN); - - // TODO fill in NED and Calibrated stds - // write measurements to msg - init_measurement(fix.initPositionGeodetic(), fix_pos_geo_vec, nans, this->gps_mode); - init_measurement(fix.initPositionECEF(), fix_ecef, fix_ecef_std, this->gps_mode); - init_measurement(fix.initVelocityECEF(), vel_ecef, vel_ecef_std, this->gps_mode); - init_measurement(fix.initVelocityNED(), ned_vel, nans, this->gps_mode); - init_measurement(fix.initVelocityDevice(), vel_device, vel_device_std, true); - init_measurement(fix.initAccelerationDevice(), accDevice, accDeviceErr, true); - init_measurement(fix.initOrientationECEF(), orientation_ecef, orientation_ecef_std, this->gps_mode); - init_measurement(fix.initCalibratedOrientationECEF(), calibrated_orientation_ecef, nans, this->calibrated && this->gps_mode); - init_measurement(fix.initOrientationNED(), orientation_ned, orientation_ned_std, this->gps_mode); - init_measurement(fix.initCalibratedOrientationNED(), calibrated_orientation_ned, nans, this->calibrated && this->gps_mode); - init_measurement(fix.initAngularVelocityDevice(), angVelocityDevice, angVelocityDeviceErr, true); - init_measurement(fix.initVelocityCalibrated(), vel_calib, vel_calib_std, this->calibrated); - init_measurement(fix.initAngularVelocityCalibrated(), ang_vel_calib, ang_vel_calib_std, this->calibrated); - init_measurement(fix.initAccelerationCalibrated(), acc_calib, acc_calib_std, this->calibrated); - if (DEBUG) { - init_measurement(fix.initFilterState(), predicted_state, predicted_std, true); - } - - double old_mean = 0.0, new_mean = 0.0; - int i = 0; - for (double x : this->posenet_stds) { - if (i < POSENET_STD_HIST_HALF) { - old_mean += x; - } else { - new_mean += x; - } - i++; - } - old_mean /= POSENET_STD_HIST_HALF; - new_mean /= POSENET_STD_HIST_HALF; - // experimentally found these values, no false positives in 20k minutes of driving - bool std_spike = (new_mean / old_mean > 4.0 && new_mean > 7.0); - - fix.setPosenetOK(!(std_spike && this->car_speed > 5.0)); - fix.setDeviceStable(!this->device_fell); - fix.setExcessiveResets(this->reset_tracker > MAX_RESET_TRACKER); - fix.setTimeToFirstFix(std::isnan(this->ttff) ? -1. : this->ttff); - this->device_fell = false; - - //fix.setGpsWeek(this->time.week); - //fix.setGpsTimeOfWeek(this->time.tow); - fix.setUnixTimestampMillis(this->unix_timestamp_millis); - - double time_since_reset = this->kf->get_filter_time() - this->last_reset_time; - fix.setTimeSinceReset(time_since_reset); - if (fix_ecef_std.norm() < VALID_POS_STD && this->calibrated && time_since_reset > VALID_TIME_SINCE_RESET) { - fix.setStatus(cereal::LiveLocationKalman::Status::VALID); - } else if (fix_ecef_std.norm() < VALID_POS_STD && time_since_reset > VALID_TIME_SINCE_RESET) { - fix.setStatus(cereal::LiveLocationKalman::Status::UNCALIBRATED); - } else { - fix.setStatus(cereal::LiveLocationKalman::Status::UNINITIALIZED); - } -} - -VectorXd Localizer::get_position_geodetic() { - VectorXd fix_ecef = this->kf->get_x().segment(STATE_ECEF_POS_START); - ECEF fix_ecef_ecef = { .x = fix_ecef(0), .y = fix_ecef(1), .z = fix_ecef(2) }; - Geodetic fix_pos_geo = ecef2geodetic(fix_ecef_ecef); - return Vector3d(fix_pos_geo.lat, fix_pos_geo.lon, fix_pos_geo.alt); -} - -VectorXd Localizer::get_state() { - return this->kf->get_x(); -} - -VectorXd Localizer::get_stdev() { - return this->kf->get_P().diagonal().array().sqrt(); -} - -bool Localizer::are_inputs_ok() { - return this->critical_services_valid(this->observation_values_invalid) && !this->observation_timings_invalid; -} - -void Localizer::observation_timings_invalid_reset(){ - this->observation_timings_invalid = false; -} - -void Localizer::handle_sensor(double current_time, const cereal::SensorEventData::Reader& log) { - // TODO does not yet account for double sensor readings in the log - - // Ignore empty readings (e.g. in case the magnetometer had no data ready) - if (log.getTimestamp() == 0) { - return; - } - - double sensor_time = 1e-9 * log.getTimestamp(); - - // sensor time and log time should be close - if (std::abs(current_time - sensor_time) > 0.1) { - LOGE("Sensor reading ignored, sensor timestamp more than 100ms off from log time"); - this->observation_timings_invalid = true; - return; - } else if (!this->is_timestamp_valid(sensor_time)) { - this->observation_timings_invalid = true; - return; - } - - // TODO: handle messages from two IMUs at the same time - if (log.getSource() == cereal::SensorEventData::SensorSource::BMX055) { - return; - } - - // Gyro Uncalibrated - if (log.getSensor() == SENSOR_GYRO_UNCALIBRATED && log.getType() == SENSOR_TYPE_GYROSCOPE_UNCALIBRATED) { - auto v = log.getGyroUncalibrated().getV(); - auto meas = Vector3d(-v[2], -v[1], -v[0]); - - VectorXd gyro_bias = this->kf->get_x().segment(STATE_GYRO_BIAS_START); - float gyro_camodo_yawrate_err = std::abs((meas[2] - gyro_bias[2]) - this->camodo_yawrate_distribution[0]); - float gyro_camodo_yawrate_err_threshold = YAWRATE_CROSS_ERR_CHECK_FACTOR * this->camodo_yawrate_distribution[1]; - bool gyro_valid = gyro_camodo_yawrate_err < gyro_camodo_yawrate_err_threshold; - - if ((meas.norm() < ROTATION_SANITY_CHECK) && gyro_valid) { - this->kf->predict_and_observe(sensor_time, OBSERVATION_PHONE_GYRO, { meas }); - this->observation_values_invalid["gyroscope"] *= DECAY; - } else { - this->observation_values_invalid["gyroscope"] += 1.0; - } - } - - // Accelerometer - if (log.getSensor() == SENSOR_ACCELEROMETER && log.getType() == SENSOR_TYPE_ACCELEROMETER) { - auto v = log.getAcceleration().getV(); - - // TODO: reduce false positives and re-enable this check - // check if device fell, estimate 10 for g - // 40m/s**2 is a good filter for falling detection, no false positives in 20k minutes of driving - // this->device_fell |= (floatlist2vector(v) - Vector3d(10.0, 0.0, 0.0)).norm() > 40.0; - - auto meas = Vector3d(-v[2], -v[1], -v[0]); - if (meas.norm() < ACCEL_SANITY_CHECK) { - this->kf->predict_and_observe(sensor_time, OBSERVATION_PHONE_ACCEL, { meas }); - this->observation_values_invalid["accelerometer"] *= DECAY; - } else { - this->observation_values_invalid["accelerometer"] += 1.0; - } - } -} - -void Localizer::input_fake_gps_observations(double current_time) { - // This is done to make sure that the error estimate of the position does not blow up - // when the filter is in no-gps mode - // Steps : first predict -> observe current obs with reasonable STD - this->kf->predict(current_time); - - VectorXd current_x = this->kf->get_x(); - VectorXd ecef_pos = current_x.segment(STATE_ECEF_POS_START); - VectorXd ecef_vel = current_x.segment(STATE_ECEF_VELOCITY_START); - const MatrixXdr &ecef_pos_R = this->kf->get_fake_gps_pos_cov(); - const MatrixXdr &ecef_vel_R = this->kf->get_fake_gps_vel_cov(); - - this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); - this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); -} - -void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset) { - bool gps_unreasonable = (Vector2d(log.getHorizontalAccuracy(), log.getVerticalAccuracy()).norm() >= SANE_GPS_UNCERTAINTY); - bool gps_accuracy_insane = ((log.getVerticalAccuracy() <= 0) || (log.getSpeedAccuracy() <= 0) || (log.getBearingAccuracyDeg() <= 0)); - bool gps_lat_lng_alt_insane = ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK)); - bool gps_vel_insane = (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK); - - if (!log.getHasFix() || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane) { - //this->gps_valid = false; - this->determine_gps_mode(current_time); - return; - } - - double sensor_time = current_time - sensor_time_offset; - - // Process message - //this->gps_valid = true; - this->gps_mode = true; - Geodetic geodetic = { log.getLatitude(), log.getLongitude(), log.getAltitude() }; - this->converter = std::make_unique(geodetic); - - VectorXd ecef_pos = this->converter->ned2ecef({ 0.0, 0.0, 0.0 }).to_vector(); - VectorXd ecef_vel = this->converter->ned2ecef({ log.getVNED()[0], log.getVNED()[1], log.getVNED()[2] }).to_vector() - ecef_pos; - float ecef_pos_std = std::sqrt(this->gps_variance_factor * std::pow(log.getHorizontalAccuracy(), 2) + this->gps_vertical_variance_factor * std::pow(log.getVerticalAccuracy(), 2)); - MatrixXdr ecef_pos_R = Vector3d::Constant(std::pow(this->gps_std_factor * ecef_pos_std, 2)).asDiagonal(); - MatrixXdr ecef_vel_R = Vector3d::Constant(std::pow(this->gps_std_factor * log.getSpeedAccuracy(), 2)).asDiagonal(); - - this->unix_timestamp_millis = log.getUnixTimestampMillis(); - double gps_est_error = (this->kf->get_x().segment(STATE_ECEF_POS_START) - ecef_pos).norm(); - - VectorXd orientation_ecef = quat2euler(vector2quat(this->kf->get_x().segment(STATE_ECEF_ORIENTATION_START))); - VectorXd orientation_ned = ned_euler_from_ecef({ ecef_pos(0), ecef_pos(1), ecef_pos(2) }, orientation_ecef); - VectorXd orientation_ned_gps = Vector3d(0.0, 0.0, DEG2RAD(log.getBearingDeg())); - VectorXd orientation_error = (orientation_ned - orientation_ned_gps).array() - M_PI; - for (int i = 0; i < orientation_error.size(); i++) { - orientation_error(i) = std::fmod(orientation_error(i), 2.0 * M_PI); - if (orientation_error(i) < 0.0) { - orientation_error(i) += 2.0 * M_PI; - } - orientation_error(i) -= M_PI; - } - VectorXd initial_pose_ecef_quat = quat2vector(euler2quat(ecef_euler_from_ned({ ecef_pos(0), ecef_pos(1), ecef_pos(2) }, orientation_ned_gps))); - - if (ecef_vel.norm() > 5.0 && orientation_error.norm() > 1.0) { - LOGE("Locationd vs ubloxLocation orientation difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); - } else if (gps_est_error > 100.0) { - LOGE("Locationd vs ubloxLocation position difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - } - - this->last_gps_msg = sensor_time; - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); -} - -void Localizer::handle_gnss(double current_time, const cereal::GnssMeasurements::Reader& log) { - - if (!log.getPositionECEF().getValid() || !log.getVelocityECEF().getValid()) { - this->determine_gps_mode(current_time); - return; - } - - double sensor_time = log.getMeasTime() * 1e-9; - sensor_time -= this->gps_time_offset; - - auto ecef_pos_v = log.getPositionECEF().getValue(); - VectorXd ecef_pos = Vector3d(ecef_pos_v[0], ecef_pos_v[1], ecef_pos_v[2]); - - // indexed at 0 cause all std values are the same MAE - auto ecef_pos_std = log.getPositionECEF().getStd()[0]; - MatrixXdr ecef_pos_R = Vector3d::Constant(pow(this->gps_std_factor*ecef_pos_std, 2)).asDiagonal(); - - auto ecef_vel_v = log.getVelocityECEF().getValue(); - VectorXd ecef_vel = Vector3d(ecef_vel_v[0], ecef_vel_v[1], ecef_vel_v[2]); - - // indexed at 0 cause all std values are the same MAE - auto ecef_vel_std = log.getVelocityECEF().getStd()[0]; - MatrixXdr ecef_vel_R = Vector3d::Constant(pow(this->gps_std_factor*ecef_vel_std, 2)).asDiagonal(); - - double gps_est_error = (this->kf->get_x().segment(STATE_ECEF_POS_START) - ecef_pos).norm(); - - VectorXd orientation_ecef = quat2euler(vector2quat(this->kf->get_x().segment(STATE_ECEF_ORIENTATION_START))); - VectorXd orientation_ned = ned_euler_from_ecef({ ecef_pos[0], ecef_pos[1], ecef_pos[2] }, orientation_ecef); - - LocalCoord convs((ECEF){ .x = ecef_pos[0], .y = ecef_pos[1], .z = ecef_pos[2] }); - ECEF next_ecef = {.x = ecef_pos[0] + ecef_vel[0], .y = ecef_pos[1] + ecef_vel[1], .z = ecef_pos[2] + ecef_vel[2]}; - VectorXd ned_vel = convs.ecef2ned(next_ecef).to_vector(); - double bearing_rad = atan2(ned_vel[1], ned_vel[0]); - - VectorXd orientation_ned_gps = Vector3d(0.0, 0.0, bearing_rad); - VectorXd orientation_error = (orientation_ned - orientation_ned_gps).array() - M_PI; - for (int i = 0; i < orientation_error.size(); i++) { - orientation_error(i) = std::fmod(orientation_error(i), 2.0 * M_PI); - if (orientation_error(i) < 0.0) { - orientation_error(i) += 2.0 * M_PI; - } - orientation_error(i) -= M_PI; - } - VectorXd initial_pose_ecef_quat = quat2vector(euler2quat(ecef_euler_from_ned({ ecef_pos(0), ecef_pos(1), ecef_pos(2) }, orientation_ned_gps))); - - if (ecef_pos_std > GPS_POS_STD_THRESHOLD || ecef_vel_std > GPS_VEL_STD_THRESHOLD) { - this->determine_gps_mode(current_time); - return; - } - - // prevent jumping gnss measurements (covered lots, standstill...) - bool orientation_reset = ecef_vel_std < GPS_VEL_STD_RESET_THRESHOLD; - orientation_reset &= orientation_error.norm() > GPS_ORIENTATION_ERROR_RESET_THRESHOLD; - orientation_reset &= !this->standstill; - if (orientation_reset) { - this->orientation_reset_count++; - } else { - this->orientation_reset_count = 0; - } - - if ((gps_est_error > GPS_POS_ERROR_RESET_THRESHOLD && ecef_pos_std < GPS_POS_STD_RESET_THRESHOLD) || this->last_gps_msg == 0) { - // always reset on first gps message and if the location is off but the accuracy is high - LOGE("Locationd vs gnssMeasurement position difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - } else if (orientation_reset_count > GPS_ORIENTATION_ERROR_RESET_CNT) { - LOGE("Locationd vs gnssMeasurement orientation difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); - this->orientation_reset_count = 0; - } - - this->gps_mode = true; - this->last_gps_msg = sensor_time; - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); -} - -void Localizer::handle_car_state(double current_time, const cereal::CarState::Reader& log) { - this->car_speed = std::abs(log.getVEgo()); - this->standstill = log.getStandstill(); - if (this->standstill) { - this->kf->predict_and_observe(current_time, OBSERVATION_NO_ROT, { Vector3d(0.0, 0.0, 0.0) }); - this->kf->predict_and_observe(current_time, OBSERVATION_NO_ACCEL, { Vector3d(0.0, 0.0, 0.0) }); - } -} - -void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log) { - VectorXd rot_device = this->device_from_calib * floatlist2vector(log.getRot()); - VectorXd trans_device = this->device_from_calib * floatlist2vector(log.getTrans()); - - if (!this->is_timestamp_valid(current_time)) { - this->observation_timings_invalid = true; - return; - } - - if ((rot_device.norm() > ROTATION_SANITY_CHECK) || (trans_device.norm() > TRANS_SANITY_CHECK)) { - this->observation_values_invalid["cameraOdometry"] += 1.0; - return; - } - - VectorXd rot_calib_std = floatlist2vector(log.getRotStd()); - VectorXd trans_calib_std = floatlist2vector(log.getTransStd()); - - if ((rot_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK) || (trans_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK)) { - this->observation_values_invalid["cameraOdometry"] += 1.0; - return; - } - - if ((rot_calib_std.norm() > 10 * ROTATION_SANITY_CHECK) || (trans_calib_std.norm() > 10 * TRANS_SANITY_CHECK)) { - this->observation_values_invalid["cameraOdometry"] += 1.0; - return; - } - - this->posenet_stds.pop_front(); - this->posenet_stds.push_back(trans_calib_std[0]); - - // Multiply by 10 to avoid to high certainty in kalman filter because of temporally correlated noise - trans_calib_std *= 10.0; - rot_calib_std *= 10.0; - MatrixXdr rot_device_cov = rotate_std(this->device_from_calib, rot_calib_std).array().square().matrix().asDiagonal(); - MatrixXdr trans_device_cov = rotate_std(this->device_from_calib, trans_calib_std).array().square().matrix().asDiagonal(); - this->kf->predict_and_observe(current_time, OBSERVATION_CAMERA_ODO_ROTATION, - { rot_device }, { rot_device_cov }); - this->kf->predict_and_observe(current_time, OBSERVATION_CAMERA_ODO_TRANSLATION, - { trans_device }, { trans_device_cov }); - this->observation_values_invalid["cameraOdometry"] *= DECAY; - this->camodo_yawrate_distribution = Vector2d(rot_device[2], rotate_std(this->device_from_calib, rot_calib_std)[2]); -} - -void Localizer::handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log) { - if (!this->is_timestamp_valid(current_time)) { - this->observation_timings_invalid = true; - return; - } - - if (log.getRpyCalib().size() > 0) { - auto live_calib = floatlist2vector(log.getRpyCalib()); - if ((live_calib.minCoeff() < -CALIB_RPY_SANITY_CHECK) || (live_calib.maxCoeff() > CALIB_RPY_SANITY_CHECK)) { - this->observation_values_invalid["liveCalibration"] += 1.0; - return; - } - - this->calib = live_calib; - this->device_from_calib = euler2rot(this->calib); - this->calib_from_device = this->device_from_calib.transpose(); - this->calibrated = log.getCalStatus() == cereal::LiveCalibrationData::Status::CALIBRATED; - this->observation_values_invalid["liveCalibration"] *= DECAY; - } -} - -void Localizer::reset_kalman(double current_time) { - const VectorXd &init_x = this->kf->get_initial_x(); - const MatrixXdr &init_P = this->kf->get_initial_P(); - this->reset_kalman(current_time, init_x, init_P); -} - -void Localizer::finite_check(double current_time) { - bool all_finite = this->kf->get_x().array().isFinite().all() or this->kf->get_P().array().isFinite().all(); - if (!all_finite) { - LOGE("Non-finite values detected, kalman reset"); - this->reset_kalman(current_time); - } -} - -void Localizer::time_check(double current_time) { - if (std::isnan(this->last_reset_time)) { - this->last_reset_time = current_time; - } - if (std::isnan(this->first_valid_log_time)) { - this->first_valid_log_time = current_time; - } - double filter_time = this->kf->get_filter_time(); - bool big_time_gap = !std::isnan(filter_time) && (current_time - filter_time > 10); - if (big_time_gap) { - LOGE("Time gap of over 10s detected, kalman reset"); - this->reset_kalman(current_time); - } -} - -void Localizer::update_reset_tracker() { - // reset tracker is tuned to trigger when over 1reset/10s over 2min period - if (this->is_gps_ok()) { - this->reset_tracker *= RESET_TRACKER_DECAY; - } else { - this->reset_tracker = 0.0; - } -} - -void Localizer::reset_kalman(double current_time, const VectorXd &init_orient, const VectorXd &init_pos, const VectorXd &init_vel, const MatrixXdr &init_pos_R, const MatrixXdr &init_vel_R) { - // too nonlinear to init on completely wrong - VectorXd current_x = this->kf->get_x(); - MatrixXdr current_P = this->kf->get_P(); - MatrixXdr init_P = this->kf->get_initial_P(); - const MatrixXdr &reset_orientation_P = this->kf->get_reset_orientation_P(); - int non_ecef_state_err_len = init_P.rows() - (STATE_ECEF_POS_ERR_LEN + STATE_ECEF_ORIENTATION_ERR_LEN + STATE_ECEF_VELOCITY_ERR_LEN); - - current_x.segment(STATE_ECEF_ORIENTATION_START) = init_orient; - current_x.segment(STATE_ECEF_VELOCITY_START) = init_vel; - current_x.segment(STATE_ECEF_POS_START) = init_pos; - - init_P.block(STATE_ECEF_POS_ERR_START, STATE_ECEF_POS_ERR_START).diagonal() = init_pos_R.diagonal(); - init_P.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_ORIENTATION_ERR_START).diagonal() = reset_orientation_P.diagonal(); - init_P.block(STATE_ECEF_VELOCITY_ERR_START, STATE_ECEF_VELOCITY_ERR_START).diagonal() = init_vel_R.diagonal(); - init_P.block(STATE_ANGULAR_VELOCITY_ERR_START, STATE_ANGULAR_VELOCITY_ERR_START, non_ecef_state_err_len, non_ecef_state_err_len).diagonal() = current_P.block(STATE_ANGULAR_VELOCITY_ERR_START, - STATE_ANGULAR_VELOCITY_ERR_START, non_ecef_state_err_len, non_ecef_state_err_len).diagonal(); - - this->reset_kalman(current_time, current_x, init_P); -} - -void Localizer::reset_kalman(double current_time, const VectorXd &init_x, const MatrixXdr &init_P) { - this->kf->init_state(init_x, init_P, current_time); - this->last_reset_time = current_time; - this->reset_tracker += 1.0; -} - -void Localizer::handle_msg_bytes(const char *data, const size_t size) { - AlignedBuffer aligned_buf; - - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(data, size)); - cereal::Event::Reader event = cmsg.getRoot(); - - this->handle_msg(event); -} - -void Localizer::handle_msg(const cereal::Event::Reader& log) { - double t = log.getLogMonoTime() * 1e-9; - this->time_check(t); - if (log.isAccelerometer()) { - this->handle_sensor(t, log.getAccelerometer()); - } else if (log.isGyroscope()) { - this->handle_sensor(t, log.getGyroscope()); - } else if (log.isGpsLocation()) { - this->handle_gps(t, log.getGpsLocation(), GPS_QUECTEL_SENSOR_TIME_OFFSET); - } else if (log.isGpsLocationExternal()) { - this->handle_gps(t, log.getGpsLocationExternal(), GPS_UBLOX_SENSOR_TIME_OFFSET); - //} else if (log.isGnssMeasurements()) { - // this->handle_gnss(t, log.getGnssMeasurements()); - } else if (log.isCarState()) { - this->handle_car_state(t, log.getCarState()); - } else if (log.isCameraOdometry()) { - this->handle_cam_odo(t, log.getCameraOdometry()); - } else if (log.isLiveCalibration()) { - this->handle_live_calib(t, log.getLiveCalibration()); - } - this->finite_check(); - this->update_reset_tracker(); -} - -kj::ArrayPtr Localizer::get_message_bytes(MessageBuilder& msg_builder, bool inputsOK, - bool sensorsOK, bool gpsOK, bool msgValid) { - cereal::Event::Builder evt = msg_builder.initEvent(); - evt.setValid(msgValid); - cereal::LiveLocationKalman::Builder liveLoc = evt.initLiveLocationKalman(); - this->build_live_location(liveLoc); - liveLoc.setSensorsOK(sensorsOK); - liveLoc.setGpsOK(gpsOK); - liveLoc.setInputsOK(inputsOK); - return msg_builder.toBytes(); -} - -bool Localizer::is_gps_ok() { - return (this->kf->get_filter_time() - this->last_gps_msg) < 2.0; -} - -bool Localizer::critical_services_valid(const std::map &critical_services) { - for (auto &kv : critical_services){ - if (kv.second >= INPUT_INVALID_THRESHOLD){ - return false; - } - } - return true; -} - -bool Localizer::is_timestamp_valid(double current_time) { - double filter_time = this->kf->get_filter_time(); - if (!std::isnan(filter_time) && ((filter_time - current_time) > MAX_FILTER_REWIND_TIME)) { - LOGE("Observation timestamp is older than the max rewind threshold of the filter"); - return false; - } - return true; -} - -void Localizer::determine_gps_mode(double current_time) { - // 1. If the pos_std is greater than what's not acceptable and localizer is in gps-mode, reset to no-gps-mode - // 2. If the pos_std is greater than what's not acceptable and localizer is in no-gps-mode, fake obs - // 3. If the pos_std is smaller than what's not acceptable, let gps-mode be whatever it is - VectorXd current_pos_std = this->kf->get_P().block(STATE_ECEF_POS_ERR_START, STATE_ECEF_POS_ERR_START).diagonal().array().sqrt(); - if (current_pos_std.norm() > SANE_GPS_UNCERTAINTY){ - if (this->gps_mode){ - this->gps_mode = false; - this->reset_kalman(current_time); - } else { - this->input_fake_gps_observations(current_time); - } - } -} - -void Localizer::configure_gnss_source(const LocalizerGnssSource &source) { - this->gnss_source = source; - if (source == LocalizerGnssSource::UBLOX) { - this->gps_std_factor = 10.0; - this->gps_variance_factor = 1.0; - this->gps_vertical_variance_factor = 1.0; - this->gps_time_offset = GPS_UBLOX_SENSOR_TIME_OFFSET; - } else { - this->gps_std_factor = 2.0; - this->gps_variance_factor = 0.0; - this->gps_vertical_variance_factor = 3.0; - this->gps_time_offset = GPS_QUECTEL_SENSOR_TIME_OFFSET; - } -} - -int Localizer::locationd_thread() { - Params params; - LocalizerGnssSource source; - const char* gps_location_socket; - if (params.getBool("UbloxAvailable")) { - source = LocalizerGnssSource::UBLOX; - gps_location_socket = "gpsLocationExternal"; - } else { - source = LocalizerGnssSource::QCOM; - gps_location_socket = "gpsLocation"; - } - - this->configure_gnss_source(source); - const std::initializer_list service_list = {gps_location_socket, "cameraOdometry", "liveCalibration", - "carState", "accelerometer", "gyroscope"}; - - SubMaster sm(service_list, {}, nullptr, {gps_location_socket}); - PubMaster pm({"liveLocationKalman"}); - - uint64_t cnt = 0; - bool filterInitialized = false; - const std::vector critical_input_services = {"cameraOdometry", "liveCalibration", "accelerometer", "gyroscope"}; - for (std::string service : critical_input_services) { - this->observation_values_invalid.insert({service, 0.0}); - } - - while (!do_exit) { - sm.update(); - if (filterInitialized){ - this->observation_timings_invalid_reset(); - for (const char* service : service_list) { - if (sm.updated(service) && sm.valid(service)){ - const cereal::Event::Reader log = sm[service]; - this->handle_msg(log); - } - } - } else { - filterInitialized = sm.allAliveAndValid(); - } - - const char* trigger_msg = "cameraOdometry"; - if (sm.updated(trigger_msg)) { - bool inputsOK = sm.allValid() && this->are_inputs_ok(); - bool gpsOK = this->is_gps_ok(); - bool sensorsOK = sm.allAliveAndValid({"accelerometer", "gyroscope"}); - - // Log time to first fix - if (gpsOK && std::isnan(this->ttff) && !std::isnan(this->first_valid_log_time)) { - this->ttff = std::max(1e-3, (sm[trigger_msg].getLogMonoTime() * 1e-9) - this->first_valid_log_time); - } - - MessageBuilder msg_builder; - kj::ArrayPtr bytes = this->get_message_bytes(msg_builder, inputsOK, sensorsOK, gpsOK, filterInitialized); - pm.send("liveLocationKalman", bytes.begin(), bytes.size()); - - if (cnt % 1200 == 0 && gpsOK) { // once a minute - VectorXd posGeo = this->get_position_geodetic(); - std::string lastGPSPosJSON = util::string_format( - "{\"latitude\": %.15f, \"longitude\": %.15f, \"altitude\": %.15f}", posGeo(0), posGeo(1), posGeo(2)); - params.putNonBlocking("LastGPSPosition", lastGPSPosJSON); - } - cnt++; - } - } - return 0; -} - -int main() { - util::set_realtime_priority(5); - - Localizer localizer; - return localizer.locationd_thread(); -} diff --git a/selfdrive/locationd/locationd.h b/selfdrive/locationd/locationd.h deleted file mode 100644 index 47c8bf5627bb608..000000000000000 --- a/selfdrive/locationd/locationd.h +++ /dev/null @@ -1,100 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/transformations/coordinates.hpp" -#include "common/transformations/orientation.hpp" -#include "common/params.h" -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" - -#include "system/sensord/sensors/constants.h" -#define VISION_DECIMATION 2 -#define SENSOR_DECIMATION 10 -#include "selfdrive/locationd/models/live_kf.h" - -#define POSENET_STD_HIST_HALF 20 - -enum LocalizerGnssSource { - UBLOX, QCOM -}; - -class Localizer { -public: - Localizer(LocalizerGnssSource gnss_source = LocalizerGnssSource::UBLOX); - - int locationd_thread(); - - void reset_kalman(double current_time = NAN); - void reset_kalman(double current_time, const Eigen::VectorXd &init_orient, const Eigen::VectorXd &init_pos, const Eigen::VectorXd &init_vel, const MatrixXdr &init_pos_R, const MatrixXdr &init_vel_R); - void reset_kalman(double current_time, const Eigen::VectorXd &init_x, const MatrixXdr &init_P); - void finite_check(double current_time = NAN); - void time_check(double current_time = NAN); - void update_reset_tracker(); - bool is_gps_ok(); - bool critical_services_valid(const std::map &critical_services); - bool is_timestamp_valid(double current_time); - void determine_gps_mode(double current_time); - bool are_inputs_ok(); - void observation_timings_invalid_reset(); - - kj::ArrayPtr get_message_bytes(MessageBuilder& msg_builder, - bool inputsOK, bool sensorsOK, bool gpsOK, bool msgValid); - void build_live_location(cereal::LiveLocationKalman::Builder& fix); - - Eigen::VectorXd get_position_geodetic(); - Eigen::VectorXd get_state(); - Eigen::VectorXd get_stdev(); - - void handle_msg_bytes(const char *data, const size_t size); - void handle_msg(const cereal::Event::Reader& log); - void handle_sensor(double current_time, const cereal::SensorEventData::Reader& log); - void handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset); - void handle_gnss(double current_time, const cereal::GnssMeasurements::Reader& log); - void handle_car_state(double current_time, const cereal::CarState::Reader& log); - void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log); - void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log); - - void input_fake_gps_observations(double current_time); - -private: - std::unique_ptr kf; - - Eigen::VectorXd calib; - MatrixXdr device_from_calib; - MatrixXdr calib_from_device; - bool calibrated = false; - - double car_speed = 0.0; - double last_reset_time = NAN; - std::deque posenet_stds; - - std::unique_ptr converter; - - int64_t unix_timestamp_millis = 0; - double reset_tracker = 0.0; - bool device_fell = false; - bool gps_mode = false; - double first_valid_log_time = NAN; - double ttff = NAN; - double last_gps_msg = 0; - LocalizerGnssSource gnss_source; - bool observation_timings_invalid = false; - std::map observation_values_invalid; - bool standstill = true; - int32_t orientation_reset_count = 0; - float gps_std_factor; - float gps_variance_factor; - float gps_vertical_variance_factor; - double gps_time_offset; - Eigen::VectorXd camodo_yawrate_distribution = Eigen::Vector2d(0.0, 10.0); // mean, std - - void configure_gnss_source(const LocalizerGnssSource &source); -}; diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py new file mode 100755 index 000000000000000..7f5541b8c295be4 --- /dev/null +++ b/selfdrive/locationd/locationd.py @@ -0,0 +1,320 @@ +#!/usr/bin/env python3 +import os +import json +import time +import capnp +import numpy as np +from enum import Enum +from collections import defaultdict + +from cereal import log, messaging +from openpilot.common.transformations.orientation import rot_from_euler +from openpilot.common.realtime import config_realtime_process +from openpilot.common.params import Params +from openpilot.selfdrive.locationd.helpers import rotate_std +from openpilot.selfdrive.locationd.models.pose_kf import PoseKalman, States +from openpilot.selfdrive.locationd.models.constants import ObservationKind, GENERATED_DIR + +ACCEL_SANITY_CHECK = 100.0 # m/s^2 +ROTATION_SANITY_CHECK = 10.0 # rad/s +TRANS_SANITY_CHECK = 200.0 # m/s +CALIB_RPY_SANITY_CHECK = 0.5 # rad (+- 30 deg) +MIN_STD_SANITY_CHECK = 1e-5 # m or rad +MAX_FILTER_REWIND_TIME = 0.8 # s +MAX_SENSOR_TIME_DIFF = 0.1 # s +YAWRATE_CROSS_ERR_CHECK_FACTOR = 30 +INPUT_INVALID_THRESHOLD = 0.5 +INPUT_INVALID_DECAY = 0.9993 # ~10 secs to resume after a bad input +POSENET_STD_INITIAL_VALUE = 10.0 +POSENET_STD_HIST_HALF = 20 + + +def init_xyz_measurement(measurement: capnp._DynamicStructBuilder, values: np.ndarray, stds: np.ndarray, valid: bool): + assert len(values) == len(stds) == 3 + measurement.x, measurement.y, measurement.z = map(float, values) + measurement.xStd, measurement.yStd, measurement.zStd = map(float, stds) + measurement.valid = valid + + +class HandleLogResult(Enum): + SUCCESS = 0 + TIMING_INVALID = 1 + INPUT_INVALID = 2 + SENSOR_SOURCE_INVALID = 3 + + +class LocationEstimator: + def __init__(self, debug: bool): + self.kf = PoseKalman(GENERATED_DIR, MAX_FILTER_REWIND_TIME) + + self.debug = debug + + self.posenet_stds = np.array([POSENET_STD_INITIAL_VALUE] * (POSENET_STD_HIST_HALF * 2)) + self.car_speed = 0.0 + self.camodo_yawrate_distribution = np.array([0.0, 10.0]) # mean, std + self.device_from_calib = np.eye(3) + + obs_kinds = [ObservationKind.PHONE_ACCEL, ObservationKind.PHONE_GYRO, ObservationKind.CAMERA_ODO_ROTATION, ObservationKind.CAMERA_ODO_TRANSLATION] + self.observations = {kind: np.zeros(3, dtype=np.float32) for kind in obs_kinds} + self.observation_errors = {kind: np.zeros(3, dtype=np.float32) for kind in obs_kinds} + + def reset(self, t: float, x_initial: np.ndarray = PoseKalman.initial_x, P_initial: np.ndarray = PoseKalman.initial_P): + self.kf.reset(t, x_initial, P_initial) + + def _validate_sensor_source(self, source: log.SensorEventData.SensorSource): + # some segments have two IMUs, ignore the second one + return source != log.SensorEventData.SensorSource.bmx055 + + def _validate_sensor_time(self, sensor_time: float, t: float): + # ignore empty readings + if sensor_time == 0: + return False + + # sensor time and log time should be close + sensor_time_invalid = abs(sensor_time - t) > MAX_SENSOR_TIME_DIFF + if sensor_time_invalid: + print("Sensor reading ignored, sensor timestamp more than 100ms off from log time") + return not sensor_time_invalid + + def _validate_timestamp(self, t: float): + kf_t = self.kf.t + invalid = not np.isnan(kf_t) and (kf_t - t) > MAX_FILTER_REWIND_TIME + if invalid: + print("Observation timestamp is older than the max rewind threshold of the filter") + return not invalid + + def _finite_check(self, t: float, new_x: np.ndarray, new_P: np.ndarray): + all_finite = np.isfinite(new_x).all() and np.isfinite(new_P).all() + if not all_finite: + print("Non-finite values detected, kalman reset") + self.reset(t) + + def handle_log(self, t: float, which: str, msg: capnp._DynamicStructReader) -> HandleLogResult: + new_x, new_P = None, None + if which == "accelerometer" and msg.which() == "acceleration": + sensor_time = msg.timestamp * 1e-9 + + if not self._validate_sensor_time(sensor_time, t) or not self._validate_timestamp(sensor_time): + return HandleLogResult.TIMING_INVALID + + if not self._validate_sensor_source(msg.source): + return HandleLogResult.SENSOR_SOURCE_INVALID + + v = msg.acceleration.v + meas = np.array([-v[2], -v[1], -v[0]]) + if np.linalg.norm(meas) >= ACCEL_SANITY_CHECK: + return HandleLogResult.INPUT_INVALID + + acc_res = self.kf.predict_and_observe(sensor_time, ObservationKind.PHONE_ACCEL, meas) + if acc_res is not None: + _, new_x, _, new_P, _, _, (acc_err,), _, _ = acc_res + self.observation_errors[ObservationKind.PHONE_ACCEL] = np.array(acc_err) + self.observations[ObservationKind.PHONE_ACCEL] = meas + + elif which == "gyroscope" and msg.which() == "gyroUncalibrated": + sensor_time = msg.timestamp * 1e-9 + + if not self._validate_sensor_time(sensor_time, t) or not self._validate_timestamp(sensor_time): + return HandleLogResult.TIMING_INVALID + + if not self._validate_sensor_source(msg.source): + return HandleLogResult.SENSOR_SOURCE_INVALID + + v = msg.gyroUncalibrated.v + meas = np.array([-v[2], -v[1], -v[0]]) + + gyro_bias = self.kf.x[States.GYRO_BIAS] + gyro_camodo_yawrate_err = np.abs((meas[2] - gyro_bias[2]) - self.camodo_yawrate_distribution[0]) + gyro_camodo_yawrate_err_threshold = YAWRATE_CROSS_ERR_CHECK_FACTOR * self.camodo_yawrate_distribution[1] + gyro_valid = gyro_camodo_yawrate_err < gyro_camodo_yawrate_err_threshold + + if np.linalg.norm(meas) >= ROTATION_SANITY_CHECK or not gyro_valid: + return HandleLogResult.INPUT_INVALID + + gyro_res = self.kf.predict_and_observe(sensor_time, ObservationKind.PHONE_GYRO, meas) + if gyro_res is not None: + _, new_x, _, new_P, _, _, (gyro_err,), _, _ = gyro_res + self.observation_errors[ObservationKind.PHONE_GYRO] = np.array(gyro_err) + self.observations[ObservationKind.PHONE_GYRO] = meas + + elif which == "carState": + self.car_speed = abs(msg.vEgo) + + elif which == "liveCalibration": + if len(msg.rpyCalib) > 0: + calib = np.array(msg.rpyCalib) + if calib.min() < -CALIB_RPY_SANITY_CHECK or calib.max() > CALIB_RPY_SANITY_CHECK: + return HandleLogResult.INPUT_INVALID + + self.device_from_calib = rot_from_euler(calib) + self.calibrated = msg.calStatus == log.LiveCalibrationData.Status.calibrated + + elif which == "cameraOdometry": + if not self._validate_timestamp(t): + return HandleLogResult.TIMING_INVALID + + rot_device = np.matmul(self.device_from_calib, np.array(msg.rot)) + trans_device = np.matmul(self.device_from_calib, np.array(msg.trans)) + + if np.linalg.norm(rot_device) > ROTATION_SANITY_CHECK or np.linalg.norm(trans_device) > TRANS_SANITY_CHECK: + return HandleLogResult.INPUT_INVALID + + rot_calib_std = np.array(msg.rotStd) + trans_calib_std = np.array(msg.transStd) + + if rot_calib_std.min() <= MIN_STD_SANITY_CHECK or trans_calib_std.min() <= MIN_STD_SANITY_CHECK: + return HandleLogResult.INPUT_INVALID + + if np.linalg.norm(rot_calib_std) > 10 * ROTATION_SANITY_CHECK or np.linalg.norm(trans_calib_std) > 10 * TRANS_SANITY_CHECK: + return HandleLogResult.INPUT_INVALID + + self.posenet_stds = np.roll(self.posenet_stds, -1) + self.posenet_stds[-1] = trans_calib_std[0] + + # Multiply by N to avoid to high certainty in kalman filter because of temporally correlated noise + rot_calib_std *= 10 + trans_calib_std *= 2 + + rot_device_std = rotate_std(self.device_from_calib, rot_calib_std) + trans_device_std = rotate_std(self.device_from_calib, trans_calib_std) + rot_device_noise = rot_device_std ** 2 + trans_device_noise = trans_device_std ** 2 + + cam_odo_rot_res = self.kf.predict_and_observe(t, ObservationKind.CAMERA_ODO_ROTATION, rot_device, rot_device_noise) + cam_odo_trans_res = self.kf.predict_and_observe(t, ObservationKind.CAMERA_ODO_TRANSLATION, trans_device, trans_device_noise) + self.camodo_yawrate_distribution = np.array([rot_device[2], rot_device_std[2]]) + if cam_odo_rot_res is not None: + _, new_x, _, new_P, _, _, (cam_odo_rot_err,), _, _ = cam_odo_rot_res + self.observation_errors[ObservationKind.CAMERA_ODO_ROTATION] = np.array(cam_odo_rot_err) + self.observations[ObservationKind.CAMERA_ODO_ROTATION] = rot_device + if cam_odo_trans_res is not None: + _, new_x, _, new_P, _, _, (cam_odo_trans_err,), _, _ = cam_odo_trans_res + self.observation_errors[ObservationKind.CAMERA_ODO_TRANSLATION] = np.array(cam_odo_trans_err) + self.observations[ObservationKind.CAMERA_ODO_TRANSLATION] = trans_device + + if new_x is not None and new_P is not None: + self._finite_check(t, new_x, new_P) + return HandleLogResult.SUCCESS + + def get_msg(self, sensors_valid: bool, inputs_valid: bool, filter_valid: bool): + state, cov = self.kf.x, self.kf.P + std = np.sqrt(np.diag(cov)) + + orientation_ned, orientation_ned_std = state[States.NED_ORIENTATION], std[States.NED_ORIENTATION] + velocity_device, velocity_device_std = state[States.DEVICE_VELOCITY], std[States.DEVICE_VELOCITY] + angular_velocity_device, angular_velocity_device_std = state[States.ANGULAR_VELOCITY], std[States.ANGULAR_VELOCITY] + acceleration_device, acceleration_device_std = state[States.ACCELERATION], std[States.ACCELERATION] + + msg = messaging.new_message("livePose") + msg.valid = filter_valid + + livePose = msg.livePose + init_xyz_measurement(livePose.orientationNED, orientation_ned, orientation_ned_std, filter_valid) + init_xyz_measurement(livePose.velocityDevice, velocity_device, velocity_device_std, filter_valid) + init_xyz_measurement(livePose.angularVelocityDevice, angular_velocity_device, angular_velocity_device_std, filter_valid) + init_xyz_measurement(livePose.accelerationDevice, acceleration_device, acceleration_device_std, filter_valid) + if self.debug: + livePose.debugFilterState.value = state.tolist() + livePose.debugFilterState.std = std.tolist() + livePose.debugFilterState.valid = filter_valid + livePose.debugFilterState.observations = [ + {'kind': k, 'value': self.observations[k].tolist(), 'error': self.observation_errors[k].tolist()} + for k in self.observations.keys() + ] + + old_mean = np.mean(self.posenet_stds[:POSENET_STD_HIST_HALF]) + new_mean = np.mean(self.posenet_stds[POSENET_STD_HIST_HALF:]) + std_spike = (new_mean / old_mean) > 4.0 and new_mean > 7.0 + + livePose.inputsOK = inputs_valid + livePose.posenetOK = not std_spike or self.car_speed <= 5.0 + livePose.sensorsOK = sensors_valid + + return msg + + +def sensor_all_checks(acc_msgs, gyro_msgs, sensor_valid, sensor_recv_time, sensor_alive, simulation): + cur_time = time.monotonic() + for which, msgs in [("accelerometer", acc_msgs), ("gyroscope", gyro_msgs)]: + if len(msgs) > 0: + sensor_valid[which] = msgs[-1].valid + sensor_recv_time[which] = cur_time + + if not simulation: + sensor_alive[which] = (cur_time - sensor_recv_time[which]) < 0.1 + else: + sensor_alive[which] = len(msgs) > 0 + + return all(sensor_alive.values()) and all(sensor_valid.values()) + + +def main(): + config_realtime_process([0, 1, 2, 3], 5) + + DEBUG = bool(int(os.getenv("DEBUG", "0"))) + SIMULATION = bool(int(os.getenv("SIMULATION", "0"))) + + pm = messaging.PubMaster(['livePose']) + sm = messaging.SubMaster(['carState', 'liveCalibration', 'cameraOdometry'], poll='cameraOdometry') + # separate sensor sockets for efficiency + sensor_sockets = [messaging.sub_sock(which, timeout=20) for which in ['accelerometer', 'gyroscope']] + sensor_alive, sensor_valid, sensor_recv_time = defaultdict(bool), defaultdict(bool), defaultdict(float) + + params = Params() + + estimator = LocationEstimator(DEBUG) + + filter_initialized = False + critcal_services = ["accelerometer", "gyroscope", "liveCalibration", "cameraOdometry"] + observation_timing_invalid = False + observation_input_invalid = defaultdict(int) + + initial_pose = params.get("LocationFilterInitialState") + if initial_pose is not None: + initial_pose = json.loads(initial_pose) + x_initial = np.array(initial_pose["x"], dtype=np.float64) + P_initial = np.diag(np.array(initial_pose["P"], dtype=np.float64)) + estimator.reset(None, x_initial, P_initial) + + while True: + sm.update() + + acc_msgs, gyro_msgs = (messaging.drain_sock(sock) for sock in sensor_sockets) + + if filter_initialized: + observation_timing_invalid = False + + msgs = [] + for msg in acc_msgs + gyro_msgs: + t, valid, which, data = msg.logMonoTime, msg.valid, msg.which(), getattr(msg, msg.which()) + msgs.append((t, valid, which, data)) + for which, updated in sm.updated.items(): + if not updated: + continue + t, valid, data = sm.logMonoTime[which], sm.valid[which], sm[which] + msgs.append((t, valid, which, data)) + + for log_mono_time, valid, which, msg in sorted(msgs, key=lambda x: x[0]): + if valid: + t = log_mono_time * 1e-9 + res = estimator.handle_log(t, which, msg) + if res == HandleLogResult.TIMING_INVALID: + observation_timing_invalid = True + elif res == HandleLogResult.INPUT_INVALID: + observation_input_invalid[which] += 1 + else: + observation_input_invalid[which] *= INPUT_INVALID_DECAY + else: + filter_initialized = sm.all_checks() and sensor_all_checks(acc_msgs, gyro_msgs, sensor_valid, sensor_recv_time, sensor_alive, SIMULATION) + + if sm.updated["cameraOdometry"]: + critical_service_inputs_valid = all(observation_input_invalid[s] < INPUT_INVALID_THRESHOLD for s in critcal_services) + inputs_valid = sm.all_valid() and critical_service_inputs_valid and not observation_timing_invalid + sensors_valid = sensor_all_checks(acc_msgs, gyro_msgs, sensor_valid, sensor_recv_time, sensor_alive, SIMULATION) + + msg = estimator.get_msg(sensors_valid, inputs_valid, filter_initialized) + pm.send("livePose", msg) + + +if __name__ == "__main__": + main() diff --git a/selfdrive/locationd/models/live_kf.cc b/selfdrive/locationd/models/live_kf.cc deleted file mode 100644 index fc3bfb72461697f..000000000000000 --- a/selfdrive/locationd/models/live_kf.cc +++ /dev/null @@ -1,122 +0,0 @@ -#include "selfdrive/locationd/models/live_kf.h" - -using namespace EKFS; -using namespace Eigen; - -Eigen::Map get_mapvec(const Eigen::VectorXd &vec) { - return Eigen::Map((double*)vec.data(), vec.rows(), vec.cols()); -} - -Eigen::Map get_mapmat(const MatrixXdr &mat) { - return Eigen::Map((double*)mat.data(), mat.rows(), mat.cols()); -} - -std::vector> get_vec_mapvec(const std::vector &vec_vec) { - std::vector> res; - for (const Eigen::VectorXd &vec : vec_vec) { - res.push_back(get_mapvec(vec)); - } - return res; -} - -std::vector> get_vec_mapmat(const std::vector &mat_vec) { - std::vector> res; - for (const MatrixXdr &mat : mat_vec) { - res.push_back(get_mapmat(mat)); - } - return res; -} - -LiveKalman::LiveKalman() { - this->dim_state = live_initial_x.rows(); - this->dim_state_err = live_initial_P_diag.rows(); - - this->initial_x = live_initial_x; - this->initial_P = live_initial_P_diag.asDiagonal(); - this->fake_gps_pos_cov = live_fake_gps_pos_cov_diag.asDiagonal(); - this->fake_gps_vel_cov = live_fake_gps_vel_cov_diag.asDiagonal(); - this->reset_orientation_P = live_reset_orientation_diag.asDiagonal(); - this->Q = live_Q_diag.asDiagonal(); - for (auto& pair : live_obs_noise_diag) { - this->obs_noise[pair.first] = pair.second.asDiagonal(); - } - - // init filter - this->filter = std::make_shared(this->name, get_mapmat(this->Q), get_mapvec(this->initial_x), - get_mapmat(initial_P), this->dim_state, this->dim_state_err, 0, 0, 0, std::vector(), - std::vector{3}, std::vector(), 0.8); -} - -void LiveKalman::init_state(const VectorXd &state, const VectorXd &covs_diag, double filter_time) { - MatrixXdr covs = covs_diag.asDiagonal(); - this->filter->init_state(get_mapvec(state), get_mapmat(covs), filter_time); -} - -void LiveKalman::init_state(const VectorXd &state, const MatrixXdr &covs, double filter_time) { - this->filter->init_state(get_mapvec(state), get_mapmat(covs), filter_time); -} - -void LiveKalman::init_state(const VectorXd &state, double filter_time) { - MatrixXdr covs = this->filter->covs(); - this->filter->init_state(get_mapvec(state), get_mapmat(covs), filter_time); -} - -VectorXd LiveKalman::get_x() { - return this->filter->state(); -} - -MatrixXdr LiveKalman::get_P() { - return this->filter->covs(); -} - -double LiveKalman::get_filter_time() { - return this->filter->get_filter_time(); -} - -std::vector LiveKalman::get_R(int kind, int n) { - std::vector R; - for (int i = 0; i < n; i++) { - R.push_back(this->obs_noise[kind]); - } - return R; -} - -std::optional LiveKalman::predict_and_observe(double t, int kind, const std::vector &meas, std::vector R) { - std::optional r; - if (R.size() == 0) { - R = this->get_R(kind, meas.size()); - } - r = this->filter->predict_and_update_batch(t, kind, get_vec_mapvec(meas), get_vec_mapmat(R)); - return r; -} - -void LiveKalman::predict(double t) { - this->filter->predict(t); -} - -const Eigen::VectorXd &LiveKalman::get_initial_x() { - return this->initial_x; -} - -const MatrixXdr &LiveKalman::get_initial_P() { - return this->initial_P; -} - -const MatrixXdr &LiveKalman::get_fake_gps_pos_cov() { - return this->fake_gps_pos_cov; -} - -const MatrixXdr &LiveKalman::get_fake_gps_vel_cov() { - return this->fake_gps_vel_cov; -} - -const MatrixXdr &LiveKalman::get_reset_orientation_P() { - return this->reset_orientation_P; -} - -MatrixXdr LiveKalman::H(const VectorXd &in) { - assert(in.size() == 6); - Matrix res; - this->filter->get_extra_routine("H")((double*)in.data(), res.data()); - return res; -} diff --git a/selfdrive/locationd/models/live_kf.h b/selfdrive/locationd/models/live_kf.h deleted file mode 100644 index e4b3e326b3c6140..000000000000000 --- a/selfdrive/locationd/models/live_kf.h +++ /dev/null @@ -1,66 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include -#include - -#include "generated/live_kf_constants.h" -#include "rednose/helpers/ekf_sym.h" - -#define EARTH_GM 3.986005e14 // m^3/s^2 (gravitational constant * mass of earth) - -using namespace EKFS; - -Eigen::Map get_mapvec(const Eigen::VectorXd &vec); -Eigen::Map get_mapmat(const MatrixXdr &mat); -std::vector> get_vec_mapvec(const std::vector &vec_vec); -std::vector> get_vec_mapmat(const std::vector &mat_vec); - -class LiveKalman { -public: - LiveKalman(); - - void init_state(const Eigen::VectorXd &state, const Eigen::VectorXd &covs_diag, double filter_time); - void init_state(const Eigen::VectorXd &state, const MatrixXdr &covs, double filter_time); - void init_state(const Eigen::VectorXd &state, double filter_time); - - Eigen::VectorXd get_x(); - MatrixXdr get_P(); - double get_filter_time(); - std::vector get_R(int kind, int n); - - std::optional predict_and_observe(double t, int kind, const std::vector &meas, std::vector R = {}); - std::optional predict_and_update_odo_speed(std::vector speed, double t, int kind); - std::optional predict_and_update_odo_trans(std::vector trans, double t, int kind); - std::optional predict_and_update_odo_rot(std::vector rot, double t, int kind); - void predict(double t); - - const Eigen::VectorXd &get_initial_x(); - const MatrixXdr &get_initial_P(); - const MatrixXdr &get_fake_gps_pos_cov(); - const MatrixXdr &get_fake_gps_vel_cov(); - const MatrixXdr &get_reset_orientation_P(); - - MatrixXdr H(const Eigen::VectorXd &in); - -private: - std::string name = "live"; - - std::shared_ptr filter; - - int dim_state; - int dim_state_err; - - Eigen::VectorXd initial_x; - MatrixXdr initial_P; - MatrixXdr fake_gps_pos_cov; - MatrixXdr fake_gps_vel_cov; - MatrixXdr reset_orientation_P; - MatrixXdr Q; // process noise - std::unordered_map obs_noise; -}; diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py deleted file mode 100755 index 0cc3eca61dd1c8c..000000000000000 --- a/selfdrive/locationd/models/live_kf.py +++ /dev/null @@ -1,242 +0,0 @@ -#!/usr/bin/env python3 - -import sys -import os -import numpy as np - -from openpilot.selfdrive.locationd.models.constants import ObservationKind - -import sympy as sp -import inspect -from rednose.helpers.sympy_helpers import euler_rotate, quat_matrix_r, quat_rotate -from rednose.helpers.ekf_sym import gen_code - -EARTH_GM = 3.986005e14 # m^3/s^2 (gravitational constant * mass of earth) - - -def numpy2eigenstring(arr): - assert(len(arr.shape) == 1) - arr_str = np.array2string(arr, precision=20, separator=',')[1:-1].replace(' ', '').replace('\n', '') - return f"(Eigen::VectorXd({len(arr)}) << {arr_str}).finished()" - - -class States: - ECEF_POS = slice(0, 3) # x, y and z in ECEF in meters - ECEF_ORIENTATION = slice(3, 7) # quat for pose of phone in ecef - ECEF_VELOCITY = slice(7, 10) # ecef velocity in m/s - ANGULAR_VELOCITY = slice(10, 13) # roll, pitch and yaw rates in device frame in radians/s - GYRO_BIAS = slice(13, 16) # roll, pitch and yaw biases - ACCELERATION = slice(16, 19) # Acceleration in device frame in m/s**2 - ACC_BIAS = slice(19, 22) # Acceletometer bias in m/s**2 - - # Error-state has different slices because it is an ESKF - ECEF_POS_ERR = slice(0, 3) - ECEF_ORIENTATION_ERR = slice(3, 6) # euler angles for orientation error - ECEF_VELOCITY_ERR = slice(6, 9) - ANGULAR_VELOCITY_ERR = slice(9, 12) - GYRO_BIAS_ERR = slice(12, 15) - ACCELERATION_ERR = slice(15, 18) - ACC_BIAS_ERR = slice(18, 21) - - -class LiveKalman: - name = 'live' - - initial_x = np.array([3.88e6, -3.37e6, 3.76e6, - 0.42254641, -0.31238054, -0.83602975, -0.15788347, # NED [0,0,0] -> ECEF Quat - 0, 0, 0, - 0, 0, 0, - 0, 0, 0, - 0, 0, 0, - 0, 0, 0]) - - # state covariance - initial_P_diag = np.array([10**2, 10**2, 10**2, - 0.01**2, 0.01**2, 0.01**2, - 10**2, 10**2, 10**2, - 1**2, 1**2, 1**2, - 1**2, 1**2, 1**2, - 100**2, 100**2, 100**2, - 0.01**2, 0.01**2, 0.01**2]) - - # state covariance when resetting midway in a segment - reset_orientation_diag = np.array([1**2, 1**2, 1**2]) - - # fake observation covariance, to ensure the uncertainty estimate of the filter is under control - fake_gps_pos_cov_diag = np.array([1000**2, 1000**2, 1000**2]) - fake_gps_vel_cov_diag = np.array([10**2, 10**2, 10**2]) - - # process noise - Q_diag = np.array([0.03**2, 0.03**2, 0.03**2, - 0.001**2, 0.001**2, 0.001**2, - 0.01**2, 0.01**2, 0.01**2, - 0.1**2, 0.1**2, 0.1**2, - (0.005 / 100)**2, (0.005 / 100)**2, (0.005 / 100)**2, - 3**2, 3**2, 3**2, - 0.005**2, 0.005**2, 0.005**2]) - - obs_noise_diag = {ObservationKind.PHONE_GYRO: np.array([0.025**2, 0.025**2, 0.025**2]), - ObservationKind.PHONE_ACCEL: np.array([.5**2, .5**2, .5**2]), - ObservationKind.CAMERA_ODO_ROTATION: np.array([0.05**2, 0.05**2, 0.05**2]), - ObservationKind.NO_ROT: np.array([0.005**2, 0.005**2, 0.005**2]), - ObservationKind.NO_ACCEL: np.array([0.05**2, 0.05**2, 0.05**2]), - ObservationKind.ECEF_POS: np.array([5**2, 5**2, 5**2]), - ObservationKind.ECEF_VEL: np.array([.5**2, .5**2, .5**2]), - ObservationKind.ECEF_ORIENTATION_FROM_GPS: np.array([.2**2, .2**2, .2**2, .2**2])} - - @staticmethod - def generate_code(generated_dir): - name = LiveKalman.name - dim_state = LiveKalman.initial_x.shape[0] - dim_state_err = LiveKalman.initial_P_diag.shape[0] - - state_sym = sp.MatrixSymbol('state', dim_state, 1) - state = sp.Matrix(state_sym) - x, y, z = state[States.ECEF_POS, :] - q = state[States.ECEF_ORIENTATION, :] - v = state[States.ECEF_VELOCITY, :] - vx, vy, vz = v - omega = state[States.ANGULAR_VELOCITY, :] - vroll, vpitch, vyaw = omega - roll_bias, pitch_bias, yaw_bias = state[States.GYRO_BIAS, :] - acceleration = state[States.ACCELERATION, :] - acc_bias = state[States.ACC_BIAS, :] - - dt = sp.Symbol('dt') - - # calibration and attitude rotation matrices - quat_rot = quat_rotate(*q) - - # Got the quat predict equations from here - # A New Quaternion-Based Kalman Filter for - # Real-Time Attitude Estimation Using the Two-Step - # Geometrically-Intuitive Correction Algorithm - A = 0.5 * sp.Matrix([[0, -vroll, -vpitch, -vyaw], - [vroll, 0, vyaw, -vpitch], - [vpitch, -vyaw, 0, vroll], - [vyaw, vpitch, -vroll, 0]]) - q_dot = A * q - - # Time derivative of the state as a function of state - state_dot = sp.Matrix(np.zeros((dim_state, 1))) - state_dot[States.ECEF_POS, :] = v - state_dot[States.ECEF_ORIENTATION, :] = q_dot - state_dot[States.ECEF_VELOCITY, 0] = quat_rot * acceleration - - # Basic descretization, 1st order intergrator - # Can be pretty bad if dt is big - f_sym = state + dt * state_dot - - state_err_sym = sp.MatrixSymbol('state_err', dim_state_err, 1) - state_err = sp.Matrix(state_err_sym) - quat_err = state_err[States.ECEF_ORIENTATION_ERR, :] - v_err = state_err[States.ECEF_VELOCITY_ERR, :] - omega_err = state_err[States.ANGULAR_VELOCITY_ERR, :] - acceleration_err = state_err[States.ACCELERATION_ERR, :] - - # Time derivative of the state error as a function of state error and state - quat_err_matrix = euler_rotate(quat_err[0], quat_err[1], quat_err[2]) - q_err_dot = quat_err_matrix * quat_rot * (omega + omega_err) - state_err_dot = sp.Matrix(np.zeros((dim_state_err, 1))) - state_err_dot[States.ECEF_POS_ERR, :] = v_err - state_err_dot[States.ECEF_ORIENTATION_ERR, :] = q_err_dot - state_err_dot[States.ECEF_VELOCITY_ERR, :] = quat_err_matrix * quat_rot * (acceleration + acceleration_err) - f_err_sym = state_err + dt * state_err_dot - - # Observation matrix modifier - H_mod_sym = sp.Matrix(np.zeros((dim_state, dim_state_err))) - H_mod_sym[States.ECEF_POS, States.ECEF_POS_ERR] = np.eye(States.ECEF_POS.stop - States.ECEF_POS.start) - H_mod_sym[States.ECEF_ORIENTATION, States.ECEF_ORIENTATION_ERR] = 0.5 * quat_matrix_r(state[3:7])[:, 1:] - H_mod_sym[States.ECEF_ORIENTATION.stop:, States.ECEF_ORIENTATION_ERR.stop:] = np.eye(dim_state - States.ECEF_ORIENTATION.stop) - - # these error functions are defined so that say there - # is a nominal x and true x: - # true x = err_function(nominal x, delta x) - # delta x = inv_err_function(nominal x, true x) - nom_x = sp.MatrixSymbol('nom_x', dim_state, 1) - true_x = sp.MatrixSymbol('true_x', dim_state, 1) - delta_x = sp.MatrixSymbol('delta_x', dim_state_err, 1) - - err_function_sym = sp.Matrix(np.zeros((dim_state, 1))) - delta_quat = sp.Matrix(np.ones(4)) - delta_quat[1:, :] = sp.Matrix(0.5 * delta_x[States.ECEF_ORIENTATION_ERR, :]) - err_function_sym[States.ECEF_POS, :] = sp.Matrix(nom_x[States.ECEF_POS, :] + delta_x[States.ECEF_POS_ERR, :]) - err_function_sym[States.ECEF_ORIENTATION, 0] = quat_matrix_r(nom_x[States.ECEF_ORIENTATION, 0]) * delta_quat - err_function_sym[States.ECEF_ORIENTATION.stop:, :] = sp.Matrix(nom_x[States.ECEF_ORIENTATION.stop:, :] + delta_x[States.ECEF_ORIENTATION_ERR.stop:, :]) - - inv_err_function_sym = sp.Matrix(np.zeros((dim_state_err, 1))) - inv_err_function_sym[States.ECEF_POS_ERR, 0] = sp.Matrix(-nom_x[States.ECEF_POS, 0] + true_x[States.ECEF_POS, 0]) - delta_quat = quat_matrix_r(nom_x[States.ECEF_ORIENTATION, 0]).T * true_x[States.ECEF_ORIENTATION, 0] - inv_err_function_sym[States.ECEF_ORIENTATION_ERR, 0] = sp.Matrix(2 * delta_quat[1:]) - inv_err_function_sym[States.ECEF_ORIENTATION_ERR.stop:, 0] = sp.Matrix(-nom_x[States.ECEF_ORIENTATION.stop:, 0] + true_x[States.ECEF_ORIENTATION.stop:, 0]) - - eskf_params = [[err_function_sym, nom_x, delta_x], - [inv_err_function_sym, nom_x, true_x], - H_mod_sym, f_err_sym, state_err_sym] - # - # Observation functions - # - h_gyro_sym = sp.Matrix([ - vroll + roll_bias, - vpitch + pitch_bias, - vyaw + yaw_bias]) - - pos = sp.Matrix([x, y, z]) - gravity = quat_rot.T * ((EARTH_GM / ((x**2 + y**2 + z**2)**(3.0 / 2.0))) * pos) - h_acc_sym = (gravity + acceleration + acc_bias) - h_acc_stationary_sym = acceleration - h_phone_rot_sym = sp.Matrix([vroll, vpitch, vyaw]) - h_pos_sym = sp.Matrix([x, y, z]) - h_vel_sym = sp.Matrix([vx, vy, vz]) - h_orientation_sym = q - h_relative_motion = sp.Matrix(quat_rot.T * v) - - obs_eqs = [[h_gyro_sym, ObservationKind.PHONE_GYRO, None], - [h_phone_rot_sym, ObservationKind.NO_ROT, None], - [h_acc_sym, ObservationKind.PHONE_ACCEL, None], - [h_pos_sym, ObservationKind.ECEF_POS, None], - [h_vel_sym, ObservationKind.ECEF_VEL, None], - [h_orientation_sym, ObservationKind.ECEF_ORIENTATION_FROM_GPS, None], - [h_relative_motion, ObservationKind.CAMERA_ODO_TRANSLATION, None], - [h_phone_rot_sym, ObservationKind.CAMERA_ODO_ROTATION, None], - [h_acc_stationary_sym, ObservationKind.NO_ACCEL, None]] - - # this returns a sympy routine for the jacobian of the observation function of the local vel - in_vec = sp.MatrixSymbol('in_vec', 6, 1) # roll, pitch, yaw, vx, vy, vz - h = euler_rotate(in_vec[0], in_vec[1], in_vec[2]).T * (sp.Matrix([in_vec[3], in_vec[4], in_vec[5]])) - extra_routines = [('H', h.jacobian(in_vec), [in_vec])] - - gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state_err, eskf_params, extra_routines=extra_routines) - - # write constants to extra header file for use in cpp - live_kf_header = "#pragma once\n\n" - live_kf_header += "#include \n" - live_kf_header += "#include \n\n" - for state, slc in inspect.getmembers(States, lambda x: isinstance(x, slice)): - assert(slc.step is None) # unsupported - live_kf_header += f'#define STATE_{state}_START {slc.start}\n' - live_kf_header += f'#define STATE_{state}_END {slc.stop}\n' - live_kf_header += f'#define STATE_{state}_LEN {slc.stop - slc.start}\n' - live_kf_header += "\n" - - for kind, val in inspect.getmembers(ObservationKind, lambda x: isinstance(x, int)): - live_kf_header += f'#define OBSERVATION_{kind} {val}\n' - live_kf_header += "\n" - - live_kf_header += f"static const Eigen::VectorXd live_initial_x = {numpy2eigenstring(LiveKalman.initial_x)};\n" - live_kf_header += f"static const Eigen::VectorXd live_initial_P_diag = {numpy2eigenstring(LiveKalman.initial_P_diag)};\n" - live_kf_header += f"static const Eigen::VectorXd live_fake_gps_pos_cov_diag = {numpy2eigenstring(LiveKalman.fake_gps_pos_cov_diag)};\n" - live_kf_header += f"static const Eigen::VectorXd live_fake_gps_vel_cov_diag = {numpy2eigenstring(LiveKalman.fake_gps_vel_cov_diag)};\n" - live_kf_header += f"static const Eigen::VectorXd live_reset_orientation_diag = {numpy2eigenstring(LiveKalman.reset_orientation_diag)};\n" - live_kf_header += f"static const Eigen::VectorXd live_Q_diag = {numpy2eigenstring(LiveKalman.Q_diag)};\n" - live_kf_header += "static const std::unordered_map> live_obs_noise_diag = {\n" - for kind, noise in LiveKalman.obs_noise_diag.items(): - live_kf_header += f" {{ {kind}, {numpy2eigenstring(noise)} }},\n" - live_kf_header += "};\n\n" - - open(os.path.join(generated_dir, "live_kf_constants.h"), 'w').write(live_kf_header) - - -if __name__ == "__main__": - generated_dir = sys.argv[2] - LiveKalman.generate_code(generated_dir) diff --git a/selfdrive/locationd/models/pose_kf.py b/selfdrive/locationd/models/pose_kf.py new file mode 100755 index 000000000000000..df63518441e1969 --- /dev/null +++ b/selfdrive/locationd/models/pose_kf.py @@ -0,0 +1,138 @@ +#!/usr/bin/env python3 + +import sys +import numpy as np + +from openpilot.selfdrive.locationd.models.constants import ObservationKind + +if __name__=="__main__": + import sympy as sp + from rednose.helpers.ekf_sym import gen_code + from rednose.helpers.sympy_helpers import euler_rotate, rot_to_euler +else: + from rednose.helpers.ekf_sym_pyx import EKF_sym_pyx + +EARTH_G = 9.81 + + +class States: + NED_ORIENTATION = slice(0, 3) # roll, pitch, yaw in rad + DEVICE_VELOCITY = slice(3, 6) # ned velocity in m/s + ANGULAR_VELOCITY = slice(6, 9) # roll, pitch and yaw rates in rad/s + GYRO_BIAS = slice(9, 12) # roll, pitch and yaw gyroscope biases in rad/s + ACCELERATION = slice(12, 15) # acceleration in device frame in m/s**2 + ACCEL_BIAS = slice(15, 18) # Acceletometer bias in m/s**2 + + +class PoseKalman: + name = "pose" + + # state + initial_x = np.array([0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0]) + # state covariance + initial_P = np.diag([0.01**2, 0.01**2, 0.01**2, + 10**2, 10**2, 10**2, + 1**2, 1**2, 1**2, + 1**2, 1**2, 1**2, + 100**2, 100**2, 100**2, + 0.01**2, 0.01**2, 0.01**2]) + + # process noise + Q = np.diag([0.001**2, 0.001**2, 0.001**2, + 0.01**2, 0.01**2, 0.01**2, + 0.1**2, 0.1**2, 0.1**2, + (0.005 / 100)**2, (0.005 / 100)**2, (0.005 / 100)**2, + 3**2, 3**2, 3**2, + 0.005**2, 0.005**2, 0.005**2]) + + obs_noise = {ObservationKind.PHONE_GYRO: np.array([0.025**2, 0.025**2, 0.025**2]), + ObservationKind.PHONE_ACCEL: np.array([.5**2, .5**2, .5**2]), + ObservationKind.CAMERA_ODO_TRANSLATION: np.array([0.5**2, 0.5**2, 0.5**2]), + ObservationKind.CAMERA_ODO_ROTATION: np.array([0.05**2, 0.05**2, 0.05**2])} + + @staticmethod + def generate_code(generated_dir): + name = PoseKalman.name + dim_state = PoseKalman.initial_x.shape[0] + dim_state_err = PoseKalman.initial_P.shape[0] + + state_sym = sp.MatrixSymbol('state', dim_state, 1) + state = sp.Matrix(state_sym) + roll, pitch, yaw = state[States.NED_ORIENTATION, :] + velocity = state[States.DEVICE_VELOCITY, :] + angular_velocity = state[States.ANGULAR_VELOCITY, :] + vroll, vpitch, vyaw = angular_velocity + gyro_bias = state[States.GYRO_BIAS, :] + acceleration = state[States.ACCELERATION, :] + acc_bias = state[States.ACCEL_BIAS, :] + + dt = sp.Symbol('dt') + + ned_from_device = euler_rotate(roll, pitch, yaw) + device_from_ned = ned_from_device.T + + state_dot = sp.Matrix(np.zeros((dim_state, 1))) + state_dot[States.DEVICE_VELOCITY, :] = acceleration + + f_sym = state + dt * state_dot + device_from_device_t1 = euler_rotate(dt*vroll, dt*vpitch, dt*vyaw) + ned_from_device_t1 = ned_from_device * device_from_device_t1 + f_sym[States.NED_ORIENTATION, :] = rot_to_euler(ned_from_device_t1) + + centripetal_acceleration = angular_velocity.cross(velocity) + gravity = sp.Matrix([0, 0, -EARTH_G]) + h_gyro_sym = angular_velocity + gyro_bias + h_acc_sym = device_from_ned * gravity + acceleration + centripetal_acceleration + acc_bias + h_phone_rot_sym = angular_velocity + h_relative_motion_sym = velocity + obs_eqs = [ + [h_gyro_sym, ObservationKind.PHONE_GYRO, None], + [h_acc_sym, ObservationKind.PHONE_ACCEL, None], + [h_relative_motion_sym, ObservationKind.CAMERA_ODO_TRANSLATION, None], + [h_phone_rot_sym, ObservationKind.CAMERA_ODO_ROTATION, None], + ] + gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state_err) + + def __init__(self, generated_dir, max_rewind_age): + dim_state, dim_state_err = PoseKalman.initial_x.shape[0], PoseKalman.initial_P.shape[0] + self.filter = EKF_sym_pyx(generated_dir, self.name, PoseKalman.Q, PoseKalman.initial_x, PoseKalman.initial_P, + dim_state, dim_state_err, max_rewind_age=max_rewind_age) + + @property + def x(self): + return self.filter.state() + + @property + def P(self): + return self.filter.covs() + + @property + def t(self): + return self.filter.get_filter_time() + + def predict_and_observe(self, t, kind, data, obs_noise=None): + data = np.atleast_2d(data) + if obs_noise is None: + obs_noise = self.obs_noise[kind] + R = self._get_R(len(data), obs_noise) + return self.filter.predict_and_update_batch(t, kind, data, R) + + def reset(self, t, x_init, P_init): + self.filter.init_state(x_init, P_init, t) + + def _get_R(self, n, obs_noise): + dim = obs_noise.shape[0] + R = np.zeros((n, dim, dim)) + for i in range(n): + R[i, :, :] = np.diag(obs_noise) + return R + + +if __name__ == "__main__": + generated_dir = sys.argv[2] + PoseKalman.generate_code(generated_dir) diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index d124eb5f059b1c1..19ded3b4f7176be 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -5,13 +5,13 @@ import numpy as np import cereal.messaging as messaging -from cereal import car -from cereal import log +from cereal import car, log 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.selfdrive.locationd.helpers import PoseCalibrator, Pose from openpilot.common.swaglog import cloudlog @@ -40,6 +40,8 @@ def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset, P_initial=No self.active = False + self.calibrator = PoseCalibrator() + self.speed = 0.0 self.yaw_rate = 0.0 self.yaw_rate_std = 0.0 @@ -48,12 +50,13 @@ def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset, P_initial=No self.roll_valid = False def handle_log(self, t, which, msg): - if which == 'liveLocationKalman': - self.yaw_rate = msg.angularVelocityCalibrated.value[2] - self.yaw_rate_std = msg.angularVelocityCalibrated.std[2] + if which == 'livePose': + device_pose = Pose.from_live_pose(msg) + calibrated_pose = self.calibrator.build_calibrated_pose(device_pose) + self.yaw_rate, self.yaw_rate_std = calibrated_pose.angular_velocity.z, calibrated_pose.angular_velocity.z_std - localizer_roll = msg.orientationNED.value[0] - localizer_roll_std = np.radians(1) if np.isnan(msg.orientationNED.std[0]) else msg.orientationNED.std[0] + localizer_roll, localizer_roll_std = device_pose.orientation.x, device_pose.orientation.x_std + localizer_roll_std = np.radians(1) if np.isnan(localizer_roll_std) else localizer_roll_std self.roll_valid = (localizer_roll_std < ROLL_STD_MAX) and (ROLL_MIN < localizer_roll < ROLL_MAX) and msg.sensorsOK if self.roll_valid: roll = localizer_roll @@ -65,7 +68,7 @@ def handle_log(self, t, which, msg): roll_std = np.radians(10.0) self.roll = clip(roll, self.roll - ROLL_MAX_DELTA, self.roll + ROLL_MAX_DELTA) - yaw_rate_valid = msg.angularVelocityCalibrated.valid + yaw_rate_valid = msg.angularVelocityDevice.valid and self.calibrator.calib_valid yaw_rate_valid = yaw_rate_valid and 0 < self.yaw_rate_std < 10 # rad/s yaw_rate_valid = yaw_rate_valid and abs(self.yaw_rate) < 1 # rad/s @@ -92,6 +95,9 @@ def handle_log(self, t, which, msg): self.kf.predict_and_observe(t, ObservationKind.STIFFNESS, np.array([[stiffness]])) self.kf.predict_and_observe(t, ObservationKind.STEER_RATIO, np.array([[steer_ratio]])) + elif which == 'liveCalibration': + self.calibrator.feed_live_calib(msg) + elif which == 'carState': self.steering_angle = msg.steeringAngleDeg self.speed = msg.vEgo @@ -124,13 +130,12 @@ def main(): REPLAY = bool(int(os.getenv("REPLAY", "0"))) pm = messaging.PubMaster(['liveParameters']) - sm = messaging.SubMaster(['liveLocationKalman', 'carState'], poll='liveLocationKalman') + sm = messaging.SubMaster(['livePose', 'liveCalibration', 'carState'], poll='livePose') params_reader = Params() # wait for stats about the car to come in from controls cloudlog.info("paramsd is waiting for CarParams") - with car.CarParams.from_bytes(params_reader.get("CarParams", block=True)) as msg: - CP = msg + CP = messaging.log_from_bytes(params_reader.get("CarParams", block=True), car.CarParams) cloudlog.info("paramsd got CarParams") min_sr, max_sr = 0.5 * CP.steerRatio, 2.0 * CP.steerRatio @@ -172,7 +177,7 @@ def main(): pInitial = None if DEBUG: - pInitial = np.array(params['filterState']['std']) if 'filterState' in params else None + pInitial = np.array(params['debugFilterState']['std']) if 'debugFilterState' in params else None learner = ParamsLearner(CP, params['steerRatio'], params['stiffnessFactor'], math.radians(params['angleOffsetAverageDeg']), pInitial) angle_offset_average = params['angleOffsetAverageDeg'] @@ -190,7 +195,7 @@ def main(): t = sm.logMonoTime[which] * 1e-9 learner.handle_log(t, which, sm[which]) - if sm.updated['liveLocationKalman']: + if sm.updated['livePose']: x = learner.kf.x P = np.sqrt(learner.kf.P.diagonal()) if not all(map(math.isfinite, x)): @@ -237,10 +242,9 @@ def main(): liveParameters.angleOffsetAverageStd = float(P[States.ANGLE_OFFSET].item()) liveParameters.angleOffsetFastStd = float(P[States.ANGLE_OFFSET_FAST].item()) if DEBUG: - liveParameters.filterState = log.LiveLocationKalman.Measurement.new_message() - liveParameters.filterState.value = x.tolist() - liveParameters.filterState.std = P.tolist() - liveParameters.filterState.valid = True + liveParameters.debugFilterState = log.LiveParametersData.FilterState.new_message() + liveParameters.debugFilterState.value = x.tolist() + liveParameters.debugFilterState.std = P.tolist() msg.valid = sm.all_checks() diff --git a/selfdrive/locationd/test/test_locationd.py b/selfdrive/locationd/test/test_locationd.py index 74ac7d2962de6db..d0b1a82988d1ab6 100644 --- a/selfdrive/locationd/test/test_locationd.py +++ b/selfdrive/locationd/test/test_locationd.py @@ -1,13 +1,7 @@ -import pytest -import json -import random -import time import capnp import cereal.messaging as messaging -from cereal.services import SERVICE_LIST from openpilot.common.params import Params -from openpilot.common.transformations.coordinates import ecef2geodetic from openpilot.system.manager.process_config import managed_processes @@ -60,30 +54,3 @@ def get_msg(self, name, t): msg.logMonoTime = t msg.valid = True return msg - - def test_params_gps(self): - random.seed(123489234) - self.params.remove('LastGPSPosition') - - self.x = -2710700 + (random.random() * 1e5) - self.y = -4280600 + (random.random() * 1e5) - self.z = 3850300 + (random.random() * 1e5) - self.lat, self.lon, self.alt = ecef2geodetic([self.x, self.y, self.z]) - - # get fake messages at the correct frequency, listed in services.py - msgs = [] - for sec in range(65): - for name in self.LLD_MSGS: - for j in range(int(SERVICE_LIST[name].frequency)): - msgs.append(self.get_msg(name, int((sec + j / SERVICE_LIST[name].frequency) * 1e9))) - - for msg in sorted(msgs, key=lambda x: x.logMonoTime): - self.pm.send(msg.which(), msg) - if msg.which() == "cameraOdometry": - self.pm.wait_for_readers_to_update(msg.which(), 0.1, dt=0.005) - time.sleep(1) # wait for async params write - - lastGPS = json.loads(self.params.get('LastGPSPosition')) - assert lastGPS['latitude'] == pytest.approx(self.lat, abs=0.001) - assert lastGPS['longitude'] == pytest.approx(self.lon, abs=0.001) - assert lastGPS['altitude'] == pytest.approx(self.alt, abs=0.001) diff --git a/selfdrive/locationd/test/test_locationd_scenarios.py b/selfdrive/locationd/test/test_locationd_scenarios.py index ca52bffeea3742d..166d715c3474757 100644 --- a/selfdrive/locationd/test/test_locationd_scenarios.py +++ b/selfdrive/locationd/test/test_locationd_scenarios.py @@ -7,12 +7,12 @@ from openpilot.selfdrive.test.process_replay.migration import migrate_all from openpilot.selfdrive.test.process_replay.process_replay import replay_process_with_name -TEST_ROUTE = "ff2bd20623fcaeaa|2023-09-05--10-14-54/4" +# TODO find a new segment to test +TEST_ROUTE = "4019fff6e54cf1c7|00000123--4bc0d95ef6/5" GPS_MESSAGES = ['gpsLocationExternal', 'gpsLocation'] SELECT_COMPARE_FIELDS = { - 'yaw_rate': ['angularVelocityCalibrated', 'value', 2], - 'roll': ['orientationNED', 'value', 0], - 'gps_flag': ['gpsOK'], + 'yaw_rate': ['angularVelocityDevice', 'z'], + 'roll': ['orientationNED', 'x'], 'inputs_flag': ['inputsOK'], 'sensors_flag': ['sensorsOK'], } @@ -21,10 +21,6 @@ class Scenario(Enum): BASE = 'base' - GPS_OFF = 'gps_off' - GPS_OFF_MIDWAY = 'gps_off_midway' - GPS_ON_MIDWAY = 'gps_on_midway' - GPS_TUNNEL = 'gps_tunnel' GYRO_OFF = 'gyro_off' GYRO_SPIKE_MIDWAY = 'gyro_spike_midway' ACCEL_OFF = 'accel_off' @@ -37,9 +33,9 @@ def get_nested_keys(msg, keys): for key in keys: val = getattr(msg if val is None else val, key) if isinstance(key, str) else val[key] return val - llk = [x.liveLocationKalman for x in logs if x.which() == 'liveLocationKalman'] + lp = [x.livePose for x in logs if x.which() == 'livePose'] data = defaultdict(list) - for msg in llk: + for msg in lp: for key, fields in SELECT_COMPARE_FIELDS.items(): data[key].append(get_nested_keys(msg, fields)) for key in data: @@ -51,24 +47,6 @@ def run_scenarios(scenario, logs): if scenario == Scenario.BASE: pass - elif scenario == Scenario.GPS_OFF: - logs = sorted([x for x in logs if x.which() not in GPS_MESSAGES], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.GPS_OFF_MIDWAY: - non_gps = [x for x in logs if x.which() not in GPS_MESSAGES] - gps = [x for x in logs if x.which() in GPS_MESSAGES] - logs = sorted(non_gps + gps[: len(gps) // 2], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.GPS_ON_MIDWAY: - non_gps = [x for x in logs if x.which() not in GPS_MESSAGES] - gps = [x for x in logs if x.which() in GPS_MESSAGES] - logs = sorted(non_gps + gps[len(gps) // 2:], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.GPS_TUNNEL: - non_gps = [x for x in logs if x.which() not in GPS_MESSAGES] - gps = [x for x in logs if x.which() in GPS_MESSAGES] - logs = sorted(non_gps + gps[:len(gps) // 4] + gps[-len(gps) // 4:], key=lambda x: x.logMonoTime) - elif scenario == Scenario.GYRO_OFF: logs = sorted([x for x in logs if x.which() != 'gyroscope'], key=lambda x: x.logMonoTime) @@ -116,61 +94,8 @@ def test_base(self): - roll: unchanged """ orig_data, replayed_data = run_scenarios(Scenario.BASE, self.logs) - assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2)) - assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5)) - - def test_gps_off(self): - """ - Test: no GPS message for the entire segment - Expected Result: - - yaw_rate: unchanged - - roll: - - gpsOK: False - """ - orig_data, replayed_data = run_scenarios(Scenario.GPS_OFF, self.logs) - assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2)) - assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5)) - assert np.all(replayed_data['gps_flag'] == 0.0) - - def test_gps_off_midway(self): - """ - Test: no GPS message for the second half of the segment - Expected Result: - - yaw_rate: unchanged - - roll: - - gpsOK: True for the first half, False for the second half - """ - orig_data, replayed_data = run_scenarios(Scenario.GPS_OFF_MIDWAY, self.logs) - assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2)) - assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5)) - assert np.diff(replayed_data['gps_flag'])[512] == -1.0 - - def test_gps_on_midway(self): - """ - Test: no GPS message for the first half of the segment - Expected Result: - - yaw_rate: unchanged - - roll: - - gpsOK: False for the first half, True for the second half - """ - orig_data, replayed_data = run_scenarios(Scenario.GPS_ON_MIDWAY, self.logs) - assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2)) - assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(1.5)) - assert np.diff(replayed_data['gps_flag'])[505] == 1.0 - - def test_gps_tunnel(self): - """ - Test: no GPS message for the middle section of the segment - Expected Result: - - yaw_rate: unchanged - - roll: - - gpsOK: False for the middle section, True for the rest - """ - orig_data, replayed_data = run_scenarios(Scenario.GPS_TUNNEL, self.logs) - assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2)) - assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5)) - assert np.diff(replayed_data['gps_flag'])[213] == -1.0 - assert np.diff(replayed_data['gps_flag'])[805] == 1.0 + assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.35)) + assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.55)) def test_gyro_off(self): """ @@ -194,10 +119,10 @@ def test_gyro_spikes(self): - inputsOK: False for some time after the spike, True for the rest """ orig_data, replayed_data = run_scenarios(Scenario.GYRO_SPIKE_MIDWAY, self.logs) - assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2)) - assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5)) - assert np.diff(replayed_data['inputs_flag'])[500] == -1.0 - assert np.diff(replayed_data['inputs_flag'])[694] == 1.0 + assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.35)) + assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.55)) + assert np.diff(replayed_data['inputs_flag'])[499] == -1.0 + assert np.diff(replayed_data['inputs_flag'])[696] == 1.0 def test_accel_off(self): """ @@ -219,5 +144,5 @@ def test_accel_spikes(self): Expected Result: Right now, the kalman filter is not robust to small spikes like it is to gyroscope spikes. """ orig_data, replayed_data = run_scenarios(Scenario.ACCEL_SPIKE_MIDWAY, self.logs) - assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2)) - assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5)) + assert np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.35)) + assert np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.55)) diff --git a/selfdrive/locationd/torqued.py b/selfdrive/locationd/torqued.py index 06f9044738e7aed..2b7cc62527be976 100755 --- a/selfdrive/locationd/torqued.py +++ b/selfdrive/locationd/torqued.py @@ -9,7 +9,7 @@ from openpilot.common.filter_simple import FirstOrderFilter 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 +from openpilot.selfdrive.locationd.helpers import PointBuckets, ParameterEstimator, PoseCalibrator, Pose HISTORY = 5 # secs POINTS_PER_BUCKET = 1500 @@ -36,8 +36,8 @@ def slope2rot(slope): - sin = np.sqrt(slope**2 / (slope**2 + 1)) - cos = np.sqrt(1 / (slope**2 + 1)) + sin = np.sqrt(slope ** 2 / (slope ** 2 + 1)) + cos = np.sqrt(1 / (slope ** 2 + 1)) return np.array([[cos, -sin], [sin, cos]]) @@ -50,9 +50,10 @@ def add_point(self, x, y): class TorqueEstimator(ParameterEstimator): - def __init__(self, CP, decimated=False): + def __init__(self, CP, decimated=False, track_all_points=False): self.hist_len = int(HISTORY / DT_MDL) - self.lag = CP.steerActuatorDelay + .2 # from controlsd + self.lag = CP.steerActuatorDelay + .2 # from controlsd + self.track_all_points = track_all_points # for offline analysis, without max lateral accel or max steer torque filters if decimated: self.min_bucket_points = MIN_BUCKET_POINTS / 10 self.min_points_total = MIN_POINTS_TOTAL_QLOG @@ -76,6 +77,8 @@ def __init__(self, CP, decimated=False): self.offline_friction = CP.lateralTuning.torque.friction self.offline_latAccelFactor = CP.lateralTuning.torque.latAccelFactor + self.calibrator = PoseCalibrator() + self.reset() initial_params = { @@ -119,7 +122,8 @@ def __init__(self, CP, decimated=False): for param in initial_params: self.filtered_params[param] = FirstOrderFilter(initial_params[param], self.decay, DT_MDL) - def get_restore_key(self, CP, version): + @staticmethod + def get_restore_key(CP, version): a, b = None, None if CP.lateralTuning.which() == 'torque': a = CP.lateralTuning.torque.friction @@ -135,6 +139,7 @@ def reset(self): min_points_total=self.min_points_total, points_per_bucket=POINTS_PER_BUCKET, rowsize=3) + self.all_torque_points = [] def estimate_params(self): points = self.filtered_points.get_points(self.fit_points) @@ -159,25 +164,41 @@ def update_params(self, params): def handle_log(self, t, which, msg): if which == "carControl": self.raw_points["carControl_t"].append(t + self.lag) - self.raw_points["active"].append(msg.latActive) + self.raw_points["lat_active"].append(msg.latActive) elif which == "carOutput": self.raw_points["carOutput_t"].append(t + self.lag) self.raw_points["steer_torque"].append(-msg.actuatorsOutput.steer) elif which == "carState": self.raw_points["carState_t"].append(t + self.lag) + # TODO: check if high aEgo affects resulting lateral accel self.raw_points["vego"].append(msg.vEgo) self.raw_points["steer_override"].append(msg.steeringPressed) - elif which == "liveLocationKalman": + elif which == "liveCalibration": + self.calibrator.feed_live_calib(msg) + + # calculate lateral accel from past steering torque + elif which == "livePose": if len(self.raw_points['steer_torque']) == self.hist_len: - yaw_rate = msg.angularVelocityCalibrated.value[2] - roll = msg.orientationNED.value[0] - active = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t, DT_MDL), self.raw_points['carControl_t'], self.raw_points['active']).astype(bool) - steer_override = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t, DT_MDL), self.raw_points['carState_t'], self.raw_points['steer_override']).astype(bool) + device_pose = Pose.from_live_pose(msg) + calibrated_pose = self.calibrator.build_calibrated_pose(device_pose) + angular_velocity_calibrated = calibrated_pose.angular_velocity + + yaw_rate = angular_velocity_calibrated.yaw + roll = device_pose.orientation.roll + # check lat active up to now (without lag compensation) + lat_active = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t + self.lag, DT_MDL), + self.raw_points['carControl_t'], self.raw_points['lat_active']).astype(bool) + steer_override = np.interp(np.arange(t - MIN_ENGAGE_BUFFER, t + self.lag, DT_MDL), + self.raw_points['carState_t'], self.raw_points['steer_override']).astype(bool) vego = np.interp(t, self.raw_points['carState_t'], self.raw_points['vego']) - steer = np.interp(t, self.raw_points['carOutput_t'], self.raw_points['steer_torque']) - lateral_acc = (vego * yaw_rate) - (np.sin(roll) * ACCELERATION_DUE_TO_GRAVITY) - if all(active) and (not any(steer_override)) and (vego > MIN_VEL) and (abs(steer) > STEER_MIN_THRESHOLD) and (abs(lateral_acc) <= LAT_ACC_THRESHOLD): - self.filtered_points.add_point(float(steer), float(lateral_acc)) + steer = np.interp(t, self.raw_points['carOutput_t'], self.raw_points['steer_torque']).item() + lateral_acc = (vego * yaw_rate) - (np.sin(roll) * ACCELERATION_DUE_TO_GRAVITY).item() + if all(lat_active) and not any(steer_override) and (vego > MIN_VEL) and (abs(steer) > STEER_MIN_THRESHOLD): + if abs(lateral_acc) <= LAT_ACC_THRESHOLD: + self.filtered_points.add_point(steer, lateral_acc) + + if self.track_all_points: + self.all_torque_points.append([steer, lateral_acc]) def get_msg(self, valid=True, with_points=False): msg = messaging.new_message('liveTorqueParameters') @@ -220,11 +241,10 @@ def main(demo=False): config_realtime_process([0, 1, 2, 3], 5) pm = messaging.PubMaster(['liveTorqueParameters']) - sm = messaging.SubMaster(['carControl', 'carOutput', 'carState', 'liveLocationKalman'], poll='liveLocationKalman') + sm = messaging.SubMaster(['carControl', 'carOutput', 'carState', 'liveCalibration', 'livePose'], poll='livePose') params = Params() - with car.CarParams.from_bytes(params.get("CarParams", block=True)) as CP: - estimator = TorqueEstimator(CP) + estimator = TorqueEstimator(messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams)) while True: sm.update() @@ -234,7 +254,7 @@ def main(demo=False): t = sm.logMonoTime[which] * 1e-9 estimator.handle_log(t, which, sm[which]) - # 4Hz driven by liveLocationKalman + # 4Hz driven by livePose if sm.frame % 5 == 0: pm.send('liveTorqueParameters', estimator.get_msg(valid=sm.all_checks())) @@ -243,8 +263,10 @@ def main(demo=False): msg = estimator.get_msg(valid=sm.all_checks(), with_points=True) params.put_nonblocking("LiveTorqueParameters", msg.to_bytes()) + if __name__ == "__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() diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript index deb84d5952554a1..d47299841636206 100644 --- a/selfdrive/modeld/SConscript +++ b/selfdrive/modeld/SConscript @@ -4,7 +4,7 @@ Import('env', 'envCython', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', lenv = env.Clone() lenvCython = envCython.Clone() -libs = [cereal, messaging, visionipc, gpucommon, common, 'capnp', 'zmq', 'kj', 'pthread'] +libs = [cereal, messaging, visionipc, gpucommon, common, 'capnp', 'kj', 'pthread'] frameworks = [] common_src = [ @@ -69,6 +69,10 @@ if arch == "larch64" or GetOption('pc_thneed'): lenv.Command(fn + ".thneed", [fn + ".onnx"] + tinygrad_files, cmd) - thneed_lib = env.SharedLibrary('thneed', thneed_src, LIBS=[gpucommon, common, 'zmq', 'OpenCL', 'dl']) + fn_dm = File("models/dmonitoring_model").abspath + cmd = f"cd {Dir('#').abspath}/tinygrad_repo && " + ' '.join(tinygrad_opts) + f" python3 openpilot/compile2.py {fn_dm}.onnx {fn_dm}.thneed" + lenv.Command(fn_dm + ".thneed", [fn_dm + ".onnx"] + tinygrad_files, cmd) + + thneed_lib = env.SharedLibrary('thneed', thneed_src, LIBS=[gpucommon, common, 'OpenCL', 'dl']) thneedmodel_lib = env.Library('thneedmodel', ['runners/thneedmodel.cc']) - lenvCython.Program('runners/thneedmodel_pyx.so', 'runners/thneedmodel_pyx.pyx', LIBS=envCython["LIBS"]+[thneedmodel_lib, thneed_lib, gpucommon, common, 'dl', 'zmq', 'OpenCL']) + lenvCython.Program('runners/thneedmodel_pyx.so', 'runners/thneedmodel_pyx.pyx', LIBS=envCython["LIBS"]+[thneedmodel_lib, thneed_lib, gpucommon, common, 'dl', 'OpenCL']) diff --git a/selfdrive/modeld/constants.py b/selfdrive/modeld/constants.py index ca81bffcc88ce3b..bf74c2d1a065ec6 100644 --- a/selfdrive/modeld/constants.py +++ b/selfdrive/modeld/constants.py @@ -15,7 +15,8 @@ class ModelConstants: # model inputs constants MODEL_FREQ = 20 FEATURE_LEN = 512 - HISTORY_BUFFER_LEN = 99 + FULL_HISTORY_BUFFER_LEN = 99 + HISTORY_BUFFER_LEN = 24 DESIRE_LEN = 8 TRAFFIC_CONVENTION_LEN = 2 LAT_PLANNER_STATE_LEN = 4 @@ -59,6 +60,8 @@ class ModelConstants: RYG_GREEN = 0.01165 RYG_YELLOW = 0.06157 + POLY_PATH_DEGREE = 4 + # model outputs slices class Plan: POSITION = slice(0, 3) @@ -70,13 +73,14 @@ class Plan: class Meta: ENGAGED = slice(0, 1) # next 2, 4, 6, 8, 10 seconds - GAS_DISENGAGE = slice(1, 36, 7) - BRAKE_DISENGAGE = slice(2, 36, 7) - STEER_OVERRIDE = slice(3, 36, 7) - HARD_BRAKE_3 = slice(4, 36, 7) - HARD_BRAKE_4 = slice(5, 36, 7) - HARD_BRAKE_5 = slice(6, 36, 7) - GAS_PRESS = slice(7, 36, 7) + GAS_DISENGAGE = slice(1, 31, 6) + BRAKE_DISENGAGE = slice(2, 31, 6) + STEER_OVERRIDE = slice(3, 31, 6) + HARD_BRAKE_3 = slice(4, 31, 6) + HARD_BRAKE_4 = slice(5, 31, 6) + HARD_BRAKE_5 = slice(6, 31, 6) # next 0, 2, 4, 6, 8, 10 seconds - LEFT_BLINKER = slice(36, 48, 2) - RIGHT_BLINKER = slice(37, 48, 2) + GAS_PRESS = slice(31, 55, 4) + BRAKE_PRESS = slice(32, 55, 4) + LEFT_BLINKER = slice(33, 55, 4) + RIGHT_BLINKER = slice(34, 55, 4) diff --git a/selfdrive/modeld/dmonitoringmodeld b/selfdrive/modeld/dmonitoringmodeld new file mode 100755 index 000000000000000..80157e175196000 --- /dev/null +++ b/selfdrive/modeld/dmonitoringmodeld @@ -0,0 +1,10 @@ +#!/usr/bin/env bash + +DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" +cd "$DIR/../../" + +if [ -f "$DIR/libthneed.so" ]; then + export LD_PRELOAD="$DIR/libthneed.so" +fi + +exec "$DIR/dmonitoringmodeld.py" "$@" diff --git a/selfdrive/modeld/dmonitoringmodeld.py b/selfdrive/modeld/dmonitoringmodeld.py index a388bf089cb9b90..31440c1295cd510 100755 --- a/selfdrive/modeld/dmonitoringmodeld.py +++ b/selfdrive/modeld/dmonitoringmodeld.py @@ -6,6 +6,7 @@ import ctypes import numpy as np from pathlib import Path +from setproctitle import setproctitle from cereal import messaging from cereal.messaging import PubMaster, SubMaster @@ -14,16 +15,19 @@ from openpilot.common.params import Params from openpilot.common.realtime import set_realtime_priority from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime -from openpilot.selfdrive.modeld.models.commonmodel_pyx import sigmoid +from openpilot.selfdrive.modeld.models.commonmodel_pyx import CLContext +from openpilot.selfdrive.modeld.parse_model_outputs import sigmoid CALIB_LEN = 3 -REG_SCALE = 0.25 MODEL_WIDTH = 1440 MODEL_HEIGHT = 960 -OUTPUT_SIZE = 84 +FEATURE_LEN = 512 +OUTPUT_SIZE = 84 + FEATURE_LEN + +PROCESS_NAME = "selfdrive.modeld.dmonitoringmodeld" SEND_RAW_PRED = os.getenv('SEND_RAW_PRED') MODEL_PATHS = { - ModelRunner.SNPE: Path(__file__).parent / 'models/dmonitoring_model_q.dlc', + ModelRunner.THNEED: Path(__file__).parent / 'models/dmonitoring_model.thneed', ModelRunner.ONNX: Path(__file__).parent / 'models/dmonitoring_model.onnx'} class DriverStateResult(ctypes.Structure): @@ -49,21 +53,22 @@ class DMonitoringModelResult(ctypes.Structure): ("driver_state_lhd", DriverStateResult), ("driver_state_rhd", DriverStateResult), ("poor_vision_prob", ctypes.c_float), - ("wheel_on_right_prob", ctypes.c_float)] + ("wheel_on_right_prob", ctypes.c_float), + ("features", ctypes.c_float*FEATURE_LEN)] class ModelState: inputs: dict[str, np.ndarray] output: np.ndarray model: ModelRunner - def __init__(self): + def __init__(self, cl_ctx): assert ctypes.sizeof(DMonitoringModelResult) == OUTPUT_SIZE * ctypes.sizeof(ctypes.c_float) self.output = np.zeros(OUTPUT_SIZE, dtype=np.float32) self.inputs = { 'input_img': np.zeros(MODEL_HEIGHT * MODEL_WIDTH, dtype=np.uint8), 'calib': np.zeros(CALIB_LEN, dtype=np.float32)} - self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.DSP, True, None) + self.model = ModelRunner(MODEL_PATHS, self.output, Runtime.GPU, False, cl_ctx) self.model.addInput("input_img", None) self.model.addInput("calib", self.inputs['calib']) @@ -76,37 +81,37 @@ def run(self, buf:VisionBuf, calib:np.ndarray) -> tuple[np.ndarray, float]: input_data = self.inputs['input_img'].reshape(MODEL_HEIGHT, MODEL_WIDTH) input_data[:] = buf_data[v_offset:v_offset+MODEL_HEIGHT, h_offset:h_offset+MODEL_WIDTH] - t1 = time.perf_counter() self.model.setInputBuffer("input_img", self.inputs['input_img'].view(np.float32)) + t1 = time.perf_counter() self.model.execute() t2 = time.perf_counter() return self.output, t2 - t1 def fill_driver_state(msg, ds_result: DriverStateResult): - msg.faceOrientation = [x * REG_SCALE for x in ds_result.face_orientation] + msg.faceOrientation = list(ds_result.face_orientation) msg.faceOrientationStd = [math.exp(x) for x in ds_result.face_orientation_std] - msg.facePosition = [x * REG_SCALE for x in ds_result.face_position[:2]] + msg.facePosition = list(ds_result.face_position[:2]) msg.facePositionStd = [math.exp(x) for x in ds_result.face_position_std[:2]] - msg.faceProb = sigmoid(ds_result.face_prob) - msg.leftEyeProb = sigmoid(ds_result.left_eye_prob) - msg.rightEyeProb = sigmoid(ds_result.right_eye_prob) - msg.leftBlinkProb = sigmoid(ds_result.left_blink_prob) - msg.rightBlinkProb = sigmoid(ds_result.right_blink_prob) - msg.sunglassesProb = sigmoid(ds_result.sunglasses_prob) - msg.occludedProb = sigmoid(ds_result.occluded_prob) - msg.readyProb = [sigmoid(x) for x in ds_result.ready_prob] - msg.notReadyProb = [sigmoid(x) for x in ds_result.not_ready_prob] - -def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: int, execution_time: float, dsp_execution_time: float): + msg.faceProb = float(sigmoid(ds_result.face_prob)) + msg.leftEyeProb = float(sigmoid(ds_result.left_eye_prob)) + msg.rightEyeProb = float(sigmoid(ds_result.right_eye_prob)) + msg.leftBlinkProb = float(sigmoid(ds_result.left_blink_prob)) + msg.rightBlinkProb = float(sigmoid(ds_result.right_blink_prob)) + msg.sunglassesProb = float(sigmoid(ds_result.sunglasses_prob)) + msg.occludedProb = float(sigmoid(ds_result.occluded_prob)) + msg.readyProb = [float(sigmoid(x)) for x in ds_result.ready_prob] + msg.notReadyProb = [float(sigmoid(x)) for x in ds_result.not_ready_prob] + +def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: int, execution_time: float, gpu_execution_time: float): model_result = ctypes.cast(model_output.ctypes.data, ctypes.POINTER(DMonitoringModelResult)).contents msg = messaging.new_message('driverStateV2', valid=True) ds = msg.driverStateV2 ds.frameId = frame_id ds.modelExecutionTime = execution_time - ds.dspExecutionTime = dsp_execution_time - ds.poorVisionProb = sigmoid(model_result.poor_vision_prob) - ds.wheelOnRightProb = sigmoid(model_result.wheel_on_right_prob) + ds.gpuExecutionTime = gpu_execution_time + ds.poorVisionProb = float(sigmoid(model_result.poor_vision_prob)) + ds.wheelOnRightProb = float(sigmoid(model_result.wheel_on_right_prob)) ds.rawPredictions = model_output.tobytes() if SEND_RAW_PRED else b'' fill_driver_state(ds.leftDriverData, model_result.driver_state_lhd) fill_driver_state(ds.rightDriverData, model_result.driver_state_rhd) @@ -115,14 +120,16 @@ def get_driverstate_packet(model_output: np.ndarray, frame_id: int, location_ts: def main(): gc.disable() + setproctitle(PROCESS_NAME) set_realtime_priority(1) - model = ModelState() + cl_context = CLContext() + model = ModelState(cl_context) cloudlog.warning("models loaded, dmonitoringmodeld starting") Params().put_bool("DmModelInitialized", True) cloudlog.warning("connecting to driver stream") - vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True) + vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_DRIVER, True, cl_context) while not vipc_client.connect(False): time.sleep(0.1) assert vipc_client.is_connected() @@ -132,7 +139,6 @@ def main(): pm = PubMaster(["driverStateV2"]) calib = np.zeros(CALIB_LEN, dtype=np.float32) - # last = 0 while True: buf = vipc_client.recv() @@ -144,12 +150,10 @@ def main(): calib[:] = np.array(sm["liveCalibration"].rpyCalib) t1 = time.perf_counter() - model_output, dsp_execution_time = model.run(buf, calib) + model_output, gpu_execution_time = model.run(buf, calib) t2 = time.perf_counter() - pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, dsp_execution_time)) - # print("dmonitoring process: %.2fms, from last %.2fms\n" % (t2 - t1, t1 - last)) - # last = t1 + pm.send("driverStateV2", get_driverstate_packet(model_output, vipc_client.frame_id, vipc_client.timestamp_sof, t2 - t1, gpu_execution_time)) if __name__ == "__main__": diff --git a/selfdrive/modeld/fill_model_msg.py b/selfdrive/modeld/fill_model_msg.py index f6a57f1a4027c7e..115ec94f88fcbdd 100644 --- a/selfdrive/modeld/fill_model_msg.py +++ b/selfdrive/modeld/fill_model_msg.py @@ -41,17 +41,43 @@ def fill_xyvat(builder, t, x, y, v, a, x_std=None, y_std=None, v_std=None, a_std if a_std is not None: builder.aStd = a_std.tolist() -def fill_model_msg(msg: capnp._DynamicStructBuilder, net_output_data: dict[str, np.ndarray], publish_state: PublishState, +def fill_xyz_poly(builder, degree, x, y, z): + xyz = np.stack([x, y, z], axis=1) + coeffs = np.polynomial.polynomial.polyfit(ModelConstants.T_IDXS, xyz, deg=degree) + builder.xCoefficients = coeffs[:, 0].tolist() + builder.yCoefficients = coeffs[:, 1].tolist() + builder.zCoefficients = coeffs[:, 2].tolist() + +def fill_lane_line_meta(builder, lane_lines, lane_line_probs): + builder.leftY = lane_lines[1].y[0] + builder.leftProb = lane_line_probs[1] + builder.rightY = lane_lines[2].y[0] + builder.rightProb = lane_line_probs[2] + +def fill_model_msg(base_msg: capnp._DynamicStructBuilder, extended_msg: capnp._DynamicStructBuilder, + net_output_data: dict[str, np.ndarray], publish_state: PublishState, vipc_frame_id: int, vipc_frame_id_extra: int, frame_id: int, frame_drop: float, timestamp_eof: int, model_execution_time: float, valid: bool) -> None: frame_age = frame_id - vipc_frame_id if frame_id > vipc_frame_id else 0 - msg.valid = valid + frame_drop_perc = frame_drop * 100 + extended_msg.valid = valid + base_msg.valid = valid - modelV2 = msg.modelV2 + driving_model_data = base_msg.drivingModelData + + driving_model_data.frameId = vipc_frame_id + driving_model_data.frameIdExtra = vipc_frame_id_extra + driving_model_data.frameDropPerc = frame_drop_perc + driving_model_data.modelExecutionTime = model_execution_time + + action = driving_model_data.action + action.desiredCurvature = float(net_output_data['desired_curvature'][0,0]) + + modelV2 = extended_msg.modelV2 modelV2.frameId = vipc_frame_id modelV2.frameIdExtra = vipc_frame_id_extra modelV2.frameAge = frame_age - modelV2.frameDropPerc = frame_drop * 100 + modelV2.frameDropPerc = frame_drop_perc modelV2.timestampEof = timestamp_eof modelV2.modelExecutionTime = model_execution_time @@ -67,6 +93,17 @@ def fill_model_msg(msg: capnp._DynamicStructBuilder, net_output_data: dict[str, orientation_rate = modelV2.orientationRate fill_xyzt(orientation_rate, ModelConstants.T_IDXS, *net_output_data['plan'][0,:,Plan.ORIENTATION_RATE].T) + # temporal pose + temporal_pose = modelV2.temporalPose + temporal_pose.trans = net_output_data['plan'][0,0,Plan.VELOCITY].tolist() + temporal_pose.transStd = net_output_data['plan_stds'][0,0,Plan.VELOCITY].tolist() + temporal_pose.rot = net_output_data['plan'][0,0,Plan.ORIENTATION_RATE].tolist() + temporal_pose.rotStd = net_output_data['plan_stds'][0,0,Plan.ORIENTATION_RATE].tolist() + + # poly path + poly_path = driving_model_data.path + fill_xyz_poly(poly_path, ModelConstants.POLY_PATH_DEGREE, *net_output_data['plan'][0,:,Plan.POSITION].T) + # lateral planning action = modelV2.action action.desiredCurvature = float(net_output_data['desired_curvature'][0,0]) @@ -98,6 +135,9 @@ def fill_model_msg(msg: capnp._DynamicStructBuilder, net_output_data: dict[str, modelV2.laneLineStds = net_output_data['lane_lines_stds'][0,:,0,0].tolist() modelV2.laneLineProbs = net_output_data['lane_lines_prob'][0,1::2].tolist() + lane_line_meta = driving_model_data.laneLineMeta + fill_lane_line_meta(lane_line_meta, modelV2.laneLines, modelV2.laneLineProbs) + # road edges modelV2.init('roadEdges', 2) for i in range(2): @@ -127,6 +167,8 @@ def fill_model_msg(msg: capnp._DynamicStructBuilder, net_output_data: dict[str, disengage_predictions.brake3MetersPerSecondSquaredProbs = net_output_data['meta'][0,Meta.HARD_BRAKE_3].tolist() disengage_predictions.brake4MetersPerSecondSquaredProbs = net_output_data['meta'][0,Meta.HARD_BRAKE_4].tolist() disengage_predictions.brake5MetersPerSecondSquaredProbs = net_output_data['meta'][0,Meta.HARD_BRAKE_5].tolist() + disengage_predictions.gasPressProbs = net_output_data['meta'][0,Meta.GAS_PRESS].tolist() + disengage_predictions.brakePressProbs = net_output_data['meta'][0,Meta.BRAKE_PRESS].tolist() publish_state.prev_brake_5ms2_probs[:-1] = publish_state.prev_brake_5ms2_probs[1:] publish_state.prev_brake_5ms2_probs[-1] = net_output_data['meta'][0,Meta.HARD_BRAKE_5][0] @@ -136,13 +178,6 @@ def fill_model_msg(msg: capnp._DynamicStructBuilder, net_output_data: dict[str, (publish_state.prev_brake_3ms2_probs > ModelConstants.FCW_THRESHOLDS_3MS2).all() meta.hardBrakePredicted = hard_brake_predicted.item() - # temporal pose - temporal_pose = modelV2.temporalPose - temporal_pose.trans = net_output_data['sim_pose'][0,:3].tolist() - temporal_pose.transStd = net_output_data['sim_pose_stds'][0,:3].tolist() - temporal_pose.rot = net_output_data['sim_pose'][0,3:].tolist() - temporal_pose.rotStd = net_output_data['sim_pose_stds'][0,3:].tolist() - # confidence if vipc_frame_id % (2*ModelConstants.MODEL_FREQ) == 0: # any disengage prob diff --git a/selfdrive/modeld/modeld.py b/selfdrive/modeld/modeld.py index 3ac80aad91110ab..4e91d324007943c 100755 --- a/selfdrive/modeld/modeld.py +++ b/selfdrive/modeld/modeld.py @@ -9,6 +9,7 @@ from setproctitle import setproctitle from cereal.messaging import PubMaster, SubMaster from msgq.visionipc import VisionIpcClient, VisionStreamType, VisionBuf +from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.swaglog import cloudlog from openpilot.common.params import Params from openpilot.common.filter_simple import FirstOrderFilter @@ -16,7 +17,6 @@ from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.transformations.model import get_warp_matrix from openpilot.system import sentry -from openpilot.selfdrive.car.car_helpers import get_demo_car_params from openpilot.selfdrive.controls.lib.desire_helper import DesireHelper from openpilot.selfdrive.modeld.runners import ModelRunner, Runtime from openpilot.selfdrive.modeld.parse_model_outputs import Parser @@ -33,6 +33,7 @@ METADATA_PATH = Path(__file__).parent / 'models/supercombo_metadata.pkl' + class FrameMeta: frame_id: int = 0 timestamp_sof: int = 0 @@ -54,6 +55,11 @@ def __init__(self, context: CLContext): self.frame = ModelFrame(context) self.wide_frame = ModelFrame(context) self.prev_desire = np.zeros(ModelConstants.DESIRE_LEN, dtype=np.float32) + self.full_features_20Hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN, ModelConstants.FEATURE_LEN), dtype=np.float32) + self.desire_20Hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN + 1, ModelConstants.DESIRE_LEN), dtype=np.float32) + self.prev_desired_curv_20hz = np.zeros((ModelConstants.FULL_HISTORY_BUFFER_LEN + 1, ModelConstants.PREV_DESIRED_CURV_LEN), dtype=np.float32) + + # img buffers are managed in openCL transform code 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), @@ -86,17 +92,18 @@ def run(self, buf: VisionBuf, wbuf: VisionBuf, transform: np.ndarray, transform_ inputs: dict[str, np.ndarray], prepare_only: bool) -> dict[str, np.ndarray] | None: # Model decides when action is completed, so desire input is just a pulse triggered on rising edge inputs['desire'][0] = 0 - self.inputs['desire'][:-ModelConstants.DESIRE_LEN] = self.inputs['desire'][ModelConstants.DESIRE_LEN:] - self.inputs['desire'][-ModelConstants.DESIRE_LEN:] = np.where(inputs['desire'] - self.prev_desire > .99, inputs['desire'], 0) + new_desire = np.where(inputs['desire'] - self.prev_desire > .99, inputs['desire'], 0) self.prev_desire[:] = inputs['desire'] + self.desire_20Hz[:-1] = self.desire_20Hz[1:] + self.desire_20Hz[-1] = new_desire + self.inputs['desire'][:] = self.desire_20Hz.reshape((25,4,-1)).max(axis=1).flatten() + self.inputs['traffic_convention'][:] = inputs['traffic_convention'] self.inputs['lateral_control_params'][:] = inputs['lateral_control_params'] - # 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"))) - if wbuf is not None: - self.model.setInputBuffer("big_input_imgs", self.wide_frame.prepare(wbuf, transform_wide.flatten(), self.model.getCLBuffer("big_input_imgs"))) + self.model.setInputBuffer("big_input_imgs", self.wide_frame.prepare(wbuf, transform_wide.flatten(), self.model.getCLBuffer("big_input_imgs"))) if prepare_only: return None @@ -104,10 +111,16 @@ def run(self, buf: VisionBuf, wbuf: VisionBuf, transform: np.ndarray, transform_ self.model.execute() outputs = self.parser.parse_outputs(self.slice_outputs(self.output)) - 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['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, :] + self.full_features_20Hz[:-1] = self.full_features_20Hz[1:] + self.full_features_20Hz[-1] = outputs['hidden_state'][0, :] + + self.prev_desired_curv_20hz[:-1] = self.prev_desired_curv_20hz[1:] + self.prev_desired_curv_20hz[-1] = outputs['desired_curvature'][0, :] + + idxs = np.arange(-4,-100,-4)[::-1] + self.inputs['features_buffer'][:] = self.full_features_20Hz[idxs].flatten() + # TODO model only uses last value now, once that changes we need to input strided action history buffer + self.inputs['prev_desired_curv'][-ModelConstants.PREV_DESIRED_CURV_LEN:] = 0. * self.prev_desired_curv_20hz[-4, :] return outputs @@ -149,7 +162,7 @@ def main(demo=False): cloudlog.warning(f"connected extra cam with buffer size: {vipc_client_extra.buffer_len} ({vipc_client_extra.width} x {vipc_client_extra.height})") # messaging - pm = PubMaster(["modelV2", "cameraOdometry"]) + pm = PubMaster(["modelV2", "drivingModelData", "cameraOdometry"]) sm = SubMaster(["deviceState", "carState", "roadCameraState", "liveCalibration", "driverMonitoringState", "carControl"]) publish_state = PublishState() @@ -172,8 +185,7 @@ def main(demo=False): if demo: CP = get_demo_car_params() else: - with car.CarParams.from_bytes(params.get("CarParams", block=True)) as msg: - CP = msg + CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) cloudlog.info("modeld got CarParams: %s", CP.carName) # TODO this needs more thought, use .2s extra for now to estimate other delays @@ -218,7 +230,8 @@ def main(demo=False): 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) + v_ego = max(sm["carState"].vEgo, 0.) + lateral_control_params = np.array([v_ego, steer_delay], dtype=np.float32) if sm.updated["liveCalibration"] and sm.seen['roadCameraState'] and sm.seen['deviceState']: device_from_calib_euler = np.array(sm["liveCalibration"].rpyCalib, dtype=np.float32) dc = DEVICE_CAMERAS[(str(sm['deviceState'].deviceType), str(sm['roadCameraState'].sensor))] @@ -259,9 +272,10 @@ def main(demo=False): if model_output is not None: modelv2_send = messaging.new_message('modelV2') + drivingdata_send = messaging.new_message('drivingModelData') posenet_send = messaging.new_message('cameraOdometry') - 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, model_execution_time, live_calib_seen) + fill_model_msg(drivingdata_send, modelv2_send, model_output, publish_state, meta_main.frame_id, meta_extra.frame_id, frame_id, + frame_drop_ratio, meta_main.timestamp_eof, model_execution_time, live_calib_seen) desire_state = modelv2_send.modelV2.meta.desireState l_lane_change_prob = desire_state[log.Desire.laneChangeLeft] @@ -270,9 +284,12 @@ def main(demo=False): 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 + drivingdata_send.drivingModelData.meta.laneChangeState = DH.lane_change_state + drivingdata_send.drivingModelData.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('drivingModelData', drivingdata_send) pm.send('cameraOdometry', posenet_send) last_vipc_frame_id = meta_main.frame_id diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc index 523ce00e436eda5..e8a5a7ed52a55e9 100644 --- a/selfdrive/modeld/models/commonmodel.cc +++ b/selfdrive/modeld/models/commonmodel.cc @@ -7,32 +7,39 @@ #include "common/clutil.h" ModelFrame::ModelFrame(cl_device_id device_id, cl_context context) { - input_frames = std::make_unique(buf_size); + input_frames = std::make_unique(buf_size); q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err)); y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_WIDTH * MODEL_HEIGHT, NULL, &err)); u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); - net_input_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_FRAME_SIZE * sizeof(float), NULL, &err)); + img_buffer_20hz_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, 5*frame_size_bytes, NULL, &err)); + region.origin = 4 * frame_size_bytes; + region.size = frame_size_bytes; + last_img_cl = CL_CHECK_ERR(clCreateSubBuffer(img_buffer_20hz_cl, CL_MEM_READ_WRITE, CL_BUFFER_CREATE_TYPE_REGION, ®ion, &err)); transform_init(&transform, context, device_id); loadyuv_init(&loadyuv, context, device_id, MODEL_WIDTH, MODEL_HEIGHT); } -float* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3 &projection, cl_mem *output) { +uint8_t* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3 &projection, cl_mem *output) { transform_queue(&this->transform, q, - yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset, - y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, projection); + yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset, + y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, projection); + for (int i = 0; i < 4; i++) { + CL_CHECK(clEnqueueCopyBuffer(q, img_buffer_20hz_cl, img_buffer_20hz_cl, (i+1)*frame_size_bytes, i*frame_size_bytes, frame_size_bytes, 0, nullptr, nullptr)); + } + loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, last_img_cl); if (output == NULL) { - loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, net_input_cl); - - std::memmove(&input_frames[0], &input_frames[MODEL_FRAME_SIZE], sizeof(float) * MODEL_FRAME_SIZE); - CL_CHECK(clEnqueueReadBuffer(q, net_input_cl, CL_TRUE, 0, MODEL_FRAME_SIZE * sizeof(float), &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); + CL_CHECK(clEnqueueReadBuffer(q, img_buffer_20hz_cl, CL_TRUE, 0, frame_size_bytes, &input_frames[0], 0, nullptr, nullptr)); + CL_CHECK(clEnqueueReadBuffer(q, last_img_cl, CL_TRUE, 0, frame_size_bytes, &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); clFinish(q); return &input_frames[0]; } else { - loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, *output, true); + copy_queue(&loadyuv, q, img_buffer_20hz_cl, *output, 0, 0, frame_size_bytes); + copy_queue(&loadyuv, q, last_img_cl, *output, 0, frame_size_bytes, frame_size_bytes); + // NOTE: Since thneed is using a different command queue, this clFinish is needed to ensure the image is ready. clFinish(q); return NULL; @@ -42,13 +49,10 @@ float* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int ModelFrame::~ModelFrame() { transform_destroy(&transform); loadyuv_destroy(&loadyuv); - CL_CHECK(clReleaseMemObject(net_input_cl)); + CL_CHECK(clReleaseMemObject(img_buffer_20hz_cl)); + CL_CHECK(clReleaseMemObject(last_img_cl)); CL_CHECK(clReleaseMemObject(v_cl)); CL_CHECK(clReleaseMemObject(u_cl)); CL_CHECK(clReleaseMemObject(y_cl)); CL_CHECK(clReleaseCommandQueue(q)); -} - -float sigmoid(float input) { - return 1 / (1 + expf(-input)); -} +} \ No newline at end of file diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h index 2cf79094a692629..1c7360f1596b878 100644 --- a/selfdrive/modeld/models/commonmodel.h +++ b/selfdrive/modeld/models/commonmodel.h @@ -16,23 +16,23 @@ #include "selfdrive/modeld/transforms/loadyuv.h" #include "selfdrive/modeld/transforms/transform.h" -float sigmoid(float input); - class ModelFrame { public: ModelFrame(cl_device_id device_id, cl_context context); ~ModelFrame(); - float* prepare(cl_mem yuv_cl, int width, int height, int frame_stride, int frame_uv_offset, const mat3& transform, cl_mem *output); + uint8_t* prepare(cl_mem yuv_cl, int width, int height, int frame_stride, int frame_uv_offset, const mat3& transform, cl_mem *output); const int MODEL_WIDTH = 512; const int MODEL_HEIGHT = 256; const int MODEL_FRAME_SIZE = MODEL_WIDTH * MODEL_HEIGHT * 3 / 2; const int buf_size = MODEL_FRAME_SIZE * 2; + const size_t frame_size_bytes = MODEL_FRAME_SIZE * sizeof(uint8_t); private: Transform transform; LoadYUVState loadyuv; cl_command_queue q; - cl_mem y_cl, u_cl, v_cl, net_input_cl; - std::unique_ptr input_frames; -}; + cl_mem y_cl, u_cl, v_cl, img_buffer_20hz_cl, last_img_cl; + cl_buffer_region region; + std::unique_ptr input_frames; +}; \ No newline at end of file diff --git a/selfdrive/modeld/models/commonmodel.pxd b/selfdrive/modeld/models/commonmodel.pxd index 7c3eb0b3d7e4d5a..3348af3f1746653 100644 --- a/selfdrive/modeld/models/commonmodel.pxd +++ b/selfdrive/modeld/models/commonmodel.pxd @@ -12,9 +12,7 @@ cdef extern from "common/clutil.h": cl_context cl_create_context(cl_device_id) cdef extern from "selfdrive/modeld/models/commonmodel.h": - float sigmoid(float) - cppclass ModelFrame: int buf_size ModelFrame(cl_device_id, cl_context) - float * prepare(cl_mem, int, int, int, int, mat3, cl_mem*) + unsigned char * prepare(cl_mem, int, int, int, int, mat3, cl_mem*) diff --git a/selfdrive/modeld/models/commonmodel_pyx.pyx b/selfdrive/modeld/models/commonmodel_pyx.pyx index e292bb0d2da6c54..99f9c5dc173991f 100644 --- a/selfdrive/modeld/models/commonmodel_pyx.pyx +++ b/selfdrive/modeld/models/commonmodel_pyx.pyx @@ -1,5 +1,5 @@ # distutils: language = c++ -# cython: c_string_encoding=ascii +# cython: c_string_encoding=ascii, language_level=3 import numpy as np cimport numpy as cnp @@ -8,10 +8,8 @@ from libc.string cimport memcpy from msgq.visionipc.visionipc cimport cl_mem from msgq.visionipc.visionipc_pyx cimport VisionBuf, CLContext as BaseCLContext from .commonmodel cimport CL_DEVICE_TYPE_DEFAULT, cl_get_device_id, cl_create_context -from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame +from .commonmodel cimport mat3, ModelFrame as cppModelFrame -def sigmoid(x): - return cppSigmoid(x) cdef class CLContext(BaseCLContext): def __cinit__(self): @@ -37,11 +35,11 @@ cdef class ModelFrame: def prepare(self, VisionBuf buf, float[:] projection, CLMem output): cdef mat3 cprojection memcpy(cprojection.v, &projection[0], 9*sizeof(float)) - cdef float * data + cdef unsigned char * data if output is None: data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, NULL) else: data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) if not data: return None - return np.asarray( data) + return np.asarray( data) diff --git a/selfdrive/modeld/models/dmonitoring_model.current b/selfdrive/modeld/models/dmonitoring_model.current index f935ab06b34e271..121871ef2b690b0 100644 --- a/selfdrive/modeld/models/dmonitoring_model.current +++ b/selfdrive/modeld/models/dmonitoring_model.current @@ -1,2 +1,2 @@ -5ec97a39-0095-4cea-adfa-6d72b1966cc1 -26cac7a9757a27c783a365403040a1bd27ccdaea \ No newline at end of file +fa69be01-b430-4504-9d72-7dcb058eb6dd +d9fb22d1c4fa3ca3d201dbc8edf1d0f0918e53e6 diff --git a/selfdrive/modeld/models/dmonitoring_model.onnx b/selfdrive/modeld/models/dmonitoring_model.onnx index a9a1cede31f9e7a..b891902e34d1eaa 100644 Binary files a/selfdrive/modeld/models/dmonitoring_model.onnx and b/selfdrive/modeld/models/dmonitoring_model.onnx differ diff --git a/selfdrive/modeld/models/dmonitoring_model_q.dlc b/selfdrive/modeld/models/dmonitoring_model_q.dlc deleted file mode 100644 index 1ed22c82eec5cda..000000000000000 Binary files a/selfdrive/modeld/models/dmonitoring_model_q.dlc and /dev/null differ diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.onnx index d0117f8756f1953..06fb13600923d82 100644 Binary files a/selfdrive/modeld/models/supercombo.onnx and b/selfdrive/modeld/models/supercombo.onnx differ diff --git a/selfdrive/modeld/parse_model_outputs.py b/selfdrive/modeld/parse_model_outputs.py index af57e11d03c7a9f..4367e9db8a2bcd8 100644 --- a/selfdrive/modeld/parse_model_outputs.py +++ b/selfdrive/modeld/parse_model_outputs.py @@ -1,15 +1,19 @@ import numpy as np from openpilot.selfdrive.modeld.constants import ModelConstants +def safe_exp(x, out=None): + # -11 is around 10**14, more causes float16 overflow + return np.exp(np.clip(x, -np.inf, 11), out=out) + def sigmoid(x): - return 1. / (1. + np.exp(-x)) + return 1. / (1. + safe_exp(-x)) def softmax(x, axis=-1): x -= np.max(x, axis=axis, keepdims=True) if x.dtype == np.float32 or x.dtype == np.float64: - np.exp(x, out=x) + safe_exp(x, out=x) else: - x = np.exp(x) + x = safe_exp(x) x /= np.sum(x, axis=axis, keepdims=True) return x @@ -42,10 +46,9 @@ def parse_mdn(self, name, outs, in_N=0, out_N=1, out_shape=None): raw = outs[name] raw = raw.reshape((raw.shape[0], max(in_N, 1), -1)) - pred_mu = raw[:,:,:(raw.shape[2] - out_N)//2] n_values = (raw.shape[2] - out_N)//2 pred_mu = raw[:,:,:n_values] - pred_std = np.exp(raw[:,:,n_values: 2*n_values]) + pred_std = safe_exp(raw[:,:,n_values: 2*n_values]) if in_N > 1: weights = np.zeros((raw.shape[0], in_N, out_N), dtype=raw.dtype) @@ -88,7 +91,6 @@ def parse_outputs(self, outs: dict[str, np.ndarray]) -> dict[str, np.ndarray]: self.parse_mdn('road_edges', outs, in_N=0, out_N=0, out_shape=(ModelConstants.NUM_ROAD_EDGES,ModelConstants.IDX_N,ModelConstants.LANE_LINES_WIDTH)) self.parse_mdn('pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) self.parse_mdn('road_transform', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) - self.parse_mdn('sim_pose', outs, in_N=0, out_N=0, out_shape=(ModelConstants.POSE_WIDTH,)) 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)) diff --git a/selfdrive/modeld/runners/onnxmodel.py b/selfdrive/modeld/runners/onnxmodel.py index 69b44a5a97116ac..2b174227406521e 100644 --- a/selfdrive/modeld/runners/onnxmodel.py +++ b/selfdrive/modeld/runners/onnxmodel.py @@ -14,8 +14,12 @@ def attributeproto_fp16_to_fp32(attr): attr.data_type = 1 attr.raw_data = float32_list.astype(np.float32).tobytes() -def convert_fp16_to_fp32(path): - model = onnx.load(path) +def convert_fp16_to_fp32(onnx_path_or_bytes): + if isinstance(onnx_path_or_bytes, bytes): + model = onnx.load_from_string(onnx_path_or_bytes) + elif isinstance(onnx_path_or_bytes, str): + model = onnx.load(onnx_path_or_bytes) + for i in model.graph.initializer: if i.data_type == 10: attributeproto_fp16_to_fp32(i) @@ -23,6 +27,8 @@ def convert_fp16_to_fp32(path): if i.type.tensor_type.elem_type == 10: i.type.tensor_type.elem_type = 1 for i in model.graph.node: + if i.op_type == 'Cast' and i.attribute[0].i == 10: + i.attribute[0].i = 1 for a in i.attribute: if hasattr(a, 't'): if a.t.data_type == 10: @@ -61,7 +67,6 @@ class ONNXModel(RunModel): def __init__(self, path, output, runtime, use_tf8, cl_context): self.inputs = {} self.output = output - self.use_tf8 = use_tf8 self.session = create_ort_session(path, fp16_to_fp32=True) self.input_names = [x.name for x in self.session.get_inputs()] @@ -85,7 +90,7 @@ def getCLBuffer(self, name): return None def execute(self): - inputs = {k: (v.view(np.uint8) / 255. if self.use_tf8 and k == 'input_img' else v) for k,v in self.inputs.items()} + inputs = {k: v.view(self.input_dtypes[k]) for k,v in self.inputs.items()} inputs = {k: v.reshape(self.input_shapes[k]).astype(self.input_dtypes[k]) for k,v in inputs.items()} outputs = self.session.run(None, inputs) assert len(outputs) == 1, "Only single model outputs are supported" diff --git a/selfdrive/modeld/runners/runmodel_pyx.pyx b/selfdrive/modeld/runners/runmodel_pyx.pyx index e1b201a6a927429..12b8ec10ff8fe9a 100644 --- a/selfdrive/modeld/runners/runmodel_pyx.pyx +++ b/selfdrive/modeld/runners/runmodel_pyx.pyx @@ -1,5 +1,5 @@ # distutils: language = c++ -# cython: c_string_encoding=ascii +# cython: c_string_encoding=ascii, language_level=3 from libcpp.string cimport string diff --git a/selfdrive/modeld/runners/snpemodel_pyx.pyx b/selfdrive/modeld/runners/snpemodel_pyx.pyx index c3b2b7e9bd3db44..f83b7c8cff389a5 100644 --- a/selfdrive/modeld/runners/snpemodel_pyx.pyx +++ b/selfdrive/modeld/runners/snpemodel_pyx.pyx @@ -1,5 +1,5 @@ # distutils: language = c++ -# cython: c_string_encoding=ascii +# cython: c_string_encoding=ascii, language_level=3 import os from libcpp cimport bool diff --git a/selfdrive/modeld/runners/thneedmodel_pyx.pyx b/selfdrive/modeld/runners/thneedmodel_pyx.pyx index 53487afa1bf582e..6f8fdd255fa5bb3 100644 --- a/selfdrive/modeld/runners/thneedmodel_pyx.pyx +++ b/selfdrive/modeld/runners/thneedmodel_pyx.pyx @@ -1,5 +1,5 @@ # distutils: language = c++ -# cython: c_string_encoding=ascii +# cython: c_string_encoding=ascii, language_level=3 from libcpp cimport bool from libcpp.string cimport string diff --git a/selfdrive/modeld/tests/test_modeld.py b/selfdrive/modeld/tests/test_modeld.py index 1e19a591bf7564e..6927c9e4731ef36 100644 --- a/selfdrive/modeld/tests/test_modeld.py +++ b/selfdrive/modeld/tests/test_modeld.py @@ -3,9 +3,10 @@ import cereal.messaging as messaging from msgq.visionipc import VisionIpcServer, VisionStreamType +from opendbc.car.car_helpers import get_demo_car_params +from openpilot.common.params import Params from openpilot.common.transformations.camera import DEVICE_CAMERAS from openpilot.common.realtime import DT_MDL -from openpilot.selfdrive.car.car_helpers import write_car_param from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state @@ -18,11 +19,11 @@ class TestModeld: def setup_method(self): self.vipc_server = VisionIpcServer("camerad") - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 40, False, CAM.width, CAM.height) - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, CAM.width, CAM.height) - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, CAM.width, CAM.height) + self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 40, CAM.width, CAM.height) + self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, CAM.width, CAM.height) + self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, CAM.width, CAM.height) self.vipc_server.start_listener() - write_car_param() + Params().put("CarParams", get_demo_car_params().to_bytes()) self.sm = messaging.SubMaster(['modelV2', 'cameraOdometry']) self.pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState', 'liveCalibration']) diff --git a/selfdrive/modeld/tests/tf_test/build.sh b/selfdrive/modeld/tests/tf_test/build.sh index 4e92ca069819996..df1d24761e9b077 100755 --- a/selfdrive/modeld/tests/tf_test/build.sh +++ b/selfdrive/modeld/tests/tf_test/build.sh @@ -1,2 +1,2 @@ -#!/bin/bash +#!/usr/bin/env bash clang++ -I /home/batman/one/external/tensorflow/include/ -L /home/batman/one/external/tensorflow/lib -Wl,-rpath=/home/batman/one/external/tensorflow/lib main.cc -ltensorflow diff --git a/selfdrive/modeld/transforms/loadyuv.cc b/selfdrive/modeld/transforms/loadyuv.cc index c7ce7b0830aa4fa..c93f5cd038183df 100644 --- a/selfdrive/modeld/transforms/loadyuv.cc +++ b/selfdrive/modeld/transforms/loadyuv.cc @@ -33,17 +33,8 @@ void loadyuv_destroy(LoadYUVState* s) { void loadyuv_queue(LoadYUVState* s, cl_command_queue q, cl_mem y_cl, cl_mem u_cl, cl_mem v_cl, - cl_mem out_cl, bool do_shift) { + cl_mem out_cl) { cl_int global_out_off = 0; - if (do_shift) { - // shift the image in slot 1 to slot 0, then place the new image in slot 1 - global_out_off += (s->width*s->height) + (s->width/2)*(s->height/2)*2; - CL_CHECK(clSetKernelArg(s->copy_krnl, 0, sizeof(cl_mem), &out_cl)); - CL_CHECK(clSetKernelArg(s->copy_krnl, 1, sizeof(cl_int), &global_out_off)); - const size_t copy_work_size = global_out_off/8; - CL_CHECK(clEnqueueNDRangeKernel(q, s->copy_krnl, 1, NULL, - ©_work_size, NULL, 0, 0, NULL)); - } CL_CHECK(clSetKernelArg(s->loadys_krnl, 0, sizeof(cl_mem), &y_cl)); CL_CHECK(clSetKernelArg(s->loadys_krnl, 1, sizeof(cl_mem), &out_cl)); @@ -72,3 +63,14 @@ void loadyuv_queue(LoadYUVState* s, cl_command_queue q, CL_CHECK(clEnqueueNDRangeKernel(q, s->loaduv_krnl, 1, NULL, &loaduv_work_size, NULL, 0, 0, NULL)); } + +void copy_queue(LoadYUVState* s, cl_command_queue q, cl_mem src, cl_mem dst, + size_t src_offset, size_t dst_offset, size_t size) { + CL_CHECK(clSetKernelArg(s->copy_krnl, 0, sizeof(cl_mem), &src)); + CL_CHECK(clSetKernelArg(s->copy_krnl, 1, sizeof(cl_mem), &dst)); + CL_CHECK(clSetKernelArg(s->copy_krnl, 2, sizeof(cl_int), &src_offset)); + CL_CHECK(clSetKernelArg(s->copy_krnl, 3, sizeof(cl_int), &dst_offset)); + const size_t copy_work_size = size/8; + CL_CHECK(clEnqueueNDRangeKernel(q, s->copy_krnl, 1, NULL, + ©_work_size, NULL, 0, 0, NULL)); +} \ No newline at end of file diff --git a/selfdrive/modeld/transforms/loadyuv.cl b/selfdrive/modeld/transforms/loadyuv.cl index 7dd3d973a3ef693..970187a6d701290 100644 --- a/selfdrive/modeld/transforms/loadyuv.cl +++ b/selfdrive/modeld/transforms/loadyuv.cl @@ -1,7 +1,7 @@ #define UV_SIZE ((TRANSFORMED_WIDTH/2)*(TRANSFORMED_HEIGHT/2)) __kernel void loadys(__global uchar8 const * const Y, - __global float * out, + __global uchar * out, int out_offset) { const int gid = get_global_id(0); @@ -10,13 +10,12 @@ __kernel void loadys(__global uchar8 const * const Y, const int ox = ois % TRANSFORMED_WIDTH; const uchar8 ys = Y[gid]; - const float8 ysf = convert_float8(ys); // 02 // 13 - __global float* outy0; - __global float* outy1; + __global uchar* outy0; + __global uchar* outy1; if ((oy & 1) == 0) { outy0 = out + out_offset; //y0 outy1 = out + out_offset + UV_SIZE*2; //y2 @@ -25,23 +24,24 @@ __kernel void loadys(__global uchar8 const * const Y, outy1 = out + out_offset + UV_SIZE*3; //y3 } - vstore4(ysf.s0246, 0, outy0 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); - vstore4(ysf.s1357, 0, outy1 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); + vstore4(ys.s0246, 0, outy0 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); + vstore4(ys.s1357, 0, outy1 + (oy/2) * (TRANSFORMED_WIDTH/2) + ox/2); } __kernel void loaduv(__global uchar8 const * const in, - __global float8 * out, + __global uchar8 * out, int out_offset) { const int gid = get_global_id(0); const uchar8 inv = in[gid]; - const float8 outv = convert_float8(inv); - out[gid + out_offset / 8] = outv; + out[gid + out_offset / 8] = inv; } -__kernel void copy(__global float8 * inout, - int in_offset) +__kernel void copy(__global uchar8 * in, + __global uchar8 * out, + int in_offset, + int out_offset) { const int gid = get_global_id(0); - inout[gid] = inout[gid + in_offset / 8]; + out[gid + out_offset / 8] = in[gid + in_offset / 8]; } diff --git a/selfdrive/modeld/transforms/loadyuv.h b/selfdrive/modeld/transforms/loadyuv.h index 7d27ef5d468dba4..659059cd25e6106 100644 --- a/selfdrive/modeld/transforms/loadyuv.h +++ b/selfdrive/modeld/transforms/loadyuv.h @@ -13,4 +13,8 @@ void loadyuv_destroy(LoadYUVState* s); void loadyuv_queue(LoadYUVState* s, cl_command_queue q, cl_mem y_cl, cl_mem u_cl, cl_mem v_cl, - cl_mem out_cl, bool do_shift = false); + cl_mem out_cl); + + +void copy_queue(LoadYUVState* s, cl_command_queue q, cl_mem src, cl_mem dst, + size_t src_offset, size_t dst_offset, size_t size); \ No newline at end of file diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index 80af7b71d079c54..54d22c124375012 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -13,7 +13,7 @@ def dmonitoringd_thread(): params = Params() pm = messaging.PubMaster(['driverMonitoringState']) - sm = messaging.SubMaster(['driverStateV2', 'liveCalibration', 'carState', 'controlsState', 'modelV2'], poll='driverStateV2') + sm = messaging.SubMaster(['driverStateV2', 'liveCalibration', 'carState', 'selfdriveState', 'modelV2'], poll='driverStateV2') DM = DriverMonitoring(rhd_saved=params.get_bool("IsRhdDetected"), always_on=params.get_bool("AlwaysOnDM")) diff --git a/selfdrive/monitoring/helpers.py b/selfdrive/monitoring/helpers.py index dfb35182b24dad2..88665778a2b7a92 100644 --- a/selfdrive/monitoring/helpers.py +++ b/selfdrive/monitoring/helpers.py @@ -1,15 +1,15 @@ from math import atan2 -from cereal import car +from cereal import car, log import cereal.messaging as messaging -from openpilot.selfdrive.controls.lib.events import Events +from openpilot.selfdrive.selfdrived.events import Events from openpilot.common.numpy_fast import interp from openpilot.common.realtime import DT_DMON from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.stat_live import RunningStatFilter from openpilot.common.transformations.camera import DEVICE_CAMERAS -EventName = car.CarEvent.EventName +EventName = log.OnroadEvent.EventName # ****************************************************************************************** # NOTE: To fork maintainers. @@ -33,8 +33,8 @@ def __init__(self): self._SG_THRESHOLD = 0.9 self._BLINK_THRESHOLD = 0.865 - self._EE_THRESH11 = 0.25 - self._EE_THRESH12 = 7.5 + self._EE_THRESH11 = 0.4 + self._EE_THRESH12 = 15.0 self._EE_MAX_OFFSET1 = 0.06 self._EE_MIN_OFFSET1 = 0.025 self._EE_THRESH21 = 0.01 @@ -57,7 +57,7 @@ def __init__(self): self._POSESTD_THRESHOLD = 0.3 self._HI_STD_FALLBACK_TIME = int(10 / self._DT_DMON) # fall back to wheel touch if model is uncertain for 10s self._DISTRACTED_FILTER_TS = 0.25 # 0.6Hz - self._ALWAYS_ON_ALERT_MIN_SPEED = 7 + self._ALWAYS_ON_ALERT_MIN_SPEED = 11 self._POSE_CALIB_MIN_SPEED = 13 # 30 mph self._POSE_OFFSET_MIN_COUNT = int(60 / self._DT_DMON) # valid data counts before calibration completes, 1min cumulative @@ -337,9 +337,9 @@ def _update_events(self, driver_engaged, op_engaged, standstill, wrong_gear, car _reaching_audible = self.awareness - self.step_change <= self.threshold_prompt _reaching_terminal = self.awareness - self.step_change <= 0 - standstill_exemption = standstill and _reaching_audible + standstill_orange_exemption = standstill and _reaching_audible always_on_red_exemption = always_on_valid and not op_engaged and _reaching_terminal - always_on_lowspeed_exemption = always_on_valid and not op_engaged and car_speed < self.settings._ALWAYS_ON_ALERT_MIN_SPEED and _reaching_audible + always_on_lowspeed_exemption = always_on_valid and not op_engaged and car_speed < self.settings._ALWAYS_ON_ALERT_MIN_SPEED certainly_distracted = self.driver_distraction_filter.x > 0.63 and self.driver_distracted and self.face_detected maybe_distracted = self.hi_stds > self.settings._HI_STD_FALLBACK_TIME or not self.face_detected @@ -347,7 +347,7 @@ def _update_events(self, driver_engaged, op_engaged, standstill, wrong_gear, car if certainly_distracted or maybe_distracted: # should always be counting if distracted unless at standstill (lowspeed for always-on) and reaching orange # also will not be reaching 0 if DM is active when not engaged - if not (standstill_exemption or always_on_red_exemption or always_on_lowspeed_exemption): + if not (standstill_orange_exemption or always_on_red_exemption or (always_on_lowspeed_exemption and _reaching_audible)): self.awareness = max(self.awareness - self.step_change, -0.1) alert = None @@ -360,7 +360,7 @@ def _update_events(self, driver_engaged, op_engaged, standstill, wrong_gear, car elif self.awareness <= self.threshold_prompt: # prompt orange alert alert = EventName.promptDriverDistracted if self.active_monitoring_mode else EventName.promptDriverUnresponsive - elif self.awareness <= self.threshold_pre: + elif self.awareness <= self.threshold_pre and not always_on_lowspeed_exemption: # pre green alert alert = EventName.preDriverDistracted if self.active_monitoring_mode else EventName.preDriverUnresponsive @@ -403,13 +403,13 @@ def run_step(self, sm): driver_state=sm['driverStateV2'], cal_rpy=sm['liveCalibration'].rpyCalib, car_speed=sm['carState'].vEgo, - op_engaged=sm['controlsState'].enabled + op_engaged=sm['selfdriveState'].enabled ) # Update distraction events self._update_events( driver_engaged=sm['carState'].steeringPressed or sm['carState'].gasPressed, - op_engaged=sm['controlsState'].enabled, + op_engaged=sm['selfdriveState'].enabled, standstill=sm['carState'].standstill, wrong_gear=sm['carState'].gearShifter in [car.CarState.GearShifter.reverse, car.CarState.GearShifter.park], car_speed=sm['carState'].vEgo diff --git a/selfdrive/monitoring/test_monitoring.py b/selfdrive/monitoring/test_monitoring.py index f750437dc369519..2a20b20dc106b36 100644 --- a/selfdrive/monitoring/test_monitoring.py +++ b/selfdrive/monitoring/test_monitoring.py @@ -1,10 +1,10 @@ import numpy as np -from cereal import car, log +from cereal import log from openpilot.common.realtime import DT_DMON from openpilot.selfdrive.monitoring.helpers import DriverMonitoring, DRIVER_MONITOR_SETTINGS -EventName = car.CarEvent.EventName +EventName = log.OnroadEvent.EventName dm_settings = DRIVER_MONITOR_SETTINGS() TEST_TIMESPAN = 120 # seconds diff --git a/selfdrive/navd/.gitignore b/selfdrive/navd/.gitignore deleted file mode 100644 index 4801d60a2c86c81..000000000000000 --- a/selfdrive/navd/.gitignore +++ /dev/null @@ -1,6 +0,0 @@ -moc_* -*.moc - -mapsd -map_renderer -libmap_renderer.so diff --git a/selfdrive/navd/README.md b/selfdrive/navd/README.md deleted file mode 100644 index 81de8ae39f6c09d..000000000000000 --- a/selfdrive/navd/README.md +++ /dev/null @@ -1,24 +0,0 @@ -# navigation - -This directory contains two daemons, `navd` and `mapsd`, which support navigation in the openpilot stack. - -### navd - -`navd` takes in a route through the `NavDestination` param and sends out two packets: `navRoute` and `navInstruction`. These packets contain the coordinates of the planned route and turn-by-turn instructions. - -### map renderer - -The map renderer listens for the `navRoute` and publishes a simplified rendered map view over VisionIPC. The rendered maps look like this: - -![](https://i.imgur.com/oZLfmwq.png) - -## development - -Currently, [mapbox](https://www.mapbox.com/) is used for navigation. - -* get an API token: https://docs.mapbox.com/help/glossary/access-token/ -* set an API token using the `MAPBOX_TOKEN` environment variable -* routes/destinations are set through the `NavDestination` param - * use `set_destination.py` for debugging -* edit the map: https://www.mapbox.com/contribute -* mapbox API playground: https://docs.mapbox.com/playground/ diff --git a/selfdrive/navd/SConscript b/selfdrive/navd/SConscript deleted file mode 100644 index 295e8127dbc7f6d..000000000000000 --- a/selfdrive/navd/SConscript +++ /dev/null @@ -1,20 +0,0 @@ -Import('qt_env', 'arch', 'common', 'messaging', 'visionipc', 'transformations') - -map_env = qt_env.Clone() -libs = ['qt_widgets', 'qt_util', 'QMapLibre', common, messaging, visionipc, transformations, - '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/maplibre-native-qt/{arch}/lib").srcnode().abspath - map_env["RPATH"] += [rpath, ] - - style_path = File("style.json").abspath - map_env['CXXFLAGS'].append(f'-DSTYLE_PATH=\\"{style_path}\\"') - - map_env["RPATH"].append(Dir('.').abspath) - map_env["LIBPATH"].append(Dir('.').abspath) - maplib = map_env.SharedLibrary("maprender", ["map_renderer.cc"], LIBS=libs) - # map_env.Program("mapsd", ["main.cc", ], LIBS=[maplib[0].get_path(), ] + libs) diff --git a/selfdrive/navd/helpers.py b/selfdrive/navd/helpers.py deleted file mode 100644 index 0f0410c2c7ccda2..000000000000000 --- a/selfdrive/navd/helpers.py +++ /dev/null @@ -1,189 +0,0 @@ -from __future__ import annotations - -import json -import math -from typing import Any, cast - -from openpilot.common.conversions import Conversions -from openpilot.common.numpy_fast import clip -from openpilot.common.params import Params - -DIRECTIONS = ('left', 'right', 'straight') -MODIFIABLE_DIRECTIONS = ('left', 'right') - -EARTH_MEAN_RADIUS = 6371007.2 -SPEED_CONVERSIONS = { - 'km/h': Conversions.KPH_TO_MS, - 'mph': Conversions.MPH_TO_MS, - } - - -class Coordinate: - def __init__(self, latitude: float, longitude: float) -> None: - self.latitude = latitude - self.longitude = longitude - self.annotations: dict[str, float] = {} - - @classmethod - def from_mapbox_tuple(cls, t: tuple[float, float]) -> Coordinate: - return cls(t[1], t[0]) - - def as_dict(self) -> dict[str, float]: - return {'latitude': self.latitude, 'longitude': self.longitude} - - def __str__(self) -> str: - return f'Coordinate({self.latitude}, {self.longitude})' - - def __repr__(self) -> str: - return self.__str__() - - def __eq__(self, other) -> bool: - if not isinstance(other, Coordinate): - return False - return (self.latitude == other.latitude) and (self.longitude == other.longitude) - - def __sub__(self, other: Coordinate) -> Coordinate: - return Coordinate(self.latitude - other.latitude, self.longitude - other.longitude) - - def __add__(self, other: Coordinate) -> Coordinate: - return Coordinate(self.latitude + other.latitude, self.longitude + other.longitude) - - def __mul__(self, c: float) -> Coordinate: - return Coordinate(self.latitude * c, self.longitude * c) - - def dot(self, other: Coordinate) -> float: - return self.latitude * other.latitude + self.longitude * other.longitude - - def distance_to(self, other: Coordinate) -> float: - # Haversine formula - dlat = math.radians(other.latitude - self.latitude) - dlon = math.radians(other.longitude - self.longitude) - - haversine_dlat = math.sin(dlat / 2.0) - haversine_dlat *= haversine_dlat - haversine_dlon = math.sin(dlon / 2.0) - haversine_dlon *= haversine_dlon - - y = haversine_dlat \ - + math.cos(math.radians(self.latitude)) \ - * math.cos(math.radians(other.latitude)) \ - * haversine_dlon - x = 2 * math.asin(math.sqrt(y)) - return x * EARTH_MEAN_RADIUS - - -def minimum_distance(a: Coordinate, b: Coordinate, p: Coordinate): - if a.distance_to(b) < 0.01: - return a.distance_to(p) - - ap = p - a - ab = b - a - t = clip(ap.dot(ab) / ab.dot(ab), 0.0, 1.0) - projection = a + ab * t - return projection.distance_to(p) - - -def distance_along_geometry(geometry: list[Coordinate], pos: Coordinate) -> float: - if len(geometry) <= 2: - return geometry[0].distance_to(pos) - - # 1. Find segment that is closest to current position - # 2. Total distance is sum of distance to start of closest segment - # + all previous segments - total_distance = 0.0 - total_distance_closest = 0.0 - closest_distance = 1e9 - - for i in range(len(geometry) - 1): - d = minimum_distance(geometry[i], geometry[i + 1], pos) - - if d < closest_distance: - closest_distance = d - total_distance_closest = total_distance + geometry[i].distance_to(pos) - - total_distance += geometry[i].distance_to(geometry[i + 1]) - - return total_distance_closest - - -def coordinate_from_param(param: str, params: Params = None) -> Coordinate | None: - if params is None: - params = Params() - - json_str = params.get(param) - if json_str is None: - return None - - pos = json.loads(json_str) - if 'latitude' not in pos or 'longitude' not in pos: - return None - - return Coordinate(pos['latitude'], pos['longitude']) - - -def string_to_direction(direction: str) -> str: - for d in DIRECTIONS: - if d in direction: - if 'slight' in direction and d in MODIFIABLE_DIRECTIONS: - return 'slight' + d.capitalize() - return d - return 'none' - - -def maxspeed_to_ms(maxspeed: dict[str, str | float]) -> float: - unit = cast(str, maxspeed['unit']) - speed = cast(float, maxspeed['speed']) - return SPEED_CONVERSIONS[unit] * speed - - -def field_valid(dat: dict, field: str) -> bool: - return field in dat and dat[field] is not None - - -def parse_banner_instructions(banners: Any, distance_to_maneuver: float = 0.0) -> dict[str, Any] | None: - if not len(banners): - return None - - instruction = {} - - # A segment can contain multiple banners, find one that we need to show now - current_banner = banners[0] - for banner in banners: - if distance_to_maneuver < banner['distanceAlongGeometry']: - current_banner = banner - - # Only show banner when close enough to maneuver - instruction['showFull'] = distance_to_maneuver < current_banner['distanceAlongGeometry'] - - # Primary - p = current_banner['primary'] - if field_valid(p, 'text'): - instruction['maneuverPrimaryText'] = p['text'] - if field_valid(p, 'type'): - instruction['maneuverType'] = p['type'] - if field_valid(p, 'modifier'): - instruction['maneuverModifier'] = p['modifier'] - - # Secondary - if field_valid(current_banner, 'secondary'): - instruction['maneuverSecondaryText'] = current_banner['secondary']['text'] - - # Lane lines - if field_valid(current_banner, 'sub'): - lanes = [] - for component in current_banner['sub']['components']: - if component['type'] != 'lane': - continue - - lane = { - 'active': component['active'], - 'directions': [string_to_direction(d) for d in component['directions']], - } - - if field_valid(component, 'active_direction'): - lane['activeDirection'] = string_to_direction(component['active_direction']) - - lanes.append(lane) - instruction['lanes'] = lanes - - return instruction diff --git a/selfdrive/navd/main.cc b/selfdrive/navd/main.cc deleted file mode 100644 index 2e7b4d3b60fc61e..000000000000000 --- a/selfdrive/navd/main.cc +++ /dev/null @@ -1,29 +0,0 @@ -#include -#include - -#include -#include - -#include "common/util.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/navd/map_renderer.h" -#include "system/hardware/hw.h" - -int main(int argc, char *argv[]) { - Hardware::config_cpu_rendering(true); - - qInstallMessageHandler(swagLogMessageHandler); - setpriority(PRIO_PROCESS, 0, -20); - int ret = util::set_core_affinity({0, 1, 2, 3}); - assert(ret == 0); - - QApplication app(argc, argv); - std::signal(SIGINT, sigTermHandler); - std::signal(SIGTERM, sigTermHandler); - - MapRenderer * m = new MapRenderer(get_mapbox_settings()); - assert(m); - - return app.exec(); -} diff --git a/selfdrive/navd/map_renderer.cc b/selfdrive/navd/map_renderer.cc deleted file mode 100644 index 1e57ad3e7c9f881..000000000000000 --- a/selfdrive/navd/map_renderer.cc +++ /dev/null @@ -1,338 +0,0 @@ -#include "selfdrive/navd/map_renderer.h" - -#include -#include -#include -#include - -#include "common/util.h" -#include "common/timing.h" -#include "common/swaglog.h" -#include "selfdrive/ui/qt/maps/map_helpers.h" - -const float DEFAULT_ZOOM = 13.5; // Don't go below 13 or features will start to disappear -const int HEIGHT = 256, WIDTH = 256; -const int NUM_VIPC_BUFFERS = 4; - -const int EARTH_CIRCUMFERENCE_METERS = 40075000; -const int EARTH_RADIUS_METERS = 6378137; -const int PIXELS_PER_TILE = 256; -const int MAP_OFFSET = 128; - -const bool TEST_MODE = getenv("MAP_RENDER_TEST_MODE"); -const int LLK_DECIMATION = TEST_MODE ? 1 : 10; - -float get_zoom_level_for_scale(float lat, float meters_per_pixel) { - float meters_per_tile = meters_per_pixel * PIXELS_PER_TILE; - float num_tiles = cos(DEG2RAD(lat)) * EARTH_CIRCUMFERENCE_METERS / meters_per_tile; - return log2(num_tiles) - 1; -} - -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 QMapLibre::Coordinate(RAD2DEG(lat2), RAD2DEG(lon2)); -} - - -MapRenderer::MapRenderer(const QMapLibre::Settings &settings, bool online) : m_settings(settings) { - QSurfaceFormat fmt; - fmt.setRenderableType(QSurfaceFormat::OpenGLES); - - m_settings.setMapMode(QMapLibre::Settings::MapMode::Static); - - ctx = std::make_unique(); - ctx->setFormat(fmt); - ctx->create(); - assert(ctx->isValid()); - - surface = std::make_unique(); - surface->setFormat(ctx->format()); - surface->create(); - - ctx->makeCurrent(surface.get()); - assert(QOpenGLContext::currentContext() == ctx.get()); - - gl_functions.reset(ctx->functions()); - gl_functions->initializeOpenGLFunctions(); - - QOpenGLFramebufferObjectFormat fbo_format; - fbo.reset(new QOpenGLFramebufferObject(WIDTH, HEIGHT, fbo_format)); - - std::string style = util::read_file(STYLE_PATH); - 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; - - m_map->resize(fbo->size()); - m_map->setFramebufferObject(fbo->handle(), fbo->size()); - gl_functions->glViewport(0, 0, WIDTH, HEIGHT); - - 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 != 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(), &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()); - }); - - QObject::connect(m_map.data(), &QMapLibre::Map::staticRenderFinished, [=](const QString &error) { - rendering = false; - - if (!error.isEmpty()) { - LOGE("Static map rendering failed with error: '%s'\n", error.toStdString().c_str()); - } else if (vipc_server != nullptr) { - double end_render_t = millis_since_boot(); - publish((end_render_t - start_render_t) / 1000.0, true); - last_llk_rendered = (*sm)["liveLocationKalman"].getLogMonoTime(); - } - }); - - if (online) { - vipc_server.reset(new VisionIpcServer("navd")); - vipc_server->create_buffers(VisionStreamType::VISION_STREAM_MAP, NUM_VIPC_BUFFERS, false, WIDTH, HEIGHT); - vipc_server->start_listener(); - - pm.reset(new PubMaster({"navThumbnail", "mapRenderState"})); - sm.reset(new SubMaster({"liveLocationKalman", "navRoute"}, {"liveLocationKalman"})); - - timer = new QTimer(this); - timer->setSingleShot(true); - QObject::connect(timer, SIGNAL(timeout()), this, SLOT(msgUpdate())); - timer->start(0); - } -} - -void MapRenderer::msgUpdate() { - sm->update(1000); - - if (sm->updated("liveLocationKalman")) { - auto location = (*sm)["liveLocationKalman"].getLiveLocationKalman(); - auto pos = location.getPositionGeodetic(); - auto orientation = location.getCalibratedOrientationNED(); - - if ((sm->rcv_frame("liveLocationKalman") % LLK_DECIMATION) == 0) { - float bearing = RAD2DEG(orientation.getValue()[2]); - updatePosition(get_point_along_line(pos.getValue()[0], pos.getValue()[1], bearing, MAP_OFFSET), bearing); - - if (!rendering) { - update(); - } - - if (!rendered()) { - publish(0, false); - } - } - - - } - - if (sm->updated("navRoute")) { - QList route; - auto coords = (*sm)["navRoute"].getNavRoute().getCoordinates(); - for (auto const &c : coords) { - route.push_back(QGeoCoordinate(c.getLatitude(), c.getLongitude())); - } - updateRoute(route); - } - - // schedule next update - timer->start(0); -} - -void MapRenderer::updatePosition(QMapLibre::Coordinate position, float bearing) { - if (m_map.isNull()) { - return; - } - - // Choose a scale that ensures above 13 zoom level up to and above 75deg of lat - float meters_per_pixel = 2; - float zoom = get_zoom_level_for_scale(position.first, meters_per_pixel); - - m_map->setCoordinate(position); - m_map->setBearing(bearing); - m_map->setZoom(zoom); - if (!rendering) { - update(); - } -} - -bool MapRenderer::loaded() { - return m_map->isFullyLoaded(); -} - -void MapRenderer::update() { - rendering = true; - gl_functions->glClear(GL_COLOR_BUFFER_BIT); - start_render_t = millis_since_boot(); - m_map->startStaticRender(); -} - -void MapRenderer::sendThumbnail(const uint64_t ts, const kj::Array &buf) { - MessageBuilder msg; - auto thumbnaild = msg.initEvent().initNavThumbnail(); - thumbnaild.setFrameId(frame_id); - thumbnaild.setTimestampEof(ts); - thumbnaild.setThumbnail(buf); - pm->send("navThumbnail", msg); -} - -void MapRenderer::publish(const double render_time, const bool loaded) { - QImage cap = fbo->toImage().convertToFormat(QImage::Format_RGB888, Qt::AutoColor); - - auto location = (*sm)["liveLocationKalman"].getLiveLocationKalman(); - bool valid = loaded && (location.getStatus() == cereal::LiveLocationKalman::Status::VALID) && location.getPositionGeodetic().getValid(); - ever_loaded = ever_loaded || loaded; - uint64_t ts = nanos_since_boot(); - VisionBuf* buf = vipc_server->get_buffer(VisionStreamType::VISION_STREAM_MAP); - VisionIpcBufExtra extra = { - .frame_id = frame_id, - .timestamp_sof = (*sm)["liveLocationKalman"].getLogMonoTime(), - .timestamp_eof = ts, - .valid = valid, - }; - - assert(cap.sizeInBytes() >= buf->len); - uint8_t* dst = (uint8_t*)buf->addr; - uint8_t* src = cap.bits(); - - // RGB to greyscale - memset(dst, 128, buf->len); - for (int i = 0; i < WIDTH * HEIGHT; i++) { - dst[i] = src[i * 3]; - } - - vipc_server->send(buf, &extra); - - // Send thumbnail - if (TEST_MODE) { - // Full image in thumbnails in test mode - kj::Array buffer_kj = kj::heapArray((const capnp::byte*)cap.bits(), cap.sizeInBytes()); - sendThumbnail(ts, buffer_kj); - } else if (frame_id % 100 == 0) { - // Write jpeg into buffer - QByteArray buffer_bytes; - QBuffer buffer(&buffer_bytes); - buffer.open(QIODevice::WriteOnly); - cap.save(&buffer, "JPG", 50); - - kj::Array buffer_kj = kj::heapArray((const capnp::byte*)buffer_bytes.constData(), buffer_bytes.size()); - sendThumbnail(ts, buffer_kj); - } - - // Send state msg - MessageBuilder msg; - auto evt = msg.initEvent(); - auto state = evt.initMapRenderState(); - evt.setValid(valid); - state.setLocationMonoTime((*sm)["liveLocationKalman"].getLogMonoTime()); - state.setRenderTime(render_time); - state.setFrameId(frame_id); - pm->send("mapRenderState", msg); - - frame_id++; -} - -uint8_t* MapRenderer::getImage() { - QImage cap = fbo->toImage().convertToFormat(QImage::Format_RGB888, Qt::AutoColor); - - uint8_t* src = cap.bits(); - uint8_t* dst = new uint8_t[WIDTH * HEIGHT]; - - // RGB to greyscale - for (int i = 0; i < WIDTH * HEIGHT; i++) { - dst[i] = src[i * 3]; - } - - return dst; -} - -void MapRenderer::updateRoute(QList coordinates) { - if (m_map.isNull()) return; - initLayers(); - - auto route_points = coordinate_list_to_collection(coordinates); - QMapLibre::Feature feature(QMapLibre::Feature::LineStringType, route_points, {}, {}); - QVariantMap navSource; - navSource["type"] = "geojson"; - navSource["data"] = QVariant::fromValue(feature); - m_map->updateSource("navSource", navSource); - m_map->setLayoutProperty("navLayer", "visibility", "visible"); -} - -void MapRenderer::initLayers() { - if (!m_map->layerExists("navLayer")) { - LOGD("Initializing navLayer"); - QVariantMap nav; - nav["type"] = "line"; - nav["source"] = "navSource"; - 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"); - } -} - -MapRenderer::~MapRenderer() { -} - -extern "C" { - MapRenderer* map_renderer_init(char *maps_host = nullptr, char *token = nullptr) { - char *argv[] = { - (char*)"navd", - nullptr - }; - int argc = 0; - QApplication *app = new QApplication(argc, argv); - assert(app); - - QMapLibre::Settings settings; - settings.setProviderTemplate(QMapLibre::Settings::ProviderTemplate::MapboxProvider); - settings.setApiBaseUrl(maps_host == nullptr ? MAPS_HOST : maps_host); - settings.setApiKey(token == nullptr ? get_mapbox_token() : token); - - return new MapRenderer(settings, false); - } - - void map_renderer_update_position(MapRenderer *inst, float lat, float lon, float bearing) { - inst->updatePosition({lat, lon}, bearing); - QApplication::processEvents(); - } - - void map_renderer_update_route(MapRenderer *inst, char* polyline) { - inst->updateRoute(polyline_to_coordinate_list(QString::fromUtf8(polyline))); - } - - void map_renderer_update(MapRenderer *inst) { - inst->update(); - } - - void map_renderer_process(MapRenderer *inst) { - QApplication::processEvents(); - } - - bool map_renderer_loaded(MapRenderer *inst) { - return inst->loaded(); - } - - uint8_t * map_renderer_get_image(MapRenderer *inst) { - return inst->getImage(); - } - - void map_renderer_free_image(MapRenderer *inst, uint8_t * buf) { - delete[] buf; - } -} diff --git a/selfdrive/navd/map_renderer.h b/selfdrive/navd/map_renderer.h deleted file mode 100644 index 956c1d54bc6a439..000000000000000 --- a/selfdrive/navd/map_renderer.h +++ /dev/null @@ -1,61 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "msgq/visionipc/visionipc_server.h" -#include "cereal/messaging/messaging.h" - - -class MapRenderer : public QObject { - Q_OBJECT - -public: - MapRenderer(const QMapLibre::Settings &, bool online=true); - uint8_t* getImage(); - void update(); - bool loaded(); - ~MapRenderer(); - -private: - std::unique_ptr ctx; - std::unique_ptr surface; - std::unique_ptr gl_functions; - std::unique_ptr fbo; - - std::unique_ptr vipc_server; - std::unique_ptr pm; - std::unique_ptr sm; - void publish(const double render_time, const bool loaded); - void sendThumbnail(const uint64_t ts, const kj::Array &buf); - - QMapLibre::Settings m_settings; - QScopedPointer m_map; - - void initLayers(); - - double start_render_t; - uint32_t frame_id = 0; - uint64_t last_llk_rendered = 0; - bool rendering = false; - bool rendered() { - return last_llk_rendered == (*sm)["liveLocationKalman"].getLogMonoTime(); - } - - QTimer* timer; - bool ever_loaded = false; - -public slots: - void updatePosition(QMapLibre::Coordinate position, float bearing); - void updateRoute(QList coordinates); - void msgUpdate(); -}; diff --git a/selfdrive/navd/map_renderer.py b/selfdrive/navd/map_renderer.py deleted file mode 100755 index e44b883436cb0b9..000000000000000 --- a/selfdrive/navd/map_renderer.py +++ /dev/null @@ -1,100 +0,0 @@ -#!/usr/bin/env python3 -# You might need to uninstall the PyQt5 pip package to avoid conflicts - -import os -import time -import numpy as np -import polyline -from cffi import FFI - -from openpilot.common.ffi_wrapper import suffix -from openpilot.common.basedir import BASEDIR - -HEIGHT = WIDTH = SIZE = 256 -METERS_PER_PIXEL = 2 - - -def get_ffi(): - lib = os.path.join(BASEDIR, "selfdrive", "navd", "libmaprender" + suffix()) - - ffi = FFI() - ffi.cdef(""" -void* map_renderer_init(char *maps_host, char *token); -void map_renderer_update_position(void *inst, float lat, float lon, float bearing); -void map_renderer_update_route(void *inst, char *polyline); -void map_renderer_update(void *inst); -void map_renderer_process(void *inst); -bool map_renderer_loaded(void *inst); -uint8_t* map_renderer_get_image(void *inst); -void map_renderer_free_image(void *inst, uint8_t *buf); -""") - return ffi, ffi.dlopen(lib) - - -def wait_ready(lib, renderer, timeout=None): - st = time.time() - while not lib.map_renderer_loaded(renderer): - lib.map_renderer_update(renderer) - - # The main qt app is not execed, so we need to periodically process events for e.g. network requests - lib.map_renderer_process(renderer) - - time.sleep(0.01) - - if timeout is not None and time.time() - st > timeout: - raise TimeoutError("Timeout waiting for map renderer to be ready") - - -def get_image(lib, renderer): - buf = lib.map_renderer_get_image(renderer) - r = list(buf[0:WIDTH * HEIGHT]) - lib.map_renderer_free_image(renderer, buf) - - # Convert to numpy - r = np.asarray(r) - return r.reshape((WIDTH, HEIGHT)) - - -def navRoute_to_polyline(nr): - coords = [(m.latitude, m.longitude) for m in nr.navRoute.coordinates] - return coords_to_polyline(coords) - - -def coords_to_polyline(coords): - # TODO: where does this factor of 10 come from? - return polyline.encode([(lat * 10., lon * 10.) for lat, lon in coords]) - - -def polyline_to_coords(p): - coords = polyline.decode(p) - return [(lat / 10., lon / 10.) for lat, lon in coords] - - - -if __name__ == "__main__": - import matplotlib.pyplot as plt - - ffi, lib = get_ffi() - renderer = lib.map_renderer_init(ffi.NULL, ffi.NULL) - wait_ready(lib, renderer) - - geometry = r"{yxk}@|obn~Eg@@eCFqc@J{RFw@?kA@gA?q|@Riu@NuJBgi@ZqVNcRBaPBkG@iSD{I@_H@cH?gG@mG@gG?aD@{LDgDDkVVyQLiGDgX@q_@@qI@qKhS{R~[}NtYaDbGoIvLwNfP_b@|f@oFnF_JxHel@bf@{JlIuxAlpAkNnLmZrWqFhFoh@jd@kX|TkJxH_RnPy^|[uKtHoZ~Um`DlkCorC``CuShQogCtwB_ThQcr@fk@sVrWgRhVmSb\\oj@jxA{Qvg@u]tbAyHzSos@xjBeKbWszAbgEc~@~jCuTrl@cYfo@mRn\\_m@v}@ij@jp@om@lk@y|A`pAiXbVmWzUod@xj@wNlTw}@|uAwSn\\kRfYqOdS_IdJuK`KmKvJoOhLuLbHaMzGwO~GoOzFiSrEsOhD}PhCqw@vJmnAxSczA`Vyb@bHk[fFgl@pJeoDdl@}}@zIyr@hG}X`BmUdBcM^aRR}Oe@iZc@mR_@{FScHxAn_@vz@zCzH~GjPxAhDlB~DhEdJlIbMhFfG|F~GlHrGjNjItLnGvQ~EhLnBfOn@p`@AzAAvn@CfC?fc@`@lUrArStCfSxEtSzGxM|ElFlBrOzJlEbDnC~BfDtCnHjHlLvMdTnZzHpObOf^pKla@~G|a@dErg@rCbj@zArYlj@ttJ~AfZh@r]LzYg@`TkDbj@gIdv@oE|i@kKzhA{CdNsEfOiGlPsEvMiDpLgBpHyB`MkB|MmArPg@|N?|P^rUvFz~AWpOCdAkB|PuB`KeFfHkCfGy@tAqC~AsBPkDs@uAiAcJwMe@s@eKkPMoXQux@EuuCoH?eI?Kas@}Dy@wAUkMOgDL" # noqa: E501 - lib.map_renderer_update_route(renderer, geometry.encode()) - - POSITIONS = [ - (32.71569271952601, -117.16384270868463, 0), (32.71569271952601, -117.16384270868463, 45), # San Diego - (52.378641991483136, 4.902623379456488, 0), (52.378641991483136, 4.902623379456488, 45), # Amsterdam - ] - plt.figure() - - for i, pos in enumerate(POSITIONS): - t = time.time() - lib.map_renderer_update_position(renderer, *pos) - wait_ready(lib, renderer) - - print(f"{pos} took {time.time() - t:.2f} s") - - plt.subplot(2, 2, i + 1) - plt.imshow(get_image(lib, renderer), cmap='gray') - - plt.show() diff --git a/selfdrive/navd/navd.py b/selfdrive/navd/navd.py deleted file mode 100755 index 8cfc495f272a409..000000000000000 --- a/selfdrive/navd/navd.py +++ /dev/null @@ -1,368 +0,0 @@ -#!/usr/bin/env python3 -import json -import math -import os -import threading - -import requests - -import cereal.messaging as messaging -from cereal import log -from openpilot.common.api import Api -from openpilot.common.params import Params -from openpilot.common.realtime import Ratekeeper -from openpilot.selfdrive.navd.helpers import (Coordinate, coordinate_from_param, - distance_along_geometry, maxspeed_to_ms, - minimum_distance, - parse_banner_instructions) -from openpilot.common.swaglog import cloudlog - -REROUTE_DISTANCE = 25 -MANEUVER_TRANSITION_THRESHOLD = 10 -REROUTE_COUNTER_MIN = 3 - - -class RouteEngine: - def __init__(self, sm, pm): - self.sm = sm - self.pm = pm - - self.params = Params() - - # Get last gps position from params - self.last_position = coordinate_from_param("LastGPSPosition", self.params) - self.last_bearing = None - - self.gps_ok = False - self.localizer_valid = False - - self.nav_destination = None - self.step_idx = None - self.route = None - self.route_geometry = None - - self.recompute_backoff = 0 - self.recompute_countdown = 0 - - self.ui_pid = None - - self.reroute_counter = 0 - - - self.api = None - self.mapbox_token = None - if "MAPBOX_TOKEN" in os.environ: - self.mapbox_token = os.environ["MAPBOX_TOKEN"] - self.mapbox_host = "https://api.mapbox.com" - else: - self.api = Api(self.params.get("DongleId", encoding='utf8')) - self.mapbox_host = "https://maps.comma.ai" - - def update(self): - self.sm.update(0) - - if self.sm.updated["managerState"]: - ui_pid = [p.pid for p in self.sm["managerState"].processes if p.name == "ui" and p.running] - if ui_pid: - if self.ui_pid and self.ui_pid != ui_pid[0]: - cloudlog.warning("UI restarting, sending route") - threading.Timer(5.0, self.send_route).start() - self.ui_pid = ui_pid[0] - - self.update_location() - try: - self.recompute_route() - self.send_instruction() - except Exception: - cloudlog.exception("navd.failed_to_compute") - - def update_location(self): - location = self.sm['liveLocationKalman'] - self.gps_ok = location.gpsOK - - self.localizer_valid = (location.status == log.LiveLocationKalman.Status.valid) and location.positionGeodetic.valid - - if self.localizer_valid: - self.last_bearing = math.degrees(location.calibratedOrientationNED.value[2]) - self.last_position = Coordinate(location.positionGeodetic.value[0], location.positionGeodetic.value[1]) - - def recompute_route(self): - if self.last_position is None: - return - - new_destination = coordinate_from_param("NavDestination", self.params) - if new_destination is None: - self.clear_route() - self.reset_recompute_limits() - return - - should_recompute = self.should_recompute() - if new_destination != self.nav_destination: - cloudlog.warning(f"Got new destination from NavDestination param {new_destination}") - should_recompute = True - - # Don't recompute when GPS drifts in tunnels - if not self.gps_ok and self.step_idx is not None: - return - - if self.recompute_countdown == 0 and should_recompute: - self.recompute_countdown = 2**self.recompute_backoff - self.recompute_backoff = min(6, self.recompute_backoff + 1) - self.calculate_route(new_destination) - self.reroute_counter = 0 - else: - self.recompute_countdown = max(0, self.recompute_countdown - 1) - - def calculate_route(self, destination): - cloudlog.warning(f"Calculating route {self.last_position} -> {destination}") - self.nav_destination = destination - - lang = self.params.get('LanguageSetting', encoding='utf8') - if lang is not None: - lang = lang.replace('main_', '') - - token = self.mapbox_token - if token is None: - token = self.api.get_token() - - params = { - 'access_token': token, - 'annotations': 'maxspeed', - 'geometries': 'geojson', - 'overview': 'full', - 'steps': 'true', - 'banner_instructions': 'true', - 'alternatives': 'false', - 'language': lang, - } - - # TODO: move waypoints into NavDestination param? - waypoints = self.params.get('NavDestinationWaypoints', encoding='utf8') - waypoint_coords = [] - if waypoints is not None and len(waypoints) > 0: - waypoint_coords = json.loads(waypoints) - - coords = [ - (self.last_position.longitude, self.last_position.latitude), - *waypoint_coords, - (destination.longitude, destination.latitude) - ] - params['waypoints'] = f'0;{len(coords)-1}' - if self.last_bearing is not None: - params['bearings'] = f"{(self.last_bearing + 360) % 360:.0f},90" + (';'*(len(coords)-1)) - - coords_str = ';'.join([f'{lon},{lat}' for lon, lat in coords]) - url = self.mapbox_host + '/directions/v5/mapbox/driving-traffic/' + coords_str - try: - resp = requests.get(url, params=params, timeout=10) - if resp.status_code != 200: - cloudlog.event("API request failed", status_code=resp.status_code, text=resp.text, error=True) - resp.raise_for_status() - - r = resp.json() - if len(r['routes']): - self.route = r['routes'][0]['legs'][0]['steps'] - self.route_geometry = [] - - maxspeed_idx = 0 - maxspeeds = r['routes'][0]['legs'][0]['annotation']['maxspeed'] - - # Convert coordinates - for step in self.route: - coords = [] - - for c in step['geometry']['coordinates']: - coord = Coordinate.from_mapbox_tuple(c) - - # Last step does not have maxspeed - if (maxspeed_idx < len(maxspeeds)): - maxspeed = maxspeeds[maxspeed_idx] - if ('unknown' not in maxspeed) and ('none' not in maxspeed): - coord.annotations['maxspeed'] = maxspeed_to_ms(maxspeed) - - coords.append(coord) - maxspeed_idx += 1 - - self.route_geometry.append(coords) - maxspeed_idx -= 1 # Every segment ends with the same coordinate as the start of the next - - self.step_idx = 0 - else: - cloudlog.warning("Got empty route response") - self.clear_route() - - # clear waypoints to avoid a re-route including past waypoints - # TODO: only clear once we're past a waypoint - self.params.remove('NavDestinationWaypoints') - - except requests.exceptions.RequestException: - cloudlog.exception("failed to get route") - self.clear_route() - - self.send_route() - - def send_instruction(self): - msg = messaging.new_message('navInstruction', valid=True) - - if self.step_idx is None: - msg.valid = False - self.pm.send('navInstruction', msg) - return - - step = self.route[self.step_idx] - geometry = self.route_geometry[self.step_idx] - along_geometry = distance_along_geometry(geometry, self.last_position) - distance_to_maneuver_along_geometry = step['distance'] - along_geometry - - # Banner instructions are for the following maneuver step, don't use empty last step - banner_step = step - if not len(banner_step['bannerInstructions']) and self.step_idx == len(self.route) - 1: - banner_step = self.route[max(self.step_idx - 1, 0)] - - # Current instruction - msg.navInstruction.maneuverDistance = distance_to_maneuver_along_geometry - instruction = parse_banner_instructions(banner_step['bannerInstructions'], distance_to_maneuver_along_geometry) - if instruction is not None: - for k,v in instruction.items(): - setattr(msg.navInstruction, k, v) - - # All instructions - maneuvers = [] - for i, step_i in enumerate(self.route): - if i < self.step_idx: - distance_to_maneuver = -sum(self.route[j]['distance'] for j in range(i+1, self.step_idx)) - along_geometry - elif i == self.step_idx: - distance_to_maneuver = distance_to_maneuver_along_geometry - else: - distance_to_maneuver = distance_to_maneuver_along_geometry + sum(self.route[j]['distance'] for j in range(self.step_idx+1, i+1)) - - instruction = parse_banner_instructions(step_i['bannerInstructions'], distance_to_maneuver) - if instruction is None: - continue - maneuver = {'distance': distance_to_maneuver} - if 'maneuverType' in instruction: - maneuver['type'] = instruction['maneuverType'] - if 'maneuverModifier' in instruction: - maneuver['modifier'] = instruction['maneuverModifier'] - maneuvers.append(maneuver) - - msg.navInstruction.allManeuvers = maneuvers - - # Compute total remaining time and distance - remaining = 1.0 - along_geometry / max(step['distance'], 1) - total_distance = step['distance'] * remaining - total_time = step['duration'] * remaining - - if step['duration_typical'] is None: - total_time_typical = total_time - else: - total_time_typical = step['duration_typical'] * remaining - - # Add up totals for future steps - for i in range(self.step_idx + 1, len(self.route)): - total_distance += self.route[i]['distance'] - total_time += self.route[i]['duration'] - 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 - msg.navInstruction.timeRemainingTypical = total_time_typical - - # Speed limit - closest_idx, closest = min(enumerate(geometry), key=lambda p: p[1].distance_to(self.last_position)) - if closest_idx > 0: - # If we are not past the closest point, show previous - if along_geometry < distance_along_geometry(geometry, geometry[closest_idx]): - closest = geometry[closest_idx - 1] - - if ('maxspeed' in closest.annotations) and self.localizer_valid: - msg.navInstruction.speedLimit = closest.annotations['maxspeed'] - - # Speed limit sign type - if 'speedLimitSign' in step: - if step['speedLimitSign'] == 'mutcd': - msg.navInstruction.speedLimitSign = log.NavInstruction.SpeedLimitSign.mutcd - elif step['speedLimitSign'] == 'vienna': - msg.navInstruction.speedLimitSign = log.NavInstruction.SpeedLimitSign.vienna - - self.pm.send('navInstruction', msg) - - # Transition to next route segment - if distance_to_maneuver_along_geometry < -MANEUVER_TRANSITION_THRESHOLD: - if self.step_idx + 1 < len(self.route): - self.step_idx += 1 - self.reset_recompute_limits() - else: - cloudlog.warning("Destination reached") - - # Clear route if driving away from destination - dist = self.nav_destination.distance_to(self.last_position) - if dist > REROUTE_DISTANCE: - self.params.remove("NavDestination") - self.clear_route() - - def send_route(self): - coords = [] - - if self.route is not None: - for path in self.route_geometry: - coords += [c.as_dict() for c in path] - - msg = messaging.new_message('navRoute', valid=True) - msg.navRoute.coordinates = coords - self.pm.send('navRoute', msg) - - def clear_route(self): - self.route = None - self.route_geometry = None - self.step_idx = None - self.nav_destination = None - - def reset_recompute_limits(self): - self.recompute_backoff = 0 - self.recompute_countdown = 0 - - def should_recompute(self): - if self.step_idx is None or self.route is None: - return True - - # Don't recompute in last segment, assume destination is reached - if self.step_idx == len(self.route) - 1: - return False - - # Compute closest distance to all line segments in the current path - min_d = REROUTE_DISTANCE + 1 - path = self.route_geometry[self.step_idx] - for i in range(len(path) - 1): - a = path[i] - b = path[i + 1] - - if a.distance_to(b) < 1.0: - continue - - min_d = min(min_d, minimum_distance(a, b, self.last_position)) - - if min_d > REROUTE_DISTANCE: - self.reroute_counter += 1 - else: - self.reroute_counter = 0 - return self.reroute_counter > REROUTE_COUNTER_MIN - # TODO: Check for going wrong way in segment - - -def main(): - pm = messaging.PubMaster(['navInstruction', 'navRoute']) - sm = messaging.SubMaster(['liveLocationKalman', 'managerState']) - - rk = Ratekeeper(1.0) - route_engine = RouteEngine(sm, pm) - while True: - route_engine.update() - rk.keep_time() - - -if __name__ == "__main__": - main() diff --git a/selfdrive/navd/set_destination.py b/selfdrive/navd/set_destination.py deleted file mode 100755 index 811aa576d1ef89b..000000000000000 --- a/selfdrive/navd/set_destination.py +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env python3 -import json -import sys - -from openpilot.common.params import Params - -if __name__ == "__main__": - params = Params() - - # set from google maps url - if len(sys.argv) > 1: - coords = sys.argv[1].split("/@")[-1].split("/")[0].split(",") - dest = { - "latitude": float(coords[0]), - "longitude": float(coords[1]) - } - params.put("NavDestination", json.dumps(dest)) - params.remove("NavDestinationWaypoints") - else: - print("Setting to Taco Bell") - dest = { - "latitude": 32.71160109904473, - "longitude": -117.12556569985693, - } - params.put("NavDestination", json.dumps(dest)) - - waypoints = [ - (-117.16020713111648, 32.71997612490662), - ] - params.put("NavDestinationWaypoints", json.dumps(waypoints)) - - print(dest) - print(waypoints) diff --git a/selfdrive/navd/style.json b/selfdrive/navd/style.json deleted file mode 100644 index 06bb750d1ffdc61..000000000000000 --- a/selfdrive/navd/style.json +++ /dev/null @@ -1 +0,0 @@ -{"version": 8, "name": "Navigation Model", "metadata": {"mapbox:type": "default", "mapbox:origin": "monochrome-dark-v1", "mapbox:sdk-support": {"android": "10.0.0", "ios": "10.0.0", "js": "2.3.0"}, "mapbox:autocomposite": true, "mapbox:groups": {"Transit, transit-labels": {"name": "Transit, transit-labels", "collapsed": true}, "Administrative boundaries, admin": {"name": "Administrative boundaries, admin", "collapsed": true}, "Transit, bridges": {"name": "Transit, bridges", "collapsed": true}, "Transit, surface": {"name": "Transit, surface", "collapsed": true}, "Road network, bridges": {"name": "Road network, bridges", "collapsed": false}, "Land, water, & sky, water": {"name": "Land, water, & sky, water", "collapsed": true}, "Road network, tunnels": {"name": "Road network, tunnels", "collapsed": false}, "Road network, road-labels": {"name": "Road network, road-labels", "collapsed": true}, "Buildings, built": {"name": "Buildings, built", "collapsed": true}, "Natural features, natural-labels": {"name": "Natural features, natural-labels", "collapsed": true}, "Road network, surface": {"name": "Road network, surface", "collapsed": false}, "Land, water, & sky, built": {"name": "Land, water, & sky, built", "collapsed": true}, "Place labels, place-labels": {"name": "Place labels, place-labels", "collapsed": true}, "Point of interest labels, poi-labels": {"name": "Point of interest labels, poi-labels", "collapsed": true}, "Road network, tunnels-case": {"name": "Road network, tunnels-case", "collapsed": true}, "Transit, built": {"name": "Transit, built", "collapsed": true}, "Road network, surface-icons": {"name": "Road network, surface-icons", "collapsed": false}, "Land, water, & sky, land": {"name": "Land, water, & sky, land", "collapsed": true}}}, "center": [-117.19189443261149, 32.756553679559985], "zoom": 12.932776547838778, "bearing": 0, "pitch": 0.5017568344510897, "sources": {"composite": {"url": "mapbox://mapbox.mapbox-streets-v8", "type": "vector", "maxzoom": 13}}, "sprite": "mapbox://sprites/commaai/ckvmksrpd4n0a14pfdo5heqzr/bkx9h9tjdf3xedbnjvfo5xnbv", "glyphs": "mapbox://fonts/mapbox/{fontstack}/{range}.pbf", "layers": [{"id": "land", "type": "background", "layout": {"visibility": "none"}, "paint": {"background-color": "rgb(252, 252, 252)"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, land"}}, {"minzoom": 5, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, land"}, "filter": ["==", ["get", "class"], "national_park"], "type": "fill", "source": "composite", "id": "national-park", "paint": {"fill-color": "rgb(240, 240, 240)", "fill-opacity": ["interpolate", ["linear"], ["zoom"], 5, 0, 6, 0.5, 10, 0.5]}, "source-layer": "landuse_overlay"}, {"minzoom": 5, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, land"}, "filter": ["match", ["get", "class"], ["park", "airport", "glacier", "pitch", "sand", "facility"], true, false], "type": "fill", "source": "composite", "id": "landuse", "paint": {"fill-color": "rgb(240, 240, 240)", "fill-opacity": ["interpolate", ["linear"], ["zoom"], 5, 0, 6, ["match", ["get", "class"], "glacier", 0.5, 1]]}, "source-layer": "landuse"}, {"id": "waterway-shadow", "type": "line", "source": "composite", "source-layer": "waterway", "minzoom": 8, "layout": {"line-cap": ["step", ["zoom"], "butt", 11, "round"], "line-join": "round", "visibility": "none"}, "paint": {"line-color": "rgb(204, 204, 204)", "line-width": ["interpolate", ["exponential", 1.3], ["zoom"], 9, ["match", ["get", "class"], ["canal", "river"], 0.1, 0], 20, ["match", ["get", "class"], ["canal", "river"], 8, 3]], "line-translate": ["interpolate", ["exponential", 1.2], ["zoom"], 7, ["literal", [0, 0]], 16, ["literal", [-1, -1]]], "line-translate-anchor": "viewport", "line-opacity": ["interpolate", ["linear"], ["zoom"], 8, 0, 8.5, 1]}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, water"}}, {"id": "water-shadow", "type": "fill", "source": "composite", "source-layer": "water", "layout": {"visibility": "none"}, "paint": {"fill-color": "rgb(204, 204, 204)", "fill-translate": ["interpolate", ["exponential", 1.2], ["zoom"], 7, ["literal", [0, 0]], 16, ["literal", [-1, -1]]], "fill-translate-anchor": "viewport"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, water"}}, {"id": "waterway", "type": "line", "source": "composite", "source-layer": "waterway", "minzoom": 8, "layout": {"line-cap": ["step", ["zoom"], "butt", 11, "round"], "line-join": "round", "visibility": "none"}, "paint": {"line-color": "rgb(224, 224, 224)", "line-width": ["interpolate", ["exponential", 1.3], ["zoom"], 9, ["match", ["get", "class"], ["canal", "river"], 0.1, 0], 20, ["match", ["get", "class"], ["canal", "river"], 8, 3]], "line-opacity": ["interpolate", ["linear"], ["zoom"], 8, 0, 8.5, 1]}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, water"}}, {"id": "water", "type": "fill", "source": "composite", "source-layer": "water", "layout": {"visibility": "none"}, "paint": {"fill-color": "rgb(224, 224, 224)"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, water"}}, {"minzoom": 13, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, built"}, "filter": ["all", ["==", ["geometry-type"], "Polygon"], ["==", ["get", "class"], "land"]], "type": "fill", "source": "composite", "id": "land-structure-polygon", "paint": {"fill-color": "rgb(252, 252, 252)"}, "source-layer": "structure"}, {"minzoom": 13, "layout": {"line-cap": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "land-and-water", "mapbox:group": "Land, water, & sky, built"}, "filter": ["all", ["==", ["geometry-type"], "LineString"], ["==", ["get", "class"], "land"]], "type": "line", "source": "composite", "id": "land-structure-line", "paint": {"line-width": ["interpolate", ["exponential", 1.99], ["zoom"], 14, 0.75, 20, 40], "line-color": "rgb(252, 252, 252)"}, "source-layer": "structure"}, {"minzoom": 11, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, built"}, "filter": ["all", ["==", ["geometry-type"], "Polygon"], ["match", ["get", "type"], ["runway", "taxiway", "helipad"], true, false]], "type": "fill", "source": "composite", "id": "aeroway-polygon", "paint": {"fill-color": "rgb(255, 255, 255)", "fill-opacity": ["interpolate", ["linear"], ["zoom"], 11, 0, 11.5, 1]}, "source-layer": "aeroway"}, {"minzoom": 9, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, built"}, "filter": ["==", ["geometry-type"], "LineString"], "type": "line", "source": "composite", "id": "aeroway-line", "paint": {"line-color": "rgb(255, 255, 255)", "line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 9, ["match", ["get", "type"], "runway", 1, 0.5], 18, ["match", ["get", "type"], "runway", 80, 20]]}, "source-layer": "aeroway"}, {"minzoom": 13, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "buildings", "mapbox:group": "Buildings, built"}, "filter": ["all", ["!=", ["get", "type"], "building:part"], ["==", ["get", "underground"], "false"]], "type": "line", "source": "composite", "id": "building-outline", "paint": {"line-color": "rgb(227, 227, 227)", "line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 15, 0.75, 20, 3], "line-opacity": ["interpolate", ["linear"], ["zoom"], 15, 0, 16, 1]}, "source-layer": "building"}, {"minzoom": 13, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "buildings", "mapbox:group": "Buildings, built"}, "filter": ["all", ["!=", ["get", "type"], "building:part"], ["==", ["get", "underground"], "false"]], "type": "fill", "source": "composite", "id": "building", "paint": {"fill-color": ["interpolate", ["linear"], ["zoom"], 15, "rgb(242, 242, 242)", 16, "rgb(242, 242, 242)"], "fill-opacity": ["interpolate", ["linear"], ["zoom"], 15, 0, 16, 1], "fill-outline-color": "rgb(227, 227, 227)"}, "source-layer": "building"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-street-minor-low", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-color": "rgb(235, 235, 235)", "line-opacity": ["step", ["zoom"], 1, 14, 0]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-street-minor-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(255, 255, 255)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-opacity": ["step", ["zoom"], 0, 14, 1], "line-dasharray": [3, 3]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["primary", "secondary", "tertiary"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-primary-secondary-tertiary-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, ["match", ["get", "class"], "primary", 1, 0.75], 18, 2], "line-color": "rgb(255, 255, 255)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, ["match", ["get", "class"], "primary", 0.75, 0.1], 18, ["match", ["get", "class"], "primary", 32, 26]], "line-dasharray": [3, 3]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-major-link-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(255, 255, 255)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-dasharray": [3, 3]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-motorway-trunk-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(255, 255, 255)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-dasharray": [3, 3]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels-case"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["==", ["get", "class"], "construction"], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-construction", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 2, 18, 18], "line-color": "rgb(235, 235, 235)", "line-dasharray": ["step", ["zoom"], ["literal", [0.4, 0.8]], 15, ["literal", [0.3, 0.6]], 16, ["literal", [0.2, 0.3]], 17, ["literal", [0.2, 0.25]], 18, ["literal", [0.15, 0.15]]]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-major-link", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(235, 235, 235)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-street-minor", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-color": "rgb(235, 235, 235)", "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["primary", "secondary", "tertiary"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-primary-secondary-tertiary", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, ["match", ["get", "class"], "primary", 0.75, 0.1], 18, ["match", ["get", "class"], "primary", 32, 26]], "line-color": "rgb(235, 235, 235)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, tunnels"}, "filter": ["all", ["==", ["get", "structure"], "tunnel"], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "tunnel-motorway-trunk", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(235, 235, 235)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"icon-image": "turning-circle-outline", "icon-size": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 0.122, 18, 0.969, 20, 1], "icon-allow-overlap": true, "icon-ignore-placement": true, "icon-padding": 0, "icon-rotation-alignment": "map", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["==", ["geometry-type"], "Point"], ["match", ["get", "class"], ["turning_circle", "turning_loop"], true, false]], "type": "symbol", "source": "composite", "id": "turning-feature-outline", "paint": {}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["step", ["zoom"], ["==", ["get", "class"], "track"], 1, ["match", ["get", "class"], ["track", "secondary_link", "tertiary_link", "service"], true, false]], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-minor-low", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, ["match", ["get", "class"], "track", 1, 0.5], 18, 12], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 1, 14, 0]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["step", ["zoom"], ["==", ["get", "class"], "track"], 1, ["match", ["get", "class"], ["track", "secondary_link", "tertiary_link", "service"], true, false]], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-minor-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, ["match", ["get", "class"], "track", 1, 0.5], 18, 12], "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 11, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["street", "street_limited", "primary_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-street-low", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 1, 14, 0]}, "source-layer": "road"}, {"minzoom": 11, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["street", "street_limited", "primary_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-street-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 8, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["secondary", "tertiary"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-secondary-tertiary-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 0.75, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.1, 18, 26], "line-opacity": ["step", ["zoom"], 0, 10, 1]}, "source-layer": "road"}, {"minzoom": 7, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["==", ["get", "class"], "primary"], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-primary-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-opacity": ["step", ["zoom"], 0, 10, 1]}, "source-layer": "road"}, {"minzoom": 10, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-major-link-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-opacity": ["step", ["zoom"], 0, 11, 1]}, "source-layer": "road"}, {"minzoom": 5, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-motorway-trunk-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-opacity": ["step", ["zoom"], ["match", ["get", "class"], "motorway", 1, 0], 6, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["==", ["get", "class"], "construction"], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-construction", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)", "line-dasharray": ["step", ["zoom"], ["literal", [0.4, 0.8]], 15, ["literal", [0.3, 0.6]], 16, ["literal", [0.2, 0.3]], 17, ["literal", [0.2, 0.25]], 18, ["literal", [0.15, 0.15]]]}, "source-layer": "road"}, {"minzoom": 10, "layout": {"line-cap": ["step", ["zoom"], "butt", 13, "round"], "line-join": ["step", ["zoom"], "miter", 13, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-major-link", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["step", ["zoom"], ["==", ["get", "class"], "track"], 1, ["match", ["get", "class"], ["track", "secondary_link", "tertiary_link", "service"], true, false]], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-minor", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, ["match", ["get", "class"], "track", 1, 0.5], 18, 12], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 11, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["street", "street_limited", "primary_link"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-street", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 8, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["match", ["get", "class"], ["secondary", "tertiary"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-secondary-tertiary", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.1, 18, 26], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 6, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}, "filter": ["all", ["==", ["get", "class"], "primary"], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "road-primary", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"id": "road-motorway-trunk", "type": "line", "source": "composite", "source-layer": "road", "filter": ["all", ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false], ["==", ["geometry-type"], "LineString"]], "layout": {"line-cap": ["step", ["zoom"], "butt", 13, "round"], "line-join": ["step", ["zoom"], "miter", 13, "round"]}, "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(255, 255, 255)"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface"}}, {"minzoom": 13, "layout": {"line-join": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, surface"}, "filter": ["all", ["match", ["get", "class"], ["major_rail", "minor_rail"], true, false], ["match", ["get", "structure"], ["none", "ford"], true, false]], "type": "line", "source": "composite", "id": "road-rail", "paint": {"line-color": ["interpolate", ["linear"], ["zoom"], 13, "rgb(242, 242, 242)", 17, "rgb(227, 227, 227)"], "line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 0.5, 20, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"icon-image": "turning-circle", "icon-size": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 0.095, 18, 1], "icon-allow-overlap": true, "icon-ignore-placement": true, "icon-padding": 0, "icon-rotation-alignment": "map", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, surface-icons"}, "filter": ["all", ["==", ["geometry-type"], "Point"], ["match", ["get", "class"], ["turning_circle", "turning_loop"], true, false]], "type": "symbol", "source": "composite", "id": "turning-feature", "paint": {}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-street-minor-low", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 1, 14, 0]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-street-minor-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["primary", "secondary", "tertiary"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-primary-secondary-tertiary-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, ["match", ["get", "class"], "primary", 1, 0.75], 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, ["match", ["get", "class"], "primary", 0.75, 0.1], 18, ["match", ["get", "class"], "primary", 32, 26]], "line-opacity": ["step", ["zoom"], 0, 10, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["<=", ["get", "layer"], 1], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-major-link-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["<=", ["get", "layer"], 1], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-motorway-trunk-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32]}, "source-layer": "road"}, {"minzoom": 13, "layout": {}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["==", ["get", "class"], "construction"], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-construction", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)", "line-dasharray": ["step", ["zoom"], ["literal", [0.4, 0.8]], 15, ["literal", [0.3, 0.6]], 16, ["literal", [0.2, 0.3]], 17, ["literal", [0.2, 0.25]], 18, ["literal", [0.15, 0.15]]]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": "round", "line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["<=", ["get", "layer"], 1], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-major-link", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["step", ["zoom"], ["match", ["get", "class"], ["street", "street_limited", "primary_link", "track"], true, false], 1, ["match", ["get", "class"], ["street", "street_limited", "track", "primary_link", "secondary_link", "tertiary_link", "service"], true, false]], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-street-minor", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 2, "track", 1, 0.5], 18, ["match", ["get", "class"], ["street", "street_limited", "primary_link"], 18, 12]], "line-color": "rgb(255, 255, 255)", "line-opacity": ["step", ["zoom"], 0, 14, 1]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["primary", "secondary", "tertiary"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-primary-secondary-tertiary", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, ["match", ["get", "class"], "primary", 0.75, 0.1], 18, ["match", ["get", "class"], "primary", 32, 26]], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": "round", "line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["<=", ["get", "layer"], 1], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-motorway-trunk", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], [">=", ["get", "layer"], 2], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-major-link-2-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.75, 20, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], [">=", ["get", "layer"], 2], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-motorway-trunk-2-case", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 10, 1, 18, 2], "line-color": "rgb(242, 242, 242)", "line-gap-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32]}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": "round", "line-join": "round"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], [">=", ["get", "layer"], 2], ["match", ["get", "class"], ["motorway_link", "trunk_link"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-major-link-2", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 12, 0.5, 14, 2, 18, 18], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-cap": ["step", ["zoom"], "butt", 14, "round"], "line-join": ["step", ["zoom"], "miter", 14, "round"]}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], [">=", ["get", "layer"], 2], ["match", ["get", "class"], ["motorway", "trunk"], true, false], ["==", ["geometry-type"], "LineString"]], "type": "line", "source": "composite", "id": "bridge-motorway-trunk-2", "paint": {"line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 5, 0.75, 18, 32], "line-color": "rgb(255, 255, 255)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"line-join": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, bridges"}, "filter": ["all", ["==", ["get", "structure"], "bridge"], ["match", ["get", "class"], ["major_rail", "minor_rail"], true, false]], "type": "line", "source": "composite", "id": "bridge-rail", "paint": {"line-color": "rgb(227, 227, 227)", "line-width": ["interpolate", ["exponential", 1.5], ["zoom"], 14, 0.5, 20, 1]}, "source-layer": "road"}, {"minzoom": 7, "layout": {"line-join": "bevel", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "admin_level"], 1], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-1-boundary-bg", "paint": {"line-color": ["interpolate", ["linear"], ["zoom"], 8, "rgb(227, 227, 227)", 16, "rgb(227, 227, 227)"], "line-width": ["interpolate", ["linear"], ["zoom"], 7, 3.75, 12, 5.5], "line-opacity": ["interpolate", ["linear"], ["zoom"], 7, 0, 8, 0.75], "line-dasharray": [1, 0], "line-blur": ["interpolate", ["linear"], ["zoom"], 3, 0, 8, 3]}, "source-layer": "admin"}, {"minzoom": 1, "layout": {"visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "admin_level"], 0], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-0-boundary-bg", "paint": {"line-width": ["interpolate", ["linear"], ["zoom"], 3, 3.5, 10, 8], "line-color": "rgb(227, 227, 227)", "line-opacity": ["interpolate", ["linear"], ["zoom"], 3, 0, 4, 0.5], "line-blur": ["interpolate", ["linear"], ["zoom"], 3, 0, 10, 2]}, "source-layer": "admin"}, {"minzoom": 2, "layout": {"line-join": "round", "line-cap": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "admin_level"], 1], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-1-boundary", "paint": {"line-dasharray": ["step", ["zoom"], ["literal", [2, 0]], 7, ["literal", [2, 2, 6, 2]]], "line-width": ["interpolate", ["linear"], ["zoom"], 7, 0.75, 12, 1.5], "line-opacity": ["interpolate", ["linear"], ["zoom"], 2, 0, 3, 1], "line-color": ["interpolate", ["linear"], ["zoom"], 3, "rgb(224, 224, 224)", 7, "rgb(184, 184, 184)"]}, "source-layer": "admin"}, {"minzoom": 1, "layout": {"line-join": "round", "line-cap": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "admin_level"], 0], ["==", ["get", "disputed"], "false"], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-0-boundary", "paint": {"line-color": "rgb(184, 184, 184)", "line-width": ["interpolate", ["linear"], ["zoom"], 3, 0.5, 10, 2], "line-dasharray": [10, 0]}, "source-layer": "admin"}, {"minzoom": 1, "layout": {"line-join": "round", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "admin-boundaries", "mapbox:group": "Administrative boundaries, admin"}, "filter": ["all", ["==", ["get", "disputed"], "true"], ["==", ["get", "admin_level"], 0], ["==", ["get", "maritime"], "false"], ["match", ["get", "worldview"], ["all", "US"], true, false]], "type": "line", "source": "composite", "id": "admin-0-boundary-disputed", "paint": {"line-color": "rgb(184, 184, 184)", "line-width": ["interpolate", ["linear"], ["zoom"], 3, 0.5, 10, 2], "line-dasharray": ["step", ["zoom"], ["literal", [3.25, 3.25]], 6, ["literal", [2.5, 2.5]], 7, ["literal", [2, 2.25]], 8, ["literal", [1.75, 2]]]}, "source-layer": "admin"}, {"minzoom": 10, "layout": {"text-size": ["interpolate", ["linear"], ["zoom"], 10, ["match", ["get", "class"], ["motorway", "trunk", "primary", "secondary", "tertiary"], 10, ["motorway_link", "trunk_link", "primary_link", "secondary_link", "tertiary_link", "street", "street_limited"], 9, 6.5], 18, ["match", ["get", "class"], ["motorway", "trunk", "primary", "secondary", "tertiary"], 16, ["motorway_link", "trunk_link", "primary_link", "secondary_link", "tertiary_link", "street", "street_limited"], 14, 13]], "text-max-angle": 30, "text-font": ["DIN Pro Regular", "Arial Unicode MS Regular"], "symbol-placement": "line", "text-padding": 1, "visibility": "none", "text-rotation-alignment": "map", "text-pitch-alignment": "viewport", "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-letter-spacing": 0.01}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, road-labels"}, "filter": ["step", ["zoom"], ["match", ["get", "class"], ["motorway", "trunk", "primary", "secondary", "tertiary"], true, false], 1, ["match", ["get", "class"], ["motorway", "trunk", "primary", "secondary", "tertiary", "street", "street_limited"], true, false], 2, ["match", ["get", "class"], ["path", "pedestrian", "golf", "ferry", "aerialway"], false, true]], "type": "symbol", "source": "composite", "id": "road-label", "paint": {"text-color": "rgb(128, 128, 128)", "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1, "text-halo-blur": 1}, "source-layer": "road"}, {"minzoom": 13, "layout": {"text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "icon-image": "intersection", "icon-text-fit": "both", "icon-text-fit-padding": [1, 2, 1, 2], "text-size": ["interpolate", ["exponential", 1.2], ["zoom"], 15, 9, 18, 12], "text-font": ["DIN Pro Bold", "Arial Unicode MS Bold"], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "road-network", "mapbox:group": "Road network, road-labels"}, "filter": ["all", ["==", ["get", "class"], "intersection"], ["has", "name"]], "type": "symbol", "source": "composite", "id": "road-intersection", "paint": {"text-color": "rgb(153, 153, 153)"}, "source-layer": "road"}, {"minzoom": 13, "layout": {"text-font": ["DIN Pro Italic", "Arial Unicode MS Regular"], "text-max-angle": 30, "symbol-spacing": ["interpolate", ["linear", 1], ["zoom"], 15, 250, 17, 400], "text-size": ["interpolate", ["linear"], ["zoom"], 13, 12, 18, 16], "symbol-placement": "line", "text-pitch-alignment": "viewport", "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}, "filter": ["all", ["match", ["get", "class"], ["canal", "river", "stream"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_canal", "disputed_river", "disputed_stream"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "LineString"]], "type": "symbol", "source": "composite", "id": "waterway-label", "paint": {"text-color": "rgb(150, 150, 150)"}, "source-layer": "natural_label"}, {"minzoom": 4, "layout": {"text-size": ["step", ["zoom"], ["step", ["get", "sizerank"], 18, 5, 12], 17, ["step", ["get", "sizerank"], 18, 13, 12]], "text-max-angle": 30, "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "symbol-placement": "line-center", "text-pitch-alignment": "viewport", "visibility": "none"}, "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}, "filter": ["all", ["match", ["get", "class"], ["glacier", "landform"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_glacier", "disputed_landform"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "LineString"], ["<=", ["get", "filterrank"], 1]], "type": "symbol", "source": "composite", "id": "natural-line-label", "paint": {"text-halo-width": 0.5, "text-halo-color": "rgb(255, 255, 255)", "text-halo-blur": 0.5, "text-color": "rgb(128, 128, 128)"}, "source-layer": "natural_label"}, {"minzoom": 4, "layout": {"text-size": ["step", ["zoom"], ["step", ["get", "sizerank"], 18, 5, 12], 17, ["step", ["get", "sizerank"], 18, 13, 12]], "icon-image": "", "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "text-offset": ["literal", [0, 0]], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}, "filter": ["all", ["match", ["get", "class"], ["dock", "glacier", "landform", "water_feature", "wetland"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_dock", "disputed_glacier", "disputed_landform", "disputed_water_feature", "disputed_wetland"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "Point"], ["<=", ["get", "filterrank"], 1]], "type": "symbol", "source": "composite", "id": "natural-point-label", "paint": {"icon-opacity": ["step", ["zoom"], ["step", ["get", "sizerank"], 0, 5, 1], 17, ["step", ["get", "sizerank"], 0, 13, 1]], "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 0.5, "text-halo-blur": 0.5, "text-color": "rgb(128, 128, 128)"}, "source-layer": "natural_label"}, {"id": "water-line-label", "type": "symbol", "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}, "source": "composite", "source-layer": "natural_label", "filter": ["all", ["match", ["get", "class"], ["bay", "ocean", "reservoir", "sea", "water"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_bay", "disputed_ocean", "disputed_reservoir", "disputed_sea", "disputed_water"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "LineString"]], "layout": {"text-size": ["interpolate", ["linear"], ["zoom"], 7, ["step", ["get", "sizerank"], 20, 6, 18, 12, 12], 10, ["step", ["get", "sizerank"], 15, 9, 12], 18, ["step", ["get", "sizerank"], 15, 9, 14]], "text-max-angle": 30, "text-letter-spacing": ["match", ["get", "class"], "ocean", 0.25, ["sea", "bay"], 0.15, 0], "text-font": ["DIN Pro Italic", "Arial Unicode MS Regular"], "symbol-placement": "line-center", "text-pitch-alignment": "viewport", "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "visibility": "none"}, "paint": {"text-color": "rgb(150, 150, 150)"}}, {"id": "water-point-label", "type": "symbol", "source": "composite", "source-layer": "natural_label", "filter": ["all", ["match", ["get", "class"], ["bay", "ocean", "reservoir", "sea", "water"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_bay", "disputed_ocean", "disputed_reservoir", "disputed_sea", "disputed_water"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["==", ["geometry-type"], "Point"]], "layout": {"text-line-height": 1.3, "text-size": ["interpolate", ["linear"], ["zoom"], 7, ["step", ["get", "sizerank"], 20, 6, 15, 12, 12], 10, ["step", ["get", "sizerank"], 15, 9, 12]], "text-font": ["DIN Pro Italic", "Arial Unicode MS Regular"], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-letter-spacing": ["match", ["get", "class"], "ocean", 0.25, ["bay", "sea"], 0.15, 0.01], "text-max-width": ["match", ["get", "class"], "ocean", 4, "sea", 5, ["bay", "water"], 7, 10], "visibility": "none"}, "paint": {"text-color": "rgb(150, 150, 150)"}, "metadata": {"mapbox:featureComponent": "natural-features", "mapbox:group": "Natural features, natural-labels"}}, {"minzoom": 6, "layout": {"text-size": ["step", ["zoom"], ["step", ["get", "sizerank"], 18, 5, 12], 17, ["step", ["get", "sizerank"], 18, 13, 12]], "icon-image": "", "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "text-offset": [0, 0], "text-anchor": ["step", ["zoom"], ["step", ["get", "sizerank"], "center", 5, "top"], 17, ["step", ["get", "sizerank"], "center", 13, "top"]], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "point-of-interest-labels", "mapbox:group": "Point of interest labels, poi-labels"}, "filter": ["<=", ["get", "filterrank"], ["+", ["step", ["zoom"], 1, 2, 3, 4, 5], 1]], "type": "symbol", "source": "composite", "id": "poi-label", "paint": {"text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 0.5, "text-halo-blur": 0.5, "text-color": ["step", ["zoom"], ["step", ["get", "sizerank"], "rgb(184, 184, 184)", 5, "rgb(161, 161, 161)"], 17, ["step", ["get", "sizerank"], "rgb(184, 184, 184)", 13, "rgb(161, 161, 161)"]]}, "source-layer": "poi_label"}, {"minzoom": 8, "layout": {"text-line-height": 1.1, "text-size": ["step", ["get", "sizerank"], 18, 9, 12], "icon-image": ["get", "maki"], "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "visibility": "none", "text-offset": [0, 0.75], "text-rotation-alignment": "viewport", "text-anchor": "top", "text-field": ["step", ["get", "sizerank"], ["coalesce", ["get", "name_en"], ["get", "name"]], 15, ["get", "ref"]], "text-letter-spacing": 0.01, "text-max-width": 9}, "metadata": {"mapbox:featureComponent": "transit", "mapbox:group": "Transit, transit-labels"}, "filter": ["match", ["get", "class"], ["military", "civil"], ["match", ["get", "worldview"], ["all", "US"], true, false], ["disputed_military", "disputed_civil"], ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], "type": "symbol", "source": "composite", "id": "airport-label", "paint": {"text-color": "rgb(128, 128, 128)", "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1}, "source-layer": "airport_label"}, {"minzoom": 10, "layout": {"text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-transform": "uppercase", "text-font": ["DIN Pro Regular", "Arial Unicode MS Regular"], "text-letter-spacing": ["match", ["get", "type"], "suburb", 0.15, 0.1], "text-max-width": 7, "text-padding": 3, "text-size": ["interpolate", ["cubic-bezier", 0.5, 0, 1, 1], ["zoom"], 11, ["match", ["get", "type"], "suburb", 11, 10.5], 15, ["match", ["get", "type"], "suburb", 15, 14]], "visibility": "none"}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 15, "filter": ["all", ["match", ["get", "class"], "settlement_subdivision", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_settlement_subdivision", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["<=", ["get", "filterrank"], 4]], "type": "symbol", "source": "composite", "id": "settlement-subdivision-label", "paint": {"text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1, "text-color": "rgb(179, 179, 179)", "text-halo-blur": 0.5}, "source-layer": "place_label"}, {"minzoom": 3, "layout": {"text-line-height": 1.1, "text-size": ["interpolate", ["cubic-bezier", 0.2, 0, 0.9, 1], ["zoom"], 3, ["step", ["get", "symbolrank"], 12, 9, 11, 10, 10.5, 12, 9.5, 14, 8.5, 16, 6.5, 17, 4], 13, ["step", ["get", "symbolrank"], 23, 9, 21, 10, 19, 11, 17, 12, 16, 13, 15, 15, 13]], "text-radial-offset": ["step", ["zoom"], ["match", ["get", "capital"], 2, 0.6, 0.55], 8, 0], "icon-image": ["step", ["zoom"], ["case", ["==", ["get", "capital"], 2], "border-dot-13", ["step", ["get", "symbolrank"], "dot-11", 9, "dot-10", 11, "dot-9"]], 8, ""], "text-font": ["DIN Pro Regular", "Arial Unicode MS Regular"], "text-justify": "auto", "visibility": "none", "text-anchor": ["step", ["zoom"], ["get", "text_anchor"], 8, "center"], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-max-width": 7}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 13, "filter": ["all", ["<=", ["get", "filterrank"], 3], ["match", ["get", "class"], "settlement", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_settlement", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["step", ["zoom"], [">", ["get", "symbolrank"], 6], 1, [">=", ["get", "symbolrank"], 7], 2, [">=", ["get", "symbolrank"], 8], 3, [">=", ["get", "symbolrank"], 10], 4, [">=", ["get", "symbolrank"], 11], 5, [">=", ["get", "symbolrank"], 13], 6, [">=", ["get", "symbolrank"], 15]]], "type": "symbol", "source": "composite", "id": "settlement-minor-label", "paint": {"text-color": ["step", ["get", "symbolrank"], "rgb(128, 128, 128)", 11, "rgb(161, 161, 161)", 16, "rgb(184, 184, 184)"], "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1, "text-halo-blur": 1}, "source-layer": "place_label"}, {"minzoom": 3, "layout": {"text-line-height": 1.1, "text-size": ["interpolate", ["cubic-bezier", 0.2, 0, 0.9, 1], ["zoom"], 3, ["step", ["get", "symbolrank"], 13, 6, 12], 6, ["step", ["get", "symbolrank"], 16, 6, 15, 7, 14], 8, ["step", ["get", "symbolrank"], 18, 9, 17, 10, 15], 15, ["step", ["get", "symbolrank"], 23, 9, 22, 10, 20, 11, 18, 12, 16, 13, 15, 15, 13]], "text-radial-offset": ["step", ["zoom"], ["match", ["get", "capital"], 2, 0.6, 0.55], 8, 0], "icon-image": ["step", ["zoom"], ["case", ["==", ["get", "capital"], 2], "border-dot-13", ["step", ["get", "symbolrank"], "dot-11", 9, "dot-10", 11, "dot-9"]], 8, ""], "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "text-justify": ["step", ["zoom"], ["match", ["get", "text_anchor"], ["left", "bottom-left", "top-left"], "left", ["right", "bottom-right", "top-right"], "right", "center"], 8, "center"], "visibility": "none", "text-anchor": ["step", ["zoom"], ["get", "text_anchor"], 8, "center"], "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-max-width": 7}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 15, "filter": ["all", ["<=", ["get", "filterrank"], 3], ["match", ["get", "class"], "settlement", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_settlement", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], ["step", ["zoom"], false, 1, ["<=", ["get", "symbolrank"], 6], 2, ["<", ["get", "symbolrank"], 7], 3, ["<", ["get", "symbolrank"], 8], 4, ["<", ["get", "symbolrank"], 10], 5, ["<", ["get", "symbolrank"], 11], 6, ["<", ["get", "symbolrank"], 13], 7, ["<", ["get", "symbolrank"], 15], 8, [">=", ["get", "symbolrank"], 11], 9, [">=", ["get", "symbolrank"], 15]]], "type": "symbol", "source": "composite", "id": "settlement-major-label", "paint": {"text-color": ["step", ["get", "symbolrank"], "rgb(128, 128, 128)", 11, "rgb(161, 161, 161)", 16, "rgb(184, 184, 184)"], "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1, "text-halo-blur": 1}, "source-layer": "place_label"}, {"minzoom": 3, "layout": {"text-size": ["interpolate", ["cubic-bezier", 0.85, 0.7, 0.65, 1], ["zoom"], 4, ["step", ["get", "symbolrank"], 10, 6, 9.5, 7, 9], 9, ["step", ["get", "symbolrank"], 21, 6, 16, 7, 13]], "text-transform": "uppercase", "text-font": ["DIN Pro Bold", "Arial Unicode MS Bold"], "text-field": ["step", ["zoom"], ["step", ["get", "symbolrank"], ["coalesce", ["get", "name_en"], ["get", "name"]], 5, ["coalesce", ["get", "abbr"], ["get", "name_en"], ["get", "name"]]], 5, ["coalesce", ["get", "name_en"], ["get", "name"]]], "text-letter-spacing": 0.15, "text-max-width": 6, "visibility": "none"}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 9, "filter": ["match", ["get", "class"], "state", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_state", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], "type": "symbol", "source": "composite", "id": "state-label", "paint": {"text-color": "rgb(184, 184, 184)", "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1}, "source-layer": "place_label"}, {"minzoom": 1, "layout": {"text-line-height": 1.1, "text-size": ["interpolate", ["cubic-bezier", 0.2, 0, 0.7, 1], ["zoom"], 1, ["step", ["get", "symbolrank"], 11, 4, 9, 5, 8], 9, ["step", ["get", "symbolrank"], 22, 4, 19, 5, 17]], "text-radial-offset": ["step", ["zoom"], 0.6, 8, 0], "icon-image": "", "text-font": ["DIN Pro Medium", "Arial Unicode MS Regular"], "text-justify": ["step", ["zoom"], ["match", ["get", "text_anchor"], ["left", "bottom-left", "top-left"], "left", ["right", "bottom-right", "top-right"], "right", "center"], 7, "auto"], "visibility": "none", "text-field": ["coalesce", ["get", "name_en"], ["get", "name"]], "text-max-width": 6}, "metadata": {"mapbox:featureComponent": "place-labels", "mapbox:group": "Place labels, place-labels"}, "maxzoom": 10, "filter": ["match", ["get", "class"], "country", ["match", ["get", "worldview"], ["all", "US"], true, false], "disputed_country", ["all", ["==", ["get", "disputed"], "true"], ["match", ["get", "worldview"], ["all", "US"], true, false]], false], "type": "symbol", "source": "composite", "id": "country-label", "paint": {"icon-opacity": ["step", ["zoom"], ["case", ["has", "text_anchor"], 1, 0], 7, 0], "text-color": "rgb(128, 128, 128)", "text-halo-color": "rgb(255, 255, 255)", "text-halo-width": 1.25}, "source-layer": "place_label"}], "created": "2021-11-05T16:12:04.822Z", "modified": "2021-11-25T13:58:04.167Z", "id": "ckvmksrpd4n0a14pfdo5heqzr", "owner": "commaai", "visibility": "private", "protected": false, "draft": false} \ No newline at end of file diff --git a/selfdrive/navd/tests/test_map_renderer.py b/selfdrive/navd/tests/test_map_renderer.py deleted file mode 100644 index 04363883b2c0f47..000000000000000 --- a/selfdrive/navd/tests/test_map_renderer.py +++ /dev/null @@ -1,212 +0,0 @@ -import time -import numpy as np -import os -import pytest -import requests -import threading -import http.server -import cereal.messaging as messaging - -from typing import Any -from msgq.visionipc import VisionIpcClient, VisionStreamType -from openpilot.common.mock.generators import LLK_DECIMATION, LOCATION1, LOCATION2, generate_liveLocationKalman -from openpilot.selfdrive.test.helpers import with_processes - -CACHE_PATH = "/data/mbgl-cache-navd.db" - -RENDER_FRAMES = 15 -DEFAULT_ITERATIONS = RENDER_FRAMES * LLK_DECIMATION -LOCATION1_REPEATED = [LOCATION1] * DEFAULT_ITERATIONS -LOCATION2_REPEATED = [LOCATION2] * DEFAULT_ITERATIONS - - -class MapBoxInternetDisabledRequestHandler(http.server.BaseHTTPRequestHandler): - INTERNET_ACTIVE = True - - def do_GET(self): - if not self.INTERNET_ACTIVE: - self.send_response(500) - self.end_headers() - return - - url = f'https://api.mapbox.com{self.path}' - - headers = dict(self.headers) - headers["Host"] = "api.mapbox.com" - - r = requests.get(url, headers=headers, timeout=5) - - self.send_response(r.status_code) - self.end_headers() - self.wfile.write(r.content) - - def log_message(self, *args: Any) -> None: - return - - def log_error(self, *args: Any) -> None: - return - - -class MapBoxInternetDisabledServer(threading.Thread): - def run(self): - self.server = http.server.HTTPServer(("127.0.0.1", 0), MapBoxInternetDisabledRequestHandler) - self.port = self.server.server_port - self.server.serve_forever() - - def stop(self): - self.server.shutdown() - - def disable_internet(self): - MapBoxInternetDisabledRequestHandler.INTERNET_ACTIVE = False - - def enable_internet(self): - MapBoxInternetDisabledRequestHandler.INTERNET_ACTIVE = True - - -@pytest.mark.skip(reason="not used") -class TestMapRenderer: - server: MapBoxInternetDisabledServer - - @classmethod - def setup_class(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 teardown_class(cls) -> None: - cls.server.stop() - - def setup_method(self): - self.server.enable_internet() - os.environ['MAPS_HOST'] = f'http://localhost:{self.server.port}' - - self.sm = messaging.SubMaster(['mapRenderState']) - self.pm = messaging.PubMaster(['liveLocationKalman']) - self.vipc = VisionIpcClient("navd", VisionStreamType.VISION_STREAM_MAP, True) - - if os.path.exists(CACHE_PATH): - os.remove(CACHE_PATH) - - def _setup_test(self): - 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() - - def _run_test(self, expect_valid, locations=LOCATION1_REPEATED): - starting_frame_id = None - - render_times = [] - - # run test - prev_frame_id = -1 - for i, location in enumerate(locations): - frame_expected = (i+1) % LLK_DECIMATION == 0 - - if self.sm.logMonoTime['mapRenderState'] == 0: - prev_valid = False - prev_frame_id = -1 - else: - prev_valid = self.sm.valid['mapRenderState'] - prev_frame_id = self.sm['mapRenderState'].frameId - - if starting_frame_id is None: - starting_frame_id = prev_frame_id - - 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) - assert self.sm.updated['mapRenderState'] == frame_expected, "renderer running at wrong frequency" - - if not frame_expected: - continue - - frames_since_test_start = self.sm['mapRenderState'].frameId - starting_frame_id - - # give a few frames to switch from valid to invalid, or vice versa - invalid_and_not_previously_valid = (expect_valid and not self.sm.valid['mapRenderState'] and not prev_valid) - valid_and_not_previously_invalid = (not expect_valid and self.sm.valid['mapRenderState'] and prev_valid) - - if (invalid_and_not_previously_valid or valid_and_not_previously_invalid) and frames_since_test_start < 20: - continue - - # check output - assert self.sm.valid['mapRenderState'] == expect_valid - assert self.sm['mapRenderState'].frameId == (prev_frame_id + 1) - assert self.sm['mapRenderState'].locationMonoTime == llk.logMonoTime - if not expect_valid: - assert self.sm['mapRenderState'].renderTime == 0. - else: - assert 0. < self.sm['mapRenderState'].renderTime < 0.1 - render_times.append(self.sm['mapRenderState'].renderTime) - - # check vision ipc output - assert self.vipc.recv() is not None - assert self.vipc.valid == expect_valid - 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) - - self.server.disable_internet() - - # change locations to force mapsd to refetch - self._run_test(False, LOCATION2_REPEATED) - - self.server.enable_internet() - self._run_test(True, LOCATION2_REPEATED) - - @with_processes(["mapsd"]) - @pytest.mark.tici - def test_render_time_distribution(self): - self._setup_test() - # from location1 -> location2 and back - locations = np.array([*np.linspace(LOCATION1, LOCATION2, 2000), *np.linspace(LOCATION2, LOCATION1, 2000)]).tolist() - - render_times = self._run_test(True, locations) - - _min = np.min(render_times) - _max = np.max(render_times) - _mean = np.mean(render_times) - _median = np.median(render_times) - _stddev = np.std(render_times) - - print(f"Stats: min: {_min}, max: {_max}, mean: {_mean}, median: {_median}, stddev: {_stddev}, count: {len(render_times)}") - - def assert_stat(stat, nominal, tol=0.3): - tol = (nominal / (1+tol)), (nominal * (1+tol)) - assert tol[0] < stat < tol[1], f"{stat} not in tolerance {tol}" - - assert_stat(_mean, 0.030) - assert_stat(_median, 0.027) - assert_stat(_stddev, 0.0078) - - assert _max < 0.065 - assert _min > 0.015 - diff --git a/selfdrive/navd/tests/test_navd.py b/selfdrive/navd/tests/test_navd.py deleted file mode 100644 index b6580acff18a7ae..000000000000000 --- a/selfdrive/navd/tests/test_navd.py +++ /dev/null @@ -1,57 +0,0 @@ -import json -import random -import numpy as np - -from parameterized import parameterized - -import cereal.messaging as messaging -from openpilot.common.params import Params -from openpilot.system.manager.process_config import managed_processes - - -class TestNavd: - def setup_method(self): - self.params = Params() - self.sm = messaging.SubMaster(['navRoute', 'navInstruction']) - - def teardown_method(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) diff --git a/selfdrive/pandad/SConscript b/selfdrive/pandad/SConscript index 63a2c1e650d5398..58777cafe962eb6 100644 --- a/selfdrive/pandad/SConscript +++ b/selfdrive/pandad/SConscript @@ -3,9 +3,11 @@ Import('env', 'envCython', 'common', 'messaging') libs = ['usb-1.0', common, messaging, 'pthread'] panda = env.Library('panda', ['panda.cc', 'panda_comms.cc', 'spi.cc']) -env.Program('pandad', ['main.cc', 'pandad.cc'], LIBS=[panda] + libs) +env.Program('pandad', ['main.cc', 'pandad.cc', 'panda_safety.cc'], LIBS=[panda] + libs) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) -envCython.Program('pandad_api_impl.so', 'pandad_api_impl.pyx', LIBS=["can_list_to_can_capnp", 'capnp', 'kj'] + envCython["LIBS"]) +pandad_python = envCython.Program('pandad_api_impl.so', 'pandad_api_impl.pyx', LIBS=["can_list_to_can_capnp", 'capnp', 'kj'] + envCython["LIBS"]) +Export('pandad_python') + if GetOption('extras'): env.Program('tests/test_pandad_usbprotocol', ['tests/test_pandad_usbprotocol.cc'], LIBS=[panda] + libs) diff --git a/selfdrive/pandad/__init__.py b/selfdrive/pandad/__init__.py index 8081a62dd0f1d74..b72c8ccb57dd14f 100644 --- a/selfdrive/pandad/__init__.py +++ b/selfdrive/pandad/__init__.py @@ -1,10 +1,11 @@ # Cython, now uses scons to build -from openpilot.selfdrive.pandad.pandad_api_impl import can_list_to_can_capnp +from openpilot.selfdrive.pandad.pandad_api_impl import can_list_to_can_capnp, can_capnp_to_list assert can_list_to_can_capnp +assert can_capnp_to_list def can_capnp_to_can_list(can, src_filter=None): ret = [] for msg in can: if src_filter is None or msg.src in src_filter: - ret.append((msg.address, msg.busTime, msg.dat, msg.src)) + ret.append((msg.address, msg.dat, msg.src)) return ret diff --git a/selfdrive/pandad/can_list_to_can_capnp.cc b/selfdrive/pandad/can_list_to_can_capnp.cc index 9fc2648da27a62b..ad2393b986ccff9 100644 --- a/selfdrive/pandad/can_list_to_can_capnp.cc +++ b/selfdrive/pandad/can_list_to_can_capnp.cc @@ -1,16 +1,16 @@ #include "cereal/messaging/messaging.h" #include "selfdrive/pandad/panda.h" +#include "opendbc/can/common.h" -void can_list_to_can_capnp_cpp(const std::vector &can_list, std::string &out, bool sendCan, bool valid) { +void can_list_to_can_capnp_cpp(const std::vector &can_list, std::string &out, bool sendcan, bool valid) { MessageBuilder msg; auto event = msg.initEvent(valid); - auto canData = sendCan ? event.initSendcan(can_list.size()) : event.initCan(can_list.size()); + auto canData = sendcan ? event.initSendcan(can_list.size()) : event.initCan(can_list.size()); int j = 0; for (auto it = can_list.begin(); it != can_list.end(); it++, j++) { auto c = canData[j]; c.setAddress(it->address); - c.setBusTime(it->busTime); c.setDat(kj::arrayPtr((uint8_t*)it->dat.data(), it->dat.size())); c.setSrc(it->src); } @@ -19,3 +19,33 @@ void can_list_to_can_capnp_cpp(const std::vector &can_list, std::stri kj::ArrayOutputStream output_stream(kj::ArrayPtr((unsigned char *)out.data(), msg_size)); capnp::writeMessage(output_stream, msg); } + +// Converts a vector of Cap'n Proto serialized can strings into a vector of CanData structures. +void can_capnp_to_can_list_cpp(const std::vector &strings, std::vector &can_list, bool sendcan) { + AlignedBuffer aligned_buf; + can_list.reserve(strings.size()); + + for (const auto &str : strings) { + // extract the messages + capnp::FlatArrayMessageReader reader(aligned_buf.align(str.data(), str.size())); + cereal::Event::Reader event = reader.getRoot(); + + auto frames = sendcan ? event.getSendcan() : event.getCan(); + + // Add new CanData entry + CanData &can_data = can_list.emplace_back(); + can_data.nanos = event.getLogMonoTime(); + can_data.frames.reserve(frames.size()); + + // Populate CAN frames + for (const auto &frame : frames) { + CanFrame &can_frame = can_data.frames.emplace_back(); + can_frame.src = frame.getSrc(); + can_frame.address = frame.getAddress(); + + // Copy CAN data + auto dat = frame.getDat(); + can_frame.dat.assign(dat.begin(), dat.end()); + } + } +} diff --git a/selfdrive/pandad/panda.cc b/selfdrive/pandad/panda.cc index a404ad3880662d9..5372e54aef8774b 100644 --- a/selfdrive/pandad/panda.cc +++ b/selfdrive/pandad/panda.cc @@ -10,6 +10,8 @@ #include "common/swaglog.h" #include "common/util.h" +const bool PANDAD_MAXOUT = getenv("PANDAD_MAXOUT") != nullptr; + Panda::Panda(std::string serial, uint32_t bus_offset) : bus_offset(bus_offset) { // try USB first, then SPI try { @@ -26,8 +28,6 @@ Panda::Panda(std::string serial, uint32_t bus_offset) : bus_offset(bus_offset) { hw_type = get_hw_type(); can_reset_communications(); - - return; } bool Panda::connected() { @@ -47,7 +47,7 @@ std::vector Panda::list(bool usb_only) { #ifndef __APPLE__ if (!usb_only) { - for (auto s : PandaSpiHandle::list()) { + for (const auto &s : PandaSpiHandle::list()) { if (std::find(serials.begin(), serials.end(), s) == serials.end()) { serials.push_back(s); } @@ -169,7 +169,7 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data int32_t pos = 0; uint8_t send_buf[2 * USB_TX_SOFT_LIMIT]; - for (auto cmsg : can_data_list) { + for (const auto &cmsg : can_data_list) { // check if the message is intended for this panda uint8_t bus = cmsg.getSrc(); if (bus < bus_offset || bus >= (bus_offset + PANDA_BUS_OFFSET)) { @@ -206,7 +206,7 @@ void Panda::pack_can_buffer(const capnp::List::Reader &can_data if (pos > 0) write_func(send_buf, pos); } -void Panda::can_send(capnp::List::Reader can_data_list) { +void Panda::can_send(const capnp::List::Reader &can_data_list) { pack_can_buffer(can_data_list, [=](uint8_t* data, size_t size) { handle->bulk_write(3, data, size, 5); }); @@ -221,7 +221,7 @@ bool Panda::can_receive(std::vector& out_vec) { return false; } - if (getenv("PANDAD_MAXOUT") != NULL) { + if (PANDAD_MAXOUT) { static uint8_t junk[RECV_SIZE]; handle->bulk_read(0xab, junk, RECV_SIZE - recv); } @@ -259,7 +259,6 @@ bool Panda::unpack_can_buffer(uint8_t *data, uint32_t &size, std::vector::Reader can_data_list); + void can_send(const capnp::List::Reader &can_data_list); bool can_receive(std::vector& out_vec); void can_reset_communications(); diff --git a/selfdrive/pandad/panda_comms.cc b/selfdrive/pandad/panda_comms.cc index 4e8a0a27ba8e63f..59908f0cde23d7a 100644 --- a/selfdrive/pandad/panda_comms.cc +++ b/selfdrive/pandad/panda_comms.cc @@ -120,7 +120,7 @@ std::vector PandaUsbHandle::list() { libusb_close(handle); if (ret < 0) { goto finish; } - serials.push_back(std::string((char *)desc_serial, ret).c_str()); + serials.push_back(std::string((char *)desc_serial, ret)); } } diff --git a/selfdrive/pandad/panda_safety.cc b/selfdrive/pandad/panda_safety.cc new file mode 100644 index 000000000000000..0a14894677fcdc4 --- /dev/null +++ b/selfdrive/pandad/panda_safety.cc @@ -0,0 +1,83 @@ +#include "selfdrive/pandad/pandad.h" +#include "cereal/messaging/messaging.h" +#include "common/swaglog.h" + +void PandaSafety::configureSafetyMode() { + bool is_onroad = params_.getBool("IsOnroad"); + + if (is_onroad && !safety_configured_) { + updateMultiplexingMode(); + + auto car_params = fetchCarParams(); + if (!car_params.empty()) { + LOGW("got %lu bytes CarParams", car_params.size()); + setSafetyMode(car_params); + safety_configured_ = true; + } + } else if (!is_onroad) { + initialized_ = false; + safety_configured_ = false; + log_once_ = false; + } +} + +void PandaSafety::updateMultiplexingMode() { + // Initialize to ELM327 without OBD multiplexing for initial fingerprinting + if (!initialized_) { + prev_obd_multiplexing_ = false; + for (int i = 0; i < pandas_.size(); ++i) { + pandas_[i]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, 1U); + } + initialized_ = true; + } + + // Switch between multiplexing modes based on the OBD multiplexing request + bool obd_multiplexing_requested = params_.getBool("ObdMultiplexingEnabled"); + if (obd_multiplexing_requested != prev_obd_multiplexing_) { + for (int i = 0; i < pandas_.size(); ++i) { + const uint16_t safety_param = (i > 0 || !obd_multiplexing_requested) ? 1U : 0U; + pandas_[i]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, safety_param); + } + prev_obd_multiplexing_ = obd_multiplexing_requested; + params_.putBool("ObdMultiplexingChanged", true); + } +} + +std::string PandaSafety::fetchCarParams() { + if (!params_.getBool("FirmwareQueryDone")) { + return {}; + } + + if (!log_once_) { + LOGW("Finished FW query, Waiting for params to set safety model"); + log_once_ = true; + } + + if (!params_.getBool("ControlsReady")) { + return {}; + } + return params_.get("CarParams"); +} + +void PandaSafety::setSafetyMode(const std::string ¶ms_string) { + AlignedBuffer aligned_buf; + capnp::FlatArrayMessageReader cmsg(aligned_buf.align(params_string.data(), params_string.size())); + cereal::CarParams::Reader car_params = cmsg.getRoot(); + + auto safety_configs = car_params.getSafetyConfigs(); + uint16_t alternative_experience = car_params.getAlternativeExperience(); + + for (int i = 0; i < pandas_.size(); ++i) { + // Default to SILENT safety model if not specified + cereal::CarParams::SafetyModel safety_model = cereal::CarParams::SafetyModel::SILENT; + uint16_t safety_param = 0U; + if (i < safety_configs.size()) { + safety_model = safety_configs[i].getSafetyModel(); + safety_param = safety_configs[i].getSafetyParam(); + } + + LOGW("Panda %d: setting safety model: %d, param: %d, alternative experience: %d", i, (int)safety_model, safety_param, alternative_experience); + pandas_[i]->set_alternative_experience(alternative_experience); + pandas_[i]->set_safety_model(safety_model, safety_param); + } +} diff --git a/selfdrive/pandad/pandad.cc b/selfdrive/pandad/pandad.cc index 095a7893b4665a6..a85159f33a818b3 100644 --- a/selfdrive/pandad/pandad.cc +++ b/selfdrive/pandad/pandad.cc @@ -2,18 +2,15 @@ #include #include -#include #include #include #include -#include -#include #include #include +#include #include "cereal/gen/cpp/car.capnp.h" #include "cereal/messaging/messaging.h" -#include "common/params.h" #include "common/ratekeeper.h" #include "common/swaglog.h" #include "common/timing.h" @@ -43,9 +40,6 @@ #define MIN_IR_POWER 0.0f #define CUTOFF_IL 400 #define SATURATE_IL 1000 -using namespace std::chrono_literals; - -std::atomic ignition(false); ExitHandler do_exit; @@ -59,88 +53,6 @@ bool check_all_connected(const std::vector &pandas) { return true; } -bool safety_setter_thread(std::vector pandas) { - LOGD("Starting safety setter thread"); - - Params p; - - // there should be at least one panda connected - if (pandas.size() == 0) { - return false; - } - - // initialize to ELM327 without OBD multiplexing for fingerprinting - bool obd_multiplexing_enabled = false; - for (int i = 0; i < pandas.size(); i++) { - pandas[i]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, 1U); - } - - // openpilot can switch between multiplexing modes for different FW queries - while (true) { - if (do_exit || !check_all_connected(pandas) || !ignition) { - return false; - } - - bool obd_multiplexing_requested = p.getBool("ObdMultiplexingEnabled"); - if (obd_multiplexing_requested != obd_multiplexing_enabled) { - for (int i = 0; i < pandas.size(); i++) { - const uint16_t safety_param = (i > 0 || !obd_multiplexing_requested) ? 1U : 0U; - pandas[i]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, safety_param); - } - obd_multiplexing_enabled = obd_multiplexing_requested; - p.putBool("ObdMultiplexingChanged", true); - } - - if (p.getBool("FirmwareQueryDone")) { - LOGW("finished FW query"); - break; - } - util::sleep_for(20); - } - - std::string params; - LOGW("waiting for params to set safety model"); - while (true) { - if (do_exit || !check_all_connected(pandas) || !ignition) { - return false; - } - - if (p.getBool("ControlsReady")) { - params = p.get("CarParams"); - if (params.size() > 0) break; - } - util::sleep_for(100); - } - LOGW("got %lu bytes CarParams", params.size()); - - AlignedBuffer aligned_buf; - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(params.data(), params.size())); - cereal::CarParams::Reader car_params = cmsg.getRoot(); - cereal::CarParams::SafetyModel safety_model; - uint16_t safety_param; - - auto safety_configs = car_params.getSafetyConfigs(); - uint16_t alternative_experience = car_params.getAlternativeExperience(); - for (uint32_t i = 0; i < pandas.size(); i++) { - auto panda = pandas[i]; - - if (safety_configs.size() > i) { - safety_model = safety_configs[i].getSafetyModel(); - safety_param = safety_configs[i].getSafetyParam(); - } else { - // If no safety mode is specified, default to silent - safety_model = cereal::CarParams::SafetyModel::SILENT; - safety_param = 0U; - } - - LOGW("panda %d: setting safety model: %d, param: %d, alternative experience: %d", i, (int)safety_model, safety_param, alternative_experience); - panda->set_alternative_experience(alternative_experience); - panda->set_safety_model(safety_model, safety_param); - } - - return true; -} - Panda *connect(std::string serial="", uint32_t index=0) { std::unique_ptr panda; try { @@ -197,16 +109,9 @@ void can_send_thread(std::vector pandas, bool fake_send) { } } -void can_recv_thread(std::vector pandas) { - util::set_thread_name("pandad_can_recv"); - - PubMaster pm({"can"}); - - // run at 100Hz - RateKeeper rk("pandad_can_recv", 100); - std::vector raw_can_data; - - while (!do_exit && check_all_connected(pandas)) { +void can_recv(std::vector &pandas, PubMaster *pm) { + static std::vector raw_can_data; + { bool comms_healthy = true; raw_can_data.clear(); for (const auto& panda : pandas) { @@ -217,18 +122,71 @@ void can_recv_thread(std::vector pandas) { auto evt = msg.initEvent(); evt.setValid(comms_healthy); auto canData = evt.initCan(raw_can_data.size()); - for (uint i = 0; isend("can", msg); } } +void fill_panda_state(cereal::PandaState::Builder &ps, cereal::PandaState::PandaType hw_type, const health_t &health) { + ps.setVoltage(health.voltage_pkt); + ps.setCurrent(health.current_pkt); + ps.setUptime(health.uptime_pkt); + ps.setSafetyTxBlocked(health.safety_tx_blocked_pkt); + ps.setSafetyRxInvalid(health.safety_rx_invalid_pkt); + ps.setIgnitionLine(health.ignition_line_pkt); + ps.setIgnitionCan(health.ignition_can_pkt); + ps.setControlsAllowed(health.controls_allowed_pkt); + ps.setTxBufferOverflow(health.tx_buffer_overflow_pkt); + ps.setRxBufferOverflow(health.rx_buffer_overflow_pkt); + ps.setPandaType(hw_type); + ps.setSafetyModel(cereal::CarParams::SafetyModel(health.safety_mode_pkt)); + ps.setSafetyParam(health.safety_param_pkt); + ps.setFaultStatus(cereal::PandaState::FaultStatus(health.fault_status_pkt)); + ps.setPowerSaveEnabled((bool)(health.power_save_enabled_pkt)); + 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_pkt); + ps.setFanPower(health.fan_power); + ps.setFanStallCount(health.fan_stall_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); +} + +void fill_panda_can_state(cereal::PandaState::PandaCanState::Builder &cs, const can_health_t &can_health) { + cs.setBusOff((bool)can_health.bus_off); + cs.setBusOffCnt(can_health.bus_off_cnt); + cs.setErrorWarning((bool)can_health.error_warning); + cs.setErrorPassive((bool)can_health.error_passive); + cs.setLastError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_error)); + cs.setLastStoredError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_stored_error)); + cs.setLastDataError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_data_error)); + cs.setLastDataStoredError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_data_stored_error)); + cs.setReceiveErrorCnt(can_health.receive_error_cnt); + cs.setTransmitErrorCnt(can_health.transmit_error_cnt); + cs.setTotalErrorCnt(can_health.total_error_cnt); + cs.setTotalTxLostCnt(can_health.total_tx_lost_cnt); + cs.setTotalRxLostCnt(can_health.total_rx_lost_cnt); + cs.setTotalTxCnt(can_health.total_tx_cnt); + cs.setTotalRxCnt(can_health.total_rx_cnt); + cs.setTotalFwdCnt(can_health.total_fwd_cnt); + cs.setCanSpeed(can_health.can_speed); + cs.setCanDataSpeed(can_health.can_data_speed); + cs.setCanfdEnabled(can_health.canfd_enabled); + cs.setBrsEnabled(can_health.brs_enabled); + cs.setCanfdNonIso(can_health.canfd_non_iso); + cs.setIrq0CallRate(can_health.irq0_call_rate); + cs.setIrq1CallRate(can_health.irq1_call_rate); + cs.setIrq2CallRate(can_health.irq2_call_rate); + cs.setCanCoreResetCnt(can_health.can_core_reset_cnt); +} + std::optional send_panda_states(PubMaster *pm, const std::vector &pandas, bool spoofing_started) { bool ignition_local = false; const uint32_t pandas_cnt = pandas.size(); @@ -306,61 +264,11 @@ std::optional send_panda_states(PubMaster *pm, const std::vector } auto ps = pss[i]; - ps.setVoltage(health.voltage_pkt); - ps.setCurrent(health.current_pkt); - ps.setUptime(health.uptime_pkt); - ps.setSafetyTxBlocked(health.safety_tx_blocked_pkt); - ps.setSafetyRxInvalid(health.safety_rx_invalid_pkt); - ps.setIgnitionLine(health.ignition_line_pkt); - ps.setIgnitionCan(health.ignition_can_pkt); - ps.setControlsAllowed(health.controls_allowed_pkt); - ps.setTxBufferOverflow(health.tx_buffer_overflow_pkt); - ps.setRxBufferOverflow(health.rx_buffer_overflow_pkt); - ps.setPandaType(panda->hw_type); - ps.setSafetyModel(cereal::CarParams::SafetyModel(health.safety_mode_pkt)); - ps.setSafetyParam(health.safety_param_pkt); - ps.setFaultStatus(cereal::PandaState::FaultStatus(health.fault_status_pkt)); - ps.setPowerSaveEnabled((bool)(health.power_save_enabled_pkt)); - 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_pkt); - ps.setFanPower(health.fan_power); - ps.setFanStallCount(health.fan_stall_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); - - std::array cs = {ps.initCanState0(), ps.initCanState1(), ps.initCanState2()}; + fill_panda_state(ps, panda->hw_type, health); + auto cs = std::array{ps.initCanState0(), ps.initCanState1(), ps.initCanState2()}; for (uint32_t j = 0; j < PANDA_CAN_CNT; j++) { - const auto &can_health = pandaCanStates[i][j]; - cs[j].setBusOff((bool)can_health.bus_off); - cs[j].setBusOffCnt(can_health.bus_off_cnt); - cs[j].setErrorWarning((bool)can_health.error_warning); - cs[j].setErrorPassive((bool)can_health.error_passive); - cs[j].setLastError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_error)); - cs[j].setLastStoredError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_stored_error)); - cs[j].setLastDataError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_data_error)); - cs[j].setLastDataStoredError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_data_stored_error)); - cs[j].setReceiveErrorCnt(can_health.receive_error_cnt); - cs[j].setTransmitErrorCnt(can_health.transmit_error_cnt); - cs[j].setTotalErrorCnt(can_health.total_error_cnt); - cs[j].setTotalTxLostCnt(can_health.total_tx_lost_cnt); - cs[j].setTotalRxLostCnt(can_health.total_rx_lost_cnt); - cs[j].setTotalTxCnt(can_health.total_tx_cnt); - cs[j].setTotalRxCnt(can_health.total_rx_cnt); - cs[j].setTotalFwdCnt(can_health.total_fwd_cnt); - cs[j].setCanSpeed(can_health.can_speed); - cs[j].setCanDataSpeed(can_health.can_data_speed); - cs[j].setCanfdEnabled(can_health.canfd_enabled); - cs[j].setBrsEnabled(can_health.brs_enabled); - cs[j].setCanfdNonIso(can_health.canfd_non_iso); - cs[j].setIrq0CallRate(can_health.irq0_call_rate); - cs[j].setIrq1CallRate(can_health.irq1_call_rate); - cs[j].setIrq2CallRate(can_health.irq2_call_rate); - cs[j].setCanCoreResetCnt(can_health.can_core_reset_cnt); + fill_panda_can_state(cs[j], pandaCanStates[i][j]); } // Convert faults bitset to capnp list @@ -381,7 +289,7 @@ std::optional send_panda_states(PubMaster *pm, const std::vector return ignition_local; } -void send_peripheral_state(PubMaster *pm, Panda *panda) { +void send_peripheral_state(Panda *panda, PubMaster *pm) { // build msg MessageBuilder msg; auto evt = msg.initEvent(); @@ -398,52 +306,39 @@ void send_peripheral_state(PubMaster *pm, Panda *panda) { LOGW("reading hwmon took %lfms", read_time); } + // fall back to panda's voltage and current measurement + if (ps.getVoltage() == 0 && ps.getCurrent() == 0) { + auto health_opt = panda->get_state(); + if (health_opt) { + health_t health = *health_opt; + ps.setVoltage(health.voltage_pkt); + ps.setCurrent(health.current_pkt); + } + } + uint16_t fan_speed_rpm = panda->get_fan_speed(); ps.setFanSpeedRpm(fan_speed_rpm); pm->send("peripheralState", msg); } -void panda_state_thread(std::vector pandas, bool spoofing_started) { - util::set_thread_name("pandad_panda_state"); - - Params params; - SubMaster sm({"controlsState"}); - PubMaster pm({"pandaStates", "peripheralState"}); - - Panda *peripheral_panda = pandas[0]; - bool is_onroad = false; - bool is_onroad_last = false; - std::future safety_future; +void process_panda_state(std::vector &pandas, PubMaster *pm, bool spoofing_started) { + static SubMaster sm({"selfdriveState"}); std::vector connected_serials; for (Panda *p : pandas) { connected_serials.push_back(p->hw_serial()); } - LOGD("start panda state thread"); - - // run at 10hz - RateKeeper rk("panda_state_thread", 10); - - while (!do_exit && check_all_connected(pandas)) { - // send out peripheralState at 2Hz - if (sm.frame % 5 == 0) { - send_peripheral_state(&pm, peripheral_panda); - } - - auto ignition_opt = send_panda_states(&pm, pandas, spoofing_started); - + { + auto ignition_opt = send_panda_states(pm, pandas, spoofing_started); if (!ignition_opt) { LOGE("Failed to get ignition_opt"); - rk.keepTime(); - continue; + return; } - ignition = *ignition_opt; - // check if we should have pandad reconnect - if (!ignition) { + if (!ignition_opt.value()) { bool comms_healthy = true; for (const auto &panda : pandas) { comms_healthy &= panda->comms_healthy(); @@ -463,52 +358,28 @@ void panda_state_thread(std::vector pandas, bool spoofing_started) { } } } - - if (do_exit) { - break; - } - } - - is_onroad = params.getBool("IsOnroad"); - - // set new safety on onroad transition, after params are cleared - if (is_onroad && !is_onroad_last) { - if (!safety_future.valid() || safety_future.wait_for(0ms) == std::future_status::ready) { - safety_future = std::async(std::launch::async, safety_setter_thread, pandas); - } else { - LOGW("Safety setter thread already running"); - } } - is_onroad_last = is_onroad; - sm.update(0); - const bool engaged = sm.allAliveAndValid({"controlsState"}) && sm["controlsState"].getControlsState().getEnabled(); - + const bool engaged = sm.allAliveAndValid({"selfdriveState"}) && sm["selfdriveState"].getSelfdriveState().getEnabled(); for (const auto &panda : pandas) { panda->send_heartbeat(engaged); } - - rk.keepTime(); } } +void process_peripheral_state(Panda *panda, PubMaster *pm, bool no_fan_control) { + static SubMaster sm({"deviceState", "driverCameraState"}); -void peripheral_control_thread(Panda *panda, bool no_fan_control) { - util::set_thread_name("pandad_peripheral_control"); - - SubMaster sm({"deviceState", "driverCameraState"}); - - uint64_t last_driver_camera_t = 0; - uint16_t prev_fan_speed = 999; - uint16_t ir_pwr = 0; - uint16_t prev_ir_pwr = 999; + static uint64_t last_driver_camera_t = 0; + static uint16_t prev_fan_speed = 999; + static uint16_t ir_pwr = 0; + static uint16_t prev_ir_pwr = 999; - FirstOrderFilter integ_lines_filter(0, 30.0, 0.05); - - while (!do_exit && panda->connected()) { - sm.update(1000); + static FirstOrderFilter integ_lines_filter(0, 30.0, 0.05); + { + sm.update(0); if (sm.updated("deviceState") && !no_fan_control) { // Fan speed uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired(); @@ -546,9 +417,46 @@ void peripheral_control_thread(Panda *panda, bool no_fan_control) { } } -void pandad_main_thread(std::vector serials) { - LOGW("launching pandad"); +void pandad_run(std::vector &pandas) { + const bool no_fan_control = getenv("NO_FAN_CONTROL") != nullptr; + const bool spoofing_started = getenv("STARTED") != nullptr; + const bool fake_send = getenv("FAKESEND") != nullptr; + + // Start the CAN send thread + std::thread send_thread(can_send_thread, pandas, fake_send); + + RateKeeper rk("pandad", 100); + PubMaster pm({"can", "pandaStates", "peripheralState"}); + PandaSafety panda_safety(pandas); + Panda *peripheral_panda = pandas[0]; + + // Main loop: receive CAN data and process states + while (!do_exit && check_all_connected(pandas)) { + can_recv(pandas, &pm); + + // Process peripheral state at 20 Hz + if (rk.frame() % 5 == 0) { + process_peripheral_state(peripheral_panda, &pm, no_fan_control); + } + + // Process panda state at 10 Hz + if (rk.frame() % 10 == 0) { + process_panda_state(pandas, &pm, spoofing_started); + panda_safety.configureSafetyMode(); + } + // Send out peripheralState at 2Hz + if (rk.frame() % 50 == 0) { + send_peripheral_state(peripheral_panda, &pm); + } + + rk.keepTime(); + } + + send_thread.join(); +} + +void pandad_main_thread(std::vector serials) { if (serials.size() == 0) { serials = Panda::list(); @@ -580,16 +488,7 @@ void pandad_main_thread(std::vector serials) { if (!do_exit) { LOGW("connected to all pandas"); - - std::vector threads; - - threads.emplace_back(panda_state_thread, pandas, getenv("STARTED") != nullptr); - threads.emplace_back(peripheral_control_thread, pandas[0], getenv("NO_FAN_CONTROL") != nullptr); - - threads.emplace_back(can_send_thread, pandas, getenv("FAKESEND") != nullptr); - threads.emplace_back(can_recv_thread, pandas); - - for (auto &t : threads) t.join(); + pandad_run(pandas); } for (Panda *panda : pandas) { diff --git a/selfdrive/pandad/pandad.h b/selfdrive/pandad/pandad.h index 9d35949a8fd1f49..dedd8ae79a219b3 100644 --- a/selfdrive/pandad/pandad.h +++ b/selfdrive/pandad/pandad.h @@ -3,7 +3,25 @@ #include #include +#include "common/params.h" #include "selfdrive/pandad/panda.h" -bool safety_setter_thread(std::vector pandas); void pandad_main_thread(std::vector serials); + +class PandaSafety { +public: + PandaSafety(const std::vector &pandas) : pandas_(pandas) {} + void configureSafetyMode(); + +private: + void updateMultiplexingMode(); + std::string fetchCarParams(); + void setSafetyMode(const std::string ¶ms_string); + + bool initialized_ = false; + bool log_once_ = false; + bool safety_configured_ = false; + bool prev_obd_multiplexing_ = false; + std::vector pandas_; + Params params_; +}; diff --git a/selfdrive/pandad/pandad_api_impl.pyx b/selfdrive/pandad/pandad_api_impl.pyx index cbac8cc5a3adf0f..787968f53e7db31 100644 --- a/selfdrive/pandad/pandad_api_impl.pyx +++ b/selfdrive/pandad/pandad_api_impl.pyx @@ -1,18 +1,30 @@ # distutils: language = c++ # cython: language_level=3 +from cython.operator cimport dereference as deref, preincrement as preinc from libcpp.vector cimport vector from libcpp.string cimport string from libcpp cimport bool +from libc.stdint cimport uint8_t, uint32_t, uint64_t cdef extern from "panda.h": cdef struct can_frame: long address string dat - long busTime long src +cdef extern from "opendbc/can/common.h": + cdef struct CanFrame: + long src + uint32_t address + vector[uint8_t] dat + + cdef struct CanData: + uint64_t nanos + vector[CanFrame] frames + cdef extern from "can_list_to_can_capnp.cc": - void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendcan, bool valid) + void can_capnp_to_can_list_cpp(const vector[string] &strings, vector[CanData] &can_data, bool sendcan) def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): cdef can_frame *f @@ -22,10 +34,23 @@ def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): for can_msg in can_msgs: f = &(can_list.emplace_back()) f.address = can_msg[0] - f.busTime = can_msg[1] - f.dat = can_msg[2] - f.src = can_msg[3] + f.dat = can_msg[1] + f.src = can_msg[2] cdef string out can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) return out + +def can_capnp_to_list(strings, msgtype='can'): + cdef vector[CanData] data + can_capnp_to_can_list_cpp(strings, data, msgtype == 'sendcan') + + result = [] + cdef CanData *d + cdef vector[CanData].iterator it = data.begin() + while it != data.end(): + d = &deref(it) + frames = [(f.address, (&f.dat[0])[:f.dat.size()], f.src) for f in d.frames] + result.append((d.nanos, frames)) + preinc(it) + return result diff --git a/selfdrive/pandad/tests/test_pandad.py b/selfdrive/pandad/tests/test_pandad.py index 467c7f04c9dde6e..213678193fc0be3 100644 --- a/selfdrive/pandad/tests/test_pandad.py +++ b/selfdrive/pandad/tests/test_pandad.py @@ -103,9 +103,8 @@ def test_best_case_startup_time(self): # 5s for USB (due to enumeration) # - 0.2s pandad -> pandad # - plus some buffer - assert 0.1 < (sum(ts)/len(ts)) < (0.5 if self.spi else 5.0) print("startup times", ts, sum(ts) / len(ts)) - + assert 0.1 < (sum(ts)/len(ts)) < (0.7 if self.spi else 5.0) def test_protocol_version_check(self): if not self.spi: diff --git a/selfdrive/pandad/tests/test_pandad_loopback.py b/selfdrive/pandad/tests/test_pandad_loopback.py index d2b6d047d562b86..0f41201ececc0ea 100644 --- a/selfdrive/pandad/tests/test_pandad_loopback.py +++ b/selfdrive/pandad/tests/test_pandad_loopback.py @@ -8,11 +8,11 @@ import cereal.messaging as messaging from cereal import car, log +from opendbc.car.can_definitions import CanData from openpilot.common.retry import retry from openpilot.common.params import Params from openpilot.common.timeout import Timeout from openpilot.selfdrive.pandad import can_list_to_can_capnp -from openpilot.selfdrive.car import make_can_msg from openpilot.system.hardware import TICI from openpilot.selfdrive.test.helpers import phone_only, with_processes @@ -60,7 +60,7 @@ def send_random_can_messages(sendcan, count, num_pandas=1): if (addr, dat) in sent_msgs[bus]: continue sent_msgs[bus].add((addr, dat)) - to_send.append(make_can_msg(addr, dat, bus)) + to_send.append(CanData(addr, dat, bus)) sendcan.send(can_list_to_can_capnp(to_send, msgtype='sendcan')) return sent_msgs diff --git a/selfdrive/pandad/tests/test_pandad_spi.py b/selfdrive/pandad/tests/test_pandad_spi.py index 11e20e72ccde6c1..9c5990cd3f59d63 100644 --- a/selfdrive/pandad/tests/test_pandad_spi.py +++ b/selfdrive/pandad/tests/test_pandad_spi.py @@ -84,8 +84,8 @@ def test_spi_corruption(self, subtests): ps = m.peripheralState assert ps.pandaType == "tres" assert 4000 < ps.voltage < 14000 - assert 100 < ps.current < 1000 - assert ps.fanSpeedRpm < 8000 + assert 50 < ps.current < 1000 + assert ps.fanSpeedRpm < 10000 time.sleep(0.5) et = time.monotonic() - st diff --git a/selfdrive/selfdrived/alertmanager.py b/selfdrive/selfdrived/alertmanager.py new file mode 100644 index 000000000000000..ac1006ff258c017 --- /dev/null +++ b/selfdrive/selfdrived/alertmanager.py @@ -0,0 +1,67 @@ +import copy +import os +import json +from collections import defaultdict +from dataclasses import dataclass + +from openpilot.common.basedir import BASEDIR +from openpilot.common.params import Params +from openpilot.selfdrive.selfdrived.events import Alert, EmptyAlert + + +with open(os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json")) as f: + OFFROAD_ALERTS = json.load(f) + + +def set_offroad_alert(alert: str, show_alert: bool, extra_text: str = None) -> None: + if show_alert: + a = copy.copy(OFFROAD_ALERTS[alert]) + a['extra'] = extra_text or '' + Params().put(alert, json.dumps(a)) + else: + Params().remove(alert) + + +@dataclass +class AlertEntry: + alert: Alert | None = None + start_frame: int = -1 + end_frame: int = -1 + added_frame: int = -1 + + def active(self, frame: int) -> bool: + return frame <= self.end_frame + + def just_added(self, frame: int) -> bool: + return self.active(frame) and frame == (self.added_frame + 1) + +class AlertManager: + def __init__(self): + self.alerts: dict[str, AlertEntry] = defaultdict(AlertEntry) + self.current_alert = EmptyAlert + + def add_many(self, frame: int, alerts: list[Alert]) -> None: + for alert in alerts: + entry = self.alerts[alert.alert_type] + entry.alert = alert + if not entry.just_added(frame): + entry.start_frame = frame + min_end_frame = entry.start_frame + alert.duration + entry.end_frame = max(frame + 1, min_end_frame) + entry.added_frame = frame + + def process_alerts(self, frame: int, clear_event_types: set): + ae = AlertEntry() + for v in self.alerts.values(): + if not v.alert: + continue + + if v.alert.event_type in clear_event_types: + v.end_frame = -1 + + # sort by priority first and then by start_frame + greater = ae.alert is None or (v.alert.priority, v.start_frame) > (ae.alert.priority, ae.start_frame) + if v.active(frame) and greater: + ae = v + + self.current_alert = ae.alert if ae.alert is not None else EmptyAlert diff --git a/selfdrive/controls/lib/alerts_offroad.json b/selfdrive/selfdrived/alerts_offroad.json similarity index 88% rename from selfdrive/controls/lib/alerts_offroad.json rename to selfdrive/selfdrived/alerts_offroad.json index 6fb6c569b023f27..86e07d3213945f3 100644 --- a/selfdrive/controls/lib/alerts_offroad.json +++ b/selfdrive/selfdrived/alerts_offroad.json @@ -41,10 +41,6 @@ "text": "openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai.", "severity": 0 }, - "Offroad_NoFirmware": { - "text": "openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai.", - "severity": 0 - }, "Offroad_Recalibration": { "text": "openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield.", "severity": 0 diff --git a/selfdrive/controls/lib/events.py b/selfdrive/selfdrived/events.py similarity index 88% rename from selfdrive/controls/lib/events.py rename to selfdrive/selfdrived/events.py index b01818d704bf228..cdc23e53c93d9e9 100755 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/selfdrived/events.py @@ -12,11 +12,11 @@ from openpilot.common.realtime import DT_CTRL from openpilot.selfdrive.locationd.calibrationd import MIN_SPEED_FILTER -AlertSize = log.ControlsState.AlertSize -AlertStatus = log.ControlsState.AlertStatus +AlertSize = log.SelfdriveState.AlertSize +AlertStatus = log.SelfdriveState.AlertStatus VisualAlert = car.CarControl.HUDControl.VisualAlert AudibleAlert = car.CarControl.HUDControl.AudibleAlert -EventName = car.CarEvent.EventName +EventName = log.OnroadEvent.EventName # Alert priorities @@ -98,7 +98,7 @@ def add_from_msg(self, events): def to_msg(self): ret = [] for event_name in self.events: - event = car.CarEvent.new_message() + event = log.OnroadEvent.new_message() event.name = event_name for event_type in EVENTS.get(event_name, {}): setattr(event, event_type, True) @@ -110,13 +110,12 @@ class Alert: def __init__(self, alert_text_1: str, alert_text_2: str, - alert_status: log.ControlsState.AlertStatus, - alert_size: log.ControlsState.AlertSize, + alert_status: log.SelfdriveState.AlertStatus, + alert_size: log.SelfdriveState.AlertSize, priority: Priority, visual_alert: car.CarControl.HUDControl.VisualAlert, audible_alert: car.CarControl.HUDControl.AudibleAlert, duration: float, - alert_rate: float = 0., creation_delay: float = 0.): self.alert_text_1 = alert_text_1 @@ -129,7 +128,6 @@ def __init__(self, self.duration = int(duration / DT_CTRL) - self.alert_rate = alert_rate self.creation_delay = creation_delay self.alert_type = "" @@ -143,6 +141,8 @@ def __gt__(self, alert2) -> bool: return False return self.priority > alert2.priority +EmptyAlert = Alert("" , "", AlertStatus.normal, AlertSize.none, Priority.LOWEST, + VisualAlert.none, AudibleAlert.none, 0) class NoEntryAlert(Alert): def __init__(self, alert_text_2: str, @@ -207,35 +207,35 @@ def get_display_speed(speed_ms: float, metric: bool) -> str: # ********** alert callback functions ********** -AlertCallbackType = Callable[[car.CarParams, car.CarState, messaging.SubMaster, bool, int], Alert] +AlertCallbackType = Callable[[car.CarParams, car.CarState, messaging.SubMaster, bool, int, log.ControlsState], Alert] def soft_disable_alert(alert_text_2: str) -> AlertCallbackType: - def func(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: + def func(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: if soft_disable_time < int(0.5 / DT_CTRL): return ImmediateDisableAlert(alert_text_2) return SoftDisableAlert(alert_text_2) return func def user_soft_disable_alert(alert_text_2: str) -> AlertCallbackType: - def func(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: + def func(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: if soft_disable_time < int(0.5 / DT_CTRL): return ImmediateDisableAlert(alert_text_2) return UserSoftDisableAlert(alert_text_2) return func -def startup_master_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def startup_master_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: branch = get_short_branch() # Ensure get_short_branch is cached to avoid lags on startup if "REPLAY" in os.environ: branch = "replay" return StartupAlert("WARNING: This branch is not tested", branch, alert_status=AlertStatus.userPrompt) -def below_engage_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def below_engage_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: return NoEntryAlert(f"Drive above {get_display_speed(CP.minEnableSpeed, metric)} to engage") -def below_steer_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def below_steer_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: return Alert( f"Steer Unavailable Below {get_display_speed(CP.minSteerSpeed, metric)}", "", @@ -243,7 +243,7 @@ def below_steer_speed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.S Priority.LOW, VisualAlert.steerRequired, AudibleAlert.prompt, 0.4) -def calibration_incomplete_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def calibration_incomplete_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: first_word = 'Recalibration' if sm['liveCalibration'].calStatus == log.LiveCalibrationData.Status.recalibrating else 'Calibration' return Alert( f"{first_word} in Progress: {sm['liveCalibration'].calPerc:.0f}%", @@ -254,37 +254,37 @@ def calibration_incomplete_alert(CP: car.CarParams, CS: car.CarState, sm: messag # *** debug alerts *** -def out_of_space_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def out_of_space_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: full_perc = round(100. - sm['deviceState'].freeSpacePercent) return NormalPermanentAlert("Out of Storage", f"{full_perc}% full") -def posenet_invalid_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def posenet_invalid_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: mdl = sm['modelV2'].velocity.x[0] if len(sm['modelV2'].velocity.x) else math.nan err = CS.vEgo - mdl msg = f"Speed Error: {err:.1f} m/s" return NoEntryAlert(msg, alert_text_1="Posenet Speed Invalid") -def process_not_running_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def process_not_running_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: not_running = [p.name for p in sm['managerState'].processes if not p.running and p.shouldBeRunning] msg = ', '.join(not_running) return NoEntryAlert(msg, alert_text_1="Process Not Running") -def comm_issue_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def comm_issue_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: bs = [s for s in sm.data.keys() if not sm.all_checks([s, ])] msg = ', '.join(bs[:4]) # can't fit too many on one line return NoEntryAlert(msg, alert_text_1="Communication Issue Between Processes") -def camera_malfunction_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def camera_malfunction_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: all_cams = ('roadCameraState', 'driverCameraState', 'wideRoadCameraState') bad_cams = [s.replace('State', '') for s in all_cams if s in sm.data.keys() and not sm.all_checks([s, ])] return NormalPermanentAlert("Camera Malfunction", ', '.join(bad_cams)) -def calibration_invalid_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def calibration_invalid_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: rpy = sm['liveCalibration'].rpyCalib yaw = math.degrees(rpy[2] if len(rpy) == 3 else math.nan) pitch = math.degrees(rpy[1] if len(rpy) == 3 else math.nan) @@ -292,40 +292,55 @@ def calibration_invalid_alert(CP: car.CarParams, CS: car.CarState, sm: messaging return NormalPermanentAlert("Calibration Invalid", angles) -def overheat_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def overheat_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: cpu = max(sm['deviceState'].cpuTempC, default=0.) gpu = max(sm['deviceState'].gpuTempC, default=0.) temp = max((cpu, gpu, sm['deviceState'].memoryTempC)) return NormalPermanentAlert("System Overheated", f"{temp:.0f} °C") -def low_memory_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def low_memory_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: return NormalPermanentAlert("Low Memory", f"{sm['deviceState'].memoryUsagePercent}% used") -def high_cpu_usage_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def high_cpu_usage_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: x = max(sm['deviceState'].cpuUsagePercent, default=0.) return NormalPermanentAlert("High CPU Usage", f"{x}% used") -def modeld_lagging_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def modeld_lagging_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: return NormalPermanentAlert("Driving Model Lagging", f"{sm['modelV2'].frameDropPerc:.1f}% frames dropped") -def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: +def wrong_car_mode_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: text = "Enable Adaptive Cruise to Engage" if CP.carName == "honda": text = "Enable Main Switch to Engage" return NoEntryAlert(text) -def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - axes = sm['testJoystick'].axes - gb, steer = list(axes)[:2] if len(axes) else (0., 0.) +def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: + gb = sm['carControl'].actuators.accel / 4. + steer = sm['carControl'].actuators.steer vals = f"Gas: {round(gb * 100.)}%, Steer: {round(steer * 100.)}%" return NormalPermanentAlert("Joystick Mode", vals) +def longitudinal_maneuver_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: + ad = sm['alertDebug'] + audible_alert = AudibleAlert.prompt if 'Active' in ad.alertText1 else AudibleAlert.none + alert_status = AlertStatus.userPrompt if 'Active' in ad.alertText1 else AlertStatus.normal + alert_size = AlertSize.mid if ad.alertText2 else AlertSize.small + return Alert(ad.alertText1, ad.alertText2, + alert_status, alert_size, + Priority.LOW, VisualAlert.none, audible_alert, 0.2) + + +def personality_changed_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, metric: bool, soft_disable_time: int, personality) -> Alert: + personality = str(personality).title() + return NormalPermanentAlert(f"Driving Personality: {personality}", duration=1.5) + + EVENTS: dict[int, dict[str, Alert | AlertCallbackType]] = { # ********** events with no alerts ********** @@ -340,7 +355,13 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, ET.PERMANENT: NormalPermanentAlert("Joystick Mode"), }, - EventName.controlsInitializing: { + EventName.longitudinalManeuver: { + ET.WARNING: longitudinal_maneuver_alert, + ET.PERMANENT: NormalPermanentAlert("Longitudinal Maneuver Mode", + "Ensure road ahead is clear"), + }, + + EventName.selfdriveInitializing: { ET.NO_ENTRY: NoEntryAlert("System Initializing"), }, @@ -352,21 +373,19 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, ET.PERMANENT: startup_master_alert, }, - # Car is recognized, but marked as dashcam only EventName.startupNoControl: { ET.PERMANENT: StartupAlert("Dashcam mode"), ET.NO_ENTRY: NoEntryAlert("Dashcam mode"), }, - # Car is not recognized EventName.startupNoCar: { ET.PERMANENT: StartupAlert("Dashcam mode for unsupported car"), }, - EventName.startupNoFw: { - ET.PERMANENT: StartupAlert("Car Unrecognized", - "Check comma power connections", - alert_status=AlertStatus.userPrompt), + EventName.startupNoSecOcKey: { + ET.PERMANENT: NormalPermanentAlert("Dashcam Mode", + "Security Key Not Available", + priority=Priority.HIGH), }, EventName.dashcamMode: { @@ -375,8 +394,9 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, }, EventName.invalidLkasSetting: { - ET.PERMANENT: NormalPermanentAlert("Stock LKAS is on", - "Turn off stock LKAS to engage"), + ET.PERMANENT: NormalPermanentAlert("Invalid LKAS setting", + "Toggle stock LKAS on or off to engage"), + ET.NO_ENTRY: NoEntryAlert("Invalid LKAS setting"), }, EventName.cruiseMismatch: { @@ -392,6 +412,15 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, priority=Priority.LOWEST), }, + EventName.aeb: { + ET.PERMANENT: Alert( + "BRAKE!", + "Emergency Braking: Risk of Collision", + AlertStatus.critical, AlertSize.full, + Priority.HIGHEST, VisualAlert.fcw, AudibleAlert.none, 2.), + ET.NO_ENTRY: NoEntryAlert("AEB: Risk of Collision"), + }, + EventName.stockAeb: { ET.PERMANENT: Alert( "BRAKE!", @@ -456,7 +485,7 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, "Touch Steering Wheel: No Face Detected", "", AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .1, alert_rate=0.75), + Priority.LOW, VisualAlert.steerRequired, AudibleAlert.none, .1), }, EventName.promptDriverUnresponsive: { @@ -500,7 +529,7 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, "Steer Left to Start Lane Change Once Safe", "", AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.none, .1, alert_rate=0.75), + Priority.LOW, VisualAlert.none, AudibleAlert.none, .1), }, EventName.preLaneChangeRight: { @@ -508,7 +537,7 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, "Steer Right to Start Lane Change Once Safe", "", AlertStatus.normal, AlertSize.small, - Priority.LOW, VisualAlert.none, AudibleAlert.none, .1, alert_rate=0.75), + Priority.LOW, VisualAlert.none, AudibleAlert.none, .1), }, EventName.laneChangeBlocked: { @@ -695,11 +724,6 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, Priority.LOWER, VisualAlert.none, AudibleAlert.none, .2, creation_delay=600.) }, - EventName.soundsUnavailable: { - ET.PERMANENT: NormalPermanentAlert("Speaker not found", "Reboot your Device"), - ET.NO_ENTRY: NoEntryAlert("Speaker not found"), - }, - EventName.tooDistracted: { ET.NO_ENTRY: NoEntryAlert("Distraction Level Too High"), }, @@ -771,9 +795,9 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, ET.NO_ENTRY: NoEntryAlert("Low Communication Rate Between Processes"), }, - EventName.controlsdLagging: { - ET.SOFT_DISABLE: soft_disable_alert("Controls Lagging"), - ET.NO_ENTRY: NoEntryAlert("Controls Process Lagging: Reboot Your Device"), + EventName.selfdrivedLagging: { + ET.SOFT_DISABLE: soft_disable_alert("System Lagging"), + ET.NO_ENTRY: NoEntryAlert("Selfdrive Process Lagging: Reboot Your Device"), }, # Thrown when manager detects a service exited unexpectedly while driving @@ -819,41 +843,22 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, ET.NO_ENTRY: NoEntryAlert("Low Memory: Reboot Your Device"), }, - EventName.highCpuUsage: { - #ET.SOFT_DISABLE: soft_disable_alert("System Malfunction: Reboot Your Device"), - #ET.PERMANENT: NormalPermanentAlert("System Malfunction", "Reboot your Device"), - ET.NO_ENTRY: high_cpu_usage_alert, - }, - EventName.accFaulted: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Cruise Fault: Restart the Car"), ET.PERMANENT: NormalPermanentAlert("Cruise Fault: Restart the car to engage"), ET.NO_ENTRY: NoEntryAlert("Cruise Fault: Restart the Car"), }, + EventName.espActive: { + ET.SOFT_DISABLE: soft_disable_alert("Electronic Stability Control Active"), + ET.NO_ENTRY: NoEntryAlert("Electronic Stability Control Active"), + }, + EventName.controlsMismatch: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Controls Mismatch"), ET.NO_ENTRY: NoEntryAlert("Controls Mismatch"), }, - EventName.roadCameraError: { - ET.PERMANENT: NormalPermanentAlert("Camera CRC Error - Road", - duration=1., - creation_delay=30.), - }, - - EventName.wideRoadCameraError: { - ET.PERMANENT: NormalPermanentAlert("Camera CRC Error - Road Fisheye", - duration=1., - creation_delay=30.), - }, - - EventName.driverCameraError: { - ET.PERMANENT: NormalPermanentAlert("Camera CRC Error - Driver", - duration=1., - creation_delay=30.), - }, - # Sometimes the USB stack on the device can get into a bad state # causing the connection to the panda to be lost EventName.usbError: { @@ -936,22 +941,16 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, ET.NO_ENTRY: NoEntryAlert("Slow down to engage"), }, - EventName.lowSpeedLockout: { - ET.PERMANENT: NormalPermanentAlert("Cruise Fault: Restart the car to engage"), - ET.NO_ENTRY: NoEntryAlert("Cruise Fault: Restart the Car"), - }, - - EventName.lkasDisabled: { - ET.PERMANENT: NormalPermanentAlert("LKAS Disabled: Enable LKAS to engage"), - ET.NO_ENTRY: NoEntryAlert("LKAS Disabled"), - }, - EventName.vehicleSensorsInvalid: { ET.IMMEDIATE_DISABLE: ImmediateDisableAlert("Vehicle Sensors Invalid"), ET.PERMANENT: NormalPermanentAlert("Vehicle Sensors Calibrating", "Drive to Calibrate"), ET.NO_ENTRY: NoEntryAlert("Vehicle Sensors Calibrating"), }, + EventName.personalityChanged: { + ET.WARNING: personality_changed_alert, + }, + } @@ -970,7 +969,7 @@ def joystick_alert(CP: car.CarParams, CS: car.CarState, sm: messaging.SubMaster, for i, alerts in EVENTS.items(): for et, alert in alerts.items(): if callable(alert): - alert = alert(CP, CS, sm, False, 1) + alert = alert(CP, CS, sm, False, 1, log.LongitudinalPersonality.standard) alerts_by_type[et][alert.priority].append(event_names[i]) all_alerts: dict[str, list[tuple[Priority, list[str]]]] = {} diff --git a/selfdrive/selfdrived/selfdrived.py b/selfdrive/selfdrived/selfdrived.py new file mode 100755 index 000000000000000..d24939884d5798a --- /dev/null +++ b/selfdrive/selfdrived/selfdrived.py @@ -0,0 +1,497 @@ +#!/usr/bin/env python3 +import os +import time +import threading + +import cereal.messaging as messaging + +from cereal import car, log +from msgq.visionipc import VisionIpcClient, VisionStreamType +from panda import ALTERNATIVE_EXPERIENCE + + +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.common.gps import get_gps_location_service + +from openpilot.selfdrive.car.car_specific import CarSpecificEvents +from openpilot.selfdrive.selfdrived.events import Events, ET +from openpilot.selfdrive.selfdrived.state import StateMachine +from openpilot.selfdrive.selfdrived.alertmanager import AlertManager, set_offroad_alert +from openpilot.selfdrive.controls.lib.latcontrol import MIN_LATERAL_CONTROL_SPEED + +from openpilot.system.version import get_build_metadata + +REPLAY = "REPLAY" in os.environ +SIMULATION = "SIMULATION" in os.environ +TESTING_CLOSET = "TESTING_CLOSET" in os.environ +IGNORE_PROCESSES = {"loggerd", "encoderd", "statsd"} +LONGITUDINAL_PERSONALITY_MAP = {v: k for k, v in log.LongitudinalPersonality.schema.enumerants.items()} + +ThermalStatus = log.DeviceState.ThermalStatus +State = log.SelfdriveState.OpenpilotState +PandaType = log.PandaState.PandaType +LaneChangeState = log.LaneChangeState +LaneChangeDirection = log.LaneChangeDirection +EventName = log.OnroadEvent.EventName +ButtonType = car.CarState.ButtonEvent.Type +SafetyModel = car.CarParams.SafetyModel + +IGNORED_SAFETY_MODES = (SafetyModel.silent, SafetyModel.noOutput) + + +class SelfdriveD: + def __init__(self, CP=None): + self.params = Params() + + # Ensure the current branch is cached, otherwise the first cycle lags + build_metadata = get_build_metadata() + + if CP is None: + cloudlog.info("selfdrived is waiting for CarParams") + self.CP = messaging.log_from_bytes(self.params.get("CarParams", block=True), car.CarParams) + cloudlog.info("selfdrived got CarParams") + else: + self.CP = CP + + self.car_events = CarSpecificEvents(self.CP) + self.disengage_on_accelerator = not (self.CP.alternativeExperience & ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS) + + # Setup sockets + self.pm = messaging.PubMaster(['selfdriveState', 'onroadEvents']) + + self.gps_location_service = get_gps_location_service(self.params) + self.gps_packets = [self.gps_location_service] + self.sensor_packets = ["accelerometer", "gyroscope"] + self.camera_packets = ["roadCameraState", "driverCameraState", "wideRoadCameraState"] + + # TODO: de-couple selfdrived with card/conflate on carState without introducing controls mismatches + self.car_state_sock = messaging.sub_sock('carState', timeout=20) + + ignore = self.sensor_packets + self.gps_packets + ['alertDebug'] + if SIMULATION: + ignore += ['driverCameraState', 'managerState'] + if REPLAY: + # no vipc in replay will make them ignored anyways + ignore += ['roadCameraState', 'wideRoadCameraState'] + self.sm = messaging.SubMaster(['deviceState', 'pandaStates', 'peripheralState', 'modelV2', 'liveCalibration', + 'carOutput', 'driverMonitoringState', 'longitudinalPlan', 'livePose', + 'managerState', 'liveParameters', 'radarState', 'liveTorqueParameters', + 'controlsState', 'carControl', 'driverAssistance', 'alertDebug'] + \ + self.camera_packets + self.sensor_packets + self.gps_packets, + ignore_alive=ignore, ignore_avg_freq=ignore+['radarState',], + ignore_valid=ignore, frequency=int(1/DT_CTRL)) + + # read params + self.is_metric = self.params.get_bool("IsMetric") + self.is_ldw_enabled = self.params.get_bool("IsLdwEnabled") + + car_recognized = self.CP.carName != 'mock' + + # cleanup old params + if not self.CP.experimentalLongitudinalAvailable: + self.params.remove("ExperimentalLongitudinalEnabled") + if not self.CP.openpilotLongitudinalControl: + self.params.remove("ExperimentalMode") + + self.CS_prev = car.CarState.new_message() + self.AM = AlertManager() + self.events = Events() + + self.initialized = False + self.enabled = False + self.active = False + self.mismatch_counter = 0 + self.cruise_mismatch_counter = 0 + self.last_steering_pressed_frame = 0 + self.distance_traveled = 0 + self.last_functional_fan_frame = 0 + self.events_prev = [] + self.logged_comm_issue = None + self.not_running_prev = None + self.experimental_mode = False + self.personality = self.read_personality_param() + self.recalibrating_seen = False + self.state_machine = StateMachine() + self.rk = Ratekeeper(100, print_delay_threshold=None) + + # Determine startup event + self.startup_event = EventName.startup if build_metadata.openpilot.comma_remote and build_metadata.tested_channel else EventName.startupMaster + if not car_recognized: + self.startup_event = EventName.startupNoCar + elif car_recognized and self.CP.passive: + self.startup_event = EventName.startupNoControl + elif self.CP.secOcRequired and not self.CP.secOcKeyAvailable: + self.startup_event = EventName.startupNoSecOcKey + + if not car_recognized: + self.events.add(EventName.carUnrecognized, static=True) + set_offroad_alert("Offroad_CarUnrecognized", True) + elif self.CP.passive: + self.events.add(EventName.dashcamMode, static=True) + + def update_events(self, CS): + """Compute onroadEvents from carState""" + + self.events.clear() + + if self.sm['controlsState'].lateralControlState.which() == 'debugState': + self.events.add(EventName.joystickDebug) + self.startup_event = None + + if self.sm.recv_frame['alertDebug'] > 0: + self.events.add(EventName.longitudinalManeuver) + self.startup_event = None + + # Add startup event + if self.startup_event is not None: + self.events.add(self.startup_event) + self.startup_event = None + + # Don't add any more events if not initialized + if not self.initialized: + self.events.add(EventName.selfdriveInitializing) + return + + # no more events while in dashcam mode + if self.CP.passive: + return + + # Block resume if cruise never previously enabled + resume_pressed = any(be.type in (ButtonType.accelCruise, ButtonType.resumeCruise) for be in CS.buttonEvents) + if not self.CP.pcmCruise and CS.vCruise > 250 and resume_pressed: + self.events.add(EventName.resumeBlocked) + + if not self.CP.notCar: + self.events.add_from_msg(self.sm['driverMonitoringState'].events) + + # Add car events, ignore if CAN isn't valid + if CS.canValid: + car_events = self.car_events.update(CS, self.CS_prev, self.sm['carControl']).to_msg() + self.events.add_from_msg(car_events) + + if self.CP.notCar: + # wait for everything to init first + if self.sm.frame > int(5. / DT_CTRL) and self.initialized: + # body always wants to enable + self.events.add(EventName.pcmEnable) + + # Disable on rising edge of accelerator or brake. Also disable on brake when speed > 0 + if (CS.gasPressed and not self.CS_prev.gasPressed and self.disengage_on_accelerator) or \ + (CS.brakePressed and (not self.CS_prev.brakePressed or not CS.standstill)) or \ + (CS.regenBraking and (not self.CS_prev.regenBraking or not CS.standstill)): + self.events.add(EventName.pedalPressed) + + # Create events for temperature, disk space, and memory + if self.sm['deviceState'].thermalStatus >= ThermalStatus.red: + self.events.add(EventName.overheat) + if self.sm['deviceState'].freeSpacePercent < 7 and not SIMULATION: + self.events.add(EventName.outOfSpace) + if self.sm['deviceState'].memoryUsagePercent > 90 and not SIMULATION: + self.events.add(EventName.lowMemory) + + # Alert if fan isn't spinning for 5 seconds + if self.sm['peripheralState'].pandaType != log.PandaState.PandaType.unknown: + if self.sm['peripheralState'].fanSpeedRpm < 500 and self.sm['deviceState'].fanSpeedPercentDesired > 50: + # allow enough time for the fan controller in the panda to recover from stalls + if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 15.0: + self.events.add(EventName.fanMalfunction) + else: + self.last_functional_fan_frame = self.sm.frame + + # Handle calibration status + cal_status = self.sm['liveCalibration'].calStatus + if cal_status != log.LiveCalibrationData.Status.calibrated: + if cal_status == log.LiveCalibrationData.Status.uncalibrated: + self.events.add(EventName.calibrationIncomplete) + elif cal_status == log.LiveCalibrationData.Status.recalibrating: + if not self.recalibrating_seen: + set_offroad_alert("Offroad_Recalibration", True) + self.recalibrating_seen = True + self.events.add(EventName.calibrationRecalibrating) + else: + self.events.add(EventName.calibrationInvalid) + + # Lane departure warning + if self.is_ldw_enabled and self.sm.valid['driverAssistance']: + if self.sm['driverAssistance'].leftLaneDeparture or self.sm['driverAssistance'].rightLaneDeparture: + self.events.add(EventName.ldw) + + # Handle lane change + 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) + else: + if direction == LaneChangeDirection.left: + self.events.add(EventName.preLaneChangeLeft) + else: + self.events.add(EventName.preLaneChangeRight) + elif self.sm['modelV2'].meta.laneChangeState in (LaneChangeState.laneChangeStarting, + LaneChangeState.laneChangeFinishing): + self.events.add(EventName.laneChange) + + for i, pandaState in enumerate(self.sm['pandaStates']): + # All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput + if i < len(self.CP.safetyConfigs): + safety_mismatch = pandaState.safetyModel != self.CP.safetyConfigs[i].safetyModel or \ + pandaState.safetyParam != self.CP.safetyConfigs[i].safetyParam or \ + pandaState.alternativeExperience != self.CP.alternativeExperience + else: + safety_mismatch = pandaState.safetyModel not in IGNORED_SAFETY_MODES + + # safety mismatch allows some time for pandad 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: + self.events.add(EventName.relayMalfunction) + + # Handle HW and system malfunctions + # Order is very intentional here. Be careful when modifying this. + # All events here should at least have NO_ENTRY and SOFT_DISABLE. + 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.recv_frame['managerState'] and len(not_running): + if not_running != self.not_running_prev: + cloudlog.event("process_not_running", not_running=not_running, error=True) + self.not_running_prev = not_running + if self.sm.recv_frame['managerState'] and (not_running - IGNORE_PROCESSES): + self.events.add(EventName.processNotRunning) + else: + if not SIMULATION and not self.rk.lagging: + if not self.sm.all_alive(self.camera_packets): + self.events.add(EventName.cameraMalfunction) + elif not self.sm.all_freq_ok(self.camera_packets): + self.events.add(EventName.cameraFrameRate) + if not REPLAY and self.rk.lagging: + self.events.add(EventName.selfdrivedLagging) + if len(self.sm['radarState'].radarErrors) or ((not self.rk.lagging or REPLAY) and not self.sm.all_checks(['radarState'])): + self.events.add(EventName.radarFault) + if not self.sm.valid['pandaStates']: + self.events.add(EventName.usbError) + if CS.canTimeout: + self.events.add(EventName.canBusMissing) + elif not CS.canValid: + self.events.add(EventName.canError) + + # generic catch-all. ideally, a more specific event should be added above instead + 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() and no_system_errors: + if not self.sm.all_alive(): + self.events.add(EventName.commIssue) + elif not self.sm.all_freq_ok(): + self.events.add(EventName.commIssueAvgFreq) + else: + self.events.add(EventName.commIssue) + + logs = { + '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], + } + if logs != self.logged_comm_issue: + cloudlog.event("commIssue", error=True, **logs) + self.logged_comm_issue = logs + else: + self.logged_comm_issue = None + + if not self.CP.notCar: + if not self.sm['livePose'].posenetOK: + self.events.add(EventName.posenetInvalid) + if not self.sm['livePose'].inputsOK: + self.events.add(EventName.locationdTemporaryError) + if not self.sm['liveParameters'].valid and not TESTING_CLOSET and (not SIMULATION or REPLAY): + self.events.add(EventName.paramsdTemporaryError) + + # conservative HW alert. if the data or frequency are off, locationd will throw an error + 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: + # Check for mismatch between openpilot and car's PCM + cruise_mismatch = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) + self.cruise_mismatch_counter = self.cruise_mismatch_counter + 1 if cruise_mismatch else 0 + if self.cruise_mismatch_counter > int(6. / DT_CTRL): + self.events.add(EventName.cruiseMismatch) + + # Send a "steering required alert" if saturation count has reached the limit + if CS.steeringPressed: + self.last_steering_pressed_frame = self.sm.frame + recent_steer_pressed = (self.sm.frame - self.last_steering_pressed_frame)*DT_CTRL < 2.0 + controlstate = self.sm['controlsState'] + lac = getattr(controlstate.lateralControlState, controlstate.lateralControlState.which()) + if lac.active and not recent_steer_pressed and not self.CP.notCar: + clipped_speed = max(CS.vEgo, MIN_LATERAL_CONTROL_SPEED) + actual_lateral_accel = controlstate.curvature * (clipped_speed**2) + desired_lateral_accel = controlstate.desiredCurvature * (clipped_speed**2) + undershooting = abs(desired_lateral_accel) / abs(1e-3 + actual_lateral_accel) > 1.2 + turning = abs(desired_lateral_accel) > 1.0 + good_speed = CS.vEgo > 5 + if undershooting and turning and good_speed and lac.saturated: + self.events.add(EventName.steerSaturated) + + # Check for FCW + stock_long_is_braking = self.enabled and not self.CP.openpilotLongitudinalControl and CS.aEgo < -1.25 + model_fcw = self.sm['modelV2'].meta.hardBrakePredicted and not CS.brakePressed and not stock_long_is_braking + planner_fcw = self.sm['longitudinalPlan'].fcw and self.enabled + if (planner_fcw or model_fcw) and not self.CP.notCar: + self.events.add(EventName.fcw) + + # TODO: fix simulator + if not SIMULATION or REPLAY: + # Not show in first 1.5 km to allow for driving out of garage. This event shows after 5 minutes + gps_ok = self.sm.recv_frame[self.gps_location_service] > 0 and (self.sm.frame - self.sm.recv_frame[self.gps_location_service]) * DT_CTRL < 2.0 + if not gps_ok and self.sm['livePose'].inputsOK and (self.distance_traveled > 1500): + self.events.add(EventName.noGps) + if gps_ok: + self.distance_traveled = 0 + self.distance_traveled += abs(CS.vEgo) * DT_CTRL + + if self.sm['modelV2'].frameDropPerc > 20: + self.events.add(EventName.modeldLagging) + + # decrement personality on distance button press + if self.CP.openpilotLongitudinalControl: + if any(not be.pressed and be.type == ButtonType.gapAdjustCruise for be in CS.buttonEvents): + self.personality = (self.personality - 1) % 3 + self.params.put_nonblocking('LongitudinalPersonality', str(self.personality)) + self.events.add(EventName.personalityChanged) + + def data_sample(self): + car_state = messaging.recv_one(self.car_state_sock) + CS = car_state.carState if car_state else self.CS_prev + + 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 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: + self.sm.ignore_alive.append('roadCameraState') + self.sm.ignore_valid.append('roadCameraState') + if VisionStreamType.VISION_STREAM_WIDE_ROAD not in available_streams: + self.sm.ignore_alive.append('wideRoadCameraState') + self.sm.ignore_valid.append('wideRoadCameraState') + + if REPLAY and any(ps.controlsAllowed for ps in self.sm['pandaStates']): + self.state_machine.state = State.enabled + + self.initialized = True + cloudlog.event( + "selfdrived.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 selfdrived do not agree on controls_allowed + # we want to disengage openpilot. However the status from the panda goes through + # another socket other than the CAN messages and one can arrive earlier than the other. + # Therefore we allow a mismatch for two samples, then we trigger the disengagement. + if not self.enabled: + self.mismatch_counter = 0 + + # All pandas not in silent mode must have controlsAllowed when openpilot is enabled + if self.enabled and any(not ps.controlsAllowed for ps in self.sm['pandaStates'] + if ps.safetyModel not in IGNORED_SAFETY_MODES): + self.mismatch_counter += 1 + + return CS + + def update_alerts(self, CS): + clear_event_types = set() + if ET.WARNING not in self.state_machine.current_alert_types: + clear_event_types.add(ET.WARNING) + if self.enabled: + clear_event_types.add(ET.NO_ENTRY) + + pers = LONGITUDINAL_PERSONALITY_MAP[self.personality] + alerts = self.events.create_alerts(self.state_machine.current_alert_types, [self.CP, CS, self.sm, self.is_metric, + self.state_machine.soft_disable_timer, pers]) + self.AM.add_many(self.sm.frame, alerts) + self.AM.process_alerts(self.sm.frame, clear_event_types) + + def publish_selfdriveState(self, CS): + # selfdriveState + ss_msg = messaging.new_message('selfdriveState') + ss_msg.valid = True + ss = ss_msg.selfdriveState + ss.enabled = self.enabled + ss.active = self.active + ss.state = self.state_machine.state + ss.engageable = not self.events.contains(ET.NO_ENTRY) + ss.experimentalMode = self.experimental_mode + ss.personality = self.personality + + ss.alertText1 = self.AM.current_alert.alert_text_1 + ss.alertText2 = self.AM.current_alert.alert_text_2 + ss.alertSize = self.AM.current_alert.alert_size + ss.alertStatus = self.AM.current_alert.alert_status + ss.alertType = self.AM.current_alert.alert_type + ss.alertSound = self.AM.current_alert.audible_alert + + self.pm.send('selfdriveState', ss_msg) + + # 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('onroadEvents', len(self.events)) + ce_send.valid = True + ce_send.onroadEvents = self.events.to_msg() + self.pm.send('onroadEvents', ce_send) + self.events_prev = self.events.names.copy() + + def step(self): + CS = self.data_sample() + self.update_events(CS) + if not self.CP.passive and self.initialized: + self.enabled, self.active = self.state_machine.update(self.events) + self.update_alerts(CS) + + self.publish_selfdriveState(CS) + + self.CS_prev = CS + + def read_personality_param(self): + try: + return int(self.params.get('LongitudinalPersonality')) + except (ValueError, TypeError): + return log.LongitudinalPersonality.standard + + 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 + self.personality = self.read_personality_param() + time.sleep(0.1) + + def run(self): + e = threading.Event() + t = threading.Thread(target=self.params_thread, args=(e, )) + try: + t.start() + while True: + self.step() + self.rk.monitor_time() + finally: + e.set() + t.join() + + +def main(): + config_realtime_process(4, Priority.CTRL_HIGH) + s = SelfdriveD() + s.run() + +if __name__ == "__main__": + main() diff --git a/selfdrive/selfdrived/state.py b/selfdrive/selfdrived/state.py new file mode 100644 index 000000000000000..073ddb56eb9dc6f --- /dev/null +++ b/selfdrive/selfdrived/state.py @@ -0,0 +1,98 @@ +from cereal import log +from openpilot.selfdrive.selfdrived.events import Events, ET +from openpilot.common.realtime import DT_CTRL + +State = log.SelfdriveState.OpenpilotState + +SOFT_DISABLE_TIME = 3 # seconds +ACTIVE_STATES = (State.enabled, State.softDisabling, State.overriding) +ENABLED_STATES = (State.preEnabled, *ACTIVE_STATES) + +class StateMachine: + def __init__(self): + self.current_alert_types = [ET.PERMANENT] + self.state = State.disabled + self.soft_disable_timer = 0 + + def update(self, events: Events): + # decrement the soft disable timer at every step, as it's reset on + # entrance in SOFT_DISABLING state + self.soft_disable_timer = max(0, self.soft_disable_timer - 1) + + self.current_alert_types = [ET.PERMANENT] + + # ENABLED, SOFT DISABLING, PRE ENABLING, OVERRIDING + if self.state != State.disabled: + # user and immediate disable always have priority in a non-disabled state + if events.contains(ET.USER_DISABLE): + self.state = State.disabled + self.current_alert_types.append(ET.USER_DISABLE) + + elif events.contains(ET.IMMEDIATE_DISABLE): + self.state = State.disabled + self.current_alert_types.append(ET.IMMEDIATE_DISABLE) + + else: + # ENABLED + if self.state == State.enabled: + if events.contains(ET.SOFT_DISABLE): + self.state = State.softDisabling + self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) + self.current_alert_types.append(ET.SOFT_DISABLE) + + elif events.contains(ET.OVERRIDE_LATERAL) or events.contains(ET.OVERRIDE_LONGITUDINAL): + self.state = State.overriding + self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] + + # SOFT DISABLING + elif self.state == State.softDisabling: + if not events.contains(ET.SOFT_DISABLE): + # no more soft disabling condition, so go back to ENABLED + self.state = State.enabled + + elif self.soft_disable_timer > 0: + self.current_alert_types.append(ET.SOFT_DISABLE) + + elif self.soft_disable_timer <= 0: + self.state = State.disabled + + # PRE ENABLING + elif self.state == State.preEnabled: + if not events.contains(ET.PRE_ENABLE): + self.state = State.enabled + else: + self.current_alert_types.append(ET.PRE_ENABLE) + + # OVERRIDING + elif self.state == State.overriding: + if events.contains(ET.SOFT_DISABLE): + self.state = State.softDisabling + self.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) + self.current_alert_types.append(ET.SOFT_DISABLE) + elif not (events.contains(ET.OVERRIDE_LATERAL) or events.contains(ET.OVERRIDE_LONGITUDINAL)): + self.state = State.enabled + else: + self.current_alert_types += [ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL] + + # DISABLED + elif self.state == State.disabled: + if events.contains(ET.ENABLE): + if events.contains(ET.NO_ENTRY): + self.current_alert_types.append(ET.NO_ENTRY) + + else: + if events.contains(ET.PRE_ENABLE): + self.state = State.preEnabled + elif events.contains(ET.OVERRIDE_LATERAL) or events.contains(ET.OVERRIDE_LONGITUDINAL): + self.state = State.overriding + else: + self.state = State.enabled + self.current_alert_types.append(ET.ENABLE) + + # Check if openpilot is engaged and actuators are enabled + enabled = self.state in ENABLED_STATES + active = self.state in ACTIVE_STATES + if active: + self.current_alert_types.append(ET.WARNING) + return enabled, active + diff --git a/selfdrive/selfdrived/tests/test_alertmanager.py b/selfdrive/selfdrived/tests/test_alertmanager.py new file mode 100644 index 000000000000000..030b7d4515c2f28 --- /dev/null +++ b/selfdrive/selfdrived/tests/test_alertmanager.py @@ -0,0 +1,58 @@ +import random + +from openpilot.selfdrive.selfdrived.events import Alert, EmptyAlert, EVENTS +from openpilot.selfdrive.selfdrived.alertmanager import AlertManager + + +class TestAlertManager: + + def test_duration(self): + """ + Enforce that an alert lasts for max(alert duration, duration the alert is added) + """ + for duration in range(1, 100): + alert = None + while not isinstance(alert, Alert): + event = random.choice([e for e in EVENTS.values() if len(e)]) + alert = random.choice(list(event.values())) + + alert.duration = duration + + # check two cases: + # - alert is added to AM for <= the alert's duration + # - alert is added to AM for > alert's duration + for greater in (True, False): + if greater: + add_duration = duration + random.randint(1, 10) + else: + add_duration = random.randint(1, duration) + show_duration = max(duration, add_duration) + + AM = AlertManager() + for frame in range(duration+10): + if frame < add_duration: + AM.add_many(frame, [alert, ]) + AM.process_alerts(frame, set()) + + shown = AM.current_alert != EmptyAlert + should_show = frame <= show_duration + assert shown == should_show, f"{frame=} {add_duration=} {duration=}" + + # check one case: + # - if alert is re-added to AM before it ends the duration is extended + if duration > 1: + AM = AlertManager() + show_duration = duration * 2 + for frame in range(duration * 2 + 10): + if frame == 0: + AM.add_many(frame, [alert, ]) + + if frame == duration: + # add alert one frame before it ends + assert AM.current_alert == alert + AM.add_many(frame, [alert, ]) + AM.process_alerts(frame, set()) + + shown = AM.current_alert != EmptyAlert + should_show = frame <= show_duration + assert shown == should_show, f"{frame=} {duration=}" diff --git a/selfdrive/controls/tests/test_alerts.py b/selfdrive/selfdrived/tests/test_alerts.py similarity index 89% rename from selfdrive/controls/tests/test_alerts.py rename to selfdrive/selfdrived/tests/test_alerts.py index 38dc04594999909..f6a0e365fce070a 100644 --- a/selfdrive/controls/tests/test_alerts.py +++ b/selfdrive/selfdrived/tests/test_alerts.py @@ -8,13 +8,13 @@ from cereal.messaging import SubMaster from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.events import Alert, EVENTS, ET -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.events import Alert, EVENTS, ET +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS -AlertSize = log.ControlsState.AlertSize +AlertSize = log.SelfdriveState.AlertSize -OFFROAD_ALERTS_PATH = os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json") +OFFROAD_ALERTS_PATH = os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json") # TODO: add callback alerts ALERTS = [] @@ -33,12 +33,12 @@ def setup_class(cls): # Create fake objects for callback cls.CS = car.CarState.new_message() cls.CP = car.CarParams.new_message() - cfg = [c for c in CONFIGS if c.proc_name == 'controlsd'][0] + cfg = [c for c in CONFIGS if c.proc_name == 'selfdrived'][0] cls.sm = SubMaster(cfg.pubs) def test_events_defined(self): # Ensure all events in capnp schema are defined in events.py - events = car.CarEvent.EventName.schema.enumerants + events = log.OnroadEvent.EventName.schema.enumerants for name, e in events.items(): if not name.endswith("DEPRECATED"): @@ -63,7 +63,7 @@ def test_alert_text_length(self): for alert in ALERTS: if not isinstance(alert, Alert): - alert = alert(self.CP, self.CS, self.sm, metric=False, soft_disable_time=100) + alert = alert(self.CP, self.CS, self.sm, metric=False, soft_disable_time=100, personality=log.LongitudinalPersonality.standard) # for full size alerts, both text fields wrap the text, # so it's unlikely that they would go past the max width diff --git a/selfdrive/selfdrived/tests/test_state_machine.py b/selfdrive/selfdrived/tests/test_state_machine.py new file mode 100644 index 000000000000000..b720f48f1ec02b8 --- /dev/null +++ b/selfdrive/selfdrived/tests/test_state_machine.py @@ -0,0 +1,92 @@ +from cereal import log +from openpilot.common.realtime import DT_CTRL +from openpilot.selfdrive.selfdrived.state import StateMachine, SOFT_DISABLE_TIME +from openpilot.selfdrive.selfdrived.events import Events, ET, EVENTS, NormalPermanentAlert + +State = log.SelfdriveState.OpenpilotState + +# The event types that maintain the current state +MAINTAIN_STATES = {State.enabled: (None,), State.disabled: (None,), State.softDisabling: (ET.SOFT_DISABLE,), + State.preEnabled: (ET.PRE_ENABLE,), State.overriding: (ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL)} +ALL_STATES = tuple(State.schema.enumerants.values()) +# The event types checked in DISABLED section of state machine +ENABLE_EVENT_TYPES = (ET.ENABLE, ET.PRE_ENABLE, ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL) + + +def make_event(event_types): + event = {} + for ev in event_types: + event[ev] = NormalPermanentAlert("alert") + EVENTS[0] = event + return 0 + + +class TestStateMachine: + def setup_method(self): + self.events = Events() + self.state_machine = StateMachine() + self.state_machine.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) + + def test_immediate_disable(self): + for state in ALL_STATES: + for et in MAINTAIN_STATES[state]: + self.events.add(make_event([et, ET.IMMEDIATE_DISABLE])) + self.state_machine.state = state + self.state_machine.update(self.events) + assert State.disabled == self.state_machine.state + self.events.clear() + + def test_user_disable(self): + for state in ALL_STATES: + for et in MAINTAIN_STATES[state]: + self.events.add(make_event([et, ET.USER_DISABLE])) + self.state_machine.state = state + self.state_machine.update(self.events) + assert State.disabled == self.state_machine.state + self.events.clear() + + def test_soft_disable(self): + for state in ALL_STATES: + if state == State.preEnabled: # preEnabled considers NO_ENTRY instead + continue + for et in MAINTAIN_STATES[state]: + self.events.add(make_event([et, ET.SOFT_DISABLE])) + self.state_machine.state = state + self.state_machine.update(self.events) + assert self.state_machine.state == State.disabled if state == State.disabled else State.softDisabling + self.events.clear() + + def test_soft_disable_timer(self): + self.state_machine.state = State.enabled + self.events.add(make_event([ET.SOFT_DISABLE])) + self.state_machine.update(self.events) + for _ in range(int(SOFT_DISABLE_TIME / DT_CTRL)): + assert self.state_machine.state == State.softDisabling + self.state_machine.update(self.events) + + assert self.state_machine.state == State.disabled + + def test_no_entry(self): + # Make sure noEntry keeps us disabled + for et in ENABLE_EVENT_TYPES: + self.events.add(make_event([ET.NO_ENTRY, et])) + self.state_machine.update(self.events) + assert self.state_machine.state == State.disabled + self.events.clear() + + def test_no_entry_pre_enable(self): + # preEnabled with noEntry event + self.state_machine.state = State.preEnabled + self.events.add(make_event([ET.NO_ENTRY, ET.PRE_ENABLE])) + self.state_machine.update(self.events) + assert self.state_machine.state == State.preEnabled + + def test_maintain_states(self): + # Given current state's event type, we should maintain state + for state in ALL_STATES: + for et in MAINTAIN_STATES[state]: + self.state_machine.state = state + self.events.add(make_event([et])) + self.state_machine.update(self.events) + assert self.state_machine.state == state + self.events.clear() diff --git a/selfdrive/test/ci_shell.sh b/selfdrive/test/ci_shell.sh index a5ff714b2d3cdd8..76f0a9f78c9e057 100755 --- a/selfdrive/test/ci_shell.sh +++ b/selfdrive/test/ci_shell.sh @@ -1,4 +1,5 @@ -#!/bin/bash -e +#!/usr/bin/env bash +set -e DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" OP_ROOT="$DIR/../../" diff --git a/selfdrive/test/cpp_harness.py b/selfdrive/test/cpp_harness.py index f9d3e681a54ffa8..f9f425102b85151 100755 --- a/selfdrive/test/cpp_harness.py +++ b/selfdrive/test/cpp_harness.py @@ -4,8 +4,7 @@ from openpilot.common.prefix import OpenpilotPrefix - with OpenpilotPrefix(): ret = subprocess.call(sys.argv[1:]) -exit(ret) +sys.exit(ret) diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py index 6c8495cc3b55678..301f99dd568afe6 100644 --- a/selfdrive/test/longitudinal_maneuvers/maneuver.py +++ b/selfdrive/test/longitudinal_maneuvers/maneuver.py @@ -12,11 +12,14 @@ def __init__(self, title, duration, **kwargs): self.breakpoints = kwargs.get("breakpoints", [0.0, duration]) self.speed_lead_values = kwargs.get("speed_lead_values", [0.0 for i in range(len(self.breakpoints))]) self.prob_lead_values = kwargs.get("prob_lead_values", [1.0 for i in range(len(self.breakpoints))]) + self.prob_throttle_values = kwargs.get("prob_throttle_values", [1.0 for i in range(len(self.breakpoints))]) self.cruise_values = kwargs.get("cruise_values", [50.0 for i in range(len(self.breakpoints))]) + self.pitch_values = kwargs.get("pitch_values", [0.0 for i in range(len(self.breakpoints))]) self.only_lead2 = kwargs.get("only_lead2", False) self.only_radar = kwargs.get("only_radar", False) self.ensure_start = kwargs.get("ensure_start", False) + self.ensure_slowdown = kwargs.get("ensure_slowdown", False) self.enabled = kwargs.get("enabled", True) self.e2e = kwargs.get("e2e", False) self.personality = kwargs.get("personality", 0) @@ -42,9 +45,11 @@ def evaluate(self): logs = [] while plant.current_time < self.duration: speed_lead = np.interp(plant.current_time, self.breakpoints, self.speed_lead_values) - prob = np.interp(plant.current_time, self.breakpoints, self.prob_lead_values) + prob_lead = np.interp(plant.current_time, self.breakpoints, self.prob_lead_values) cruise = np.interp(plant.current_time, self.breakpoints, self.cruise_values) - log = plant.step(speed_lead, prob, cruise) + pitch = np.interp(plant.current_time, self.breakpoints, self.pitch_values) + prob_throttle = np.interp(plant.current_time, self.breakpoints, self.prob_throttle_values) + log = plant.step(speed_lead, prob_lead, cruise, pitch, prob_throttle) d_rel = log['distance_lead'] - log['distance'] if self.lead_relevancy else 200. v_rel = speed_lead - log['speed'] if self.lead_relevancy else 0. @@ -57,13 +62,18 @@ def evaluate(self): speed_lead, log['acceleration']])) - if d_rel < .4 and (self.only_radar or prob > 0.5): + if d_rel < .4 and (self.only_radar or prob_lead > 0.5): print("Crashed!!!!") valid = False if self.ensure_start and log['v_rel'] > 0 and log['speeds'][-1] <= 0.1: print('LongitudinalPlanner not starting!') valid = False + + if self.ensure_slowdown and log['speed'] > 5.5: + print('LongitudinalPlanner not slowing down!') + valid = False + if self.force_decel and log['speed'] > 1e-1 and log['acceleration'] > -0.04: print('Not stopping with force decel') valid = False diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index daf7cec32b8e750..c08ac6d36925398 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -21,6 +21,7 @@ def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0, if not Plant.messaging_initialized: Plant.radar = messaging.pub_sock('radarState') Plant.controls_state = messaging.pub_sock('controlsState') + Plant.selfdrive_state = messaging.pub_sock('selfdriveState') Plant.car_state = messaging.pub_sock('carState') Plant.plan = messaging.sub_sock('longitudinalPlan') Plant.messaging_initialized = True @@ -47,8 +48,8 @@ def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0, time.sleep(0.1) self.sm = messaging.SubMaster(['longitudinalPlan']) - from openpilot.selfdrive.car.honda.values import CAR - from openpilot.selfdrive.car.honda.interface import CarInterface + from opendbc.car.honda.values import CAR + from opendbc.car.honda.interface import CarInterface self.planner = LongitudinalPlanner(CarInterface.get_non_essential_params(CAR.HONDA_CIVIC), init_v=self.speed) @@ -56,12 +57,15 @@ def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0, def current_time(self): return float(self.rk.frame) / self.rate - def step(self, v_lead=0.0, prob=1.0, v_cruise=50.): + def step(self, v_lead=0.0, prob_lead=1.0, v_cruise=50., pitch=0.0, prob_throttle=1.0): # ******** publish a fake model going straight and fake calibration ******** # note that this is worst case for MPC, since model will delay long mpc by one time step radar = messaging.new_message('radarState') control = messaging.new_message('controlsState') + ss = messaging.new_message('selfdriveState') car_state = messaging.new_message('carState') + lp = messaging.new_message('liveParameters') + car_control = messaging.new_message('carControl') model = messaging.new_message('modelV2') a_lead = (v_lead - self.v_lead_prev)/self.ts self.v_lead_prev = v_lead @@ -71,14 +75,14 @@ def step(self, v_lead=0.0, prob=1.0, v_cruise=50.): v_rel = v_lead - self.speed if self.only_radar: status = True - elif prob > .5: + elif prob_lead > .5: status = True else: status = False else: d_rel = 200. v_rel = 0. - prob = 0.0 + prob_lead = 0.0 status = False lead = log.RadarState.LeadData.new_message() @@ -92,7 +96,7 @@ def step(self, v_lead=0.0, prob=1.0, v_cruise=50.): # TODO use real radard logic for this lead.aLeadTau = float(_LEAD_ACCEL_TAU) lead.status = status - lead.modelProb = float(prob) + lead.modelProb = float(prob_lead) if not self.only_lead2: radar.radarState.leadOne = lead radar.radarState.leadTwo = lead @@ -105,23 +109,29 @@ def step(self, v_lead=0.0, prob=1.0, v_cruise=50.): model.modelV2.position = position velocity = log.XYZTData.new_message() velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(ModelConstants.T_IDXS)] + velocity.x[0] = float(self.speed) # always start at current speed model.modelV2.velocity = velocity acceleration = log.XYZTData.new_message() acceleration.x = [float(x) for x in np.zeros_like(ModelConstants.T_IDXS)] model.modelV2.acceleration = acceleration + model.modelV2.meta.disengagePredictions.gasPressProbs = [float(prob_throttle) for _ in range(6)] control.controlsState.longControlState = LongCtrlState.pid if self.enabled else LongCtrlState.off - control.controlsState.vCruise = float(v_cruise * 3.6) - control.controlsState.experimentalMode = self.e2e - control.controlsState.personality = self.personality + ss.selfdriveState.experimentalMode = self.e2e + ss.selfdriveState.personality = self.personality control.controlsState.forceDecel = self.force_decel car_state.carState.vEgo = float(self.speed) car_state.carState.standstill = self.speed < 0.01 + car_state.carState.vCruise = float(v_cruise * 3.6) + car_control.carControl.orientationNED = [0., float(pitch), 0.] # ******** get controlsState messages for plotting *** sm = {'radarState': radar.radarState, 'carState': car_state.carState, + 'carControl': car_control.carControl, 'controlsState': control.controlsState, + 'selfdriveState': ss.selfdriveState, + 'liveParameters': lp.liveParameters, 'modelV2': model.modelV2} self.planner.update(sm) self.speed = self.planner.v_desired_filter.x diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py index 62a95babeb3c053..4bc1ebba8fc95f6 100644 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py @@ -82,6 +82,32 @@ def create_maneuvers(kwargs): breakpoints=[0.0, 2., 2.01], **kwargs, ), + Maneuver( + "approach stopped car at 20m/s, with prob_throttle_values and pitch = -0.1", + duration=30., + initial_speed=20., + lead_relevancy=True, + initial_distance_lead=120., + speed_lead_values=[0.0, 0., 0.], + prob_throttle_values=[1., 0., 0.], + cruise_values=[20., 20., 20.], + pitch_values=[0., -0.1, -0.1], + breakpoints=[0.0, 2., 2.01], + **kwargs, + ), + Maneuver( + "approach stopped car at 20m/s, with prob_throttle_values and pitch = +0.1", + duration=30., + initial_speed=20., + lead_relevancy=True, + initial_distance_lead=120., + speed_lead_values=[0.0, 0., 0.], + prob_throttle_values=[1., 0., 0.], + cruise_values=[20., 20., 20.], + pitch_values=[0., 0.1, 0.1], + breakpoints=[0.0, 2., 2.01], + **kwargs, + ), Maneuver( "approach slower cut-in car at 20m/s", duration=20., @@ -125,6 +151,20 @@ def create_maneuvers(kwargs): **kwargs, ), ] + if not kwargs['e2e']: + # allow_throttle won't trigger with e2e + maneuvers.append(Maneuver( + "slow to 5m/s with allow_throttle = False and pitch = +0.1", + duration=30., + initial_speed=20., + lead_relevancy=False, + prob_throttle_values=[1., 0., 0.], + cruise_values=[20., 20., 20.], + pitch_values=[0., 0.1, 0.1], + breakpoints=[0.0, 2., 2.01], + ensure_slowdown=True, + **kwargs, + )) if not kwargs['force_decel']: # controls relies on planner commanding to move for stock-ACC resume spamming maneuvers.append(Maneuver( diff --git a/selfdrive/test/process_replay/README.md b/selfdrive/test/process_replay/README.md index 008a9010100756c..381e4dcb7fc131f 100644 --- a/selfdrive/test/process_replay/README.md +++ b/selfdrive/test/process_replay/README.md @@ -30,7 +30,7 @@ optional arguments: --whitelist-cars WHITELIST_CARS Whitelist given cars from the test (e.g. HONDA) --blacklist-procs BLACKLIST_PROCS Blacklist given processes from the test (e.g. controlsd) --blacklist-cars BLACKLIST_CARS Blacklist given cars from the test (e.g. HONDA) - --ignore-fields IGNORE_FIELDS Extra fields or msgs to ignore (e.g. carState.events) + --ignore-fields IGNORE_FIELDS Extra fields or msgs to ignore (e.g. driverMonitoringState.events) --ignore-msgs IGNORE_MSGS Msgs to ignore (e.g. onroadEvents) --update-refs Updates reference logs using current commit --upload-only Skips testing processes and uploads logs from previous test run diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py index 673f3b484c740e5..13d51a636f1b9ea 100755 --- a/selfdrive/test/process_replay/compare_logs.py +++ b/selfdrive/test/process_replay/compare_logs.py @@ -141,7 +141,7 @@ def format_diff(results, log_paths, ref_commit): if __name__ == "__main__": log1 = list(LogReader(sys.argv[1])) log2 = list(LogReader(sys.argv[2])) - ignore_fields = sys.argv[3:] or ["logMonoTime", "controlsState.startMonoTime", "controlsState.cumLagMs"] + ignore_fields = sys.argv[3:] or ["logMonoTime"] results = {"segment": {"proc": compare_logs(log1, log2, ignore_fields)}} log_paths = {"segment": {"proc": {"ref": sys.argv[1], "new": sys.argv[2]}}} diff_short, diff_long, failed = format_diff(results, log_paths, None) diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py index 0715fcf7b43f1e8..5376f91aee427fb 100644 --- a/selfdrive/test/process_replay/migration.py +++ b/selfdrive/test/process_replay/migration.py @@ -1,106 +1,285 @@ from collections import defaultdict - -from cereal import messaging -from openpilot.selfdrive.car.fingerprints import MIGRATION +from collections.abc import Callable +import functools +import capnp + +from cereal import messaging, car, log +from opendbc.car.fingerprints import MIGRATION +from opendbc.car.toyota.values import EPS_SCALE +from opendbc.car.ford.values import CAR as FORD, FordFlags +from openpilot.selfdrive.modeld.constants import ModelConstants +from openpilot.selfdrive.modeld.fill_model_msg import fill_xyz_poly, fill_lane_line_meta from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index -from openpilot.selfdrive.car.toyota.values import EPS_SCALE +from openpilot.selfdrive.controls.lib.longitudinal_planner import get_accel_from_plan from openpilot.system.manager.process_config import managed_processes +from openpilot.tools.lib.logreader import LogIterable from panda import Panda - -# TODO: message migration should happen in-place -def migrate_all(lr, old_logtime=False, manager_states=False, panda_states=False, camera_states=False): - msgs = migrate_sensorEvents(lr, old_logtime) - msgs = migrate_carParams(msgs, old_logtime) - msgs = migrate_gpsLocation(msgs) - msgs = migrate_deviceState(msgs) - msgs = migrate_carOutput(msgs) +MessageWithIndex = tuple[int, capnp.lib.capnp._DynamicStructReader] +MigrationOps = tuple[list[tuple[int, capnp.lib.capnp._DynamicStructReader]], list[capnp.lib.capnp._DynamicStructReader], list[int]] +MigrationFunc = Callable[[list[MessageWithIndex]], MigrationOps] + + +## rules for migration functions +## 1. must use the decorator @migration(inputs=[...], product="...") and MigrationFunc signature +## 2. it only gets the messages that are in the inputs list +## 3. product is the message type created by the migration function, and the function will be skipped if product type already exists in lr +## 4. it must return a list of operations to be applied to the logreader (replace, add, delete) +## 5. all migration functions must be independent of each other +def migrate_all(lr: LogIterable, manager_states: bool = False, panda_states: bool = False, camera_states: bool = False): + migrations = [ + migrate_sensorEvents, + migrate_carParams, + migrate_gpsLocation, + migrate_deviceState, + migrate_carOutput, + migrate_controlsState, + migrate_carState, + migrate_liveLocationKalman, + migrate_liveTracks, + migrate_driverAssistance, + migrate_drivingModelData, + migrate_onroadEvents, + migrate_driverMonitoringState, + migrate_longitudinalPlan, + ] if manager_states: - msgs = migrate_managerState(msgs) + migrations.append(migrate_managerState) if panda_states: - msgs = migrate_pandaStates(msgs) - msgs = migrate_peripheralState(msgs) + migrations.extend([migrate_pandaStates, migrate_peripheralState]) if camera_states: - msgs = migrate_cameraStates(msgs) + migrations.append(migrate_cameraStates) - return msgs + return migrate(lr, migrations) -def migrate_managerState(lr): - all_msgs = [] - for msg in lr: - if msg.which() != "managerState": - all_msgs.append(msg) +def migrate(lr: LogIterable, migration_funcs: list[MigrationFunc]): + lr = list(lr) + grouped = defaultdict(list) + for i, msg in enumerate(lr): + grouped[msg.which()].append(i) + + replace_ops, add_ops, del_ops = [], [], [] + for migration in migration_funcs: + assert hasattr(migration, "inputs") and hasattr(migration, "product"), "Migration functions must use @migration decorator" + if migration.product in grouped: # skip if product already exists continue + sorted_indices = sorted(ii for i in migration.inputs for ii in grouped[i]) + msg_gen = [(i, lr[i]) for i in sorted_indices] + r_ops, a_ops, d_ops = migration(msg_gen) + replace_ops.extend(r_ops) + add_ops.extend(a_ops) + del_ops.extend(d_ops) + + for index, msg in replace_ops: + lr[index] = msg + for index in sorted(del_ops, reverse=True): + del lr[index] + for msg in add_ops: + lr.append(msg) + lr = sorted(lr, key=lambda x: x.logMonoTime) + + return lr + + +def migration(inputs: list[str], product: str|None=None): + def decorator(func): + @functools.wraps(func) + def wrapper(*args, **kwargs): + return func(*args, **kwargs) + wrapper.inputs = inputs + wrapper.product = product + return wrapper + return decorator + + +@migration(inputs=["longitudinalPlan", "carParams"]) +def migrate_longitudinalPlan(msgs): + ops = [] + + needs_migration = all(msg.longitudinalPlan.aTarget == 0.0 for _, msg in msgs if msg.which() == 'longitudinalPlan') + CP = next((m.carParams for _, m in msgs if m.which() == 'carParams'), None) + if not needs_migration or CP is None: + return [], [], [] + + for index, msg in msgs: + if msg.which() != 'longitudinalPlan': + continue new_msg = msg.as_builder() - new_msg.managerState.processes = [{'name': name, 'running': True} for name in managed_processes] - all_msgs.append(new_msg.as_reader()) + new_msg.longitudinalPlan.aTarget, new_msg.longitudinalPlan.shouldStop = get_accel_from_plan(CP, msg.longitudinalPlan.speeds, msg.longitudinalPlan.accels) + ops.append((index, new_msg.as_reader())) + return ops, [], [] + + +@migration(inputs=["longitudinalPlan"], product="driverAssistance") +def migrate_driverAssistance(msgs): + add_ops = [] + for _, msg in msgs: + new_msg = messaging.new_message('driverAssistance', valid=True, logMonoTime=msg.logMonoTime) + add_ops.append(new_msg.as_reader()) + return [], add_ops, [] + + +@migration(inputs=["modelV2"], product="drivingModelData") +def migrate_drivingModelData(msgs): + add_ops = [] + for _, msg in msgs: + dmd = messaging.new_message('drivingModelData', valid=msg.valid, logMonoTime=msg.logMonoTime) + for field in ["frameId", "frameIdExtra", "frameDropPerc", "modelExecutionTime", "action"]: + setattr(dmd.drivingModelData, field, getattr(msg.modelV2, field)) + for meta_field in ["laneChangeState", "laneChangeState"]: + setattr(dmd.drivingModelData.meta, meta_field, getattr(msg.modelV2.meta, meta_field)) + if len(msg.modelV2.laneLines) and len(msg.modelV2.laneLineProbs): + fill_lane_line_meta(dmd.drivingModelData.laneLineMeta, msg.modelV2.laneLines, msg.modelV2.laneLineProbs) + if all(len(a) for a in [msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z]): + fill_xyz_poly(dmd.drivingModelData.path, ModelConstants.POLY_PATH_DEGREE, msg.modelV2.position.x, msg.modelV2.position.y, msg.modelV2.position.z) + add_ops.append( dmd.as_reader()) + return [], add_ops, [] + + +@migration(inputs=["liveTracksDEPRECATED"], product="liveTracks") +def migrate_liveTracks(msgs): + ops = [] + for index, msg in msgs: + new_msg = messaging.new_message('liveTracks') + new_msg.valid = msg.valid + new_msg.logMonoTime = msg.logMonoTime - return all_msgs + pts = [] + for track in msg.liveTracksDEPRECATED: + pt = car.RadarData.RadarPoint() + pt.trackId = track.trackId + + pt.dRel = track.dRel + pt.yRel = track.yRel + pt.vRel = track.vRel + pt.aRel = track.aRel + pt.measured = True + pts.append(pt) + + new_msg.liveTracks.points = pts + ops.append((index, new_msg.as_reader())) + return ops, [], [] + + +@migration(inputs=["liveLocationKalmanDEPRECATED"], product="livePose") +def migrate_liveLocationKalman(msgs): + nans = [float('nan')] * 3 + ops = [] + for index, msg in msgs: + m = messaging.new_message('livePose') + m.valid = msg.valid + m.logMonoTime = msg.logMonoTime + for field in ["orientationNED", "velocityDevice", "accelerationDevice", "angularVelocityDevice"]: + lp_field, llk_field = getattr(m.livePose, field), getattr(msg.liveLocationKalmanDEPRECATED, field) + lp_field.x, lp_field.y, lp_field.z = llk_field.value or nans + lp_field.xStd, lp_field.yStd, lp_field.zStd = llk_field.std or nans + lp_field.valid = llk_field.valid + for flag in ["inputsOK", "posenetOK", "sensorsOK"]: + setattr(m.livePose, flag, getattr(msg.liveLocationKalmanDEPRECATED, flag)) + ops.append((index, m.as_reader())) + return ops, [], [] + + +@migration(inputs=["controlsState"], product="selfdriveState") +def migrate_controlsState(msgs): + add_ops = [] + for _, msg in msgs: + m = messaging.new_message('selfdriveState') + m.valid = msg.valid + m.logMonoTime = msg.logMonoTime + ss = m.selfdriveState + for field in ("enabled", "active", "state", "engageable", "alertText1", "alertText2", + "alertStatus", "alertSize", "alertType", "experimentalMode", + "personality"): + setattr(ss, field, getattr(msg.controlsState, field+"DEPRECATED")) + add_ops.append(m.as_reader()) + return [], add_ops, [] + + +@migration(inputs=["carState", "controlsState"]) +def migrate_carState(msgs): + ops = [] + last_cs = None + for index, msg in msgs: + if msg.which() == 'controlsState': + last_cs = msg + elif msg.which() == 'carState' and last_cs is not None: + if last_cs.controlsState.vCruiseDEPRECATED - msg.carState.vCruise > 0.1: + msg = msg.as_builder() + msg.carState.vCruise = last_cs.controlsState.vCruiseDEPRECATED + msg.carState.vCruiseCluster = last_cs.controlsState.vCruiseClusterDEPRECATED + ops.append((index, msg.as_reader())) + return ops, [], [] + + +@migration(inputs=["managerState"]) +def migrate_managerState(msgs): + ops = [] + for index, msg in msgs: + new_msg = msg.as_builder() + new_msg.managerState.processes = [{'name': name, 'running': True} for name in managed_processes] + ops.append((index, new_msg.as_reader())) + return ops, [], [] -def migrate_gpsLocation(lr): - all_msgs = [] - for msg in lr: - if msg.which() in ('gpsLocation', 'gpsLocationExternal'): - new_msg = msg.as_builder() - g = getattr(new_msg, new_msg.which()) - # hasFix is a newer field - if not g.hasFix and g.flags == 1: - g.hasFix = True - all_msgs.append(new_msg.as_reader()) - else: - all_msgs.append(msg) - return all_msgs +@migration(inputs=["gpsLocation", "gpsLocationExternal"]) +def migrate_gpsLocation(msgs): + ops = [] + for index, msg in msgs: + new_msg = msg.as_builder() + g = getattr(new_msg, new_msg.which()) + # hasFix is a newer field + if not g.hasFix and g.flags == 1: + g.hasFix = True + ops.append((index, new_msg.as_reader())) + return ops, [], [] -def migrate_deviceState(lr): - all_msgs = [] +@migration(inputs=["deviceState", "initData"]) +def migrate_deviceState(msgs): + ops = [] dt = None - for msg in lr: + for i, msg in msgs: if msg.which() == 'initData': dt = msg.initData.deviceType if msg.which() == 'deviceState': n = msg.as_builder() n.deviceState.deviceType = dt - all_msgs.append(n.as_reader()) - else: - all_msgs.append(msg) - return all_msgs - + ops.append((i, n.as_reader())) + return ops, [], [] -def migrate_carOutput(lr): - # migration needed only for routes before carOutput - if any(msg.which() == 'carOutput' for msg in lr): - return lr - all_msgs = [] - for msg in lr: - if msg.which() == 'carControl': - co = messaging.new_message('carOutput') - co.valid = msg.valid - co.logMonoTime = msg.logMonoTime - co.carOutput.actuatorsOutput = msg.carControl.actuatorsOutputDEPRECATED - all_msgs.append(co.as_reader()) - all_msgs.append(msg) - return all_msgs +@migration(inputs=["carControl"], product="carOutput") +def migrate_carOutput(msgs): + add_ops = [] + for _, msg in msgs: + co = messaging.new_message('carOutput') + co.valid = msg.valid + co.logMonoTime = msg.logMonoTime + co.carOutput.actuatorsOutput = msg.carControl.actuatorsOutputDEPRECATED + add_ops.append(co.as_reader()) + return [], add_ops, [] -def migrate_pandaStates(lr): - all_msgs = [] +@migration(inputs=["pandaStates", "pandaStateDEPRECATED", "carParams"]) +def migrate_pandaStates(msgs): # TODO: safety param migration should be handled automatically safety_param_migration = { "TOYOTA_PRIUS": EPS_SCALE["TOYOTA_PRIUS"] | Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL, "TOYOTA_RAV4": EPS_SCALE["TOYOTA_RAV4"] | Panda.FLAG_TOYOTA_ALT_BRAKE, "KIA_EV6": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_CANFD_HDA2, } + # TODO: get new Ford route + safety_param_migration |= {car: Panda.FLAG_FORD_LONG_CONTROL for car in (set(FORD) - FORD.with_flags(FordFlags.CANFD))} - # Migrate safety param base on carState - CP = next((m.carParams for m in lr if m.which() == 'carParams'), None) + # Migrate safety param base on carParams + CP = next((m.carParams for _, m in msgs if m.which() == 'carParams'), None) assert CP is not None, "carParams message not found" - if CP.carFingerprint in safety_param_migration: - safety_param = safety_param_migration[CP.carFingerprint] + fingerprint = MIGRATION.get(CP.carFingerprint, CP.carFingerprint) + if fingerprint in safety_param_migration: + safety_param = safety_param_migration[fingerprint] elif len(CP.safetyConfigs): safety_param = CP.safetyConfigs[0].safetyParam if CP.safetyConfigs[0].safetyParamDEPRECATED != 0: @@ -108,49 +287,45 @@ def migrate_pandaStates(lr): else: safety_param = CP.safetyParamDEPRECATED - for msg in lr: + ops = [] + for index, msg in msgs: if msg.which() == 'pandaStateDEPRECATED': new_msg = messaging.new_message('pandaStates', 1) new_msg.valid = msg.valid new_msg.logMonoTime = msg.logMonoTime new_msg.pandaStates[0] = msg.pandaStateDEPRECATED new_msg.pandaStates[0].safetyParam = safety_param - all_msgs.append(new_msg.as_reader()) + ops.append((index, new_msg.as_reader())) elif msg.which() == 'pandaStates': new_msg = msg.as_builder() new_msg.pandaStates[-1].safetyParam = safety_param - all_msgs.append(new_msg.as_reader()) - else: - all_msgs.append(msg) + ops.append((index, new_msg.as_reader())) + return ops, [], [] - return all_msgs +@migration(inputs=["pandaStates", "pandaStateDEPRECATED"], product="peripheralState") +def migrate_peripheralState(msgs): + add_ops = [] -def migrate_peripheralState(lr): - if any(msg.which() == "peripheralState" for msg in lr): - return lr - - all_msg = [] - for msg in lr: - all_msg.append(msg) - if msg.which() not in ["pandaStates", "pandaStateDEPRECATED"]: + which = "pandaStates" if any(msg.which() == "pandaStates" for _, msg in msgs) else "pandaStateDEPRECATED" + for _, msg in msgs: + if msg.which() != which: continue - new_msg = messaging.new_message("peripheralState") new_msg.valid = msg.valid new_msg.logMonoTime = msg.logMonoTime - all_msg.append(new_msg.as_reader()) + add_ops.append(new_msg.as_reader()) + return [], add_ops, [] - return all_msg - -def migrate_cameraStates(lr): - all_msgs = [] +@migration(inputs=["roadEncodeIdx", "wideRoadEncodeIdx", "driverEncodeIdx", "roadCameraState", "wideRoadCameraState", "driverCameraState"]) +def migrate_cameraStates(msgs): + add_ops, del_ops = [], [] frame_to_encode_id = defaultdict(dict) # just for encodeId fallback mechanism min_frame_id = defaultdict(lambda: float('inf')) - for msg in lr: + for _, msg in msgs: if msg.which() not in ["roadEncodeIdx", "wideRoadEncodeIdx", "driverEncodeIdx"]: continue @@ -160,9 +335,8 @@ def migrate_cameraStates(lr): assert encode_index.segmentId < 1200, f"Encoder index segmentId greater that 1200: {msg.which()} {encode_index.segmentId}" frame_to_encode_id[meta.camera_state][encode_index.frameId] = encode_index.segmentId - for msg in lr: + for index, msg in msgs: if msg.which() not in ["roadCameraState", "wideRoadCameraState", "driverCameraState"]: - all_msgs.append(msg) continue camera_state = getattr(msg, msg.which()) @@ -172,6 +346,7 @@ def migrate_cameraStates(lr): if encode_id is None: print(f"Missing encoded frame for camera feed {msg.which()} with frameId: {camera_state.frameId}") if len(frame_to_encode_id[msg.which()]) != 0: + del_ops.append(index) continue # fallback mechanism for logs without encodeIdx (e.g. logs from before 2022 with dcamera recording disabled) @@ -192,34 +367,27 @@ def migrate_cameraStates(lr): new_msg.logMonoTime = msg.logMonoTime new_msg.valid = msg.valid - all_msgs.append(new_msg.as_reader()) - - return all_msgs + del_ops.append(index) + add_ops.append(new_msg.as_reader()) + return [], add_ops, del_ops -def migrate_carParams(lr, old_logtime=False): - all_msgs = [] - for msg in lr: - if msg.which() == 'carParams': - CP = msg.as_builder() - CP.carParams.carFingerprint = MIGRATION.get(CP.carParams.carFingerprint, CP.carParams.carFingerprint) - for car_fw in CP.carParams.carFw: - car_fw.brand = CP.carParams.carName - if old_logtime: - CP.logMonoTime = msg.logMonoTime - msg = CP.as_reader() - all_msgs.append(msg) +@migration(inputs=["carParams"]) +def migrate_carParams(msgs): + ops = [] + for index, msg in msgs: + CP = msg.as_builder() + CP.carParams.carFingerprint = MIGRATION.get(CP.carParams.carFingerprint, CP.carParams.carFingerprint) + for car_fw in CP.carParams.carFw: + car_fw.brand = CP.carParams.carName + ops.append((index, CP.as_reader())) + return ops, [], [] - return all_msgs - - -def migrate_sensorEvents(lr, old_logtime=False): - all_msgs = [] - for msg in lr: - if msg.which() != 'sensorEventsDEPRECATED': - all_msgs.append(msg) - continue +@migration(inputs=["sensorEventsDEPRECATED"], product="sensorEvents") +def migrate_sensorEvents(msgs): + add_ops, del_ops = [], [] + for index, msg in msgs: # migrate to split sensor events for evt in msg.sensorEventsDEPRECATED: # build new message for each sensor type @@ -237,18 +405,46 @@ def migrate_sensorEvents(lr, old_logtime=False): m = messaging.new_message(sensor_service) m.valid = True - if old_logtime: - m.logMonoTime = msg.logMonoTime + m.logMonoTime = msg.logMonoTime m_dat = getattr(m, sensor_service) m_dat.version = evt.version m_dat.sensor = evt.sensor m_dat.type = evt.type m_dat.source = evt.source - if old_logtime: - m_dat.timestamp = evt.timestamp + m_dat.timestamp = evt.timestamp setattr(m_dat, evt.which(), getattr(evt, evt.which())) - all_msgs.append(m.as_reader()) + add_ops.append(m.as_reader()) + del_ops.append(index) + return [], add_ops, del_ops + + +@migration(inputs=["onroadEventsDEPRECATED"], product="onroadEvents") +def migrate_onroadEvents(msgs): + ops = [] + for index, msg in msgs: + new_msg = messaging.new_message('onroadEvents', len(msg.onroadEventsDEPRECATED)) + new_msg.valid = msg.valid + new_msg.logMonoTime = msg.logMonoTime + + # dict converts name enum into string representation + new_msg.onroadEvents = [log.OnroadEvent(**event.to_dict()) for event in msg.onroadEventsDEPRECATED if + not str(event.name).endswith('DEPRECATED')] + ops.append((index, new_msg.as_reader())) + + return ops, [], [] + + +@migration(inputs=["driverMonitoringState"]) +def migrate_driverMonitoringState(msgs): + ops = [] + for index, msg in msgs: + msg = msg.as_builder() + # dict converts name enum into string representation + msg.driverMonitoringState.events = [log.OnroadEvent(**event.to_dict()) for event in + msg.driverMonitoringState.eventsDEPRECATED if + not str(event.name).endswith('DEPRECATED')] + ops.append((index, msg.as_reader())) - return all_msgs + return ops, [], [] diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py index cba2edfd58b5a8f..c6720cc60183c59 100755 --- a/selfdrive/test/process_replay/model_replay.py +++ b/selfdrive/test/process_replay/model_replay.py @@ -3,15 +3,19 @@ import sys from collections import defaultdict from typing import Any +import tempfile +from itertools import zip_longest + +import matplotlib.pyplot as plt from openpilot.common.git import get_commit from openpilot.system.hardware import PC -from openpilot.tools.lib.openpilotci import BASE_URL, get_url +from openpilot.tools.lib.openpilotci import get_url from openpilot.selfdrive.test.process_replay.compare_logs import compare_logs, format_diff from openpilot.selfdrive.test.process_replay.process_replay import get_process_config, replay_process from openpilot.tools.lib.framereader import FrameReader -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.helpers import save_log +from openpilot.tools.lib.logreader import LogReader, save_log +from openpilot.tools.lib.github_utils import GithubUtils TEST_ROUTE = "2f4452b03ccb98f0|2022-12-03--13-45-30" SEGMENT = 6 @@ -20,10 +24,93 @@ NO_MODEL = "NO_MODEL" in os.environ SEND_EXTRA_INPUTS = bool(int(os.getenv("SEND_EXTRA_INPUTS", "0"))) +DATA_TOKEN = os.getenv("CI_ARTIFACTS_TOKEN","") +API_TOKEN = os.getenv("GITHUB_COMMENTS_TOKEN","") +MODEL_REPLAY_BUCKET="model_replay_master" +GITHUB = GithubUtils(API_TOKEN, DATA_TOKEN) + + +def get_log_fn(test_route, ref="master"): + return f"{test_route}_model_tici_{ref}.bz2" + +def plot(proposed, master, title, tmp): + proposed = list(proposed) + master = list(master) + fig, ax = plt.subplots() + ax.plot(proposed, label='PROPOSED') + ax.plot(master, label='MASTER') + plt.legend(loc='best') + plt.title(title) + plt.savefig(f'{tmp}/{title}.png') + return (title + '.png', proposed == master) + +def get_event(logs, event): + return (getattr(m, m.which()) for m in filter(lambda m: m.which() == event, logs)) + +def zl(array, fill): + return zip_longest(array, [], fillvalue=fill) + +def generate_report(proposed, master, tmp, commit): + ModelV2_Plots = zl([ + (lambda x: x.velocity.x[0], "velocity.x"), + (lambda x: x.action.desiredCurvature, "desiredCurvature"), + (lambda x: x.leadsV3[0].x[0], "leadsV3.x"), + (lambda x: x.laneLines[1].y[0], "laneLines.y"), + (lambda x: x.meta.disengagePredictions.gasPressProbs[1], "gasPressProbs") + ], "modelV2") + DriverStateV2_Plots = zl([ + (lambda x: x.wheelOnRightProb, "wheelOnRightProb"), + (lambda x: x.leftDriverData.faceProb, "leftDriverData.faceProb"), + (lambda x: x.leftDriverData.faceOrientation[0], "leftDriverData.faceOrientation0"), + (lambda x: x.leftDriverData.leftBlinkProb, "leftDriverData.leftBlinkProb"), + (lambda x: x.leftDriverData.notReadyProb[0], "leftDriverData.notReadyProb0"), + (lambda x: x.rightDriverData.faceProb, "rightDriverData.faceProb"), + ], "driverStateV2") + + return [plot(map(v[0], get_event(proposed, event)), \ + map(v[0], get_event(master, event)), f"{v[1]}_{commit[:7]}", tmp) \ + for v,event in ([*ModelV2_Plots] + [*DriverStateV2_Plots])] + +def create_table(title, files, link, open_table=False): + if not files: + return "" + table = [f'
{title}
'] + for i,f in enumerate(files): + if not (i % 2): + table.append("") + table.append(f'') + if (i % 2): + table.append("") + table.append("
") + table = "".join(table) + return table + +def comment_replay_report(proposed, master, full_logs): + with tempfile.TemporaryDirectory() as tmp: + PR_BRANCH = os.getenv("GIT_BRANCH","") + DATA_BUCKET = f"model_replay_{PR_BRANCH}" + + try: + GITHUB.get_pr_number(PR_BRANCH) + except Exception: + print("No PR associated with this branch. Skipping report.") + return + + commit = get_commit() + files = generate_report(proposed, master, tmp, commit) + + GITHUB.upload_files(DATA_BUCKET, [(x[0], tmp + '/' + x[0]) for x in files]) -def get_log_fn(ref_commit, test_route): - return f"{test_route}_model_tici_{ref_commit}.bz2" + log_name = get_log_fn(TEST_ROUTE, commit) + save_log(log_name, full_logs) + GITHUB.upload_file(DATA_BUCKET, os.path.basename(log_name), log_name) + diff_files = [x for x in files if not x[1]] + link = GITHUB.get_bucket_link(DATA_BUCKET) + diff_plots = create_table("Model Replay Differences", diff_files, link, open_table=True) + all_plots = create_table("All Model Replay Plots", files, link) + comment = f"ref for commit {commit}: {link}/{log_name}" + diff_plots + all_plots + GITHUB.comment_on_pr(comment, PR_BRANCH) def trim_logs_to_max_frames(logs, max_frames, frs_types, include_all_types): all_msgs = [] @@ -69,43 +156,17 @@ def model_replay(lr, frs): if __name__ == "__main__": - update = "--update" in sys.argv + update = "--update" in sys.argv or (os.getenv("GIT_BRANCH", "") == 'master') replay_dir = os.path.dirname(os.path.abspath(__file__)) - ref_commit_fn = os.path.join(replay_dir, "model_replay_ref_commit") # load logs - lr = list(LogReader(get_url(TEST_ROUTE, SEGMENT))) + lr = list(LogReader(get_url(TEST_ROUTE, SEGMENT, "rlog.bz2"))) frs = { - 'roadCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="fcamera"), readahead=True), - 'driverCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="dcamera"), readahead=True), - 'wideRoadCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="ecamera"), readahead=True) + 'roadCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, "fcamera.hevc"), readahead=True), + 'driverCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, "dcamera.hevc"), readahead=True), + 'wideRoadCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, "ecamera.hevc"), readahead=True) } - # Update tile refs - if update: - import urllib - import requests - import threading - import http.server - from openpilot.tools.lib.openpilotci import upload_bytes - os.environ['MAPS_HOST'] = 'http://localhost:5000' - - class HTTPRequestHandler(http.server.BaseHTTPRequestHandler): - def do_GET(self): - assert len(self.path) > 10 # Sanity check on path length - r = requests.get(f'https://api.mapbox.com{self.path}', timeout=30) - upload_bytes(r.content, urllib.parse.urlparse(self.path).path.lstrip('/')) - self.send_response(r.status_code) - self.send_header('Content-type','text/html') - self.end_headers() - self.wfile.write(r.content) - - server = http.server.HTTPServer(("127.0.0.1", 5000), HTTPRequestHandler) - thread = threading.Thread(None, server.serve_forever, daemon=True) - thread.start() - else: - os.environ['MAPS_HOST'] = BASE_URL.rstrip('/') - log_msgs = [] # run replays if not NO_MODEL: @@ -114,44 +175,57 @@ def do_GET(self): # get diff failed = False if not update: - with open(ref_commit_fn) as f: - ref_commit = f.read().strip() - log_fn = get_log_fn(ref_commit, TEST_ROUTE) + log_fn = get_log_fn(TEST_ROUTE) try: - all_logs = list(LogReader(BASE_URL + log_fn)) + all_logs = list(LogReader(GITHUB.get_file_url(MODEL_REPLAY_BUCKET, log_fn))) cmp_log = [] - # logs are ordered based on type: modelV2, driverStateV2 + # logs are ordered based on type: modelV2, drivingModelData, driverStateV2 if not NO_MODEL: - model_start_index = next(i for i, m in enumerate(all_logs) if m.which() in ("modelV2", "cameraOdometry")) - cmp_log += all_logs[model_start_index:model_start_index + MAX_FRAMES*2] + model_start_index = next(i for i, m in enumerate(all_logs) if m.which() in ("modelV2", "drivingModelData", "cameraOdometry")) + cmp_log += all_logs[model_start_index:model_start_index + MAX_FRAMES*3] dmon_start_index = next(i for i, m in enumerate(all_logs) if m.which() == "driverStateV2") cmp_log += all_logs[dmon_start_index:dmon_start_index + MAX_FRAMES] ignore = [ 'logMonoTime', + 'drivingModelData.frameDropPerc', + 'drivingModelData.modelExecutionTime', 'modelV2.frameDropPerc', 'modelV2.modelExecutionTime', 'driverStateV2.modelExecutionTime', - 'driverStateV2.dspExecutionTime' + 'driverStateV2.gpuExecutionTime' ] if PC: - ignore += [ - 'modelV2.laneLines.0.t', - 'modelV2.laneLines.1.t', - 'modelV2.laneLines.2.t', - 'modelV2.laneLines.3.t', - 'modelV2.roadEdges.0.t', - 'modelV2.roadEdges.1.t', - ] - # TODO this tolerance is absurdly large - tolerance = 2.0 if PC else None + # TODO We ignore whole bunch so we can compare important stuff + # like posenet with reasonable tolerance + ignore += ['modelV2.acceleration.x', + 'modelV2.position.x', + 'modelV2.position.xStd', + 'modelV2.position.y', + 'modelV2.position.yStd', + 'modelV2.position.z', + 'modelV2.position.zStd', + 'drivingModelData.path.xCoefficients',] + for i in range(3): + for field in ('x', 'y', 'v', 'a'): + ignore.append(f'modelV2.leadsV3.{i}.{field}') + ignore.append(f'modelV2.leadsV3.{i}.{field}Std') + for i in range(4): + for field in ('x', 'y', 'z', 't'): + ignore.append(f'modelV2.laneLines.{i}.{field}') + for i in range(2): + for field in ('x', 'y', 'z', 't'): + ignore.append(f'modelV2.roadEdges.{i}.{field}') + tolerance = .3 if PC else None results: Any = {TEST_ROUTE: {}} - log_paths: Any = {TEST_ROUTE: {"models": {'ref': BASE_URL + log_fn, 'new': log_fn}}} + log_paths: Any = {TEST_ROUTE: {"models": {'ref': log_fn, 'new': log_fn}}} results[TEST_ROUTE]["models"] = compare_logs(cmp_log, log_msgs, tolerance=tolerance, ignore_fields=ignore) - diff_short, diff_long, failed = format_diff(results, log_paths, ref_commit) + diff_short, diff_long, failed = format_diff(results, log_paths, 'master') if "CI" in os.environ: + comment_replay_report(log_msgs, cmp_log, log_msgs) + failed = False print(diff_long) print('-------------\n'*5) print(diff_short) @@ -162,22 +236,13 @@ def do_GET(self): failed = True # upload new refs - if (update or failed) and not PC: - from openpilot.tools.lib.openpilotci import upload_file - + if update and not PC: print("Uploading new refs") - - new_commit = get_commit() - log_fn = get_log_fn(new_commit, TEST_ROUTE) + log_fn = get_log_fn(TEST_ROUTE) save_log(log_fn, log_msgs) try: - upload_file(log_fn, os.path.basename(log_fn)) + GITHUB.upload_file(MODEL_REPLAY_BUCKET, os.path.basename(log_fn), log_fn) except Exception as e: print("failed to upload", e) - with open(ref_commit_fn, 'w') as f: - f.write(str(new_commit)) - - print("\n\nNew ref commit: ", new_commit) - sys.exit(int(failed)) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit deleted file mode 100644 index 87f1adfadad7667..000000000000000 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ /dev/null @@ -1 +0,0 @@ -73eb11111fb6407fa307c3f2bdd3331f2514c707 diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 739efcb985a75b7..448dc6896d17cd4 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -17,12 +17,13 @@ from cereal import car from cereal.services import SERVICE_LIST from msgq.visionipc import VisionIpcServer, get_endpoint_name as vipc_get_endpoint_name +from opendbc.car.car_helpers import get_car, interfaces from openpilot.common.params import Params from openpilot.common.prefix import OpenpilotPrefix from openpilot.common.timeout import Timeout from openpilot.common.realtime import DT_CTRL from panda.python import ALTERNATIVE_EXPERIENCE -from openpilot.selfdrive.car.car_helpers import get_car, interfaces +from openpilot.selfdrive.car.card import can_comm_callbacks from openpilot.system.manager.process_config import managed_processes from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state, available_streams from openpilot.selfdrive.test.process_replay.migration import migrate_all @@ -211,7 +212,7 @@ def _setup_vision_ipc(self, all_msgs: LogIterable, frs: dict[str, Any]): for meta in streams_metas: if meta.camera_state in self.cfg.vision_pubs: frame_size = (frs[meta.camera_state].w, frs[meta.camera_state].h) - vipc_server.create_buffers(meta.stream, 2, False, *frame_size) + vipc_server.create_buffers(meta.stream, 2, *frame_size) vipc_server.start_listener() self.vipc_server = vipc_server @@ -335,36 +336,43 @@ def card_fingerprint_callback(rc, pm, msgs, fingerprint): m = canmsgs.pop(0) rc.send_sync(pm, "can", m.as_builder().to_bytes()) - rc.wait_for_next_recv(False) + rc.wait_for_next_recv(True) def get_car_params_callback(rc, pm, msgs, fingerprint): params = Params() if fingerprint: - CarInterface, _, _ = interfaces[fingerprint] + CarInterface, _, _, _ = interfaces[fingerprint] CP = CarInterface.get_non_essential_params(fingerprint) else: can = DummySocket() sendcan = DummySocket() canmsgs = [msg for msg in msgs if msg.which() == "can"] - has_cached_cp = params.get("CarParamsCache") is not None + cached_params_raw = params.get("CarParamsCache") + has_cached_cp = cached_params_raw is not None assert len(canmsgs) != 0, "CAN messages are required for fingerprinting" assert os.environ.get("SKIP_FW_QUERY", False) or has_cached_cp, \ "CarParamsCache is required for fingerprinting. Make sure to keep carParams msgs in the logs." for m in canmsgs[:300]: can.send(m.as_builder().to_bytes()) - _, CP = get_car(can, sendcan, Params().get_bool("ExperimentalLongitudinalEnabled")) + can_callbacks = can_comm_callbacks(can, sendcan) + + cached_params = None + if has_cached_cp: + with car.CarParams.from_bytes(cached_params_raw) as _cached_params: + cached_params = _cached_params + + CP = get_car(*can_callbacks, lambda obd: None, Params().get_bool("ExperimentalLongitudinalEnabled"), cached_params=cached_params).CP if not params.get_bool("DisengageOnAccelerator"): CP.alternativeExperience |= ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS params.put("CarParams", CP.to_bytes()) - return CP -def controlsd_rcv_callback(msg, cfg, frame): +def selfdrived_rcv_callback(msg, cfg, frame): return (frame - 1) == 0 or msg.which() == 'carState' @@ -390,7 +398,7 @@ def calibration_rcv_callback(msg, cfg, frame): def torqued_rcv_callback(msg, cfg, frame): # should_recv always true to increment frame - return (frame - 1) == 0 or msg.which() == 'liveLocationKalman' + return (frame - 1) == 0 or msg.which() == 'livePose' def dmonitoringmodeld_rcv_callback(msg, cfg, frame): @@ -443,22 +451,7 @@ def __call__(self, msg, cfg, frame): return bool(len(resp_sockets)) -def controlsd_config_callback(params, cfg, lr): - controlsState = None - initialized = False - for msg in lr: - if msg.which() == "controlsState": - controlsState = msg.controlsState - if initialized: - break - elif msg.which() == "onroadEvents": - initialized = car.CarEvent.EventName.controlsInitializing not in [e.name for e in msg.onroadEvents] - - assert controlsState is not None and initialized, "controlsState never initialized" - params.put("ReplayControlsState", controlsState.as_builder().to_bytes()) - - -def locationd_config_pubsub_callback(params, cfg, lr): +def selfdrived_config_callback(params, cfg, lr): ublox = params.get_bool("UbloxAvailable") sub_keys = ({"gpsLocation", } if ublox else {"gpsLocationExternal", }) @@ -467,25 +460,37 @@ def locationd_config_pubsub_callback(params, cfg, lr): CONFIGS = [ ProcessConfig( - proc_name="controlsd", + proc_name="selfdrived", pubs=[ "carState", "deviceState", "pandaStates", "peripheralState", "liveCalibration", "driverMonitoringState", - "longitudinalPlan", "liveLocationKalman", "liveParameters", "radarState", + "longitudinalPlan", "livePose", "liveParameters", "radarState", "modelV2", "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", - "testJoystick", "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput" + "liveTorqueParameters", "accelerometer", "gyroscope", "carOutput", + "gpsLocationExternal", "gpsLocation", "controlsState", "carControl", "driverAssistance", "alertDebug", ], - subs=["controlsState", "carControl", "onroadEvents"], - ignore=["logMonoTime", "controlsState.startMonoTime", "controlsState.cumLagMs"], - config_callback=controlsd_config_callback, + subs=["selfdriveState", "onroadEvents"], + ignore=["logMonoTime"], + config_callback=selfdrived_config_callback, init_callback=get_car_params_callback, - should_recv_callback=controlsd_rcv_callback, + should_recv_callback=selfdrived_rcv_callback, tolerance=NUMPY_TOLERANCE, processing_time=0.004, ), + ProcessConfig( + proc_name="controlsd", + pubs=["liveParameters", "liveTorqueParameters", "modelV2", "selfdriveState", + "liveCalibration", "livePose", "longitudinalPlan", "carState", "carOutput", + "driverMonitoringState", "onroadEvents", "driverAssistance"], + subs=["carControl", "controlsState"], + ignore=["logMonoTime", ], + init_callback=get_car_params_callback, + should_recv_callback=MessageBasedRcvCallback("selfdriveState"), + tolerance=NUMPY_TOLERANCE, + ), ProcessConfig( proc_name="card", pubs=["pandaStates", "carControl", "onroadEvents", "can"], - subs=["sendcan", "carState", "carParams", "carOutput"], + subs=["sendcan", "carState", "carParams", "carOutput", "liveTracks"], ignore=["logMonoTime", "carState.cumLagMs"], init_callback=card_fingerprint_callback, should_recv_callback=card_rcv_callback, @@ -495,17 +500,16 @@ def locationd_config_pubsub_callback(params, cfg, lr): ), ProcessConfig( proc_name="radard", - pubs=["can", "carState", "modelV2"], - subs=["radarState", "liveTracks"], - ignore=["logMonoTime", "radarState.cumLagMs"], + pubs=["liveTracks", "carState", "modelV2"], + subs=["radarState"], + ignore=["logMonoTime"], init_callback=get_car_params_callback, - should_recv_callback=MessageBasedRcvCallback("can"), - main_pub="can", + should_recv_callback=FrequencyBasedRcvCallback("modelV2"), ), ProcessConfig( proc_name="plannerd", - pubs=["modelV2", "carControl", "carState", "controlsState", "radarState"], - subs=["longitudinalPlan", "uiPlan"], + pubs=["modelV2", "carControl", "carState", "controlsState", "liveParameters", "radarState", "selfdriveState"], + subs=["longitudinalPlan", "driverAssistance"], ignore=["logMonoTime", "longitudinalPlan.processingDelay", "longitudinalPlan.solverExecutionTime"], init_callback=get_car_params_callback, should_recv_callback=FrequencyBasedRcvCallback("modelV2"), @@ -520,7 +524,7 @@ def locationd_config_pubsub_callback(params, cfg, lr): ), ProcessConfig( proc_name="dmonitoringd", - pubs=["driverStateV2", "liveCalibration", "carState", "modelV2", "controlsState"], + pubs=["driverStateV2", "liveCalibration", "carState", "modelV2", "selfdriveState"], subs=["driverMonitoringState"], ignore=["logMonoTime"], should_recv_callback=FrequencyBasedRcvCallback("driverStateV2"), @@ -529,21 +533,21 @@ def locationd_config_pubsub_callback(params, cfg, lr): ProcessConfig( proc_name="locationd", pubs=[ - "cameraOdometry", "accelerometer", "gyroscope", "gpsLocationExternal", - "liveCalibration", "carState", "gpsLocation" + "cameraOdometry", "accelerometer", "gyroscope", "liveCalibration", "carState" ], - subs=["liveLocationKalman"], + subs=["livePose"], ignore=["logMonoTime"], - config_callback=locationd_config_pubsub_callback, + should_recv_callback=MessageBasedRcvCallback("cameraOdometry"), tolerance=NUMPY_TOLERANCE, + unlocked_pubs=["accelerometer", "gyroscope"], ), ProcessConfig( proc_name="paramsd", - pubs=["liveLocationKalman", "carState"], + pubs=["livePose", "liveCalibration", "carState"], subs=["liveParameters"], ignore=["logMonoTime"], init_callback=get_car_params_callback, - should_recv_callback=FrequencyBasedRcvCallback("liveLocationKalman"), + should_recv_callback=FrequencyBasedRcvCallback("livePose"), tolerance=NUMPY_TOLERANCE, processing_time=0.004, ), @@ -555,7 +559,7 @@ def locationd_config_pubsub_callback(params, cfg, lr): ), ProcessConfig( proc_name="torqued", - pubs=["liveLocationKalman", "carState", "carControl", "carOutput"], + pubs=["livePose", "liveCalibration", "carState", "carControl", "carOutput"], subs=["liveTorqueParameters"], ignore=["logMonoTime"], init_callback=get_car_params_callback, @@ -564,9 +568,9 @@ def locationd_config_pubsub_callback(params, cfg, lr): ), ProcessConfig( proc_name="modeld", - pubs=["deviceState", "roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState"], - subs=["modelV2", "cameraOdometry"], - ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime"], + pubs=["deviceState", "roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState", "carState"], + subs=["modelV2", "drivingModelData", "cameraOdometry"], + ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime", "drivingModelData.frameDropPerc", "drivingModelData.modelExecutionTime"], should_recv_callback=ModeldCameraSyncRcvCallback(), tolerance=NUMPY_TOLERANCE, processing_time=0.020, @@ -580,7 +584,7 @@ def locationd_config_pubsub_callback(params, cfg, lr): proc_name="dmonitoringmodeld", pubs=["liveCalibration", "driverCameraState"], subs=["driverStateV2"], - ignore=["logMonoTime", "driverStateV2.modelExecutionTime", "driverStateV2.dspExecutionTime"], + ignore=["logMonoTime", "driverStateV2.modelExecutionTime", "driverStateV2.gpuExecutionTime"], should_recv_callback=dmonitoringmodeld_rcv_callback, tolerance=NUMPY_TOLERANCE, processing_time=0.020, @@ -654,7 +658,7 @@ def replay_process( else: cfgs = [cfg] - all_msgs = migrate_all(lr, old_logtime=True, + all_msgs = migrate_all(lr, manager_states=True, panda_states=any("pandaStates" in cfg.pubs for cfg in cfgs), camera_states=any(len(cfg.vision_pubs) != 0 for cfg in cfgs)) @@ -808,8 +812,8 @@ def check_openpilot_enabled(msgs: LogIterable) -> bool: if msg.which() == "carParams": if msg.carParams.notCar: return True - elif msg.which() == "controlsState": - if msg.controlsState.active: + elif msg.which() == "selfdriveState": + if msg.selfdriveState.active: cur_enabled_count += 1 else: cur_enabled_count = 0 @@ -819,11 +823,15 @@ def check_openpilot_enabled(msgs: LogIterable) -> bool: def check_most_messages_valid(msgs: LogIterable, threshold: float = 0.9) -> bool: + relevant_services = {sock for cfg in CONFIGS for sock in cfg.subs} msgs_counts = Counter(msg.which() for msg in msgs) msgs_valid_counts = Counter(msg.which() for msg in msgs if msg.valid) most_valid_for_service = {} for msg_type in msgs_counts.keys(): + if msg_type not in relevant_services: + continue + valid_share = msgs_valid_counts.get(msg_type, 0) / msgs_counts[msg_type] ok = valid_share >= threshold if not ok: diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index 70178b8ea366ced..c779902d6bdd71d 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -e536df5586a71b22baa789dc584d7eab67f1fbbb +2fc2e865ab77fd8145feab86d454f2111c5d9871 diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py index bf7a4bfd978a954..e87b8347e1a213a 100755 --- a/selfdrive/test/process_replay/regen.py +++ b/selfdrive/test/process_replay/regen.py @@ -14,8 +14,7 @@ from openpilot.selfdrive.test.update_ci_routes import upload_route from openpilot.tools.lib.route import Route from openpilot.tools.lib.framereader import FrameReader, BaseFrameReader, FrameType -from openpilot.tools.lib.logreader import LogReader, LogIterable -from openpilot.tools.lib.helpers import save_log +from openpilot.tools.lib.logreader import LogReader, LogIterable, save_log class DummyFrameReader(BaseFrameReader): @@ -75,7 +74,7 @@ def setup_data_readers( assert device_type != "neo", "Driver camera not supported on neo segments. Use dummy dcamera." frs['driverCameraState'] = FrameReader(r.dcamera_paths()[sidx]) else: - lr = LogReader(f"cd:/{route.replace('|', '/')}/{sidx}/rlog.bz2") + lr = LogReader(f"{route}/{sidx}/r") frs = {} if needs_road_cam: frs['roadCameraState'] = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/fcamera.hevc") @@ -119,7 +118,7 @@ def regen_and_save( log_dir = os.path.join(outdir, time.strftime("%Y-%m-%d--%H-%M-%S--0", time.gmtime())) rel_log_dir = os.path.relpath(log_dir) - rpath = os.path.join(log_dir, "rlog.bz2") + rpath = os.path.join(log_dir, "rlog.zst") os.makedirs(log_dir) save_log(rpath, output_logs, compress=True) diff --git a/selfdrive/test/process_replay/test_fuzzy.py b/selfdrive/test/process_replay/test_fuzzy.py index c802d9c573d2c83..723112163ebd737 100644 --- a/selfdrive/test/process_replay/test_fuzzy.py +++ b/selfdrive/test/process_replay/test_fuzzy.py @@ -1,26 +1,29 @@ import copy +import os from hypothesis import given, HealthCheck, Phase, settings import hypothesis.strategies as st from parameterized import parameterized from cereal import log -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA +from opendbc.car.toyota.values import CAR as TOYOTA from openpilot.selfdrive.test.fuzzy_generation import FuzzyGenerator import openpilot.selfdrive.test.process_replay.process_replay as pr # These processes currently fail because of unrealistic data breaking assumptions # that openpilot makes causing error with NaN, inf, int size, array indexing ... # TODO: Make each one testable -NOT_TESTED = ['controlsd', 'card', 'plannerd', 'calibrationd', 'dmonitoringd', 'paramsd', 'dmonitoringmodeld', 'modeld'] +NOT_TESTED = ['selfdrived', 'controlsd', 'card', 'plannerd', 'calibrationd', 'dmonitoringd', 'paramsd', 'dmonitoringmodeld', 'modeld'] TEST_CASES = [(cfg.proc_name, copy.deepcopy(cfg)) for cfg in pr.CONFIGS if cfg.proc_name not in NOT_TESTED] +MAX_EXAMPLES = int(os.environ.get("MAX_EXAMPLES", "10")) class TestFuzzProcesses: # TODO: make this faster and increase examples @parameterized.expand(TEST_CASES) @given(st.data()) - @settings(phases=[Phase.generate, Phase.target], max_examples=10, deadline=1000, suppress_health_check=[HealthCheck.too_slow, HealthCheck.data_too_large]) + @settings(phases=[Phase.generate, Phase.target], max_examples=MAX_EXAMPLES, deadline=1000, + suppress_health_check=[HealthCheck.too_slow, HealthCheck.data_too_large]) def test_fuzz_process(self, proc_name, cfg, data): msgs = FuzzyGenerator.get_random_event_msg(data.draw, events=cfg.pubs, real_floats=True) lr = [log.Event.new_message(**m).as_reader() for m in msgs] diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py index 533ab125f9ab8e5..8af779ccf8d3853 100755 --- a/selfdrive/test/process_replay/test_processes.py +++ b/selfdrive/test/process_replay/test_processes.py @@ -7,15 +7,14 @@ from tqdm import tqdm from typing import Any +from opendbc.car.car_helpers import interface_names from openpilot.common.git import get_commit -from openpilot.selfdrive.car.car_helpers import interface_names from openpilot.tools.lib.openpilotci import get_url, upload_file from openpilot.selfdrive.test.process_replay.compare_logs import compare_logs, format_diff from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, FAKEDATA, replay_process, \ - check_openpilot_enabled, check_most_messages_valid + check_most_messages_valid from openpilot.tools.lib.filereader import FileReader -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.helpers import save_log +from openpilot.tools.lib.logreader import LogReader, save_log source_segments = [ ("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.COMMA_BODY @@ -37,28 +36,27 @@ ("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"), # FORD.FORD_BRONCO_SPORT_MK1 # Enable when port is tested and dashcamOnly is no longer set - #("TESLA", "bb50caf5f0945ab1|2021-06-19--17-20-18--3"), # TESLA.TESLA_AP2_MODELS #("VOLKSWAGEN2", "3cfdec54aa035f3f|2022-07-19--23-45-10--2"), # VOLKSWAGEN.VOLKSWAGEN_PASSAT_NMS ] segments = [ - ("BODY", "regen29FD9FF7760|2024-05-21--06-58-51--0"), - ("HYUNDAI", "regen0B1B76A1C27|2024-05-21--06-57-53--0"), - ("HYUNDAI2", "regen3BB55FA5E20|2024-05-21--06-59-03--0"), - ("TOYOTA", "regenF6FB954C1E2|2024-05-21--06-57-53--0"), - ("TOYOTA2", "regen0AC637CE7BA|2024-05-21--06-57-54--0"), - ("TOYOTA3", "regenC7BE3FAE496|2024-05-21--06-59-01--0"), - ("HONDA", "regen58E9F8B695A|2024-05-21--06-57-55--0"), - ("HONDA2", "regen8695608EB15|2024-05-21--06-57-55--0"), - ("CHRYSLER", "regenB0F8C25C902|2024-05-21--06-59-47--0"), - ("RAM", "regenB3B2C7A105B|2024-05-21--07-00-47--0"), - ("SUBARU", "regen860FD736DCC|2024-05-21--07-00-50--0"), - ("GM", "regen8CB3048DEB9|2024-05-21--06-59-49--0"), - ("GM2", "regen379D446541D|2024-05-21--07-00-51--0"), - ("NISSAN", "regen24871108F80|2024-05-21--07-00-38--0"), - ("VOLKSWAGEN", "regenF390392F275|2024-05-21--07-00-52--0"), - ("MAZDA", "regenE5A36020581|2024-05-21--07-01-51--0"), - ("FORD", "regenDC288ED0D78|2024-05-21--07-02-18--0"), + ("BODY", "regenA67A128BCD8|2024-08-30--02-36-22--0"), + ("HYUNDAI", "regen9CBD921E93E|2024-08-30--02-38-51--0"), + ("HYUNDAI2", "regen306779F6870|2024-10-03--04-03-23--0"), + ("TOYOTA", "regen1CA7A48E6F7|2024-08-30--02-45-08--0"), + ("TOYOTA2", "regen6E484EDAB96|2024-08-30--02-47-37--0"), + ("TOYOTA3", "regen4CE950B0267|2024-08-30--02-51-30--0"), + ("HONDA", "regenC8F0D6ADC5C|2024-08-30--02-54-01--0"), + ("HONDA2", "regen4B38A7428CD|2024-08-30--02-56-31--0"), + ("CHRYSLER", "regenF3DBBA9E8DF|2024-08-30--02-59-03--0"), + ("RAM", "regenDB02684E00A|2024-08-30--03-02-54--0"), + ("SUBARU", "regenAA1FF48CF1F|2024-08-30--03-06-45--0"), + ("GM", "regen720F2BA4CF6|2024-08-30--03-09-15--0"), + ("GM2", "regen9ADBECBCD1C|2024-08-30--03-13-04--0"), + ("NISSAN", "regen58464878D07|2024-08-30--03-15-31--0"), + ("VOLKSWAGEN", "regenED976DEB757|2024-08-30--03-18-02--0"), + ("MAZDA", "regenACF84CCF482|2024-08-30--03-21-55--0"), + ("FORD", "regen756F8230C21|2024-11-07--00-08-24--0"), ] # dashcamOnly makes don't need to be tested until a full port is done @@ -88,7 +86,7 @@ def run_test_process(data): def get_log_data(segment): r, n = segment.rsplit("--", 1) - with FileReader(get_url(r, n)) as f: + with FileReader(get_url(r, n, "rlog.zst")) as f: return (segment, f.read()) @@ -105,14 +103,11 @@ def test_process(cfg, lr, segment, ref_log_path, new_log_path, ignore_fields=Non except Exception as e: raise Exception("failed on segment: " + segment) from e - # check to make sure openpilot is engaged in the route - if cfg.proc_name == "controlsd": - if not check_openpilot_enabled(log_msgs): - return f"Route did not enable at all or for long enough: {new_log_path}", log_msgs if not check_most_messages_valid(log_msgs): return f"Route did not have enough valid messages: {new_log_path}", log_msgs - if cfg.proc_name != 'ubloxd' or segment != 'regen3BB55FA5E20|2024-05-21--06-59-03--0': + # skip this check if the segment is using qcom gps + if cfg.proc_name != 'ubloxd' or any(m.which() in cfg.pubs for m in lr): seen_msgs = {m.which() for m in log_msgs} expected_msgs = set(cfg.subs) if seen_msgs != expected_msgs: @@ -140,7 +135,7 @@ def test_process(cfg, lr, segment, ref_log_path, new_log_path, ignore_fields=Non parser.add_argument("--blacklist-cars", type=str, nargs="*", default=[], help="Blacklist given cars from the test (e.g. HONDA)") parser.add_argument("--ignore-fields", type=str, nargs="*", default=[], - help="Extra fields or msgs to ignore (e.g. carState.events)") + help="Extra fields or msgs to ignore (e.g. driverMonitoringState.events)") parser.add_argument("--ignore-msgs", type=str, nargs="*", default=[], help="Msgs to ignore (e.g. carEvents)") parser.add_argument("--update-refs", action="store_true", @@ -198,11 +193,15 @@ def test_process(cfg, lr, segment, ref_log_path, new_log_path, ignore_fields=Non if cfg.proc_name not in tested_procs: continue - cur_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{cur_commit}.bz2") + # to speed things up, we only test all segments on card + if cfg.proc_name != 'card' and car_brand not in ('HYUNDAI', 'TOYOTA', 'HONDA', 'SUBARU', 'FORD'): + continue + + cur_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{cur_commit}.zst") if args.update_refs: # reference logs will not exist if routes were just regenerated - ref_log_path = get_url(*segment.rsplit("--", 1)) + ref_log_path = get_url(*segment.rsplit("--", 1,), "rlog.zst") else: - ref_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{ref_commit}.bz2") + ref_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{ref_commit}.zst") ref_log_path = ref_log_fn if os.path.exists(ref_log_fn) else BASE_URL + os.path.basename(ref_log_fn) dat = None if args.upload_only else log_data[segment] diff --git a/selfdrive/test/process_replay/test_regen.py b/selfdrive/test/process_replay/test_regen.py index 17fefcb49799771..6c4b48c8d564e06 100644 --- a/selfdrive/test/process_replay/test_regen.py +++ b/selfdrive/test/process_replay/test_regen.py @@ -15,13 +15,13 @@ def ci_setup_data_readers(route, sidx): - lr = LogReader(get_url(route, sidx, "rlog")) + lr = LogReader(get_url(route, sidx, "rlog.bz2")) frs = { - 'roadCameraState': FrameReader(get_url(route, sidx, "fcamera")), + 'roadCameraState': FrameReader(get_url(route, sidx, "fcamera.hevc")), 'driverCameraState': DummyFrameReader.zero_dcamera() } if next((True for m in lr if m.which() == "wideRoadCameraState"), False): - frs["wideRoadCameraState"] = FrameReader(get_url(route, sidx, "ecamera")) + frs["wideRoadCameraState"] = FrameReader(get_url(route, sidx, "ecamera.hevc")) return lr, frs diff --git a/selfdrive/test/profiling/lib.py b/selfdrive/test/profiling/lib.py index 93ba2153867444b..62bb305ca851d7d 100644 --- a/selfdrive/test/profiling/lib.py +++ b/selfdrive/test/profiling/lib.py @@ -1,4 +1,4 @@ -from collections import defaultdict, deque +from collections import defaultdict from cereal.services import SERVICE_LIST import cereal.messaging as messaging import capnp @@ -45,7 +45,7 @@ def __init__(self, msgs, trigger, services, check_averag_freq=False): self.rcv_frame = {s: 0 for s in services} self.valid = {s: True for s in services} self.freq_ok = {s: True for s in services} - self.recv_dts = {s: deque([0.0] * messaging.AVG_FREQ_HISTORY, maxlen=messaging.AVG_FREQ_HISTORY) for s in services} + self.freq_tracker = {s: messaging.FrequencyTracker(SERVICE_LIST[s].frequency, SERVICE_LIST[s].frequency, False) for s in services} self.logMonoTime = {} self.sock = {} self.freq = {} diff --git a/selfdrive/test/profiling/profiler.py b/selfdrive/test/profiling/profiler.py index 2cd547171a4ac34..d50b157a37efca7 100755 --- a/selfdrive/test/profiling/profiler.py +++ b/selfdrive/test/profiling/profiler.py @@ -5,13 +5,13 @@ import pprofile import pyprof2calltree +from opendbc.car.toyota.values import CAR as TOYOTA +from opendbc.car.honda.values import CAR as HONDA +from opendbc.car.volkswagen.values import CAR as VW from openpilot.common.params import Params from openpilot.tools.lib.logreader import LogReader from openpilot.selfdrive.test.profiling.lib import SubMaster, PubMaster, SubSocket, ReplayDone from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.volkswagen.values import CAR as VW BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" diff --git a/selfdrive/test/scons_build_test.sh b/selfdrive/test/scons_build_test.sh index a3b33f797a852c0..5ffdb4379e004cd 100755 --- a/selfdrive/test/scons_build_test.sh +++ b/selfdrive/test/scons_build_test.sh @@ -1,10 +1,20 @@ -#!/bin/bash +#!/usr/bin/env bash +set -e SCRIPT_DIR=$(dirname "$0") BASEDIR=$(realpath "$SCRIPT_DIR/../../") cd $BASEDIR -# tests that our build system's dependencies are configured properly, +# tests that our build system's dependencies are configured properly, # needs a machine with lots of cores + +# helpful commands: +# scons -Q --tree=derived + +cd $BASEDIR/opendbc_repo/ scons --clean -scons --no-cache --random -j$(nproc) \ No newline at end of file +scons --no-cache --random -j$(nproc) +if ! scons -q; then + echo "FAILED: all build products not up to date after first pass." + exit 1 +fi diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh index 84dae25821e2a48..67671546a678db8 100755 --- a/selfdrive/test/setup_device_ci.sh +++ b/selfdrive/test/setup_device_ci.sh @@ -1,6 +1,7 @@ -#!/usr/bin/bash +#!/usr/bin/env bash set -e +set -x if [ -z "$SOURCE_DIR" ]; then echo "SOURCE_DIR must be set" @@ -17,13 +18,15 @@ if [ -z "$TEST_DIR" ]; then exit 1 fi -umount /data/safe_staging/merged/ || true -sudo umount /data/safe_staging/merged/ || true -rm -rf /data/safe_staging/* || true +rm -rf /data/safe_staging/ || true +if [ -d /data/safe_staging/ ]; then + sudo umount /data/safe_staging/merged/ || true + rm -rf /data/safe_staging/ || true +fi CONTINUE_PATH="/data/continue.sh" tee $CONTINUE_PATH << EOF -#!/usr/bin/bash +#!/usr/bin/env bash sudo abctl --set_success @@ -112,8 +115,8 @@ if [ ! -d "$SOURCE_DIR" ]; then fi if [ ! -z "$UNSAFE" ]; then - echo "doing unsafe checkout" - unsafe_checkout + echo "trying unsafe checkout" + unsafe_checkout || safe_checkout else echo "doing safe checkout" safe_checkout diff --git a/selfdrive/test/setup_vsound.sh b/selfdrive/test/setup_vsound.sh index a6601d0a61d0acb..aab14997448b4a4 100755 --- a/selfdrive/test/setup_vsound.sh +++ b/selfdrive/test/setup_vsound.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash { #start pulseaudio daemon diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index 75585e2f14ce509..9b131a639a19c59 100644 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -1,4 +1,3 @@ -import bz2 import math import json import os @@ -9,20 +8,22 @@ import subprocess import time import numpy as np +import zstandard as zstd from collections import Counter, defaultdict -from functools import cached_property from pathlib import Path +from tabulate import tabulate -from cereal import car +from cereal import car, log import cereal.messaging as messaging from cereal.services import SERVICE_LIST from openpilot.common.basedir import BASEDIR from openpilot.common.timeout import Timeout from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.events import EVENTS, ET -from openpilot.system.hardware import HARDWARE +from openpilot.selfdrive.selfdrived.events import EVENTS, ET from openpilot.selfdrive.test.helpers import set_params_enabled, release_only +from openpilot.system.hardware import HARDWARE from openpilot.system.hardware.hw import Paths +from openpilot.system.loggerd.uploader import LOG_COMPRESSION_LEVEL from openpilot.tools.lib.logreader import LogReader """ @@ -31,44 +32,48 @@ * total CPU usage of openpilot (sum(PROCS.values()) should not exceed MAX_TOTAL_CPU """ -MAX_TOTAL_CPU = 250. # total for all 8 cores + +TEST_DURATION = 25 +LOG_OFFSET = 8 + +MAX_TOTAL_CPU = 265. # total for all 8 cores PROCS = { # Baseline CPU usage by process - "selfdrive.controls.controlsd": 32.0, - "selfdrive.car.card": 22.0, + "selfdrive.controls.controlsd": 16.0, + "selfdrive.selfdrived.selfdrived": 16.0, + "selfdrive.car.card": 26.0, "./loggerd": 14.0, "./encoderd": 17.0, "./camerad": 14.5, - "./locationd": 11.0, - "selfdrive.controls.plannerd": 11.0, + "selfdrive.controls.plannerd": 9.0, "./ui": 18.0, "selfdrive.locationd.paramsd": 9.0, "./sensord": 7.0, - "selfdrive.controls.radard": 7.0, - "selfdrive.modeld.modeld": 13.0, - "selfdrive.modeld.dmonitoringmodeld": 8.0, - "system.hardware.hardwared": 3.87, + "selfdrive.controls.radard": 2.0, + "selfdrive.modeld.modeld": 17.0, + "selfdrive.modeld.dmonitoringmodeld": 11.0, + "system.hardware.hardwared": 4.0, "selfdrive.locationd.calibrationd": 2.0, "selfdrive.locationd.torqued": 5.0, - "selfdrive.ui.soundd": 3.5, + "selfdrive.locationd.locationd": 25.0, + "selfdrive.ui.soundd": 3.0, "selfdrive.monitoring.dmonitoringd": 4.0, - "./proclogd": 1.54, - "system.logmessaged": 0.2, + "./proclogd": 2.0, + "system.logmessaged": 1.0, "system.tombstoned": 0, - "./logcatd": 0, - "system.micd": 6.0, + "./logcatd": 1.0, + "system.micd": 5.0, "system.timed": 0, "selfdrive.pandad.pandad": 0, - "system.statsd": 0.4, - "selfdrive.navd.navd": 0.4, - "system.loggerd.uploader": (0.5, 15.0), - "system.loggerd.deleter": 0.1, + "system.statsd": 1.0, + "system.loggerd.uploader": 15.0, + "system.loggerd.deleter": 1.0, } PROCS.update({ "tici": { "./pandad": 4.0, - "./ubloxd": 0.02, + "./ubloxd": 1.0, "system.ubloxd.pigeond": 6.0, }, "tizi": { @@ -87,14 +92,22 @@ "carControl": [2.5, 0.35], "controlsState": [2.5, 0.35], "longitudinalPlan": [2.5, 0.5], + "driverAssistance": [2.5, 0.5], "roadCameraState": [2.5, 0.35], "driverCameraState": [2.5, 0.35], "modelV2": [2.5, 0.35], "driverStateV2": [2.5, 0.40], - "liveLocationKalman": [2.5, 0.35], + "livePose": [2.5, 0.35], "wideRoadCameraState": [1.5, 0.35], } +LOGS_SIZE_RATE = { + "qlog": 0.0083, + "rlog": 0.1528, + "qcamera.ts": 0.03828, +} +LOGS_SIZE_RATE.update(dict.fromkeys(['ecamera.hevc', 'fcamera.hevc'], 1.2740)) + def cputime_total(ct): return ct.cpuUser + ct.cpuSystem + ct.cpuChildrenUser + ct.cpuChildrenSystem @@ -121,7 +134,7 @@ def setup_class(cls): if os.path.exists(Paths.log_root()): shutil.rmtree(Paths.log_root()) - # start manager and run openpilot for a minute + # start manager and run openpilot for TEST_DURATION proc = None try: manager_path = os.path.join(BASEDIR, "system/manager/manager.py") @@ -132,23 +145,24 @@ def setup_class(cls): while sm.recv_frame['carState'] < 0: sm.update(1000) - # make sure we get at least two full segments route = None cls.segments = [] with Timeout(300, "timed out waiting for logs"): while route is None: route = params.get("CurrentRoute", encoding="utf-8") - time.sleep(0.1) + time.sleep(0.01) + + # test car params caching + params.put("CarParamsCache", car.CarParams().to_bytes()) - while len(cls.segments) < 3: + while len(cls.segments) < 1: segs = set() if Path(Paths.log_root()).exists(): segs = set(Path(Paths.log_root()).glob(f"{route}--*")) cls.segments = sorted(segs, key=lambda s: int(str(s).rsplit('--')[-1])) - time.sleep(2) + time.sleep(0.01) - # chop off last, incomplete segment - cls.segments = cls.segments[:-1] + time.sleep(TEST_DURATION) finally: cls.gpu_procs = {psutil.Process(int(f.name)).name() for f in pathlib.Path('/sys/devices/virtual/kgsl/kgsl/proc/').iterdir() if f.is_dir()} @@ -160,28 +174,24 @@ def setup_class(cls): cls.lrs = [list(LogReader(os.path.join(str(s), "rlog"))) for s in cls.segments] - # use the second segment by default as it's the first full segment - cls.lr = list(LogReader(os.path.join(str(cls.segments[1]), "rlog"))) - cls.log_path = cls.segments[1] + cls.lr = list(LogReader(os.path.join(str(cls.segments[0]), "rlog"))) + cls.log_path = cls.segments[0] cls.log_sizes = {} for f in cls.log_path.iterdir(): assert f.is_file() - cls.log_sizes[f] = f.stat().st_size / 1e6 + 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 + cls.log_sizes[f] = len(zstd.compress(ff.read(), LOG_COMPRESSION_LEVEL)) / 1e6 + cls.msgs = defaultdict(list) + for m in cls.lr: + cls.msgs[m.which()].append(m) - @cached_property - def service_msgs(self): - msgs = defaultdict(list) - for m in self.lr: - msgs[m.which()].append(m) - return msgs def test_service_frequencies(self, subtests): - for s, msgs in self.service_msgs.items(): + for s, msgs in self.msgs.items(): if s in ('initData', 'sentinel'): continue @@ -190,10 +200,10 @@ def test_service_frequencies(self, subtests): continue with subtests.test(service=s): - assert len(msgs) >= math.floor(SERVICE_LIST[s].frequency*55) + assert len(msgs) >= math.floor(SERVICE_LIST[s].frequency*int(TEST_DURATION*0.8)) def test_cloudlog_size(self): - msgs = [m for m in self.lr if m.which() == 'logMessage'] + msgs = self.msgs['logMessage'] total_size = sum(len(m.as_builder().to_bytes()) for m in msgs) assert total_size < 3.5e5 @@ -204,16 +214,10 @@ def test_cloudlog_size(self): def test_log_sizes(self): for f, sz in self.log_sizes.items(): - if f.name == "qcamera.ts": - assert 2.15 < sz < 2.35 - elif f.name == "qlog": - assert 0.7 < sz < 1.0 - elif f.name == "rlog": - assert 5 < sz < 50 - elif f.name.endswith('.hevc'): - assert 70 < sz < 77 - else: - raise NotImplementedError + rate = LOGS_SIZE_RATE[f.name] + minn = rate * TEST_DURATION * 0.8 + maxx = rate * TEST_DURATION * 1.2 + assert minn < sz < maxx def test_ui_timings(self): result = "\n" @@ -221,7 +225,7 @@ def test_ui_timings(self): result += "-------------- UI Draw Timing ------------------\n" result += "------------------------------------------------\n" - ts = [m.uiDebug.drawTimeMillis for m in self.service_msgs['uiDebug']] + ts = [m.uiDebug.drawTimeMillis for m in self.msgs['uiDebug']] result += f"min {min(ts):.2f}ms\n" result += f"max {max(ts):.2f}ms\n" result += f"std {np.std(ts):.2f}ms\n" @@ -238,52 +242,44 @@ def test_ui_timings(self): assert len(veryslow) < 5, f"Too many slow frame draw times: {veryslow}" def test_cpu_usage(self, subtests): - result = "\n" - result += "------------------------------------------------\n" - result += "------------------ CPU Usage -------------------\n" - result += "------------------------------------------------\n" + print("\n------------------------------------------------") + print("------------------ CPU Usage -------------------") + print("------------------------------------------------") plogs_by_proc = defaultdict(list) - for pl in self.service_msgs['procLog']: + for pl in self.msgs['procLog']: for x in pl.procLog.procs: if len(x.cmdline) > 0: n = list(x.cmdline)[0] plogs_by_proc[n].append(x) - print(plogs_by_proc.keys()) cpu_ok = True - dt = (self.service_msgs['procLog'][-1].logMonoTime - self.service_msgs['procLog'][0].logMonoTime) / 1e9 - for proc_name, expected_cpu in PROCS.items(): + dt = (self.msgs['procLog'][-1].logMonoTime - self.msgs['procLog'][0].logMonoTime) / 1e9 + header = ['process', 'usage', 'expected', 'max allowed', 'test result'] + rows = [] + for proc_name, expected in PROCS.items(): - err = "" - cpu_usage = 0. + error = "" + usage = 0. x = plogs_by_proc[proc_name] if len(x) > 2: cpu_time = cputime_total(x[-1]) - cputime_total(x[0]) - cpu_usage = cpu_time / dt * 100. - - if isinstance(expected_cpu, tuple): - exp = str(expected_cpu) - minn, maxx = expected_cpu - else: - exp = f"{expected_cpu:5.2f}" - minn = min(expected_cpu * 0.65, max(expected_cpu - 1.0, 0.0)) - maxx = max(expected_cpu * 1.15, expected_cpu + 5.0) - - if cpu_usage > maxx: - err = "using more CPU than expected" - elif cpu_usage < minn: - err = "using less CPU than expected" - else: - err = "NO METRICS FOUND" + usage = cpu_time / dt * 100. + + max_allowed = max(expected * 1.8, expected + 5.0) + if usage > max_allowed: + error = "❌ USING MORE CPU THAN EXPECTED ❌" + cpu_ok = False - result += f"{proc_name.ljust(35)} {cpu_usage:5.2f}% ({exp}%) {err}\n" - if len(err) > 0: + else: + error = "❌ NO METRICS FOUND ❌" cpu_ok = False - result += "------------------------------------------------\n" + + rows.append([proc_name, usage, expected, max_allowed, error or "✅"]) + print(tabulate(rows, header, tablefmt="simple_grid", stralign="center", numalign="center", floatfmt=".2f")) # Ensure there's no missing procs - all_procs = {p.name for p in self.service_msgs['managerState'][0].managerState.processes if p.shouldBeRunning} + all_procs = {p.name for p in self.msgs['managerState'][0].managerState.processes if p.shouldBeRunning} for p in all_procs: with subtests.test(proc=p): assert any(p in pp for pp in PROCS.keys()), f"Expected CPU usage missing for {p}" @@ -292,16 +288,15 @@ def test_cpu_usage(self, subtests): procs_tot = sum([(max(x) if isinstance(x, tuple) else x) for x in PROCS.values()]) with subtests.test(name="total CPU"): assert procs_tot < MAX_TOTAL_CPU, "Total CPU budget exceeded" - result += "------------------------------------------------\n" - result += f"Total allocated CPU usage is {procs_tot}%, budget is {MAX_TOTAL_CPU}%, {MAX_TOTAL_CPU-procs_tot:.1f}% left\n" - result += "------------------------------------------------\n" - - print(result) + print("------------------------------------------------") + print(f"Total allocated CPU usage is {procs_tot}%, budget is {MAX_TOTAL_CPU}%, {MAX_TOTAL_CPU-procs_tot:.1f}% left") + print("------------------------------------------------") assert cpu_ok def test_memory_usage(self): - mems = [m.deviceState.memoryUsagePercent for m in self.service_msgs['deviceState']] + offset = int(SERVICE_LIST['deviceState'].frequency * LOG_OFFSET) + mems = [m.deviceState.memoryUsagePercent for m in self.msgs['deviceState'][offset:]] print("Memory usage: ", mems) # check for big leaks. note that memory usage is @@ -309,7 +304,7 @@ def test_memory_usage(self): assert max(mems) - min(mems) <= 3.0 def test_gpu_usage(self): - assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld"} + assert self.gpu_procs == {"weston", "ui", "camerad", "selfdrive.modeld.modeld", "selfdrive.modeld.dmonitoringmodeld"} def test_camera_processing_time(self): result = "\n" @@ -317,7 +312,9 @@ def test_camera_processing_time(self): result += "-------------- ImgProc Timing ------------------\n" result += "------------------------------------------------\n" - ts = [getattr(m, m.which()).processingTime for m in self.lr if 'CameraState' in m.which()] + ts = [] + for s in ['roadCameraState', 'driverCameraState', 'wideCameraState']: + ts.extend(getattr(m, s).processingTime for m in self.msgs[s]) assert min(ts) < 0.025, f"high execution time: {min(ts)}" result += f"execution time: min {min(ts):.5f}s\n" result += f"execution time: max {max(ts):.5f}s\n" @@ -350,7 +347,7 @@ def test_mpc_execution_timings(self): 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]] + ts = [getattr(m, s).solverExecutionTime for m in self.msgs[s]] assert max(ts) < instant_max, f"high '{s}' execution time: {max(ts)}" assert np.mean(ts) < avg_max, f"high avg '{s}' execution time: {np.mean(ts)}" result += f"'{s}' execution time: min {min(ts):.5f}s\n" @@ -370,7 +367,7 @@ def test_model_execution_timings(self): ("driverStateV2", 0.050, 0.026), ] for (s, instant_max, avg_max) in cfgs: - ts = [getattr(m, s).modelExecutionTime for m in self.service_msgs[s]] + ts = [getattr(m, s).modelExecutionTime for m in self.msgs[s]] assert max(ts) < instant_max, f"high '{s}' execution time: {max(ts)}" assert np.mean(ts) < avg_max, f"high avg '{s}' execution time: {np.mean(ts)}" result += f"'{s}' execution time: min {min(ts):.5f}s\n" @@ -381,33 +378,32 @@ def test_model_execution_timings(self): def test_timings(self): passed = True - result = "\n" - result += "------------------------------------------------\n" - result += "----------------- Service Timings --------------\n" - result += "------------------------------------------------\n" + print("\n------------------------------------------------") + print("----------------- Service Timings --------------") + print("------------------------------------------------") + + header = ['service', 'max', 'min', 'mean', 'expected mean', 'rsd', 'max allowed rsd', 'test result'] + rows = [] for s, (maxmin, rsd) in TIMINGS.items(): - msgs = [m.logMonoTime for m in self.service_msgs[s]] + offset = int(SERVICE_LIST[s].frequency * LOG_OFFSET) + msgs = [m.logMonoTime for m in self.msgs[s][offset:]] if not len(msgs): raise Exception(f"missing {s}") ts = np.diff(msgs) / 1e9 dt = 1 / SERVICE_LIST[s].frequency - try: - np.testing.assert_allclose(np.mean(ts), dt, rtol=0.03, err_msg=f"{s} - failed mean timing check") - np.testing.assert_allclose([np.max(ts), np.min(ts)], dt, rtol=maxmin, err_msg=f"{s} - failed max/min timing check") - except Exception as e: - result += str(e) + "\n" - passed = False - - if np.std(ts) / dt > rsd: - result += f"{s} - failed RSD timing check\n" - passed = False - - result += f"{s.ljust(40)}: {np.array([np.mean(ts), np.max(ts), np.min(ts)])*1e3}\n" - result += f"{''.ljust(40)} {np.max(np.absolute([np.max(ts)/dt, np.min(ts)/dt]))} {np.std(ts)/dt}\n" - result += "="*67 - print(result) + errors = [] + if not np.allclose(np.mean(ts), dt, rtol=0.03, atol=0): + errors.append("❌ FAILED MEAN TIMING CHECK ❌") + if not np.allclose([np.max(ts), np.min(ts)], dt, rtol=maxmin, atol=0): + errors.append("❌ FAILED MAX/MIN TIMING CHECK ❌") + if (np.std(ts)/dt) > rsd: + errors.append("❌ FAILED RSD TIMING CHECK ❌") + passed = not errors and passed + rows.append([s, *(np.array([np.max(ts), np.min(ts), np.mean(ts), dt])*1e3), np.std(ts)/dt, rsd, "\n".join(errors) or "✅"]) + + print(tabulate(rows, header, tablefmt="simple_grid", stralign="center", numalign="center", floatfmt=".2f")) assert passed @release_only @@ -415,19 +411,20 @@ def test_startup(self): startup_alert = None for msg in self.lrs[0]: # 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 + if msg.which() == "selfdriveState": + startup_alert = msg.selfdriveState.alertText1 break - expected = EVENTS[car.CarEvent.EventName.startup][ET.PERMANENT].alert_text_1 + expected = EVENTS[log.OnroadEvent.EventName.startup][ET.PERMANENT].alert_text_1 assert startup_alert == expected, "wrong startup alert" def test_engagable(self): no_entries = Counter() - for m in self.service_msgs['onroadEvents']: + for m in self.msgs['onroadEvents']: for evt in m.onroadEvents: if evt.noEntry: no_entries[evt.name] += 1 - eng = [m.controlsState.engageable for m in self.service_msgs['controlsState']] + offset = int(SERVICE_LIST['selfdriveState'].frequency * LOG_OFFSET) + eng = [m.selfdriveState.engageable for m in self.msgs['selfdriveState'][offset:]] assert all(eng), \ - f"Not engageable for whole segment:\n- controlsState.engageable: {Counter(eng)}\n- No entry events: {no_entries}" + f"Not engageable for whole segment:\n- selfdriveState.engageable: {Counter(eng)}\n- No entry events: {no_entries}" diff --git a/selfdrive/test/test_time_to_onroad.py b/selfdrive/test/test_time_to_onroad.py index e08d0e676cf9740..e68386bb5813c94 100644 --- a/selfdrive/test/test_time_to_onroad.py +++ b/selfdrive/test/test_time_to_onroad.py @@ -3,13 +3,13 @@ import time import subprocess -from cereal import car +from cereal import log import cereal.messaging as messaging from openpilot.common.basedir import BASEDIR from openpilot.common.timeout import Timeout from openpilot.selfdrive.test.helpers import set_params_enabled -EventName = car.CarEvent.EventName +EventName = log.OnroadEvent.EventName @pytest.mark.tici @@ -20,7 +20,7 @@ def test_time_to_onroad(): proc = subprocess.Popen(["python", manager_path]) start_time = time.monotonic() - sm = messaging.SubMaster(['controlsState', 'deviceState', 'onroadEvents']) + sm = messaging.SubMaster(['selfdriveState', 'deviceState', 'onroadEvents']) try: # wait for onroad. timeout assumes panda is up to date with Timeout(10, "timed out waiting to go onroad"): @@ -34,12 +34,12 @@ def test_time_to_onroad(): while True: sm.update(100) - if sm.seen['onroadEvents'] and not any(EventName.controlsInitializing == e.name for e in sm['onroadEvents']): + if sm.seen['onroadEvents'] and not any(EventName.selfdriveInitializing == e.name for e in sm['onroadEvents']): initialized = True if initialized: sm.update(100) - assert sm['controlsState'].engageable, f"events: {sm['onroadEvents']}" + assert sm['selfdriveState'].engageable, f"events: {sm['onroadEvents']}" break finally: print(f"onroad events: {sm['onroadEvents']}") @@ -50,8 +50,7 @@ def test_time_to_onroad(): while (time.monotonic() - st) < 10.: sm.update(100) assert sm.all_alive(), sm.alive - assert sm['controlsState'].engageable, f"events: {sm['onroadEvents']}" - assert sm['controlsState'].cumLagMs < 10. + assert sm['selfdriveState'].engageable, f"events: {sm['onroadEvents']}" finally: proc.terminate() if proc.wait(20) is None: diff --git a/selfdrive/test/test_updated.py b/selfdrive/test/test_updated.py index f8eae94823420f5..ea945d94c29487e 100644 --- a/selfdrive/test/test_updated.py +++ b/selfdrive/test/test_updated.py @@ -164,7 +164,7 @@ def _check_update_state(self, update_available): # make sure LastUpdateTime is recent t = self._read_param("LastUpdateTime") last_update_time = datetime.datetime.fromisoformat(t) - td = datetime.datetime.utcnow() - last_update_time + td = datetime.datetime.now(datetime.UTC).replace(tzinfo=None) - last_update_time assert td.total_seconds() < 10 self.params.remove("LastUpdateTime") diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py index a9f4494ffd9aa6c..2bf06b48603e51e 100755 --- a/selfdrive/test/update_ci_routes.py +++ b/selfdrive/test/update_ci_routes.py @@ -7,7 +7,7 @@ from tqdm import tqdm -from openpilot.selfdrive.car.tests.routes import routes as test_car_models_routes +from opendbc.car.tests.routes import routes as test_car_models_routes from openpilot.selfdrive.test.process_replay.test_processes import source_segments as replay_segments from openpilot.tools.lib.azure_container import AzureContainer from openpilot.tools.lib.openpilotcontainers import DataCIContainer, DataProdContainer, OpenpilotCIContainer diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index e181cb9abdc45f1..81c18d03df39b73 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -8,8 +8,6 @@ base_libs = [common, messaging, visionipc, transformations, if arch == 'larch64': base_libs.append('EGL') -maps = arch in ['larch64', 'aarch64', 'x86_64'] - if arch == "Darwin": del base_libs[base_libs.index('OpenCL')] qt_env['FRAMEWORKS'] += ['OpenCL'] @@ -18,29 +16,22 @@ if arch == "Darwin": 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", +widgets_src = ["qt/widgets/input.cc", "qt/widgets/wifi.cc", "qt/prime_state.cc", "qt/widgets/ssh_keys.cc", "qt/widgets/toggle.cc", "qt/widgets/controls.cc", "qt/widgets/offroad_alerts.cc", "qt/widgets/prime.cc", "qt/widgets/keyboard.cc", "qt/widgets/scrollview.cc", "qt/widgets/cameraview.cc", "#third_party/qrcode/QrCode.cc", "qt/request_repeater.cc", "qt/qt_window.cc", "qt/network/networking.cc", "qt/network/wifi_manager.cc"] -qt_env['CPPDEFINES'] = [] -if maps: - 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"] - widgets = qt_env.Library("qt_widgets", widgets_src, LIBS=base_libs) Export('widgets') qt_libs = [widgets, qt_util] + base_libs -qt_src = ["main.cc", "qt/sidebar.cc", "qt/body.cc", +qt_src = ["main.cc", "ui.cc", "qt/sidebar.cc", "qt/body.cc", "qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc", - "qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc", + "qt/offroad/software_settings.cc", "qt/offroad/developer_panel.cc", "qt/offroad/onboarding.cc", "qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc", - "qt/onroad/onroad_home.cc", "qt/onroad/annotated_camera.cc", - "qt/onroad/buttons.cc", "qt/onroad/alerts.cc"] + "qt/onroad/onroad_home.cc", "qt/onroad/annotated_camera.cc", "qt/onroad/model.cc", + "qt/onroad/buttons.cc", "qt/onroad/alerts.cc", "qt/onroad/driver_monitoring.cc", "qt/onroad/hud.cc"] # build translation files with open(File("translations/languages.json").abspath) as f: @@ -49,7 +40,7 @@ translation_sources = [f"#selfdrive/ui/translations/{l}.ts" for l in languages.v translation_targets = [src.replace(".ts", ".qm") for src in translation_sources] lrelease_bin = 'third_party/qt5/larch64/bin/lrelease' if arch == 'larch64' else 'lrelease' -lupdate = qt_env.Command(translation_sources, qt_src + widgets_src, "selfdrive/ui/update_translations.py") +lupdate = qt_env.Command(translation_sources + ["translations/alerts_generated.h"], qt_src + widgets_src, "selfdrive/ui/update_translations.py") lrelease = qt_env.Command(translation_targets, translation_sources, f"{lrelease_bin} $SOURCES") qt_env.Depends(lrelease, lupdate) qt_env.NoClean(translation_sources) @@ -70,32 +61,28 @@ 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) -qt_env.SharedLibrary("qt/python_helpers", ["qt/qt_window.cc"], LIBS=qt_libs) - -# spinner and text window -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) 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) - qt_env.Program('tests/ui_snapshot', [asset_obj, "tests/ui_snapshot.cc"] + qt_src, LIBS=qt_libs) - if GetOption('extras') and arch != "Darwin": + qt_env.SharedLibrary("qt/python_helpers", ["qt/qt_window.cc"], LIBS=qt_libs) + + # spinner and text window + qt_env.Program("_text", ["qt/text.cc"], LIBS=qt_libs) + qt_env.Program("_spinner", ["qt/spinner.cc"], LIBS=qt_libs) + + # setup and factory resetter qt_env.Program("qt/setup/reset", ["qt/setup/reset.cc"], LIBS=qt_libs) qt_env.Program("qt/setup/setup", ["qt/setup/setup.cc", asset_obj], - LIBS=qt_libs + ['curl', 'common', 'json11']) + LIBS=qt_libs + ['curl', 'common']) # 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') @@ -105,7 +92,7 @@ if GetOption('extras') and arch != "Darwin": ("openpilot", release), ("openpilot_test", f"{release}-staging"), ("openpilot_nightly", "nightly"), - ("openpilot_internal", "master"), + ("openpilot_internal", "nightly-dev"), ] cont = senv.Command(f"installer/continue_openpilot.o", f"installer/continue_openpilot.sh", @@ -115,15 +102,13 @@ if GetOption('extras') and arch != "Darwin": if "internal" in name: d['INTERNAL'] = "1" - import requests - r = requests.get("https://github.com/commaci2.keys") - 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], LIBS=qt_libs) # keep installers small - assert f[0].get_size() < 350*1e3 + assert f[0].get_size() < 370*1e3 # build watch3 if arch in ['x86_64', 'aarch64', 'Darwin'] or GetOption('extras'): - qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'json11', 'msgq', 'visionipc']) + qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'msgq', 'visionipc']) + +SConscript(['raylib/SConscript']) diff --git a/selfdrive/ui/installer/continue_openpilot.sh b/selfdrive/ui/installer/continue_openpilot.sh index 3da67313eb949c8..ed41ab6f3fd16f0 100755 --- a/selfdrive/ui/installer/continue_openpilot.sh +++ b/selfdrive/ui/installer/continue_openpilot.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash cd /data/openpilot exec ./launch_openpilot.sh diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc index d43ed37ae8aa92b..17f6ba19abd08f9 100644 --- a/selfdrive/ui/installer/installer.cc +++ b/selfdrive/ui/installer/installer.cc @@ -180,10 +180,12 @@ void Installer::cloneFinished(int exitCode, QProcess::ExitStatus exitStatus) { #ifdef INTERNAL run("mkdir -p /data/params/d/"); + // https://github.com/commaci2.keys + const std::string ssh_keys = "ssh-ed25519 AAAAC3NzaC1lZDI1NTE5AAAAIMX2kU8eBZyEWmbq0tjMPxksWWVuIV/5l64GabcYbdpI"; std::map params = { {"SshEnabled", "1"}, {"RecordFrontLock", "1"}, - {"GithubSshKeys", SSH_KEYS}, + {"GithubSshKeys", ssh_keys}, }; for (const auto& [key, value] : params) { std::ofstream param; diff --git a/selfdrive/ui/mui.cc b/selfdrive/ui/mui.cc deleted file mode 100644 index 98029ee3114d4fe..000000000000000 --- a/selfdrive/ui/mui.cc +++ /dev/null @@ -1,50 +0,0 @@ -#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/home.cc b/selfdrive/ui/qt/home.cc index 9dbe7cbae39b863..9f179e0a38590ba 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -9,10 +9,6 @@ #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/widgets/prime.h" -#ifdef ENABLE_MAPS -#include "selfdrive/ui/qt/maps/map_settings.h" -#endif - // HomeWindow: the container for the offroad and onroad UIs HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { @@ -32,17 +28,11 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { slayout->addWidget(home); onroad = new OnroadWindow(this); - QObject::connect(onroad, &OnroadWindow::mapPanelRequested, this, [=] { sidebar->hide(); }); slayout->addWidget(onroad); body = new BodyWindow(this); slayout->addWidget(body); - driver_view = new DriverViewWindow(this); - connect(driver_view, &DriverViewWindow::done, [=] { - showDriverView(false); - }); - slayout->addWidget(driver_view); setAttribute(Qt::WA_NoSystemBackground); QObject::connect(uiState(), &UIState::uiUpdate, this, &HomeWindow::updateState); QObject::connect(uiState(), &UIState::offroadTransition, this, &HomeWindow::offroadTransition); @@ -53,10 +43,6 @@ void HomeWindow::showSidebar(bool show) { sidebar->setVisible(show); } -void HomeWindow::showMapPanel(bool show) { - onroad->showMapPanel(show); -} - void HomeWindow::updateState(const UIState &s) { const SubMaster &sm = *(s.sm); @@ -77,20 +63,10 @@ void HomeWindow::offroadTransition(bool offroad) { } } -void HomeWindow::showDriverView(bool show) { - if (show) { - emit closeSettings(); - slayout->setCurrentWidget(driver_view); - } else { - slayout->setCurrentWidget(home); - } - sidebar->setVisible(show == false); -} - void HomeWindow::mousePressEvent(QMouseEvent* e) { // Handle sidebar collapsing if ((onroad->isVisible() || body->isVisible()) && (!sidebar->isVisible() || e->x() > sidebar->width())) { - sidebar->setVisible(!sidebar->isVisible() && !onroad->isMapVisible()); + sidebar->setVisible(!sidebar->isVisible()); } } @@ -145,19 +121,22 @@ OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { home_layout->setContentsMargins(0, 0, 0, 0); home_layout->setSpacing(30); - // left: MapSettings/PrimeAdWidget + // left: PrimeAdWidget QStackedWidget *left_widget = new QStackedWidget(this); -#ifdef ENABLE_MAPS - left_widget->addWidget(new MapSettings); -#else - left_widget->addWidget(new QWidget); -#endif + QVBoxLayout *left_prime_layout = new QVBoxLayout(); + QWidget *prime_user = new PrimeUserWidget(); + prime_user->setStyleSheet(R"( + border-radius: 10px; + background-color: #333333; + )"); + left_prime_layout->addWidget(prime_user); + left_prime_layout->addStretch(); + left_widget->addWidget(new LayoutWidget(left_prime_layout)); left_widget->addWidget(new PrimeAdWidget); left_widget->setStyleSheet("border-radius: 10px;"); - left_widget->setCurrentIndex(uiState()->hasPrime() ? 0 : 1); - connect(uiState(), &UIState::primeChanged, [=](bool prime) { - left_widget->setCurrentIndex(prime ? 0 : 1); + connect(uiState()->prime_state, &PrimeState::changed, [left_widget]() { + left_widget->setCurrentIndex(uiState()->prime_state->isSubscribed() ? 0 : 1); }); home_layout->addWidget(left_widget, 1); diff --git a/selfdrive/ui/qt/home.h b/selfdrive/ui/qt/home.h index f60b80b21a9ce3b..55bc706c0ddf8f9 100644 --- a/selfdrive/ui/qt/home.h +++ b/selfdrive/ui/qt/home.h @@ -8,7 +8,6 @@ #include #include "common/params.h" -#include "selfdrive/ui/qt/offroad/driverview.h" #include "selfdrive/ui/qt/body.h" #include "selfdrive/ui/qt/onroad/onroad_home.h" #include "selfdrive/ui/qt/sidebar.h" @@ -53,9 +52,7 @@ class HomeWindow : public QWidget { public slots: void offroadTransition(bool offroad); - void showDriverView(bool show); void showSidebar(bool show); - void showMapPanel(bool show); protected: void mousePressEvent(QMouseEvent* e) override; @@ -66,7 +63,6 @@ public slots: OffroadHome *home; OnroadWindow *onroad; BodyWindow *body; - DriverViewWindow *driver_view; QStackedLayout *slayout; private slots: diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc deleted file mode 100644 index 490eb118cad0476..000000000000000 --- a/selfdrive/ui/qt/maps/map.cc +++ /dev/null @@ -1,390 +0,0 @@ -#include "selfdrive/ui/qt/maps/map.h" - -#include -#include - -#include - -#include "common/swaglog.h" -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/ui.h" - - -const int INTERACTION_TIMEOUT = 100; - -const float MAX_ZOOM = 17; -const float MIN_ZOOM = 14; -const float MAX_PITCH = 50; -const float MIN_PITCH = 0; -const float MAP_SCALE = 2; - -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); - map_overlay->setAttribute(Qt::WA_TranslucentBackground, true); - QVBoxLayout *overlay_layout = new QVBoxLayout(map_overlay); - overlay_layout->setContentsMargins(0, 0, 0, 0); - - // Instructions - map_instructions = new MapInstructions(this); - map_instructions->setVisible(false); - - map_eta = new MapETA(this); - map_eta->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); - map_eta->setFixedHeight(120); - - error = new QLabel(this); - error->setStyleSheet(R"(color:white;padding:50px 11px;font-size: 90px; background-color:rgba(0, 0, 0, 150);)"); - error->setAlignment(Qt::AlignCenter); - - overlay_layout->addWidget(error); - overlay_layout->addWidget(map_instructions); - overlay_layout->addStretch(1); - overlay_layout->addWidget(map_eta); - - last_position = coordinate_from_param("LastGPSPosition"); - grabGesture(Qt::GestureType::PinchGesture); - qDebug() << "MapWindow initialized"; -} - -MapWindow::~MapWindow() { - makeCurrent(); -} - -void MapWindow::initLayers() { - // This doesn't work from initializeGL - if (!m_map->layerExists("modelPathLayer")) { - qDebug() << "Initializing modelPathLayer"; - QVariantMap modelPath; - //modelPath["id"] = "modelPathLayer"; - modelPath["type"] = "line"; - modelPath["source"] = "modelPathSource"; - 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"); - } - if (!m_map->layerExists("navLayer")) { - qDebug() << "Initializing navLayer"; - QVariantMap nav; - nav["type"] = "line"; - nav["source"] = "navSource"; - m_map->addLayer("navLayer", nav, "road-intersection"); - - QVariantMap transition; - transition["duration"] = 400; // ms - m_map->setPaintProperty("navLayer", "line-color", QColor("#31a1ee")); - m_map->setPaintProperty("navLayer", "line-color-transition", transition); - m_map->setPaintProperty("navLayer", "line-width", 7.5); - m_map->setLayoutProperty("navLayer", "line-cap", "round"); - } - if (!m_map->layerExists("pinLayer")) { - qDebug() << "Initializing pinLayer"; - m_map->addImage("default_marker", QImage("../assets/navigation/default_marker.svg")); - QVariantMap pin; - pin["type"] = "symbol"; - pin["source"] = "pinSource"; - 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); - m_map->setLayoutProperty("pinLayer", "icon-allow-overlap", true); - m_map->setLayoutProperty("pinLayer", "symbol-sort-key", 0); - m_map->setLayoutProperty("pinLayer", "icon-anchor", "bottom"); - } - if (!m_map->layerExists("carPosLayer")) { - qDebug() << "Initializing carPosLayer"; - m_map->addImage("label-arrow", QImage("../assets/images/triangle.svg")); - - QVariantMap carPos; - carPos["type"] = "symbol"; - carPos["source"] = "carPosSource"; - 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); - m_map->setLayoutProperty("carPosLayer", "icon-ignore-placement", true); - m_map->setLayoutProperty("carPosLayer", "icon-allow-overlap", true); - // TODO: remove, symbol-sort-key does not seem to matter outside of each layer - m_map->setLayoutProperty("carPosLayer", "symbol-sort-key", 0); - } -} - -void MapWindow::updateState(const UIState &s) { - if (!uiState()->scene.started) { - return; - } - const SubMaster &sm = *(s.sm); - update(); - - // on rising edge of a valid system time, reinitialize the map to set a new token - if (sm.valid("clocks") && !prev_time_valid) { - LOGW("Time is now valid, reinitializing map"); - m_settings.setApiKey(get_mapbox_token()); - initializeGL(); - } - prev_time_valid = sm.valid("clocks"); - - if (sm.updated("liveLocationKalman")) { - auto locationd_location = sm["liveLocationKalman"].getLiveLocationKalman(); - auto locationd_pos = locationd_location.getPositionGeodetic(); - auto locationd_orientation = locationd_location.getCalibratedOrientationNED(); - auto locationd_velocity = locationd_location.getVelocityCalibrated(); - auto locationd_ecef = locationd_location.getPositionECEF(); - - locationd_valid = (locationd_pos.getValid() && locationd_orientation.getValid() && locationd_velocity.getValid() && locationd_ecef.getValid()); - if (locationd_valid) { - // Check std norm - auto pos_ecef_std = locationd_ecef.getStd(); - bool pos_accurate_enough = sqrt(pow(pos_ecef_std[0], 2) + pow(pos_ecef_std[1], 2) + pow(pos_ecef_std[2], 2)) < 100; - locationd_valid = pos_accurate_enough; - } - - if (locationd_valid) { - 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])); - } - } - - if (sm.updated("navRoute") && sm["navRoute"].getNavRoute().getCoordinates().size()) { - auto nav_dest = coordinate_from_param("NavDestination"); - bool allow_open = std::exchange(last_valid_nav_dest, nav_dest) != nav_dest && - nav_dest && !isVisible(); - qWarning() << "Got new navRoute from navd. Opening map:" << allow_open; - - // Show map on destination set/change - if (allow_open) { - emit requestSettings(false); - emit requestVisible(true); - } - } - - loaded_once = loaded_once || (m_map && m_map->isFullyLoaded()); - if (!loaded_once) { - setError(tr("Map Loading")); - return; - } - initLayers(); - - if (!locationd_valid) { - setError(tr("Waiting for GPS")); - } else if (routing_problem) { - setError(tr("Waiting for route")); - } else { - setError(""); - } - - if (locationd_valid) { - // Update current location marker - auto point = coordinate_to_collection(*last_position); - QMapLibre::Feature feature1(QMapLibre::Feature::PointType, point, {}, {}); - QVariantMap carPosSource; - carPosSource["type"] = "geojson"; - carPosSource["data"] = QVariant::fromValue(feature1); - m_map->updateSource("carPosSource", carPosSource); - - // Map bearing isn't updated when interacting, keep location marker up to date - if (last_bearing) { - m_map->setLayoutProperty("carPosLayer", "icon-rotate", *last_bearing - m_map->bearing()); - } - } - - if (interaction_counter == 0) { - if (last_position) m_map->setCoordinate(*last_position); - if (last_bearing) m_map->setBearing(*last_bearing); - m_map->setZoom(util::map_val(velocity_filter.x(), 0, 30, MAX_ZOOM, MIN_ZOOM)); - } else { - interaction_counter--; - } - - if (sm.updated("navInstruction")) { - // an invalid navInstruction packet with a nav destination is only possible if: - // - API exception/no internet - // - route response is empty - // - any time navd is waiting for recompute_countdown - routing_problem = !sm.valid("navInstruction") && coordinate_from_param("NavDestination").has_value(); - - if (sm.valid("navInstruction")) { - auto i = sm["navInstruction"].getNavInstruction(); - map_eta->updateETA(i.getTimeRemaining(), i.getTimeRemainingTypical(), i.getDistanceRemaining()); - - if (locationd_valid) { - m_map->setPitch(MAX_PITCH); // TODO: smooth pitching based on maneuver distance - map_instructions->updateInstructions(i); - } - } else { - clearRoute(); - } - } - - if (sm.rcv_frame("navRoute") != route_rcv_frame) { - qWarning() << "Updating navLayer with new route"; - auto route = sm["navRoute"].getNavRoute(); - auto route_points = capnp_coordinate_list_to_collection(route.getCoordinates()); - QMapLibre::Feature feature(QMapLibre::Feature::LineStringType, route_points, {}, {}); - QVariantMap navSource; - navSource["type"] = "geojson"; - navSource["data"] = QVariant::fromValue(feature); - m_map->updateSource("navSource", navSource); - m_map->setLayoutProperty("navLayer", "visibility", "visible"); - - route_rcv_frame = sm.rcv_frame("navRoute"); - updateDestinationMarker(); - } -} - -void MapWindow::setError(const QString &err_str) { - if (err_str != error->text()) { - error->setText(err_str); - error->setVisible(!err_str.isEmpty()); - if (!err_str.isEmpty()) map_instructions->setVisible(false); - } -} - -void MapWindow::resizeGL(int w, int h) { - m_map->resize(size() / MAP_SCALE); - map_overlay->setFixedSize(width(), height()); -} - -void MapWindow::initializeGL() { - 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(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(), &QMapLibre::Map::mapChanged, [=](QMapLibre::Map::MapChange change) { - // set global animation duration to 0 ms so visibility changes are instant - if (change == QMapLibre::Map::MapChange::MapChangeDidFinishLoadingStyle) { - m_map->setTransitionOptions(0, 0); - } - if (change == QMapLibre::Map::MapChange::MapChangeDidFinishLoadingMap) { - loaded_once = true; - } - }); - - 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()); - }); -} - -void MapWindow::paintGL() { - if (!isVisible() || m_map.isNull()) return; - m_map->render(); -} - -void MapWindow::clearRoute() { - if (!m_map.isNull()) { - m_map->setLayoutProperty("navLayer", "visibility", "none"); - m_map->setPitch(MIN_PITCH); - updateDestinationMarker(); - } - - map_instructions->setVisible(false); - map_eta->setVisible(false); - last_valid_nav_dest = std::nullopt; -} - -void MapWindow::mousePressEvent(QMouseEvent *ev) { - m_lastPos = ev->localPos(); - ev->accept(); -} - -void MapWindow::mouseDoubleClickEvent(QMouseEvent *ev) { - if (last_position) m_map->setCoordinate(*last_position); - if (last_bearing) m_map->setBearing(*last_bearing); - m_map->setZoom(util::map_val(velocity_filter.x(), 0, 30, MAX_ZOOM, MIN_ZOOM)); - update(); - - interaction_counter = 0; -} - -void MapWindow::mouseMoveEvent(QMouseEvent *ev) { - QPointF delta = ev->localPos() - m_lastPos; - - if (!delta.isNull()) { - interaction_counter = INTERACTION_TIMEOUT; - m_map->moveBy(delta / MAP_SCALE); - update(); - } - - m_lastPos = ev->localPos(); - ev->accept(); -} - -void MapWindow::wheelEvent(QWheelEvent *ev) { - if (ev->orientation() == Qt::Horizontal) { - return; - } - - float factor = ev->delta() / 1200.; - if (ev->delta() < 0) { - factor = factor > -1 ? factor : 1 / factor; - } - - m_map->scaleBy(1 + factor, ev->pos() / MAP_SCALE); - update(); - - interaction_counter = INTERACTION_TIMEOUT; - ev->accept(); -} - -bool MapWindow::event(QEvent *event) { - if (event->type() == QEvent::Gesture) { - return gestureEvent(static_cast(event)); - } - - return QWidget::event(event); -} - -bool MapWindow::gestureEvent(QGestureEvent *event) { - if (QGesture *pinch = event->gesture(Qt::PinchGesture)) { - pinchTriggered(static_cast(pinch)); - } - return true; -} - -void MapWindow::pinchTriggered(QPinchGesture *gesture) { - QPinchGesture::ChangeFlags changeFlags = gesture->changeFlags(); - if (changeFlags & QPinchGesture::ScaleFactorChanged) { - // TODO: figure out why gesture centerPoint doesn't work - m_map->scaleBy(gesture->scaleFactor(), {width() / 2.0 / MAP_SCALE, height() / 2.0 / MAP_SCALE}); - update(); - interaction_counter = INTERACTION_TIMEOUT; - } -} - -void MapWindow::offroadTransition(bool offroad) { - if (offroad) { - clearRoute(); - routing_problem = false; - } else { - auto dest = coordinate_from_param("NavDestination"); - emit requestVisible(dest.has_value()); - } - last_bearing = {}; -} - -void MapWindow::updateDestinationMarker() { - auto nav_dest = coordinate_from_param("NavDestination"); - if (nav_dest.has_value()) { - auto point = coordinate_to_collection(*nav_dest); - QMapLibre::Feature feature(QMapLibre::Feature::PointType, point, {}, {}); - QVariantMap pinSource; - pinSource["type"] = "geojson"; - pinSource["data"] = QVariant::fromValue(feature); - m_map->updateSource("pinSource", pinSource); - m_map->setPaintProperty("pinLayer", "visibility", "visible"); - } else { - m_map->setPaintProperty("pinLayer", "visibility", "none"); - } -} diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h deleted file mode 100644 index 31a44f27b1ecec6..000000000000000 --- a/selfdrive/ui/qt/maps/map.h +++ /dev/null @@ -1,86 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/params.h" -#include "common/util.h" -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/maps/map_eta.h" -#include "selfdrive/ui/qt/maps/map_instructions.h" - -class MapWindow : public QOpenGLWidget { - Q_OBJECT - -public: - MapWindow(const QMapLibre::Settings &); - ~MapWindow(); - -private: - void initializeGL() final; - void paintGL() final; - void resizeGL(int w, int h) override; - - QMapLibre::Settings m_settings; - QScopedPointer m_map; - - void initLayers(); - - void mousePressEvent(QMouseEvent *ev) final; - void mouseDoubleClickEvent(QMouseEvent *ev) final; - void mouseMoveEvent(QMouseEvent *ev) final; - void wheelEvent(QWheelEvent *ev) final; - bool event(QEvent *event) final; - bool gestureEvent(QGestureEvent *event); - void pinchTriggered(QPinchGesture *gesture); - void setError(const QString &err_str); - - bool loaded_once = false; - bool prev_time_valid = true; - - // Panning - QPointF m_lastPos; - int interaction_counter = 0; - - // Position - std::optional last_valid_nav_dest; - std::optional last_position; - std::optional last_bearing; - FirstOrderFilter velocity_filter; - bool locationd_valid = false; - bool routing_problem = false; - - QWidget *map_overlay; - QLabel *error; - MapInstructions* map_instructions; - MapETA* map_eta; - - void clearRoute(); - void updateDestinationMarker(); - uint64_t route_rcv_frame = 0; - -private slots: - void updateState(const UIState &s); - -public slots: - void offroadTransition(bool offroad); - -signals: - void requestVisible(bool visible); - void requestSettings(bool settings); -}; diff --git a/selfdrive/ui/qt/maps/map_eta.cc b/selfdrive/ui/qt/maps/map_eta.cc deleted file mode 100644 index 0eb77e36ce6773b..000000000000000 --- a/selfdrive/ui/qt/maps/map_eta.cc +++ /dev/null @@ -1,59 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_eta.h" - -#include -#include - -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/ui/ui.h" - -const float MANEUVER_TRANSITION_THRESHOLD = 10; - -MapETA::MapETA(QWidget *parent) : QWidget(parent) { - setVisible(false); - setAttribute(Qt::WA_TranslucentBackground); - eta_doc.setUndoRedoEnabled(false); - eta_doc.setDefaultStyleSheet("body {font-family:Inter;font-size:70px;color:white;} b{font-weight:600;} td{padding:0 3px;}"); -} - -void MapETA::paintEvent(QPaintEvent *event) { - if (!eta_doc.isEmpty()) { - QPainter p(this); - p.setRenderHint(QPainter::Antialiasing); - p.setPen(Qt::NoPen); - 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); - eta_doc.drawContents(&p); - } -} - -void MapETA::updateETA(float s, float s_typical, float d) { - // ETA - auto eta_t = QDateTime::currentDateTime().addSecs(s).time(); - auto eta = format_24h ? std::pair{eta_t.toString("HH:mm"), tr("eta")} - : std::pair{eta_t.toString("h:mm a").split(' ')[0], eta_t.toString("a")}; - - // Remaining time - auto remaining = s < 3600 ? std::pair{QString::number(int(s / 60)), tr("min")} - : std::pair{QString("%1:%2").arg((int)s / 3600).arg(((int)s % 3600) / 60, 2, 10, QLatin1Char('0')), tr("hr")}; - QString color = "#25DA6E"; - if (std::abs(s_typical) > 1e-5) { - if (s / s_typical > 1.5) { - color = "#DA3025"; - } else if (s / s_typical > 1.2) { - color = "#DAA725"; - } - } - - // Distance - auto distance = map_format_distance(d, uiState()->scene.is_metric); - - eta_doc.setHtml(QString(R"( - - )") - .arg(eta.first, eta.second, color, remaining.first, remaining.second, distance.first, distance.second)); - - setVisible(d >= MANEUVER_TRANSITION_THRESHOLD); - update(); -} diff --git a/selfdrive/ui/qt/maps/map_eta.h b/selfdrive/ui/qt/maps/map_eta.h deleted file mode 100644 index 6e59837de3d7461..000000000000000 --- a/selfdrive/ui/qt/maps/map_eta.h +++ /dev/null @@ -1,23 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "common/params.h" - -class MapETA : public QWidget { - Q_OBJECT - -public: - MapETA(QWidget * parent=nullptr); - void updateETA(float seconds, float seconds_typical, float distance); - -private: - void paintEvent(QPaintEvent *event) override; - void showEvent(QShowEvent *event) override { format_24h = param.getBool("NavSettingTime24h"); } - - bool format_24h = false; - QTextDocument eta_doc; - Params param; -}; diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc deleted file mode 100644 index 16923f7a435c1b3..000000000000000 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ /dev/null @@ -1,153 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_helpers.h" - -#include -#include -#include - -#include -#include - -#include "common/params.h" -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/api.h" - -QString get_mapbox_token() { - // Valid for 4 weeks since we can't swap tokens on the fly - return MAPBOX_TOKEN.isEmpty() ? CommaApi::create_jwt({}, 4 * 7 * 24 * 3600) : MAPBOX_TOKEN; -} - -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.setApiKey(get_mapbox_token()); - - return settings; -} - -QGeoCoordinate to_QGeoCoordinate(const QMapLibre::Coordinate &in) { - return QGeoCoordinate(in.first, in.second); -} - -QMapLibre::CoordinatesCollections model_to_collection( - const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, - const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, - const cereal::XYZTData::Reader &line){ - - Eigen::Vector3d ecef(positionECEF.getValue()[0], positionECEF.getValue()[1], positionECEF.getValue()[2]); - Eigen::Vector3d orient(calibratedOrientationECEF.getValue()[0], calibratedOrientationECEF.getValue()[1], calibratedOrientationECEF.getValue()[2]); - Eigen::Matrix3d ecef_from_local = euler2rot(orient); - - QMapLibre::Coordinates coordinates; - auto x = line.getX(); - auto y = line.getY(); - auto z = line.getZ(); - for (int i = 0; i < x.size(); i++) { - Eigen::Vector3d point_ecef = ecef_from_local * Eigen::Vector3d(x[i], y[i], z[i]) + ecef; - Geodetic point_geodetic = ecef2geodetic((ECEF){.x = point_ecef[0], .y = point_ecef[1], .z = point_ecef[2]}); - coordinates.push_back({point_geodetic.lat, point_geodetic.lon}); - } - - return {QMapLibre::CoordinatesCollection{coordinates}}; -} - -QMapLibre::CoordinatesCollections coordinate_to_collection(const QMapLibre::Coordinate &c) { - QMapLibre::Coordinates coordinates{c}; - return {QMapLibre::CoordinatesCollection{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 {QMapLibre::CoordinatesCollection{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 {QMapLibre::CoordinatesCollection{coordinates}}; -} - -QList polyline_to_coordinate_list(const QString &polylineString) { - QList path; - if (polylineString.isEmpty()) - return path; - - QByteArray data = polylineString.toLatin1(); - - bool parsingLatitude = true; - - int shift = 0; - int value = 0; - - QGeoCoordinate coord(0, 0); - - for (int i = 0; i < data.length(); ++i) { - unsigned char c = data.at(i) - 63; - - value |= (c & 0x1f) << shift; - shift += 5; - - // another chunk - if (c & 0x20) - continue; - - int diff = (value & 1) ? ~(value >> 1) : (value >> 1); - - if (parsingLatitude) { - coord.setLatitude(coord.latitude() + (double)diff/1e6); - } else { - coord.setLongitude(coord.longitude() + (double)diff/1e6); - path.append(coord); - } - - parsingLatitude = !parsingLatitude; - - value = 0; - shift = 0; - } - - return path; -} - -std::optional coordinate_from_param(const std::string ¶m) { - QString json_str = QString::fromStdString(Params().get(param)); - if (json_str.isEmpty()) return {}; - - QJsonDocument doc = QJsonDocument::fromJson(json_str.toUtf8()); - if (doc.isNull()) return {}; - - QJsonObject json = doc.object(); - if (json["latitude"].isDouble() && json["longitude"].isDouble()) { - QMapLibre::Coordinate coord(json["latitude"].toDouble(), json["longitude"].toDouble()); - return coord; - } else { - return {}; - } -} - -// return {distance, unit} -std::pair map_format_distance(float d, bool is_metric) { - auto round_distance = [](float d) -> QString { - return (d > 10) ? QString::number(std::nearbyint(d)) : QString::number(std::nearbyint(d * 10) / 10.0, 'f', 1); - }; - - d = std::max(d, 0.0f); - if (is_metric) { - return (d > 500) ? std::pair{round_distance(d / 1000), QObject::tr("km")} - : std::pair{QString::number(50 * std::nearbyint(d / 50)), QObject::tr("m")}; - } else { - float feet = d * METER_TO_FOOT; - return (feet > 500) ? std::pair{round_distance(d * METER_TO_MILE), QObject::tr("mi")} - : std::pair{QString::number(50 * std::nearbyint(d / 50)), QObject::tr("ft")}; - } -} diff --git a/selfdrive/ui/qt/maps/map_helpers.h b/selfdrive/ui/qt/maps/map_helpers.h deleted file mode 100644 index 0f4be674f056336..000000000000000 --- a/selfdrive/ui/qt/maps/map_helpers.h +++ /dev/null @@ -1,32 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include - -#include "common/util.h" -#include "common/transformations/coordinates.hpp" -#include "common/transformations/orientation.hpp" -#include "cereal/messaging/messaging.h" - -const QString MAPBOX_TOKEN = util::getenv("MAPBOX_TOKEN").c_str(); -const QString MAPS_HOST = util::getenv("MAPS_HOST", MAPBOX_TOKEN.isEmpty() ? "https://maps.comma.ai" : "https://api.mapbox.com").c_str(); -const QString MAPS_CACHE_PATH = "/data/mbgl-cache-navd.db"; - -QString get_mapbox_token(); -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); -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::pair map_format_distance(float d, bool is_metric); diff --git a/selfdrive/ui/qt/maps/map_instructions.cc b/selfdrive/ui/qt/maps/map_instructions.cc deleted file mode 100644 index ba8cb356bd1651d..000000000000000 --- a/selfdrive/ui/qt/maps/map_instructions.cc +++ /dev/null @@ -1,144 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_instructions.h" - -#include -#include - -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/ui/ui.h" - -const QString ICON_SUFFIX = ".png"; - -MapInstructions::MapInstructions(QWidget *parent) : QWidget(parent) { - is_rhd = Params().getBool("IsRhdDetected"); - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(11, UI_BORDER_SIZE, 11, 20); - - QHBoxLayout *top_layout = new QHBoxLayout; - top_layout->addWidget(icon_01 = new QLabel, 0, Qt::AlignTop); - - QVBoxLayout *right_layout = new QVBoxLayout; - right_layout->setContentsMargins(9, 9, 9, 0); - right_layout->addWidget(distance = new QLabel); - distance->setStyleSheet(R"(font-size: 90px;)"); - - right_layout->addWidget(primary = new QLabel); - primary->setStyleSheet(R"(font-size: 60px;)"); - primary->setWordWrap(true); - - right_layout->addWidget(secondary = new QLabel); - secondary->setStyleSheet(R"(font-size: 50px;)"); - secondary->setWordWrap(true); - - top_layout->addLayout(right_layout); - - main_layout->addLayout(top_layout); - main_layout->addLayout(lane_layout = new QHBoxLayout); - lane_layout->setAlignment(Qt::AlignHCenter); - lane_layout->setSpacing(10); - - setStyleSheet("color:white"); - QPalette pal = palette(); - pal.setColor(QPalette::Background, QColor(0, 0, 0, 150)); - setAutoFillBackground(true); - setPalette(pal); - - buildPixmapCache(); -} - -void MapInstructions::buildPixmapCache() { - QDir dir("../assets/navigation"); - for (QString fn : dir.entryList({"*" + ICON_SUFFIX}, QDir::Files)) { - QPixmap pm(dir.filePath(fn)); - QString key = fn.left(fn.size() - ICON_SUFFIX.length()); - pm = pm.scaledToWidth(200, Qt::SmoothTransformation); - - // Maneuver icons - pixmap_cache[key] = pm; - // lane direction icons - if (key.contains("turn_")) { - pixmap_cache["lane_" + key] = pm.scaled({125, 125}, Qt::IgnoreAspectRatio, Qt::SmoothTransformation); - } - - // for rhd, reflect direction and then flip - if (key.contains("_left")) { - pixmap_cache["rhd_" + key.replace("_left", "_right")] = pm.transformed(QTransform().scale(-1, 1)); - } else if (key.contains("_right")) { - pixmap_cache["rhd_" + key.replace("_right", "_left")] = pm.transformed(QTransform().scale(-1, 1)); - } - } -} - -void MapInstructions::updateInstructions(cereal::NavInstruction::Reader instruction) { - setUpdatesEnabled(false); - - // Show instruction text - QString primary_str = QString::fromStdString(instruction.getManeuverPrimaryText()); - QString secondary_str = QString::fromStdString(instruction.getManeuverSecondaryText()); - - primary->setText(primary_str); - secondary->setVisible(secondary_str.length() > 0); - secondary->setText(secondary_str); - - auto distance_str_pair = map_format_distance(instruction.getManeuverDistance(), uiState()->scene.is_metric); - distance->setText(QString("%1 %2").arg(distance_str_pair.first, distance_str_pair.second)); - - // Show arrow with direction - QString type = QString::fromStdString(instruction.getManeuverType()); - QString modifier = QString::fromStdString(instruction.getManeuverModifier()); - if (!type.isEmpty()) { - QString fn = "direction_" + type; - if (!modifier.isEmpty()) { - fn += "_" + modifier; - } - fn = fn.replace(' ', '_'); - bool rhd = is_rhd && (fn.contains("_left") || fn.contains("_right")); - icon_01->setPixmap(pixmap_cache[!rhd ? fn : "rhd_" + fn]); - icon_01->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); - icon_01->setVisible(true); - } else { - icon_01->setVisible(false); - } - - // Hide distance after arrival - distance->setVisible(type != "arrive" || instruction.getManeuverDistance() > 0); - - // Show lanes - auto lanes = instruction.getLanes(); - for (int i = 0; i < lanes.size(); ++i) { - bool active = lanes[i].getActive(); - const auto active_direction = lanes[i].getActiveDirection(); - - // TODO: Make more images based on active direction and combined directions - QString fn = "lane_direction_"; - - // active direction has precedence - if (active && active_direction != cereal::NavInstruction::Direction::NONE) { - fn += "turn_" + DIRECTIONS[active_direction]; - } else { - for (auto const &direction : lanes[i].getDirections()) { - if (direction != cereal::NavInstruction::Direction::NONE) { - fn += "turn_" + DIRECTIONS[direction]; - break; - } - } - } - - if (!active) { - fn += "_inactive"; - } - - QLabel *label = (i < lane_labels.size()) ? lane_labels[i] : lane_labels.emplace_back(new QLabel); - if (!label->parentWidget()) { - lane_layout->addWidget(label); - } - label->setPixmap(pixmap_cache[fn]); - label->setVisible(true); - } - - for (int i = lanes.size(); i < lane_labels.size(); ++i) { - lane_labels[i]->setVisible(false); - } - - setUpdatesEnabled(true); - setVisible(true); -} diff --git a/selfdrive/ui/qt/maps/map_instructions.h b/selfdrive/ui/qt/maps/map_instructions.h deleted file mode 100644 index 06a943d27fb0a80..000000000000000 --- a/selfdrive/ui/qt/maps/map_instructions.h +++ /dev/null @@ -1,38 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include - -#include "cereal/gen/cpp/log.capnp.h" - -static std::map DIRECTIONS = { - {cereal::NavInstruction::Direction::NONE, "none"}, - {cereal::NavInstruction::Direction::LEFT, "left"}, - {cereal::NavInstruction::Direction::RIGHT, "right"}, - {cereal::NavInstruction::Direction::STRAIGHT, "straight"}, - {cereal::NavInstruction::Direction::SLIGHT_LEFT, "slight_left"}, - {cereal::NavInstruction::Direction::SLIGHT_RIGHT, "slight_right"}, -}; - -class MapInstructions : public QWidget { - Q_OBJECT - -private: - QLabel *distance; - QLabel *primary; - QLabel *secondary; - QLabel *icon_01; - QHBoxLayout *lane_layout; - bool is_rhd = false; - std::vector lane_labels; - QHash pixmap_cache; - -public: - MapInstructions(QWidget * parent=nullptr); - void buildPixmapCache(); - void updateInstructions(cereal::NavInstruction::Reader instruction); -}; diff --git a/selfdrive/ui/qt/maps/map_panel.cc b/selfdrive/ui/qt/maps/map_panel.cc deleted file mode 100644 index c4cc20e21d3a75e..000000000000000 --- a/selfdrive/ui/qt/maps/map_panel.cc +++ /dev/null @@ -1,43 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_panel.h" - -#include -#include - -#include "selfdrive/ui/qt/maps/map.h" -#include "selfdrive/ui/qt/maps/map_settings.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/ui.h" - -MapPanel::MapPanel(const QMapLibre::Settings &mapboxSettings, QWidget *parent) : QFrame(parent) { - content_stack = new QStackedLayout(this); - content_stack->setContentsMargins(0, 0, 0, 0); - - auto map = new MapWindow(mapboxSettings); - QObject::connect(uiState(), &UIState::offroadTransition, map, &MapWindow::offroadTransition); - QObject::connect(device(), &Device::interactiveTimeout, this, [=]() { - content_stack->setCurrentIndex(0); - }); - QObject::connect(map, &MapWindow::requestVisible, this, [=](bool visible) { - // when we show the map for a new route, signal HomeWindow to hide the sidebar - if (visible) { emit mapPanelRequested(); } - setVisible(visible); - }); - QObject::connect(map, &MapWindow::requestSettings, this, [=](bool settings) { - content_stack->setCurrentIndex(settings ? 1 : 0); - }); - content_stack->addWidget(map); - - auto settings = new MapSettings(true, parent); - QObject::connect(settings, &MapSettings::closeSettings, this, [=]() { - content_stack->setCurrentIndex(0); - }); - content_stack->addWidget(settings); -} - -void MapPanel::toggleMapSettings() { - // show settings if not visible, then toggle between map and settings - int new_index = isVisible() ? (1 - content_stack->currentIndex()) : 1; - content_stack->setCurrentIndex(new_index); - emit mapPanelRequested(); - show(); -} diff --git a/selfdrive/ui/qt/maps/map_panel.h b/selfdrive/ui/qt/maps/map_panel.h deleted file mode 100644 index 190bb634464db5c..000000000000000 --- a/selfdrive/ui/qt/maps/map_panel.h +++ /dev/null @@ -1,21 +0,0 @@ -#pragma once - -#include -#include -#include - -class MapPanel : public QFrame { - Q_OBJECT - -public: - explicit MapPanel(const QMapLibre::Settings &settings, QWidget *parent = nullptr); - -signals: - void mapPanelRequested(); - -public slots: - void toggleMapSettings(); - -private: - QStackedLayout *content_stack; -}; diff --git a/selfdrive/ui/qt/maps/map_settings.cc b/selfdrive/ui/qt/maps/map_settings.cc deleted file mode 100644 index 4d655be36cd81fd..000000000000000 --- a/selfdrive/ui/qt/maps/map_settings.cc +++ /dev/null @@ -1,385 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_settings.h" - -#include - -#include -#include - -#include "common/util.h" -#include "selfdrive/ui/qt/request_repeater.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" - -static void swap(QJsonValueRef v1, QJsonValueRef v2) { std::swap(v1, v2); } - -static bool locationEqual(const QJsonValue &v1, const QJsonValue &v2) { - return v1["latitude"] == v2["latitude"] && v1["longitude"] == v2["longitude"]; -} - -static qint64 convertTimestampToEpoch(const QString ×tamp) { - QDateTime dt = QDateTime::fromString(timestamp, Qt::ISODate); - return dt.isValid() ? dt.toSecsSinceEpoch() : 0; -} - -MapSettings::MapSettings(bool closeable, QWidget *parent) : QFrame(parent) { - setContentsMargins(0, 0, 0, 0); - setAttribute(Qt::WA_NoMousePropagation); - - auto *frame = new QVBoxLayout(this); - frame->setContentsMargins(40, 40, 40, 0); - frame->setSpacing(0); - - auto *heading_frame = new QHBoxLayout; - heading_frame->setContentsMargins(0, 0, 0, 0); - heading_frame->setSpacing(32); - { - if (closeable) { - auto *close_btn = new QPushButton("←"); - close_btn->setStyleSheet(R"( - QPushButton { - color: #FFFFFF; - font-size: 100px; - padding-bottom: 8px; - border 1px grey solid; - border-radius: 70px; - background-color: #292929; - font-weight: 500; - } - QPushButton:pressed { - background-color: #3B3B3B; - } - )"); - close_btn->setFixedSize(140, 140); - QObject::connect(close_btn, &QPushButton::clicked, [=]() { emit closeSettings(); }); - // TODO: read map_on_left from ui state - heading_frame->addWidget(close_btn); - } - - auto *heading = new QVBoxLayout; - heading->setContentsMargins(0, 0, 0, 0); - heading->setSpacing(16); - { - auto *title = new QLabel(tr("NAVIGATION"), this); - title->setStyleSheet("color: #FFFFFF; font-size: 54px; font-weight: 600;"); - heading->addWidget(title); - - auto *subtitle = new QLabel(tr("Manage at connect.comma.ai"), this); - subtitle->setStyleSheet("color: #A0A0A0; font-size: 40px; font-weight: 300;"); - heading->addWidget(subtitle); - } - heading_frame->addLayout(heading, 1); - } - frame->addLayout(heading_frame); - frame->addSpacing(32); - - current_widget = new DestinationWidget(this); - QObject::connect(current_widget, &DestinationWidget::actionClicked, - []() { NavManager::instance()->setCurrentDestination({}); }); - frame->addWidget(current_widget); - frame->addSpacing(32); - - QWidget *destinations_container = new QWidget(this); - destinations_layout = new QVBoxLayout(destinations_container); - destinations_layout->setContentsMargins(0, 32, 0, 32); - destinations_layout->setSpacing(20); - destinations_layout->addWidget(home_widget = new DestinationWidget(this)); - destinations_layout->addWidget(work_widget = new DestinationWidget(this)); - QObject::connect(home_widget, &DestinationWidget::navigateTo, this, &MapSettings::navigateTo); - QObject::connect(work_widget, &DestinationWidget::navigateTo, this, &MapSettings::navigateTo); - destinations_layout->addStretch(); - - ScrollView *destinations_scroller = new ScrollView(destinations_container, this); - destinations_scroller->setFrameShape(QFrame::NoFrame); - frame->addWidget(destinations_scroller); - - setStyleSheet("MapSettings { background-color: #333333; }"); - QObject::connect(NavManager::instance(), &NavManager::updated, this, &MapSettings::refresh); -} - -void MapSettings::showEvent(QShowEvent *event) { - refresh(); -} - -void MapSettings::refresh() { - if (!isVisible()) return; - - setUpdatesEnabled(false); - - auto get_w = [this](int i) { - auto w = i < widgets.size() ? widgets[i] : widgets.emplace_back(new DestinationWidget); - if (!w->parentWidget()) { - destinations_layout->insertWidget(destinations_layout->count() - 1, w); - QObject::connect(w, &DestinationWidget::navigateTo, this, &MapSettings::navigateTo); - } - return w; - }; - - const auto current_dest = NavManager::instance()->currentDestination(); - if (!current_dest.isEmpty()) { - current_widget->set(current_dest, true); - } else { - current_widget->unset("", true); - } - home_widget->unset(NAV_FAVORITE_LABEL_HOME); - work_widget->unset(NAV_FAVORITE_LABEL_WORK); - - int n = 0; - for (auto location : NavManager::instance()->currentLocations()) { - DestinationWidget *w = nullptr; - auto dest = location.toObject(); - if (dest["save_type"].toString() == NAV_TYPE_FAVORITE) { - auto label = dest["label"].toString(); - if (label == NAV_FAVORITE_LABEL_HOME) w = home_widget; - if (label == NAV_FAVORITE_LABEL_WORK) w = work_widget; - } - w = w ? w : get_w(n++); - w->set(dest, false); - w->setVisible(!locationEqual(dest, current_dest)); - } - for (; n < widgets.size(); ++n) widgets[n]->setVisible(false); - - setUpdatesEnabled(true); -} - -void MapSettings::navigateTo(const QJsonObject &place) { - NavManager::instance()->setCurrentDestination(place); - emit closeSettings(); -} - -DestinationWidget::DestinationWidget(QWidget *parent) : QPushButton(parent) { - setContentsMargins(0, 0, 0, 0); - - auto *frame = new QHBoxLayout(this); - frame->setContentsMargins(32, 24, 32, 24); - frame->setSpacing(32); - - icon = new QLabel(this); - icon->setAlignment(Qt::AlignCenter); - icon->setFixedSize(96, 96); - icon->setObjectName("icon"); - frame->addWidget(icon); - - auto *inner_frame = new QVBoxLayout; - inner_frame->setContentsMargins(0, 0, 0, 0); - inner_frame->setSpacing(0); - { - title = new ElidedLabel(this); - title->setAttribute(Qt::WA_TransparentForMouseEvents); - inner_frame->addWidget(title); - - subtitle = new ElidedLabel(this); - subtitle->setAttribute(Qt::WA_TransparentForMouseEvents); - subtitle->setObjectName("subtitle"); - inner_frame->addWidget(subtitle); - } - frame->addLayout(inner_frame, 1); - - action = new QPushButton(this); - action->setFixedSize(96, 96); - action->setObjectName("action"); - action->setStyleSheet("font-size: 65px; font-weight: 600;"); - QObject::connect(action, &QPushButton::clicked, this, &QPushButton::clicked); - QObject::connect(action, &QPushButton::clicked, this, &DestinationWidget::actionClicked); - frame->addWidget(action); - - setFixedHeight(164); - setStyleSheet(R"( - DestinationWidget { background-color: #202123; border-radius: 10px; } - QLabel { color: #FFFFFF; font-size: 48px; font-weight: 400; } - #icon { background-color: #3B4356; border-radius: 48px; } - #subtitle { color: #9BA0A5; } - #action { border: none; border-radius: 48px; color: #FFFFFF; padding-bottom: 4px; } - - /* current destination */ - [current="true"] { background-color: #E8E8E8; } - [current="true"] QLabel { color: #000000; } - [current="true"] #icon { background-color: #42906B; } - [current="true"] #subtitle { color: #333333; } - [current="true"] #action { color: #202123; } - - /* no saved destination */ - [set="false"] QLabel { color: #9BA0A5; } - [current="true"][set="false"] QLabel { color: #A0000000; } - - /* pressed */ - [current="false"]:pressed { background-color: #18191B; } - [current="true"] #action:pressed { background-color: #D6D6D6; } - )"); - QObject::connect(this, &QPushButton::clicked, [this]() { if (!dest.isEmpty()) emit navigateTo(dest); }); -} - -void DestinationWidget::set(const QJsonObject &destination, bool current) { - if (dest == destination) return; - - dest = destination; - setProperty("current", current); - setProperty("set", true); - - auto icon_pixmap = current ? icons().directions : icons().recent; - auto title_text = destination["place_name"].toString(); - auto subtitle_text = destination["place_details"].toString(); - - if (destination["save_type"] == NAV_TYPE_FAVORITE) { - if (destination["label"] == NAV_FAVORITE_LABEL_HOME) { - icon_pixmap = icons().home; - subtitle_text = title_text + ", " + subtitle_text; - title_text = tr("Home"); - } else if (destination["label"] == NAV_FAVORITE_LABEL_WORK) { - icon_pixmap = icons().work; - subtitle_text = title_text + ", " + subtitle_text; - title_text = tr("Work"); - } else { - icon_pixmap = icons().favorite; - } - } - - icon->setPixmap(icon_pixmap); - - title->setText(title_text); - subtitle->setText(subtitle_text); - subtitle->setVisible(true); - - // TODO: use pixmap - action->setAttribute(Qt::WA_TransparentForMouseEvents, !current); - action->setText(current ? "×" : "→"); - action->setVisible(true); - - setStyleSheet(styleSheet()); -} - -void DestinationWidget::unset(const QString &label, bool current) { - dest = {}; - setProperty("current", current); - setProperty("set", false); - - if (label.isEmpty()) { - icon->setPixmap(icons().directions); - title->setText(tr("No destination set")); - } else { - QString title_text = label == NAV_FAVORITE_LABEL_HOME ? tr("home") : tr("work"); - icon->setPixmap(label == NAV_FAVORITE_LABEL_HOME ? icons().home : icons().work); - title->setText(tr("No %1 location set").arg(title_text)); - } - - subtitle->setVisible(false); - action->setVisible(false); - - setStyleSheet(styleSheet()); - setVisible(true); -} - -// singleton NavManager - -NavManager *NavManager::instance() { - static NavManager *request = new NavManager(qApp); - return request; -} - -NavManager::NavManager(QObject *parent) : QObject(parent) { - locations = QJsonDocument::fromJson(params.get("NavPastDestinations").c_str()).array(); - current_dest = QJsonDocument::fromJson(params.get("NavDestination").c_str()).object(); - if (auto dongle_id = getDongleId()) { - { - // Fetch favorite and recent locations - QString url = CommaApi::BASE_URL + "/v1/navigation/" + *dongle_id + "/locations"; - RequestRepeater *repeater = new RequestRepeater(this, url, "ApiCache_NavDestinations", 30, true); - QObject::connect(repeater, &RequestRepeater::requestDone, this, &NavManager::parseLocationsResponse); - } - { - auto param_watcher = new ParamWatcher(this); - QObject::connect(param_watcher, &ParamWatcher::paramChanged, this, &NavManager::updated); - - // Destination set while offline - QString url = CommaApi::BASE_URL + "/v1/navigation/" + *dongle_id + "/next"; - HttpRequest *deleter = new HttpRequest(this); - RequestRepeater *repeater = new RequestRepeater(this, url, "", 10, true); - QObject::connect(repeater, &RequestRepeater::requestDone, [=](const QString &resp, bool success) { - if (success && resp != "null") { - if (params.get("NavDestination").empty()) { - qWarning() << "Setting NavDestination from /next" << resp; - params.put("NavDestination", resp.toStdString()); - } else { - qWarning() << "Got location from /next, but NavDestination already set"; - } - // Send DELETE to clear destination server side - deleter->sendRequest(url, HttpRequest::Method::DELETE); - } - - // athena can set destination at any time - param_watcher->addParam("NavDestination"); - current_dest = QJsonDocument::fromJson(params.get("NavDestination").c_str()).object(); - emit updated(); - }); - } - } -} - -void NavManager::parseLocationsResponse(const QString &response, bool success) { - if (!success || response == prev_response) return; - - prev_response = response; - QJsonDocument doc = QJsonDocument::fromJson(response.trimmed().toUtf8()); - if (doc.isNull()) { - qWarning() << "JSON Parse failed on navigation locations" << response; - return; - } - - // set last activity time. - auto remote_locations = doc.array(); - for (QJsonValueRef loc : remote_locations) { - auto obj = loc.toObject(); - auto serverTime = convertTimestampToEpoch(obj["modified"].toString()); - obj.insert("time", qMax(serverTime, getLastActivity(obj))); - loc = obj; - } - - locations = remote_locations; - sortLocations(); - emit updated(); -} - -void NavManager::sortLocations() { - // Sort: alphabetical FAVORITES, and then most recent. - // We don't need to care about the ordering of HOME and WORK. DestinationWidget always displays them at the top. - std::stable_sort(locations.begin(), locations.end(), [](const QJsonValue &a, const QJsonValue &b) { - if (a["save_type"] == NAV_TYPE_FAVORITE || b["save_type"] == NAV_TYPE_FAVORITE) { - return (std::tuple(a["save_type"].toString(), a["place_name"].toString()) < - std::tuple(b["save_type"].toString(), b["place_name"].toString())); - } else { - return a["time"].toVariant().toLongLong() > b["time"].toVariant().toLongLong(); - } - }); - - write_param_future = std::async(std::launch::async, [destinations = QJsonArray(locations)]() { - Params().put("NavPastDestinations", QJsonDocument(destinations).toJson().toStdString()); - }); -} - -qint64 NavManager::getLastActivity(const QJsonObject &loc) const { - qint64 last_activity = 0; - auto it = std::find_if(locations.begin(), locations.end(), - [&loc](const QJsonValue &l) { return locationEqual(loc, l); }); - if (it != locations.end()) { - auto tm = it->toObject().value("time"); - if (!tm.isUndefined() && !tm.isNull()) { - last_activity = tm.toVariant().toLongLong(); - } - } - return last_activity; -} - -void NavManager::setCurrentDestination(const QJsonObject &loc) { - current_dest = loc; - if (!current_dest.isEmpty()) { - current_dest["time"] = QDateTime::currentSecsSinceEpoch(); - auto it = std::find_if(locations.begin(), locations.end(), - [&loc](const QJsonValue &l) { return locationEqual(loc, l); }); - if (it != locations.end()) { - *it = current_dest; - sortLocations(); - } - params.put("NavDestination", QJsonDocument(current_dest).toJson().toStdString()); - } else { - params.remove("NavDestination"); - } - emit updated(); -} diff --git a/selfdrive/ui/qt/maps/map_settings.h b/selfdrive/ui/qt/maps/map_settings.h deleted file mode 100644 index 0e151df4ad4ccd5..000000000000000 --- a/selfdrive/ui/qt/maps/map_settings.h +++ /dev/null @@ -1,102 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "common/params.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/controls.h" - -const QString NAV_TYPE_FAVORITE = "favorite"; -const QString NAV_TYPE_RECENT = "recent"; - -const QString NAV_FAVORITE_LABEL_HOME = "home"; -const QString NAV_FAVORITE_LABEL_WORK = "work"; - -class DestinationWidget; - -class NavManager : public QObject { - Q_OBJECT - -public: - static NavManager *instance(); - QJsonArray currentLocations() const { return locations; } - QJsonObject currentDestination() const { return current_dest; } - void setCurrentDestination(const QJsonObject &loc); - qint64 getLastActivity(const QJsonObject &loc) const; - -signals: - void updated(); - -private: - NavManager(QObject *parent); - void parseLocationsResponse(const QString &response, bool success); - void sortLocations(); - - Params params; - QString prev_response; - QJsonArray locations; - QJsonObject current_dest; - std::future write_param_future; -}; - -class MapSettings : public QFrame { - Q_OBJECT -public: - explicit MapSettings(bool closeable = false, QWidget *parent = nullptr); - void navigateTo(const QJsonObject &place); - -private: - void showEvent(QShowEvent *event) override; - void refresh(); - - QVBoxLayout *destinations_layout; - DestinationWidget *current_widget; - DestinationWidget *home_widget; - DestinationWidget *work_widget; - std::vector widgets; - -signals: - void closeSettings(); -}; - -class DestinationWidget : public QPushButton { - Q_OBJECT -public: - explicit DestinationWidget(QWidget *parent = nullptr); - void set(const QJsonObject &location, bool current = false); - void unset(const QString &label, bool current = false); - -signals: - void actionClicked(); - void navigateTo(const QJsonObject &destination); - -private: - struct NavIcons { - QPixmap home, work, favorite, recent, directions; - }; - - static NavIcons icons() { - static NavIcons nav_icons { - loadPixmap("../assets/navigation/icon_home.svg", {48, 48}), - loadPixmap("../assets/navigation/icon_work.svg", {48, 48}), - loadPixmap("../assets/navigation/icon_favorite.svg", {48, 48}), - loadPixmap("../assets/navigation/icon_recent.svg", {48, 48}), - loadPixmap("../assets/navigation/icon_directions.svg", {48, 48}), - }; - return nav_icons; - } - -private: - QLabel *icon, *title, *subtitle; - QPushButton *action; - QJsonObject dest; -}; diff --git a/selfdrive/ui/qt/network/networking.cc b/selfdrive/ui/qt/network/networking.cc index d7cdddff443a693..066dc3ca7ebbec3 100644 --- a/selfdrive/ui/qt/network/networking.cc +++ b/selfdrive/ui/qt/network/networking.cc @@ -6,7 +6,6 @@ #include #include -#include "selfdrive/ui/ui.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/widgets/controls.h" @@ -73,6 +72,11 @@ Networking::Networking(QWidget* parent, bool show_advanced) : QFrame(parent) { main_layout->setCurrentWidget(wifiScreen); } +void Networking::setPrimeType(PrimeState::Type type) { + an->setGsmVisible(type == PrimeState::PRIME_TYPE_NONE || type == PrimeState::PRIME_TYPE_LITE); + wifi->ipv4_forward = (type == PrimeState::PRIME_TYPE_NONE || type == PrimeState::PRIME_TYPE_LITE); +} + void Networking::refresh() { wifiWidget->refresh(); an->refresh(); @@ -145,10 +149,6 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid ipLabel = new LabelControl(tr("IP Address"), wifi->ipv4_address); list->addItem(ipLabel); - // SSH keys - list->addItem(new SshToggle()); - list->addItem(new SshControl()); - // Roaming toggle const bool roamingEnabled = params.getBool("GsmRoaming"); roamingToggle = new ToggleControl(tr("Enable Roaming"), "", "", roamingEnabled); @@ -204,17 +204,16 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid // Set initial config wifi->updateGsmSettings(roamingEnabled, QString::fromStdString(params.get("GsmApn")), metered); - connect(uiState(), &UIState::primeTypeChanged, this, [=](PrimeType prime_type) { - bool gsmVisible = prime_type == PrimeType::NONE || prime_type == PrimeType::LITE; - roamingToggle->setVisible(gsmVisible); - editApnButton->setVisible(gsmVisible); - meteredToggle->setVisible(gsmVisible); - }); - main_layout->addWidget(new ScrollView(list, this)); main_layout->addStretch(1); } +void AdvancedNetworking::setGsmVisible(bool visible) { + roamingToggle->setVisible(visible); + editApnButton->setVisible(visible); + meteredToggle->setVisible(visible); +} + void AdvancedNetworking::refresh() { ipLabel->setText(wifi->ipv4_address); tetheringToggle->setEnabled(true); diff --git a/selfdrive/ui/qt/network/networking.h b/selfdrive/ui/qt/network/networking.h index 9b6af005ea640c8..4fd604039b4ecaa 100644 --- a/selfdrive/ui/qt/network/networking.h +++ b/selfdrive/ui/qt/network/networking.h @@ -3,6 +3,7 @@ #include #include "selfdrive/ui/qt/network/wifi_manager.h" +#include "selfdrive/ui/qt/prime_state.h" #include "selfdrive/ui/qt/widgets/input.h" #include "selfdrive/ui/qt/widgets/ssh_keys.h" #include "selfdrive/ui/qt/widgets/toggle.h" @@ -56,6 +57,7 @@ class AdvancedNetworking : public QWidget { Q_OBJECT public: explicit AdvancedNetworking(QWidget* parent = 0, WifiManager* wifi = 0); + void setGsmVisible(bool visible); private: LabelControl* ipLabel; @@ -81,6 +83,7 @@ class Networking : public QFrame { public: explicit Networking(QWidget* parent = 0, bool show_advanced = true); + void setPrimeType(PrimeState::Type type); WifiManager* wifi = nullptr; private: diff --git a/selfdrive/ui/qt/network/wifi_manager.cc b/selfdrive/ui/qt/network/wifi_manager.cc index 717da47096913ef..fd9ee17078c86c3 100644 --- a/selfdrive/ui/qt/network/wifi_manager.cc +++ b/selfdrive/ui/qt/network/wifi_manager.cc @@ -2,10 +2,6 @@ #include -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/widgets/prime.h" - -#include "common/params.h" #include "common/swaglog.h" #include "selfdrive/ui/qt/util.h" @@ -445,9 +441,6 @@ void WifiManager::addTetheringConnection() { } void WifiManager::tetheringActivated(QDBusPendingCallWatcher *call) { - int prime_type = uiState()->primeType(); - int ipv4_forward = (prime_type == PrimeType::NONE || prime_type == PrimeType::LITE); - if (!ipv4_forward) { QTimer::singleShot(5000, this, [=] { qWarning() << "net.ipv4.ip_forward = 0"; @@ -455,6 +448,7 @@ void WifiManager::tetheringActivated(QDBusPendingCallWatcher *call) { }); } call->deleteLater(); + tethering_on = true; } void WifiManager::setTetheringEnabled(bool enabled) { @@ -472,6 +466,7 @@ void WifiManager::setTetheringEnabled(bool enabled) { } else { deactivateConnectionBySsid(tethering_ssid); + tethering_on = false; } } diff --git a/selfdrive/ui/qt/network/wifi_manager.h b/selfdrive/ui/qt/network/wifi_manager.h index 2f6a1829d785cd2..e5f79c5149bf3c1 100644 --- a/selfdrive/ui/qt/network/wifi_manager.h +++ b/selfdrive/ui/qt/network/wifi_manager.h @@ -42,6 +42,8 @@ class WifiManager : public QObject { QMap seenNetworks; QMap knownConnections; QString ipv4_address; + bool tethering_on = false; + bool ipv4_forward = false; explicit WifiManager(QObject* parent); void start(); diff --git a/selfdrive/ui/qt/offroad/developer_panel.cc b/selfdrive/ui/qt/offroad/developer_panel.cc new file mode 100644 index 000000000000000..bb11b3540471513 --- /dev/null +++ b/selfdrive/ui/qt/offroad/developer_panel.cc @@ -0,0 +1,36 @@ +#include + +#include "selfdrive/ui/qt/offroad/developer_panel.h" +#include "selfdrive/ui/qt/widgets/ssh_keys.h" +#include "selfdrive/ui/qt/widgets/controls.h" + +DeveloperPanel::DeveloperPanel(SettingsWindow *parent) : ListWidget(parent) { + // SSH keys + addItem(new SshToggle()); + addItem(new SshControl()); + + joystickToggle = new ParamControl("JoystickDebugMode", tr("Joystick Debug Mode"), "", ""); + QObject::connect(joystickToggle, &ParamControl::toggleFlipped, [=](bool state) { + params.putBool("LongitudinalManeuverMode", false); + longManeuverToggle->refresh(); + }); + addItem(joystickToggle); + + longManeuverToggle = new ParamControl("LongitudinalManeuverMode", tr("Longitudinal Maneuver Mode"), "", ""); + QObject::connect(longManeuverToggle, &ParamControl::toggleFlipped, [=](bool state) { + params.putBool("JoystickDebugMode", false); + joystickToggle->refresh(); + }); + addItem(longManeuverToggle); + + // Joystick and longitudinal maneuvers should be hidden on release branches + // also the toggles should be not available to change in onroad state + const bool is_release = params.getBool("IsReleaseBranch"); + QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { + for (auto btn : findChildren()) { + btn->setVisible(!is_release); + btn->setEnabled(offroad); + } + }); + +} diff --git a/selfdrive/ui/qt/offroad/developer_panel.h b/selfdrive/ui/qt/offroad/developer_panel.h new file mode 100644 index 000000000000000..9fcff1e97b8424b --- /dev/null +++ b/selfdrive/ui/qt/offroad/developer_panel.h @@ -0,0 +1,14 @@ +#pragma once + +#include "selfdrive/ui/qt/offroad/settings.h" + +class DeveloperPanel : public ListWidget { + Q_OBJECT +public: + explicit DeveloperPanel(SettingsWindow *parent); + +private: + Params params; + ParamControl* joystickToggle; + ParamControl* longManeuverToggle; +}; diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index df9bb246510cfb9..a8d3151627be110 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -5,28 +5,7 @@ #include "selfdrive/ui/qt/util.h" -const int FACE_IMG_SIZE = 130; - -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 DriverViewWindow::showEvent(QShowEvent* event) { - params.putBool("IsDriverViewEnabled", true); - device()->resetInteractiveTimeout(60); - CameraWidget::showEvent(event); -} - -void DriverViewWindow::hideEvent(QHideEvent* event) { - params.putBool("IsDriverViewEnabled", false); - stopVipcThread(); - CameraWidget::hideEvent(event); +DriverViewWindow::DriverViewWindow(QWidget* parent) : CameraWidget("camerad", VISION_STREAM_DRIVER, parent) { } void DriverViewWindow::paintGL() { @@ -68,10 +47,35 @@ void DriverViewWindow::paintGL() { p.drawRoundedRect(fbox_x - box_size / 2, fbox_y - box_size / 2, box_size, box_size, 35.0, 35.0); } - // icon - const int img_offset = 60; - const int img_x = is_rhd ? rect().right() - FACE_IMG_SIZE - img_offset : rect().left() + img_offset; - const int img_y = rect().bottom() - FACE_IMG_SIZE - img_offset; - p.setOpacity(face_detected ? 1.0 : 0.2); - p.drawPixmap(img_x, img_y, face_img); + driver_monitor.updateState(*uiState()); + driver_monitor.draw(p, rect()); +} + +mat4 DriverViewWindow::calcFrameMatrix() { + const float driver_view_ratio = 2.0; + const float yscale = stream_height * driver_view_ratio / stream_width; + const float xscale = yscale * glHeight() / glWidth() * stream_width / stream_height; + return mat4{{ + xscale, 0.0, 0.0, 0.0, + 0.0, yscale, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; +} + +DriverViewDialog::DriverViewDialog(QWidget *parent) : DialogBase(parent) { + Params().putBool("IsDriverViewEnabled", true); + device()->resetInteractiveTimeout(60); + + QVBoxLayout *main_layout = new QVBoxLayout(this); + main_layout->setContentsMargins(0, 0, 0, 0); + auto camera = new DriverViewWindow(this); + main_layout->addWidget(camera); + QObject::connect(camera, &DriverViewWindow::clicked, this, &DialogBase::accept); + QObject::connect(device(), &Device::interactiveTimeout, this, &DialogBase::accept); +} + +void DriverViewDialog::done(int r) { + Params().putBool("IsDriverViewEnabled", false); + QDialog::done(r); } diff --git a/selfdrive/ui/qt/offroad/driverview.h b/selfdrive/ui/qt/offroad/driverview.h index 155e4ede32073d3..10a97c1da8a5b59 100644 --- a/selfdrive/ui/qt/offroad/driverview.h +++ b/selfdrive/ui/qt/offroad/driverview.h @@ -1,21 +1,21 @@ #pragma once #include "selfdrive/ui/qt/widgets/cameraview.h" +#include "selfdrive/ui/qt/onroad/driver_monitoring.h" +#include "selfdrive/ui/qt/widgets/input.h" class DriverViewWindow : public CameraWidget { Q_OBJECT - public: explicit DriverViewWindow(QWidget *parent); - -signals: - void done(); - -protected: - void showEvent(QShowEvent *event) override; - void hideEvent(QHideEvent *event) override; void paintGL() override; + mat4 calcFrameMatrix() override; + DriverMonitorRenderer driver_monitor; +}; - Params params; - QPixmap face_img; +class DriverViewDialog : public DialogBase { + Q_OBJECT +public: + DriverViewDialog(QWidget *parent); + void done(int r) override; }; diff --git a/selfdrive/ui/qt/offroad/onboarding.cc b/selfdrive/ui/qt/offroad/onboarding.cc index b1219055fd07aec..bae7e3bdf31ef9a 100644 --- a/selfdrive/ui/qt/offroad/onboarding.cc +++ b/selfdrive/ui/qt/offroad/onboarding.cc @@ -4,8 +4,7 @@ #include #include -#include -#include +#include #include #include @@ -13,6 +12,7 @@ #include "common/params.h" #include "selfdrive/ui/qt/util.h" #include "selfdrive/ui/qt/widgets/input.h" +#include "selfdrive/ui/qt/widgets/scrollview.h" TrainingGuide::TrainingGuide(QWidget *parent) : QFrame(parent) { setAttribute(Qt::WA_OpaquePaintEvent); @@ -98,25 +98,17 @@ void TermsPage::showEvent(QShowEvent *event) { title->setStyleSheet("font-size: 90px; font-weight: 600;"); main_layout->addWidget(title); - main_layout->addSpacing(30); - - QQuickWidget *text = new QQuickWidget(this); - text->setResizeMode(QQuickWidget::SizeRootObjectToView); - text->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); - text->setAttribute(Qt::WA_AlwaysStackOnTop); - text->setClearColor(QColor("#1B1B1B")); - - QString text_view = util::read_file("../assets/offroad/tc.html").c_str(); - text->rootContext()->setContextProperty("text_view", text_view); - - text->setSource(QUrl::fromLocalFile("qt/offroad/text_view.qml")); + QLabel *text = new QLabel(this); + text->setTextFormat(Qt::RichText); + text->setWordWrap(true); + text->setText(QString::fromStdString(util::read_file("../assets/offroad/tc.html"))); + text->setStyleSheet("font-size:50px; font-weight: 200; color: #C9C9C9; background-color:#1B1B1B; padding:50px 50px;"); + ScrollView *scroll = new ScrollView(text, this); - main_layout->addWidget(text, 1); + main_layout->addSpacing(30); + main_layout->addWidget(scroll); main_layout->addSpacing(50); - QObject *obj = (QObject*)text->rootObject(); - QObject::connect(obj, SIGNAL(scroll()), SLOT(enableAccept())); - QHBoxLayout* buttons = new QHBoxLayout; buttons->setMargin(0); buttons->setSpacing(45); @@ -141,6 +133,12 @@ void TermsPage::showEvent(QShowEvent *event) { )"); buttons->addWidget(accept_btn); QObject::connect(accept_btn, &QPushButton::clicked, this, &TermsPage::acceptedTerms); + QScrollBar *scroll_bar = scroll->verticalScrollBar(); + connect(scroll_bar, &QScrollBar::valueChanged, this, [this, scroll_bar](int value) { + if (value == scroll_bar->maximum()) { + enableAccept(); + } + }); } void TermsPage::enableAccept() { diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 5aa33974ac7b609..d4aab53f5afcb68 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -8,12 +8,13 @@ #include "common/watchdog.h" #include "common/util.h" +#include "selfdrive/ui/qt/offroad/driverview.h" #include "selfdrive/ui/qt/network/networking.h" #include "selfdrive/ui/qt/offroad/settings.h" #include "selfdrive/ui/qt/qt_window.h" #include "selfdrive/ui/qt/widgets/prime.h" #include "selfdrive/ui/qt/widgets/scrollview.h" -#include "selfdrive/ui/qt/widgets/ssh_keys.h" +#include "selfdrive/ui/qt/offroad/developer_panel.h" TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { // param, title, desc, icon @@ -22,7 +23,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { "OpenpilotEnabledToggle", tr("Enable openpilot"), tr("Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off."), - "../assets/offroad/icon_openpilot.png", + "../assets/img_chffr_wheel.png", }, { "ExperimentalLongitudinalEnabled", @@ -51,6 +52,12 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { tr("Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h)."), "../assets/offroad/icon_warning.png", }, + { + "AlwaysOnDM", + tr("Always-On Driver Monitoring"), + tr("Enable driver monitoring even when openpilot is not engaged."), + "../assets/offroad/icon_monitoring.png", + }, { "RecordFront", tr("Record and Upload Driver Camera"), @@ -63,20 +70,6 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { tr("Display speed in km/h instead of mph."), "../assets/offroad/icon_metric.png", }, -#ifdef ENABLE_MAPS - { - "NavSettingTime24h", - tr("Show ETA in 24h Format"), - tr("Use 24h format instead of am/pm"), - "../assets/offroad/icon_metric.png", - }, - { - "NavSettingLeftSide", - tr("Show Map on Left Side of UI"), - tr("Show map on left side when in split screen view."), - "../assets/offroad/icon_road.png", - }, -#endif }; @@ -119,8 +112,8 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { void TogglesPanel::updateState(const UIState &s) { const SubMaster &sm = *(s.sm); - if (sm.updated("controlsState")) { - auto personality = sm["controlsState"].getControlsState().getPersonality(); + if (sm.updated("selfdriveState")) { + auto personality = sm["selfdriveState"].getSelfdriveState().getPersonality(); if (personality != s.scene.personality && s.scene.started && isVisible()) { long_personality_setting->setCheckedButton(static_cast(personality)); } @@ -212,7 +205,12 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { auto dcamBtn = new ButtonControl(tr("Driver Camera"), tr("PREVIEW"), tr("Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)")); - connect(dcamBtn, &ButtonControl::clicked, [=]() { emit showDriverView(); }); + connect(dcamBtn, &ButtonControl::clicked, [this, dcamBtn]() { + dcamBtn->setEnabled(false); + DriverViewDialog driver_view(this); + driver_view.exec(); + dcamBtn->setEnabled(true); + }); addItem(dcamBtn); auto resetCalibBtn = new ButtonControl(tr("Reset Calibration"), tr("RESET"), ""); @@ -255,8 +253,8 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { }); addItem(translateBtn); - QObject::connect(uiState(), &UIState::primeTypeChanged, [this] (PrimeType type) { - pair_device->setVisible(type == PrimeType::UNPAIRED); + QObject::connect(uiState()->prime_state, &PrimeState::changed, [this] (PrimeState::Type type) { + pair_device->setVisible(type == PrimeState::PRIME_TYPE_UNPAIRED); }); QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { for (auto btn : findChildren()) { @@ -343,11 +341,6 @@ void DevicePanel::poweroff() { } } -void DevicePanel::showEvent(QShowEvent *event) { - pair_device->setVisible(uiState()->primeType() == PrimeType::UNPAIRED); - ListWidget::showEvent(event); -} - void SettingsWindow::showEvent(QShowEvent *event) { setCurrentPanel(0); } @@ -389,16 +382,19 @@ SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { // setup panels DevicePanel *device = new DevicePanel(this); QObject::connect(device, &DevicePanel::reviewTrainingGuide, this, &SettingsWindow::reviewTrainingGuide); - QObject::connect(device, &DevicePanel::showDriverView, this, &SettingsWindow::showDriverView); TogglesPanel *toggles = new TogglesPanel(this); QObject::connect(this, &SettingsWindow::expandToggleDescription, toggles, &TogglesPanel::expandToggleDescription); + auto networking = new Networking(this); + QObject::connect(uiState()->prime_state, &PrimeState::changed, networking, &Networking::setPrimeType); + QList> panels = { {tr("Device"), device}, - {tr("Network"), new Networking(this)}, + {tr("Network"), networking}, {tr("Toggles"), toggles}, {tr("Software"), new SoftwarePanel(this)}, + {tr("Developer"), new DeveloperPanel(this)}, }; nav_btns = new QButtonGroup(this); diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index 35a044bdd20f1e2..de0528ee0a62b4f 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -28,7 +28,6 @@ class SettingsWindow : public QFrame { signals: void closeSettings(); void reviewTrainingGuide(); - void showDriverView(); void expandToggleDescription(const QString ¶m); private: @@ -42,11 +41,9 @@ class DevicePanel : public ListWidget { Q_OBJECT public: explicit DevicePanel(SettingsWindow *parent); - void showEvent(QShowEvent *event) override; signals: void reviewTrainingGuide(); - void showDriverView(); private slots: void poweroff(); diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc index c8245205ce8b5d5..194b723fc9d380c 100644 --- a/selfdrive/ui/qt/offroad/software_settings.cc +++ b/selfdrive/ui/qt/offroad/software_settings.cc @@ -54,7 +54,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { connect(targetBranchBtn, &ButtonControl::clicked, [=]() { auto current = params.get("GitBranch"); QStringList branches = QString::fromStdString(params.get("UpdaterAvailableBranches")).split(","); - for (QString b : {current.c_str(), "devel-staging", "devel", "nightly", "master-ci", "master"}) { + for (QString b : {current.c_str(), "devel-staging", "devel", "nightly", "nightly-dev", "master-ci", "master"}) { auto i = branches.indexOf(b); if (i >= 0) { branches.removeAt(i); diff --git a/selfdrive/ui/qt/offroad/text_view.qml b/selfdrive/ui/qt/offroad/text_view.qml deleted file mode 100644 index 10b423bacbd09b1..000000000000000 --- a/selfdrive/ui/qt/offroad/text_view.qml +++ /dev/null @@ -1,47 +0,0 @@ -import QtQuick 2.0 - -Item { - id: root - signal scroll() - - Flickable { - id: flickArea - objectName: "flickArea" - anchors.fill: parent - contentHeight: helpText.height - contentWidth: width - (leftMargin + rightMargin) - bottomMargin: 50 - topMargin: 50 - rightMargin: 50 - leftMargin: 50 - flickableDirection: Flickable.VerticalFlick - flickDeceleration: 7500.0 - maximumFlickVelocity: 10000.0 - pixelAligned: true - - onAtYEndChanged: root.scroll() - - Text { - id: helpText - width: flickArea.contentWidth - font.family: "Inter" - font.weight: "Light" - font.pixelSize: 50 - textFormat: Text.RichText - color: "#C9C9C9" - wrapMode: Text.Wrap - text: text_view - } - } - - Rectangle { - id: scrollbar - anchors.right: flickArea.right - anchors.rightMargin: 20 - y: flickArea.topMargin + flickArea.visibleArea.yPosition * (flickArea.height - flickArea.bottomMargin - flickArea.topMargin) - width: 12 - radius: 6 - height: flickArea.visibleArea.heightRatio * (flickArea.height - flickArea.bottomMargin - flickArea.topMargin) - color: "#808080" - } -} diff --git a/selfdrive/ui/qt/onroad/alerts.cc b/selfdrive/ui/qt/onroad/alerts.cc index 0235c5ff424a8db..0236e20f1684764 100644 --- a/selfdrive/ui/qt/onroad/alerts.cc +++ b/selfdrive/ui/qt/onroad/alerts.cc @@ -19,35 +19,35 @@ void OnroadAlerts::clear() { } OnroadAlerts::Alert OnroadAlerts::getAlert(const SubMaster &sm, uint64_t started_frame) { - const cereal::ControlsState::Reader &cs = sm["controlsState"].getControlsState(); - const uint64_t controls_frame = sm.rcv_frame("controlsState"); + const cereal::SelfdriveState::Reader &ss = sm["selfdriveState"].getSelfdriveState(); + const uint64_t selfdrive_frame = sm.rcv_frame("selfdriveState"); Alert a = {}; - if (controls_frame >= started_frame) { // Don't get old alert. - a = {cs.getAlertText1().cStr(), cs.getAlertText2().cStr(), - cs.getAlertType().cStr(), cs.getAlertSize(), cs.getAlertStatus()}; + if (selfdrive_frame >= started_frame) { // Don't get old alert. + a = {ss.getAlertText1().cStr(), ss.getAlertText2().cStr(), + ss.getAlertType().cStr(), ss.getAlertSize(), ss.getAlertStatus()}; } - if (!sm.updated("controlsState") && (sm.frame - started_frame) > 5 * UI_FREQ) { - const int CONTROLS_TIMEOUT = 5; - const int controls_missing = (nanos_since_boot() - sm.rcv_time("controlsState")) / 1e9; + if (!sm.updated("selfdriveState") && (sm.frame - started_frame) > 5 * UI_FREQ) { + const int SELFDRIVE_STATE_TIMEOUT = 5; + const int ss_missing = (nanos_since_boot() - sm.rcv_time("selfdriveState")) / 1e9; - // Handle controls timeout - if (controls_frame < started_frame) { - // car is started, but controlsState hasn't been seen at all - a = {tr("openpilot Unavailable"), tr("Waiting for controls to start"), - "controlsWaiting", cereal::ControlsState::AlertSize::MID, - cereal::ControlsState::AlertStatus::NORMAL}; - } else if (controls_missing > CONTROLS_TIMEOUT && !Hardware::PC()) { - // car is started, but controls is lagging or died - if (cs.getEnabled() && (controls_missing - CONTROLS_TIMEOUT) < 10) { - a = {tr("TAKE CONTROL IMMEDIATELY"), tr("Controls Unresponsive"), - "controlsUnresponsive", cereal::ControlsState::AlertSize::FULL, - cereal::ControlsState::AlertStatus::CRITICAL}; + // Handle selfdrive timeout + if (selfdrive_frame < started_frame) { + // car is started, but selfdriveState hasn't been seen at all + a = {tr("openpilot Unavailable"), tr("Waiting to start"), + "selfdriveWaiting", cereal::SelfdriveState::AlertSize::MID, + cereal::SelfdriveState::AlertStatus::NORMAL}; + } else if (ss_missing > SELFDRIVE_STATE_TIMEOUT && !Hardware::PC()) { + // car is started, but selfdrive is lagging or died + if (ss.getEnabled() && (ss_missing - SELFDRIVE_STATE_TIMEOUT) < 10) { + a = {tr("TAKE CONTROL IMMEDIATELY"), tr("System Unresponsive"), + "selfdriveUnresponsive", cereal::SelfdriveState::AlertSize::FULL, + cereal::SelfdriveState::AlertStatus::CRITICAL}; } else { - a = {tr("Controls Unresponsive"), tr("Reboot Device"), - "controlsUnresponsivePermanent", cereal::ControlsState::AlertSize::MID, - cereal::ControlsState::AlertStatus::NORMAL}; + a = {tr("System Unresponsive"), tr("Reboot Device"), + "selfdriveUnresponsivePermanent", cereal::SelfdriveState::AlertSize::MID, + cereal::SelfdriveState::AlertStatus::NORMAL}; } } } @@ -55,19 +55,19 @@ OnroadAlerts::Alert OnroadAlerts::getAlert(const SubMaster &sm, uint64_t started } void OnroadAlerts::paintEvent(QPaintEvent *event) { - if (alert.size == cereal::ControlsState::AlertSize::NONE) { + if (alert.size == cereal::SelfdriveState::AlertSize::NONE) { return; } - static std::map alert_heights = { - {cereal::ControlsState::AlertSize::SMALL, 271}, - {cereal::ControlsState::AlertSize::MID, 420}, - {cereal::ControlsState::AlertSize::FULL, height()}, + static std::map alert_heights = { + {cereal::SelfdriveState::AlertSize::SMALL, 271}, + {cereal::SelfdriveState::AlertSize::MID, 420}, + {cereal::SelfdriveState::AlertSize::FULL, height()}, }; int h = alert_heights[alert.size]; int margin = 40; int radius = 30; - if (alert.size == cereal::ControlsState::AlertSize::FULL) { + if (alert.size == cereal::SelfdriveState::AlertSize::FULL) { margin = 0; radius = 0; } @@ -94,15 +94,15 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) { const QPoint c = r.center(); p.setPen(QColor(0xff, 0xff, 0xff)); p.setRenderHint(QPainter::TextAntialiasing); - if (alert.size == cereal::ControlsState::AlertSize::SMALL) { + if (alert.size == cereal::SelfdriveState::AlertSize::SMALL) { p.setFont(InterFont(74, QFont::DemiBold)); p.drawText(r, Qt::AlignCenter, alert.text1); - } else if (alert.size == cereal::ControlsState::AlertSize::MID) { + } else if (alert.size == cereal::SelfdriveState::AlertSize::MID) { p.setFont(InterFont(88, QFont::Bold)); p.drawText(QRect(0, c.y() - 125, width(), 150), Qt::AlignHCenter | Qt::AlignTop, alert.text1); p.setFont(InterFont(66)); p.drawText(QRect(0, c.y() + 21, width(), 90), Qt::AlignHCenter, alert.text2); - } else if (alert.size == cereal::ControlsState::AlertSize::FULL) { + } else if (alert.size == cereal::SelfdriveState::AlertSize::FULL) { bool l = alert.text1.length() > 15; p.setFont(InterFont(l ? 132 : 177, QFont::Bold)); p.drawText(QRect(0, r.y() + (l ? 240 : 270), width(), 600), Qt::AlignHCenter | Qt::TextWordWrap, alert.text1); diff --git a/selfdrive/ui/qt/onroad/alerts.h b/selfdrive/ui/qt/onroad/alerts.h index 1f76ba305b45ec2..de38d8ffc36d366 100644 --- a/selfdrive/ui/qt/onroad/alerts.h +++ b/selfdrive/ui/qt/onroad/alerts.h @@ -17,18 +17,18 @@ class OnroadAlerts : public QWidget { QString text1; QString text2; QString type; - cereal::ControlsState::AlertSize size; - cereal::ControlsState::AlertStatus status; + cereal::SelfdriveState::AlertSize size; + cereal::SelfdriveState::AlertStatus status; bool equal(const Alert &other) const { return text1 == other.text1 && text2 == other.text2 && type == other.type; } }; - const QMap alert_colors = { - {cereal::ControlsState::AlertStatus::NORMAL, QColor(0x15, 0x15, 0x15, 0xf1)}, - {cereal::ControlsState::AlertStatus::USER_PROMPT, QColor(0xDA, 0x6F, 0x25, 0xf1)}, - {cereal::ControlsState::AlertStatus::CRITICAL, QColor(0xC9, 0x22, 0x31, 0xf1)}, + const QMap alert_colors = { + {cereal::SelfdriveState::AlertStatus::NORMAL, QColor(0x15, 0x15, 0x15, 0xf1)}, + {cereal::SelfdriveState::AlertStatus::USER_PROMPT, QColor(0xDA, 0x6F, 0x25, 0xf1)}, + {cereal::SelfdriveState::AlertStatus::CRITICAL, QColor(0xC9, 0x22, 0x31, 0xf1)}, }; void paintEvent(QPaintEvent*) override; diff --git a/selfdrive/ui/qt/onroad/annotated_camera.cc b/selfdrive/ui/qt/onroad/annotated_camera.cc index f7fb6b480f0f7a5..f504ad69f1e2c22 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.cc +++ b/selfdrive/ui/qt/onroad/annotated_camera.cc @@ -6,12 +6,12 @@ #include #include "common/swaglog.h" -#include "selfdrive/ui/qt/onroad/buttons.h" #include "selfdrive/ui/qt/util.h" // Window that shows camera view and variety of info drawn on top -AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraWidget("camerad", type, true, parent) { - pm = std::make_unique>({"uiDebug"}); +AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget *parent) + : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraWidget("camerad", type, parent) { + pm = std::make_unique(std::vector{"uiDebug"}); main_layout = new QVBoxLayout(this); main_layout->setMargin(UI_BORDER_SIZE); @@ -19,169 +19,12 @@ AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget* par experimental_btn = new ExperimentalButton(this); main_layout->addWidget(experimental_btn, 0, Qt::AlignTop | Qt::AlignRight); - - map_settings_btn = new MapSettingsButton(this); - main_layout->addWidget(map_settings_btn, 0, Qt::AlignBottom | Qt::AlignRight); - - dm_img = loadPixmap("../assets/img_driver_face.png", {img_size + 5, img_size + 5}); } void AnnotatedCameraWidget::updateState(const UIState &s) { - const int SET_SPEED_NA = 255; - const SubMaster &sm = *(s.sm); - - const bool cs_alive = sm.alive("controlsState"); - const bool nav_alive = sm.alive("navInstruction") && sm["navInstruction"].getValid(); - const auto cs = sm["controlsState"].getControlsState(); - const auto car_state = sm["carState"].getCarState(); - 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(); - 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) { - setSpeed *= KM_TO_MILE; - } - - // Handle older routes where vEgoCluster is not set - v_ego_cluster_seen = v_ego_cluster_seen || car_state.getVEgoCluster() != 0.0; - float v_ego = v_ego_cluster_seen ? car_state.getVEgoCluster() : car_state.getVEgo(); - speed = cs_alive ? std::max(0.0, v_ego) : 0.0; - speed *= s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH; - - auto speed_limit_sign = nav_instruction.getSpeedLimitSign(); - speedLimit = nav_alive ? nav_instruction.getSpeedLimit() : 0.0; - speedLimit *= (s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH); - - has_us_speed_limit = (nav_alive && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::MUTCD); - has_eu_speed_limit = (nav_alive && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::VIENNA); - is_metric = s.scene.is_metric; - speedUnit = s.scene.is_metric ? tr("km/h") : tr("mph"); - hideBottomIcons = (cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE); - status = s.status; - // update engageability/experimental mode button experimental_btn->updateState(s); - - // update DM icon - auto dm_state = sm["driverMonitoringState"].getDriverMonitoringState(); - dmActive = dm_state.getIsActiveMode(); - rightHandDM = dm_state.getIsRHD(); - // DM icon transition - dm_fade_state = std::clamp(dm_fade_state+0.2*(0.5-dmActive), 0.0, 1.0); - - // hide map settings button for alerts and flip for right hand DM - if (map_settings_btn->isEnabled()) { - map_settings_btn->setVisible(!hideBottomIcons); - main_layout->setAlignment(map_settings_btn, (rightHandDM ? Qt::AlignLeft : Qt::AlignRight) | Qt::AlignBottom); - } -} - -void AnnotatedCameraWidget::drawHud(QPainter &p) { - p.save(); - - // Header gradient - QLinearGradient bg(0, UI_HEADER_HEIGHT - (UI_HEADER_HEIGHT / 2.5), 0, UI_HEADER_HEIGHT); - bg.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.45)); - bg.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0)); - p.fillRect(0, 0, width(), UI_HEADER_HEIGHT, bg); - - QString speedLimitStr = (speedLimit > 1) ? QString::number(std::nearbyint(speedLimit)) : "–"; - QString speedStr = QString::number(std::nearbyint(speed)); - QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed)) : "–"; - - // Draw outer box + border to contain set speed and speed limit - const int sign_margin = 12; - const int us_sign_height = 186; - const int eu_sign_size = 176; - - const QSize default_size = {172, 204}; - QSize set_speed_size = default_size; - if (is_metric || has_eu_speed_limit) set_speed_size.rwidth() = 200; - if (has_us_speed_limit && speedLimitStr.size() >= 3) set_speed_size.rwidth() = 223; - - if (has_us_speed_limit) set_speed_size.rheight() += us_sign_height + sign_margin; - else if (has_eu_speed_limit) set_speed_size.rheight() += eu_sign_size + sign_margin; - - int top_radius = 32; - int bottom_radius = has_eu_speed_limit ? 100 : 32; - - QRect set_speed_rect(QPoint(60 + (default_size.width() - set_speed_size.width()) / 2, 45), set_speed_size); - p.setPen(QPen(whiteColor(75), 6)); - p.setBrush(blackColor(166)); - drawRoundedRect(p, set_speed_rect, top_radius, top_radius, bottom_radius, bottom_radius); - - // Draw MAX - QColor max_color = QColor(0x80, 0xd8, 0xa6, 0xff); - QColor set_speed_color = whiteColor(); - if (is_cruise_set) { - if (status == STATUS_DISENGAGED) { - max_color = whiteColor(); - } else if (status == STATUS_OVERRIDE) { - max_color = QColor(0x91, 0x9b, 0x95, 0xff); - } else if (speedLimit > 0) { - auto interp_color = [=](QColor c1, QColor c2, QColor c3) { - return speedLimit > 0 ? interpColor(setSpeed, {speedLimit + 5, speedLimit + 15, speedLimit + 25}, {c1, c2, c3}) : c1; - }; - max_color = interp_color(max_color, QColor(0xff, 0xe4, 0xbf), QColor(0xff, 0xbf, 0xbf)); - set_speed_color = interp_color(set_speed_color, QColor(0xff, 0x95, 0x00), QColor(0xff, 0x00, 0x00)); - } - } else { - max_color = QColor(0xa6, 0xa6, 0xa6, 0xff); - set_speed_color = QColor(0x72, 0x72, 0x72, 0xff); - } - p.setFont(InterFont(40, QFont::DemiBold)); - p.setPen(max_color); - p.drawText(set_speed_rect.adjusted(0, 27, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("MAX")); - p.setFont(InterFont(90, QFont::Bold)); - p.setPen(set_speed_color); - p.drawText(set_speed_rect.adjusted(0, 77, 0, 0), Qt::AlignTop | Qt::AlignHCenter, setSpeedStr); - - const QRect sign_rect = set_speed_rect.adjusted(sign_margin, default_size.height(), -sign_margin, -sign_margin); - // US/Canada (MUTCD style) sign - if (has_us_speed_limit) { - p.setPen(Qt::NoPen); - p.setBrush(whiteColor()); - p.drawRoundedRect(sign_rect, 24, 24); - p.setPen(QPen(blackColor(), 6)); - p.drawRoundedRect(sign_rect.adjusted(9, 9, -9, -9), 16, 16); - - p.setFont(InterFont(28, QFont::DemiBold)); - p.drawText(sign_rect.adjusted(0, 22, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("SPEED")); - p.drawText(sign_rect.adjusted(0, 51, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("LIMIT")); - p.setFont(InterFont(70, QFont::Bold)); - p.drawText(sign_rect.adjusted(0, 85, 0, 0), Qt::AlignTop | Qt::AlignHCenter, speedLimitStr); - } - - // EU (Vienna style) sign - if (has_eu_speed_limit) { - p.setPen(Qt::NoPen); - p.setBrush(whiteColor()); - p.drawEllipse(sign_rect); - p.setPen(QPen(Qt::red, 20)); - p.drawEllipse(sign_rect.adjusted(16, 16, -16, -16)); - - p.setFont(InterFont((speedLimitStr.size() >= 3) ? 60 : 70, QFont::Bold)); - p.setPen(blackColor()); - p.drawText(sign_rect, Qt::AlignCenter, speedLimitStr); - } - - // current speed - p.setFont(InterFont(176, QFont::Bold)); - drawText(p, rect().center().x(), 210, speedStr); - p.setFont(InterFont(66)); - drawText(p, rect().center().x(), 290, speedUnit, 200); - - p.restore(); -} - -void AnnotatedCameraWidget::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { - QRect real_rect = p.fontMetrics().boundingRect(text); - real_rect.moveCenter({x, y - real_rect.height() / 2}); - - p.setPen(QColor(0xff, 0xff, 0xff, alpha)); - p.drawText(real_rect.x(), real_rect.bottom(), text); + dmon.updateState(s); } void AnnotatedCameraWidget::initializeGL() { @@ -195,165 +38,59 @@ void AnnotatedCameraWidget::initializeGL() { setBackgroundColor(bg_colors[STATUS_DISENGAGED]); } -void AnnotatedCameraWidget::updateFrameMat() { - CameraWidget::updateFrameMat(); - UIState *s = uiState(); +mat4 AnnotatedCameraWidget::calcFrameMatrix() { + // Project point at "infinity" to compute x and y offsets + // to ensure this ends up in the middle of the screen + // for narrow come and a little lower for wide cam. + // TODO: use proper perspective transform? + + // Select intrinsic matrix and calibration based on camera type + auto *s = uiState(); + bool wide_cam = active_stream_type == VISION_STREAM_WIDE_ROAD; + const auto &intrinsic_matrix = wide_cam ? ECAM_INTRINSIC_MATRIX : FCAM_INTRINSIC_MATRIX; + const auto &calibration = wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib; + + // Compute the calibration transformation matrix + const auto calib_transform = intrinsic_matrix * calibration; + + float zoom = wide_cam ? 2.0 : 1.1; + Eigen::Vector3f inf(1000., 0., 0.); + auto Kep = calib_transform * inf; + int w = width(), h = height(); + float center_x = intrinsic_matrix(0, 2); + float center_y = intrinsic_matrix(1, 2); - s->fb_w = w; - s->fb_h = h; + float max_x_offset = center_x * zoom - w / 2 - 5; + float max_y_offset = center_y * zoom - h / 2 - 5; + float x_offset = std::clamp((Kep.x() / Kep.z() - center_x) * zoom, -max_x_offset, max_x_offset); + float y_offset = std::clamp((Kep.y() / Kep.z() - center_y) * zoom, -max_y_offset, max_y_offset); // Apply transformation such that video pixel coordinates match video // 1) Put (0, 0) in the middle of the video // 2) Apply same scaling as video // 3) Put (0, 0) in top left corner of video - s->car_space_transform.reset(); - s->car_space_transform.translate(w / 2 - x_offset, h / 2 - y_offset) - .scale(zoom, zoom) - .translate(-intrinsic_matrix.v[2], -intrinsic_matrix.v[5]); -} - -void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) { - painter.save(); - - const UIScene &scene = s->scene; - SubMaster &sm = *(s->sm); - - // lanelines - for (int i = 0; i < std::size(scene.lane_line_vertices); ++i) { - painter.setBrush(QColor::fromRgbF(1.0, 1.0, 1.0, std::clamp(scene.lane_line_probs[i], 0.0, 0.7))); - painter.drawPolygon(scene.lane_line_vertices[i]); - } - - // road edges - for (int i = 0; i < std::size(scene.road_edge_vertices); ++i) { - painter.setBrush(QColor::fromRgbF(1.0, 0, 0, std::clamp(1.0 - scene.road_edge_stds[i], 0.0, 1.0))); - painter.drawPolygon(scene.road_edge_vertices[i]); - } - - // paint path - QLinearGradient bg(0, height(), 0, 0); - if (sm["controlsState"].getControlsState().getExperimentalMode()) { - // The first half of track_vertices are the points for the right side of the path - // and the indices match the positions of accel from uiPlan - const auto &acceleration = sm["uiPlan"].getUiPlan().getAccel(); - const int max_len = std::min(scene.track_vertices.length() / 2, acceleration.size()); - - for (int i = 0; i < max_len; ++i) { - // Some points are out of frame - if (scene.track_vertices[i].y() < 0 || scene.track_vertices[i].y() > height()) continue; - - // Flip so 0 is bottom of frame - float lin_grad_point = (height() - scene.track_vertices[i].y()) / height(); - - // speed up: 120, slow down: 0 - float path_hue = fmax(fmin(60 + acceleration[i] * 35, 120), 0); - // FIXME: painter.drawPolygon can be slow if hue is not rounded - path_hue = int(path_hue * 100 + 0.5) / 100; - - float saturation = fmin(fabs(acceleration[i] * 1.5), 1); - float lightness = util::map_val(saturation, 0.0f, 1.0f, 0.95f, 0.62f); // lighter when grey - float alpha = util::map_val(lin_grad_point, 0.75f / 2.f, 0.75f, 0.4f, 0.0f); // matches previous alpha fade - bg.setColorAt(lin_grad_point, QColor::fromHslF(path_hue / 360., saturation, lightness, alpha)); - - // Skip a point, unless next is last - i += (i + 2) < max_len ? 1 : 0; - } - - } else { - bg.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 0.4)); - bg.setColorAt(0.5, QColor::fromHslF(112 / 360., 1.0, 0.68, 0.35)); - bg.setColorAt(1.0, QColor::fromHslF(112 / 360., 1.0, 0.68, 0.0)); - } - - painter.setBrush(bg); - painter.drawPolygon(scene.track_vertices); - - painter.restore(); -} - -void AnnotatedCameraWidget::drawDriverState(QPainter &painter, const UIState *s) { - const UIScene &scene = s->scene; - - painter.save(); - - // base icon - int offset = UI_BORDER_SIZE + btn_size / 2; - int x = rightHandDM ? width() - offset : offset; - int y = height() - offset; - float opacity = dmActive ? 0.65 : 0.2; - drawIcon(painter, QPoint(x, y), dm_img, blackColor(70), opacity); - - // face - QPointF face_kpts_draw[std::size(default_face_kpts_3d)]; - float kp; - for (int i = 0; i < std::size(default_face_kpts_3d); ++i) { - kp = (scene.face_kpts_draw[i].v[2] - 8) / 120 + 1.0; - face_kpts_draw[i] = QPointF(scene.face_kpts_draw[i].v[0] * kp + x, scene.face_kpts_draw[i].v[1] * kp + y); - } - - painter.setPen(QPen(QColor::fromRgbF(1.0, 1.0, 1.0, opacity), 5.2, Qt::SolidLine, Qt::RoundCap)); - painter.drawPolyline(face_kpts_draw, std::size(default_face_kpts_3d)); - - // tracking arcs - const int arc_l = 133; - const float arc_t_default = 6.7; - const float arc_t_extend = 12.0; - QColor arc_color = QColor::fromRgbF(0.545 - 0.445 * s->engaged(), - 0.545 + 0.4 * s->engaged(), - 0.545 - 0.285 * s->engaged(), - 0.4 * (1.0 - dm_fade_state)); - float delta_x = -scene.driver_pose_sins[1] * arc_l / 2; - float delta_y = -scene.driver_pose_sins[0] * arc_l / 2; - painter.setPen(QPen(arc_color, arc_t_default+arc_t_extend*fmin(1.0, scene.driver_pose_diff[1] * 5.0), Qt::SolidLine, Qt::RoundCap)); - painter.drawArc(QRectF(std::fmin(x + delta_x, x), y - arc_l / 2, fabs(delta_x), arc_l), (scene.driver_pose_sins[1]>0 ? 90 : -90) * 16, 180 * 16); - painter.setPen(QPen(arc_color, arc_t_default+arc_t_extend*fmin(1.0, scene.driver_pose_diff[0] * 5.0), Qt::SolidLine, Qt::RoundCap)); - painter.drawArc(QRectF(x - arc_l / 2, std::fmin(y + delta_y, y), arc_l, fabs(delta_y)), (scene.driver_pose_sins[0]>0 ? 0 : 180) * 16, 180 * 16); - - painter.restore(); -} - -void AnnotatedCameraWidget::drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd) { - painter.save(); - - const float speedBuff = 10.; - const float leadBuff = 40.; - const float d_rel = lead_data.getDRel(); - const float v_rel = lead_data.getVRel(); - - float fillAlpha = 0; - if (d_rel < leadBuff) { - fillAlpha = 255 * (1.0 - (d_rel / leadBuff)); - if (v_rel < 0) { - fillAlpha += 255 * (-1 * (v_rel / speedBuff)); - } - fillAlpha = (int)(fmin(fillAlpha, 255)); - } - - float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * 2.35; - float x = std::clamp((float)vd.x(), 0.f, width() - sz / 2); - float y = std::fmin(height() - sz * .6, (float)vd.y()); - - float g_xo = sz / 5; - float g_yo = sz / 10; - - QPointF glow[] = {{x + (sz * 1.35) + g_xo, y + sz + g_yo}, {x, y - g_yo}, {x - (sz * 1.35) - g_xo, y + sz + g_yo}}; - painter.setBrush(QColor(218, 202, 37, 255)); - painter.drawPolygon(glow, std::size(glow)); - - // chevron - QPointF chevron[] = {{x + (sz * 1.25), y + sz}, {x, y}, {x - (sz * 1.25), y + sz}}; - painter.setBrush(redColor(fillAlpha)); - painter.drawPolygon(chevron, std::size(chevron)); - - painter.restore(); + Eigen::Matrix3f video_transform =(Eigen::Matrix3f() << + zoom, 0.0f, (w / 2 - x_offset) - (center_x * zoom), + 0.0f, zoom, (h / 2 - y_offset) - (center_y * zoom), + 0.0f, 0.0f, 1.0f).finished(); + + model.setTransform(video_transform * calib_transform); + + float zx = zoom * 2 * center_x / w; + float zy = zoom * 2 * center_y / h; + return mat4{{ + zx, 0.0, 0.0, -x_offset / w * 2, + 0.0, zy, 0.0, y_offset / h * 2, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; } void AnnotatedCameraWidget::paintGL() { UIState *s = uiState(); SubMaster &sm = *(s->sm); const double start_draw_t = millis_since_boot(); - const cereal::ModelDataV2::Reader &model = sm["modelV2"].getModelV2(); // draw camera frame { @@ -381,20 +118,10 @@ void AnnotatedCameraWidget::paintGL() { } else if (v_ego > 15) { wide_cam_requested = false; } - wide_cam_requested = wide_cam_requested && sm["controlsState"].getControlsState().getExperimentalMode(); - // for replay of old routes, never go to widecam - wide_cam_requested = wide_cam_requested && s->scene.calibration_wide_valid; + wide_cam_requested = wide_cam_requested && sm["selfdriveState"].getSelfdriveState().getExperimentalMode(); } CameraWidget::setStreamType(wide_cam_requested ? VISION_STREAM_WIDE_ROAD : VISION_STREAM_ROAD); - - s->scene.wide_cam = CameraWidget::getStreamType() == VISION_STREAM_WIDE_ROAD; - if (s->scene.calibration_valid) { - auto calib = s->scene.wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib; - CameraWidget::updateCalibration(calib); - } else { - CameraWidget::updateCalibration(DEFAULT_CALIBRATION); - } - CameraWidget::setFrameId(model.getFrameId()); + CameraWidget::setFrameId(sm["modelV2"].getModelV2().getFrameId()); CameraWidget::paintGL(); } @@ -402,31 +129,10 @@ void AnnotatedCameraWidget::paintGL() { painter.setRenderHint(QPainter::Antialiasing); painter.setPen(Qt::NoPen); - if (s->scene.world_objects_visible) { - update_model(s, model, sm["uiPlan"].getUiPlan()); - drawLaneLines(painter, s); - - 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()) { - drawLead(painter, lead_one, s->scene.lead_vertices[0]); - } - if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) { - drawLead(painter, lead_two, s->scene.lead_vertices[1]); - } - } - } - - // DMoji - if (!hideBottomIcons && (sm.rcv_frame("driverStateV2") > s->scene.started_frame)) { - update_dmonitoring(s, sm["driverStateV2"].getDriverStateV2(), dm_fade_state, rightHandDM); - drawDriverState(painter, s); - } - - drawHud(painter); + model.draw(painter, rect()); + dmon.draw(painter, rect()); + hud.updateState(*s); + hud.draw(painter, rect()); double cur_draw_t = millis_since_boot(); double dt = cur_draw_t - prev_draw_t; diff --git a/selfdrive/ui/qt/onroad/annotated_camera.h b/selfdrive/ui/qt/onroad/annotated_camera.h index 0be4adfffa68dd1..d205579f6c90591 100644 --- a/selfdrive/ui/qt/onroad/annotated_camera.h +++ b/selfdrive/ui/qt/onroad/annotated_camera.h @@ -2,8 +2,10 @@ #include #include - +#include "selfdrive/ui/qt/onroad/hud.h" #include "selfdrive/ui/qt/onroad/buttons.h" +#include "selfdrive/ui/qt/onroad/driver_monitoring.h" +#include "selfdrive/ui/qt/onroad/model.h" #include "selfdrive/ui/qt/widgets/cameraview.h" class AnnotatedCameraWidget : public CameraWidget { @@ -13,28 +15,12 @@ class AnnotatedCameraWidget : public CameraWidget { explicit AnnotatedCameraWidget(VisionStreamType type, QWidget* parent = 0); void updateState(const UIState &s); - MapSettingsButton *map_settings_btn; - private: - void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255); - QVBoxLayout *main_layout; ExperimentalButton *experimental_btn; - QPixmap dm_img; - float speed; - QString speedUnit; - float setSpeed; - float speedLimit; - bool is_cruise_set = false; - bool is_metric = false; - bool dmActive = false; - bool hideBottomIcons = false; - bool rightHandDM = false; - float dm_fade_state = 1.0; - bool has_us_speed_limit = false; - bool has_eu_speed_limit = false; - bool v_ego_cluster_seen = false; - int status = STATUS_DISENGAGED; + DriverMonitorRenderer dmon; + HudRenderer hud; + ModelRenderer model; std::unique_ptr pm; int skip_frame_count = 0; @@ -44,14 +30,7 @@ class AnnotatedCameraWidget : public CameraWidget { void paintGL() override; void initializeGL() override; void showEvent(QShowEvent *event) override; - void updateFrameMat() override; - void drawLaneLines(QPainter &painter, const UIState *s); - void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd); - void drawHud(QPainter &p); - void drawDriverState(QPainter &painter, const UIState *s); - inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); } - inline QColor whiteColor(int alpha = 255) { return QColor(255, 255, 255, alpha); } - inline QColor blackColor(int alpha = 255) { return QColor(0, 0, 0, alpha); } + mat4 calcFrameMatrix() override; double prev_draw_t = 0; FirstOrderFilter fps_filter; diff --git a/selfdrive/ui/qt/onroad/buttons.cc b/selfdrive/ui/qt/onroad/buttons.cc index 75ec3161740d7a5..2c2cc672b9aeba8 100644 --- a/selfdrive/ui/qt/onroad/buttons.cc +++ b/selfdrive/ui/qt/onroad/buttons.cc @@ -33,7 +33,7 @@ void ExperimentalButton::changeMode() { } void ExperimentalButton::updateState(const UIState &s) { - const auto cs = (*s.sm)["controlsState"].getControlsState(); + const auto cs = (*s.sm)["selfdriveState"].getSelfdriveState(); bool eng = cs.getEngageable() || cs.getEnabled(); if ((cs.getExperimentalMode() != experimental_mode) || (eng != engageable)) { engageable = eng; @@ -47,18 +47,3 @@ void ExperimentalButton::paintEvent(QPaintEvent *event) { QPixmap img = experimental_mode ? experimental_img : engage_img; drawIcon(p, QPoint(btn_size / 2, btn_size / 2), img, QColor(0, 0, 0, 166), (isDown() || !engageable) ? 0.6 : 1.0); } - -// MapSettingsButton -MapSettingsButton::MapSettingsButton(QWidget *parent) : QPushButton(parent) { - setFixedSize(btn_size, btn_size); - settings_img = loadPixmap("../assets/navigation/icon_directions_outlined.svg", {img_size, img_size}); - - // hidden by default, made visible if map is created (has prime or mapbox token) - setVisible(false); - setEnabled(false); -} - -void MapSettingsButton::paintEvent(QPaintEvent *event) { - QPainter p(this); - drawIcon(p, QPoint(btn_size / 2, btn_size / 2), settings_img, QColor(0, 0, 0, 166), isDown() ? 0.6 : 1.0); -} diff --git a/selfdrive/ui/qt/onroad/buttons.h b/selfdrive/ui/qt/onroad/buttons.h index b0757795fb56d86..9c91bc3c7b649f6 100644 --- a/selfdrive/ui/qt/onroad/buttons.h +++ b/selfdrive/ui/qt/onroad/buttons.h @@ -25,17 +25,4 @@ class ExperimentalButton : public QPushButton { bool engageable; }; - -class MapSettingsButton : public QPushButton { - Q_OBJECT - -public: - explicit MapSettingsButton(QWidget *parent = 0); - -private: - void paintEvent(QPaintEvent *event) override; - - QPixmap settings_img; -}; - void drawIcon(QPainter &p, const QPoint ¢er, const QPixmap &img, const QBrush &bg, float opacity); diff --git a/selfdrive/ui/qt/onroad/driver_monitoring.cc b/selfdrive/ui/qt/onroad/driver_monitoring.cc new file mode 100644 index 000000000000000..afd003cf8f412a7 --- /dev/null +++ b/selfdrive/ui/qt/onroad/driver_monitoring.cc @@ -0,0 +1,107 @@ +#include "selfdrive/ui/qt/onroad/driver_monitoring.h" +#include +#include + +#include "selfdrive/ui/qt/onroad/buttons.h" +#include "selfdrive/ui/qt/util.h" + +// Default 3D coordinates for face keypoints +static 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}, + {-34.10, -32.00, 8.00}, {-36.16, -21.03, 8.00}, {-36.16, 6.40, 8.00}, {-35.47, 10.51, 8.00}, {-32.73, 19.43, 8.00}, + {-29.30, 26.29, 8.00}, {-24.50, 33.83, 8.00}, {-19.01, 41.37, 8.00}, {-14.21, 46.17, 8.00}, {-12.16, 47.54, 8.00}, + {-4.61, 49.60, 8.00}, {4.99, 49.60, 8.00}, {12.53, 47.54, 8.00}, {14.59, 46.17, 8.00}, {19.39, 41.37, 8.00}, + {24.87, 33.83, 8.00}, {29.67, 26.29, 8.00}, {33.10, 19.43, 8.00}, {35.84, 10.51, 8.00}, {36.53, 6.40, 8.00}, + {36.53, -21.03, 8.00}, {34.47, -32.00, 8.00}, {32.42, -37.49, 8.00}, {30.36, -40.91, 8.00}, {24.19, -46.40, 8.00}, + {18.02, -49.14, 8.00}, {6.36, -51.20, 8.00}, {-5.98, -51.20, 8.00}, +}; + +// Colors used for drawing based on monitoring state +static const QColor DMON_ENGAGED_COLOR = QColor::fromRgbF(0.1, 0.945, 0.26); +static const QColor DMON_DISENGAGED_COLOR = QColor::fromRgbF(0.545, 0.545, 0.545); + +DriverMonitorRenderer::DriverMonitorRenderer() : face_kpts_draw(std::size(DEFAULT_FACE_KPTS_3D)) { + dm_img = loadPixmap("../assets/img_driver_face.png", {img_size + 5, img_size + 5}); +} + +void DriverMonitorRenderer::updateState(const UIState &s) { + auto &sm = *(s.sm); + is_visible = sm["selfdriveState"].getSelfdriveState().getAlertSize() == cereal::SelfdriveState::AlertSize::NONE && + sm.rcv_frame("driverStateV2") > s.scene.started_frame; + if (!is_visible) return; + + auto dm_state = sm["driverMonitoringState"].getDriverMonitoringState(); + is_active = dm_state.getIsActiveMode(); + is_rhd = dm_state.getIsRHD(); + dm_fade_state = std::clamp(dm_fade_state + 0.2f * (0.5f - is_active), 0.0f, 1.0f); + + const auto &driverstate = sm["driverStateV2"].getDriverStateV2(); + const auto driver_orient = is_rhd ? driverstate.getRightDriverData().getFaceOrientation() : driverstate.getLeftDriverData().getFaceOrientation(); + + for (int i = 0; i < 3; ++i) { + float v_this = (i == 0 ? (driver_orient[i] < 0 ? 0.7 : 0.9) : 0.4) * driver_orient[i]; + driver_pose_diff[i] = std::abs(driver_pose_vals[i] - v_this); + driver_pose_vals[i] = 0.8f * v_this + (1 - 0.8) * driver_pose_vals[i]; + driver_pose_sins[i] = std::sin(driver_pose_vals[i] * (1.0f - dm_fade_state)); + driver_pose_coss[i] = std::cos(driver_pose_vals[i] * (1.0f - dm_fade_state)); + } + + auto [sin_y, sin_x, sin_z] = driver_pose_sins; + auto [cos_y, cos_x, cos_z] = driver_pose_coss; + + // Rotation matrix for transforming face keypoints based on driver's head orientation + const mat3 r_xyz = {{ + cos_x * cos_z, cos_x * sin_z, -sin_x, + -sin_y * sin_x * cos_z - cos_y * sin_z, -sin_y * sin_x * sin_z + cos_y * cos_z, -sin_y * cos_x, + cos_y * sin_x * cos_z - sin_y * sin_z, cos_y * sin_x * sin_z + sin_y * cos_z, cos_y * cos_x, + }}; + + // Transform vertices + for (int i = 0; i < face_kpts_draw.size(); ++i) { + vec3 kpt = matvecmul3(r_xyz, DEFAULT_FACE_KPTS_3D[i]); + face_kpts_draw[i] = {{kpt.v[0], kpt.v[1], kpt.v[2] * (1.0f - dm_fade_state) + 8 * dm_fade_state}}; + } +} + +void DriverMonitorRenderer::draw(QPainter &painter, const QRect &surface_rect) { + if (!is_visible) return; + + painter.save(); + + int offset = UI_BORDER_SIZE + btn_size / 2; + float x = is_rhd ? surface_rect.width() - offset : offset; + float y = surface_rect.height() - offset; + float opacity = is_active ? 0.65f : 0.2f; + + drawIcon(painter, QPoint(x, y), dm_img, QColor(0, 0, 0, 70), opacity); + + QPointF keypoints[std::size(DEFAULT_FACE_KPTS_3D)]; + for (int i = 0; i < std::size(keypoints); ++i) { + const auto &v = face_kpts_draw[i].v; + float kp = (v[2] - 8) / 120.0f + 1.0f; + keypoints[i] = QPointF(v[0] * kp + x, v[1] * kp + y); + } + + painter.setPen(QPen(QColor::fromRgbF(1.0, 1.0, 1.0, opacity), 5.2, Qt::SolidLine, Qt::RoundCap)); + painter.drawPolyline(keypoints, std::size(keypoints)); + + // tracking arcs + const int arc_l = 133; + const float arc_t_default = 6.7f; + const float arc_t_extend = 12.0f; + QColor arc_color = uiState()->engaged() ? DMON_ENGAGED_COLOR : DMON_DISENGAGED_COLOR; + arc_color.setAlphaF(0.4 * (1.0f - dm_fade_state)); + + float delta_x = -driver_pose_sins[1] * arc_l / 2.0f; + float delta_y = -driver_pose_sins[0] * arc_l / 2.0f; + + // Draw horizontal tracking arc + painter.setPen(QPen(arc_color, arc_t_default + arc_t_extend * std::min(1.0, driver_pose_diff[1] * 5.0), Qt::SolidLine, Qt::RoundCap)); + painter.drawArc(QRectF(std::min(x + delta_x, x), y - arc_l / 2, std::abs(delta_x), arc_l), (driver_pose_sins[1] > 0 ? 90 : -90) * 16, 180 * 16); + + // Draw vertical tracking arc + painter.setPen(QPen(arc_color, arc_t_default + arc_t_extend * std::min(1.0, driver_pose_diff[0] * 5.0), Qt::SolidLine, Qt::RoundCap)); + painter.drawArc(QRectF(x - arc_l / 2, std::min(y + delta_y, y), arc_l, std::abs(delta_y)), (driver_pose_sins[0] > 0 ? 0 : 180) * 16, 180 * 16); + + painter.restore(); +} diff --git a/selfdrive/ui/qt/onroad/driver_monitoring.h b/selfdrive/ui/qt/onroad/driver_monitoring.h new file mode 100644 index 000000000000000..47db151c81b136e --- /dev/null +++ b/selfdrive/ui/qt/onroad/driver_monitoring.h @@ -0,0 +1,24 @@ +#pragma once + +#include +#include +#include "selfdrive/ui/ui.h" + +class DriverMonitorRenderer { +public: + DriverMonitorRenderer(); + void updateState(const UIState &s); + void draw(QPainter &painter, const QRect &surface_rect); + +private: + float driver_pose_vals[3] = {}; + float driver_pose_diff[3] = {}; + float driver_pose_sins[3] = {}; + float driver_pose_coss[3] = {}; + bool is_visible = false; + bool is_active = false; + bool is_rhd = false; + float dm_fade_state = 1.0; + QPixmap dm_img; + std::vector face_kpts_draw; +}; diff --git a/selfdrive/ui/qt/onroad/hud.cc b/selfdrive/ui/qt/onroad/hud.cc new file mode 100644 index 000000000000000..c63962caf65d10a --- /dev/null +++ b/selfdrive/ui/qt/onroad/hud.cc @@ -0,0 +1,109 @@ +#include "selfdrive/ui/qt/onroad/hud.h" + +#include + +#include "selfdrive/ui/qt/util.h" + +constexpr int SET_SPEED_NA = 255; + +HudRenderer::HudRenderer() {} + +void HudRenderer::updateState(const UIState &s) { + is_metric = s.scene.is_metric; + status = s.status; + + const SubMaster &sm = *(s.sm); + if (sm.rcv_frame("carState") < s.scene.started_frame) { + is_cruise_set = false; + set_speed = SET_SPEED_NA; + speed = 0.0; + return; + } + + const auto &controls_state = sm["controlsState"].getControlsState(); + const auto &car_state = sm["carState"].getCarState(); + + // Handle older routes where vCruiseCluster is not set + set_speed = car_state.getVCruiseCluster() == 0.0 ? controls_state.getVCruiseDEPRECATED() : car_state.getVCruiseCluster(); + is_cruise_set = set_speed > 0 && set_speed != SET_SPEED_NA; + + if (is_cruise_set && !is_metric) { + set_speed *= KM_TO_MILE; + } + + // Handle older routes where vEgoCluster is not set + v_ego_cluster_seen = v_ego_cluster_seen || car_state.getVEgoCluster() != 0.0; + float v_ego = v_ego_cluster_seen ? car_state.getVEgoCluster() : car_state.getVEgo(); + speed = std::max(0.0f, v_ego * (is_metric ? MS_TO_KPH : MS_TO_MPH)); +} + +void HudRenderer::draw(QPainter &p, const QRect &surface_rect) { + p.save(); + + // Draw header gradient + QLinearGradient bg(0, UI_HEADER_HEIGHT - (UI_HEADER_HEIGHT / 2.5), 0, UI_HEADER_HEIGHT); + bg.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.45)); + bg.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0)); + p.fillRect(0, 0, surface_rect.width(), UI_HEADER_HEIGHT, bg); + + + drawSetSpeed(p, surface_rect); + drawCurrentSpeed(p, surface_rect); + + p.restore(); +} + +void HudRenderer::drawSetSpeed(QPainter &p, const QRect &surface_rect) { + // Draw outer box + border to contain set speed + const QSize default_size = {172, 204}; + QSize set_speed_size = is_metric ? QSize(200, 204) : default_size; + QRect set_speed_rect(QPoint(60 + (default_size.width() - set_speed_size.width()) / 2, 45), set_speed_size); + + // Draw set speed box + p.setPen(QPen(QColor(255, 255, 255, 75), 6)); + p.setBrush(QColor(0, 0, 0, 166)); + p.drawRoundedRect(set_speed_rect, 32, 32); + + // Colors based on status + QColor max_color = QColor(0xa6, 0xa6, 0xa6, 0xff); + QColor set_speed_color = QColor(0x72, 0x72, 0x72, 0xff); + if (is_cruise_set) { + set_speed_color = QColor(255, 255, 255); + if (status == STATUS_DISENGAGED) { + max_color = QColor(255, 255, 255); + } else if (status == STATUS_OVERRIDE) { + max_color = QColor(0x91, 0x9b, 0x95, 0xff); + } else { + max_color = QColor(0x80, 0xd8, 0xa6, 0xff); + } + } + + // Draw "MAX" text + p.setFont(InterFont(40, QFont::DemiBold)); + p.setPen(max_color); + p.drawText(set_speed_rect.adjusted(0, 27, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("MAX")); + + // Draw set speed + QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(set_speed)) : "–"; + p.setFont(InterFont(90, QFont::Bold)); + p.setPen(set_speed_color); + p.drawText(set_speed_rect.adjusted(0, 77, 0, 0), Qt::AlignTop | Qt::AlignHCenter, setSpeedStr); +} + +void HudRenderer::drawCurrentSpeed(QPainter &p, const QRect &surface_rect) { + QString speedStr = QString::number(std::nearbyint(speed)); + + p.setFont(InterFont(176, QFont::Bold)); + drawText(p, surface_rect.center().x(), 210, speedStr); + + p.setFont(InterFont(66)); + drawText(p, surface_rect.center().x(), 290, is_metric ? tr("km/h") : tr("mph"), 200); +} + +void HudRenderer::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { + QRect real_rect = p.fontMetrics().boundingRect(text); + real_rect.moveCenter({x, y - real_rect.height() / 2}); + + p.setPen(QColor(0xff, 0xff, 0xff, alpha)); + p.drawText(real_rect.x(), real_rect.bottom(), text); +} diff --git a/selfdrive/ui/qt/onroad/hud.h b/selfdrive/ui/qt/onroad/hud.h new file mode 100644 index 000000000000000..0b1220a27a766e4 --- /dev/null +++ b/selfdrive/ui/qt/onroad/hud.h @@ -0,0 +1,25 @@ +#pragma once + +#include +#include "selfdrive/ui/ui.h" + +class HudRenderer : public QObject { + Q_OBJECT + +public: + HudRenderer(); + void updateState(const UIState &s); + void draw(QPainter &p, const QRect &surface_rect); + +private: + void drawSetSpeed(QPainter &p, const QRect &surface_rect); + void drawCurrentSpeed(QPainter &p, const QRect &surface_rect); + void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255); + + float speed = 0; + float set_speed = 0; + bool is_cruise_set = false; + bool is_metric = false; + bool v_ego_cluster_seen = false; + int status = STATUS_DISENGAGED; +}; diff --git a/selfdrive/ui/qt/onroad/model.cc b/selfdrive/ui/qt/onroad/model.cc new file mode 100644 index 000000000000000..52902abdc8d2cf3 --- /dev/null +++ b/selfdrive/ui/qt/onroad/model.cc @@ -0,0 +1,250 @@ +#include "selfdrive/ui/qt/onroad/model.h" + +constexpr int CLIP_MARGIN = 500; +constexpr float MIN_DRAW_DISTANCE = 10.0; +constexpr float MAX_DRAW_DISTANCE = 100.0; + +static 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 < line_x.size() && line_x[i] <= path_height; ++i) { + max_idx = i; + } + return max_idx; +} + +void ModelRenderer::draw(QPainter &painter, const QRect &surface_rect) { + auto *s = uiState(); + auto &sm = *(s->sm); + // Check if data is up-to-date + if (sm.rcv_frame("liveCalibration") < s->scene.started_frame || + sm.rcv_frame("modelV2") < s->scene.started_frame) { + return; + } + + clip_region = surface_rect.adjusted(-CLIP_MARGIN, -CLIP_MARGIN, CLIP_MARGIN, CLIP_MARGIN); + experimental_mode = sm["selfdriveState"].getSelfdriveState().getExperimentalMode(); + longitudinal_control = sm["carParams"].getCarParams().getOpenpilotLongitudinalControl(); + path_offset_z = sm["liveCalibration"].getLiveCalibration().getHeight()[0]; + + painter.save(); + + const auto &model = sm["modelV2"].getModelV2(); + const auto &radar_state = sm["radarState"].getRadarState(); + const auto &lead_one = radar_state.getLeadOne(); + + update_model(model, lead_one); + drawLaneLines(painter); + drawPath(painter, model, surface_rect.height()); + + if (longitudinal_control && sm.alive("radarState")) { + update_leads(radar_state, model.getPosition()); + const auto &lead_two = radar_state.getLeadTwo(); + if (lead_one.getStatus()) { + drawLead(painter, lead_one, lead_vertices[0], surface_rect); + } + if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) { + drawLead(painter, lead_two, lead_vertices[1], surface_rect); + } + } + + painter.restore(); +} + +void ModelRenderer::update_leads(const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line) { + for (int i = 0; i < 2; ++i) { + const auto &lead_data = (i == 0) ? radar_state.getLeadOne() : radar_state.getLeadTwo(); + if (lead_data.getStatus()) { + float z = line.getZ()[get_path_length_idx(line, lead_data.getDRel())]; + mapToScreen(lead_data.getDRel(), -lead_data.getYRel(), z + path_offset_z, &lead_vertices[i]); + } + } +} + +void ModelRenderer::update_model(const cereal::ModelDataV2::Reader &model, const cereal::RadarState::LeadData::Reader &lead) { + const auto &model_position = model.getPosition(); + float max_distance = std::clamp(*(model_position.getX().end() - 1), MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE); + + // update lane lines + const auto &lane_lines = model.getLaneLines(); + const auto &line_probs = model.getLaneLineProbs(); + int max_idx = get_path_length_idx(lane_lines[0], max_distance); + for (int i = 0; i < std::size(lane_line_vertices); i++) { + lane_line_probs[i] = line_probs[i]; + mapLineToPolygon(lane_lines[i], 0.025 * lane_line_probs[i], 0, &lane_line_vertices[i], max_idx); + } + + // update road edges + const auto &road_edges = model.getRoadEdges(); + const auto &edge_stds = model.getRoadEdgeStds(); + for (int i = 0; i < std::size(road_edge_vertices); i++) { + road_edge_stds[i] = edge_stds[i]; + mapLineToPolygon(road_edges[i], 0.025, 0, &road_edge_vertices[i], max_idx); + } + + // update path + if (lead.getStatus()) { + const float lead_d = lead.getDRel() * 2.; + max_distance = std::clamp((float)(lead_d - fmin(lead_d * 0.35, 10.)), 0.0f, max_distance); + } + max_idx = get_path_length_idx(model_position, max_distance); + mapLineToPolygon(model_position, 0.9, path_offset_z, &track_vertices, max_idx, false); +} + +void ModelRenderer::drawLaneLines(QPainter &painter) { + // lanelines + for (int i = 0; i < std::size(lane_line_vertices); ++i) { + painter.setBrush(QColor::fromRgbF(1.0, 1.0, 1.0, std::clamp(lane_line_probs[i], 0.0, 0.7))); + painter.drawPolygon(lane_line_vertices[i]); + } + + // road edges + for (int i = 0; i < std::size(road_edge_vertices); ++i) { + painter.setBrush(QColor::fromRgbF(1.0, 0, 0, std::clamp(1.0 - road_edge_stds[i], 0.0, 1.0))); + painter.drawPolygon(road_edge_vertices[i]); + } +} + +void ModelRenderer::drawPath(QPainter &painter, const cereal::ModelDataV2::Reader &model, int height) { + QLinearGradient bg(0, height, 0, 0); + if (experimental_mode) { + // The first half of track_vertices are the points for the right side of the path + const auto &acceleration = model.getAcceleration().getX(); + const int max_len = std::min(track_vertices.length() / 2, acceleration.size()); + + for (int i = 0; i < max_len; ++i) { + // Some points are out of frame + int track_idx = max_len - i - 1; // flip idx to start from bottom right + if (track_vertices[track_idx].y() < 0 || track_vertices[track_idx].y() > height) continue; + + // Flip so 0 is bottom of frame + float lin_grad_point = (height - track_vertices[track_idx].y()) / height; + + // speed up: 120, slow down: 0 + float path_hue = fmax(fmin(60 + acceleration[i] * 35, 120), 0); + // FIXME: painter.drawPolygon can be slow if hue is not rounded + path_hue = int(path_hue * 100 + 0.5) / 100; + + float saturation = fmin(fabs(acceleration[i] * 1.5), 1); + float lightness = util::map_val(saturation, 0.0f, 1.0f, 0.95f, 0.62f); // lighter when grey + float alpha = util::map_val(lin_grad_point, 0.75f / 2.f, 0.75f, 0.4f, 0.0f); // matches previous alpha fade + bg.setColorAt(lin_grad_point, QColor::fromHslF(path_hue / 360., saturation, lightness, alpha)); + + // Skip a point, unless next is last + i += (i + 2) < max_len ? 1 : 0; + } + + } else { + updatePathGradient(bg); + } + + painter.setBrush(bg); + painter.drawPolygon(track_vertices); +} + +void ModelRenderer::updatePathGradient(QLinearGradient &bg) { + static const QColor throttle_colors[] = { + QColor::fromHslF(148. / 360., 0.94, 0.51, 0.4), + QColor::fromHslF(112. / 360., 1.0, 0.68, 0.35), + QColor::fromHslF(112. / 360., 1.0, 0.68, 0.0)}; + + static const QColor no_throttle_colors[] = { + QColor::fromHslF(148. / 360., 0.0, 0.95, 0.4), + QColor::fromHslF(112. / 360., 0.0, 0.95, 0.35), + QColor::fromHslF(112. / 360., 0.0, 0.95, 0.0), + }; + + // Transition speed; 0.1 corresponds to 0.5 seconds at UI_FREQ + constexpr float transition_speed = 0.1f; + + // Start transition if throttle state changes + bool allow_throttle = (*uiState()->sm)["longitudinalPlan"].getLongitudinalPlan().getAllowThrottle() || !longitudinal_control; + if (allow_throttle != prev_allow_throttle) { + prev_allow_throttle = allow_throttle; + // Invert blend factor for a smooth transition when the state changes mid-animation + blend_factor = std::max(1.0f - blend_factor, 0.0f); + } + + const QColor *begin_colors = allow_throttle ? no_throttle_colors : throttle_colors; + const QColor *end_colors = allow_throttle ? throttle_colors : no_throttle_colors; + if (blend_factor < 1.0f) { + blend_factor = std::min(blend_factor + transition_speed, 1.0f); + } + + // Set gradient colors by blending the start and end colors + bg.setColorAt(0.0f, blendColors(begin_colors[0], end_colors[0], blend_factor)); + bg.setColorAt(0.5f, blendColors(begin_colors[1], end_colors[1], blend_factor)); + bg.setColorAt(1.0f, blendColors(begin_colors[2], end_colors[2], blend_factor)); +} + +QColor ModelRenderer::blendColors(const QColor &start, const QColor &end, float t) { + if (t == 1.0f) return end; + return QColor::fromRgbF( + (1 - t) * start.redF() + t * end.redF(), + (1 - t) * start.greenF() + t * end.greenF(), + (1 - t) * start.blueF() + t * end.blueF(), + (1 - t) * start.alphaF() + t * end.alphaF()); +} + +void ModelRenderer::drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, + const QPointF &vd, const QRect &surface_rect) { + const float speedBuff = 10.; + const float leadBuff = 40.; + const float d_rel = lead_data.getDRel(); + const float v_rel = lead_data.getVRel(); + + float fillAlpha = 0; + if (d_rel < leadBuff) { + fillAlpha = 255 * (1.0 - (d_rel / leadBuff)); + if (v_rel < 0) { + fillAlpha += 255 * (-1 * (v_rel / speedBuff)); + } + fillAlpha = (int)(fmin(fillAlpha, 255)); + } + + float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * 2.35; + float x = std::clamp(vd.x(), 0.f, surface_rect.width() - sz / 2); + float y = std::min(vd.y(), surface_rect.height() - sz * 0.6); + + float g_xo = sz / 5; + float g_yo = sz / 10; + + QPointF glow[] = {{x + (sz * 1.35) + g_xo, y + sz + g_yo}, {x, y - g_yo}, {x - (sz * 1.35) - g_xo, y + sz + g_yo}}; + painter.setBrush(QColor(218, 202, 37, 255)); + painter.drawPolygon(glow, std::size(glow)); + + // chevron + QPointF chevron[] = {{x + (sz * 1.25), y + sz}, {x, y}, {x - (sz * 1.25), y + sz}}; + painter.setBrush(QColor(201, 34, 49, fillAlpha)); + painter.drawPolygon(chevron, std::size(chevron)); +} + +// Projects a point in car to space to the corresponding point in full frame image space. +bool ModelRenderer::mapToScreen(float in_x, float in_y, float in_z, QPointF *out) { + Eigen::Vector3f input(in_x, in_y, in_z); + auto pt = car_space_transform * input; + *out = QPointF(pt.x() / pt.z(), pt.y() / pt.z()); + return clip_region.contains(*out); +} + +void ModelRenderer::mapLineToPolygon(const cereal::XYZTData::Reader &line, float y_off, float z_off, + QPolygonF *pvd, int max_idx, bool allow_invert) { + const auto line_x = line.getX(), line_y = line.getY(), line_z = line.getZ(); + QPointF left, right; + pvd->clear(); + for (int i = 0; i <= max_idx; i++) { + // highly negative x positions are drawn above the frame and cause flickering, clip to zy plane of camera + if (line_x[i] < 0) continue; + + bool l = mapToScreen(line_x[i], line_y[i] - y_off, line_z[i] + z_off, &left); + bool r = mapToScreen(line_x[i], line_y[i] + y_off, line_z[i] + z_off, &right); + if (l && r) { + // For wider lines the drawn polygon will "invert" when going over a hill and cause artifacts + if (!allow_invert && pvd->size() && left.y() > pvd->back().y()) { + continue; + } + pvd->push_back(left); + pvd->push_front(right); + } + } +} diff --git a/selfdrive/ui/qt/onroad/model.h b/selfdrive/ui/qt/onroad/model.h new file mode 100644 index 000000000000000..79547e4b8314513 --- /dev/null +++ b/selfdrive/ui/qt/onroad/model.h @@ -0,0 +1,39 @@ +#pragma once + +#include +#include + +#include "selfdrive/ui/ui.h" + +class ModelRenderer { +public: + ModelRenderer() {} + void setTransform(const Eigen::Matrix3f &transform) { car_space_transform = transform; } + void draw(QPainter &painter, const QRect &surface_rect); + +private: + bool mapToScreen(float in_x, float in_y, float in_z, QPointF *out); + void mapLineToPolygon(const cereal::XYZTData::Reader &line, float y_off, float z_off, + QPolygonF *pvd, int max_idx, bool allow_invert = true); + void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd, const QRect &surface_rect); + void update_leads(const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line); + void update_model(const cereal::ModelDataV2::Reader &model, const cereal::RadarState::LeadData::Reader &lead); + void drawLaneLines(QPainter &painter); + void drawPath(QPainter &painter, const cereal::ModelDataV2::Reader &model, int height); + void updatePathGradient(QLinearGradient &bg); + QColor blendColors(const QColor &start, const QColor &end, float t); + + bool longitudinal_control = false; + bool experimental_mode = false; + float blend_factor = 1.0f; + bool prev_allow_throttle = true; + float lane_line_probs[4] = {}; + float road_edge_stds[2] = {}; + float path_offset_z = 1.22f; + QPolygonF track_vertices; + QPolygonF lane_line_vertices[4] = {}; + QPolygonF road_edge_vertices[2] = {}; + QPointF lead_vertices[2] = {}; + Eigen::Matrix3f car_space_transform = Eigen::Matrix3f::Zero(); + QRectF clip_region; +}; diff --git a/selfdrive/ui/qt/onroad/onroad_home.cc b/selfdrive/ui/qt/onroad/onroad_home.cc index 66eb1812e63a94c..080f9bd50fa4a94 100644 --- a/selfdrive/ui/qt/onroad/onroad_home.cc +++ b/selfdrive/ui/qt/onroad/onroad_home.cc @@ -3,11 +3,6 @@ #include #include -#ifdef ENABLE_MAPS -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/ui/qt/maps/map_panel.h" -#endif - #include "selfdrive/ui/qt/util.h" OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { @@ -26,15 +21,10 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { split->addWidget(nvg); if (getenv("DUAL_CAMERA_VIEW")) { - CameraWidget *arCam = new CameraWidget("camerad", VISION_STREAM_ROAD, true, this); + CameraWidget *arCam = new CameraWidget("camerad", VISION_STREAM_ROAD, this); split->insertWidget(0, arCam); } - if (getenv("MAP_RENDER_VIEW")) { - CameraWidget *map_render = new CameraWidget("navd", VISION_STREAM_MAP, false, this); - split->insertWidget(0, map_render); - } - stacked_layout->addWidget(split_wrapper); alerts = new OnroadAlerts(this); @@ -47,7 +37,6 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { setAttribute(Qt::WA_OpaquePaintEvent); QObject::connect(uiState(), &UIState::uiUpdate, this, &OnroadWindow::updateState); QObject::connect(uiState(), &UIState::offroadTransition, this, &OnroadWindow::offroadTransition); - QObject::connect(uiState(), &UIState::primeChanged, this, &OnroadWindow::primeChanged); } void OnroadWindow::updateState(const UIState &s) { @@ -55,12 +44,6 @@ void OnroadWindow::updateState(const UIState &s) { return; } - if (s.scene.map_on_left) { - split->setDirection(QBoxLayout::LeftToRight); - } else { - split->setDirection(QBoxLayout::RightToLeft); - } - alerts->updateState(s); nvg->updateState(s); @@ -72,57 +55,10 @@ void OnroadWindow::updateState(const UIState &s) { } } -void OnroadWindow::mousePressEvent(QMouseEvent* e) { -#ifdef ENABLE_MAPS - if (map != nullptr) { - bool sidebarVisible = geometry().x() > 0; - bool show_map = !sidebarVisible; - map->setVisible(show_map && !map->isVisible()); - } -#endif - // propagation event to parent(HomeWindow) - QWidget::mousePressEvent(e); -} - -void OnroadWindow::createMapWidget() { -#ifdef ENABLE_MAPS - auto m = new MapPanel(get_mapbox_settings()); - map = m; - QObject::connect(m, &MapPanel::mapPanelRequested, this, &OnroadWindow::mapPanelRequested); - QObject::connect(nvg->map_settings_btn, &MapSettingsButton::clicked, m, &MapPanel::toggleMapSettings); - nvg->map_settings_btn->setEnabled(true); - - m->setFixedWidth(topWidget(this)->width() / 2 - UI_BORDER_SIZE); - split->insertWidget(0, m); - // hidden by default, made visible when navRoute is published - m->setVisible(false); -#endif -} - void OnroadWindow::offroadTransition(bool offroad) { -#ifdef ENABLE_MAPS - if (!offroad) { - if (map == nullptr && (uiState()->hasPrime() || !MAPBOX_TOKEN.isEmpty())) { - createMapWidget(); - } - } -#endif alerts->clear(); } -void OnroadWindow::primeChanged(bool prime) { -#ifdef ENABLE_MAPS - if (map && (!prime && MAPBOX_TOKEN.isEmpty())) { - nvg->map_settings_btn->setEnabled(false); - nvg->map_settings_btn->setVisible(false); - map->deleteLater(); - map = nullptr; - } else if (!map && (prime || !MAPBOX_TOKEN.isEmpty())) { - createMapWidget(); - } -#endif -} - void OnroadWindow::paintEvent(QPaintEvent *event) { QPainter p(this); p.fillRect(rect(), QColor(bg.red(), bg.green(), bg.blue(), 255)); diff --git a/selfdrive/ui/qt/onroad/onroad_home.h b/selfdrive/ui/qt/onroad/onroad_home.h index 4976f56a67caced..c321d2d44f479ce 100644 --- a/selfdrive/ui/qt/onroad/onroad_home.h +++ b/selfdrive/ui/qt/onroad/onroad_home.h @@ -8,24 +8,15 @@ class OnroadWindow : public QWidget { public: OnroadWindow(QWidget* parent = 0); - bool isMapVisible() const { return map && map->isVisible(); } - void showMapPanel(bool show) { if (map) map->setVisible(show); } - -signals: - void mapPanelRequested(); private: - void createMapWidget(); void paintEvent(QPaintEvent *event); - void mousePressEvent(QMouseEvent* e) override; OnroadAlerts *alerts; AnnotatedCameraWidget *nvg; QColor bg = bg_colors[STATUS_DISENGAGED]; - QWidget *map = nullptr; QHBoxLayout* split; private slots: void offroadTransition(bool offroad); - void primeChanged(bool prime); void updateState(const UIState &s); }; diff --git a/selfdrive/ui/qt/prime_state.cc b/selfdrive/ui/qt/prime_state.cc new file mode 100644 index 000000000000000..f12daf1e3ccd71d --- /dev/null +++ b/selfdrive/ui/qt/prime_state.cc @@ -0,0 +1,48 @@ +#include "selfdrive/ui/qt/prime_state.h" + +#include + +#include "selfdrive/ui/qt/api.h" +#include "selfdrive/ui/qt/request_repeater.h" +#include "selfdrive/ui/qt/util.h" + +PrimeState::PrimeState(QObject* parent) : QObject(parent) { + const char *env_prime_type = std::getenv("PRIME_TYPE"); + auto type = env_prime_type ? env_prime_type : Params().get("PrimeType"); + + if (!type.empty()) { + prime_type = static_cast(std::atoi(type.c_str())); + } + + if (auto dongleId = getDongleId()) { + QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/"; + RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_Device", 5); + QObject::connect(repeater, &RequestRepeater::requestDone, this, &PrimeState::handleReply); + } + + // Emit the initial state change + QTimer::singleShot(1, [this]() { emit changed(prime_type); }); +} + +void PrimeState::handleReply(const QString& response, bool success) { + if (!success) return; + + QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8()); + if (doc.isNull()) { + qDebug() << "JSON Parse failed on getting pairing and PrimeState status"; + return; + } + + QJsonObject json = doc.object(); + bool is_paired = json["is_paired"].toBool(); + auto type = static_cast(json["prime_type"].toInt()); + setType(is_paired ? type : PrimeState::PRIME_TYPE_UNPAIRED); +} + +void PrimeState::setType(PrimeState::Type type) { + if (type != prime_type) { + prime_type = type; + Params().put("PrimeType", std::to_string(prime_type)); + emit changed(prime_type); + } +} diff --git a/selfdrive/ui/qt/prime_state.h b/selfdrive/ui/qt/prime_state.h new file mode 100644 index 000000000000000..0e2e3bb043112dc --- /dev/null +++ b/selfdrive/ui/qt/prime_state.h @@ -0,0 +1,33 @@ +#pragma once + +#include + +class PrimeState : public QObject { + Q_OBJECT + +public: + + enum Type { + PRIME_TYPE_UNKNOWN = -2, + PRIME_TYPE_UNPAIRED = -1, + PRIME_TYPE_NONE = 0, + PRIME_TYPE_MAGENTA = 1, + PRIME_TYPE_LITE = 2, + PRIME_TYPE_BLUE = 3, + PRIME_TYPE_MAGENTA_NEW = 4, + PRIME_TYPE_PURPLE = 5, + }; + + PrimeState(QObject *parent); + void setType(PrimeState::Type type); + inline PrimeState::Type currentType() const { return prime_type; } + inline bool isSubscribed() const { return prime_type > PrimeState::PRIME_TYPE_NONE; } + +signals: + void changed(PrimeState::Type prime_type); + +private: + void handleReply(const QString &response, bool success); + + PrimeState::Type prime_type = PrimeState::PRIME_TYPE_UNKNOWN; +}; diff --git a/selfdrive/ui/qt/qt_window.cc b/selfdrive/ui/qt/qt_window.cc index f71cea04e9da8ca..8d3d7cf72e400f1 100644 --- a/selfdrive/ui/qt/qt_window.cc +++ b/selfdrive/ui/qt/qt_window.cc @@ -18,7 +18,9 @@ void setMainWindow(QWidget *w) { wl_surface *s = reinterpret_cast(native->nativeResourceForWindow("surface", w->windowHandle())); wl_surface_set_buffer_transform(s, WL_OUTPUT_TRANSFORM_270); wl_surface_commit(s); - w->showFullScreen(); + + w->setWindowState(Qt::WindowFullScreen); + w->setVisible(true); // ensure we have a valid eglDisplay, otherwise the ui will silently fail void *egl = native->nativeResourceForWindow("egldisplay", w->windowHandle()); diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc index aff9b015b3a40de..c716b6b4e970d7e 100644 --- a/selfdrive/ui/qt/setup/setup.cc +++ b/selfdrive/ui/qt/setup/setup.cc @@ -408,7 +408,7 @@ Setup::Setup(QWidget *parent) : QStackedWidget(parent) { std::stringstream buffer; buffer << std::ifstream("/sys/class/hwmon/hwmon1/in1_input").rdbuf(); float voltage = (float)std::atoi(buffer.str().c_str()) / 1000.; - if (voltage < 7) { + if (voltage > 0 && voltage < 7) { addWidget(low_voltage()); } diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index 75b966c9aaf7572..966396edc23aa15 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -37,7 +37,7 @@ Sidebar::Sidebar(QWidget *parent) : QFrame(parent), onroad(false), flag_pressed( QObject::connect(uiState(), &UIState::uiUpdate, this, &Sidebar::updateState); - pm = std::make_unique>({"userFlag"}); + pm = std::make_unique(std::vector{"userFlag"}); } void Sidebar::mousePressEvent(QMouseEvent *event) { @@ -74,9 +74,11 @@ void Sidebar::updateState(const UIState &s) { auto &sm = *(s.sm); + networking = networking ? networking : window()->findChild(""); + bool tethering_on = networking && networking->wifi->tethering_on; auto deviceState = sm["deviceState"].getDeviceState(); - setProperty("netType", network_type[deviceState.getNetworkType()]); - int strength = (int)deviceState.getNetworkStrength(); + setProperty("netType", tethering_on ? "Hotspot": network_type[deviceState.getNetworkType()]); + int strength = tethering_on ? 4 : (int)deviceState.getNetworkStrength(); setProperty("netStrength", strength > 0 ? strength + 1 : 0); ItemStatus connectStatus; @@ -102,8 +104,6 @@ void Sidebar::updateState(const UIState &s) { ItemStatus pandaStatus = {{tr("VEHICLE"), tr("ONLINE")}, good_color}; if (s.scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) { pandaStatus = {{tr("NO"), tr("PANDA")}, danger_color}; - } else if (s.scene.started && !sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK()) { - pandaStatus = {{tr("GPS"), tr("SEARCH")}, warning_color}; } setProperty("pandaStatus", QVariant::fromValue(pandaStatus)); } @@ -133,8 +133,8 @@ void Sidebar::paintEvent(QPaintEvent *event) { p.setFont(InterFont(35)); p.setPen(QColor(0xff, 0xff, 0xff)); - const QRect r = QRect(50, 247, 100, 50); - p.drawText(r, Qt::AlignCenter, net_type); + const QRect r = QRect(58, 247, width() - 100, 50); + p.drawText(r, Qt::AlignLeft | Qt::AlignVCenter, net_type); // metrics drawMetric(p, temp_status.first, temp_status.second, 338); diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index f627aac810ec3dc..2091418e5286750 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -6,6 +6,7 @@ #include #include "selfdrive/ui/ui.h" +#include "selfdrive/ui/qt/network/networking.h" typedef QPair, QColor> ItemStatus; Q_DECLARE_METATYPE(ItemStatus); @@ -59,4 +60,5 @@ public slots: private: std::unique_ptr pm; + Networking *networking = nullptr; }; diff --git a/selfdrive/ui/qt/spinner_larch64 b/selfdrive/ui/qt/spinner_larch64 index 645bc4430e67739..1b59cd532e89393 100755 Binary files a/selfdrive/ui/qt/spinner_larch64 and b/selfdrive/ui/qt/spinner_larch64 differ diff --git a/selfdrive/ui/qt/text_larch64 b/selfdrive/ui/qt/text_larch64 index eb0f535bf3b5d5a..915e5f9014417c9 100755 Binary files a/selfdrive/ui/qt/text_larch64 and b/selfdrive/ui/qt/text_larch64 differ diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index 0bf5f2865e240af..399a1a98d7b3745 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -156,60 +156,6 @@ QPixmap loadPixmap(const QString &fileName, const QSize &size, Qt::AspectRatioMo } } -void drawRoundedRect(QPainter &painter, const QRectF &rect, qreal xRadiusTop, qreal yRadiusTop, qreal xRadiusBottom, qreal yRadiusBottom){ - qreal w_2 = rect.width() / 2; - qreal h_2 = rect.height() / 2; - - xRadiusTop = 100 * qMin(xRadiusTop, w_2) / w_2; - yRadiusTop = 100 * qMin(yRadiusTop, h_2) / h_2; - - xRadiusBottom = 100 * qMin(xRadiusBottom, w_2) / w_2; - yRadiusBottom = 100 * qMin(yRadiusBottom, h_2) / h_2; - - qreal x = rect.x(); - qreal y = rect.y(); - qreal w = rect.width(); - qreal h = rect.height(); - - qreal rxx2Top = w*xRadiusTop/100; - qreal ryy2Top = h*yRadiusTop/100; - - qreal rxx2Bottom = w*xRadiusBottom/100; - qreal ryy2Bottom = h*yRadiusBottom/100; - - QPainterPath path; - path.arcMoveTo(x, y, rxx2Top, ryy2Top, 180); - path.arcTo(x, y, rxx2Top, ryy2Top, 180, -90); - path.arcTo(x+w-rxx2Top, y, rxx2Top, ryy2Top, 90, -90); - path.arcTo(x+w-rxx2Bottom, y+h-ryy2Bottom, rxx2Bottom, ryy2Bottom, 0, -90); - path.arcTo(x, y+h-ryy2Bottom, rxx2Bottom, ryy2Bottom, 270, -90); - path.closeSubpath(); - - painter.drawPath(path); -} - -QColor interpColor(float xv, std::vector xp, std::vector fp) { - assert(xp.size() == fp.size()); - - int N = xp.size(); - int hi = 0; - - while (hi < N and xv > xp[hi]) hi++; - int low = hi - 1; - - if (hi == N && xv > xp[low]) { - return fp[fp.size() - 1]; - } else if (hi == 0){ - return fp[0]; - } else { - return QColor( - (xv - xp[low]) * (fp[hi].red() - fp[low].red()) / (xp[hi] - xp[low]) + fp[low].red(), - (xv - xp[low]) * (fp[hi].green() - fp[low].green()) / (xp[hi] - xp[low]) + fp[low].green(), - (xv - xp[low]) * (fp[hi].blue() - fp[low].blue()) / (xp[hi] - xp[low]) + fp[low].blue(), - (xv - xp[low]) * (fp[hi].alpha() - fp[low].alpha()) / (xp[hi] - xp[low]) + fp[low].alpha()); - } -} - static QHash load_bootstrap_icons() { QHash icons; diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index 2aae97b8602d3ee..2bf1a70a62a437c 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -26,9 +26,6 @@ void initApp(int argc, char *argv[], bool disable_hidpi = true); QWidget* topWidget(QWidget* widget); QPixmap loadPixmap(const QString &fileName, const QSize &size = {}, Qt::AspectRatioMode aspectRatioMode = Qt::KeepAspectRatio); QPixmap bootstrapPixmap(const QString &id); - -void drawRoundedRect(QPainter &painter, const QRectF &rect, qreal xRadiusTop, qreal yRadiusTop, qreal xRadiusBottom, qreal yRadiusBottom); -QColor interpColor(float xv, std::vector xp, std::vector fp); bool hasLongitudinalControl(const cereal::CarParams::Reader &car_params); struct InterFont : public QFont { diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index 914b04b65444459..674e5e999cb2cde 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -7,13 +7,7 @@ #endif #include -#include -#include -#include - #include -#include -#include namespace { @@ -66,40 +60,10 @@ const char frame_fragment_shader[] = "}\n"; #endif -mat4 get_driver_view_transform(int screen_width, int screen_height, int stream_width, int stream_height) { - const float driver_view_ratio = 2.0; - const float yscale = stream_height * driver_view_ratio / stream_width; - const float xscale = yscale*screen_height/screen_width*stream_width/stream_height; - mat4 transform = (mat4){{ - xscale, 0.0, 0.0, 0.0, - 0.0, yscale, 0.0, 0.0, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - return transform; -} - -mat4 get_fit_view_transform(float widget_aspect_ratio, float frame_aspect_ratio) { - float zx = 1, zy = 1; - if (frame_aspect_ratio > widget_aspect_ratio) { - zy = widget_aspect_ratio / frame_aspect_ratio; - } else { - zx = frame_aspect_ratio / widget_aspect_ratio; - } - - const mat4 frame_transform = {{ - zx, 0.0, 0.0, 0.0, - 0.0, zy, 0.0, 0.0, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - return frame_transform; -} - } // namespace -CameraWidget::CameraWidget(std::string stream_name, VisionStreamType type, bool zoom, QWidget* parent) : - stream_name(stream_name), active_stream_type(type), requested_stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { +CameraWidget::CameraWidget(std::string stream_name, VisionStreamType type, QWidget* parent) : + stream_name(stream_name), active_stream_type(type), requested_stream_type(type), QOpenGLWidget(parent) { setAttribute(Qt::WA_OpaquePaintEvent); qRegisterMetaType>("availableStreams"); QObject::connect(this, &CameraWidget::vipcThreadConnected, this, &CameraWidget::vipcConnected, Qt::BlockingQueuedConnection); @@ -115,7 +79,7 @@ CameraWidget::~CameraWidget() { glDeleteVertexArrays(1, &frame_vao); glDeleteBuffers(1, &frame_vbo); glDeleteBuffers(1, &frame_ibo); - glDeleteBuffers(2, textures); + glDeleteTextures(2, textures); } doneCurrent(); } @@ -214,59 +178,19 @@ void CameraWidget::availableStreamsUpdated(std::set streams) { available_streams = streams; } -void CameraWidget::updateFrameMat() { - int w = glWidth(), h = glHeight(); +mat4 CameraWidget::calcFrameMatrix() { + // Scale the frame to fit the widget while maintaining the aspect ratio. + float widget_aspect_ratio = (float)width() / height(); + float frame_aspect_ratio = (float)stream_width / stream_height; + float zx = std::min(frame_aspect_ratio / widget_aspect_ratio, 1.0f); + float zy = std::min(widget_aspect_ratio / frame_aspect_ratio, 1.0f); - if (zoomed_view) { - if (active_stream_type == VISION_STREAM_DRIVER) { - if (stream_width > 0 && stream_height > 0) { - frame_mat = get_driver_view_transform(w, h, stream_width, stream_height); - } - } else { - // Project point at "infinity" to compute x and y offsets - // to ensure this ends up in the middle of the screen - // for narrow come and a little lower for wide cam. - // TODO: use proper perspective transform? - if (active_stream_type == VISION_STREAM_WIDE_ROAD) { - intrinsic_matrix = ECAM_INTRINSIC_MATRIX; - zoom = 2.0; - } else { - intrinsic_matrix = FCAM_INTRINSIC_MATRIX; - zoom = 1.1; - } - const vec3 inf = {{1000., 0., 0.}}; - const vec3 Ep = matvecmul3(calibration, inf); - const vec3 Kep = matvecmul3(intrinsic_matrix, Ep); - - float x_offset_ = (Kep.v[0] / Kep.v[2] - intrinsic_matrix.v[2]) * zoom; - float y_offset_ = (Kep.v[1] / Kep.v[2] - intrinsic_matrix.v[5]) * zoom; - - float max_x_offset = intrinsic_matrix.v[2] * zoom - w / 2 - 5; - float max_y_offset = intrinsic_matrix.v[5] * zoom - h / 2 - 5; - - x_offset = std::clamp(x_offset_, -max_x_offset, max_x_offset); - y_offset = std::clamp(y_offset_, -max_y_offset, max_y_offset); - - float zx = zoom * 2 * intrinsic_matrix.v[2] / w; - float zy = zoom * 2 * intrinsic_matrix.v[5] / h; - const mat4 frame_transform = {{ - zx, 0.0, 0.0, -x_offset / w * 2, - 0.0, zy, 0.0, y_offset / h * 2, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - frame_mat = frame_transform; - } - } else if (stream_width > 0 && stream_height > 0) { - // fit frame to widget size - float widget_aspect_ratio = (float)w / h; - float frame_aspect_ratio = (float)stream_width / stream_height; - frame_mat = get_fit_view_transform(widget_aspect_ratio, frame_aspect_ratio); - } -} - -void CameraWidget::updateCalibration(const mat3 &calib) { - calibration = calib; + return mat4{{ + zx, 0.0, 0.0, 0.0, + 0.0, zy, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, + 0.0, 0.0, 0.0, 1.0, + }}; } void CameraWidget::paintGL() { @@ -293,7 +217,7 @@ void CameraWidget::paintGL() { VisionBuf *frame = frames[frame_idx].second; assert(frame != nullptr); - updateFrameMat(); + auto frame_mat = calcFrameMatrix(); glViewport(0, 0, glWidth(), glHeight()); glBindVertexArray(frame_vao); diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 85ec49873579dc4..29aa8493c72dfac 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -23,18 +23,16 @@ #endif #include "msgq/visionipc/visionipc_client.h" -#include "system/camerad/cameras/camera_common.h" #include "selfdrive/ui/ui.h" const int FRAME_BUFFER_SIZE = 5; -static_assert(FRAME_BUFFER_SIZE <= YUV_BUFFER_COUNT); class CameraWidget : public QOpenGLWidget, protected QOpenGLFunctions { Q_OBJECT public: using QOpenGLWidget::QOpenGLWidget; - explicit CameraWidget(std::string stream_name, VisionStreamType stream_type, bool zoom, QWidget* parent = nullptr); + explicit CameraWidget(std::string stream_name, VisionStreamType stream_type, QWidget* parent = nullptr); ~CameraWidget(); void setBackgroundColor(const QColor &color) { bg = color; } void setFrameId(int frame_id) { draw_frame_id = frame_id; } @@ -51,21 +49,17 @@ class CameraWidget : public QOpenGLWidget, protected QOpenGLFunctions { protected: void paintGL() override; void initializeGL() override; - void resizeGL(int w, int h) override { updateFrameMat(); } void showEvent(QShowEvent *event) override; void mouseReleaseEvent(QMouseEvent *event) override { emit clicked(); } - virtual void updateFrameMat(); - void updateCalibration(const mat3 &calib); + virtual mat4 calcFrameMatrix(); void vipcThread(); void clearFrames(); int glWidth(); int glHeight(); - bool zoomed_view; GLuint frame_vao, frame_vbo, frame_ibo; GLuint textures[2]; - mat4 frame_mat = {}; std::unique_ptr program; QColor bg = QColor("#000000"); @@ -81,14 +75,6 @@ class CameraWidget : public QOpenGLWidget, protected QOpenGLFunctions { std::atomic requested_stream_type; std::set available_streams; QThread *vipc_thread = nullptr; - - // Calibration - float x_offset = 0; - float y_offset = 0; - float zoom = 1.0; - mat3 calibration = DEFAULT_CALIBRATION; - mat3 intrinsic_matrix = FCAM_INTRINSIC_MATRIX; - std::recursive_mutex frame_lock; std::deque> frames; uint32_t draw_frame_id = 0; diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index aa304e0df68feeb..aebf934f2a25664 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -262,7 +262,7 @@ class ListWidget : public QWidget { outer_layout.addLayout(&inner_layout); inner_layout.setMargin(0); inner_layout.setSpacing(25); // default spacing is 25 - outer_layout.addStretch(); + outer_layout.addStretch(1); } inline void addItem(QWidget *w) { inner_layout.addWidget(w); } inline void addItem(QLayout *layout) { inner_layout.addLayout(layout); } diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc index 4ff0de29f9fe2ca..b0b6b4c23bedec7 100644 --- a/selfdrive/ui/qt/widgets/input.cc +++ b/selfdrive/ui/qt/widgets/input.cc @@ -151,7 +151,7 @@ InputDialog::InputDialog(const QString &title, QWidget *parent, const QString &s QString InputDialog::getText(const QString &prompt, QWidget *parent, const QString &subtitle, bool secret, int minLength, const QString &defaultText) { - InputDialog d = InputDialog(prompt, parent, subtitle, secret); + InputDialog d(prompt, parent, subtitle, secret); d.line->setText(defaultText); d.setMinLength(minLength); const int ret = d.exec(); @@ -230,17 +230,17 @@ ConfirmationDialog::ConfirmationDialog(const QString &prompt_text, const QString } bool ConfirmationDialog::alert(const QString &prompt_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, tr("Ok"), "", false, parent); + ConfirmationDialog d(prompt_text, tr("Ok"), "", false, parent); return d.exec(); } bool ConfirmationDialog::confirm(const QString &prompt_text, const QString &confirm_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, confirm_text, tr("Cancel"), false, parent); + ConfirmationDialog d(prompt_text, confirm_text, tr("Cancel"), false, parent); return d.exec(); } bool ConfirmationDialog::rich(const QString &prompt_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, tr("Ok"), "", true, parent); + ConfirmationDialog d(prompt_text, tr("Ok"), "", true, parent); return d.exec(); } @@ -328,7 +328,7 @@ MultiOptionDialog::MultiOptionDialog(const QString &prompt_text, const QStringLi } QString MultiOptionDialog::getSelection(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent) { - MultiOptionDialog d = MultiOptionDialog(prompt_text, l, current, parent); + MultiOptionDialog d(prompt_text, l, current, parent); if (d.exec()) { return d.selection; } diff --git a/selfdrive/ui/qt/widgets/keyboard.cc b/selfdrive/ui/qt/widgets/keyboard.cc index 370e9a53ccb62f9..629ea94f20f5ce2 100644 --- a/selfdrive/ui/qt/widgets/keyboard.cc +++ b/selfdrive/ui/qt/widgets/keyboard.cc @@ -11,7 +11,7 @@ const QString BACKSPACE_KEY = "⌫"; const QString ENTER_KEY = "→"; -const QMap KEY_STRETCH = {{" ", 5}, {ENTER_KEY, 2}}; +const QMap KEY_STRETCH = {{" ", 3}, {ENTER_KEY, 2}}; const QStringList CONTROL_BUTTONS = {"↑", "↓", "ABC", "#+=", "123", BACKSPACE_KEY, ENTER_KEY}; @@ -107,7 +107,7 @@ Keyboard::Keyboard(QWidget *parent) : QFrame(parent) { {"q", "w", "e", "r", "t", "y", "u", "i", "o", "p"}, {"a", "s", "d", "f", "g", "h", "j", "k", "l"}, {"↑", "z", "x", "c", "v", "b", "n", "m", BACKSPACE_KEY}, - {"123", " ", ".", ENTER_KEY}, + {"123", "/", "-", " ", ".", ENTER_KEY}, }; main_layout->addWidget(new KeyboardLayout(this, lowercase)); diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.cc b/selfdrive/ui/qt/widgets/offroad_alerts.cc index 74ece36d15bb5d5..f630875978d7010 100644 --- a/selfdrive/ui/qt/widgets/offroad_alerts.cc +++ b/selfdrive/ui/qt/widgets/offroad_alerts.cc @@ -70,7 +70,7 @@ AbstractAlert::AbstractAlert(bool hasRebootBtn, QWidget *parent) : QFrame(parent int OffroadAlert::refresh() { // build widgets for each offroad alert on first refresh if (alerts.empty()) { - QString json = util::read_file("../controls/lib/alerts_offroad.json").c_str(); + QString json = util::read_file("../selfdrived/alerts_offroad.json").c_str(); QJsonObject obj = QJsonDocument::fromJson(json.toUtf8()).object(); // descending sort labels by severity diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index 2621612f67f4320..62f5c0ab5054bde 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -155,7 +155,7 @@ PrimeAdWidget::PrimeAdWidget(QWidget* parent) : QFrame(parent) { main_layout->addWidget(features, 0, Qt::AlignBottom); main_layout->addSpacing(30); - QVector bullets = {tr("Remote access"), tr("24/7 LTE connectivity"), tr("1 year of drive storage"), tr("Turn-by-turn navigation")}; + QVector bullets = {tr("Remote access"), tr("24/7 LTE connectivity"), tr("1 year of drive storage"), tr("Remote snapshots")}; for (auto &b : bullets) { const QString check = " "; QLabel *l = new QLabel(check + b); @@ -180,20 +180,20 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { QFrame* finishRegistration = new QFrame; finishRegistration->setObjectName("primeWidget"); - QVBoxLayout* finishRegistationLayout = new QVBoxLayout(finishRegistration); - finishRegistationLayout->setSpacing(38); - finishRegistationLayout->setContentsMargins(64, 48, 64, 48); + QVBoxLayout* finishRegistrationLayout = new QVBoxLayout(finishRegistration); + finishRegistrationLayout->setSpacing(38); + finishRegistrationLayout->setContentsMargins(64, 48, 64, 48); QLabel* registrationTitle = new QLabel(tr("Finish Setup")); registrationTitle->setStyleSheet("font-size: 75px; font-weight: bold;"); - finishRegistationLayout->addWidget(registrationTitle); + finishRegistrationLayout->addWidget(registrationTitle); QLabel* registrationDescription = new QLabel(tr("Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.")); registrationDescription->setWordWrap(true); registrationDescription->setStyleSheet("font-size: 50px; font-weight: light;"); - finishRegistationLayout->addWidget(registrationDescription); + finishRegistrationLayout->addWidget(registrationDescription); - finishRegistationLayout->addStretch(); + finishRegistrationLayout->addStretch(); QPushButton* pair = new QPushButton(tr("Pair device")); pair->setStyleSheet(R"( @@ -208,7 +208,7 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { background-color: #3049F4; } )"); - finishRegistationLayout->addWidget(pair); + finishRegistrationLayout->addWidget(pair); popup = new PairingPopup(this); QObject::connect(pair, &QPushButton::clicked, popup, &PairingPopup::exec); @@ -225,9 +225,6 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { content_layout->setContentsMargins(0, 0, 0, 0); content_layout->setSpacing(30); - primeUser = new PrimeUserWidget; - content_layout->addWidget(primeUser); - WiFiPromptWidget *wifi_prompt = new WiFiPromptWidget; QObject::connect(wifi_prompt, &WiFiPromptWidget::openSettings, this, &SetupWidget::openSettings); content_layout->addWidget(wifi_prompt); @@ -235,7 +232,6 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { mainLayout->addWidget(content); - primeUser->setVisible(uiState()->hasPrime()); mainLayout->setCurrentIndex(1); setStyleSheet(R"( @@ -250,35 +246,12 @@ SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { sp_retain.setRetainSizeWhenHidden(true); setSizePolicy(sp_retain); - // set up API requests - if (auto dongleId = getDongleId()) { - QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/"; - RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_Device", 5); - - QObject::connect(repeater, &RequestRepeater::requestDone, this, &SetupWidget::replyFinished); - } -} - -void SetupWidget::replyFinished(const QString &response, bool success) { - if (!success) return; - - QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8()); - if (doc.isNull()) { - qDebug() << "JSON Parse failed on getting pairing and prime status"; - return; - } - - QJsonObject json = doc.object(); - bool is_paired = json["is_paired"].toBool(); - PrimeType prime_type = static_cast(json["prime_type"].toInt()); - uiState()->setPrimeType(is_paired ? prime_type : PrimeType::UNPAIRED); - - if (!is_paired) { - mainLayout->setCurrentIndex(0); - } else { - popup->reject(); - - primeUser->setVisible(uiState()->hasPrime()); - mainLayout->setCurrentIndex(1); - } + QObject::connect(uiState()->prime_state, &PrimeState::changed, [this](PrimeState::Type type) { + if (type == PrimeState::PRIME_TYPE_UNPAIRED) { + mainLayout->setCurrentIndex(0); // Display "Pair your device" widget + } else { + popup->reject(); + mainLayout->setCurrentIndex(1); // Display Wi-Fi prompt widget + } + }); } diff --git a/selfdrive/ui/qt/widgets/prime.h b/selfdrive/ui/qt/widgets/prime.h index 63341c4ceae8d99..d1ba334e81e0d66 100644 --- a/selfdrive/ui/qt/widgets/prime.h +++ b/selfdrive/ui/qt/widgets/prime.h @@ -66,8 +66,4 @@ class SetupWidget : public QFrame { private: PairingPopup *popup; QStackedWidget *mainLayout; - PrimeUserWidget *primeUser; - -private slots: - void replyFinished(const QString &response, bool success); }; diff --git a/selfdrive/ui/qt/window.cc b/selfdrive/ui/qt/window.cc index 6b579fcc5dc80c0..e1ec916c6fda0e0 100644 --- a/selfdrive/ui/qt/window.cc +++ b/selfdrive/ui/qt/window.cc @@ -20,9 +20,6 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { onboardingWindow->showTrainingGuide(); main_layout->setCurrentWidget(onboardingWindow); }); - QObject::connect(settingsWindow, &SettingsWindow::showDriverView, [=] { - homeWindow->showDriverView(true); - }); onboardingWindow = new OnboardingWindow(this); main_layout->addWidget(onboardingWindow); diff --git a/selfdrive/ui/raylib/.gitignore b/selfdrive/ui/raylib/.gitignore new file mode 100644 index 000000000000000..c66ae096aa77c35 --- /dev/null +++ b/selfdrive/ui/raylib/.gitignore @@ -0,0 +1 @@ +_spinner diff --git a/selfdrive/ui/raylib/SConscript b/selfdrive/ui/raylib/SConscript new file mode 100644 index 000000000000000..d603f263e181d93 --- /dev/null +++ b/selfdrive/ui/raylib/SConscript @@ -0,0 +1,17 @@ +Import('env', 'arch', 'common') + +raylib_env = env.Clone() +raylib_util_lib = env.Library("raylib_util_lib", ['util.cc'], LIBS='raylib') +linked_libs = ['raylib', raylib_util_lib, common] +raylib_env['LIBPATH'] += [f'#third_party/raylib/{arch}/'] + +mac_frameworks = [] +if arch == "Darwin": + mac_frameworks += ['OpenCL', 'CoreVideo', 'Cocoa', 'GLUT', 'CoreFoundation', 'OpenGL', 'IOKit'] +elif arch == 'larch64': + linked_libs += [] +else: + linked_libs += ['OpenCL', 'dl', 'pthread'] + +if arch != 'aarch64': + raylib_env.Program("_spinner", ["spinner.cc"], LIBS=linked_libs, FRAMEWORKS=mac_frameworks) diff --git a/selfdrive/ui/raylib/spinner.cc b/selfdrive/ui/raylib/spinner.cc new file mode 100644 index 000000000000000..99aa5f3269c70bc --- /dev/null +++ b/selfdrive/ui/raylib/spinner.cc @@ -0,0 +1,69 @@ +#include +#include +#include + +#include "selfdrive/ui/raylib/util.h" +#include "third_party/raylib/include/raylib.h" + +constexpr int kProgressBarWidth = 1000; +constexpr int kProgressBarHeight = 20; +constexpr float kRotationRate = 12.0f; +constexpr int kMargin = 200; +constexpr int kTextureSize = 360; +constexpr int kFontSize = 80; + +int main(int argc, char *argv[]) { + initApp("spinner", 30); + + // Turn off input buffering for std::cin + std::cin.sync_with_stdio(false); + std::cin.tie(nullptr); + + Texture2D commaTexture = LoadTextureResized("../../assets/img_spinner_comma.png", kTextureSize); + Texture2D spinnerTexture = LoadTextureResized("../../assets/img_spinner_track.png", kTextureSize); + + float rotation = 0.0f; + std::string userInput; + + while (!WindowShouldClose()) { + BeginDrawing(); + ClearBackground(BLACK); + + rotation = fmod(rotation + kRotationRate, 360.0f); + Vector2 center = {GetScreenWidth() / 2.0f, GetScreenHeight() / 2.0f}; + const Vector2 spinnerOrigin{kTextureSize / 2.0f, kTextureSize / 2.0f}; + const Vector2 commaPosition{center.x - kTextureSize / 2.0f, center.y - kTextureSize / 2.0f}; + + // Draw rotating spinner and static comma logo + DrawTexturePro(spinnerTexture, {0, 0, (float)kTextureSize, (float)kTextureSize}, + {center.x, center.y, (float)kTextureSize, (float)kTextureSize}, + spinnerOrigin, rotation, WHITE); + DrawTextureV(commaTexture, commaPosition, WHITE); + + // Check for user input + if (std::cin.rdbuf()->in_avail() > 0) { + std::getline(std::cin, userInput); + } + + // Display either a progress bar or user input text based on input + if (!userInput.empty()) { + float yPos = GetScreenHeight() - kMargin - kProgressBarHeight; + if (std::all_of(userInput.begin(), userInput.end(), ::isdigit)) { + Rectangle bar = {center.x - kProgressBarWidth / 2.0f, yPos, kProgressBarWidth, kProgressBarHeight}; + DrawRectangleRounded(bar, 0.5f, 10, GRAY); + + int progress = std::clamp(std::stoi(userInput), 0, 100); + bar.width *= progress / 100.0f; + DrawRectangleRounded(bar, 0.5f, 10, RAYWHITE); + } else { + Vector2 textSize = MeasureTextEx(getFont(), userInput.c_str(), kFontSize, 1.0); + DrawTextEx(getFont(), userInput.c_str(), {center.x - textSize.x / 2, yPos}, kFontSize, 1.0, WHITE); + } + } + + EndDrawing(); + } + + CloseWindow(); + return 0; +} diff --git a/selfdrive/ui/raylib/util.cc b/selfdrive/ui/raylib/util.cc new file mode 100644 index 000000000000000..73c0e4e0b730541 --- /dev/null +++ b/selfdrive/ui/raylib/util.cc @@ -0,0 +1,56 @@ +#include "selfdrive/ui/raylib/util.h" + +#include + +#undef GREEN +#undef RED +#undef YELLOW +#include "common/swaglog.h" +#include "system/hardware/hw.h" + +constexpr std::array(FontWeight::Count)> FONT_FILE_PATHS = { + "../../assets/fonts/Inter-Black.ttf", + "../../assets/fonts/Inter-Bold.ttf", + "../../assets/fonts/Inter-ExtraBold.ttf", + "../../assets/fonts/Inter-ExtraLight.ttf", + "../../assets/fonts/Inter-Medium.ttf", + "../../assets/fonts/Inter-Regular.ttf", + "../../assets/fonts/Inter-SemiBold.ttf", + "../../assets/fonts/Inter-Thin.ttf", +}; + +struct FontManager { + FontManager() { + for (int i = 0; i < fonts.size(); ++i) { + fonts[i] = LoadFontEx(FONT_FILE_PATHS[i], 120, nullptr, 250); + SetTextureFilter(fonts[i].texture, TEXTURE_FILTER_TRILINEAR); + } + } + + ~FontManager() { + for (auto &f : fonts) UnloadFont(f); + } + + std::array(FontWeight::Count)> fonts; +}; + +const Font& getFont(FontWeight weight) { + static FontManager font_manager; + return font_manager.fonts[(int)weight]; +} + +Texture2D LoadTextureResized(const char *fileName, int size) { + Image img = LoadImage(fileName); + ImageResize(&img, size, size); + Texture2D texture = LoadTextureFromImage(img); + SetTextureFilter(texture, TEXTURE_FILTER_TRILINEAR); + return texture; +} + +void initApp(const char *title, int fps) { + Hardware::set_display_power(true); + Hardware::set_brightness(65); + // SetTraceLogLevel(LOG_NONE); + InitWindow(0, 0, title); + SetTargetFPS(fps); +} diff --git a/selfdrive/ui/raylib/util.h b/selfdrive/ui/raylib/util.h new file mode 100644 index 000000000000000..da2ec7118be5ef9 --- /dev/null +++ b/selfdrive/ui/raylib/util.h @@ -0,0 +1,21 @@ +#pragma once + +#include + +#include "third_party/raylib/include/raylib.h" + +enum class FontWeight { + Normal, + Bold, + ExtraBold, + ExtraLight, + Medium, + Regular, + SemiBold, + Thin, + Count // To represent the total number of fonts +}; + +void initApp(const char *title, int fps); +const Font& getFont(FontWeight weight = FontWeight::Normal); +Texture2D LoadTextureResized(const char *fileName, int size); diff --git a/selfdrive/ui/soundd.py b/selfdrive/ui/soundd.py index 0550a7db9ec01e8..3cd6ae582078b73 100644 --- a/selfdrive/ui/soundd.py +++ b/selfdrive/ui/soundd.py @@ -17,7 +17,7 @@ SAMPLE_BUFFER = 4096 # (approx 100ms) MAX_VOLUME = 1.0 MIN_VOLUME = 0.1 -CONTROLS_TIMEOUT = 5 # 5 seconds +SELFDRIVE_STATE_TIMEOUT = 5 # 5 seconds FILTER_DT = 1. / (micd.SAMPLE_RATE / micd.FFT_SAMPLES) AMBIENT_DB = 30 # DB where MIN_VOLUME is applied @@ -40,11 +40,11 @@ AudibleAlert.warningImmediate: ("warning_immediate.wav", None, MAX_VOLUME), } -def check_controls_timeout_alert(sm): - controls_missing = time.monotonic() - sm.recv_time['controlsState'] +def check_selfdrive_timeout_alert(sm): + ss_missing = time.monotonic() - sm.recv_time['selfdriveState'] - if controls_missing > CONTROLS_TIMEOUT: - if sm['controlsState'].enabled and (controls_missing - CONTROLS_TIMEOUT) < 10: + if ss_missing > SELFDRIVE_STATE_TIMEOUT: + if sm['selfdriveState'].enabled and (ss_missing - SELFDRIVE_STATE_TIMEOUT) < 10: return True return False @@ -58,7 +58,7 @@ def __init__(self): self.current_volume = MIN_VOLUME self.current_sound_frame = 0 - self.controls_timeout_alert = False + self.selfdrive_timeout_alert = False self.spl_filter_weighted = FirstOrderFilter(0, 2.5, FILTER_DT, initialized=False) @@ -111,15 +111,15 @@ def update_alert(self, new_alert): self.current_sound_frame = 0 def get_audible_alert(self, sm): - if sm.updated['controlsState']: - new_alert = sm['controlsState'].alertSound.raw + if sm.updated['selfdriveState']: + new_alert = sm['selfdriveState'].alertSound.raw self.update_alert(new_alert) - elif check_controls_timeout_alert(sm): + elif check_selfdrive_timeout_alert(sm): self.update_alert(AudibleAlert.warningImmediate) - self.controls_timeout_alert = True - elif self.controls_timeout_alert: + self.selfdrive_timeout_alert = True + elif self.selfdrive_timeout_alert: self.update_alert(AudibleAlert.none) - self.controls_timeout_alert = False + self.selfdrive_timeout_alert = False def calculate_volume(self, weighted_db): volume = ((weighted_db - AMBIENT_DB) / DB_SCALE) * (MAX_VOLUME - MIN_VOLUME) + MIN_VOLUME @@ -136,7 +136,7 @@ def soundd_thread(self): # sounddevice must be imported after forking processes import sounddevice as sd - sm = messaging.SubMaster(['controlsState', 'microphone']) + sm = messaging.SubMaster(['selfdriveState', 'microphone']) with self.get_stream(sd) as stream: rk = Ratekeeper(20) diff --git a/selfdrive/ui/tests/.gitignore b/selfdrive/ui/tests/.gitignore index 6c624b66d3ecc8d..91898ac59a1e113 100644 --- a/selfdrive/ui/tests/.gitignore +++ b/selfdrive/ui/tests/.gitignore @@ -1,6 +1,3 @@ test -playsound -test_sound test_translations -ui_snapshot -test_ui/report \ No newline at end of file +test_ui/report_1 \ No newline at end of file diff --git a/selfdrive/ui/tests/create_test_translations.sh b/selfdrive/ui/tests/create_test_translations.sh index 451a3cbfb04c107..ed0890d94651d4d 100755 --- a/selfdrive/ui/tests/create_test_translations.sh +++ b/selfdrive/ui/tests/create_test_translations.sh @@ -1,4 +1,4 @@ -#!/bin/bash +#!/usr/bin/env bash set -e diff --git a/selfdrive/ui/tests/cycle_offroad_alerts.py b/selfdrive/ui/tests/cycle_offroad_alerts.py index 75b19ceb9025fab..e468d88e0e814ff 100755 --- a/selfdrive/ui/tests/cycle_offroad_alerts.py +++ b/selfdrive/ui/tests/cycle_offroad_alerts.py @@ -6,12 +6,12 @@ from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert if __name__ == "__main__": params = Params() - with open(os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json")) as f: + with open(os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json")) as f: offroad_alerts = json.load(f) t = 10 if len(sys.argv) < 2 else int(sys.argv[1]) diff --git a/selfdrive/ui/tests/playsound.cc b/selfdrive/ui/tests/playsound.cc deleted file mode 100644 index 6487d0479038c2d..000000000000000 --- a/selfdrive/ui/tests/playsound.cc +++ /dev/null @@ -1,30 +0,0 @@ -#include -#include -#include -#include - -int main(int argc, char **argv) { - - QApplication a(argc, argv); - - QTimer::singleShot(0, [=]{ - QSoundEffect s; - const char *vol = getenv("VOLUME"); - s.setVolume(vol ? atof(vol) : 1.0); - for (int i = 1; i < argc; i++) { - QString fn = argv[i]; - qDebug() << "playing" << fn; - - QEventLoop loop; - s.setSource(QUrl::fromLocalFile(fn)); - QEventLoop::connect(&s, &QSoundEffect::loadedChanged, &loop, &QEventLoop::quit); - loop.exec(); - s.play(); - QEventLoop::connect(&s, &QSoundEffect::playingChanged, &loop, &QEventLoop::quit); - loop.exec(); - } - QCoreApplication::exit(); - }); - - return a.exec(); -} diff --git a/selfdrive/ui/tests/test_runner.cc b/selfdrive/ui/tests/test_runner.cc index ac63139d178a89f..c8cc0d3e055123d 100644 --- a/selfdrive/ui/tests/test_runner.cc +++ b/selfdrive/ui/tests/test_runner.cc @@ -11,6 +11,7 @@ int main(int argc, char **argv) { QApplication app(argc, argv); QString language_file = "main_test_en"; + // FIXME: pytest-cpp considers this print as a test case qDebug() << "Loading language:" << language_file; QTranslator translator; diff --git a/selfdrive/ui/tests/test_soundd.py b/selfdrive/ui/tests/test_soundd.py index 468bc92cca79ef9..a9da8455ebdd24a 100644 --- a/selfdrive/ui/tests/test_soundd.py +++ b/selfdrive/ui/tests/test_soundd.py @@ -1,7 +1,7 @@ from cereal import car from cereal import messaging from cereal.messaging import SubMaster, PubMaster -from openpilot.selfdrive.ui.soundd import CONTROLS_TIMEOUT, check_controls_timeout_alert +from openpilot.selfdrive.ui.soundd import SELFDRIVE_STATE_TIMEOUT, check_selfdrive_timeout_alert import time @@ -9,27 +9,27 @@ class TestSoundd: - def test_check_controls_timeout_alert(self): - sm = SubMaster(['controlsState']) - pm = PubMaster(['controlsState']) + def test_check_selfdrive_timeout_alert(self): + sm = SubMaster(['selfdriveState']) + pm = PubMaster(['selfdriveState']) for _ in range(100): - cs = messaging.new_message('controlsState') - cs.controlsState.enabled = True + cs = messaging.new_message('selfdriveState') + cs.selfdriveState.enabled = True - pm.send("controlsState", cs) + pm.send("selfdriveState", cs) time.sleep(0.01) sm.update(0) - assert not check_controls_timeout_alert(sm) + assert not check_selfdrive_timeout_alert(sm) - for _ in range(CONTROLS_TIMEOUT * 110): + for _ in range(SELFDRIVE_STATE_TIMEOUT * 110): sm.update(0) time.sleep(0.01) - assert check_controls_timeout_alert(sm) + assert check_selfdrive_timeout_alert(sm) # TODO: add test with micd for checking that soundd actually outputs sounds diff --git a/selfdrive/ui/tests/test_ui/run.py b/selfdrive/ui/tests/test_ui/run.py index 1d33c103a4d02b3..2c4d8d7037e9b80 100644 --- a/selfdrive/ui/tests/test_ui/run.py +++ b/selfdrive/ui/tests/test_ui/run.py @@ -1,122 +1,208 @@ from collections import namedtuple +import capnp import pathlib import shutil import sys -import jinja2 -import matplotlib.pyplot as plt -import numpy as np import os import pywinctl +import pyautogui +import pickle import time -from cereal import messaging, car, log +from cereal import log from msgq.visionipc import VisionIpcServer, VisionStreamType - -from cereal.messaging import SubMaster, PubMaster -from openpilot.common.mock import mock_messages +from cereal.messaging import PubMaster, log_from_bytes, sub_sock +from openpilot.common.basedir import BASEDIR from openpilot.common.params import Params -from openpilot.common.realtime import DT_MDL -from openpilot.common.transformations.camera import DEVICE_CAMERAS +from openpilot.common.prefix import OpenpilotPrefix +from openpilot.common.transformations.camera import CameraConfig, DEVICE_CAMERAS +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.selfdrive.test.helpers import with_processes -from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state -from openpilot.tools.webcam.camera import Camera - -UI_DELAY = 0.5 # may be slower on CI? - -NetworkType = log.DeviceState.NetworkType -NetworkStrength = log.DeviceState.NetworkStrength - -EventName = car.CarEvent.EventName -EVENTS_BY_NAME = {v: k for k, v in EventName.schema.enumerants.items()} - - -def setup_common(click, pm: PubMaster): - Params().put("DongleId", "123456789012345") - dat = messaging.new_message('deviceState') - dat.deviceState.started = True - dat.deviceState.networkType = NetworkType.cell4G - dat.deviceState.networkStrength = NetworkStrength.moderate - dat.deviceState.freeSpacePercent = 80 - dat.deviceState.memoryUsagePercent = 2 - dat.deviceState.cpuTempC = [2,]*3 - dat.deviceState.gpuTempC = [2,]*3 - dat.deviceState.cpuUsagePercent = [2,]*8 - - pm.send("deviceState", dat) +from openpilot.selfdrive.test.process_replay.migration import migrate, migrate_controlsState, migrate_carState +from openpilot.tools.lib.logreader import LogReader +from openpilot.tools.lib.framereader import FrameReader +from openpilot.tools.lib.route import Route +from openpilot.tools.lib.cache import DEFAULT_CACHE_DIR + +UI_DELAY = 0.1 # may be slower on CI? +TEST_ROUTE = "a2a0ccea32023010|2023-07-27--13-01-19" + +STREAMS: list[tuple[VisionStreamType, CameraConfig, bytes]] = [] +OFFROAD_ALERTS = ['Offroad_StorageMissing', 'Offroad_IsTakingSnapshot'] +DATA: dict[str, capnp.lib.capnp._DynamicStructBuilder] = dict.fromkeys( + ["carParams", "deviceState", "pandaStates", "controlsState", "selfdriveState", + "liveCalibration", "modelV2", "radarState", "driverMonitoringState", "carState", + "driverStateV2", "roadCameraState", "wideRoadCameraState", "driverCameraState"], None) def setup_homescreen(click, pm: PubMaster): - setup_common(click, pm) + pass def setup_settings_device(click, pm: PubMaster): - setup_common(click, pm) - click(100, 100) -def setup_settings_network(click, pm: PubMaster): - setup_common(click, pm) +def setup_settings_toggles(click, pm: PubMaster): + setup_settings_device(click, pm) + click(278, 650) + time.sleep(UI_DELAY) + +def setup_settings_software(click, pm: PubMaster): + setup_settings_device(click, pm) + click(278, 800) + time.sleep(UI_DELAY) +def setup_settings_developer(click, pm: PubMaster): setup_settings_device(click, pm) - click(300, 600) + click(278, 960) + time.sleep(UI_DELAY) def setup_onroad(click, pm: PubMaster): - setup_common(click, pm) - - dat = messaging.new_message('pandaStates', 1) - dat.pandaStates[0].ignitionLine = True - dat.pandaStates[0].pandaType = log.PandaState.PandaType.uno + vipc_server = VisionIpcServer("camerad") + for stream_type, cam, _ in STREAMS: + vipc_server.create_buffers(stream_type, 5, cam.width, cam.height) + vipc_server.start_listener() + + uidebug_received_cnt = 0 + packet_id = 0 + uidebug_sock = sub_sock('uiDebug') + + # Condition check for uiDebug processing + check_uidebug = DATA['deviceState'].deviceState.started and not DATA['carParams'].carParams.notCar + + # Loop until 20 'uiDebug' messages are received + while uidebug_received_cnt <= 20: + for service, data in DATA.items(): + if data: + data.clear_write_flag() + pm.send(service, data) + + for stream_type, _, image in STREAMS: + vipc_server.send(stream_type, image, packet_id, packet_id, packet_id) + + if check_uidebug: + while uidebug_sock.receive(non_blocking=True): + uidebug_received_cnt += 1 + else: + uidebug_received_cnt += 1 + + packet_id += 1 + time.sleep(0.05) + +def setup_onroad_disengaged(click, pm: PubMaster): + DATA['selfdriveState'].selfdriveState.enabled = False + setup_onroad(click, pm) + DATA['selfdriveState'].selfdriveState.enabled = True - pm.send("pandaStates", dat) +def setup_onroad_override(click, pm: PubMaster): + DATA['selfdriveState'].selfdriveState.state = log.SelfdriveState.OpenpilotState.overriding + setup_onroad(click, pm) + DATA['selfdriveState'].selfdriveState.state = log.SelfdriveState.OpenpilotState.enabled - d = DEVICE_CAMERAS[("tici", "ar0231")] - server = VisionIpcServer("camerad") - server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 40, False, d.fcam.width, d.fcam.height) - server.create_buffers(VisionStreamType.VISION_STREAM_DRIVER, 40, False, d.dcam.width, d.dcam.height) - server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 40, False, d.fcam.width, d.fcam.height) - server.start_listener() - time.sleep(0.5) # give time for vipc server to start +def setup_onroad_wide(click, pm: PubMaster): + DATA['selfdriveState'].selfdriveState.experimentalMode = True + DATA["carState"].carState.vEgo = 1 + setup_onroad(click, pm) - IMG = Camera.bgr2nv12(np.random.randint(0, 255, (d.fcam.width, d.fcam.height, 3), dtype=np.uint8)) - IMG_BYTES = IMG.flatten().tobytes() +def setup_onroad_sidebar(click, pm: PubMaster): + setup_onroad(click, pm) + click(500, 500) + setup_onroad(click, pm) - cams = ('roadCameraState', 'wideRoadCameraState') +def setup_onroad_wide_sidebar(click, pm: PubMaster): + setup_onroad_wide(click, pm) + click(500, 500) + setup_onroad_wide(click, pm) - frame_id = 0 - for cam in cams: - msg = messaging.new_message(cam) - cs = getattr(msg, cam) - cs.frameId = frame_id - cs.timestampSof = int((frame_id * DT_MDL) * 1e9) - cs.timestampEof = int((frame_id * DT_MDL) * 1e9) - cam_meta = meta_from_camera_state(cam) +def setup_body(click, pm: PubMaster): + DATA['carParams'].carParams.carName = "BODY" + DATA['carParams'].carParams.notCar = True + DATA['carState'].carState.charging = True + DATA['carState'].carState.fuelGauge = 50.0 + setup_onroad(click, pm) - pm.send(msg.which(), msg) - server.send(cam_meta.stream, IMG_BYTES, cs.frameId, cs.timestampSof, cs.timestampEof) +def setup_keyboard(click, pm: PubMaster): + setup_settings_device(click, pm) + click(250, 965) + click(1930, 228) -@mock_messages(['liveLocationKalman']) -def setup_onroad_map(click, pm: PubMaster): +def setup_driver_camera(click, pm: PubMaster): + setup_settings_device(click, pm) + click(1950, 435) + DATA['deviceState'].deviceState.started = False setup_onroad(click, pm) + DATA['deviceState'].deviceState.started = True + +def setup_onroad_alert(click, pm: PubMaster, text1, text2, size, status=log.SelfdriveState.AlertStatus.normal): + print(f'setup onroad alert, size: {size}') + state = DATA['selfdriveState'] + origin_state_bytes = state.to_bytes() + cs = state.selfdriveState + cs.alertText1 = text1 + cs.alertText2 = text2 + cs.alertSize = size + cs.alertStatus = status + cs.alertType = "test_onroad_alert" + setup_onroad(click, pm) + DATA['selfdriveState'] = log_from_bytes(origin_state_bytes).as_builder() - click(500, 500) +def setup_onroad_alert_small(click, pm: PubMaster): + setup_onroad_alert(click, pm, 'This is a small alert message', '', log.SelfdriveState.AlertSize.small) - time.sleep(UI_DELAY) # give time for the map to render +def setup_onroad_alert_mid(click, pm: PubMaster): + setup_onroad_alert(click, pm, 'Medium Alert', 'This is a medium alert message', log.SelfdriveState.AlertSize.mid) -def setup_onroad_sidebar(click, pm: PubMaster): - setup_onroad_map(click, pm) - click(500, 500) +def setup_onroad_alert_full(click, pm: PubMaster): + setup_onroad_alert(click, pm, 'Full Alert', 'This is a full alert message', log.SelfdriveState.AlertSize.full) + +def setup_offroad_alert(click, pm: PubMaster): + for alert in OFFROAD_ALERTS: + set_offroad_alert(alert, True) + + # Toggle between settings and home to refresh the offroad alert widget + setup_settings_device(click, pm) + click(240, 216) + +def setup_update_available(click, pm: PubMaster): + Params().put_bool("UpdateAvailable", True) + release_notes_path = os.path.join(BASEDIR, "RELEASES.md") + with open(release_notes_path) as file: + release_notes = file.read().split('\n\n', 1)[0] + Params().put("UpdaterNewReleaseNotes", release_notes + "\n") + + setup_settings_device(click, pm) + click(240, 216) + +def setup_pair_device(click, pm: PubMaster): + click(1950, 435) + click(1800, 900) CASES = { "homescreen": setup_homescreen, + "prime": setup_homescreen, + "pair_device": setup_pair_device, "settings_device": setup_settings_device, - "settings_network": setup_settings_network, + "settings_toggles": setup_settings_toggles, + "settings_software": setup_settings_software, + "settings_developer": setup_settings_developer, "onroad": setup_onroad, - "onroad_map": setup_onroad_map, - "onroad_sidebar": setup_onroad_sidebar + "onroad_disengaged": setup_onroad_disengaged, + "onroad_override": setup_onroad_override, + "onroad_sidebar": setup_onroad_sidebar, + "onroad_alert_small": setup_onroad_alert_small, + "onroad_alert_mid": setup_onroad_alert_mid, + "onroad_alert_full": setup_onroad_alert_full, + "onroad_wide": setup_onroad_wide, + "onroad_wide_sidebar": setup_onroad_wide_sidebar, + "driver_camera": setup_driver_camera, + "body": setup_body, + "offroad_alert": setup_offroad_alert, + "update_available": setup_update_available, + "keyboard": setup_keyboard } TEST_DIR = pathlib.Path(__file__).parent -TEST_OUTPUT_DIR = TEST_DIR / "report" +TEST_OUTPUT_DIR = TEST_DIR / "report_1" SCREENSHOTS_DIR = TEST_OUTPUT_DIR / "screenshots" @@ -126,54 +212,33 @@ def __init__(self): sys.modules["mouseinfo"] = False def setup(self): - self.sm = SubMaster(["uiDebug"]) - self.pm = PubMaster(["deviceState", "pandaStates", "controlsState", 'roadCameraState', 'wideRoadCameraState', 'liveLocationKalman']) - while not self.sm.valid["uiDebug"]: - self.sm.update(1) - time.sleep(UI_DELAY) # wait a bit more for the UI to start rendering + self.pm = PubMaster(list(DATA.keys())) + DATA['deviceState'].deviceState.networkType = log.DeviceState.NetworkType.wifi + DATA['deviceState'].deviceState.lastAthenaPingTime = 0 + for _ in range(10): + self.pm.send('deviceState', DATA['deviceState']) + DATA['deviceState'].clear_write_flag() + time.sleep(0.05) try: self.ui = pywinctl.getWindowsWithTitle("ui")[0] except Exception as e: print(f"failed to find ui window, assuming that it's in the top left (for Xvfb) {e}") self.ui = namedtuple("bb", ["left", "top", "width", "height"])(0,0,2160,1080) - def screenshot(self): - import pyautogui - im = pyautogui.screenshot(region=(self.ui.left, self.ui.top, self.ui.width, self.ui.height)) + def screenshot(self, name): + im = pyautogui.screenshot(SCREENSHOTS_DIR / f"{name}.png", region=(self.ui.left, self.ui.top, self.ui.width, self.ui.height)) assert im.width == 2160 assert im.height == 1080 - img = np.array(im) - im.close() - return img def click(self, x, y, *args, **kwargs): - import pyautogui pyautogui.click(self.ui.left + x, self.ui.top + y, *args, **kwargs) time.sleep(UI_DELAY) # give enough time for the UI to react @with_processes(["ui"]) def test_ui(self, name, setup_case): self.setup() - setup_case(self.click, self.pm) - - time.sleep(UI_DELAY) # wait a bit more for the UI to finish rendering - - im = self.screenshot() - plt.imsave(SCREENSHOTS_DIR / f"{name}.png", im) - - -def create_html_report(): - OUTPUT_FILE = TEST_OUTPUT_DIR / "index.html" - - with open(TEST_DIR / "template.html") as f: - template = jinja2.Template(f.read()) - - cases = {f.stem: (str(f.relative_to(TEST_OUTPUT_DIR)), "reference.png") for f in SCREENSHOTS_DIR.glob("*.png")} - cases = dict(sorted(cases.items())) - - with open(OUTPUT_FILE, "w") as f: - f.write(template.render(cases=cases)) + self.screenshot(name) def create_screenshots(): if TEST_OUTPUT_DIR.exists(): @@ -181,13 +246,51 @@ def create_screenshots(): SCREENSHOTS_DIR.mkdir(parents=True) + route = Route(TEST_ROUTE) + + segnum = 2 + lr = LogReader(route.qlog_paths()[segnum]) + DATA['carParams'] = next((event.as_builder() for event in lr if event.which() == 'carParams'), None) + for event in migrate(lr, [migrate_controlsState, migrate_carState]): + if event.which() in DATA: + DATA[event.which()] = event.as_builder() + + if all(DATA.values()): + break + + cam = DEVICE_CAMERAS[("tici", "ar0231")] + + frames_cache = f'{DEFAULT_CACHE_DIR}/ui_frames' + if os.path.isfile(frames_cache): + with open(frames_cache, 'rb') as f: + frames = pickle.load(f) + road_img = frames[0] + wide_road_img = frames[1] + driver_img = frames[2] + else: + with open(frames_cache, 'wb') as f: + road_img = FrameReader(route.camera_paths()[segnum]).get(0, pix_fmt="nv12")[0] + wide_road_img = FrameReader(route.ecamera_paths()[segnum]).get(0, pix_fmt="nv12")[0] + driver_img = FrameReader(route.dcamera_paths()[segnum]).get(0, pix_fmt="nv12")[0] + pickle.dump([road_img, wide_road_img, driver_img], f) + + STREAMS.append((VisionStreamType.VISION_STREAM_ROAD, cam.fcam, road_img.flatten().tobytes())) + STREAMS.append((VisionStreamType.VISION_STREAM_WIDE_ROAD, cam.ecam, wide_road_img.flatten().tobytes())) + STREAMS.append((VisionStreamType.VISION_STREAM_DRIVER, cam.dcam, driver_img.flatten().tobytes())) + t = TestUI() + for name, setup in CASES.items(): - t.test_ui(name, setup) + with OpenpilotPrefix(): + params = Params() + params.put("DongleId", "123456789012345") + if name == 'prime': + params.put('PrimeType', '1') + elif name == 'pair_device': + params.put('ApiCache_Device', '{"is_paired":0, "prime_type":-1}') + + t.test_ui(name, setup) if __name__ == "__main__": print("creating test screenshots") create_screenshots() - - print("creating html report") - create_html_report() diff --git a/selfdrive/ui/tests/ui_snapshot.cc b/selfdrive/ui/tests/ui_snapshot.cc deleted file mode 100644 index 14e0fab835fc461..000000000000000 --- a/selfdrive/ui/tests/ui_snapshot.cc +++ /dev/null @@ -1,66 +0,0 @@ -#include "selfdrive/ui/tests/ui_snapshot.h" - -#include -#include -#include -#include -#include - -#include "selfdrive/ui/qt/home.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/window.h" -#include "selfdrive/ui/ui.h" - -void saveWidgetAsImage(QWidget *widget, const QString &fileName) { - QImage image(widget->size(), QImage::Format_ARGB32); - QPainter painter(&image); - widget->render(&painter); - image.save(fileName); -} - -int main(int argc, char *argv[]) { - initApp(argc, argv); - - QApplication app(argc, argv); - - QCommandLineParser parser; - parser.setApplicationDescription("Take a snapshot of the UI."); - parser.addHelpOption(); - parser.addOption(QCommandLineOption(QStringList() << "o" - << "output", - "Output image file path. The file's suffix is used to " - "determine the format. Supports PNG and JPEG formats. " - "Defaults to \"snapshot.png\".", - "file", "snapshot.png")); - parser.process(app); - - const QString output = parser.value("output"); - if (output.isEmpty()) { - qCritical() << "No output file specified"; - return 1; - } - - auto current = QDir::current(); - - // change working directory to find assets - if (!QDir::setCurrent(QCoreApplication::applicationDirPath() + QDir::separator() + "..")) { - qCritical() << "Failed to set current directory"; - return 1; - } - - MainWindow w; - w.setFixedSize(2160, 1080); - w.show(); - app.installEventFilter(&w); - - // restore working directory - QDir::setCurrent(current.absolutePath()); - - // wait for the UI to update - QObject::connect(uiState(), &UIState::uiUpdate, [&](const UIState &s) { - saveWidgetAsImage(&w, output); - app.quit(); - }); - - return app.exec(); -} diff --git a/selfdrive/ui/tests/ui_snapshot.h b/selfdrive/ui/tests/ui_snapshot.h deleted file mode 100644 index b4699f6af58c084..000000000000000 --- a/selfdrive/ui/tests/ui_snapshot.h +++ /dev/null @@ -1,5 +0,0 @@ -#pragma once - -#include - -void saveWidgetAsImage(QWidget *widget, const QString &fileName); diff --git a/selfdrive/ui/translations/create_badges.py b/selfdrive/ui/translations/create_badges.py index f56f8941114ff8d..3e14c332554bc3d 100755 --- a/selfdrive/ui/translations/create_badges.py +++ b/selfdrive/ui/translations/create_badges.py @@ -31,7 +31,7 @@ unfinished_translations += 1 percent_finished = int(100 - (unfinished_translations / total_translations * 100.)) - color = "green" if percent_finished == 100 else "orange" if percent_finished > 90 else "red" + color = f"rgb{(94, 188, 0) if percent_finished == 100 else (248, 255, 50) if percent_finished > 90 else (204, 55, 27)}" # Download badge badge_label = f"LANGUAGE {name}" diff --git a/selfdrive/ui/translations/languages.json b/selfdrive/ui/translations/languages.json index 321cdeedd2e0dbe..132b5088d7e1996 100644 --- a/selfdrive/ui/translations/languages.json +++ b/selfdrive/ui/translations/languages.json @@ -3,6 +3,7 @@ "Deutsch": "main_de", "Français": "main_fr", "Português": "main_pt-BR", + "Español": "main_es", "Türkçe": "main_tr", "العربية": "main_ar", "ไทย": "main_th", diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index d8146723a4dc5c0..2315268a72c8c22 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -87,29 +87,6 @@ من أجل "%1" - - AnnotatedCameraWidget - - km/h - كم/س - - - mph - ميل/س - - - MAX - MAX - - - SPEED - SPEED - - - LIMIT - LIMIT - - ConfirmationDialog @@ -137,30 +114,14 @@ - DestinationWidget - - Home - المنزل - - - Work - العمل - - - No destination set - لم يتم ضبط الوجهة - + DeveloperPanel - home - المنزل + Joystick Debug Mode + وضع تصحيح أخطاء عصا التحكم - work - العمل - - - No %1 location set - لم يتم ضبط %1 موقع + Longitudinal Maneuver Mode + وضع المناورة الطولية @@ -324,6 +285,21 @@ تشغيل وضع الراحة + + HudRenderer + + km/h + كم/س + + + mph + ميل/س + + + MAX + MAX + + InputDialog @@ -349,47 +325,6 @@ جارٍ التثبيت... - - MapETA - - eta - الوصول - - - min - د - - - hr - س - - - - MapSettings - - NAVIGATION - التنقل - - - Manage at connect.comma.ai - الإدارة في connect.comma.ai - - - - MapWindow - - Map Loading - تحميل الخريطة - - - Waiting for GPS - بانتظار GPS - - - Waiting for route - بانتظار الطريق - - MultiOptionDialog @@ -464,10 +399,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. لم يكن openpilot قادراً على تحديد سيارتك. إما أن تكون سيارتك غير مدعومة أو أنه لم يتم التعرف على وحدة التحكم الإلكتروني (ECUs) فيها. يرجى تقديم طلب سحب من أجل إضافة نسخ برمجيات ثابتة إلى السيارة المناسبة. هل تحتاج إلى أي مساعدة؟ لا تتردد في التواصل مع doscord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - لم يتمكن openpilot من تحديد سيارتك. تحقق من سلامة الكابلات وتأكد من تأمين جميع الوصلات، لا سيما أنه قد تم إدخال طاقة الفاصلة بالكامل في منفذ OBD-II في السيارة. هل تريد أي مساعدة؟ لا تتردد في الانضمام إلى discord.comma.ai. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. لقد اكتشف openpilot تغييراً في موقع تركيب الجهاز. تأكد من تثبيت الجهاز بشكل كامل في موقعه وتثبيته بإحكام على الزجاج الأمامي. @@ -494,22 +425,22 @@ openpilot Unavailable openpilot غير متوفر - - Waiting for controls to start - في انتظار بدء عناصر التحكم - TAKE CONTROL IMMEDIATELY تحكم على الفور - - Controls Unresponsive - الضوابط غير مستجيبة - Reboot Device إعادة التشغيل + + Waiting to start + في انتظار البدء + + + System Unresponsive + النظام لا يستجيب + PairingPopup @@ -568,8 +499,8 @@ سنة واحدة من تخزين القرص - Turn-by-turn navigation - التنقل خطوة بخطوة + Remote snapshots + لقطات عن بُعد @@ -630,22 +561,6 @@ منذ %n يوم - - km - كم - - - m - م - - - mi - ميل - - - ft - قدم - now الآن @@ -714,6 +629,10 @@ This may take up to a minute. Software البرنامج + + Developer + المطور + Setup @@ -871,14 +790,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - بحث - -- -- @@ -1090,22 +1001,6 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. عند تمكين هذه الميزة، فإن الضغط على دواسة الوقود سيؤدي إلى فك ارتباط openpilot. - - Show ETA in 24h Format - إظهار الوقت المقدر للوصول بصيغة 24 ساعة - - - Use 24h format instead of am/pm - استخدام صيغة 24 ساعة بدلاً من صباحاً/مساء - - - Show Map on Left Side of UI - عرض الخريطة على الجانب الأيسر من واجهة المستخدم - - - Show map on left side when in split screen view. - عرض الخريطة عل الجانب الأيسر عندما تكون وضعية العرض بطريقة الشاشة المنقسمة. - openpilot Longitudinal Control (Alpha) التحكم الطولي openpilot (ألفا) @@ -1176,15 +1071,15 @@ This may take up to a minute. The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner. - + ستتحول واجهة القيادة إلى الكاميرا الواسعة المواجهة للطريق عند السرعات المنخفضة لعرض بعض المنعطفات بشكل أفضل. كما سيتم عرض شعار وضع التجريبي في الزاوية العلوية اليمنى. Always-On Driver Monitoring - + مراقبة السائق المستمرة Enable driver monitoring even when openpilot is not engaged. - + تمكين مراقبة السائق حتى عندما لا يكون نظام OpenPilot مُفعّلاً. diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index 010aa4d30485cdd..2abed6e3055deba 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -87,29 +87,6 @@ für "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - MAX - - - SPEED - Geschwindigkeit - - - LIMIT - LIMIT - - ConfirmationDialog @@ -137,29 +114,13 @@ - DestinationWidget - - Home - - - - Work - - - - No destination set - - - - No %1 location set - - + DeveloperPanel - home + Joystick Debug Mode - work + Longitudinal Maneuver Mode @@ -324,6 +285,21 @@ ENTSPANNTER MODUS AN + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + MAX + + InputDialog @@ -345,47 +321,6 @@ Installiere... - - MapETA - - eta - Ankunft - - - min - min - - - hr - std - - - - MapSettings - - NAVIGATION - - - - Manage at connect.comma.ai - - - - - MapWindow - - Map Loading - Karte wird geladen - - - Waiting for GPS - Warten auf GPS - - - Waiting for route - - - MultiOptionDialog @@ -455,10 +390,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. @@ -490,19 +421,19 @@ - Waiting for controls to start + TAKE CONTROL IMMEDIATELY - TAKE CONTROL IMMEDIATELY + Reboot Device - Controls Unresponsive + Waiting to start - Reboot Device + System Unresponsive @@ -559,11 +490,11 @@ - Turn-by-turn navigation + 1 year of drive storage - 1 year of drive storage + Remote snapshots @@ -613,22 +544,6 @@ vor %n Tagen - - km - km - - - m - m - - - mi - mi - - - ft - fuß - now @@ -696,6 +611,10 @@ This may take up to a minute. Software Software + + Developer + + Setup @@ -854,14 +773,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - SUCHEN - -- -- @@ -1070,24 +981,6 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. Wenn aktiviert, deaktiviert sich Openpilot sobald das Gaspedal betätigt wird. - - Use 24h format instead of am/pm - Benutze das 24Stunden Format anstatt am/pm - - - Show Map on Left Side of UI - Too long for UI - Zeige die Karte auf der linken Seite - - - Show map on left side when in split screen view. - Zeige die Karte auf der linken Seite der Benutzeroberfläche bei geteilten Bildschirm. - - - Show ETA in 24h Format - Too long for UI - Zeige die Ankunftszeit im 24 Stunden Format - Experimental Mode Experimenteller Modus diff --git a/selfdrive/ui/translations/main_es.ts b/selfdrive/ui/translations/main_es.ts new file mode 100644 index 000000000000000..38ba964f111f4dc --- /dev/null +++ b/selfdrive/ui/translations/main_es.ts @@ -0,0 +1,1150 @@ + + + + + AbstractAlert + + Close + Cerrar + + + Snooze Update + Posponer Actualización + + + Reboot and Update + Reiniciar y Actualizar + + + + AdvancedNetworking + + Back + Volver + + + Enable Tethering + Activar Tether + + + Tethering Password + Contraseña de Tethering + + + EDIT + EDITAR + + + Enter new tethering password + Nueva contraseña de tethering + + + IP Address + Dirección IP + + + Enable Roaming + Activar Roaming + + + APN Setting + Configuración de APN + + + Enter APN + Insertar APN + + + leave blank for automatic configuration + dejar en blanco para configuración automática + + + Cellular Metered + Plano de datos limitado + + + Prevent large data uploads when on a metered connection + Evitar grandes descargas de datos cuando tenga una conexión limitada + + + Hidden Network + Red Oculta + + + CONNECT + CONECTAR + + + Enter SSID + Ingrese SSID + + + Enter password + Ingrese contraseña + + + for "%1" + para "%1" + + + + ConfirmationDialog + + Ok + OK + + + Cancel + Cancelar + + + + DeclinePage + + You must accept the Terms and Conditions in order to use openpilot. + Debe aceptar los términos y condiciones para poder utilizar openpilot. + + + Back + Atrás + + + Decline, uninstall %1 + Rechazar, desinstalar %1 + + + + DeveloperPanel + + Joystick Debug Mode + Modo de depuración de joystick + + + Longitudinal Maneuver Mode + Modo de maniobra longitudinal + + + + DevicePanel + + Dongle ID + Dongle ID + + + N/A + N/A + + + Serial + Serial + + + Pair Device + Emparejar Dispositivo + + + PAIR + EMPAREJAR + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + Empareja tu dispositivo con comma connect (connect.comma.ai) y reclama tu oferta de comma prime. + + + Driver Camera + Cámara del conductor + + + PREVIEW + VISUALIZAR + + + Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off) + Previsualizar la cámara del conductor para garantizar que la monitorización del sistema tenga buena visibilidad (el vehículo tiene que estar apagado) + + + Reset Calibration + Formatear Calibración + + + RESET + REINICIAR + + + Are you sure you want to reset calibration? + ¿Seguro que quiere formatear la calibración? + + + Reset + Formatear + + + Review Training Guide + Revisar la Guía de Entrenamiento + + + REVIEW + REVISAR + + + Review the rules, features, and limitations of openpilot + Revisar las reglas, características y limitaciones de openpilot + + + Are you sure you want to review the training guide? + ¿Seguro que quiere revisar la guía de entrenamiento? + + + Review + Revisar + + + Regulatory + Regulador + + + VIEW + VER + + + Change Language + Cambiar Idioma + + + CHANGE + CAMBIAR + + + Select a language + Seleccione el idioma + + + Reboot + Reiniciar + + + Power Off + Apagar + + + openpilot requires the device to be mounted within 4° left or right and within 5° up or 9° down. openpilot is continuously calibrating, resetting is rarely required. + openpilot requiere que el dispositivo sea montado entre 4° grados a la izquierda o derecha y entre 5° grados hacia arriba o 9° grados hacia abajo. openpilot está constantemente en calibración, formatear rara vez es necesario. + + + Your device is pointed %1° %2 and %3° %4. + Su dispositivo está apuntando %1° %2 y %3° %4. + + + down + abajo + + + up + arriba + + + left + izquierda + + + right + derecha + + + Are you sure you want to reboot? + ¿Seguro qué quiere reiniciar? + + + Disengage to Reboot + Desactivar para Reiniciar + + + Are you sure you want to power off? + ¿Seguro qué quiere apagar? + + + Disengage to Power Off + Desactivar para apagar + + + + DriverViewWindow + + camera starting + iniciando cámara + + + + ExperimentalModeButton + + EXPERIMENTAL MODE ON + MODO EXPERIMENTAL + + + CHILL MODE ON + MODO CHILL + + + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + MAX + + + + InputDialog + + Cancel + Cancelar + + + Need at least %n character(s)! + + ¡Necesita mínimo %n caracter! + ¡Necesita mínimo %n caracteres! + + + + + Installer + + Installing... + Instalando... + + + + MultiOptionDialog + + Select + Seleccionar + + + Cancel + Cancelar + + + + Networking + + Advanced + Avanzado + + + Enter password + Ingresar contraseña + + + for "%1" + para "%1" + + + Wrong password + Contraseña incorrecta + + + + OffroadAlert + + Device temperature too high. System cooling down before starting. Current internal component temperature: %1 + La temperatura del dispositivo es muy alta. El sistema se está enfriando antes de iniciar. Temperatura actual del componente interno: %1 + + + Immediately connect to the internet to check for updates. If you do not connect to the internet, openpilot won't engage in %1 + Conéctese inmediatamente al internet para buscar actualizaciones. Si no se conecta al internet, openpilot no iniciará en %1 + + + Connect to internet to check for updates. openpilot won't automatically start until it connects to internet to check for updates. + Conectese al internet para buscar actualizaciones. openpilot no iniciará automáticamente hasta conectarse al internet para buscar actualizaciones. + + + Unable to download updates +%1 + Incapaz de descargar actualizaciones. +%1 + + + Taking camera snapshots. System won't start until finished. + Tomando capturas de las cámaras. El sistema no se iniciará hasta que finalice. + + + An update to your device's operating system is downloading in the background. You will be prompted to update when it's ready to install. + Se está descargando una actualización del sistema operativo de su dispositivo en segundo plano. Se le pedirá que actualice cuando esté listo para instalarse. + + + Device failed to register. It will not connect to or upload to comma.ai servers, and receives no support from comma.ai. If this is an official device, visit https://comma.ai/support. + El dispositivo no pudo registrarse. No se conectará ni subirá datos a los servidores de comma.ai y no recibe soporte de comma.ai. Si este es un dispositivo oficial, visite https://comma.ai/support. + + + NVMe drive not mounted. + Unidad NVMe no montada. + + + Unsupported NVMe drive detected. Device may draw significantly more power and overheat due to the unsupported NVMe. + Se detectó una unidad NVMe incompatible. El dispositivo puede consumir mucha más energía y sobrecalentarse debido a esto. + + + openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. + openpilot no pudo identificar su automóvil. Su automóvil no es compatible o no se reconocen sus ECU. Por favor haga un pull request para agregar las versiones de firmware del vehículo adecuado. ¿Necesita ayuda? Únase a discord.comma.ai. + + + openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. + openpilot detectó un cambio en la posición de montaje del dispositivo. Asegúrese de que el dispositivo esté completamente asentado en el soporte y que el soporte esté firmemente asegurado al parabrisas. + + + + OffroadHome + + UPDATE + ACTUALIZAR + + + ALERTS + ALERTAS + + + ALERT + ALERTA + + + + OnroadAlerts + + openpilot Unavailable + openpilot no disponible + + + TAKE CONTROL IMMEDIATELY + TOME CONTROL INMEDIATAMENTE + + + Reboot Device + Reiniciar Dispositivo + + + Waiting to start + Esperando para iniciar + + + System Unresponsive + Systema no responde + + + + PairingPopup + + Pair your device to your comma account + Empareje su dispositivo con su cuenta de comma + + + Go to https://connect.comma.ai on your phone + Vaya a https://connect.comma.ai en su teléfono + + + Click "add new device" and scan the QR code on the right + Seleccione "agregar nuevo dispositivo" y escanee el código QR a la derecha + + + Bookmark connect.comma.ai to your home screen to use it like an app + Añada connect.comma.ai a su pantalla de inicio para usarlo como una aplicación + + + + ParamControl + + Enable + Activar + + + Cancel + Cancelar + + + + PrimeAdWidget + + Upgrade Now + Actualizar Ahora + + + Become a comma prime member at connect.comma.ai + Hazte miembro de comma prime en connect.comma.ai + + + PRIME FEATURES: + BENEFICIOS PRIME: + + + Remote access + Acceso remoto + + + 24/7 LTE connectivity + Conectividad LTE 24/7 + + + 1 year of drive storage + 1 año de almacenamiento + + + Remote snapshots + Capturas remotas + + + + PrimeUserWidget + + ✓ SUBSCRIBED + ✓ SUSCRITO + + + comma prime + comma prime + + + + QObject + + Reboot + Reiniciar + + + Exit + Salir + + + openpilot + openpilot + + + now + ahora + + + %n minute(s) ago + + hace %n min + hace %n mins + + + + %n hour(s) ago + + hace %n hora + hace %n horas + + + + %n day(s) ago + + hace %n día + hace %n días + + + + + Reset + + Reset failed. Reboot to try again. + Formateo fallido. Reinicie para reintentar. + + + Resetting device... +This may take up to a minute. + formateando dispositivo... +Esto puede tardar un minuto. + + + Are you sure you want to reset your device? + ¿Seguro que quiere formatear su dispositivo? + + + System Reset + Formatear Sistema + + + System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot. + Formateo del sistema activado. Presione confirmar para borrar todo el contenido y la configuración. Presione cancelar para reanudar el inicio. + + + Cancel + Cancelar + + + Reboot + Reiniciar + + + Confirm + Confirmar + + + Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device. + No es posible montar una partición de datos. La partición podría estar corrompida. Confirme para borrar y formatear su dispositivo. + + + + SettingsWindow + + × + × + + + Device + Dispositivo + + + Network + Red + + + Toggles + Ajustes + + + Software + Software + + + Developer + Desarrollador + + + + Setup + + Something went wrong. Reboot the device. + Algo ha ido mal. Reinicie el dispositivo. + + + Ensure the entered URL is valid, and the device’s internet connection is good. + Asegúrese de que la URL insertada es válida y que el dispositivo tiene buena conexión. + + + No custom software found at this URL. + No encontramos software personalizado en esta URL. + + + WARNING: Low Voltage + ALERTA: Voltaje bajo + + + Power your device in a car with a harness or proceed at your own risk. + Encienda su dispositivo en un auto con el arnés o proceda bajo su propio riesgo. + + + Power off + Apagar + + + Continue + Continuar + + + Getting Started + Comenzando + + + Before we get on the road, let’s finish installation and cover some details. + Antes de ponernos en marcha, terminemos la instalación y cubramos algunos detalles. + + + Connect to Wi-Fi + Conectarse al Wi-Fi + + + Back + Volver + + + Continue without Wi-Fi + Continuar sin Wi-Fi + + + Waiting for internet + Esperando conexión a internet + + + Choose Software to Install + Elija el software a instalar + + + openpilot + openpilot + + + Custom Software + Software personalizado + + + Enter URL + Insertar URL + + + for Custom Software + para Software personalizado + + + Downloading... + Descargando... + + + Download Failed + Descarga fallida + + + Reboot device + Reiniciar Dispositivo + + + Start over + Comenzar de nuevo + + + Select a language + Seleccione un idioma + + + + SetupWidget + + Finish Setup + Terminar configuración + + + Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer. + Empareje su dispositivo con comma connect (connect.comma.ai) y reclame su oferta de comma prime. + + + Pair device + Emparejar dispositivo + + + + Sidebar + + CONNECT + CONNECT + + + OFFLINE + OFFLINE + + + ONLINE + EN LÍNEA + + + ERROR + ERROR + + + TEMP + TEMP + + + HIGH + ALTA + + + GOOD + BUENA + + + OK + OK + + + VEHICLE + VEHÍCULO + + + NO + SIN + + + PANDA + PANDA + + + -- + -- + + + Wi-Fi + Wi-Fi + + + ETH + ETH + + + 2G + 2G + + + 3G + 3G + + + LTE + LTE + + + 5G + 5G + + + + SoftwarePanel + + Updates are only downloaded while the car is off. + Actualizaciones solo se descargan con el auto apagado. + + + Current Version + Versión Actual + + + Download + Descargar + + + CHECK + VERIFICAR + + + Install Update + Actualizar + + + INSTALL + INSTALAR + + + Target Branch + Rama objetivo + + + SELECT + SELECCIONAR + + + Select a branch + Selecione una rama + + + Uninstall %1 + Desinstalar %1 + + + UNINSTALL + DESINSTALAR + + + Are you sure you want to uninstall? + ¿Seguro qué desea desinstalar? + + + Uninstall + Desinstalar + + + failed to check for update + no se pudo buscar actualizaciones + + + DOWNLOAD + DESCARGAR + + + update available + actualización disponible + + + never + nunca + + + up to date, last checked %1 + actualizado, último chequeo %1 + + + + SshControl + + SSH Keys + Clave SSH + + + Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username other than your own. A comma employee will NEVER ask you to add their GitHub username. + Aviso: Esto otorga acceso SSH a todas las claves públicas en su Github. Nunca ingrese un nombre de usuario de Github que no sea suyo. Un empleado de comma NUNCA le pedirá que añada un usuario de Github que no sea el suyo. + + + ADD + AÑADIR + + + Enter your GitHub username + Ingrese su usuario de GitHub + + + LOADING + CARGANDO + + + REMOVE + ELIMINAR + + + Username '%1' has no keys on GitHub + El usuario "%1” no tiene claves en GitHub + + + Request timed out + Solicitud expirada + + + Username '%1' doesn't exist on GitHub + El usuario '%1' no existe en Github + + + + SshToggle + + Enable SSH + Habilitar SSH + + + + TermsPage + + Terms & Conditions + Términos & Condiciones + + + Decline + Rechazar + + + Scroll to accept + Desliza para aceptar + + + Agree + Aceptar + + + + TogglesPanel + + Enable openpilot + Activar openpilot + + + Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off. + Utilice el sistema openpilot para acceder a un autocrucero adaptativo y asistencia al conductor para mantenerse en el carril. Se requiere su atención en todo momento para utilizar esta función. Cambiar esta configuración solo tendrá efecto con el auto apagado. + + + openpilot Longitudinal Control (Alpha) + Control longitudinal de openpilot (fase experimental) + + + WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB). + AVISO: el control longitudinal de openpilot está en fase experimental para este automóvil y desactivará el Frenado Automático de Emergencia (AEB). + + + On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha. + En este automóvil, openpilot se configura de manera predeterminada con el Autocrucero Adaptativo (ACC) incorporado en el automóvil en lugar del control longitudinal de openpilot. Habilita esta opción para cambiar al control longitudinal de openpilot. Se recomienda activar el modo experimental al habilitar el control longitudinal de openpilot (aún en fase experimental). + + + Experimental Mode + Modo Experimental + + + Disengage on Accelerator Pedal + Desactivar con el Acelerador + + + When enabled, pressing the accelerator pedal will disengage openpilot. + Cuando esté activado, presionar el acelerador deshabilitará openpilot. + + + Enable Lane Departure Warnings + Activar Avisos de Salida de Carril + + + Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h). + Recibir alertas para volver al carril cuando su vehículo se salga fuera del carril sin que esté activada la señal de giro y esté conduciendo por encima de 50 km/h (31 mph). + + + Always-On Driver Monitoring + Monitoreo Permanente del Conductor + + + Enable driver monitoring even when openpilot is not engaged. + Habilitar el monitoreo del conductor incluso cuando Openpilot no esté activado. + + + Record and Upload Driver Camera + Grabar y Subir Cámara del Conductor + + + Upload data from the driver facing camera and help improve the driver monitoring algorithm. + Subir datos de la cámara del conductor para ayudar a mejorar el algoritmo de monitoreo del conductor. + + + Use Metric System + Usar Sistema Métrico + + + Display speed in km/h instead of mph. + Mostrar velocidad en km/h en vez de mph. + + + Aggressive + Agresivo + + + Standard + Estándar + + + Relaxed + Relajado + + + Driving Personality + Personalidad de conducción + + + Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. In relaxed mode openpilot will stay further away from lead cars. On supported cars, you can cycle through these personalities with your steering wheel distance button. + Se recomienda el modo estándar. En el modo agresivo, openpilot seguirá más cerca a los autos delante suyo y será más agresivo con el acelerador y el freno. En modo relajado, openpilot se mantendrá más alejado de los autos delante suyo. En automóviles compatibles, puede recorrer estas personalidades con el botón de distancia del volante. + + + openpilot defaults to driving in <b>chill mode</b>. Experimental mode enables <b>alpha-level features</b> that aren't ready for chill mode. Experimental features are listed below: + openpilot por defecto conduce en <b>modo chill</b>. El modo Experimental activa <b>funcionalidades en fase experimental</b>, que no están listas para el modo chill. Las funcionalidades del modo expeimental están listados abajo: + + + End-to-End Longitudinal Control + Control Longitudinal de Punta a Punta + + + Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. Since the driving model decides the speed to drive, the set speed will only act as an upper bound. This is an alpha quality feature; mistakes should be expected. + Dajar que el modelo de conducción controle la aceleración y el frenado. openpilot conducirá como piensa que lo haría una persona, incluiyendo parar en los semáforos en rojo y las señales de alto. Dado que el modelo decide la velocidad de conducción, la velocidad de crucero establecida solo actuará como el límite superior. Este recurso aún está en fase experimental; deberían esperarse errores. + + + New Driving Visualization + Nueva Visualización de la conducción + + + The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner. + La visualización de la conducción cambiará a la cámara que enfoca la carretera a velocidades bajas para mostrar mejor los giros. El logo del modo experimental también se mostrará en la esquina superior derecha. + + + Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control. + El modo Experimental no está disponible actualmente para este auto, ya que el ACC default del auto está siendo usado para el control longitudinal. + + + openpilot longitudinal control may come in a future update. + El control longitudinal de openpilot podrá llegar en futuras actualizaciones. + + + An alpha version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches. + Se puede probar una versión experimental del control longitudinal openpilot, junto con el modo Experimental, en ramas no liberadas. + + + Enable the openpilot longitudinal control (alpha) toggle to allow Experimental mode. + Activar el control longitudinal (fase experimental) para permitir el modo Experimental. + + + + Updater + + Update Required + Actualización Requerida + + + An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB. + Es necesario la actualización del sistema operativo. Conecte su dispositivo al Wi-Fi para una actualización rápida. El tamaño de descarga es de aproximadamente 1GB. + + + Connect to Wi-Fi + Conectarse a la Wi-Fi + + + Install + Instalar + + + Back + Volver + + + Loading... + Cargando... + + + Reboot + Reiniciar + + + Update failed + Actualización fallida + + + + WiFiPromptWidget + + Setup Wi-Fi + Configurar Wi-Fi + + + Connect to Wi-Fi to upload driving data and help improve openpilot + Conectarse al Wi-Fi para subir los datos de conducción y mejorar openpilot + + + Open Settings + Abrir Configuraciones + + + Ready to upload + Listo para subir + + + Training data will be pulled periodically while your device is on Wi-Fi + Los datos de entrenamiento se extraerán periódicamente mientras tu dispositivo esté conectado a Wi-Fi + + + + WifiUI + + Scanning for networks... + Buscando redes... + + + CONNECTING... + CONECTANDO... + + + FORGET + OLVIDAR + + + Forget Wi-Fi Network "%1"? + ¿Olvidar la Red de Wi-Fi "%1"? + + + Forget + Olvidar + + + diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index dde6adadd3ca5af..f4251bc41d3e790 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -87,29 +87,6 @@ pour "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mi/h - - - MAX - MAX - - - SPEED - VITESSE - - - LIMIT - LIMITE - - ConfirmationDialog @@ -137,30 +114,14 @@ - DestinationWidget - - Home - Domicile - - - Work - Travail - - - No destination set - Aucune destination définie - + DeveloperPanel - home - domicile - - - work - travail + Joystick Debug Mode + - No %1 location set - Aucun lieu %1 défini + Longitudinal Maneuver Mode + @@ -324,6 +285,21 @@ MODE DÉTENTE ACTIVÉ + + HudRenderer + + km/h + km/h + + + mph + mi/h + + + MAX + MAX + + InputDialog @@ -345,47 +321,6 @@ Installation... - - MapETA - - eta - eta - - - min - min - - - hr - h - - - - MapSettings - - NAVIGATION - NAVIGATION - - - Manage at connect.comma.ai - Gérer sur connect.comma.ai - - - - MapWindow - - Map Loading - Chargement de la carte - - - Waiting for GPS - En attente du GPS - - - Waiting for route - En attente d'un trajet - - MultiOptionDialog @@ -460,10 +395,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot n'a pas pu identifier votre voiture. Votre voiture n'est pas supportée ou ses ECUs ne sont pas reconnues. Veuillez soumettre un pull request pour ajouter les versions de firmware au véhicule approprié. Besoin d'aide ? Rejoignez discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot n'a pas pu identifier votre voiture. Vérifiez l'intégrité des câbles et assurez-vous que toutes les connexions sont correctes, en particulier l'alimentation du comma est totalement insérée dans le port OBD-II du véhicule. Besoin d'aide ? Rejoignez discord.comma.ai. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot a détecté un changement dans la position de montage de l'appareil. Assurez-vous que l'appareil est totalement inséré dans le support et que le support est fermement fixé au pare-brise. @@ -491,19 +422,19 @@ - Waiting for controls to start + TAKE CONTROL IMMEDIATELY - TAKE CONTROL IMMEDIATELY + Reboot Device - Controls Unresponsive + Waiting to start - Reboot Device + System Unresponsive @@ -564,8 +495,8 @@ 1 an de stockage de trajets - Turn-by-turn navigation - Navigation étape par étape + Remote snapshots + @@ -614,22 +545,6 @@ il y a %n jours - - km - km - - - m - m - - - mi - mi - - - ft - ft - now @@ -698,6 +613,10 @@ Cela peut prendre jusqu'à une minute. Software Logiciel + + Developer + + Setup @@ -855,14 +774,6 @@ Cela peut prendre jusqu'à une minute. PANDA PANDA - - GPS - GPS - - - SEARCH - RECHERCHE - -- -- @@ -1090,22 +1001,6 @@ Cela peut prendre jusqu'à une minute. Display speed in km/h instead of mph. Afficher la vitesse en km/h au lieu de mph. - - Show ETA in 24h Format - Afficher l'heure d'arrivée en format 24h - - - Use 24h format instead of am/pm - Utiliser le format 24h plutôt que am/pm - - - Show Map on Left Side of UI - Afficher la carte à gauche de l'interface - - - Show map on left side when in split screen view. - Afficher la carte à gauche en mode écran scindé. - Aggressive Aggressif diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index e0fb60620bc64fc..bc83d3f9ae5b72d 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -87,29 +87,6 @@ ネットワーク名:%1 - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - 最高速度 - - - SPEED - 速度 - - - LIMIT - 制限速度 - - ConfirmationDialog @@ -137,29 +114,13 @@ - DestinationWidget + DeveloperPanel - Home + Joystick Debug Mode - Work - - - - No destination set - - - - No %1 location set - - - - home - - - - work + Longitudinal Maneuver Mode @@ -324,6 +285,21 @@ チルモード + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + 最高速度 + + InputDialog @@ -344,47 +320,6 @@ インストールしています... - - MapETA - - eta - 到着予定時間 - - - min - - - - hr - 時間 - - - - MapSettings - - NAVIGATION - - - - Manage at connect.comma.ai - - - - - MapWindow - - Map Loading - マップを読み込んでいます - - - Waiting for GPS - GPS信号を探しています - - - Waiting for route - - - MultiOptionDialog @@ -454,10 +389,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. @@ -489,19 +420,19 @@ - Waiting for controls to start + TAKE CONTROL IMMEDIATELY - TAKE CONTROL IMMEDIATELY + Reboot Device - Controls Unresponsive + Waiting to start - Reboot Device + System Unresponsive @@ -558,11 +489,11 @@ - Turn-by-turn navigation + 1 year of drive storage - 1 year of drive storage + Remote snapshots @@ -609,22 +540,6 @@ %n 日前 - - km - キロメートル - - - m - メートル - - - mi - マイル - - - ft - フィート - now @@ -692,6 +607,10 @@ This may take up to a minute. Software ソフトウェア + + Developer + + Setup @@ -849,14 +768,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - 検索 - -- -- @@ -1068,22 +979,6 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. この機能を有効化すると、openpilotを利用中にアクセルを踏むとopenpilotによる運転サポートを中断します。 - - Show ETA in 24h Format - 24時間表示 - - - Use 24h format instead of am/pm - AM/PM の代わりに24時間形式を使用します - - - Show Map on Left Side of UI - ディスプレイの左側にマップを表示 - - - Show map on left side when in split screen view. - 分割画面表示の場合、ディスプレイの左側にマップを表示します。 - Experimental Mode 実験モード diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index 56fc5014eed4b2b..1d2a753e1f4b039 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -87,29 +87,6 @@ "%1"에 접속하려면 비밀번호가 필요합니다 - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - MAX - - - SPEED - SPEED - - - LIMIT - LIMIT - - ConfirmationDialog @@ -137,30 +114,14 @@ - DestinationWidget - - Home - - - - Work - 회사 - + DeveloperPanel - No destination set - 목적지가 설정되지 않았습니다 + Joystick Debug Mode + 조이스틱 디버그 모드 - No %1 location set - %1 위치가 설정되지 않았습니다 - - - home - - - - work - 회사 + Longitudinal Maneuver Mode + 롱컨 기동 모드 @@ -324,6 +285,21 @@ 안정 모드 사용 + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + MAX + + InputDialog @@ -344,47 +320,6 @@ 설치 중... - - MapETA - - eta - 도착 - - - min - - - - hr - 시간 - - - - MapSettings - - NAVIGATION - 내비게이션 - - - Manage at connect.comma.ai - connect.comma.ai에서 관리하세요 - - - - MapWindow - - Map Loading - 지도 로딩 중 - - - Waiting for GPS - GPS 수신 중 - - - Waiting for route - 경로를 기다리는 중 - - MultiOptionDialog @@ -455,10 +390,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot이 차량을 식별할 수 없었습니다. 지원되지 않는 차량이거나 ECU가 인식되지 않습니다. 해당 차량에 맞는 펌웨어 버전을 추가하려면 PR을 제출하세요. 도움이 필요하시면 discord.comma.ai에 가입하세요. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot이 차량을 식별할 수 없었습니다. 케이블의 무결성을 점검하고 모든 연결부, 특히 comma power가 차량의 OBD-II 포트에 제대로 삽입되었는지 확인하세요. 도움이 필요하시면 discord.comma.ai에 가입하세요. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot 장치의 장착 위치가 변경되었습니다. 장치가 마운트에 완전히 장착되고 마운트가 앞유리에 단단히 고정되었는지 확인하세요. @@ -489,22 +420,22 @@ openpilot Unavailable 오픈파일럿을 사용할수없습니다 - - Waiting for controls to start - 프로세스가 준비중입니다 - TAKE CONTROL IMMEDIATELY 핸들을 잡아주세요 - - Controls Unresponsive - 프로세스가 응답하지않습니다 - Reboot Device 장치를 재부팅하세요 + + Waiting to start + 시작을 기다리는중 + + + System Unresponsive + 시스템이 응답하지않습니다 + PairingPopup @@ -558,14 +489,14 @@ 24/7 LTE connectivity 항상 LTE 연결 - - Turn-by-turn navigation - 내비게이션 경로안내 - 1 year of drive storage 1년간 드라이브 로그 저장 + + Remote snapshots + 원격 스냅샷 + PrimeUserWidget @@ -610,22 +541,6 @@ %n 일 전 - - km - km - - - m - m - - - mi - mi - - - ft - ft - now now @@ -694,6 +609,10 @@ This may take up to a minute. Software 소프트웨어 + + Developer + 개발자 + Setup @@ -851,14 +770,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - 검색중 - -- -- @@ -1070,22 +981,6 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. 활성화된 경우 가속 페달을 밟으면 openpilot이 해제됩니다. - - Show ETA in 24h Format - 24시간 형식으로 도착 예정 시간 표시 - - - Use 24h format instead of am/pm - 오전/오후 대신 24시간 형식 사용 - - - Show Map on Left Side of UI - UI 왼쪽에 지도 표시 - - - Show map on left side when in split screen view. - 분할 화면 보기에서 지도를 왼쪽에 표시합니다. - Experimental Mode 실험 모드 @@ -1156,15 +1051,15 @@ This may take up to a minute. The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner. - + 운전 시각화는 일부 회전을 더 잘 보여주기 위해 저속에서 도로를 향한 광각 카메라로 전환됩니다. 실험 모드 로고도 우측 상단에 표시됩니다. Always-On Driver Monitoring - + 상시 운전자 모니터링 Enable driver monitoring even when openpilot is not engaged. - + Openpilot이 활성화되지 않은 경우에도 드라이버 모니터링을 활성화합니다. diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index feaa6e86a14abb0..a89c85510e7fe2c 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -87,29 +87,6 @@ para "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - LIMITE - - - SPEED - MAX - - - LIMIT - VELO - - ConfirmationDialog @@ -137,30 +114,14 @@ - DestinationWidget - - Home - Casa - - - Work - Trabalho - + DeveloperPanel - No destination set - Nenhum destino definido + Joystick Debug Mode + Modo Joystick Debug - No %1 location set - Endereço de %1 não definido - - - home - casa - - - work - trabalho + Longitudinal Maneuver Mode + Modo Longitudinal Maneuver @@ -324,6 +285,21 @@ MODO CHILL ON + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + LIMITE + + InputDialog @@ -345,47 +321,6 @@ Instalando... - - MapETA - - eta - eta - - - min - min - - - hr - hr - - - - MapSettings - - NAVIGATION - NAVEGAÇÃO - - - Manage at connect.comma.ai - Gerencie em connect.comma.ai - - - - MapWindow - - Map Loading - Carregando Mapa - - - Waiting for GPS - Aguardando GPS - - - Waiting for route - Aguardando rota - - MultiOptionDialog @@ -456,10 +391,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. O openpilot não conseguiu identificar o seu carro. Seu carro não é suportado ou seus ECUs não são reconhecidos. Envie um pull request para adicionar as versões de firmware ao veículo adequado. Precisa de ajuda? Junte-se discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - O openpilot não conseguiu identificar o seu carro. Verifique a integridade dos cabos e certifique-se de que todas as conexões estejam seguras, especialmente se o comma power está totalmente inserido na porta OBD-II do veículo. Precisa de ajuda? Junte-se discord.comma.ai. - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. O openpilot detectou uma mudança na posição de montagem do dispositivo. Verifique se o dispositivo está totalmente encaixado no suporte e se o suporte está firmemente preso ao para-brisa. @@ -490,22 +421,22 @@ openpilot Unavailable openpilot Indisponível - - Waiting for controls to start - Aguardando controles para iniciar - TAKE CONTROL IMMEDIATELY ASSUMA IMEDIATAMENTE - - Controls Unresponsive - Controles Não Respondem - Reboot Device Reinicie o Dispositivo + + Waiting to start + Aguardando para iniciar + + + System Unresponsive + Sistema sem Resposta + PairingPopup @@ -559,14 +490,14 @@ 24/7 LTE connectivity Conectividade LTE (só nos EUA) - - Turn-by-turn navigation - Navegação passo a passo - 1 year of drive storage 1 ano de dados em nuvem + + Remote snapshots + Captura remota + PrimeUserWidget @@ -614,22 +545,6 @@ há %n dias - - km - km - - - m - m - - - mi - milha - - - ft - pés - now agora @@ -698,6 +613,10 @@ Isso pode levar até um minuto. Software Software + + Developer + Desenvdor + Setup @@ -855,14 +774,6 @@ Isso pode levar até um minuto. PANDA PANDA - - GPS - GPS - - - SEARCH - PROCURA - -- -- @@ -1074,22 +985,6 @@ Isso pode levar até um minuto. When enabled, pressing the accelerator pedal will disengage openpilot. Quando ativado, pressionar o pedal do acelerador desacionará o openpilot. - - Show ETA in 24h Format - Mostrar ETA em Formato 24h - - - Use 24h format instead of am/pm - Use o formato 24h em vez de am/pm - - - Show Map on Left Side of UI - Exibir Mapa no Lado Esquerdo - - - Show map on left side when in split screen view. - Exibir mapa do lado esquerdo quando a tela for dividida. - Experimental Mode Modo Experimental diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index e594a6975f4c1a1..c2b2771830eabfc 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -87,29 +87,6 @@ สำหรับ "%1" - - AnnotatedCameraWidget - - km/h - กม./ชม. - - - mph - ไมล์/ชม. - - - MAX - สูงสุด - - - SPEED - ความเร็ว - - - LIMIT - จำกัด - - ConfirmationDialog @@ -137,30 +114,14 @@ - DestinationWidget - - Home - บ้าน - - - Work - ที่ทำงาน - - - No destination set - ยังไม่ได้เลือกจุดหมาย - - - home - บ้าน - + DeveloperPanel - work - ที่ทำงาน + Joystick Debug Mode + - No %1 location set - ยังไม่ได้เลือกตำแหน่ง%1 + Longitudinal Maneuver Mode + @@ -324,6 +285,21 @@ คุณกำลังใช้โหมดชิล + + HudRenderer + + km/h + กม./ชม. + + + mph + ไมล์/ชม. + + + MAX + สูงสุด + + InputDialog @@ -344,47 +320,6 @@ กำลังติดตั้ง... - - MapETA - - eta - eta - - - min - นาที - - - hr - ชม. - - - - MapSettings - - NAVIGATION - การนำทาง - - - Manage at connect.comma.ai - จัดการได้ที่ connect.comma.ai - - - - MapWindow - - Map Loading - กำลังโหลดแผนที่ - - - Waiting for GPS - กำลังรอสัญญาณ GPS - - - Waiting for route - กำลังรอเส้นทาง - - MultiOptionDialog @@ -459,10 +394,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot ไม่สามารถระบุรถยนต์ของคุณได้ ระบบอาจไม่รองรับรถยนต์ของคุณหรือไม่รู้จัก ECU กรุณาส่ง pull request เพื่อเพิ่มรุ่นของเฟิร์มแวร์ให้กับรถยนต์ที่เหมาะสม หากต้องการความช่วยเหลือให้เข้าร่วม discord.comma.ai - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot ไม่สามารถระบุรถยนต์ของคุณได้ กรุณาตรวจสอบสายเคเบิ้ลและจุดเชื่อมต่อทั้งหมดว่าแน่นหนา โดยเฉพาะ comma power ว่าได้ดันเข้าไปยังพอร์ต OBD II ของรถยนต์จนสุด หากต้องการความช่วยเหลือให้เข้าร่วม discord.comma.ai - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot ตรวจพบการเปลี่ยนแปลงของตำแหน่งที่ติดตั้ง กรุณาตรวจสอบว่าได้เลื่อนอุปกรณ์เข้ากับจุดติดตั้งจนสุดแล้ว และจุดติดตั้งได้ยึดติดกับกระจกหน้าอย่างแน่นหนา @@ -489,22 +420,22 @@ openpilot Unavailable openpilot ไม่สามารถใช้งานได้ - - Waiting for controls to start - กำลังรอให้ controls เริ่มทำงาน - TAKE CONTROL IMMEDIATELY เข้าควบคุมรถเดี๋ยวนี้ - - Controls Unresponsive - Controls ไม่ตอบสนอง - Reboot Device รีบูตอุปกรณ์ + + Waiting to start + + + + System Unresponsive + + PairingPopup @@ -563,8 +494,8 @@ จัดเก็บข้อมูลการขับขี่นาน 1 ปี - Turn-by-turn navigation - การนำทางแบบเลี้ยวต่อเลี้ยว + Remote snapshots + @@ -610,22 +541,6 @@ %n วันที่แล้ว - - km - กม. - - - m - ม. - - - mi - ไมล์ - - - ft - ฟุต - now ตอนนี้ @@ -694,6 +609,10 @@ This may take up to a minute. Software ซอฟต์แวร์ + + Developer + + Setup @@ -851,14 +770,6 @@ This may take up to a minute. PANDA PANDA - - GPS - จีพีเอส - - - SEARCH - ค้นหา - -- -- @@ -1070,22 +981,6 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. เมื่อเปิดใช้งาน การกดแป้นคันเร่งจะเป็นการยกเลิกระบบช่วยขับโดย openpilot - - Show ETA in 24h Format - แสดงเวลา ETA ในรูปแบบ 24 ชั่วโมง - - - Use 24h format instead of am/pm - ใช้รูปแบบเวลา 24 ชั่วโมง แทน am/pm - - - Show Map on Left Side of UI - แสดงแผนที่ที่ด้านซ้ายของหน้าจอ - - - Show map on left side when in split screen view. - แสดงแผนที่ด้านซ้ายของหน้าจอเมื่ออยู่ในโหมดแบ่งหน้าจอ - Experimental Mode โหมดทดลอง diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index 48615f169933b36..9a53449276fcd85 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -87,29 +87,6 @@ için "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - MAX - - - SPEED - HIZ - - - LIMIT - LİMİT - - ConfirmationDialog @@ -137,29 +114,13 @@ - DestinationWidget - - Home - - - - Work - - - - No destination set - - + DeveloperPanel - home + Joystick Debug Mode - work - - - - No %1 location set + Longitudinal Maneuver Mode @@ -324,6 +285,21 @@ + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + MAX + + InputDialog @@ -344,47 +320,6 @@ Yükleniyor... - - MapETA - - eta - tahmini varış süresi - - - min - dk - - - hr - saat - - - - MapSettings - - NAVIGATION - - - - Manage at connect.comma.ai - - - - - MapWindow - - Map Loading - Harita yükleniyor - - - Waiting for GPS - GPS verisi bekleniyor... - - - Waiting for route - - - MultiOptionDialog @@ -458,10 +393,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. @@ -489,19 +420,19 @@ - Waiting for controls to start + TAKE CONTROL IMMEDIATELY - TAKE CONTROL IMMEDIATELY + Reboot Device - Controls Unresponsive + Waiting to start - Reboot Device + System Unresponsive @@ -562,7 +493,7 @@ - Turn-by-turn navigation + Remote snapshots @@ -609,22 +540,6 @@ %n gün önce - - km - km - - - m - m - - - mi - mil - - - ft - ft - now @@ -692,6 +607,10 @@ This may take up to a minute. Software Yazılım + + Developer + + Setup @@ -849,14 +768,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - ARA - -- -- @@ -1064,22 +975,6 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. Aktifleştirilirse eğer gaz pedalına basınca openpilot devre dışı kalır. - - Show ETA in 24h Format - Tahmini varış süresini 24 saat formatı şeklinde göster - - - Use 24h format instead of am/pm - 24 saat formatını kullan - - - Show Map on Left Side of UI - Haritayı arayüzün sol tarafında göster - - - Show map on left side when in split screen view. - Bölünmüş ekran görünümündeyken haritayı sol tarafta göster. - openpilot Longitudinal Control (Alpha) diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 32119ee10f4d785..f061322c45f6fa8 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -87,29 +87,6 @@ 网络名称:"%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - 最高定速 - - - SPEED - SPEED - - - LIMIT - LIMIT - - ConfirmationDialog @@ -137,30 +114,14 @@ - DestinationWidget - - Home - 住家 - - - Work - 工作 - + DeveloperPanel - No destination set - 尚未设置目的地 + Joystick Debug Mode + - No %1 location set - 尚未设置 %1 的位置 - - - home - 住家 - - - work - 工作 + Longitudinal Maneuver Mode + @@ -324,6 +285,21 @@ 轻松模式运行 + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + 最高定速 + + InputDialog @@ -344,47 +320,6 @@ 正在安装…… - - MapETA - - eta - 抵达 - - - min - 分钟 - - - hr - 小时 - - - - MapSettings - - NAVIGATION - 导航 - - - Manage at connect.comma.ai - 请在 connect.comma.ai 上管理 - - - - MapWindow - - Map Loading - 地图加载中 - - - Waiting for GPS - 等待 GPS - - - Waiting for route - 等待路线 - - MultiOptionDialog @@ -455,10 +390,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot 无法识别您的车辆。您的车辆可能未被支持,或是其电控单元 (ECU) 未被识别。请提交一个 Pull Request 为您的车辆添加正确的固件版本。需要帮助吗?请加入 discord.comma.ai。 - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot 无法识别您的车辆。请检查线路是否正确安装并确保所有的连接都牢固,特别是确保 comma power 完全插入车辆的 OBD-II 接口。需要帮助吗?请加入 discord.comma.ai。 - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot 检测到设备的安装位置发生变化。请确保设备完全安装在支架上,并确保支架牢固地固定在挡风玻璃上。 @@ -489,22 +420,22 @@ openpilot Unavailable 无法使用 openpilot - - Waiting for controls to start - 等待控制服务啟動 - TAKE CONTROL IMMEDIATELY 立即接管 - - Controls Unresponsive - 控制服务无响应 - Reboot Device 重启设备 + + Waiting to start + 等待开始 + + + System Unresponsive + 系统无响应 + PairingPopup @@ -556,16 +487,16 @@ 24/7 LTE connectivity - 全天候 LTE 連線 - - - Turn-by-turn navigation - 领航功能 + 全天候 LTE 连接 1 year of drive storage 一年的行驶记录储存空间 + + Remote snapshots + 远程快照 + PrimeUserWidget @@ -610,22 +541,6 @@ %n 天前 - - km - km - - - m - m - - - mi - mi - - - ft - ft - now 现在 @@ -694,6 +609,10 @@ This may take up to a minute. Software 软件 + + Developer + + Setup @@ -851,14 +770,6 @@ This may take up to a minute. PANDA PANDA - - GPS - GPS - - - SEARCH - 搜索中 - -- -- @@ -1070,22 +981,6 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. 启用后,踩下油门踏板将取消openpilot。 - - Show ETA in 24h Format - 以24小时格式显示预计到达时间 - - - Use 24h format instead of am/pm - 使用24小时制代替am/pm - - - Show Map on Left Side of UI - 在介面左侧显示地图 - - - Show map on left side when in split screen view. - 在分屏模式中,将地图置于屏幕左侧。 - Experimental Mode 测试模式 diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index 9d1c16db9f08ad0..04e76a8d957272f 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -87,29 +87,6 @@ 給 "%1" - - AnnotatedCameraWidget - - km/h - km/h - - - mph - mph - - - MAX - 最高 - - - SPEED - 速度 - - - LIMIT - 速限 - - ConfirmationDialog @@ -137,30 +114,14 @@ - DestinationWidget - - Home - 住家 - - - Work - 工作 - - - No destination set - 尚未設定目的地 - - - No %1 location set - 尚未設定 %1 的位置 - + DeveloperPanel - home - 住家 + Joystick Debug Mode + - work - 工作 + Longitudinal Maneuver Mode + @@ -324,6 +285,21 @@ 輕鬆模式 ON + + HudRenderer + + km/h + km/h + + + mph + mph + + + MAX + 最高 + + InputDialog @@ -344,47 +320,6 @@ 安裝中… - - MapETA - - eta - 抵達 - - - min - 分鐘 - - - hr - 小時 - - - - MapSettings - - NAVIGATION - 導航 - - - Manage at connect.comma.ai - 請在 connect.comma.ai 上管理 - - - - MapWindow - - Map Loading - 地圖載入中 - - - Waiting for GPS - 等待 GPS - - - Waiting for route - 等待路線 - - MultiOptionDialog @@ -455,10 +390,6 @@ openpilot was unable to identify your car. Your car is either unsupported or its ECUs are not recognized. Please submit a pull request to add the firmware versions to the proper vehicle. Need help? Join discord.comma.ai. openpilot 無法識別您的車輛。您的車輛可能未被支援,或是其電控單元 (ECU) 未被識別。請提交一個 Pull Request 為您的車輛添加正確的韌體版本。需要幫助嗎?請加入 discord.comma.ai 。 - - openpilot was unable to identify your car. Check integrity of cables and ensure all connections are secure, particularly that the comma power is fully inserted in the OBD-II port of the vehicle. Need help? Join discord.comma.ai. - openpilot 無法識別您的車輛。請檢查線路是否正確的安裝並確保所有的連接都牢固,特別是確保 comma power 完全插入車輛的 OBD-II 介面。需要幫助嗎?請加入 discord.comma.ai 。 - openpilot detected a change in the device's mounting position. Ensure the device is fully seated in the mount and the mount is firmly secured to the windshield. openpilot 偵測到裝置的安裝位置發生變化。請確保裝置完全安裝在支架上,並確保支架牢固地固定在擋風玻璃上。 @@ -489,22 +420,22 @@ openpilot Unavailable 無法使用 openpilot - - Waiting for controls to start - 等待操控服務開始 - TAKE CONTROL IMMEDIATELY 立即接管 - - Controls Unresponsive - 操控服務沒有反應 - Reboot Device 請重新啟裝置 + + Waiting to start + 等待開始 + + + System Unresponsive + 系統無回應 + PairingPopup @@ -558,14 +489,14 @@ 24/7 LTE connectivity 24/7 LTE 連線 - - Turn-by-turn navigation - 導航功能 - 1 year of drive storage 一年的行駛記錄儲存空間 + + Remote snapshots + 遠端快照 + PrimeUserWidget @@ -610,22 +541,6 @@ %n 天前 - - km - km - - - m - m - - - mi - mi - - - ft - ft - now 現在 @@ -694,6 +609,10 @@ This may take up to a minute. Software 軟體 + + Developer + + Setup @@ -851,14 +770,6 @@ This may take up to a minute. PANDA 車輛通訊 - - GPS - GPS - - - SEARCH - 車輛通訊 - -- -- @@ -1070,22 +981,6 @@ This may take up to a minute. When enabled, pressing the accelerator pedal will disengage openpilot. 啟用後,踩踏油門將會取消 openpilot 控制。 - - Show ETA in 24h Format - 預計到達時間單位改用 24 小時制 - - - Use 24h format instead of am/pm - 使用 24 小時制。(預設值為 12 小時制) - - - Show Map on Left Side of UI - 將地圖顯示在畫面的左側 - - - Show map on left side when in split screen view. - 進入分割畫面後,地圖將會顯示在畫面的左側。 - Experimental Mode 實驗模式 diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index c70b7594c97775c..ec3d40961d78ba1 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -1,13 +1,11 @@ #include "selfdrive/ui/ui.h" #include -#include #include #include #include "common/transformations/orientation.hpp" -#include "common/params.h" #include "common/swaglog.h" #include "common/util.h" #include "common/watchdog.h" @@ -16,139 +14,6 @@ #define BACKLIGHT_DT 0.05 #define BACKLIGHT_TS 10.00 -// Projects a point in car to space to the corresponding point in full frame -// image space. -static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, float in_z, QPointF *out) { - const float margin = 500.0f; - const QRectF clip_region{-margin, -margin, s->fb_w + 2 * margin, s->fb_h + 2 * margin}; - - const vec3 pt = (vec3){{in_x, in_y, in_z}}; - const vec3 Ep = matvecmul3(s->scene.wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib, pt); - const vec3 KEp = matvecmul3(s->scene.wide_cam ? ECAM_INTRINSIC_MATRIX : FCAM_INTRINSIC_MATRIX, Ep); - - // Project. - QPointF point = s->car_space_transform.map(QPointF{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2]}); - if (clip_region.contains(point)) { - *out = point; - return true; - } - return false; -} - -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 < line_x.size() && line_x[i] <= path_height; ++i) { - max_idx = i; - } - return max_idx; -} - -void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line) { - for (int i = 0; i < 2; ++i) { - auto lead_data = (i == 0) ? radar_state.getLeadOne() : radar_state.getLeadTwo(); - if (lead_data.getStatus()) { - float z = line.getZ()[get_path_length_idx(line, lead_data.getDRel())]; - calib_frame_to_full_frame(s, lead_data.getDRel(), -lead_data.getYRel(), z + 1.22, &s->scene.lead_vertices[i]); - } - } -} - -void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line, - float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert=true) { - const auto line_x = line.getX(), line_y = line.getY(), line_z = line.getZ(); - QPointF left, right; - pvd->clear(); - for (int i = 0; i <= max_idx; i++) { - // highly negative x positions are drawn above the frame and cause flickering, clip to zy plane of camera - if (line_x[i] < 0) continue; - - bool l = calib_frame_to_full_frame(s, line_x[i], line_y[i] - y_off, line_z[i] + z_off, &left); - bool r = calib_frame_to_full_frame(s, line_x[i], line_y[i] + y_off, line_z[i] + z_off, &right); - if (l && r) { - // For wider lines the drawn polygon will "invert" when going over a hill and cause artifacts - if (!allow_invert && pvd->size() && left.y() > pvd->back().y()) { - continue; - } - pvd->push_back(left); - pvd->push_front(right); - } - } -} - -void update_model(UIState *s, - const cereal::ModelDataV2::Reader &model, - const cereal::UiPlan::Reader &plan) { - UIScene &scene = s->scene; - auto plan_position = plan.getPosition(); - if (plan_position.getX().size() < model.getPosition().getX().size()) { - plan_position = model.getPosition(); - } - float max_distance = std::clamp(*(plan_position.getX().end() - 1), - MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE); - - // update lane lines - const auto lane_lines = model.getLaneLines(); - const auto lane_line_probs = model.getLaneLineProbs(); - int max_idx = get_path_length_idx(lane_lines[0], max_distance); - for (int i = 0; i < std::size(scene.lane_line_vertices); i++) { - scene.lane_line_probs[i] = lane_line_probs[i]; - update_line_data(s, lane_lines[i], 0.025 * scene.lane_line_probs[i], 0, &scene.lane_line_vertices[i], max_idx); - } - - // update road edges - const auto road_edges = model.getRoadEdges(); - const auto road_edge_stds = model.getRoadEdgeStds(); - for (int i = 0; i < std::size(scene.road_edge_vertices); i++) { - scene.road_edge_stds[i] = road_edge_stds[i]; - update_line_data(s, road_edges[i], 0.025, 0, &scene.road_edge_vertices[i], max_idx); - } - - // update path - auto lead_one = (*s->sm)["radarState"].getRadarState().getLeadOne(); - if (lead_one.getStatus()) { - const float lead_d = lead_one.getDRel() * 2.; - max_distance = std::clamp((float)(lead_d - fmin(lead_d * 0.35, 10.)), 0.0f, max_distance); - } - max_idx = get_path_length_idx(plan_position, max_distance); - update_line_data(s, plan_position, 0.9, 1.22, &scene.track_vertices, max_idx, false); -} - -void update_dmonitoring(UIState *s, const cereal::DriverStateV2::Reader &driverstate, float dm_fade_state, bool is_rhd) { - UIScene &scene = s->scene; - const auto driver_orient = is_rhd ? driverstate.getRightDriverData().getFaceOrientation() : driverstate.getLeftDriverData().getFaceOrientation(); - for (int i = 0; i < std::size(scene.driver_pose_vals); i++) { - float v_this = (i == 0 ? (driver_orient[i] < 0 ? 0.7 : 0.9) : 0.4) * driver_orient[i]; - scene.driver_pose_diff[i] = fabs(scene.driver_pose_vals[i] - v_this); - scene.driver_pose_vals[i] = 0.8 * v_this + (1 - 0.8) * scene.driver_pose_vals[i]; - scene.driver_pose_sins[i] = sinf(scene.driver_pose_vals[i]*(1.0-dm_fade_state)); - scene.driver_pose_coss[i] = cosf(scene.driver_pose_vals[i]*(1.0-dm_fade_state)); - } - - auto [sin_y, sin_x, sin_z] = scene.driver_pose_sins; - auto [cos_y, cos_x, cos_z] = scene.driver_pose_coss; - - const mat3 r_xyz = (mat3){{ - cos_x * cos_z, - cos_x * sin_z, - -sin_x, - - -sin_y * sin_x * cos_z - cos_y * sin_z, - -sin_y * sin_x * sin_z + cos_y * cos_z, - -sin_y * cos_x, - - cos_y * sin_x * cos_z - sin_y * sin_z, - cos_y * sin_x * sin_z + sin_y * cos_z, - cos_y * cos_x, - }}; - - // transform vertices - for (int kpi = 0; kpi < std::size(default_face_kpts_3d); kpi++) { - vec3 kpt_this = matvecmul3(r_xyz, default_face_kpts_3d[kpi]); - scene.face_kpts_draw[kpi] = (vec3){{kpt_this.v[0], kpt_this.v[1], (float)(kpt_this.v[2] * (1.0-dm_fade_state) + 8 * dm_fade_state)}}; - } -} - static void update_sockets(UIState *s) { s->sm->update(0); } @@ -158,29 +23,19 @@ static void update_state(UIState *s) { UIScene &scene = s->scene; if (sm.updated("liveCalibration")) { + auto list2rot = [](const capnp::List::Reader &rpy_list) ->Eigen::Matrix3f { + return euler2rot({rpy_list[0], rpy_list[1], rpy_list[2]}).cast(); + }; + auto live_calib = sm["liveCalibration"].getLiveCalibration(); - auto rpy_list = live_calib.getRpyCalib(); - auto wfde_list = live_calib.getWideFromDeviceEuler(); - Eigen::Vector3d rpy; - Eigen::Vector3d wfde; - if (rpy_list.size() == 3) rpy << rpy_list[0], rpy_list[1], rpy_list[2]; - if (wfde_list.size() == 3) wfde << wfde_list[0], wfde_list[1], wfde_list[2]; - Eigen::Matrix3d device_from_calib = euler2rot(rpy); - Eigen::Matrix3d wide_from_device = euler2rot(wfde); - Eigen::Matrix3d view_from_device; - view_from_device << 0, 1, 0, - 0, 0, 1, - 1, 0, 0; - Eigen::Matrix3d view_from_calib = view_from_device * device_from_calib; - Eigen::Matrix3d view_from_wide_calib = view_from_device * wide_from_device * device_from_calib; - for (int i = 0; i < 3; i++) { - for (int j = 0; j < 3; j++) { - scene.view_from_calib.v[i*3 + j] = view_from_calib(i, j); - scene.view_from_wide_calib.v[i*3 + j] = view_from_wide_calib(i, j); - } + if (live_calib.getCalStatus() == cereal::LiveCalibrationData::Status::CALIBRATED) { + auto device_from_calib = list2rot(live_calib.getRpyCalib()); + auto wide_from_device = list2rot(live_calib.getWideFromDeviceEuler()); + s->scene.view_from_calib = VIEW_FROM_DEVICE * device_from_calib; + s->scene.view_from_wide_calib = VIEW_FROM_DEVICE * wide_from_device * device_from_calib; + } else { + s->scene.view_from_calib = s->scene.view_from_wide_calib = VIEW_FROM_DEVICE; } - scene.calibration_valid = live_calib.getCalStatus() == cereal::LiveCalibrationData::Status::CALIBRATED; - scene.calibration_wide_valid = wfde_list.size() == 3; } if (sm.updated("pandaStates")) { auto pandaStates = sm["pandaStates"].getPandaStates(); @@ -197,9 +52,6 @@ static void update_state(UIState *s) { } else if ((s->sm->frame - s->sm->rcv_frame("pandaStates")) > 5*UI_FREQ) { scene.pandaType = cereal::PandaState::PandaType::UNKNOWN; } - if (sm.updated("carParams")) { - scene.longitudinal_control = sm["carParams"].getCarParams().getOpenpilotLongitudinalControl(); - } if (sm.updated("wideRoadCameraState")) { auto cam_state = sm["wideRoadCameraState"].getWideRoadCameraState(); float scale = (cam_state.getSensor() == cereal::FrameData::ImageSensor::AR0231) ? 6.0f : 1.0f; @@ -208,28 +60,21 @@ static void update_state(UIState *s) { scene.light_sensor = -1; } 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) { auto params = Params(); s->scene.is_metric = params.getBool("IsMetric"); - s->scene.map_on_left = params.getBool("NavSettingLeftSide"); } void UIState::updateStatus() { - if (scene.started && sm->updated("controlsState")) { - auto controls_state = (*sm)["controlsState"].getControlsState(); - auto state = controls_state.getState(); - if (state == cereal::ControlsState::OpenpilotState::PRE_ENABLED || state == cereal::ControlsState::OpenpilotState::OVERRIDING) { + if (scene.started && sm->updated("selfdriveState")) { + auto ss = (*sm)["selfdriveState"].getSelfdriveState(); + auto state = ss.getState(); + if (state == cereal::SelfdriveState::OpenpilotState::PRE_ENABLED || state == cereal::SelfdriveState::OpenpilotState::OVERRIDING) { status = STATUS_OVERRIDE; } else { - status = controls_state.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; + status = ss.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; } } @@ -240,24 +85,18 @@ 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>({ + sm = std::make_unique(std::vector{ "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", - "pandaStates", "carParams", "driverMonitoringState", "carState", "liveLocationKalman", "driverStateV2", - "wideRoadCameraState", "managerState", "navInstruction", "navRoute", "uiPlan", "clocks", + "pandaStates", "carParams", "driverMonitoringState", "carState", "driverStateV2", + "wideRoadCameraState", "managerState", "selfdriveState", "longitudinalPlan", }); - - Params params; - language = QString::fromStdString(params.get("LanguageSetting")); - auto prime_value = params.get("PrimeType"); - if (!prime_value.empty()) { - prime_type = static_cast(std::atoi(prime_value.c_str())); - } + prime_state = new PrimeState(this); + language = QString::fromStdString(Params().get("LanguageSetting")); // update timer timer = new QTimer(this); @@ -276,21 +115,6 @@ void UIState::update() { emit uiUpdate(*this); } -void UIState::setPrimeType(PrimeType type) { - if (type != prime_type) { - bool prev_prime = hasPrime(); - - prime_type = type; - Params().put("PrimeType", std::to_string(prime_type)); - emit primeTypeChanged(prime_type); - - bool prime = hasPrime(); - if (prev_prime != prime) { - emit primeChanged(prime); - } - } -} - Device::Device(QObject *parent) : brightness_filter(BACKLIGHT_OFFROAD, BACKLIGHT_TS, BACKLIGHT_DT), QObject(parent) { setAwake(true); resetInteractiveTimeout(); @@ -321,7 +145,7 @@ void Device::resetInteractiveTimeout(int timeout) { void Device::updateBrightness(const UIState &s) { float clipped_brightness = offroad_brightness; - if (s.scene.started && s.scene.light_sensor > 0) { + if (s.scene.started && s.scene.light_sensor >= 0) { clipped_brightness = s.scene.light_sensor; // CIE 1931 - https://www.photonstophotos.net/GeneralTopics/Exposure/Psychometric_Lightness_and_Gamma.htm diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 7238159ddacb562..6ff67cacde9cb6c 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -1,20 +1,19 @@ #pragma once +#include #include #include -#include #include #include #include -#include -#include #include "cereal/messaging/messaging.h" #include "common/mat.h" #include "common/params.h" -#include "common/timing.h" +#include "common/util.h" #include "system/hardware/hw.h" +#include "selfdrive/ui/qt/prime_state.h" const int UI_BORDER_SIZE = 30; const int UI_HEADER_HEIGHT = 420; @@ -22,29 +21,22 @@ const int UI_HEADER_HEIGHT = 420; const int UI_FREQ = 20; // Hz const int BACKLIGHT_OFFROAD = 50; -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}}; +const Eigen::Matrix3f VIEW_FROM_DEVICE = (Eigen::Matrix3f() << + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0, + 1.0, 0.0, 0.0).finished(); + +const Eigen::Matrix3f FCAM_INTRINSIC_MATRIX = (Eigen::Matrix3f() << + 2648.0, 0.0, 1928.0 / 2, + 0.0, 2648.0, 1208.0 / 2, + 0.0, 0.0, 1.0).finished(); + // 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}, - {-34.10, -32.00, 8.00}, {-36.16, -21.03, 8.00}, {-36.16, 6.40, 8.00}, {-35.47, 10.51, 8.00}, {-32.73, 19.43, 8.00}, - {-29.30, 26.29, 8.00}, {-24.50, 33.83, 8.00}, {-19.01, 41.37, 8.00}, {-14.21, 46.17, 8.00}, {-12.16, 47.54, 8.00}, - {-4.61, 49.60, 8.00}, {4.99, 49.60, 8.00}, {12.53, 47.54, 8.00}, {14.59, 46.17, 8.00}, {19.39, 41.37, 8.00}, - {24.87, 33.83, 8.00}, {29.67, 26.29, 8.00}, {33.10, 19.43, 8.00}, {35.84, 10.51, 8.00}, {36.53, 6.40, 8.00}, - {36.53, -21.03, 8.00}, {34.47, -32.00, 8.00}, {32.42, -37.49, 8.00}, {30.36, -40.91, 8.00}, {24.19, -46.40, 8.00}, - {18.02, -49.14, 8.00}, {6.36, -51.20, 8.00}, {-5.98, -51.20, 8.00}, -}; - +const Eigen::Matrix3f ECAM_INTRINSIC_MATRIX = (Eigen::Matrix3f() << + 567.0, 0.0, 1928.0 / 2, + 0.0, 567.0, 1208.0 / 2, + 0.0, 0.0, 1.0).finished(); typedef enum UIStatus { STATUS_DISENGAGED, @@ -52,54 +44,21 @@ typedef enum UIStatus { STATUS_ENGAGED, } UIStatus; -enum PrimeType { - UNKNOWN = -2, - UNPAIRED = -1, - NONE = 0, - MAGENTA = 1, - LITE = 2, - BLUE = 3, - MAGENTA_NEW = 4, - PURPLE = 5, -}; - const QColor bg_colors [] = { [STATUS_DISENGAGED] = QColor(0x17, 0x33, 0x49, 0xc8), [STATUS_OVERRIDE] = QColor(0x91, 0x9b, 0x95, 0xf1), [STATUS_ENGAGED] = QColor(0x17, 0x86, 0x44, 0xf1), }; - typedef struct UIScene { - bool calibration_valid = false; - bool calibration_wide_valid = false; - bool wide_cam = true; - mat3 view_from_calib = DEFAULT_CALIBRATION; - mat3 view_from_wide_calib = DEFAULT_CALIBRATION; + Eigen::Matrix3f view_from_calib = VIEW_FROM_DEVICE; + Eigen::Matrix3f view_from_wide_calib = VIEW_FROM_DEVICE; cereal::PandaState::PandaType pandaType; - // modelV2 - float lane_line_probs[4]; - float road_edge_stds[2]; - QPolygonF track_vertices; - QPolygonF lane_line_vertices[4]; - QPolygonF road_edge_vertices[2]; - - // lead - QPointF lead_vertices[2]; - - // DMoji state - float driver_pose_vals[3]; - float driver_pose_diff[3]; - float driver_pose_sins[3]; - float driver_pose_coss[3]; - vec3 face_kpts_draw[std::size(default_face_kpts_3d)]; - cereal::LongitudinalPersonality personality; float light_sensor = -1; - bool started, ignition, is_metric, map_on_left, longitudinal_control; - bool world_objects_visible = false; + bool started, ignition, is_metric; uint64_t started_frame; } UIScene; @@ -110,29 +69,18 @@ class UIState : public QObject { UIState(QObject* parent = 0); void updateStatus(); inline bool engaged() const { - return scene.started && (*sm)["controlsState"].getControlsState().getEnabled(); + return scene.started && (*sm)["selfdriveState"].getSelfdriveState().getEnabled(); } - void setPrimeType(PrimeType type); - inline PrimeType primeType() const { return prime_type; } - inline bool hasPrime() const { return prime_type > PrimeType::NONE; } - - int fb_w = 0, fb_h = 0; - std::unique_ptr sm; - UIStatus status; UIScene scene = {}; - QString language; - - QTransform car_space_transform; + PrimeState *prime_state; signals: void uiUpdate(const UIState &s); void offroadTransition(bool offroad); - void primeChanged(bool prime); - void primeTypeChanged(PrimeType prime_type); private slots: void update(); @@ -140,7 +88,6 @@ private slots: private: QTimer *timer; bool started_prev = false; - PrimeType prime_type = PrimeType::UNKNOWN; }; UIState *uiState(); @@ -180,13 +127,4 @@ public slots: }; Device *device(); - void ui_update_params(UIState *s); -int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height); -void update_model(UIState *s, - const cereal::ModelDataV2::Reader &model, - const cereal::UiPlan::Reader &plan); -void update_dmonitoring(UIState *s, const cereal::DriverStateV2::Reader &driverstate, float dm_fade_state, bool is_rhd); -void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line); -void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line, - float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert); diff --git a/selfdrive/ui/ui.py b/selfdrive/ui/ui.py deleted file mode 100755 index 660495b1dec85c1..000000000000000 --- a/selfdrive/ui/ui.py +++ /dev/null @@ -1,77 +0,0 @@ -#!/usr/bin/env python3 -import os -import signal - -signal.signal(signal.SIGINT, signal.SIG_DFL) - -import cereal.messaging as messaging -from openpilot.system.hardware import HARDWARE - -from PyQt5.QtCore import Qt, QTimer -from PyQt5.QtWidgets import QLabel, QWidget, QVBoxLayout, QStackedLayout, QApplication -from openpilot.selfdrive.ui.qt.python_helpers import set_main_window - - -if __name__ == "__main__": - app = QApplication([]) - win = QWidget() - set_main_window(win) - - bg = QLabel("", alignment=Qt.AlignCenter) - - alert1 = QLabel() - alert2 = QLabel() - vlayout = QVBoxLayout() - vlayout.addWidget(alert1, alignment=Qt.AlignCenter) - vlayout.addWidget(alert2, alignment=Qt.AlignCenter) - - tmp = QWidget() - tmp.setLayout(vlayout) - - stack = QStackedLayout(win) - stack.addWidget(tmp) - stack.addWidget(bg) - stack.setStackingMode(QStackedLayout.StackAll) - - win.setObjectName("win") - win.setStyleSheet(""" - #win { - background-color: black; - } - QLabel { - color: white; - font-size: 40px; - } - """) - - sm = messaging.SubMaster(['deviceState', 'controlsState']) - - def update(): - sm.update(0) - - onroad = sm.all_checks(['deviceState']) and sm['deviceState'].started - if onroad: - cs = sm['controlsState'] - color = ("grey" if str(cs.state) in ("overriding", "preEnabled") else "green") if cs.enabled else "blue" - bg.setText("\U0001F44D" if cs.engageable else "\U0001F6D1") - bg.setStyleSheet(f"font-size: 100px; background-color: {color};") - bg.show() - - alert1.setText(cs.alertText1) - alert2.setText(cs.alertText2) - - if not sm.alive['controlsState']: - alert1.setText("waiting for controls...") - else: - bg.hide() - alert1.setText("") - alert2.setText("offroad") - - HARDWARE.set_screen_brightness(100 if onroad else 40) - os.system("echo 0 > /sys/class/backlight/panel0-backlight/bl_power") - - timer = QTimer() - timer.timeout.connect(update) - timer.start(50) - - app.exec_() diff --git a/selfdrive/ui/update_translations.py b/selfdrive/ui/update_translations.py index 0fe0f05ac4abbc2..65880bdad944870 100755 --- a/selfdrive/ui/update_translations.py +++ b/selfdrive/ui/update_translations.py @@ -16,7 +16,7 @@ def generate_translations_include(): # offroad alerts # TODO translate events from openpilot.selfdrive/controls/lib/events.py content = "// THIS IS AN AUTOGENERATED FILE, PLEASE EDIT alerts_offroad.json\n" - with open(os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json")) as f: + with open(os.path.join(BASEDIR, "selfdrive/selfdrived/alerts_offroad.json")) as f: for alert in json.load(f).values(): content += f'QT_TRANSLATE_NOOP("OffroadAlert", R"({alert["text"]})");\n' @@ -25,8 +25,6 @@ def generate_translations_include(): def update_translations(vanish: bool = False, translation_files: None | list[str] = None, translations_dir: str = TRANSLATIONS_DIR): - generate_translations_include() - if translation_files is None: with open(LANGUAGES_FILE) as f: translation_files = json.load(f).values() @@ -48,4 +46,5 @@ def update_translations(vanish: bool = False, translation_files: None | list[str parser.add_argument("--vanish", action="store_true", help="Remove translations with source text no longer found") args = parser.parse_args() + generate_translations_include() update_translations(args.vanish) diff --git a/selfdrive/ui/watch3.cc b/selfdrive/ui/watch3.cc index ec35c29b6b4c55e..258e2a7bd6ff9c5 100644 --- a/selfdrive/ui/watch3.cc +++ b/selfdrive/ui/watch3.cc @@ -19,15 +19,14 @@ int main(int argc, char *argv[]) { { QHBoxLayout *hlayout = new QHBoxLayout(); layout->addLayout(hlayout); - hlayout->addWidget(new CameraWidget("navd", VISION_STREAM_MAP, false)); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_ROAD, false)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_ROAD)); } { QHBoxLayout *hlayout = new QHBoxLayout(); layout->addLayout(hlayout); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_DRIVER, false)); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_WIDE_ROAD, false)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_DRIVER)); + hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_WIDE_ROAD)); } return a.exec(); diff --git a/site_scons/site_tools/cython.py b/site_scons/site_tools/cython.py index c2914755336b405..f11db1d71bebca0 100644 --- a/site_scons/site_tools/cython.py +++ b/site_scons/site_tools/cython.py @@ -2,14 +2,17 @@ import SCons from SCons.Action import Action from SCons.Scanner import Scanner +import numpy as np pyx_from_import_re = re.compile(r'^from\s+(\S+)\s+cimport', re.M) pyx_import_re = re.compile(r'^cimport\s+(\S+)', re.M) cdef_import_re = re.compile(r'^cdef extern from\s+.(\S+).:', re.M) +np_version = SCons.Script.Value(np.__version__) def pyx_scan(node, env, path, arg=None): contents = node.get_text_contents() + env.Depends(str(node).split('.')[0] + env['CYTHONCFILESUFFIX'], np_version) # from cimport ... matches = pyx_from_import_re.findall(contents) diff --git a/system/athena/athenad.py b/system/athena/athenad.py index 9eec7a931b72c96..b5a8f5127fed131 100755 --- a/system/athena/athenad.py +++ b/system/athena/athenad.py @@ -2,7 +2,6 @@ from __future__ import annotations import base64 -import bz2 import hashlib import io import json @@ -15,6 +14,7 @@ import tempfile import threading import time +import zstandard as zstd from dataclasses import asdict, dataclass, replace from datetime import datetime from functools import partial @@ -35,6 +35,7 @@ from openpilot.common.params import Params from openpilot.common.realtime import set_core_affinity from openpilot.system.hardware import HARDWARE, PC +from openpilot.system.loggerd.uploader import LOG_COMPRESSION_LEVEL from openpilot.system.loggerd.xattr_cache import getxattr, setxattr from openpilot.common.swaglog import cloudlog from openpilot.system.version import get_build_metadata @@ -43,7 +44,7 @@ ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) -LOCAL_PORT_WHITELIST = {8022} +LOCAL_PORT_WHITELIST = {22, } # SSH LOG_ATTR_NAME = 'user.upload' LOG_ATTR_VALUE_MAX_UNIX_TIME = int.to_bytes(2147483647, 4, sys.byteorder) @@ -103,8 +104,8 @@ def from_dict(cls, d: dict) -> UploadItem: cur_upload_items: dict[int, UploadItem | None] = {} -def strip_bz2_extension(fn: str) -> str: - if fn.endswith('.bz2'): +def strip_zst_extension(fn: str) -> str: + if fn.endswith('.zst'): return fn[:-4] return fn @@ -283,16 +284,16 @@ def _do_upload(upload_item: UploadItem, callback: Callable = None) -> requests.R path = upload_item.path compress = False - # If file does not exist, but does exist without the .bz2 extension we will compress on the fly - if not os.path.exists(path) and os.path.exists(strip_bz2_extension(path)): - path = strip_bz2_extension(path) + # If file does not exist, but does exist without the .zst extension we will compress on the fly + if not os.path.exists(path) and os.path.exists(strip_zst_extension(path)): + path = strip_zst_extension(path) compress = True with open(path, "rb") as f: content = f.read() if compress: cloudlog.event("athena.upload_handler.compress", fn=path, fn_orig=upload_item.path) - content = bz2.compress(content) + content = zstd.compress(content, LOG_COMPRESSION_LEVEL) with io.BytesIO(content) as data: return requests.put(upload_item.url, @@ -328,19 +329,6 @@ def getVersion() -> dict[str, str]: } -@dispatcher.add_method -def setNavDestination(latitude: int = 0, longitude: int = 0, place_name: str = None, place_details: str = None) -> dict[str, int]: - destination = { - "latitude": latitude, - "longitude": longitude, - "place_name": place_name, - "place_details": place_details, - } - Params().put("NavDestination", json.dumps(destination)) - - return {"success": 1} - - def scan_dir(path: str, prefix: str) -> list[str]: files = [] # only walk directories that match the prefix @@ -388,7 +376,7 @@ def uploadFilesToUrls(files_data: list[UploadFileDict]) -> UploadFilesToUrlRespo continue path = os.path.join(Paths.log_root(), file.fn) - if not os.path.exists(path) and not os.path.exists(strip_bz2_extension(path)): + if not os.path.exists(path) and not os.path.exists(strip_zst_extension(path)): failed.append(file.fn) continue @@ -414,6 +402,7 @@ def uploadFilesToUrls(files_data: list[UploadFileDict]) -> UploadFilesToUrlRespo resp: UploadFilesToUrlResponse = {"enqueued": len(items), "items": items} if failed: + cloudlog.event("athena.uploadFilesToUrls.failed", failed=failed, error=True) resp["failed"] = failed return resp @@ -456,6 +445,10 @@ def setRouteViewed(route: str) -> dict[str, int | str]: def startLocalProxy(global_end_event: threading.Event, remote_ws_uri: str, local_port: int) -> dict[str, int]: try: + # migration, can be removed once 0.9.8 is out for a while + if local_port == 8022: + local_port = 22 + if local_port not in LOCAL_PORT_WHITELIST: raise Exception("Requested local port not whitelisted") diff --git a/system/athena/registration.py b/system/athena/registration.py index 6574d9ac202df34..a1e8605a9d5a0b9 100755 --- a/system/athena/registration.py +++ b/system/athena/registration.py @@ -4,11 +4,11 @@ import jwt from pathlib import Path -from datetime import datetime, timedelta +from datetime import datetime, timedelta, UTC from openpilot.common.api import api_get from openpilot.common.params import Params from openpilot.common.spinner import Spinner -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.hardware import HARDWARE, PC from openpilot.system.hardware.hw import Paths from openpilot.common.swaglog import cloudlog @@ -16,20 +16,32 @@ UNREGISTERED_DONGLE_ID = "UnregisteredDevice" - def is_registered_device() -> bool: dongle = Params().get("DongleId", encoding='utf-8') return dongle not in (None, UNREGISTERED_DONGLE_ID) def register(show_spinner=False) -> str | None: + """ + All devices built since March 2024 come with all + info stored in /persist/. This is kept around + only for devices built before then. + + With a backend update to take serial number instead + of dongle ID to some endpoints, this can be removed + entirely. + """ params = Params() IMEI = params.get("IMEI", encoding='utf8') HardwareSerial = params.get("HardwareSerial", encoding='utf8') dongle_id: str | None = params.get("DongleId", encoding='utf8') - needs_registration = None in (IMEI, HardwareSerial, dongle_id) + if dongle_id is None and Path(Paths.persist_root()+"/comma/dongle_id").is_file(): + # not all devices will have this; added early in comma 3X production (2/28/24) + with open(Paths.persist_root()+"/comma/dongle_id") as f: + dongle_id = f.read().strip() + needs_registration = None in (IMEI, HardwareSerial, dongle_id) pubkey = Path(Paths.persist_root()+"/comma/id_rsa.pub") if not pubkey.is_file(): dongle_id = UNREGISTERED_DONGLE_ID @@ -66,7 +78,7 @@ def register(show_spinner=False) -> str | None: start_time = time.monotonic() while True: try: - register_token = jwt.encode({'register': True, 'exp': datetime.utcnow() + timedelta(hours=1)}, private_key, algorithm='RS256') + register_token = jwt.encode({'register': True, 'exp': datetime.now(UTC).replace(tzinfo=None) + timedelta(hours=1)}, private_key, algorithm='RS256') cloudlog.info("getting pilotauth") resp = api_get("v2/pilotauth/", method='POST', timeout=15, imei=imei1, imei2=imei2, serial=serial, public_key=public_key, register_token=register_token) diff --git a/system/athena/tests/test_athenad.py b/system/athena/tests/test_athenad.py index 48519a0ffd2a0e8..a4dcbef67a7bd51 100644 --- a/system/athena/tests/test_athenad.py +++ b/system/athena/tests/test_athenad.py @@ -29,7 +29,7 @@ def seed_athena_server(host, port): with Timeout(2, 'HTTP Server seeding failed'): while True: try: - requests.put(f'http://{host}:{port}/qlog.bz2', data='', timeout=10) + requests.put(f'http://{host}:{port}/qlog.zst', data='', timeout=10) break except requests.exceptions.ConnectionError: time.sleep(0.1) @@ -174,54 +174,59 @@ def test_list_data_directory(self): assert resp, 'list empty!' assert len(resp) == len(expected) - def test_strip_bz2_extension(self): + def test_strip_extension(self): + # any requested log file with an invalid extension won't return as existing fn = self._create_file('qlog.bz2') if fn.endswith('.bz2'): - assert athenad.strip_bz2_extension(fn) == fn[:-4] + assert athenad.strip_zst_extension(fn) == fn + + fn = self._create_file('qlog.zst') + if fn.endswith('.zst'): + assert athenad.strip_zst_extension(fn) == fn[:-4] @pytest.mark.parametrize("compress", [True, False]) def test_do_upload(self, host, compress): # random bytes to ensure rather large object post-compression fn = self._create_file('qlog', data=os.urandom(10000 * 1024)) - upload_fn = fn + ('.bz2' if compress else '') + upload_fn = fn + ('.zst' if compress else '') item = athenad.UploadItem(path=upload_fn, url="http://localhost:1238", headers={}, created_at=int(time.time()*1000), id='') with pytest.raises(requests.exceptions.ConnectionError): athenad._do_upload(item) - item = athenad.UploadItem(path=upload_fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='') + item = athenad.UploadItem(path=upload_fn, url=f"{host}/qlog.zst", headers={}, created_at=int(time.time()*1000), id='') resp = athenad._do_upload(item) assert resp.status_code == 201 def test_upload_file_to_url(self, host): - fn = self._create_file('qlog.bz2') + fn = self._create_file('qlog.zst') - resp = dispatcher["uploadFileToUrl"]("qlog.bz2", f"{host}/qlog.bz2", {}) + resp = dispatcher["uploadFileToUrl"]("qlog.zst", f"{host}/qlog.zst", {}) assert resp['enqueued'] == 1 assert 'failed' not in resp - assert {"path": fn, "url": f"{host}/qlog.bz2", "headers": {}}.items() <= resp['items'][0].items() + assert {"path": fn, "url": f"{host}/qlog.zst", "headers": {}}.items() <= resp['items'][0].items() assert resp['items'][0].get('id') is not None assert athenad.upload_queue.qsize() == 1 def test_upload_file_to_url_duplicate(self, host): - self._create_file('qlog.bz2') + self._create_file('qlog.zst') - url1 = f"{host}/qlog.bz2?sig=sig1" - dispatcher["uploadFileToUrl"]("qlog.bz2", url1, {}) + url1 = f"{host}/qlog.zst?sig=sig1" + dispatcher["uploadFileToUrl"]("qlog.zst", url1, {}) # Upload same file again, but with different signature - url2 = f"{host}/qlog.bz2?sig=sig2" - resp = dispatcher["uploadFileToUrl"]("qlog.bz2", url2, {}) + url2 = f"{host}/qlog.zst?sig=sig2" + resp = dispatcher["uploadFileToUrl"]("qlog.zst", url2, {}) assert resp == {'enqueued': 0, 'items': []} def test_upload_file_to_url_does_not_exist(self, host): - not_exists_resp = dispatcher["uploadFileToUrl"]("does_not_exist.bz2", "http://localhost:1238", {}) - assert not_exists_resp == {'enqueued': 0, 'items': [], 'failed': ['does_not_exist.bz2']} + not_exists_resp = dispatcher["uploadFileToUrl"]("does_not_exist.zst", "http://localhost:1238", {}) + assert not_exists_resp == {'enqueued': 0, 'items': [], 'failed': ['does_not_exist.zst']} @with_upload_handler def test_upload_handler(self, host): - fn = self._create_file('qlog.bz2') - item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) + fn = self._create_file('qlog.zst') + item = athenad.UploadItem(path=fn, url=f"{host}/qlog.zst", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) athenad.upload_queue.put_nowait(item) self._wait_for_upload() @@ -236,8 +241,8 @@ def test_upload_handler(self, host): def test_upload_handler_retry(self, mocker, host, status, retry): mock_put = mocker.patch('requests.put') mock_put.return_value.status_code = status - fn = self._create_file('qlog.bz2') - item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) + fn = self._create_file('qlog.zst') + item = athenad.UploadItem(path=fn, url=f"{host}/qlog.zst", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) athenad.upload_queue.put_nowait(item) self._wait_for_upload() @@ -251,8 +256,8 @@ def test_upload_handler_retry(self, mocker, host, status, retry): @with_upload_handler def test_upload_handler_timeout(self): """When an upload times out or fails to connect it should be placed back in the queue""" - fn = self._create_file('qlog.bz2') - item = athenad.UploadItem(path=fn, url="http://localhost:44444/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) + fn = self._create_file('qlog.zst') + item = athenad.UploadItem(path=fn, url="http://localhost:44444/qlog.zst", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) item_no_retry = replace(item, retry_count=MAX_RETRY_COUNT) athenad.upload_queue.put_nowait(item_no_retry) @@ -272,7 +277,7 @@ def test_upload_handler_timeout(self): @with_upload_handler def test_cancel_upload(self): - item = athenad.UploadItem(path="qlog.bz2", url="http://localhost:44444/qlog.bz2", headers={}, + item = athenad.UploadItem(path="qlog.zst", url="http://localhost:44444/qlog.zst", headers={}, created_at=int(time.time()*1000), id='id', allow_cellular=True) athenad.upload_queue.put_nowait(item) dispatcher["cancelUpload"](item.id) @@ -291,8 +296,8 @@ def test_cancel_expiry(self): ts = int(t_future.strftime("%s")) * 1000 # Item that would time out if actually uploaded - fn = self._create_file('qlog.bz2') - item = athenad.UploadItem(path=fn, url="http://localhost:44444/qlog.bz2", headers={}, created_at=ts, id='', allow_cellular=True) + fn = self._create_file('qlog.zst') + item = athenad.UploadItem(path=fn, url="http://localhost:44444/qlog.zst", headers={}, created_at=ts, id='', allow_cellular=True) athenad.upload_queue.put_nowait(item) self._wait_for_upload() @@ -306,8 +311,8 @@ def test_list_upload_queue_empty(self): @with_upload_handler def test_list_upload_queue_current(self, host: str): - fn = self._create_file('qlog.bz2') - item = athenad.UploadItem(path=fn, url=f"{host}/qlog.bz2", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) + fn = self._create_file('qlog.zst') + item = athenad.UploadItem(path=fn, url=f"{host}/qlog.zst", headers={}, created_at=int(time.time()*1000), id='', allow_cellular=True) athenad.upload_queue.put_nowait(item) self._wait_for_upload() @@ -317,7 +322,7 @@ def test_list_upload_queue_current(self, host: str): assert items[0]['current'] def test_list_upload_queue(self): - item = athenad.UploadItem(path="qlog.bz2", url="http://localhost:44444/qlog.bz2", headers={}, + item = athenad.UploadItem(path="qlog.zst", url="http://localhost:44444/qlog.zst", headers={}, created_at=int(time.time()*1000), id='id', allow_cellular=True) athenad.upload_queue.put_nowait(item) @@ -337,7 +342,7 @@ def test_upload_queue_persistence(self): athenad.upload_queue.put_nowait(item1) athenad.upload_queue.put_nowait(item2) - # Ensure cancelled items are not persisted + # Ensure canceled items are not persisted athenad.cancelled_uploads.add(item2.id) # serialize item diff --git a/system/athena/tests/test_athenad_ping.py b/system/athena/tests/test_athenad_ping.py index 73fe7783afc8e33..025df7d61445d8f 100644 --- a/system/athena/tests/test_athenad_ping.py +++ b/system/athena/tests/test_athenad_ping.py @@ -65,7 +65,7 @@ def assertTimeout(self, reconnect_time: float, subtests, mocker) -> None: mock_create_connection.assert_called_once() mock_create_connection.reset_mock() - # check normal behaviour, server pings on connection + # check normal behavior, server pings on connection with subtests.test("Wi-Fi: receives ping"), Timeout(70, "no ping received"): while not self._received_ping(): time.sleep(0.1) diff --git a/system/athena/tests/test_registration.py b/system/athena/tests/test_registration.py index 4f663fbc0ad8349..17ebaa472d4f138 100644 --- a/system/athena/tests/test_registration.py +++ b/system/athena/tests/test_registration.py @@ -13,13 +13,13 @@ class TestRegistration: def setup_method(self): # clear params and setup key paths self.params = Params() - self.params.clear_all() persist_dir = Path(Paths.persist_root()) / "comma" persist_dir.mkdir(parents=True, exist_ok=True) self.priv_key = persist_dir / "id_rsa" self.pub_key = persist_dir / "id_rsa.pub" + self.dongle_id = persist_dir / "dongle_id" def _generate_keys(self): self.pub_key.touch() @@ -30,16 +30,20 @@ def _generate_keys(self): f.write(k.publickey().export_key()) def test_valid_cache(self, mocker): - # if all params are written, return the cached dongle id + # if all params are written, return the cached dongle id. + # should work with a dongle ID on either /persist/ or normal params self.params.put("IMEI", "imei") self.params.put("HardwareSerial", "serial") self._generate_keys() - m = mocker.patch("openpilot.system.athena.registration.api_get", autospec=True) dongle = "DONGLE_ID_123" - self.params.put("DongleId", dongle) - assert register() == dongle - assert not m.called + m = mocker.patch("openpilot.system.athena.registration.api_get", autospec=True) + for persist, params in [(True, True), (True, False), (False, True)]: + self.params.put("DongleId", dongle if params else "") + with open(self.dongle_id, "w") as f: + f.write(dongle if persist else "") + assert register() == dongle + assert not m.called def test_no_keys(self, mocker): # missing pubkey diff --git a/system/camerad/SConscript b/system/camerad/SConscript index 511664c275c3f97..46eacf94ef9e08e 100644 --- a/system/camerad/SConscript +++ b/system/camerad/SConscript @@ -1,10 +1,11 @@ Import('env', 'arch', 'messaging', 'common', 'gpucommon', 'visionipc') -libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', messaging, visionipc, gpucommon, 'atomic'] +libs = ['pthread', common, 'jpeg', 'OpenCL', messaging, visionipc, gpucommon] -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 arch != "Darwin": + camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/spectra.cc', + 'cameras/cdm.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/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 9d82284d9f97b82..ff02fe4364ac91e 100644 --- a/system/camerad/cameras/camera_common.cc +++ b/system/camerad/cameras/camera_common.cc @@ -3,41 +3,36 @@ #include #include -#include "third_party/libyuv/include/libyuv.h" #include #include "common/clutil.h" #include "common/swaglog.h" -#include "third_party/linux/include/msm_media_info.h" -#include "system/camerad/cameras/camera_qcom2.h" -#ifdef QCOM2 -#include "CL/cl_ext_qcom.h" -#endif +#include "system/camerad/cameras/spectra.h" -ExitHandler do_exit; class ImgProc { public: - ImgProc(cl_device_id device_id, cl_context context, const CameraBuf *b, const CameraState *s, int buf_width, int uv_offset) { + ImgProc(cl_device_id device_id, cl_context context, const CameraBuf *b, const SensorInfo *sensor, int camera_num, int buf_width, int uv_offset) { char args[4096]; - const SensorInfo *ci = s->ci.get(); snprintf(args, sizeof(args), "-cl-fast-relaxed-math -cl-denorms-are-zero -Isensors " "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d " "-DSENSOR_ID=%hu -DHDR_OFFSET=%d -DVIGNETTING=%d ", - ci->frame_width, ci->frame_height, ci->hdr_offset > 0 ? ci->frame_stride * 2 : ci->frame_stride, ci->frame_offset, - b->rgb_width, b->rgb_height, buf_width, uv_offset, - static_cast(ci->image_sensor), ci->hdr_offset, s->camera_num == 1); + sensor->frame_width, sensor->frame_height, sensor->hdr_offset > 0 ? sensor->frame_stride * 2 : sensor->frame_stride, sensor->frame_offset, + b->out_img_width, b->out_img_height, buf_width, uv_offset, + static_cast(sensor->image_sensor), sensor->hdr_offset, camera_num == 1); const char *cl_file = "cameras/process_raw.cl"; cl_program prg_imgproc = cl_program_from_file(context, device_id, cl_file, args); krnl_ = CL_CHECK_ERR(clCreateKernel(prg_imgproc, "process_raw", &err)); CL_CHECK(clReleaseProgram(prg_imgproc)); + const cl_queue_properties props[] = {0}; //CL_QUEUE_PRIORITY_KHR, CL_QUEUE_PRIORITY_HIGH_KHR, 0}; + queue = CL_CHECK_ERR(clCreateCommandQueueWithProperties(context, device_id, props, &err)); } - void queue(cl_command_queue q, cl_mem cam_buf_cl, cl_mem buf_cl, int width, int height, cl_event *imgproc_event, int expo_time) { + void runKernel(cl_mem cam_buf_cl, cl_mem buf_cl, int width, int height, int expo_time) { CL_CHECK(clSetKernelArg(krnl_, 0, sizeof(cl_mem), &cam_buf_cl)); CL_CHECK(clSetKernelArg(krnl_, 1, sizeof(cl_mem), &buf_cl)); CL_CHECK(clSetKernelArg(krnl_, 2, sizeof(cl_int), &expo_time)); @@ -45,82 +40,82 @@ class ImgProc { const size_t globalWorkSize[] = {size_t(width / 2), size_t(height / 2)}; const int imgproc_local_worksize = 16; const size_t localWorkSize[] = {imgproc_local_worksize, imgproc_local_worksize}; - CL_CHECK(clEnqueueNDRangeKernel(q, krnl_, 2, NULL, globalWorkSize, localWorkSize, 0, 0, imgproc_event)); + + cl_event event; + CL_CHECK(clEnqueueNDRangeKernel(queue, krnl_, 2, NULL, globalWorkSize, localWorkSize, 0, 0, &event)); + clWaitForEvents(1, &event); + CL_CHECK(clReleaseEvent(event)); } ~ImgProc() { CL_CHECK(clReleaseKernel(krnl_)); + CL_CHECK(clReleaseCommandQueue(queue)); } private: cl_kernel krnl_; + cl_command_queue queue; }; -void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType type) { +void CameraBuf::init(cl_device_id device_id, cl_context context, SpectraCamera *cam, VisionIpcServer * v, int frame_cnt, VisionStreamType type) { vipc_server = v; stream_type = type; frame_buf_count = frame_cnt; - 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); - camera_bufs_metadata = std::make_unique(frame_buf_count); + const SensorInfo *sensor = cam->sensor.get(); + + is_raw = cam->is_raw; + camera_bufs_raw = std::make_unique(frame_buf_count); + frame_metadata = std::make_unique(frame_buf_count); + // RAW + final frames from ISP + const int raw_frame_size = (sensor->frame_height + sensor->extra_height) * sensor->frame_stride; for (int i = 0; i < frame_buf_count; i++) { - camera_bufs[i].allocate(frame_size); - camera_bufs[i].init_cl(device_id, context); + camera_bufs_raw[i].allocate(raw_frame_size); + camera_bufs_raw[i].init_cl(device_id, context); } LOGD("allocated %d CL buffers", frame_buf_count); - rgb_width = ci->frame_width; - rgb_height = ci->hdr_offset > 0 ? (ci->frame_height - ci->hdr_offset) / 2 : ci->frame_height; - - int nv12_width = VENUS_Y_STRIDE(COLOR_FMT_NV12, rgb_width); - int nv12_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, rgb_height); - assert(nv12_width == VENUS_UV_STRIDE(COLOR_FMT_NV12, rgb_width)); - assert(nv12_height/2 == VENUS_UV_SCANLINES(COLOR_FMT_NV12, rgb_height)); - size_t nv12_uv_offset = nv12_width * nv12_height; + out_img_width = sensor->frame_width; + out_img_height = sensor->hdr_offset > 0 ? (sensor->frame_height - sensor->hdr_offset) / 2 : sensor->frame_height; // the encoder HW tells us the size it wants after setting it up. // TODO: VENUS_BUFFER_SIZE should give the size, but it's too small. dependent on encoder settings? - size_t nv12_size = (rgb_width >= 2688 ? 2900 : 2346)*nv12_width; - - 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); + size_t nv12_size = (out_img_width <= 1344 ? 2900 : 2346)*cam->stride; - imgproc = new ImgProc(device_id, context, this, s, nv12_width, nv12_uv_offset); + vipc_server->create_buffers_with_sizes(stream_type, YUV_BUFFER_COUNT, out_img_width, out_img_height, nv12_size, cam->stride, cam->uv_offset); + LOGD("created %d YUV vipc buffers with size %dx%d", YUV_BUFFER_COUNT, cam->stride, cam->y_height); - 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)); + imgproc = new ImgProc(device_id, context, this, sensor, cam->cc.camera_num, cam->stride, cam->uv_offset); } CameraBuf::~CameraBuf() { for (int i = 0; i < frame_buf_count; i++) { - camera_bufs[i].free(); + camera_bufs_raw[i].free(); } if (imgproc) delete imgproc; - if (q) CL_CHECK(clReleaseCommandQueue(q)); } -bool CameraBuf::acquire() { +bool CameraBuf::acquire(int expo_time) { if (!safe_queue.try_pop(cur_buf_idx, 50)) return false; - if (camera_bufs_metadata[cur_buf_idx].frame_id == -1) { + if (frame_metadata[cur_buf_idx].frame_id == -1) { LOGE("no frame data? wtf"); return false; } - cur_frame_data = camera_bufs_metadata[cur_buf_idx]; - cur_yuv_buf = vipc_server->get_buffer(stream_type); - cur_camera_buf = &camera_bufs[cur_buf_idx]; + cur_frame_data = frame_metadata[cur_buf_idx]; + cur_camera_buf = &camera_bufs_raw[cur_buf_idx]; + if (is_raw) { + cur_yuv_buf = vipc_server->get_buffer(stream_type); - double start_time = millis_since_boot(); - cl_event event; - imgproc->queue(q, camera_bufs[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, rgb_width, rgb_height, &event, cur_frame_data.integ_lines); - clWaitForEvents(1, &event); - CL_CHECK(clReleaseEvent(event)); - cur_frame_data.processing_time = (millis_since_boot() - start_time) / 1000.0; + double start_time = millis_since_boot(); + imgproc->runKernel(camera_bufs_raw[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, out_img_width, out_img_height, expo_time); + cur_frame_data.processing_time = (millis_since_boot() - start_time) / 1000.0; + } else { + cur_yuv_buf = vipc_server->get_buffer(stream_type, cur_buf_idx); + cur_frame_data.processing_time = (double)(cur_frame_data.timestamp_end_of_isp - cur_frame_data.timestamp_eof)*1e-9; + } VisionIpcBufExtra extra = { cur_frame_data.frame_id, @@ -139,24 +134,6 @@ void CameraBuf::queue(size_t buf_idx) { // common functions -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); - framed.setGain(frame_data.gain); - framed.setHighConversionGain(frame_data.high_conversion_gain); - framed.setMeasuredGreyFraction(frame_data.measured_grey_fraction); - framed.setTargetGreyFraction(frame_data.target_grey_fraction); - 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->ci->min_ev, c->ci->max_ev, 0.0f, 100.0f); - framed.setExposureValPercent(perc); - framed.setSensor(c->ci->image_sensor); -} - kj::Array get_raw_frame_image(const CameraBuf *b) { const uint8_t *dat = (const uint8_t *)b->cur_camera_buf->addr; @@ -174,7 +151,7 @@ static kj::Array yuv420_to_jpeg(const CameraBuf *b, int thumbnail_w int in_stride = b->cur_yuv_buf->stride; // make the buffer big enough. jpeg_write_raw_data requires 16-pixels aligned height to be used. - std::unique_ptr buf(new uint8_t[(thumbnail_width * ((thumbnail_height + 15) & ~15) * 3) / 2]); + std::unique_ptr buf(new uint8_t[(thumbnail_width * ((thumbnail_height + 15) & ~15) * 3) / 2]); uint8_t *y_plane = buf.get(); uint8_t *u_plane = y_plane + thumbnail_width * thumbnail_height; uint8_t *v_plane = u_plane + (thumbnail_width * thumbnail_height) / 4; @@ -244,8 +221,8 @@ static kj::Array yuv420_to_jpeg(const CameraBuf *b, int thumbnail_w return dat; } -static void publish_thumbnail(PubMaster *pm, const CameraBuf *b) { - auto thumbnail = yuv420_to_jpeg(b, b->rgb_width / 4, b->rgb_height / 4); +void publish_thumbnail(PubMaster *pm, const CameraBuf *b) { + auto thumbnail = yuv420_to_jpeg(b, b->out_img_width / 4, b->out_img_height / 4); if (thumbnail.size() == 0) return; MessageBuilder msg; @@ -265,7 +242,7 @@ float set_exposure_target(const CameraBuf *b, Rect ae_xywh, int x_skip, int y_sk unsigned int lum_total = 0; for (int y = ae_xywh.y; y < ae_xywh.y + ae_xywh.h; y += y_skip) { for (int x = ae_xywh.x; x < ae_xywh.x + ae_xywh.w; x += x_skip) { - uint8_t lum = pix_ptr[(y * b->rgb_width) + x]; + uint8_t lum = pix_ptr[(y * b->out_img_width) + x]; lum_binning[lum]++; lum_total += 1; } @@ -284,60 +261,6 @@ float set_exposure_target(const CameraBuf *b, Rect ae_xywh, int x_skip, int y_sk return lum_med / 256.0; } -void *processing_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback) { - const char *thread_name = nullptr; - if (cs == &cameras->road_cam) { - thread_name = "RoadCamera"; - } else if (cs == &cameras->driver_cam) { - thread_name = "DriverCamera"; - } else { - thread_name = "WideRoadCamera"; - } - util::set_thread_name(thread_name); - - uint32_t cnt = 0; - while (!do_exit) { - if (!cs->buf.acquire()) continue; - - callback(cameras, cs, cnt); - - if (cs == &(cameras->road_cam) && cameras->pm && cnt % 100 == 3) { - // this takes 10ms??? - publish_thumbnail(cameras->pm, &(cs->buf)); - } - ++cnt; - } - return NULL; -} - -std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback) { - return std::thread(processing_thread, cameras, cs, callback); -} - -void camerad_thread() { - cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); -#ifdef QCOM2 - const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; - cl_context context = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err)); -#else - cl_context context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); -#endif - - { - MultiCameraState cameras = {}; - VisionIpcServer vipc_server("camerad", device_id, context); - - cameras_open(&cameras); - cameras_init(&vipc_server, &cameras, device_id, context); - - vipc_server.start_listener(); - - cameras_run(&cameras); - } - - CL_CHECK(clReleaseContext(context)); -} - int open_v4l_by_name_and_index(const char name[], int index, int flags) { for (int v4l_index = 0; /**/; ++v4l_index) { std::string v4l_name = util::read_file(util::string_format("/sys/class/video4linux/v4l-subdev%d/name", v4l_index)); diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h index 555362ab8bc7abd..e4cdb27e71e694f 100644 --- a/system/camerad/cameras/camera_common.h +++ b/system/camerad/cameras/camera_common.h @@ -1,88 +1,56 @@ #pragma once -#include #include -#include #include "cereal/messaging/messaging.h" #include "msgq/visionipc/visionipc_server.h" #include "common/queue.h" #include "common/util.h" -const int YUV_BUFFER_COUNT = 20; - -enum CameraType { - RoadCam = 0, - DriverCam, - WideRoadCam -}; -// for debugging -const bool env_disable_road = getenv("DISABLE_ROAD") != NULL; -const bool env_disable_wide_road = getenv("DISABLE_WIDE_ROAD") != NULL; -const bool env_disable_driver = getenv("DISABLE_DRIVER") != NULL; -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; +const int YUV_BUFFER_COUNT = 20; typedef struct FrameMetadata { uint32_t frame_id; uint32_t request_id; - - // Timestamps uint64_t timestamp_sof; uint64_t timestamp_eof; - - // Exposure - unsigned int integ_lines; - bool high_conversion_gain; - float gain; - float measured_grey_fraction; - float target_grey_fraction; - + uint64_t timestamp_end_of_isp; float processing_time; } FrameMetadata; -struct MultiCameraState; +class SpectraCamera; class CameraState; class ImgProc; class CameraBuf { private: - VisionIpcServer *vipc_server; ImgProc *imgproc = nullptr; - VisionStreamType stream_type; int cur_buf_idx; SafeQueue safe_queue; int frame_buf_count; + bool is_raw; public: - cl_command_queue q; + VisionIpcServer *vipc_server; + VisionStreamType stream_type; + FrameMetadata cur_frame_data; VisionBuf *cur_yuv_buf; VisionBuf *cur_camera_buf; - std::unique_ptr camera_bufs; - std::unique_ptr camera_bufs_metadata; - int rgb_width, rgb_height; + std::unique_ptr camera_bufs_raw; + std::unique_ptr frame_metadata; + int out_img_width, out_img_height; CameraBuf() = default; ~CameraBuf(); - void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType type); - bool acquire(); + void init(cl_device_id device_id, cl_context context, SpectraCamera *cam, VisionIpcServer * v, int frame_cnt, VisionStreamType type); + bool acquire(int expo_time); void queue(size_t buf_idx); }; -typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt); - -void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c); +void camerad_thread(); kj::Array get_raw_frame_image(const CameraBuf *b); float set_exposure_target(const CameraBuf *b, Rect ae_xywh, int x_skip, int y_skip); -std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback); - -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx); -void cameras_open(MultiCameraState *s); -void cameras_run(MultiCameraState *s); -void cameras_close(MultiCameraState *s); -void camerad_thread(); - +void publish_thumbnail(PubMaster *pm, const CameraBuf *b); int open_v4l_by_name_and_index(const char name[], int index = 0, int flags = O_RDWR | O_NONBLOCK); diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc index 096e288cc2e4a23..fb325ac77261554 100644 --- a/system/camerad/cameras/camera_qcom2.cc +++ b/system/camerad/cameras/camera_qcom2.cc @@ -1,4 +1,5 @@ -#include "system/camerad/cameras/camera_qcom2.h" +#include "system/camerad/cameras/camera_common.h" +#include "system/camerad/cameras/spectra.h" #include #include @@ -11,397 +12,88 @@ #include #include -#include "media/cam_defs.h" -#include "media/cam_isp.h" -#include "media/cam_isp_ife.h" -#include "media/cam_req_mgr.h" +#ifdef QCOM2 +#include "CL/cl_ext_qcom.h" +#else +#define CL_PRIORITY_HINT_HIGH_QCOM NULL +#define CL_CONTEXT_PRIORITY_HINT_QCOM NULL +#endif + #include "media/cam_sensor_cmn_header.h" -#include "media/cam_sync.h" + +#include "common/clutil.h" +#include "common/params.h" #include "common/swaglog.h" -const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py -// For debugging: -// echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl +ExitHandler do_exit; -extern ExitHandler do_exit; +// for debugging +const bool env_debug_frames = getenv("DEBUG_FRAMES") != nullptr; +const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != nullptr; +const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != nullptr; -int CameraState::clear_req_queue() { - struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; - req_mgr_flush_request.session_hdl = session_handle; - req_mgr_flush_request.link_hdl = link_handle; - req_mgr_flush_request.flush_type = CAM_REQ_MGR_FLUSH_TYPE_ALL; - int ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_FLUSH_REQ, &req_mgr_flush_request, sizeof(req_mgr_flush_request)); - // LOGD("flushed all req: %d", ret); - return ret; -} -// ************** high level camera helpers **************** +class CameraState { +public: + SpectraCamera camera; + std::thread thread; + int exposure_time = 5; + bool dc_gain_enabled = false; + int dc_gain_weight = 0; + int gain_idx = 0; + float analog_gain_frac = 0; -void CameraState::sensors_start() { - if (!enabled) return; - LOGD("starting sensor %d", camera_num); - sensors_i2c(ci->start_reg_array.data(), ci->start_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); -} + float cur_ev[3] = {}; + float best_ev_score = 0; + int new_exp_g = 0; + int new_exp_t = 0; -void CameraState::sensors_poke(int request_id) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet); - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 0; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - pkt->header.op_code = CAM_SENSOR_PACKET_OPCODE_SENSOR_NOP; - pkt->header.request_id = request_id; - - int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); - if (ret != 0) { - LOGE("** sensor %d FAILED poke, disabling", camera_num); - enabled = false; - return; - } -} + Rect ae_xywh = {}; + float measured_grey_fraction = 0; + float target_grey_fraction = 0.3; -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; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 1; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - pkt->header.op_code = op_code; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct i2c_rdwr_header) + len*sizeof(struct i2c_random_wr_payload); - buf_desc[0].type = CAM_CMD_BUF_I2C; - - auto i2c_random_wr = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - i2c_random_wr->header.count = len; - i2c_random_wr->header.op_code = 1; - i2c_random_wr->header.cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR; - i2c_random_wr->header.data_type = data_word ? CAMERA_SENSOR_I2C_TYPE_WORD : CAMERA_SENSOR_I2C_TYPE_BYTE; - i2c_random_wr->header.addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; - memcpy(i2c_random_wr->random_wr_payload, dat, len*sizeof(struct i2c_random_wr_payload)); - - int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); - if (ret != 0) { - LOGE("** sensor %d FAILED i2c, disabling", camera_num); - enabled = false; - return; - } -} - -static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { - cam_cmd_unconditional_wait *unconditional_wait = (cam_cmd_unconditional_wait *)((char *)power + (sizeof(struct cam_cmd_power) + (power->count - 1) * sizeof(struct cam_power_settings))); - unconditional_wait->cmd_type = CAMERA_SENSOR_CMD_TYPE_WAIT; - unconditional_wait->delay = delay_ms; - unconditional_wait->op_code = CAMERA_SENSOR_WAIT_OP_SW_UCND; - return (struct cam_cmd_power *)(unconditional_wait + 1); -} + float fl_pix = 0; -int CameraState::sensors_init() { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = -1; - pkt->header.op_code = 0x1000000 | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE; - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); - buf_desc[0].type = CAM_CMD_BUF_LEGACY; - auto i2c_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - auto probe = (struct cam_cmd_probe *)(i2c_info.get() + 1); - - probe->camera_id = camera_num; - 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; - i2c_info->cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_INFO; - - probe->data_type = CAMERA_SENSOR_I2C_TYPE_WORD; - probe->addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; - probe->op_code = 3; // don't care? - probe->cmd_type = CAMERA_SENSOR_CMD_TYPE_PROBE; - 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); - - // power on - struct cam_cmd_power *power = power_settings.get(); - power->count = 4; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 3; // clock?? - power->power_settings[1].power_seq_type = 1; // analog - power->power_settings[2].power_seq_type = 2; // digital - power->power_settings[3].power_seq_type = 8; // reset low - power = power_set_wait(power, 1); - - // set clock - 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 = ci->mclk_frequency; - power = power_set_wait(power, 1); - - // reset high - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 1; - // wait 650000 cycles @ 19.2 mhz = 33.8 ms - power = power_set_wait(power, 34); - - // probe happens here - - // disable clock - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = 0; - power = power_set_wait(power, 1); - - // reset high - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 1; - power = power_set_wait(power, 1); - - // reset low - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 0; - power = power_set_wait(power, 1); - - // power off - power->count = 3; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 2; - power->power_settings[1].power_seq_type = 1; - power->power_settings[2].power_seq_type = 3; - - int ret = do_cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); - LOGD("probing the sensor: %d", ret); - return ret; -} + CameraState(SpectraMaster *master, const CameraConfig &config) : camera(master, config, true /*config.stream_type == VISION_STREAM_ROAD*/) {}; + ~CameraState(); + void init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); + void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain); + void set_camera_exposure(float grey_frac); + void set_exposure_rect(); + void run(); -void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; - if (io_mem_handle != 0) { - size += sizeof(struct cam_buf_io_cfg); - } - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = 0; - // YUV has kmd_cmd_buf_offset = 1780 - // I guess this is the ISP command - // YUV also has patch_offset = 0x1030 and num_patches = 10 - - if (io_mem_handle != 0) { - pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf; - pkt->num_io_configs = 1; + float get_gain_factor() const { + return (1 + dc_gain_weight * (camera.sensor->dc_gain_factor-1) / camera.sensor->dc_gain_max_weight); } +}; - if (io_mem_handle != 0) { - pkt->header.op_code = 0xf000001; - pkt->header.request_id = request_id; - } else { - pkt->header.op_code = 0xf000000; - } - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); - - // TODO: support MMU - buf_desc[0].size = 65624; - buf_desc[0].length = 0; - buf_desc[0].type = CAM_CMD_BUF_DIRECT; - buf_desc[0].meta_data = 3; - buf_desc[0].mem_handle = buf0_mem_handle; - buf_desc[0].offset = buf0_offset; - - // parsed by cam_isp_packet_generic_blob_handler - struct isp_packet { - uint32_t type_0; - cam_isp_resource_hfr_config resource_hfr; - - uint32_t type_1; - cam_isp_clock_config clock; - uint64_t extra_rdi_hz[3]; - - uint32_t type_2; - cam_isp_bw_config bw; - struct cam_isp_bw_vote extra_rdi_vote[6]; - } __attribute__((packed)) tmp; - memset(&tmp, 0, sizeof(tmp)); - - tmp.type_0 = CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG; - tmp.type_0 |= sizeof(cam_isp_resource_hfr_config) << 8; - static_assert(sizeof(cam_isp_resource_hfr_config) == 0x20); - tmp.resource_hfr = { - .num_ports = 1, // 10 for YUV (but I don't think we need them) - .port_hfr_config[0] = { - .resource_type = CAM_ISP_IFE_OUT_RES_RDI_0, // CAM_ISP_IFE_OUT_RES_FULL for YUV - .subsample_pattern = 1, - .subsample_period = 0, - .framedrop_pattern = 1, - .framedrop_period = 0, - }}; - - tmp.type_1 = CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG; - tmp.type_1 |= (sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) << 8; - static_assert((sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) == 0x38); - tmp.clock = { - .usage_type = 1, // dual mode - .num_rdi = 4, - .left_pix_hz = 404000000, - .right_pix_hz = 404000000, - .rdi_hz[0] = 404000000, - }; - - - tmp.type_2 = CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG; - tmp.type_2 |= (sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) << 8; - static_assert((sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) == 0xe0); - tmp.bw = { - .usage_type = 1, // dual mode - .num_rdi = 4, - .left_pix_vote = { - .resource_id = 0, - .cam_bw_bps = 450000000, - .ext_bw_bps = 450000000, - }, - .rdi_vote[0] = { - .resource_id = 0, - .cam_bw_bps = 8706200000, - .ext_bw_bps = 8706200000, - }, - }; - - static_assert(offsetof(struct isp_packet, type_2) == 0x60); - - buf_desc[1].size = sizeof(tmp); - buf_desc[1].offset = io_mem_handle != 0 ? 0x60 : 0; - buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset; - buf_desc[1].type = CAM_CMD_BUF_GENERIC; - buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; - auto buf2 = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); - memcpy(buf2.get(), &tmp, sizeof(tmp)); - - 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, - .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) - .meta_size = 0x0, - .meta_offset = 0x0, - .packer_config = 0x0, // 0xb for YUV - .mode_config = 0x0, // 0x9ef for YUV - .tile_config = 0x0, - .h_init = 0x0, - .v_init = 0x0, - }; - 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 = (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; - io_cfg[0].subsample_pattern = 0x1; - io_cfg[0].framedrop_pattern = 0x1; - } - - int ret = device_config(multi_cam_state->isp_fd, session_handle, isp_dev_handle, cam_packet_handle); - assert(ret == 0); - if (ret != 0) { - LOGE("isp config failed"); - } -} - -void CameraState::enqueue_buffer(int i, bool dp) { - int ret; - int request_id = request_ids[i]; - - if (buf_handle[i] && sync_objs[i]) { - // wait - struct cam_sync_wait sync_wait = {0}; - sync_wait.sync_obj = sync_objs[i]; - sync_wait.timeout_ms = 50; // max dt tolerance, typical should be 23 - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_WAIT, &sync_wait, sizeof(sync_wait)); - if (ret != 0) { - LOGE("failed to wait for sync: %d %d", ret, sync_wait.sync_obj); - // TODO: handle frame drop cleanly - } +void CameraState::init(VisionIpcServer *v, cl_device_id device_id, cl_context ctx) { + if (!camera.enabled) return; - buf.camera_bufs_metadata[i].timestamp_eof = (uint64_t)nanos_since_boot(); // set true eof - if (dp) buf.queue(i); + camera.camera_open(v, device_id, ctx); - // destroy old output fence - struct cam_sync_info sync_destroy = {0}; - sync_destroy.sync_obj = sync_objs[i]; - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_DESTROY, &sync_destroy, sizeof(sync_destroy)); - if (ret != 0) { - LOGE("failed to destroy sync object: %d %d", ret, sync_destroy.sync_obj); - } - } - - // create output fence - struct cam_sync_info sync_create = {0}; - strcpy(sync_create.name, "NodeOutputPortFence"); - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create)); - if (ret != 0) { - LOGE("failed to create fence: %d %d", ret, sync_create.sync_obj); - } - sync_objs[i] = sync_create.sync_obj; - - // schedule request with camera request manager - struct cam_req_mgr_sched_request req_mgr_sched_request = {0}; - req_mgr_sched_request.session_hdl = session_handle; - req_mgr_sched_request.link_hdl = link_handle; - req_mgr_sched_request.req_id = request_id; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_SCHED_REQ, &req_mgr_sched_request, sizeof(req_mgr_sched_request)); - if (ret != 0) { - LOGE("failed to schedule cam mgr request: %d %d", ret, request_id); - } + fl_pix = camera.cc.focal_len / camera.sensor->pixel_size_mm; + set_exposure_rect(); - // poke sensor, must happen after schedule - sensors_poke(request_id); + dc_gain_weight = camera.sensor->dc_gain_min_weight; + gain_idx = camera.sensor->analog_gain_rec_idx; + cur_ev[0] = cur_ev[1] = cur_ev[2] = get_gain_factor() * camera.sensor->sensor_analog_gains[gain_idx] * exposure_time; - // submit request to the ife - config_isp(buf_handle[i], sync_objs[i], request_id, buf0_handle, 65632*(i+1)); + thread = std::thread(&CameraState::run, this); } -void CameraState::enqueue_req_multi(int start, int n, bool dp) { - for (int i=start; i> ae_targets = { // (Rect, F) - std::make_pair((Rect){96, 250, 1734, 524}, 567.0), // wide + std::make_pair((Rect){96, 250, 1734, 524}, 567.0), // wide std::make_pair((Rect){96, 160, 1734, 986}, 2648.0), // road - std::make_pair((Rect){96, 242, 1736, 906}, 567.0) // driver + std::make_pair((Rect){96, 242, 1736, 906}, 567.0) // driver }; int h_ref = 1208; /* @@ -412,412 +104,20 @@ void CameraState::set_exposure_rect() { [0, 0, 1] ] */ - auto ae_target = ae_targets[camera_num]; + auto ae_target = ae_targets[camera.cc.camera_num]; Rect xywh_ref = ae_target.first; float fl_ref = ae_target.second; ae_xywh = (Rect){ - std::max(0, buf.rgb_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::max(0, buf.rgb_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), - std::min((int)(fl_pix / fl_ref * xywh_ref.w), buf.rgb_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), - std::min((int)(fl_pix / fl_ref * xywh_ref.h), buf.rgb_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) - }; -} - -void CameraState::sensor_set_parameters() { - target_grey_fraction = 0.3; - - dc_gain_enabled = false; - 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 * (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) { - for (int i = 0; i < FRAME_BUF_COUNT; i++) { - // configure ISP to put the image in place - struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0}; - mem_mgr_map_cmd.mmu_hdls[0] = s->device_iommu; - mem_mgr_map_cmd.num_hdl = 1; - mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE; - mem_mgr_map_cmd.fd = buf.camera_bufs[i].fd; - int ret = do_cam_control(s->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); - LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret); - buf_handle[i] = mem_mgr_map_cmd.out.buf_handle; - } - enqueue_req_multi(1, FRAME_BUF_COUNT, 0); -} - -void CameraState::camera_init(MultiCameraState *s, VisionIpcServer * v, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type, float focal_len) { - if (!enabled) return; - - LOGD("camera init %d", camera_num); - request_id_last = 0; - skipped = true; - - buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, yuv_type); - camera_map_bufs(s); - - fl_pix = focal_len / ci->pixel_size_mm; - set_exposure_rect(); -} - -void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num_, bool enabled_) { - multi_cam_state = multi_cam_state_; - camera_num = camera_num_; - enabled = enabled_; - if (!enabled) return; - - sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", camera_num); - assert(sensor_fd >= 0); - LOGD("opened sensor for %d", camera_num); - - // init memorymanager for this camera - mm.init(multi_cam_state->video0_fd); - - LOGD("-- Probing sensor %d", camera_num); - - auto init_sensor_lambda = [this](SensorInfo *sensor) { - ci.reset(sensor); - int ret = sensors_init(); - if (ret == 0) { - sensor_set_parameters(); - } - return ret == 0; + std::max(0, camera.buf.out_img_width / 2 - (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::max(0, camera.buf.out_img_height / 2 - (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))), + std::min((int)(fl_pix / fl_ref * xywh_ref.w), camera.buf.out_img_width / 2 + (int)(fl_pix / fl_ref * xywh_ref.w / 2)), + std::min((int)(fl_pix / fl_ref * xywh_ref.h), camera.buf.out_img_height / 2 + (int)(fl_pix / fl_ref * (h_ref / 2 - xywh_ref.y))) }; - - // 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 = {}; - int ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &session_info, sizeof(session_info)); - LOGD("get session: %d 0x%X", ret, session_info.session_hdl); - session_handle = session_info.session_hdl; - - // access the sensor - LOGD("-- Accessing sensor"); - auto sensor_dev_handle_ = device_acquire(sensor_fd, session_handle, nullptr); - assert(sensor_dev_handle_); - sensor_dev_handle = *sensor_dev_handle_; - LOGD("acquire sensor dev"); - - LOG("-- Configuring sensor"); - 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 = 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), - }; - - auto isp_dev_handle_ = device_acquire(multi_cam_state->isp_fd, session_handle, &isp_resource); - assert(isp_dev_handle_); - isp_dev_handle = *isp_dev_handle_; - LOGD("acquire isp dev"); - - csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", camera_num); - assert(csiphy_fd >= 0); - LOGD("opened csiphy for %d", camera_num); - - struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {.combo_mode = 0}; - auto csiphy_dev_handle_ = device_acquire(csiphy_fd, session_handle, &csiphy_acquire_dev_info); - assert(csiphy_dev_handle_); - csiphy_dev_handle = *csiphy_dev_handle_; - LOGD("acquire csiphy dev"); - - // config ISP - alloc_w_mmu_hdl(multi_cam_state->video0_fd, 984480, (uint32_t*)&buf0_handle, 0x20, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | - CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, multi_cam_state->device_iommu, multi_cam_state->cdm_iommu); - config_isp(0, 0, 1, buf0_handle, 0); - - // config csiphy - LOG("-- Config CSI PHY"); - { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 1; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info); - buf_desc[0].type = CAM_CMD_BUF_GENERIC; - - auto csiphy_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - csiphy_info->lane_mask = 0x1f; - csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels?? - csiphy_info->csiphy_3phase = 0x0; // no 3 phase, only 2 conductors per lane - csiphy_info->combo_mode = 0x0; - csiphy_info->lane_cnt = 0x4; - csiphy_info->secure_mode = 0x0; - csiphy_info->settle_time = MIPI_SETTLE_CNT * 200000000ULL; - csiphy_info->data_rate = 48000000; // Calculated by camera_freqs.py - - int ret_ = device_config(csiphy_fd, session_handle, csiphy_dev_handle, cam_packet_handle); - assert(ret_ == 0); - } - - // link devices - LOG("-- Link devices"); - struct cam_req_mgr_link_info req_mgr_link_info = {0}; - req_mgr_link_info.session_hdl = session_handle; - req_mgr_link_info.num_devices = 2; - req_mgr_link_info.dev_hdls[0] = isp_dev_handle; - req_mgr_link_info.dev_hdls[1] = sensor_dev_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK, &req_mgr_link_info, sizeof(req_mgr_link_info)); - link_handle = req_mgr_link_info.link_hdl; - LOGD("link: %d session: 0x%X isp: 0x%X sensors: 0x%X link: 0x%X", ret, session_handle, isp_dev_handle, sensor_dev_handle, link_handle); - - struct cam_req_mgr_link_control req_mgr_link_control = {0}; - req_mgr_link_control.ops = CAM_REQ_MGR_LINK_ACTIVATE; - req_mgr_link_control.session_hdl = session_handle; - req_mgr_link_control.num_links = 1; - req_mgr_link_control.link_hdls[0] = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); - LOGD("link control: %d", ret); - - ret = device_control(csiphy_fd, CAM_START_DEV, session_handle, csiphy_dev_handle); - 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); - //LOGD("start sensor: %d", ret); -} - -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { - s->driver_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_DRIVER, DRIVER_FL_MM); - s->road_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_ROAD, ROAD_FL_MM); - s->wide_road_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_WIDE_ROAD, WIDE_FL_MM); - - s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); -} - -void cameras_open(MultiCameraState *s) { - LOG("-- Opening devices"); - // video0 is req_mgr, the target of many ioctls - s->video0_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK)); - assert(s->video0_fd >= 0); - LOGD("opened video0"); - - // video1 is cam_sync, the target of some ioctls - s->cam_sync_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK)); - assert(s->cam_sync_fd >= 0); - LOGD("opened video1 (cam_sync)"); - - // looks like there's only one of these - s->isp_fd = open_v4l_by_name_and_index("cam-isp"); - assert(s->isp_fd >= 0); - LOGD("opened isp"); - - // query icp for MMU handles - LOG("-- Query ICP for MMU handles"); - struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0}; - struct cam_query_cap_cmd query_cap_cmd = {0}; - query_cap_cmd.handle_type = 1; - query_cap_cmd.caps_handle = (uint64_t)&isp_query_cap_cmd; - query_cap_cmd.size = sizeof(isp_query_cap_cmd); - int ret = do_cam_control(s->isp_fd, CAM_QUERY_CAP, &query_cap_cmd, sizeof(query_cap_cmd)); - assert(ret == 0); - LOGD("using MMU handle: %x", isp_query_cap_cmd.device_iommu.non_secure); - LOGD("using MMU handle: %x", isp_query_cap_cmd.cdm_iommu.non_secure); - s->device_iommu = isp_query_cap_cmd.device_iommu.non_secure; - s->cdm_iommu = isp_query_cap_cmd.cdm_iommu.non_secure; - - // subscribe - LOG("-- Subscribing"); - struct v4l2_event_subscription sub = {0}; - sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT; - sub.id = V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS; - ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); - LOGD("req mgr subscribe: %d", ret); - - s->driver_cam.camera_open(s, 2, !env_disable_driver); - LOGD("driver camera opened"); - s->road_cam.camera_open(s, 1, !env_disable_road); - LOGD("road camera opened"); - s->wide_road_cam.camera_open(s, 0, !env_disable_wide_road); - LOGD("wide road camera opened"); -} - -void CameraState::camera_close() { - // stop devices - LOG("-- Stop devices %d", camera_num); - - if (enabled) { - // ret = device_control(sensor_fd, CAM_STOP_DEV, session_handle, sensor_dev_handle); - // LOGD("stop sensor: %d", ret); - int ret = device_control(multi_cam_state->isp_fd, CAM_STOP_DEV, session_handle, isp_dev_handle); - LOGD("stop isp: %d", ret); - ret = device_control(csiphy_fd, CAM_STOP_DEV, session_handle, csiphy_dev_handle); - LOGD("stop csiphy: %d", ret); - // link control stop - LOG("-- Stop link control"); - struct cam_req_mgr_link_control req_mgr_link_control = {0}; - req_mgr_link_control.ops = CAM_REQ_MGR_LINK_DEACTIVATE; - req_mgr_link_control.session_hdl = session_handle; - req_mgr_link_control.num_links = 1; - req_mgr_link_control.link_hdls[0] = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); - LOGD("link control stop: %d", ret); - - // unlink - LOG("-- Unlink"); - struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0}; - req_mgr_unlink_info.session_hdl = session_handle; - req_mgr_unlink_info.link_hdl = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_UNLINK, &req_mgr_unlink_info, sizeof(req_mgr_unlink_info)); - LOGD("unlink: %d", ret); - - // release devices - LOGD("-- Release devices"); - ret = device_control(multi_cam_state->isp_fd, CAM_RELEASE_DEV, session_handle, isp_dev_handle); - LOGD("release isp: %d", ret); - ret = device_control(csiphy_fd, CAM_RELEASE_DEV, session_handle, csiphy_dev_handle); - LOGD("release csiphy: %d", ret); - - for (int i = 0; i < FRAME_BUF_COUNT; i++) { - release(multi_cam_state->video0_fd, buf_handle[i]); - } - LOGD("released buffers"); - } - - int ret = device_control(sensor_fd, CAM_RELEASE_DEV, session_handle, sensor_dev_handle); - LOGD("release sensor: %d", ret); - - // destroyed session - struct cam_req_mgr_session_info session_info = {.session_hdl = session_handle}; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &session_info, sizeof(session_info)); - LOGD("destroyed session %d: %d", camera_num, ret); -} - -void cameras_close(MultiCameraState *s) { - s->driver_cam.camera_close(); - s->road_cam.camera_close(); - s->wide_road_cam.camera_close(); - - delete s->pm; -} - -void CameraState::handle_camera_event(void *evdat) { - if (!enabled) return; - struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)evdat; - assert(event_data->session_hdl == session_handle); - assert(event_data->u.frame_msg.link_hdl == link_handle); - - uint64_t timestamp = event_data->u.frame_msg.timestamp; - int main_id = event_data->u.frame_msg.frame_id; - int real_id = event_data->u.frame_msg.request_id; - - if (real_id != 0) { // next ready - if (real_id == 1) {idx_offset = main_id;} - int buf_idx = (real_id - 1) % FRAME_BUF_COUNT; - - // check for skipped frames - if (main_id > frame_id_last + 1 && !skipped) { - LOGE("camera %d realign", camera_num); - clear_req_queue(); - enqueue_req_multi(real_id + 1, FRAME_BUF_COUNT - 1, 0); - skipped = true; - } else if (main_id == frame_id_last + 1) { - skipped = false; - } - - // check for dropped requests - if (real_id > request_id_last + 1) { - LOGE("camera %d dropped requests %d %d", camera_num, real_id, request_id_last); - enqueue_req_multi(request_id_last + 1 + FRAME_BUF_COUNT, real_id - (request_id_last + 1), 0); - } - - // metas - frame_id_last = main_id; - request_id_last = real_id; - - 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 * (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; - meta_data.target_grey_fraction = target_grey_fraction; - exp_lock.unlock(); - - // dispatch - enqueue_req_multi(real_id + FRAME_BUF_COUNT, 1, 1); - } else { // not ready - if (main_id > frame_id_last + 10) { - LOGE("camera %d reset after half second of no response", camera_num); - clear_req_queue(); - enqueue_req_multi(request_id_last + 1, FRAME_BUF_COUNT, 0); - frame_id_last = main_id; - skipped = true; - } - } } void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain) { - float score = ci->getExposureScore(desired_ev, exp_t, exp_g_idx, exp_gain, gain_idx); + float score = camera.sensor->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; @@ -826,7 +126,7 @@ void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_i } void CameraState::set_camera_exposure(float grey_frac) { - if (!enabled) return; + if (!camera.enabled) return; const float dt = 0.05; const float ts_grey = 10.0; @@ -840,13 +140,14 @@ void CameraState::set_camera_exposure(float grey_frac) { // Therefore we use the target EV from 3 frames ago, the grey fraction that was just measured was the result of that control action. // TODO: Lower latency to 2 frames, by using the histogram outputted by the sensor we can do AE before the debayering is complete - const float cur_ev_ = cur_ev[buf.cur_frame_data.frame_id % 3]; + const float cur_ev_ = cur_ev[camera.buf.cur_frame_data.frame_id % 3]; + const auto &sensor = camera.sensor; // 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 + ci->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 + sensor->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, ci->min_ev, ci->max_ev); + float desired_ev = std::clamp(cur_ev_ * target_grey / grey_frac, sensor->min_ev, sensor->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); @@ -857,19 +158,20 @@ 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 < ci->dc_gain_on_grey) { + if (!enable_dc_gain && target_grey < sensor->dc_gain_on_grey) { enable_dc_gain = true; - dc_gain_weight = ci->dc_gain_min_weight; - } else if (enable_dc_gain && target_grey > ci->dc_gain_off_grey) { + dc_gain_weight = sensor->dc_gain_min_weight; + } else if (enable_dc_gain && target_grey > sensor->dc_gain_off_grey) { enable_dc_gain = false; - dc_gain_weight = ci->dc_gain_max_weight; + dc_gain_weight = sensor->dc_gain_max_weight; } - 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;} + if (enable_dc_gain && dc_gain_weight < sensor->dc_gain_max_weight) {dc_gain_weight += 1;} + if (!enable_dc_gain && dc_gain_weight > sensor->dc_gain_min_weight) {dc_gain_weight -= 1;} std::string gain_bytes, time_bytes; if (env_ctrl_exp_from_params) { + static Params params; gain_bytes = params.get("CameraDebugExpGain"); time_bytes = params.get("CameraDebugExpTime"); } @@ -883,16 +185,17 @@ void CameraState::set_camera_exposure(float grey_frac) { new_exp_t = exposure_time; enable_dc_gain = false; } else { - // Simple brute force optimizer to choose sensor parameters - // to reach desired EV - 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); + // Simple brute force optimizer to choose sensor parameters to reach desired EV + int min_g = std::max(gain_idx - 1, sensor->analog_gain_min_idx); + int max_g = std::min(gain_idx + 1, sensor->analog_gain_max_idx); + for (int g = min_g; g <= max_g; g++) { + float gain = sensor->sensor_analog_gains[g] * get_gain_factor(); // Compute optimal time for given gain - int t = std::clamp(int(std::round(desired_ev / gain)), ci->exposure_time_min, ci->exposure_time_max); + int t = std::clamp(int(std::round(desired_ev / gain)), sensor->exposure_time_min, sensor->exposure_time_max); // Only go below recommended gain when absolutely necessary to not overexpose - if (g < ci->analog_gain_rec_idx && t > 20 && g < gain_idx) { + if (g < sensor->analog_gain_rec_idx && t > 20 && g < gain_idx) { continue; } @@ -900,84 +203,109 @@ void CameraState::set_camera_exposure(float grey_frac) { } } - exp_lock.lock(); - measured_grey_fraction = grey_frac; target_grey_fraction = target_grey; - analog_gain_frac = ci->sensor_analog_gains[new_exp_g]; + analog_gain_frac = sensor->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 * (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(); + float gain = analog_gain_frac * get_gain_factor(); + cur_ev[camera.buf.cur_frame_data.frame_id % 3] = exposure_time * gain; // Processing a frame takes right about 50ms, so we need to wait a few ms // so we don't send i2c commands around the frame start. - int ms = (nanos_since_boot() - buf.cur_frame_data.timestamp_sof) / 1000000; + int ms = (nanos_since_boot() - camera.buf.cur_frame_data.timestamp_sof) / 1000000; if (ms < 60) { util::sleep_for(60 - ms); } - // 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)); + // LOGE("ae - camera %d, cur_t %.5f, sof %.5f, dt %.5f", camera.cc.camera_num, 1e-9 * nanos_since_boot(), 1e-9 * camera.buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - camera.buf.cur_frame_data.timestamp_sof)); - 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); + auto exp_reg_array = sensor->getExposureRegisters(exposure_time, new_exp_g, dc_gain_enabled); + camera.sensors_i2c(exp_reg_array.data(), exp_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, camera.sensor->data_word); } -static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { - c->set_camera_exposure(set_exposure_target(&c->buf, c->ae_xywh, 2, 4)); +void CameraState::run() { + util::set_thread_name(camera.cc.publish_name); + + std::vector pubs = {camera.cc.publish_name}; + if (camera.cc.stream_type == VISION_STREAM_ROAD) pubs.push_back("thumbnail"); + PubMaster pm(pubs); + + for (uint32_t cnt = 0; !do_exit; ++cnt) { + // Acquire the buffer; continue if acquisition fails + if (!camera.buf.acquire(exposure_time)) continue; + + MessageBuilder msg; + auto framed = (msg.initEvent().*camera.cc.init_camera_state)(); + const FrameMetadata &meta = camera.buf.cur_frame_data; + framed.setFrameId(meta.frame_id); + framed.setRequestId(meta.request_id); + framed.setTimestampEof(meta.timestamp_eof); + framed.setTimestampSof(meta.timestamp_sof); + framed.setIntegLines(exposure_time); + framed.setGain(analog_gain_frac * get_gain_factor()); + framed.setHighConversionGain(dc_gain_enabled); + framed.setMeasuredGreyFraction(measured_grey_fraction); + framed.setTargetGreyFraction(target_grey_fraction); + framed.setProcessingTime(meta.processing_time); + + const float ev = cur_ev[meta.frame_id % 3]; + const float perc = util::map_val(ev, camera.sensor->min_ev, camera.sensor->max_ev, 0.0f, 100.0f); + framed.setExposureValPercent(perc); + framed.setSensor(camera.sensor->image_sensor); + + // Log raw frames for road camera + if (env_log_raw_frames && camera.cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 5) { // no overlap with qlog decimation + framed.setImage(get_raw_frame_image(&camera.buf)); + } - MessageBuilder msg; - auto framed = msg.initEvent().initDriverCameraState(); - framed.setFrameType(cereal::FrameData::FrameType::FRONT); - fill_frame_data(framed, c->buf.cur_frame_data, c); + // Process camera registers and set camera exposure + if (camera.is_raw) { + camera.sensor->processRegisters((uint8_t *)camera.buf.cur_camera_buf->addr, framed); + } + set_camera_exposure(set_exposure_target(&camera.buf, ae_xywh, 2, camera.cc.stream_type != VISION_STREAM_DRIVER ? 2 : 4)); - c->ci->processRegisters(c, framed); - s->pm->send("driverCameraState", msg); + // Send the message + pm.send(camera.cc.publish_name, msg); + if (camera.cc.stream_type == VISION_STREAM_ROAD && cnt % 100 == 3) { + publish_thumbnail(&pm, &camera.buf); // this takes 10ms??? + } + } } -void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { - const CameraBuf *b = &c->buf; +void camerad_thread() { + // TODO: centralize enabled handling - MessageBuilder msg; - auto framed = c == &s->road_cam ? msg.initEvent().initRoadCameraState() : msg.initEvent().initWideRoadCameraState(); - fill_frame_data(framed, b->cur_frame_data, c); - if (env_log_raw_frames && c == &s->road_cam && cnt % 100 == 5) { // no overlap with qlog decimation - framed.setImage(get_raw_frame_image(b)); - } - LOGT(c->buf.cur_frame_data.frame_id, "%s: Image set", c == &s->road_cam ? "RoadCamera" : "WideRoadCamera"); + cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); + const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; + cl_context ctx = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err)); - c->ci->processRegisters(c, framed); - s->pm->send(c == &s->road_cam ? "roadCameraState" : "wideRoadCameraState", msg); + VisionIpcServer v("camerad", device_id, ctx); - const int skip = 2; - c->set_camera_exposure(set_exposure_target(b, c->ae_xywh, skip, skip)); -} + // *** initial ISP init *** + SpectraMaster m; + m.init(); + + // *** per-cam init *** + std::vector> cams; + for (const auto &config : {WIDE_ROAD_CAMERA_CONFIG, DRIVER_CAMERA_CONFIG, ROAD_CAMERA_CONFIG}) { + auto cam = std::make_unique(&m, config); + cam->init(&v, device_id, ctx); + cams.emplace_back(std::move(cam)); + } -void cameras_run(MultiCameraState *s) { - LOG("-- Starting threads"); - std::vector threads; - if (s->driver_cam.enabled) threads.push_back(start_process_thread(s, &s->driver_cam, process_driver_camera)); - if (s->road_cam.enabled) threads.push_back(start_process_thread(s, &s->road_cam, process_road_camera)); - if (s->wide_road_cam.enabled) threads.push_back(start_process_thread(s, &s->wide_road_cam, process_road_camera)); + v.start_listener(); // start devices LOG("-- Starting devices"); - s->driver_cam.sensors_start(); - s->road_cam.sensors_start(); - s->wide_road_cam.sensors_start(); + for (auto &cam : cams) cam->camera.sensors_start(); // poll events LOG("-- Dequeueing Video events"); while (!do_exit) { - struct pollfd fds[1] = {{0}}; - - fds[0].fd = s->video0_fd; - fds[0].events = POLLPRI; - + struct pollfd fds[1] = {{.fd = m.video0_fd, .events = POLLPRI}}; int ret = poll(fds, std::size(fds), 1000); if (ret < 0) { if (errno == EINTR || errno == EAGAIN) continue; @@ -985,7 +313,7 @@ void cameras_run(MultiCameraState *s) { break; } - if (!fds[0].revents) continue; + if (!(fds[0].revents & POLLPRI)) continue; struct v4l2_event ev = {0}; ret = HANDLE_EINTR(ioctl(fds[0].fd, VIDIOC_DQEVENT, &ev)); @@ -995,20 +323,14 @@ void cameras_run(MultiCameraState *s) { if (env_debug_frames) { printf("sess_hdl 0x%6X, link_hdl 0x%6X, frame_id %lu, req_id %lu, timestamp %.2f ms, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, 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); + do_exit = do_exit || event_data->u.frame_msg.frame_id > (1*20); } - // 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) { - s->wide_road_cam.handle_camera_event(event_data); - } else if (event_data->session_hdl == s->driver_cam.session_handle) { - s->driver_cam.handle_camera_event(event_data); - } else { - LOGE("Unknown vidioc event source"); - assert(false); + for (auto &cam : cams) { + if (event_data->session_hdl == cam->camera.session_handle) { + cam->camera.handle_camera_event(event_data); + break; + } } } else { LOGE("unhandled event %d\n", ev.type); @@ -1017,10 +339,4 @@ void cameras_run(MultiCameraState *s) { LOGE("VIDIOC_DQEVENT failed, errno=%d", errno); } } - - LOG(" ************** STOPPING **************"); - - for (auto &t : threads) t.join(); - - cameras_close(s); } diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h deleted file mode 100644 index 0b15c9c3f04f06d..000000000000000 --- a/system/camerad/cameras/camera_qcom2.h +++ /dev/null @@ -1,105 +0,0 @@ -#pragma once - -#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 ROAD_FL_MM 8.0f -#define WIDE_FL_MM 1.71f -#define DRIVER_FL_MM 1.71f - -class CameraState { -public: - MultiCameraState *multi_cam_state; - std::unique_ptr ci; - bool enabled; - - std::mutex exp_lock; - - int exposure_time; - bool dc_gain_enabled; - int dc_gain_weight; - int gain_idx; - float analog_gain_frac; - - float cur_ev[3]; - float best_ev_score; - int new_exp_g; - int new_exp_t; - - Rect ae_xywh; - float measured_grey_fraction; - float target_grey_fraction; - - unique_fd sensor_fd; - unique_fd csiphy_fd; - - int camera_num; - float fl_pix; - - void handle_camera_event(void *evdat); - void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain); - void set_camera_exposure(float grey_frac); - - void sensors_start(); - - void camera_open(MultiCameraState *multi_cam_state, int camera_num, bool enabled); - void set_exposure_rect(); - void sensor_set_parameters(); - void camera_map_bufs(MultiCameraState *s); - void camera_init(MultiCameraState *s, VisionIpcServer *v, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type, float focal_len); - void camera_close(); - - int32_t session_handle; - int32_t sensor_dev_handle; - int32_t isp_dev_handle; - int32_t csiphy_dev_handle; - - int32_t link_handle; - - int buf0_handle; - int buf_handle[FRAME_BUF_COUNT]; - int sync_objs[FRAME_BUF_COUNT]; - int request_ids[FRAME_BUF_COUNT]; - int request_id_last; - int frame_id_last; - int idx_offset; - bool skipped; - - CameraBuf buf; - MemoryManager mm; - - 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); - int clear_req_queue(); - - int sensors_init(); - void sensors_poke(int request_id); - void sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); - -private: - // for debugging - Params params; -}; - -typedef struct MultiCameraState { - unique_fd video0_fd; - unique_fd cam_sync_fd; - unique_fd isp_fd; - int device_iommu; - int cdm_iommu; - - CameraState road_cam; - CameraState wide_road_cam; - CameraState driver_cam; - - PubMaster *pm; -} MultiCameraState; diff --git a/system/camerad/cameras/camera_util.cc b/system/camerad/cameras/camera_util.cc deleted file mode 100644 index 7bd23fd9fe7e408..000000000000000 --- a/system/camerad/cameras/camera_util.cc +++ /dev/null @@ -1,137 +0,0 @@ -#include "system/camerad/cameras/camera_util.h" - -#include - -#include - -#include -#include - -#include "common/swaglog.h" -#include "common/util.h" - -// ************** low level camera helpers **************** -int do_cam_control(int fd, int op_code, void *handle, int size) { - struct cam_control camcontrol = {0}; - camcontrol.op_code = op_code; - camcontrol.handle = (uint64_t)handle; - if (size == 0) { - camcontrol.size = 8; - camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; - } else { - camcontrol.size = size; - camcontrol.handle_type = CAM_HANDLE_USER_POINTER; - } - - int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol)); - if (ret == -1) { - LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno); - } - return ret; -} - -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, - }; - int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); - return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt; -} - -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, - }; - return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd)); -} - -int device_control(int fd, int op_code, int session_handle, int dev_handle) { - // start stop and release are all the same - struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle }; - return do_cam_control(fd, op_code, &cmd, sizeof(cmd)); -} - -void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align, int flags, int mmu_hdl, int mmu_hdl2) { - struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; - mem_mgr_alloc_cmd.len = len; - mem_mgr_alloc_cmd.align = align; - mem_mgr_alloc_cmd.flags = flags; - mem_mgr_alloc_cmd.num_hdl = 0; - if (mmu_hdl != 0) { - mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl; - mem_mgr_alloc_cmd.num_hdl++; - } - if (mmu_hdl2 != 0) { - mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2; - mem_mgr_alloc_cmd.num_hdl++; - } - - do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); - *handle = mem_mgr_alloc_cmd.out.buf_handle; - - void *ptr = NULL; - if (mem_mgr_alloc_cmd.out.fd > 0) { - ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); - assert(ptr != MAP_FAILED); - } - - // LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); - - return ptr; -} - -void release(int video0_fd, uint32_t handle) { - struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0}; - mem_mgr_release_cmd.buf_handle = handle; - - int ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd)); - assert(ret == 0); -} - -void release_fd(int video0_fd, uint32_t handle) { - // handle to fd - close(handle>>16); - release(video0_fd, handle); -} - -void *MemoryManager::alloc_buf(int size, uint32_t *handle) { - lock.lock(); - void *ptr; - if (!cached_allocations[size].empty()) { - ptr = cached_allocations[size].front(); - cached_allocations[size].pop(); - *handle = handle_lookup[ptr]; - } else { - ptr = alloc_w_mmu_hdl(video0_fd, size, handle); - handle_lookup[ptr] = *handle; - size_lookup[ptr] = size; - } - lock.unlock(); - memset(ptr, 0, size); - return ptr; -} - -void MemoryManager::free(void *ptr) { - lock.lock(); - cached_allocations[size_lookup[ptr]].push(ptr); - lock.unlock(); -} - -MemoryManager::~MemoryManager() { - for (auto& x : cached_allocations) { - while (!x.second.empty()) { - void *ptr = x.second.front(); - x.second.pop(); - LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]); - munmap(ptr, size_lookup[ptr]); - release_fd(video0_fd, handle_lookup[ptr]); - handle_lookup.erase(ptr); - size_lookup.erase(ptr); - } - } -} diff --git a/system/camerad/cameras/camera_util.h b/system/camerad/cameras/camera_util.h deleted file mode 100644 index 891ce3e793a5b82..000000000000000 --- a/system/camerad/cameras/camera_util.h +++ /dev/null @@ -1,39 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include - -std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1); -int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle); -int device_control(int fd, int op_code, int session_handle, int dev_handle); -int do_cam_control(int fd, int op_code, void *handle, int size); -void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, - int mmu_hdl = 0, int mmu_hdl2 = 0); -void release(int video0_fd, uint32_t handle); - -class MemoryManager { - public: - void init(int _video0_fd) { video0_fd = _video0_fd; } - ~MemoryManager(); - - template - auto alloc(int len, uint32_t *handle) { - return std::unique_ptr>((T*)alloc_buf(len, handle), [this](void *ptr) { this->free(ptr); }); - } - - private: - void *alloc_buf(int len, uint32_t *handle); - void free(void *ptr); - - std::mutex lock; - std::map handle_lookup; - std::map size_lookup; - std::map > cached_allocations; - int video0_fd; -}; diff --git a/system/camerad/cameras/cdm.cc b/system/camerad/cameras/cdm.cc new file mode 100644 index 000000000000000..8b319bc70ccd4e1 --- /dev/null +++ b/system/camerad/cameras/cdm.cc @@ -0,0 +1,47 @@ +#include "cdm.h" +#include "stddef.h" + +int write_dmi(uint8_t *dst, uint64_t *addr, uint32_t length, uint32_t dmi_addr, uint8_t sel) { + struct cdm_dmi_cmd *cmd = (struct cdm_dmi_cmd*)dst; + cmd->cmd = CAM_CDM_CMD_DMI_32; + cmd->length = length - 1; + cmd->reserved = 0; + cmd->addr = 0; // gets patched in + cmd->DMIAddr = dmi_addr; + cmd->DMISel = sel; + + *addr = (uint64_t)(dst + offsetof(struct cdm_dmi_cmd, addr)); + return sizeof(struct cdm_dmi_cmd); +} + +int write_cont(uint8_t *dst, uint32_t reg, std::vector vals) { + struct cdm_regcontinuous_cmd *cmd = (struct cdm_regcontinuous_cmd*)dst; + cmd->cmd = CAM_CDM_CMD_REG_CONT; + cmd->count = vals.size(); + cmd->offset = reg; + cmd->reserved0 = 0; + cmd->reserved1 = 0; + + uint32_t *vd = (uint32_t*)(dst + sizeof(struct cdm_regcontinuous_cmd)); + for (int i = 0; i < vals.size(); i++) { + *vd = vals[i]; + vd++; + } + + return sizeof(struct cdm_regcontinuous_cmd) + vals.size()*sizeof(uint32_t); +} + +int write_random(uint8_t *dst, std::vector vals) { + struct cdm_regrandom_cmd *cmd = (struct cdm_regrandom_cmd*)dst; + cmd->cmd = CAM_CDM_CMD_REG_RANDOM; + cmd->count = vals.size() / 2; + cmd->reserved = 0; + + uint32_t *vd = (uint32_t*)(dst + sizeof(struct cdm_regrandom_cmd)); + for (int i = 0; i < vals.size(); i++) { + *vd = vals[i]; + vd++; + } + + return sizeof(struct cdm_regrandom_cmd) + vals.size()*sizeof(uint32_t); +} diff --git a/system/camerad/cameras/cdm.h b/system/camerad/cameras/cdm.h new file mode 100644 index 000000000000000..bd7a50e0ec90fd0 --- /dev/null +++ b/system/camerad/cameras/cdm.h @@ -0,0 +1,79 @@ +#pragma once + +#include +#include +#include +#include +#include + +// our helpers +int write_random(uint8_t *dst, std::vector vals); +int write_cont(uint8_t *dst, uint32_t reg, std::vector vals); +int write_dmi(uint8_t *dst, uint64_t *addr, uint32_t length, uint32_t dmi_addr, uint8_t sel); + +// from drivers/media/platform/msm/camera/cam_cdm/cam_cdm_util.{c,h} + +enum cam_cdm_command { + CAM_CDM_CMD_UNUSED = 0x0, + CAM_CDM_CMD_DMI = 0x1, + CAM_CDM_CMD_NOT_DEFINED = 0x2, + CAM_CDM_CMD_REG_CONT = 0x3, + CAM_CDM_CMD_REG_RANDOM = 0x4, + CAM_CDM_CMD_BUFF_INDIRECT = 0x5, + CAM_CDM_CMD_GEN_IRQ = 0x6, + CAM_CDM_CMD_WAIT_EVENT = 0x7, + CAM_CDM_CMD_CHANGE_BASE = 0x8, + CAM_CDM_CMD_PERF_CTRL = 0x9, + CAM_CDM_CMD_DMI_32 = 0xa, + CAM_CDM_CMD_DMI_64 = 0xb, + CAM_CDM_CMD_PRIVATE_BASE = 0xc, + CAM_CDM_CMD_SWD_DMI_32 = (CAM_CDM_CMD_PRIVATE_BASE + 0x64), + CAM_CDM_CMD_SWD_DMI_64 = (CAM_CDM_CMD_PRIVATE_BASE + 0x65), + CAM_CDM_CMD_PRIVATE_BASE_MAX = 0x7F +}; + +/** + * struct cdm_regrandom_cmd - Definition for CDM random register command. + * @count: Number of register writes + * @reserved: reserved bits + * @cmd: Command ID (CDMCmd) + */ +struct cdm_regrandom_cmd { + unsigned int count : 16; + unsigned int reserved : 8; + unsigned int cmd : 8; +} __attribute__((__packed__)); + +/** + * struct cdm_regcontinuous_cmd - Definition for a CDM register range command. + * @count: Number of register writes + * @reserved0: reserved bits + * @cmd: Command ID (CDMCmd) + * @offset: Start address of the range of registers + * @reserved1: reserved bits + */ +struct cdm_regcontinuous_cmd { + unsigned int count : 16; + unsigned int reserved0 : 8; + unsigned int cmd : 8; + unsigned int offset : 24; + unsigned int reserved1 : 8; +} __attribute__((__packed__)); + +/** + * struct cdm_dmi_cmd - Definition for a CDM DMI command. + * @length: Number of bytes in LUT - 1 + * @reserved: reserved bits + * @cmd: Command ID (CDMCmd) + * @addr: Address of the LUT in memory + * @DMIAddr: Address of the target DMI config register + * @DMISel: DMI identifier + */ +struct cdm_dmi_cmd { + unsigned int length : 16; + unsigned int reserved : 8; + unsigned int cmd : 8; + unsigned int addr; + unsigned int DMIAddr : 24; + unsigned int DMISel : 8; +} __attribute__((__packed__)); diff --git a/system/camerad/cameras/ife.h b/system/camerad/cameras/ife.h new file mode 100644 index 000000000000000..a232000100a5b47 --- /dev/null +++ b/system/camerad/cameras/ife.h @@ -0,0 +1,233 @@ +#include "cdm.h" + +#include "system/camerad/cameras/tici.h" +#include "system/camerad/sensors/sensor.h" + + +int build_update(uint8_t *dst, const SensorInfo *s, std::vector &patches) { + uint8_t *start = dst; + + dst += write_random(dst, { + 0x2c, 0xffffffff, + 0x30, 0xffffffff, + 0x34, 0xffffffff, + 0x38, 0xffffffff, + 0x3c, 0xffffffff, + }); + + dst += write_cont(dst, 0x560, { + 0x00000001, + 0x04440444, + 0x04450445, + 0x04440444, + 0x04450445, + 0x000000ca, + 0x0000009c, + }); + + // white balance + dst += write_cont(dst, 0x6fc, { + 0x00800080, + 0x00000080, + 0x00000000, + 0x00000000, + }); + + dst += write_cont(dst, 0x40, { + 0x00000c06, // (1<<8) to enable vignetting correction + }); + + dst += write_cont(dst, 0x48, { + (1 << 3) | (1 << 1), + }); + + dst += write_cont(dst, 0x4c, { + 0x00000019, + }); + + dst += write_cont(dst, 0xe0c, { + 0x00000e00, + }); + + dst += write_cont(dst, 0xe2c, { + 0x00000e00, + }); + + dst += write_cont(dst, 0x44, { + 0x00000000, + }); + + dst += write_cont(dst, 0xaac, { + 0x00000000, + }); + + dst += write_cont(dst, 0xf00, { + 0x00000000, + }); + + // black level scale + offset + dst += write_cont(dst, 0x6b0, { + ((uint32_t)(1 << 11) << 0xf) | (s->black_level << (14 - s->bits_per_pixel)), + 0x0, + 0x0, + }); + + return dst - start; +} + + +int build_initial_config(uint8_t *dst, const SensorInfo *s, std::vector &patches) { + uint8_t *start = dst; + + // start with the every frame config + dst += build_update(dst, s, patches); + + uint64_t addr; + + // setup + dst += write_cont(dst, 0x478, { + 0x00000004, + 0x004000c0, + }); + dst += write_cont(dst, 0x488, { + 0x00000000, + 0x00000000, + 0x00000f0f, + }); + dst += write_cont(dst, 0x49c, { + 0x00000001, + }); + dst += write_cont(dst, 0xce4, { + 0x00000000, + 0x00000000, + }); + + // linearization + dst += write_cont(dst, 0x4dc, { + 0x00000000, + }); + dst += write_cont(dst, 0x4e0, s->linearization_pts); + dst += write_cont(dst, 0x4f0, s->linearization_pts); + dst += write_cont(dst, 0x500, s->linearization_pts); + dst += write_cont(dst, 0x510, s->linearization_pts); + // TODO: this is DMI64 in the dump, does that matter? + dst += write_dmi(dst, &addr, 288, 0xc24, 9); + patches.push_back(addr - (uint64_t)start); + /* TODO + cdm_dmi_cmd_t 248 + .length = 287 + .reserved = 33 + .cmd = 11 + .addr = 0 + .DMIAddr = 3108 + .DMISel = 9 + */ + + // vignetting correction + dst += write_cont(dst, 0x6bc, { + 0x0b3c0000, + 0x00670067, + 0xd3b1300c, + 0x13b1300c, + 0x00670067, + 0xd3b1300c, + 0x13b1300c, + 0xec4e4000, + 0x0100c003, + 0xec4e4000, + 0x0100c003, + }); + dst += write_dmi(dst, &addr, 884, 0xc24, 14); + patches.push_back(addr - (uint64_t)start); + dst += write_dmi(dst, &addr, 884, 0xc24, 15); + patches.push_back(addr - (uint64_t)start); + + // debayer + dst += write_cont(dst, 0x6f8, { + 0x00000100, + }); + dst += write_cont(dst, 0x71c, { + 0x00008000, + 0x08000066, + }); + + // color correction + dst += write_cont(dst, 0x760, s->color_correct_matrix); + + // gamma + dst += write_cont(dst, 0x798, { + 0x00000000, + }); + dst += write_dmi(dst, &addr, 256, 0xc24, 26); // G + patches.push_back(addr - (uint64_t)start); + dst += write_dmi(dst, &addr, 256, 0xc24, 28); // B + patches.push_back(addr - (uint64_t)start); + dst += write_dmi(dst, &addr, 256, 0xc24, 30); // R + patches.push_back(addr - (uint64_t)start); + + // YUV + dst += write_cont(dst, 0xf30, { + 0x00680208, + 0x00000108, + 0x00400000, + 0x03ff0000, + 0x01c01ed8, + 0x00001f68, + 0x02000000, + 0x03ff0000, + 0x1fb81e88, + 0x000001c0, + 0x02000000, + 0x03ff0000, + }); + + // TODO: remove this + dst += write_cont(dst, 0xa3c, { + 0x00000003, + ((s->frame_width - 1) << 16) | (s->frame_width - 1), + 0x30036666, + 0x00000000, + 0x00000000, + s->frame_width - 1, + ((s->frame_height - 1) << 16) | (s->frame_height - 1), + 0x30036666, + 0x00000000, + 0x00000000, + s->frame_height - 1, + }); + dst += write_cont(dst, 0xa68, { + 0x00000003, + ((s->frame_width/2 - 1) << 16) | (s->frame_width - 1), + 0x3006cccc, + 0x00000000, + 0x00000000, + s->frame_width - 1, + ((s->frame_height/2 - 1) << 16) | (s->frame_height - 1), + 0x3006cccc, + 0x00000000, + 0x00000000, + s->frame_height - 1, + }); + + // cropping + dst += write_cont(dst, 0xe10, { + s->frame_height - 1, + s->frame_width - 1, + }); + dst += write_cont(dst, 0xe30, { + s->frame_height/2 - 1, + s->frame_width - 1, + }); + dst += write_cont(dst, 0xe18, { + 0x0ff00000, + 0x00000016, + }); + dst += write_cont(dst, 0xe38, { + 0x0ff00000, + 0x00000017, + }); + + return dst - start; +} + + diff --git a/system/camerad/cameras/spectra.cc b/system/camerad/cameras/spectra.cc new file mode 100644 index 000000000000000..b262ddba9a57ab1 --- /dev/null +++ b/system/camerad/cameras/spectra.cc @@ -0,0 +1,1112 @@ +#include "cdm.h" + +#include +#include +#include +#include + +#include "media/cam_defs.h" +#include "media/cam_isp.h" +#include "media/cam_icp.h" +#include "media/cam_isp_ife.h" +#include "media/cam_sensor_cmn_header.h" +#include "media/cam_sync.h" +#include "third_party/linux/include/msm_media_info.h" + +#include "common/util.h" +#include "common/swaglog.h" +#include "system/camerad/cameras/ife.h" +#include "system/camerad/cameras/spectra.h" +#include "third_party/linux/include/msm_media_info.h" + +// For debugging: +// echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl + +// ************** low level camera helpers **************** + +int do_cam_control(int fd, int op_code, void *handle, int size) { + struct cam_control camcontrol = {0}; + camcontrol.op_code = op_code; + camcontrol.handle = (uint64_t)handle; + if (size == 0) { + camcontrol.size = 8; + camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; + } else { + camcontrol.size = size; + camcontrol.handle_type = CAM_HANDLE_USER_POINTER; + } + + int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol)); + if (ret == -1) { + LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno); + } + return ret; +} + +int do_sync_control(int fd, uint32_t id, void *handle, uint32_t size) { + struct cam_private_ioctl_arg arg = { + .id = id, + .size = size, + .ioctl_ptr = (uint64_t)handle, + }; + int ret = HANDLE_EINTR(ioctl(fd, CAM_PRIVATE_IOCTL_CMD, &arg)); + + int32_t ioctl_result = (int32_t)arg.result; + if (ret < 0) { + LOGE("CAM_SYNC error: id %u - errno %d - ret %d - ioctl_result %d", id, errno, ret, ioctl_result); + return ret; + } + if (ioctl_result < 0) { + LOGE("CAM_SYNC error: id %u - errno %d - ret %d - ioctl_result %d", id, errno, ret, ioctl_result); + return ioctl_result; + } + return ret; +} + +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, + }; + int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); + return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt; +} + +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, + }; + return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd)); +} + +int device_control(int fd, int op_code, int session_handle, int dev_handle) { + // start stop and release are all the same + struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle }; + return do_cam_control(fd, op_code, &cmd, sizeof(cmd)); +} + +void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align, int flags, int mmu_hdl, int mmu_hdl2) { + struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; + mem_mgr_alloc_cmd.len = len; + mem_mgr_alloc_cmd.align = align; + mem_mgr_alloc_cmd.flags = flags; + mem_mgr_alloc_cmd.num_hdl = 0; + if (mmu_hdl != 0) { + mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl; + mem_mgr_alloc_cmd.num_hdl++; + } + if (mmu_hdl2 != 0) { + mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2; + mem_mgr_alloc_cmd.num_hdl++; + } + + do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); + *handle = mem_mgr_alloc_cmd.out.buf_handle; + + void *ptr = NULL; + if (mem_mgr_alloc_cmd.out.fd > 0) { + ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); + assert(ptr != MAP_FAILED); + } + + // LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); + + return ptr; +} + +void release(int video0_fd, uint32_t handle) { + struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0}; + mem_mgr_release_cmd.buf_handle = handle; + + int ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd)); + assert(ret == 0); +} + +static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { + cam_cmd_unconditional_wait *unconditional_wait = (cam_cmd_unconditional_wait *)((char *)power + (sizeof(struct cam_cmd_power) + (power->count - 1) * sizeof(struct cam_power_settings))); + unconditional_wait->cmd_type = CAMERA_SENSOR_CMD_TYPE_WAIT; + unconditional_wait->delay = delay_ms; + unconditional_wait->op_code = CAMERA_SENSOR_WAIT_OP_SW_UCND; + return (struct cam_cmd_power *)(unconditional_wait + 1); +} + +// *** MemoryManager *** + +void *MemoryManager::alloc_buf(int size, uint32_t *handle) { + lock.lock(); + void *ptr; + if (!cached_allocations[size].empty()) { + ptr = cached_allocations[size].front(); + cached_allocations[size].pop(); + *handle = handle_lookup[ptr]; + } else { + ptr = alloc_w_mmu_hdl(video0_fd, size, handle); + handle_lookup[ptr] = *handle; + size_lookup[ptr] = size; + } + lock.unlock(); + memset(ptr, 0, size); + return ptr; +} + +void MemoryManager::free(void *ptr) { + lock.lock(); + cached_allocations[size_lookup[ptr]].push(ptr); + lock.unlock(); +} + +MemoryManager::~MemoryManager() { + for (auto& x : cached_allocations) { + while (!x.second.empty()) { + void *ptr = x.second.front(); + x.second.pop(); + LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]); + munmap(ptr, size_lookup[ptr]); + + // release fd + close(handle_lookup[ptr] >> 16); + release(video0_fd, handle_lookup[ptr]); + + handle_lookup.erase(ptr); + size_lookup.erase(ptr); + } + } +} + +// *** SpectraMaster *** + +void SpectraMaster::init() { + LOG("-- Opening devices"); + // video0 is req_mgr, the target of many ioctls + video0_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK)); + assert(video0_fd >= 0); + LOGD("opened video0"); + + // video1 is cam_sync, the target of some ioctls + cam_sync_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK)); + assert(cam_sync_fd >= 0); + LOGD("opened video1 (cam_sync)"); + + // looks like there's only one of these + isp_fd = open_v4l_by_name_and_index("cam-isp"); + assert(isp_fd >= 0); + LOGD("opened isp"); + + //icp_fd = open_v4l_by_name_and_index("cam-icp"); + //assert(icp_fd >= 0); + //LOGD("opened icp"); + + // query ISP for MMU handles + LOG("-- Query for MMU handles"); + struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0}; + struct cam_query_cap_cmd query_cap_cmd = {0}; + query_cap_cmd.handle_type = 1; + query_cap_cmd.caps_handle = (uint64_t)&isp_query_cap_cmd; + query_cap_cmd.size = sizeof(isp_query_cap_cmd); + int ret = do_cam_control(isp_fd, CAM_QUERY_CAP, &query_cap_cmd, sizeof(query_cap_cmd)); + assert(ret == 0); + LOGD("using MMU handle: %x", isp_query_cap_cmd.device_iommu.non_secure); + LOGD("using MMU handle: %x", isp_query_cap_cmd.cdm_iommu.non_secure); + device_iommu = isp_query_cap_cmd.device_iommu.non_secure; + cdm_iommu = isp_query_cap_cmd.cdm_iommu.non_secure; + + // query ICP for MMU handles + /* + struct cam_icp_query_cap_cmd icp_query_cap_cmd = {0}; + query_cap_cmd.caps_handle = (uint64_t)&icp_query_cap_cmd; + query_cap_cmd.size = sizeof(icp_query_cap_cmd); + ret = do_cam_control(icp_fd, CAM_QUERY_CAP, &query_cap_cmd, sizeof(query_cap_cmd)); + assert(ret == 0); + LOGD("using ICP MMU handle: %x", icp_query_cap_cmd.dev_iommu_handle.non_secure); + icp_device_iommu = icp_query_cap_cmd.dev_iommu_handle.non_secure; + */ + + // subscribe + LOG("-- Subscribing"); + struct v4l2_event_subscription sub = {0}; + sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT; + sub.id = V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS; + ret = HANDLE_EINTR(ioctl(video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); + LOGD("req mgr subscribe: %d", ret); +} + +// *** SpectraCamera *** + +SpectraCamera::SpectraCamera(SpectraMaster *master, const CameraConfig &config, bool raw) + : m(master), + enabled(config.enabled), + cc(config), + is_raw(raw) { + mm.init(m->video0_fd); +} + +SpectraCamera::~SpectraCamera() { + if (open) { + camera_close(); + } +} + +int SpectraCamera::clear_req_queue() { + struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; + req_mgr_flush_request.session_hdl = session_handle; + req_mgr_flush_request.link_hdl = link_handle; + req_mgr_flush_request.flush_type = CAM_REQ_MGR_FLUSH_TYPE_ALL; + int ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_FLUSH_REQ, &req_mgr_flush_request, sizeof(req_mgr_flush_request)); + // LOGD("flushed all req: %d", ret); + return ret; +} + +void SpectraCamera::camera_open(VisionIpcServer *v, cl_device_id device_id, cl_context ctx) { + if (!enabled) return; + + if (!openSensor()) { + return; + } + + // size is driven by all the HW that handles frames, + // the video encoder has certain alignment requirements in this case + stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, sensor->frame_width); + y_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, sensor->frame_height); + uv_height = VENUS_UV_SCANLINES(COLOR_FMT_NV12, sensor->frame_height); + uv_offset = stride*y_height; + yuv_size = uv_offset + stride*uv_height; + if (!is_raw) { + uv_offset = ALIGNED_SIZE(uv_offset, 0x1000); + yuv_size = uv_offset + ALIGNED_SIZE(stride*uv_height, 0x1000); + } + assert(stride == VENUS_UV_STRIDE(COLOR_FMT_NV12, sensor->frame_width)); + assert(y_height/2 == uv_height); + + open = true; + configISP(); + //configICP(); // needs the new AGNOS kernel + configCSIPHY(); + linkDevices(); + + LOGD("camera init %d", cc.camera_num); + buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, cc.stream_type); + camera_map_bufs(); +} + +void SpectraCamera::enqueue_req_multi(uint64_t start, int n, bool dp) { + for (uint64_t i = start; i < start + n; ++i) { + request_ids[(i - 1) % FRAME_BUF_COUNT] = i; + enqueue_buffer((i - 1) % FRAME_BUF_COUNT, dp); + } +} + +void SpectraCamera::sensors_start() { + if (!enabled) return; + LOGD("starting sensor %d", cc.camera_num); + sensors_i2c(sensor->start_reg_array.data(), sensor->start_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); +} + +void SpectraCamera::sensors_poke(int request_id) { + uint32_t cam_packet_handle = 0; + int size = sizeof(struct cam_packet); + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 0; + pkt->kmd_cmd_buf_index = -1; + pkt->header.size = size; + pkt->header.op_code = CAM_SENSOR_PACKET_OPCODE_SENSOR_NOP; + pkt->header.request_id = request_id; + + int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); + if (ret != 0) { + LOGE("** sensor %d FAILED poke, disabling", cc.camera_num); + enabled = false; + return; + } +} + +void SpectraCamera::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; + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 1; + pkt->kmd_cmd_buf_index = -1; + pkt->header.size = size; + pkt->header.op_code = op_code; + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + + buf_desc[0].size = buf_desc[0].length = sizeof(struct i2c_rdwr_header) + len*sizeof(struct i2c_random_wr_payload); + buf_desc[0].type = CAM_CMD_BUF_I2C; + + auto i2c_random_wr = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); + i2c_random_wr->header.count = len; + i2c_random_wr->header.op_code = 1; + i2c_random_wr->header.cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR; + i2c_random_wr->header.data_type = data_word ? CAMERA_SENSOR_I2C_TYPE_WORD : CAMERA_SENSOR_I2C_TYPE_BYTE; + i2c_random_wr->header.addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; + memcpy(i2c_random_wr->random_wr_payload, dat, len*sizeof(struct i2c_random_wr_payload)); + + int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); + if (ret != 0) { + LOGE("** sensor %d FAILED i2c, disabling", cc.camera_num); + enabled = false; + return; + } +} + +int SpectraCamera::sensors_init() { + uint32_t cam_packet_handle = 0; + int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 2; + pkt->kmd_cmd_buf_index = -1; + pkt->header.op_code = CSLDeviceTypeImageSensor | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE; + pkt->header.size = size; + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + + buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); + buf_desc[0].type = CAM_CMD_BUF_LEGACY; + auto i2c_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); + auto probe = (struct cam_cmd_probe *)(i2c_info.get() + 1); + + probe->camera_id = cc.camera_num; + i2c_info->slave_addr = sensor->getSlaveAddress(cc.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; + i2c_info->cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_INFO; + + probe->data_type = CAMERA_SENSOR_I2C_TYPE_WORD; + probe->addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; + probe->op_code = 3; // don't care? + probe->cmd_type = CAMERA_SENSOR_CMD_TYPE_PROBE; + probe->reg_addr = sensor->probe_reg_addr; + probe->expected_data = sensor->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); + + // power on + struct cam_cmd_power *power = power_settings.get(); + power->count = 4; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; + power->power_settings[0].power_seq_type = 3; // clock?? + power->power_settings[1].power_seq_type = 1; // analog + power->power_settings[2].power_seq_type = 2; // digital + power->power_settings[3].power_seq_type = 8; // reset low + power = power_set_wait(power, 1); + + // set clock + 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 = sensor->mclk_frequency; + power = power_set_wait(power, 1); + + // reset high + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; + power->power_settings[0].power_seq_type = 8; + power->power_settings[0].config_val_low = 1; + // wait 650000 cycles @ 19.2 mhz = 33.8 ms + power = power_set_wait(power, 34); + + // probe happens here + + // disable clock + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; + power->power_settings[0].power_seq_type = 0; + power->power_settings[0].config_val_low = 0; + power = power_set_wait(power, 1); + + // reset high + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; + power->power_settings[0].power_seq_type = 8; + power->power_settings[0].config_val_low = 1; + power = power_set_wait(power, 1); + + // reset low + power->count = 1; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; + power->power_settings[0].power_seq_type = 8; + power->power_settings[0].config_val_low = 0; + power = power_set_wait(power, 1); + + // power off + power->count = 3; + power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; + power->power_settings[0].power_seq_type = 2; + power->power_settings[1].power_seq_type = 1; + power->power_settings[2].power_seq_type = 3; + + int ret = do_cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); + LOGD("probing the sensor: %d", ret); + return ret; +} + +void SpectraCamera::config_bps(int idx, int request_id) { + /* + Handles per-frame BPS config. + * BPS = Bayer Processing Segment + */ + (void)idx; + (void)request_id; +} + +void add_patch(void *ptr, int n, int32_t dst_hdl, uint32_t dst_offset, int32_t src_hdl, uint32_t src_offset) { + struct cam_patch_desc *p = (struct cam_patch_desc *)((unsigned char*)ptr + sizeof(struct cam_patch_desc)*n); + p->dst_buf_hdl = dst_hdl; + p->src_buf_hdl = src_hdl; + p->dst_offset = dst_offset; + p->src_offset = src_offset; +}; + +void SpectraCamera::config_ife(int idx, int request_id, bool init) { + /* + Handles initial + per-frame IFE config. + * IFE = Image Front End + */ + int size = sizeof(struct cam_packet) + sizeof(struct cam_cmd_buf_desc)*2; + size += sizeof(struct cam_patch_desc)*10; + if (!init) { + size += sizeof(struct cam_buf_io_cfg); + } + + uint32_t cam_packet_handle = 0; + auto pkt = mm.alloc(size, &cam_packet_handle); + + if (!init) { + pkt->header.op_code = CSLDeviceTypeIFE | OpcodesIFEUpdate; // 0xf000001 + pkt->header.request_id = request_id; + } else { + pkt->header.op_code = CSLDeviceTypeIFE | OpcodesIFEInitialConfig; // 0xf000000 + pkt->header.request_id = 1; + } + pkt->header.size = size; + + // *** cmd buf *** + std::vector patches; + { + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + pkt->num_cmd_buf = 2; + + // *** first command *** + buf_desc[0].size = ife_cmd.size; + buf_desc[0].length = 0; + buf_desc[0].type = CAM_CMD_BUF_DIRECT; + buf_desc[0].meta_data = CAM_ISP_PACKET_META_COMMON; + buf_desc[0].mem_handle = ife_cmd.handle; + buf_desc[0].offset = ife_cmd.aligned_size()*idx; + + // stream of IFE register writes + if (!is_raw) { + if (init) { + buf_desc[0].length = build_initial_config((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, sensor.get(), patches); + } else { + buf_desc[0].length = build_update((unsigned char*)ife_cmd.ptr + buf_desc[0].offset, sensor.get(), patches); + } + } + + pkt->kmd_cmd_buf_offset = buf_desc[0].length; + pkt->kmd_cmd_buf_index = 0; + + // *** second command *** + // parsed by cam_isp_packet_generic_blob_handler + struct isp_packet { + uint32_t type_0; + cam_isp_resource_hfr_config resource_hfr; + + uint32_t type_1; + cam_isp_clock_config clock; + uint64_t extra_rdi_hz[3]; + + uint32_t type_2; + cam_isp_bw_config bw; + struct cam_isp_bw_vote extra_rdi_vote[6]; + } __attribute__((packed)) tmp; + memset(&tmp, 0, sizeof(tmp)); + + tmp.type_0 = CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG; + tmp.type_0 |= sizeof(cam_isp_resource_hfr_config) << 8; + static_assert(sizeof(cam_isp_resource_hfr_config) == 0x20); + tmp.resource_hfr = { + .num_ports = 1, + .port_hfr_config[0] = { + .resource_type = static_cast(is_raw ? CAM_ISP_IFE_OUT_RES_RDI_0 : CAM_ISP_IFE_OUT_RES_FULL), + .subsample_pattern = 1, + .subsample_period = 0, + .framedrop_pattern = 1, + .framedrop_period = 0, + } + }; + + tmp.type_1 = CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG; + tmp.type_1 |= (sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) << 8; + static_assert((sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) == 0x38); + tmp.clock = { + .usage_type = 1, // dual mode + .num_rdi = 4, + .left_pix_hz = 404000000, + .right_pix_hz = 404000000, + .rdi_hz[0] = 404000000, + }; + + tmp.type_2 = CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG; + tmp.type_2 |= (sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) << 8; + static_assert((sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) == 0xe0); + tmp.bw = { + .usage_type = 1, // dual mode + .num_rdi = 4, + .left_pix_vote = { + .resource_id = 0, + .cam_bw_bps = 450000000, + .ext_bw_bps = 450000000, + }, + .rdi_vote[0] = { + .resource_id = 0, + .cam_bw_bps = 8706200000, + .ext_bw_bps = 8706200000, + }, + }; + + static_assert(offsetof(struct isp_packet, type_2) == 0x60); + + buf_desc[1].size = sizeof(tmp); + buf_desc[1].offset = !init ? 0x60 : 0; + buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset; + buf_desc[1].type = CAM_CMD_BUF_GENERIC; + buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; + auto buf2 = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); + memcpy(buf2.get(), &tmp, sizeof(tmp)); + } + + // *** io config *** + if (!init) { + // configure output frame + pkt->num_io_configs = 1; + pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf; + + struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); + + if (is_raw) { + io_cfg[0].mem_handle[0] = buf_handle_raw[idx]; + io_cfg[0].planes[0] = (struct cam_plane_cfg){ + .width = sensor->frame_width, + .height = sensor->frame_height, + .plane_stride = sensor->frame_stride, + .slice_height = sensor->frame_height + sensor->extra_height, + }; + io_cfg[0].format = sensor->mipi_format; + io_cfg[0].color_space = CAM_COLOR_SPACE_BASE; + io_cfg[0].color_pattern = 0x5; + io_cfg[0].bpp = (sensor->mipi_format == CAM_FORMAT_MIPI_RAW_10 ? 0xa : 0xc); + io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; + io_cfg[0].fence = sync_objs[idx]; + io_cfg[0].direction = CAM_BUF_OUTPUT; + io_cfg[0].subsample_pattern = 0x1; + io_cfg[0].framedrop_pattern = 0x1; + } else { + io_cfg[0].mem_handle[0] = buf_handle_yuv[idx]; + io_cfg[0].mem_handle[1] = buf_handle_yuv[idx]; + io_cfg[0].planes[0] = (struct cam_plane_cfg){ + .width = sensor->frame_width, + .height = sensor->frame_height, + .plane_stride = stride, + .slice_height = y_height, + }; + io_cfg[0].planes[1] = (struct cam_plane_cfg){ + .width = sensor->frame_width, + .height = sensor->frame_height/2, + .plane_stride = stride, + .slice_height = uv_height, + }; + io_cfg[0].offsets[1] = uv_offset; + io_cfg[0].format = CAM_FORMAT_NV12; + io_cfg[0].color_space = 0; + io_cfg[0].color_pattern = 0x0; + io_cfg[0].bpp = 0; + io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_FULL; + io_cfg[0].fence = sync_objs[idx]; + io_cfg[0].direction = CAM_BUF_OUTPUT; + io_cfg[0].subsample_pattern = 0x1; + io_cfg[0].framedrop_pattern = 0x1; + } + } + + // *** patches *** + // sets up the kernel driver to do address translation for the IFE + { + // order here corresponds to the one in build_initial_config + assert(patches.size() == 6 || patches.size() == 0); + + pkt->num_patches = patches.size(); + pkt->patch_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf + sizeof(struct cam_buf_io_cfg)*pkt->num_io_configs; + if (pkt->num_patches > 0) { + void *p = (char*)&pkt->payload + pkt->patch_offset; + + // linearization LUT + add_patch(p, 0, ife_cmd.handle, patches[0], ife_linearization_lut.handle, 0); + + // vignetting correction LUTs + add_patch(p, 1, ife_cmd.handle, patches[1], ife_vignetting_lut.handle, 0); + add_patch(p, 2, ife_cmd.handle, patches[2], ife_vignetting_lut.handle, ife_vignetting_lut.size); + + // gamma LUTs + for (int i = 0; i < 3; i++) { + add_patch(p, i+3, ife_cmd.handle, patches[i+3], ife_gamma_lut.handle, ife_gamma_lut.size*i); + } + } + } + + int ret = device_config(m->isp_fd, session_handle, isp_dev_handle, cam_packet_handle); + assert(ret == 0); +} + +void SpectraCamera::enqueue_buffer(int i, bool dp) { + int ret; + uint64_t request_id = request_ids[i]; + + if (buf_handle_raw[i] && sync_objs[i]) { + // wait + struct cam_sync_wait sync_wait = {0}; + sync_wait.sync_obj = sync_objs[i]; + sync_wait.timeout_ms = 50; // max dt tolerance, typical should be 23 + ret = do_sync_control(m->cam_sync_fd, CAM_SYNC_WAIT, &sync_wait, sizeof(sync_wait)); + if (ret != 0) { + LOGE("failed to wait for sync: %d %d", ret, sync_wait.sync_obj); + // TODO: handle frame drop cleanly + } + buf.frame_metadata[i].timestamp_end_of_isp = (uint64_t)nanos_since_boot(); + buf.frame_metadata[i].timestamp_eof = buf.frame_metadata[i].timestamp_sof + sensor->readout_time_ns; + if (dp) buf.queue(i); + + // destroy old output fence + for (auto so : {sync_objs, sync_objs_bps_out}) { + if (so[i] == 0) continue; + struct cam_sync_info sync_destroy = {0}; + sync_destroy.sync_obj = so[i]; + ret = do_sync_control(m->cam_sync_fd, CAM_SYNC_DESTROY, &sync_destroy, sizeof(sync_destroy)); + if (ret != 0) { + LOGE("failed to destroy sync object: %d %d", ret, sync_destroy.sync_obj); + } + } + } + + // create output fences + struct cam_sync_info sync_create = {0}; + strcpy(sync_create.name, "NodeOutputPortFence"); + ret = do_sync_control(m->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create)); + if (ret != 0) { + LOGE("failed to create fence: %d %d", ret, sync_create.sync_obj); + } + sync_objs[i] = sync_create.sync_obj; + + /* + ret = do_cam_control(m->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create)); + if (ret != 0) { + LOGE("failed to create fence: %d %d", ret, sync_create.sync_obj); + } + sync_objs_bps_out[i] = sync_create.sync_obj; + */ + + // schedule request with camera request manager + struct cam_req_mgr_sched_request req_mgr_sched_request = {0}; + req_mgr_sched_request.session_hdl = session_handle; + req_mgr_sched_request.link_hdl = link_handle; + req_mgr_sched_request.req_id = request_id; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_SCHED_REQ, &req_mgr_sched_request, sizeof(req_mgr_sched_request)); + if (ret != 0) { + LOGE("failed to schedule cam mgr request: %d %lu", ret, request_id); + } + + // poke sensor, must happen after schedule + sensors_poke(request_id); + + // submit request to IFE and BPS + config_ife(i, request_id); + config_bps(i, request_id); +} + +void SpectraCamera::camera_map_bufs() { + int ret; + for (int i = 0; i < FRAME_BUF_COUNT; i++) { + // configure ISP to put the image in place + struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0}; + mem_mgr_map_cmd.mmu_hdls[0] = m->device_iommu; + //mem_mgr_map_cmd.mmu_hdls[1] = m->icp_device_iommu; + //mem_mgr_map_cmd.num_hdl = 2; + mem_mgr_map_cmd.num_hdl = 1; + mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE; + + // RAW bayer images + mem_mgr_map_cmd.fd = buf.camera_bufs_raw[i].fd; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); + assert(ret == 0); + LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs_raw[i].fd, mem_mgr_map_cmd.out.buf_handle, ret); + buf_handle_raw[i] = mem_mgr_map_cmd.out.buf_handle; + + // TODO: this needs to match camera bufs length + // final processed images + VisionBuf *vb = buf.vipc_server->get_buffer(buf.stream_type, i); + mem_mgr_map_cmd.fd = vb->fd; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); + LOGD("map buf req: (fd: %d) 0x%x %d", vb->fd, mem_mgr_map_cmd.out.buf_handle, ret); + buf_handle_yuv[i] = mem_mgr_map_cmd.out.buf_handle; + } + enqueue_req_multi(1, FRAME_BUF_COUNT, 0); +} + +bool SpectraCamera::openSensor() { + sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", cc.camera_num); + assert(sensor_fd >= 0); + LOGD("opened sensor for %d", cc.camera_num); + + LOGD("-- Probing sensor %d", cc.camera_num); + + auto init_sensor_lambda = [this](SensorInfo *s) { + sensor.reset(s); + return (sensors_init() == 0); + }; + + // Figure out which sensor we have + if (!init_sensor_lambda(new AR0231) && + !init_sensor_lambda(new OX03C10) && + !init_sensor_lambda(new OS04C10)) { + LOGE("** sensor %d FAILED bringup, disabling", cc.camera_num); + enabled = false; + return false; + } + LOGD("-- Probing sensor %d success", cc.camera_num); + + // create session + struct cam_req_mgr_session_info session_info = {}; + int ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &session_info, sizeof(session_info)); + LOGD("get session: %d 0x%X", ret, session_info.session_hdl); + session_handle = session_info.session_hdl; + + // access the sensor + LOGD("-- Accessing sensor"); + auto sensor_dev_handle_ = device_acquire(sensor_fd, session_handle, nullptr); + assert(sensor_dev_handle_); + sensor_dev_handle = *sensor_dev_handle_; + LOGD("acquire sensor dev"); + + LOG("-- Configuring sensor"); + sensors_i2c(sensor->init_reg_array.data(), sensor->init_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, sensor->data_word); + return true; +} + +void SpectraCamera::configISP() { + if (!enabled) return; + + struct cam_isp_in_port_info in_port_info = { + // ISP input to the CSID + .res_type = cc.phy, + .lane_type = CAM_ISP_LANE_TYPE_DPHY, + .lane_num = 4, + .lane_cfg = 0x3210, + + .vc = 0x0, + .dt = sensor->frame_data_type, + .format = sensor->mipi_format, + + .test_pattern = sensor->bayer_pattern, + .usage_type = 0x0, + + .left_start = 0, + .left_stop = sensor->frame_width - 1, + .left_width = sensor->frame_width, + + .right_start = 0, + .right_stop = sensor->frame_width - 1, + .right_width = sensor->frame_width, + + .line_start = sensor->frame_offset, + .line_stop = sensor->frame_height + sensor->frame_offset - 1, + .height = sensor->frame_height + sensor->frame_offset, + + .pixel_clk = 0x0, + .batch_size = 0x0, + .dsp_mode = CAM_ISP_DSP_MODE_NONE, + .hbi_cnt = 0x0, + .custom_csid = 0x0, + + // ISP outputs + .num_out_res = 0x1, + .data[0] = (struct cam_isp_out_port_info){ + .res_type = CAM_ISP_IFE_OUT_RES_FULL, + .format = CAM_FORMAT_NV12, + .width = sensor->frame_width, + .height = sensor->frame_height + sensor->extra_height, + .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, + }, + }; + + if (is_raw) { + in_port_info.line_start = 0; + in_port_info.line_stop = sensor->frame_height + sensor->extra_height - 1; + in_port_info.height = sensor->frame_height + sensor->extra_height; + + in_port_info.data[0].res_type = CAM_ISP_IFE_OUT_RES_RDI_0; + in_port_info.data[0].format = sensor->mipi_format; + } + + 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), + }; + + auto isp_dev_handle_ = device_acquire(m->isp_fd, session_handle, &isp_resource); + assert(isp_dev_handle_); + isp_dev_handle = *isp_dev_handle_; + LOGD("acquire isp dev"); + + // allocate IFE memory, then configure it + ife_cmd.init(m, 67984, 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, + m->device_iommu, m->cdm_iommu, FRAME_BUF_COUNT); + if (!is_raw) { + ife_gamma_lut.init(m, 64*sizeof(uint32_t), 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, + m->device_iommu, m->cdm_iommu, 3); // 3 for RGB + for (int i = 0; i < 3; i++) { + memcpy(ife_gamma_lut.ptr + ife_gamma_lut.size*i, sensor->gamma_lut_rgb.data(), ife_gamma_lut.size); + } + ife_linearization_lut.init(m, sensor->linearization_lut.size(), 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, + m->device_iommu, m->cdm_iommu); + memcpy(ife_linearization_lut.ptr, sensor->linearization_lut.data(), ife_linearization_lut.size); + ife_vignetting_lut.init(m, sensor->vignetting_lut.size(), 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, + m->device_iommu, m->cdm_iommu, 2); + memcpy(ife_vignetting_lut.ptr, sensor->vignetting_lut.data(), ife_vignetting_lut.size*2); + } + + config_ife(0, 1, true); +} + +void SpectraCamera::configICP() { + if (!enabled) return; + + /* + Configures both the ICP and BPS. + */ + + struct cam_icp_acquire_dev_info icp_info = { + .scratch_mem_size = 0x0, + .dev_type = 0x1, // BPS + .io_config_cmd_size = 0, + .io_config_cmd_handle = 0, + .secure_mode = 0, + .num_out_res = 1, + .in_res = (struct cam_icp_res_info){ + .format = 0x9, // RAW MIPI + .width = sensor->frame_width, + .height = sensor->frame_height, + .fps = 20, + }, + .out_res[0] = (struct cam_icp_res_info){ + .format = 0x3, // YUV420NV12 + .width = sensor->frame_width, + .height = sensor->frame_height, + .fps = 20, + }, + }; + auto h = device_acquire(m->icp_fd, session_handle, &icp_info); + assert(h); + icp_dev_handle = *h; + LOGD("acquire icp dev"); + + // BPS CMD buffer + unsigned char striping_out[] = "\x00"; + bps_cmd.init(m, FRAME_BUF_COUNT*ALIGNED_SIZE(464, 0x20), 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE | CAM_MEM_FLAG_HW_SHARED_ACCESS, + m->icp_device_iommu); + + bps_iq.init(m, 560, 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE | CAM_MEM_FLAG_HW_SHARED_ACCESS, + m->icp_device_iommu); + bps_cdm_program_array.init(m, 0x40, 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE | CAM_MEM_FLAG_HW_SHARED_ACCESS, + m->icp_device_iommu); + bps_striping.init(m, sizeof(striping_out), 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE | CAM_MEM_FLAG_HW_SHARED_ACCESS, + m->icp_device_iommu); + memcpy(bps_striping.ptr, striping_out, sizeof(striping_out)); + + bps_cdm_striping_bl.init(m, 65216, 0x20, + CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE | CAM_MEM_FLAG_HW_SHARED_ACCESS, + m->icp_device_iommu); +} + +void SpectraCamera::configCSIPHY() { + csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", cc.camera_num); + assert(csiphy_fd >= 0); + LOGD("opened csiphy for %d", cc.camera_num); + + struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {.combo_mode = 0}; + auto csiphy_dev_handle_ = device_acquire(csiphy_fd, session_handle, &csiphy_acquire_dev_info); + assert(csiphy_dev_handle_); + csiphy_dev_handle = *csiphy_dev_handle_; + LOGD("acquire csiphy dev"); + + // config csiphy + LOG("-- Config CSI PHY"); + { + uint32_t cam_packet_handle = 0; + int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; + auto pkt = mm.alloc(size, &cam_packet_handle); + pkt->num_cmd_buf = 1; + pkt->kmd_cmd_buf_index = -1; + pkt->header.size = size; + struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; + + buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info); + buf_desc[0].type = CAM_CMD_BUF_GENERIC; + + auto csiphy_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); + csiphy_info->lane_mask = 0x1f; + csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels?? + csiphy_info->csiphy_3phase = 0x0; // no 3 phase, only 2 conductors per lane + csiphy_info->combo_mode = 0x0; + csiphy_info->lane_cnt = 0x4; + csiphy_info->secure_mode = 0x0; + csiphy_info->settle_time = MIPI_SETTLE_CNT * 200000000ULL; + csiphy_info->data_rate = 48000000; // Calculated by camera_freqs.py + + int ret_ = device_config(csiphy_fd, session_handle, csiphy_dev_handle, cam_packet_handle); + assert(ret_ == 0); + } +} + +void SpectraCamera::linkDevices() { + LOG("-- Link devices"); + struct cam_req_mgr_link_info req_mgr_link_info = {0}; + req_mgr_link_info.session_hdl = session_handle; + req_mgr_link_info.num_devices = 2; + req_mgr_link_info.dev_hdls[0] = isp_dev_handle; + req_mgr_link_info.dev_hdls[1] = sensor_dev_handle; + int ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_LINK, &req_mgr_link_info, sizeof(req_mgr_link_info)); + link_handle = req_mgr_link_info.link_hdl; + LOGD("link: %d session: 0x%X isp: 0x%X sensors: 0x%X link: 0x%X", ret, session_handle, isp_dev_handle, sensor_dev_handle, link_handle); + + struct cam_req_mgr_link_control req_mgr_link_control = {0}; + req_mgr_link_control.ops = CAM_REQ_MGR_LINK_ACTIVATE; + req_mgr_link_control.session_hdl = session_handle; + req_mgr_link_control.num_links = 1; + req_mgr_link_control.link_hdls[0] = link_handle; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); + LOGD("link control: %d", ret); + + ret = device_control(csiphy_fd, CAM_START_DEV, session_handle, csiphy_dev_handle); + LOGD("start csiphy: %d", ret); + ret = device_control(m->isp_fd, CAM_START_DEV, session_handle, isp_dev_handle); + LOGD("start isp: %d", ret); + assert(ret == 0); +} + +void SpectraCamera::camera_close() { + LOG("-- Stop devices %d", cc.camera_num); + + if (enabled) { + // ret = device_control(sensor_fd, CAM_STOP_DEV, session_handle, sensor_dev_handle); + // LOGD("stop sensor: %d", ret); + int ret = device_control(m->isp_fd, CAM_STOP_DEV, session_handle, isp_dev_handle); + LOGD("stop isp: %d", ret); + ret = device_control(csiphy_fd, CAM_STOP_DEV, session_handle, csiphy_dev_handle); + LOGD("stop csiphy: %d", ret); + // link control stop + LOG("-- Stop link control"); + struct cam_req_mgr_link_control req_mgr_link_control = {0}; + req_mgr_link_control.ops = CAM_REQ_MGR_LINK_DEACTIVATE; + req_mgr_link_control.session_hdl = session_handle; + req_mgr_link_control.num_links = 1; + req_mgr_link_control.link_hdls[0] = link_handle; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); + LOGD("link control stop: %d", ret); + + // unlink + LOG("-- Unlink"); + struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0}; + req_mgr_unlink_info.session_hdl = session_handle; + req_mgr_unlink_info.link_hdl = link_handle; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_UNLINK, &req_mgr_unlink_info, sizeof(req_mgr_unlink_info)); + LOGD("unlink: %d", ret); + + // release devices + LOGD("-- Release devices"); + ret = device_control(m->isp_fd, CAM_RELEASE_DEV, session_handle, isp_dev_handle); + LOGD("release isp: %d", ret); + ret = device_control(csiphy_fd, CAM_RELEASE_DEV, session_handle, csiphy_dev_handle); + LOGD("release csiphy: %d", ret); + + for (int i = 0; i < FRAME_BUF_COUNT; i++) { + release(m->video0_fd, buf_handle_yuv[i]); + release(m->video0_fd, buf_handle_raw[i]); + } + LOGD("released buffers"); + } + + int ret = device_control(sensor_fd, CAM_RELEASE_DEV, session_handle, sensor_dev_handle); + LOGD("release sensor: %d", ret); + + // destroyed session + struct cam_req_mgr_session_info session_info = {.session_hdl = session_handle}; + ret = do_cam_control(m->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &session_info, sizeof(session_info)); + LOGD("destroyed session %d: %d", cc.camera_num, ret); +} + +void SpectraCamera::handle_camera_event(const cam_req_mgr_message *event_data) { + if (!enabled) return; + + uint64_t timestamp = event_data->u.frame_msg.timestamp; + uint64_t main_id = event_data->u.frame_msg.frame_id; + uint64_t real_id = event_data->u.frame_msg.request_id; + + if (real_id != 0) { // next ready + if (real_id == 1) {idx_offset = main_id;} + int buf_idx = (real_id - 1) % FRAME_BUF_COUNT; + + // check for skipped frames + if (main_id > frame_id_last + 1 && !skipped) { + LOGE("camera %d realign", cc.camera_num); + clear_req_queue(); + enqueue_req_multi(real_id + 1, FRAME_BUF_COUNT - 1, 0); + skipped = true; + } else if (main_id == frame_id_last + 1) { + skipped = false; + } + + // check for dropped requests + if (real_id > request_id_last + 1) { + LOGE("camera %d dropped requests %ld %ld", cc.camera_num, real_id, request_id_last); + enqueue_req_multi(request_id_last + 1 + FRAME_BUF_COUNT, real_id - (request_id_last + 1), 0); + } + + // metas + frame_id_last = main_id; + request_id_last = real_id; + + auto &meta_data = buf.frame_metadata[buf_idx]; + meta_data.frame_id = main_id - idx_offset; + meta_data.request_id = real_id; + meta_data.timestamp_sof = timestamp; // this is timestamped in the kernel's SOF IRQ callback + + // dispatch + enqueue_req_multi(real_id + FRAME_BUF_COUNT, 1, 1); + } else { // not ready + if (main_id > frame_id_last + 10) { + LOGE("camera %d reset after half second of no response", cc.camera_num); + clear_req_queue(); + enqueue_req_multi(request_id_last + 1, FRAME_BUF_COUNT, 0); + frame_id_last = main_id; + skipped = true; + } + } +} diff --git a/system/camerad/cameras/spectra.h b/system/camerad/cameras/spectra.h new file mode 100644 index 000000000000000..ea5c56316700653 --- /dev/null +++ b/system/camerad/cameras/spectra.h @@ -0,0 +1,169 @@ +#pragma once + +#include +#include +#include +#include + +#include "media/cam_req_mgr.h" + +#include "common/util.h" +#include "system/camerad/cameras/tici.h" +#include "system/camerad/cameras/camera_common.h" +#include "system/camerad/sensors/sensor.h" + +#define FRAME_BUF_COUNT 4 + +const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py + +// For use with the Titan 170 ISP in the SDM845 +// https://github.com/commaai/agnos-kernel-sdm845 + + +// CSLDeviceType/CSLPacketOpcodesIFE from camx +// cam_packet_header.op_code = (device << 24) | (opcode); +#define CSLDeviceTypeImageSensor (0x1 << 24) +#define CSLDeviceTypeIFE (0xF << 24) +#define OpcodesIFEInitialConfig 0x0 +#define OpcodesIFEUpdate 0x1 + +std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1); +int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle); +int device_control(int fd, int op_code, int session_handle, int dev_handle); +int do_cam_control(int fd, int op_code, void *handle, int size); +void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, + int mmu_hdl = 0, int mmu_hdl2 = 0); +void release(int video0_fd, uint32_t handle); + +class MemoryManager { +public: + void init(int _video0_fd) { video0_fd = _video0_fd; } + ~MemoryManager(); + + template + auto alloc(int len, uint32_t *handle) { + return std::unique_ptr>((T*)alloc_buf(len, handle), [this](void *ptr) { this->free(ptr); }); + } + +private: + void *alloc_buf(int len, uint32_t *handle); + void free(void *ptr); + + std::mutex lock; + std::map handle_lookup; + std::map size_lookup; + std::map > cached_allocations; + int video0_fd; +}; + +class SpectraMaster { +public: + void init(); + + unique_fd video0_fd; + unique_fd cam_sync_fd; + unique_fd isp_fd; + unique_fd icp_fd; + int device_iommu = -1; + int cdm_iommu = -1; + int icp_device_iommu = -1; +}; + +class SpectraBuf { +public: + void init(SpectraMaster *m, int s, int a, int flags, int mmu_hdl = 0, int mmu_hdl2 = 0, int count=1) { + size = s; + alignment = a; + void *p = alloc_w_mmu_hdl(m->video0_fd, ALIGNED_SIZE(size, alignment)*count, (uint32_t*)&handle, alignment, flags, mmu_hdl, mmu_hdl2); + ptr = (unsigned char*)p; + assert(ptr != NULL); + }; + + uint32_t aligned_size() { + return ALIGNED_SIZE(size, alignment); + }; + + unsigned char *ptr; + int size, alignment, handle; +}; + +class SpectraCamera { +public: + SpectraCamera(SpectraMaster *master, const CameraConfig &config, bool raw); + ~SpectraCamera(); + + void camera_open(VisionIpcServer *v, cl_device_id device_id, cl_context ctx); + void handle_camera_event(const cam_req_mgr_message *event_data); + void camera_close(); + void camera_map_bufs(); + void config_bps(int idx, int request_id); + void config_ife(int idx, int request_id, bool init=false); + + int clear_req_queue(); + void enqueue_buffer(int i, bool dp); + void enqueue_req_multi(uint64_t start, int n, bool dp); + + int sensors_init(); + void sensors_start(); + void sensors_poke(int request_id); + void sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); + + bool openSensor(); + void configISP(); + void configICP(); + void configCSIPHY(); + void linkDevices(); + + // *** state *** + + bool open = false; + bool enabled = true; + CameraConfig cc; + std::unique_ptr sensor; + + // YUV image size + uint32_t stride; + uint32_t y_height; + uint32_t uv_height; + uint32_t uv_offset; + uint32_t yuv_size; + + unique_fd sensor_fd; + unique_fd csiphy_fd; + + int32_t session_handle = -1; + int32_t sensor_dev_handle = -1; + int32_t isp_dev_handle = -1; + int32_t icp_dev_handle = -1; + int32_t csiphy_dev_handle = -1; + + int32_t link_handle = -1; + + SpectraBuf ife_cmd; + SpectraBuf ife_gamma_lut; + SpectraBuf ife_linearization_lut; + SpectraBuf ife_vignetting_lut; + + SpectraBuf bps_cmd; + SpectraBuf bps_cdm_buffer; + SpectraBuf bps_cdm_program_array; + SpectraBuf bps_cdm_striping_bl; + SpectraBuf bps_iq; + SpectraBuf bps_striping; + + int buf_handle_yuv[FRAME_BUF_COUNT] = {}; + int buf_handle_raw[FRAME_BUF_COUNT] = {}; + int sync_objs[FRAME_BUF_COUNT] = {}; + int sync_objs_bps_out[FRAME_BUF_COUNT] = {}; + uint64_t request_ids[FRAME_BUF_COUNT] = {}; + uint64_t request_id_last = 0; + uint64_t frame_id_last = 0; + uint64_t idx_offset = 0; + bool skipped = true; + + bool is_raw; + + CameraBuf buf; + MemoryManager mm; + SpectraMaster *m; +}; diff --git a/system/camerad/cameras/tici.h b/system/camerad/cameras/tici.h new file mode 100644 index 000000000000000..d0b2aece6d84cc4 --- /dev/null +++ b/system/camerad/cameras/tici.h @@ -0,0 +1,51 @@ +#pragma once + +#include "common/util.h" +#include "cereal/gen/cpp/log.capnp.h" +#include "msgq/visionipc/visionipc_server.h" + +#include "media/cam_isp_ife.h" + +// For the comma 3/3X three camera platform + +struct CameraConfig { + int camera_num; + VisionStreamType stream_type; + float focal_len; // millimeters + const char *publish_name; + cereal::FrameData::Builder (cereal::Event::Builder::*init_camera_state)(); + bool enabled; + uint32_t phy; +}; + +// 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!) +const CameraConfig WIDE_ROAD_CAMERA_CONFIG = { + .camera_num = 0, + .stream_type = VISION_STREAM_WIDE_ROAD, + .focal_len = 1.71, + .publish_name = "wideRoadCameraState", + .init_camera_state = &cereal::Event::Builder::initWideRoadCameraState, + .enabled = !getenv("DISABLE_WIDE_ROAD"), + .phy = CAM_ISP_IFE_IN_RES_PHY_0, +}; + +const CameraConfig ROAD_CAMERA_CONFIG = { + .camera_num = 1, + .stream_type = VISION_STREAM_ROAD, + .focal_len = 8.0, + .publish_name = "roadCameraState", + .init_camera_state = &cereal::Event::Builder::initRoadCameraState, + .enabled = !getenv("DISABLE_ROAD"), + .phy = CAM_ISP_IFE_IN_RES_PHY_1, +}; + +const CameraConfig DRIVER_CAMERA_CONFIG = { + .camera_num = 2, + .stream_type = VISION_STREAM_DRIVER, + .focal_len = 1.71, + .publish_name = "driverCameraState", + .init_camera_state = &cereal::Event::Builder::initDriverCameraState, + .enabled = !getenv("DISABLE_DRIVER"), + .phy = CAM_ISP_IFE_IN_RES_PHY_2, +}; diff --git a/system/camerad/main.cc b/system/camerad/main.cc index b86b4f57ff737e5..d55bd495adb83ae 100644 --- a/system/camerad/main.cc +++ b/system/camerad/main.cc @@ -4,14 +4,8 @@ #include "common/params.h" #include "common/util.h" -#include "system/hardware/hw.h" int main(int argc, char *argv[]) { - if (Hardware::PC()) { - printf("exiting, camerad is not meant to run on PC\n"); - return 0; - } - int ret = util::set_realtime_priority(53); assert(ret == 0); ret = util::set_core_affinity({6}); diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc index 9b688389c4460bf..5234ebd4185d692 100644 --- a/system/camerad/sensors/ar0231.cc +++ b/system/camerad/sensors/ar0231.cc @@ -1,8 +1,7 @@ #include +#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 { @@ -17,7 +16,7 @@ const float sensor_analog_gains_AR0231[] = { 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) { +std::map> ar0231_build_register_lut(const AR0231 *s, 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. @@ -33,7 +32,7 @@ std::map> ar0231_build_register_lut(CameraState *c std::map> registers; for (int register_row = 0; register_row < 2; register_row++) { - uint8_t *registers_raw = data + c->ci->frame_stride * register_row; + uint8_t *registers_raw = data + s->frame_stride * register_row; assert(registers_raw[0] == 0x0a); // Start of line int value_tag_count = 0; @@ -58,7 +57,7 @@ std::map> ar0231_build_register_lut(CameraState *c 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); + registers[cur_addr] = std::make_pair(first_val_idx + s->frame_stride * register_row, val_idx + s->frame_stride * register_row); } value_tag_count++; @@ -79,6 +78,7 @@ float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_r AR0231::AR0231() { image_sensor = cereal::FrameData::ImageSensor::AR0231; + bayer_pattern = CAM_ISP_PATTERN_BAYER_GRGRGR; pixel_size_mm = 0.003; data_word = true; frame_width = 1928; @@ -94,10 +94,13 @@ AR0231::AR0231() { init_reg_array.assign(std::begin(init_array_ar0231), std::end(init_array_ar0231)); probe_reg_addr = 0x3000; probe_expected_data = 0x354; + bits_per_pixel = 12; 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 + readout_time_ns = 22850000; + dc_gain_factor = 2.5; dc_gain_min_weight = 0; dc_gain_max_weight = 1; @@ -117,11 +120,49 @@ AR0231::AR0231() { 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; + + black_level = 168; + color_correct_matrix = { + 0x000000af, 0x00000ff9, 0x00000fd8, + 0x00000fbc, 0x000000bb, 0x00000009, + 0x00000fb6, 0x00000fe0, 0x000000ea, + }; + for (int i = 0; i < 65; i++) { + float fx = i / 64.0; + const float gamma_k = 0.75; + const float gamma_b = 0.125; + const float mp = 0.01; // ideally midpoint should be adaptive + const float rk = 9 - 100*mp; + // poly approximation for s curve + fx = (fx > mp) ? + ((rk * (fx-mp) * (1-(gamma_k*mp+gamma_b)) * (1+1/(rk*(1-mp))) / (1+rk*(fx-mp))) + gamma_k*mp + gamma_b) : + ((rk * (fx-mp) * (gamma_k*mp+gamma_b) * (1+1/(rk*mp)) / (1-rk*(fx-mp))) + gamma_k*mp + gamma_b); + gamma_lut_rgb.push_back((uint32_t)(fx*1023.0 + 0.5)); + } + prepare_gamma_lut(); + linearization_lut = { + 0x02000000, 0x02000000, 0x02000000, 0x02000000, + 0x020007ff, 0x020007ff, 0x020007ff, 0x020007ff, + 0x02000bff, 0x02000bff, 0x02000bff, 0x02000bff, + 0x020017ff, 0x020017ff, 0x020017ff, 0x020017ff, + 0x02001bff, 0x02001bff, 0x02001bff, 0x02001bff, + 0x020023ff, 0x020023ff, 0x020023ff, 0x020023ff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + }; + for (int i = 0; i < 252; i++) { + linearization_lut.push_back(0x0); + } + linearization_pts = {0x07ff0bff, 0x17ff1bff, 0x23ff3fff, 0x3fff3fff}; + for (int i = 0; i < 884*2; i++) { + vignetting_lut.push_back(0xff); + } } -void AR0231::processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const { +void AR0231::processRegisters(uint8_t *cur_buf, 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; + uint8_t *data = cur_buf + registers_offset; if (memcmp(data, expected_preamble, std::size(expected_preamble)) != 0) { LOGE("unexpected register data found"); @@ -129,7 +170,7 @@ void AR0231::processRegisters(CameraState *c, cereal::FrameData::Builder &framed } if (ar0231_register_lut.empty()) { - ar0231_register_lut = ar0231_build_register_lut(c, data); + ar0231_register_lut = ar0231_build_register_lut(this, data); } std::map registers; for (uint16_t addr : {0x2000, 0x2002, 0x20b0, 0x20b2, 0x30c6, 0x30c8, 0x30ca, 0x30cc}) { diff --git a/system/camerad/sensors/ar0231_registers.h b/system/camerad/sensors/ar0231_registers.h index 6c4c251e8ea11a6..e0872a673a09c2a 100644 --- a/system/camerad/sensors/ar0231_registers.h +++ b/system/camerad/sensors/ar0231_registers.h @@ -6,6 +6,8 @@ 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 + // **NOTE**: if this is changed, readout_time_ns must be updated in the Sensor config + // CLOCK Settings // input clock is 19.2 / 2 * 0x37 = 528 MHz // pixclk is 528 / 6 = 88 MHz diff --git a/system/camerad/sensors/os04c10.cc b/system/camerad/sensors/os04c10.cc index 97a317407ab1e1a..f6ba4504e197b80 100644 --- a/system/camerad/sensors/os04c10.cc +++ b/system/camerad/sensors/os04c10.cc @@ -1,3 +1,5 @@ +#include + #include "system/camerad/sensors/sensor.h" namespace { @@ -20,13 +22,14 @@ const uint32_t os04c10_analog_gains_reg[] = { OS04C10::OS04C10() { image_sensor = cereal::FrameData::ImageSensor::OS04C10; - pixel_size_mm = 0.002; + bayer_pattern = CAM_ISP_PATTERN_BAYER_BGBGBG; + pixel_size_mm = 0.004; data_word = false; - hdr_offset = 64 * 2 + 8; // stagger - frame_width = 2688; - frame_height = 1520 * 2 + hdr_offset; - frame_stride = (frame_width * 10 / 8); // no alignment + // hdr_offset = 64 * 2 + 8; // stagger + frame_width = 1344; + frame_height = 760; //760 * 2 + hdr_offset; + frame_stride = (frame_width * 12 / 8); // no alignment extra_height = 0; frame_offset = 0; @@ -35,8 +38,9 @@ OS04C10::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; + bits_per_pixel = 12; + mipi_format = CAM_FORMAT_MIPI_RAW_12; + frame_data_type = 0x2c; mclk_frequency = 24000000; // Hz dc_gain_factor = 1; @@ -58,6 +62,36 @@ OS04C10::OS04C10() { 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 = 0.01; + + black_level = 64; + color_correct_matrix = { + 0x000000c2, 0x00000fe0, 0x00000fde, + 0x00000fa7, 0x000000d9, 0x00001000, + 0x00000fca, 0x00000fef, 0x000000c7, + }; + for (int i = 0; i < 65; i++) { + float fx = i / 64.0; + gamma_lut_rgb.push_back((uint32_t)((10*fx)/(1+9*fx)*1023.0 + 0.5)); + } + prepare_gamma_lut(); + linearization_lut = { + 0x02000000, 0x02000000, 0x02000000, 0x02000000, + 0x020007ff, 0x020007ff, 0x020007ff, 0x020007ff, + 0x02000bff, 0x02000bff, 0x02000bff, 0x02000bff, + 0x020017ff, 0x020017ff, 0x020017ff, 0x020017ff, + 0x02001bff, 0x02001bff, 0x02001bff, 0x02001bff, + 0x020023ff, 0x020023ff, 0x020023ff, 0x020023ff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + }; + for (int i = 0; i < 252; i++) { + linearization_lut.push_back(0x0); + } + linearization_pts = {0x07ff0bff, 0x17ff1bff, 0x23ff3fff, 0x3fff3fff}; + for (int i = 0; i < 884*2; i++) { + vignetting_lut.push_back(0xff); + } } std::vector OS04C10::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { diff --git a/system/camerad/sensors/os04c10_cl.h b/system/camerad/sensors/os04c10_cl.h index 61775dcdc8c8932..e285fb37e0bbdc7 100644 --- a/system/camerad/sensors/os04c10_cl.h +++ b/system/camerad/sensors/os04c10_cl.h @@ -2,8 +2,9 @@ #define BGGR -#define BIT_DEPTH 10 +#define BIT_DEPTH 12 #define PV_MAX10 1023 +#define PV_MAX12 4096 #define PV_MAX16 65536 // gamma curve is calibrated to 16bit #define BLACK_LVL 64 #define VIGNETTE_RSZ 2.2545f @@ -38,6 +39,11 @@ float4 normalize_pv_hdr(int4 parsed, int4 short_parsed, float vignette_factor, i return clamp(pv*vignette_factor, 0.0, 1.0); } +float4 normalize_pv(int4 parsed, float vignette_factor) { + float4 pv = (convert_float4(parsed) - BLACK_LVL) / (PV_MAX12 - BLACK_LVL); + return clamp(pv*vignette_factor, 0.0, 1.0); +} + float3 color_correct(float3 rgb) { float3 corrected = rgb.x * (float3)(1.55361989, -0.268894615, -0.000593219); corrected += rgb.y * (float3)(-0.421217301, 1.51883144, -0.69760146); @@ -46,10 +52,7 @@ float3 color_correct(float3 rgb) { } float3 apply_gamma(float3 rgb, int expo_time) { - float s = log2((float)expo_time); - if (s < 6) {s = fmin(12.0 - s, 9.0);} - // log function adaptive to number of bits - return clamp(log(1 + rgb*(PV_MAX16 - BLACK_LVL)) * (0.48*s*s - 12.92*s + 115.0) - (1.08*s*s - 29.2*s + 260.0), 0.0, 255.0) / 255.0; + return (10 * rgb) / (1 + 9 * rgb); } #endif diff --git a/system/camerad/sensors/os04c10_registers.h b/system/camerad/sensors/os04c10_registers.h index 91eb48b24f6d544..53e80e079fabde5 100644 --- a/system/camerad/sensors/os04c10_registers.h +++ b/system/camerad/sensors/os04c10_registers.h @@ -8,14 +8,14 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x0103, 0x01}, // PLL - {0x0301, 0x84}, + {0x0301, 0xe4}, {0x0303, 0x01}, - {0x0305, 0x61}, + {0x0305, 0xb6}, {0x0306, 0x01}, {0x0307, 0x17}, {0x0323, 0x04}, {0x0324, 0x01}, - {0x0325, 0x7a}, + {0x0325, 0x62}, {0x3012, 0x06}, {0x3013, 0x02}, @@ -30,40 +30,40 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x3660, 0x04}, {0x3666, 0xa5}, {0x3667, 0xa5}, - {0x366a, 0x54}, + {0x366a, 0x50}, {0x3673, 0x0d}, {0x3672, 0x0d}, {0x3671, 0x0d}, {0x3670, 0x0d}, - {0x3685, 0x0a}, + {0x3685, 0x00}, {0x3694, 0x0d}, {0x3693, 0x0d}, {0x3692, 0x0d}, {0x3691, 0x0d}, {0x3696, 0x4c}, {0x3697, 0x4c}, - {0x3698, 0x00}, + {0x3698, 0x40}, {0x3699, 0x80}, - {0x369a, 0x80}, + {0x369a, 0x18}, {0x369b, 0x1f}, - {0x369c, 0x1f}, + {0x369c, 0x14}, {0x369d, 0x80}, {0x369e, 0x40}, {0x369f, 0x21}, {0x36a0, 0x12}, - {0x36a1, 0xdd}, + {0x36a1, 0x5d}, {0x36a2, 0x66}, - {0x370a, 0x00}, - {0x370e, 0x00}, + {0x370a, 0x02}, + {0x370e, 0x0c}, {0x3710, 0x00}, - {0x3713, 0x04}, + {0x3713, 0x00}, {0x3725, 0x02}, {0x372a, 0x03}, {0x3738, 0xce}, - {0x3748, 0x00}, - {0x374a, 0x00}, - {0x374c, 0x00}, - {0x374e, 0x00}, + {0x3748, 0x02}, + {0x374a, 0x02}, + {0x374c, 0x02}, + {0x374e, 0x02}, {0x3756, 0x00}, {0x3757, 0x00}, {0x3767, 0x00}, @@ -81,11 +81,11 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x37ba, 0x03}, {0x37bb, 0x00}, {0x37bc, 0x04}, - {0x37be, 0x26}, + {0x37be, 0x08}, {0x37c4, 0x11}, {0x37c5, 0x80}, {0x37c6, 0x14}, - {0x37c7, 0xa8}, + {0x37c7, 0x08}, {0x37da, 0x11}, {0x381f, 0x08}, // {0x3829, 0x03}, @@ -95,7 +95,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x388b, 0x00}, {0x3c80, 0x10}, {0x3c86, 0x00}, - // {0x3c8c, 0x20}, + {0x3c8c, 0x20}, {0x3c9f, 0x01}, {0x3d85, 0x1b}, {0x3d8c, 0x71}, @@ -111,7 +111,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x4045, 0x7e}, {0x4047, 0x7e}, {0x4049, 0x7e}, - {0x4090, 0x14}, + {0x4090, 0x04}, {0x40b0, 0x00}, {0x40b1, 0x00}, {0x40b2, 0x00}, @@ -129,7 +129,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x4503, 0x00}, {0x4504, 0x06}, {0x4506, 0x00}, - {0x4507, 0x57}, + {0x4507, 0x47}, {0x4803, 0x00}, {0x480c, 0x32}, {0x480e, 0x04}, @@ -139,7 +139,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x4823, 0x3f}, {0x4825, 0x30}, {0x4833, 0x10}, - {0x484b, 0x07}, + {0x484b, 0x27}, {0x488b, 0x00}, {0x4d00, 0x04}, {0x4d01, 0xad}, @@ -152,7 +152,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x4e0d, 0x00}, // ISP - {0x5001, 0x00}, + {0x5001, 0x09}, {0x5004, 0x00}, {0x5080, 0x04}, {0x5036, 0x80}, @@ -173,52 +173,52 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x301c, 0xf8}, {0x301e, 0xb4}, {0x301f, 0xf0}, - {0x3022, 0x01}, + {0x3022, 0x61}, {0x3109, 0xe7}, {0x3600, 0x00}, - {0x3610, 0x75}, + {0x3610, 0x65}, {0x3611, 0x85}, {0x3613, 0x3a}, {0x3615, 0x60}, - {0x3621, 0x90}, + {0x3621, 0xb0}, {0x3620, 0x0c}, {0x3629, 0x00}, {0x3661, 0x04}, {0x3664, 0x70}, {0x3665, 0x00}, - {0x3681, 0x80}, - {0x3682, 0x40}, - {0x3683, 0x21}, - {0x3684, 0x12}, + {0x3681, 0xa6}, + {0x3682, 0x53}, + {0x3683, 0x2a}, + {0x3684, 0x15}, {0x3700, 0x2a}, {0x3701, 0x12}, {0x3703, 0x28}, {0x3704, 0x0e}, - {0x3706, 0x4a}, + {0x3706, 0x9d}, {0x3709, 0x4a}, - {0x370b, 0xa2}, + {0x370b, 0x48}, {0x370c, 0x01}, - {0x370f, 0x00}, - {0x3714, 0x24}, + {0x370f, 0x04}, + {0x3714, 0x28}, {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}, + {0x3741, 0x9d}, + {0x3743, 0x9d}, + {0x3745, 0x9d}, + {0x3747, 0x9d}, + {0x3749, 0x48}, + {0x374b, 0x48}, + {0x374d, 0x48}, + {0x374f, 0x48}, {0x3755, 0x10}, {0x376c, 0x00}, - {0x378d, 0x30}, - {0x3790, 0x4a}, - {0x3791, 0xa2}, + {0x378d, 0x3c}, + {0x3790, 0x01}, + {0x3791, 0x01}, {0x3798, 0x40}, {0x379e, 0x00}, {0x379f, 0x04}, @@ -231,24 +231,24 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x37bd, 0x01}, {0x37bf, 0x26}, {0x37c0, 0x11}, - {0x37c2, 0x04}, + {0x37c2, 0x14}, {0x37cd, 0x19}, - // {0x37e0, 0x08}, - // {0x37e6, 0x04}, + {0x37e0, 0x08}, + {0x37e6, 0x04}, {0x37e5, 0x02}, - // {0x37e1, 0x0c}, - // {0x3737, 0x04}, + {0x37e1, 0x0c}, + {0x3737, 0x04}, {0x37d8, 0x02}, - // {0x37e2, 0x10}, + {0x37e2, 0x10}, {0x3739, 0x10}, - {0x3662, 0x10}, - // {0x37e4, 0x20}, - // {0x37e3, 0x08}, - {0x37d9, 0x08}, + {0x3662, 0x08}, + {0x37e4, 0x20}, + {0x37e3, 0x08}, + {0x37d9, 0x04}, {0x4040, 0x00}, - {0x4041, 0x07}, - {0x4008, 0x02}, - {0x4009, 0x0d}, + {0x4041, 0x03}, + {0x4008, 0x01}, + {0x4009, 0x06}, // FSIN {0x3002, 0x22}, @@ -269,36 +269,36 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { {0x3802, 0x00}, {0x3803, 0x00}, {0x3804, 0x0a}, {0x3805, 0x8f}, {0x3806, 0x05}, {0x3807, 0xff}, - {0x3808, 0x0a}, {0x3809, 0x80}, - {0x380a, 0x05}, {0x380b, 0xf0}, + {0x3808, 0x05}, {0x3809, 0x40}, + {0x380a, 0x02}, {0x380b, 0xf8}, {0x3811, 0x08}, {0x3813, 0x08}, - {0x3814, 0x01}, + {0x3814, 0x03}, {0x3815, 0x01}, - {0x3816, 0x01}, + {0x3816, 0x03}, {0x3817, 0x01}, - {0x380c, 0x04}, {0x380d, 0x2e}, // HTS - {0x380e, 0x09}, {0x380f, 0xdb}, // VTS + {0x380c, 0x08}, {0x380d, 0x5c}, // HTS + {0x380e, 0x09}, {0x380f, 0x38}, // VTS - {0x3820, 0xb0}, - {0x3821, 0x04}, - {0x3880, 0x00}, + {0x3820, 0xb3}, + {0x3821, 0x01}, + {0x3880, 0x25}, {0x3882, 0x20}, {0x3c91, 0x0b}, {0x3c94, 0x45}, - // {0x3cad, 0x00}, - // {0x3cae, 0x00}, + {0x3cad, 0x00}, + {0x3cae, 0x00}, {0x4000, 0xf3}, {0x4001, 0x60}, - {0x4003, 0x40}, + {0x4003, 0x80}, {0x4300, 0xff}, {0x4302, 0x0f}, - {0x4305, 0x93}, + {0x4305, 0x83}, {0x4505, 0x84}, {0x4809, 0x0e}, {0x480a, 0x04}, - {0x4837, 0x14}, + {0x4837, 0x15}, {0x4c00, 0x08}, {0x4c01, 0x08}, {0x4c04, 0x00}, @@ -307,7 +307,7 @@ const struct i2c_random_wr_payload init_array_os04c10[] = { // {0x0100, 0x01}, // {0x320d, 0x00}, // {0x3208, 0xa0}, - // {0x3822, 0x14}, + {0x3822, 0x14}, // initialize exposure {0x3503, 0x88}, diff --git a/system/camerad/sensors/ox03c10.cc b/system/camerad/sensors/ox03c10.cc index 94efa0ea24bb072..d8cdc89648e9e69 100644 --- a/system/camerad/sensors/ox03c10.cc +++ b/system/camerad/sensors/ox03c10.cc @@ -1,3 +1,5 @@ +#include + #include "system/camerad/sensors/sensor.h" namespace { @@ -23,6 +25,7 @@ const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35 OX03C10::OX03C10() { image_sensor = cereal::FrameData::ImageSensor::OX03C10; + bayer_pattern = CAM_ISP_PATTERN_BAYER_GRGRGR; pixel_size_mm = 0.003; data_word = false; frame_width = 1928; @@ -35,10 +38,13 @@ OX03C10::OX03C10() { init_reg_array.assign(std::begin(init_array_ox03c10), std::end(init_array_ox03c10)); probe_reg_addr = 0x300a; probe_expected_data = 0x5803; + bits_per_pixel = 12; mipi_format = CAM_FORMAT_MIPI_RAW_12; frame_data_type = 0x2c; // one is 0x2a, two are 0x2b mclk_frequency = 24000000; //Hz + readout_time_ns = 14697000; + dc_gain_factor = 7.32; dc_gain_min_weight = 1; // always on is fine dc_gain_max_weight = 1; @@ -58,6 +64,37 @@ OX03C10::OX03C10() { 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; + + black_level = 0; + color_correct_matrix = { + 0x000000b6, 0x00000ff1, 0x00000fda, + 0x00000fcc, 0x000000b9, 0x00000ffb, + 0x00000fc2, 0x00000ff6, 0x000000c9, + }; + for (int i = 0; i < 65; i++) { + float fx = i / 64.0; + fx = -0.507089*exp(-12.54124638*fx) + 0.9655*pow(fx, 0.5) - 0.472597*fx + 0.507089; + gamma_lut_rgb.push_back((uint32_t)(fx*1023.0 + 0.5)); + } + prepare_gamma_lut(); + linearization_lut = { + 0x00200000, 0x00200000, 0x00200000, 0x00200000, + 0x00404080, 0x00404080, 0x00404080, 0x00404080, + 0x00804100, 0x00804100, 0x00804100, 0x00804100, + 0x02014402, 0x02014402, 0x02014402, 0x02014402, + 0x0402c804, 0x0402c804, 0x0402c804, 0x0402c804, + 0x0805d00a, 0x0805d00a, 0x0805d00a, 0x0805d00a, + 0x100ba015, 0x100ba015, 0x100ba015, 0x100ba015, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + 0x00003fff, 0x00003fff, 0x00003fff, 0x00003fff, + }; + for (int i = 0; i < 252; i++) { + linearization_lut.push_back(0x0); + } + linearization_pts = {0x07ff0bff, 0x17ff1bff, 0x1fff23ff, 0x27ff3fff}; + for (int i = 0; i < 884*2; i++) { + vignetting_lut.push_back(0xff); + } } std::vector OX03C10::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { diff --git a/system/camerad/sensors/ox03c10_cl.h b/system/camerad/sensors/ox03c10_cl.h index 21441902fc2cd07..f1fbd16ccbd0083 100644 --- a/system/camerad/sensors/ox03c10_cl.h +++ b/system/camerad/sensors/ox03c10_cl.h @@ -4,28 +4,31 @@ #define BLACK_LVL 64 #define VIGNETTE_RSZ 1.0f -constant float ox03c10_lut[] = { - 0.0000e+00, 5.9488e-08, 1.1898e-07, 1.7846e-07, 2.3795e-07, 2.9744e-07, 3.5693e-07, 4.1642e-07, 4.7591e-07, 5.3539e-07, 5.9488e-07, 6.5437e-07, 7.1386e-07, 7.7335e-07, 8.3284e-07, 8.9232e-07, 9.5181e-07, 1.0113e-06, 1.0708e-06, 1.1303e-06, 1.1898e-06, 1.2493e-06, 1.3087e-06, 1.3682e-06, 1.4277e-06, 1.4872e-06, 1.5467e-06, 1.6062e-06, 1.6657e-06, 1.7252e-06, 1.7846e-06, 1.8441e-06, 1.9036e-06, 1.9631e-06, 2.0226e-06, 2.0821e-06, 2.1416e-06, 2.2011e-06, 2.2606e-06, 2.3200e-06, 2.3795e-06, 2.4390e-06, 2.4985e-06, 2.5580e-06, 2.6175e-06, 2.6770e-06, 2.7365e-06, 2.7959e-06, 2.8554e-06, 2.9149e-06, 2.9744e-06, 3.0339e-06, 3.0934e-06, 3.1529e-06, 3.2124e-06, 3.2719e-06, 3.3313e-06, 3.3908e-06, 3.4503e-06, 3.5098e-06, 3.5693e-06, 3.6288e-06, 3.6883e-06, 3.7478e-06, 3.8072e-06, 3.8667e-06, 3.9262e-06, 3.9857e-06, 4.0452e-06, 4.1047e-06, 4.1642e-06, 4.2237e-06, 4.2832e-06, 4.3426e-06, 4.4021e-06, 4.4616e-06, 4.5211e-06, 4.5806e-06, 4.6401e-06, 4.6996e-06, 4.7591e-06, 4.8185e-06, 4.8780e-06, 4.9375e-06, 4.9970e-06, 5.0565e-06, 5.1160e-06, 5.1755e-06, 5.2350e-06, 5.2945e-06, 5.3539e-06, 5.4134e-06, 5.4729e-06, 5.5324e-06, 5.5919e-06, 5.6514e-06, 5.7109e-06, 5.7704e-06, 5.8298e-06, 5.8893e-06, 5.9488e-06, 6.0083e-06, 6.0678e-06, 6.1273e-06, 6.1868e-06, 6.2463e-06, 6.3058e-06, 6.3652e-06, 6.4247e-06, 6.4842e-06, 6.5437e-06, 6.6032e-06, 6.6627e-06, 6.7222e-06, 6.7817e-06, 6.8411e-06, 6.9006e-06, 6.9601e-06, 7.0196e-06, 7.0791e-06, 7.1386e-06, 7.1981e-06, 7.2576e-06, 7.3171e-06, 7.3765e-06, 7.4360e-06, 7.4955e-06, 7.5550e-06, 7.6145e-06, 7.6740e-06, 7.7335e-06, 7.7930e-06, 7.8524e-06, 7.9119e-06, 7.9714e-06, 8.0309e-06, 8.0904e-06, 8.1499e-06, 8.2094e-06, 8.2689e-06, 8.3284e-06, 8.3878e-06, 8.4473e-06, 8.5068e-06, 8.5663e-06, 8.6258e-06, 8.6853e-06, 8.7448e-06, 8.8043e-06, 8.8637e-06, 8.9232e-06, 8.9827e-06, 9.0422e-06, 9.1017e-06, 9.1612e-06, 9.2207e-06, 9.2802e-06, 9.3397e-06, 9.3991e-06, 9.4586e-06, 9.5181e-06, 9.5776e-06, 9.6371e-06, 9.6966e-06, 9.7561e-06, 9.8156e-06, 9.8750e-06, 9.9345e-06, 9.9940e-06, 1.0054e-05, 1.0113e-05, 1.0172e-05, 1.0232e-05, 1.0291e-05, 1.0351e-05, 1.0410e-05, 1.0470e-05, 1.0529e-05, 1.0589e-05, 1.0648e-05, 1.0708e-05, 1.0767e-05, 1.0827e-05, 1.0886e-05, 1.0946e-05, 1.1005e-05, 1.1065e-05, 1.1124e-05, 1.1184e-05, 1.1243e-05, 1.1303e-05, 1.1362e-05, 1.1422e-05, 1.1481e-05, 1.1541e-05, 1.1600e-05, 1.1660e-05, 1.1719e-05, 1.1779e-05, 1.1838e-05, 1.1898e-05, 1.1957e-05, 1.2017e-05, 1.2076e-05, 1.2136e-05, 1.2195e-05, 1.2255e-05, 1.2314e-05, 1.2374e-05, 1.2433e-05, 1.2493e-05, 1.2552e-05, 1.2612e-05, 1.2671e-05, 1.2730e-05, 1.2790e-05, 1.2849e-05, 1.2909e-05, 1.2968e-05, 1.3028e-05, 1.3087e-05, 1.3147e-05, 1.3206e-05, 1.3266e-05, 1.3325e-05, 1.3385e-05, 1.3444e-05, 1.3504e-05, 1.3563e-05, 1.3623e-05, 1.3682e-05, 1.3742e-05, 1.3801e-05, 1.3861e-05, 1.3920e-05, 1.3980e-05, 1.4039e-05, 1.4099e-05, 1.4158e-05, 1.4218e-05, 1.4277e-05, 1.4337e-05, 1.4396e-05, 1.4456e-05, 1.4515e-05, 1.4575e-05, 1.4634e-05, 1.4694e-05, 1.4753e-05, 1.4813e-05, 1.4872e-05, 1.4932e-05, 1.4991e-05, 1.5051e-05, 1.5110e-05, 1.5169e-05, // NOLINT - 1.5229e-05, 1.5288e-05, 1.5348e-05, 1.5407e-05, 1.5467e-05, 1.5526e-05, 1.5586e-05, 1.5645e-05, 1.5705e-05, 1.5764e-05, 1.5824e-05, 1.5883e-05, 1.5943e-05, 1.6002e-05, 1.6062e-05, 1.6121e-05, 1.6181e-05, 1.6240e-05, 1.6300e-05, 1.6359e-05, 1.6419e-05, 1.6478e-05, 1.6538e-05, 1.6597e-05, 1.6657e-05, 1.6716e-05, 1.6776e-05, 1.6835e-05, 1.6895e-05, 1.6954e-05, 1.7014e-05, 1.7073e-05, 1.7133e-05, 1.7192e-05, 1.7252e-05, 1.7311e-05, 1.7371e-05, 1.7430e-05, 1.7490e-05, 1.7549e-05, 1.7609e-05, 1.7668e-05, 1.7727e-05, 1.7787e-05, 1.7846e-05, 1.7906e-05, 1.7965e-05, 1.8025e-05, 1.8084e-05, 1.8144e-05, 1.8203e-05, 1.8263e-05, 1.8322e-05, 1.8382e-05, 1.8441e-05, 1.8501e-05, 1.8560e-05, 1.8620e-05, 1.8679e-05, 1.8739e-05, 1.8798e-05, 1.8858e-05, 1.8917e-05, 1.8977e-05, 1.9036e-05, 1.9096e-05, 1.9155e-05, 1.9215e-05, 1.9274e-05, 1.9334e-05, 1.9393e-05, 1.9453e-05, 1.9512e-05, 1.9572e-05, 1.9631e-05, 1.9691e-05, 1.9750e-05, 1.9810e-05, 1.9869e-05, 1.9929e-05, 1.9988e-05, 2.0048e-05, 2.0107e-05, 2.0167e-05, 2.0226e-05, 2.0285e-05, 2.0345e-05, 2.0404e-05, 2.0464e-05, 2.0523e-05, 2.0583e-05, 2.0642e-05, 2.0702e-05, 2.0761e-05, 2.0821e-05, 2.0880e-05, 2.0940e-05, 2.0999e-05, 2.1059e-05, 2.1118e-05, 2.1178e-05, 2.1237e-05, 2.1297e-05, 2.1356e-05, 2.1416e-05, 2.1475e-05, 2.1535e-05, 2.1594e-05, 2.1654e-05, 2.1713e-05, 2.1773e-05, 2.1832e-05, 2.1892e-05, 2.1951e-05, 2.2011e-05, 2.2070e-05, 2.2130e-05, 2.2189e-05, 2.2249e-05, 2.2308e-05, 2.2368e-05, 2.2427e-05, 2.2487e-05, 2.2546e-05, 2.2606e-05, 2.2665e-05, 2.2725e-05, 2.2784e-05, 2.2843e-05, 2.2903e-05, 2.2962e-05, 2.3022e-05, 2.3081e-05, 2.3141e-05, 2.3200e-05, 2.3260e-05, 2.3319e-05, 2.3379e-05, 2.3438e-05, 2.3498e-05, 2.3557e-05, 2.3617e-05, 2.3676e-05, 2.3736e-05, 2.3795e-05, 2.3855e-05, 2.3914e-05, 2.3974e-05, 2.4033e-05, 2.4093e-05, 2.4152e-05, 2.4212e-05, 2.4271e-05, 2.4331e-05, 2.4390e-05, 2.4450e-05, 2.4509e-05, 2.4569e-05, 2.4628e-05, 2.4688e-05, 2.4747e-05, 2.4807e-05, 2.4866e-05, 2.4926e-05, 2.4985e-05, 2.5045e-05, 2.5104e-05, 2.5164e-05, 2.5223e-05, 2.5282e-05, 2.5342e-05, 2.5401e-05, 2.5461e-05, 2.5520e-05, 2.5580e-05, 2.5639e-05, 2.5699e-05, 2.5758e-05, 2.5818e-05, 2.5877e-05, 2.5937e-05, 2.5996e-05, 2.6056e-05, 2.6115e-05, 2.6175e-05, 2.6234e-05, 2.6294e-05, 2.6353e-05, 2.6413e-05, 2.6472e-05, 2.6532e-05, 2.6591e-05, 2.6651e-05, 2.6710e-05, 2.6770e-05, 2.6829e-05, 2.6889e-05, 2.6948e-05, 2.7008e-05, 2.7067e-05, 2.7127e-05, 2.7186e-05, 2.7246e-05, 2.7305e-05, 2.7365e-05, 2.7424e-05, 2.7484e-05, 2.7543e-05, 2.7603e-05, 2.7662e-05, 2.7722e-05, 2.7781e-05, 2.7840e-05, 2.7900e-05, 2.7959e-05, 2.8019e-05, 2.8078e-05, 2.8138e-05, 2.8197e-05, 2.8257e-05, 2.8316e-05, 2.8376e-05, 2.8435e-05, 2.8495e-05, 2.8554e-05, 2.8614e-05, 2.8673e-05, 2.8733e-05, 2.8792e-05, 2.8852e-05, 2.8911e-05, 2.8971e-05, 2.9030e-05, 2.9090e-05, 2.9149e-05, 2.9209e-05, 2.9268e-05, 2.9328e-05, 2.9387e-05, 2.9447e-05, 2.9506e-05, 2.9566e-05, 2.9625e-05, 2.9685e-05, 2.9744e-05, 2.9804e-05, 2.9863e-05, 2.9923e-05, 2.9982e-05, 3.0042e-05, 3.0101e-05, 3.0161e-05, 3.0220e-05, 3.0280e-05, 3.0339e-05, 3.0398e-05, // NOLINT - 3.0458e-05, 3.0577e-05, 3.0697e-05, 3.0816e-05, 3.0936e-05, 3.1055e-05, 3.1175e-05, 3.1294e-05, 3.1414e-05, 3.1533e-05, 3.1652e-05, 3.1772e-05, 3.1891e-05, 3.2011e-05, 3.2130e-05, 3.2250e-05, 3.2369e-05, 3.2489e-05, 3.2608e-05, 3.2727e-05, 3.2847e-05, 3.2966e-05, 3.3086e-05, 3.3205e-05, 3.3325e-05, 3.3444e-05, 3.3563e-05, 3.3683e-05, 3.3802e-05, 3.3922e-05, 3.4041e-05, 3.4161e-05, 3.4280e-05, 3.4400e-05, 3.4519e-05, 3.4638e-05, 3.4758e-05, 3.4877e-05, 3.4997e-05, 3.5116e-05, 3.5236e-05, 3.5355e-05, 3.5475e-05, 3.5594e-05, 3.5713e-05, 3.5833e-05, 3.5952e-05, 3.6072e-05, 3.6191e-05, 3.6311e-05, 3.6430e-05, 3.6550e-05, 3.6669e-05, 3.6788e-05, 3.6908e-05, 3.7027e-05, 3.7147e-05, 3.7266e-05, 3.7386e-05, 3.7505e-05, 3.7625e-05, 3.7744e-05, 3.7863e-05, 3.7983e-05, 3.8102e-05, 3.8222e-05, 3.8341e-05, 3.8461e-05, 3.8580e-05, 3.8700e-05, 3.8819e-05, 3.8938e-05, 3.9058e-05, 3.9177e-05, 3.9297e-05, 3.9416e-05, 3.9536e-05, 3.9655e-05, 3.9775e-05, 3.9894e-05, 4.0013e-05, 4.0133e-05, 4.0252e-05, 4.0372e-05, 4.0491e-05, 4.0611e-05, 4.0730e-05, 4.0850e-05, 4.0969e-05, 4.1088e-05, 4.1208e-05, 4.1327e-05, 4.1447e-05, 4.1566e-05, 4.1686e-05, 4.1805e-05, 4.1925e-05, 4.2044e-05, 4.2163e-05, 4.2283e-05, 4.2402e-05, 4.2522e-05, 4.2641e-05, 4.2761e-05, 4.2880e-05, 4.2999e-05, 4.3119e-05, 4.3238e-05, 4.3358e-05, 4.3477e-05, 4.3597e-05, 4.3716e-05, 4.3836e-05, 4.3955e-05, 4.4074e-05, 4.4194e-05, 4.4313e-05, 4.4433e-05, 4.4552e-05, 4.4672e-05, 4.4791e-05, 4.4911e-05, 4.5030e-05, 4.5149e-05, 4.5269e-05, 4.5388e-05, 4.5508e-05, 4.5627e-05, 4.5747e-05, 4.5866e-05, 4.5986e-05, 4.6105e-05, 4.6224e-05, 4.6344e-05, 4.6463e-05, 4.6583e-05, 4.6702e-05, 4.6822e-05, 4.6941e-05, 4.7061e-05, 4.7180e-05, 4.7299e-05, 4.7419e-05, 4.7538e-05, 4.7658e-05, 4.7777e-05, 4.7897e-05, 4.8016e-05, 4.8136e-05, 4.8255e-05, 4.8374e-05, 4.8494e-05, 4.8613e-05, 4.8733e-05, 4.8852e-05, 4.8972e-05, 4.9091e-05, 4.9211e-05, 4.9330e-05, 4.9449e-05, 4.9569e-05, 4.9688e-05, 4.9808e-05, 4.9927e-05, 5.0047e-05, 5.0166e-05, 5.0286e-05, 5.0405e-05, 5.0524e-05, 5.0644e-05, 5.0763e-05, 5.0883e-05, 5.1002e-05, 5.1122e-05, 5.1241e-05, 5.1361e-05, 5.1480e-05, 5.1599e-05, 5.1719e-05, 5.1838e-05, 5.1958e-05, 5.2077e-05, 5.2197e-05, 5.2316e-05, 5.2435e-05, 5.2555e-05, 5.2674e-05, 5.2794e-05, 5.2913e-05, 5.3033e-05, 5.3152e-05, 5.3272e-05, 5.3391e-05, 5.3510e-05, 5.3630e-05, 5.3749e-05, 5.3869e-05, 5.3988e-05, 5.4108e-05, 5.4227e-05, 5.4347e-05, 5.4466e-05, 5.4585e-05, 5.4705e-05, 5.4824e-05, 5.4944e-05, 5.5063e-05, 5.5183e-05, 5.5302e-05, 5.5422e-05, 5.5541e-05, 5.5660e-05, 5.5780e-05, 5.5899e-05, 5.6019e-05, 5.6138e-05, 5.6258e-05, 5.6377e-05, 5.6497e-05, 5.6616e-05, 5.6735e-05, 5.6855e-05, 5.6974e-05, 5.7094e-05, 5.7213e-05, 5.7333e-05, 5.7452e-05, 5.7572e-05, 5.7691e-05, 5.7810e-05, 5.7930e-05, 5.8049e-05, 5.8169e-05, 5.8288e-05, 5.8408e-05, 5.8527e-05, 5.8647e-05, 5.8766e-05, 5.8885e-05, 5.9005e-05, 5.9124e-05, 5.9244e-05, 5.9363e-05, 5.9483e-05, 5.9602e-05, 5.9722e-05, 5.9841e-05, 5.9960e-05, 6.0080e-05, 6.0199e-05, 6.0319e-05, 6.0438e-05, 6.0558e-05, 6.0677e-05, 6.0797e-05, 6.0916e-05, // NOLINT - 6.1154e-05, 6.1392e-05, 6.1631e-05, 6.1869e-05, 6.2107e-05, 6.2345e-05, 6.2583e-05, 6.2821e-05, 6.3060e-05, 6.3298e-05, 6.3536e-05, 6.3774e-05, 6.4012e-05, 6.4251e-05, 6.4489e-05, 6.4727e-05, 6.4965e-05, 6.5203e-05, 6.5441e-05, 6.5680e-05, 6.5918e-05, 6.6156e-05, 6.6394e-05, 6.6632e-05, 6.6871e-05, 6.7109e-05, 6.7347e-05, 6.7585e-05, 6.7823e-05, 6.8062e-05, 6.8300e-05, 6.8538e-05, 6.8776e-05, 6.9014e-05, 6.9252e-05, 6.9491e-05, 6.9729e-05, 6.9967e-05, 7.0205e-05, 7.0443e-05, 7.0682e-05, 7.0920e-05, 7.1158e-05, 7.1396e-05, 7.1634e-05, 7.1872e-05, 7.2111e-05, 7.2349e-05, 7.2587e-05, 7.2825e-05, 7.3063e-05, 7.3302e-05, 7.3540e-05, 7.3778e-05, 7.4016e-05, 7.4254e-05, 7.4493e-05, 7.4731e-05, 7.4969e-05, 7.5207e-05, 7.5445e-05, 7.5683e-05, 7.5922e-05, 7.6160e-05, 7.6398e-05, 7.6636e-05, 7.6874e-05, 7.7113e-05, 7.7351e-05, 7.7589e-05, 7.7827e-05, 7.8065e-05, 7.8304e-05, 7.8542e-05, 7.8780e-05, 7.9018e-05, 7.9256e-05, 7.9494e-05, 7.9733e-05, 7.9971e-05, 8.0209e-05, 8.0447e-05, 8.0685e-05, 8.0924e-05, 8.1162e-05, 8.1400e-05, 8.1638e-05, 8.1876e-05, 8.2114e-05, 8.2353e-05, 8.2591e-05, 8.2829e-05, 8.3067e-05, 8.3305e-05, 8.3544e-05, 8.3782e-05, 8.4020e-05, 8.4258e-05, 8.4496e-05, 8.4735e-05, 8.4973e-05, 8.5211e-05, 8.5449e-05, 8.5687e-05, 8.5925e-05, 8.6164e-05, 8.6402e-05, 8.6640e-05, 8.6878e-05, 8.7116e-05, 8.7355e-05, 8.7593e-05, 8.7831e-05, 8.8069e-05, 8.8307e-05, 8.8545e-05, 8.8784e-05, 8.9022e-05, 8.9260e-05, 8.9498e-05, 8.9736e-05, 8.9975e-05, 9.0213e-05, 9.0451e-05, 9.0689e-05, 9.0927e-05, 9.1166e-05, 9.1404e-05, 9.1642e-05, 9.1880e-05, 9.2118e-05, 9.2356e-05, 9.2595e-05, 9.2833e-05, 9.3071e-05, 9.3309e-05, 9.3547e-05, 9.3786e-05, 9.4024e-05, 9.4262e-05, 9.4500e-05, 9.4738e-05, 9.4977e-05, 9.5215e-05, 9.5453e-05, 9.5691e-05, 9.5929e-05, 9.6167e-05, 9.6406e-05, 9.6644e-05, 9.6882e-05, 9.7120e-05, 9.7358e-05, 9.7597e-05, 9.7835e-05, 9.8073e-05, 9.8311e-05, 9.8549e-05, 9.8787e-05, 9.9026e-05, 9.9264e-05, 9.9502e-05, 9.9740e-05, 9.9978e-05, 1.0022e-04, 1.0045e-04, 1.0069e-04, 1.0093e-04, 1.0117e-04, 1.0141e-04, 1.0165e-04, 1.0188e-04, 1.0212e-04, 1.0236e-04, 1.0260e-04, 1.0284e-04, 1.0307e-04, 1.0331e-04, 1.0355e-04, 1.0379e-04, 1.0403e-04, 1.0427e-04, 1.0450e-04, 1.0474e-04, 1.0498e-04, 1.0522e-04, 1.0546e-04, 1.0569e-04, 1.0593e-04, 1.0617e-04, 1.0641e-04, 1.0665e-04, 1.0689e-04, 1.0712e-04, 1.0736e-04, 1.0760e-04, 1.0784e-04, 1.0808e-04, 1.0831e-04, 1.0855e-04, 1.0879e-04, 1.0903e-04, 1.0927e-04, 1.0951e-04, 1.0974e-04, 1.0998e-04, 1.1022e-04, 1.1046e-04, 1.1070e-04, 1.1093e-04, 1.1117e-04, 1.1141e-04, 1.1165e-04, 1.1189e-04, 1.1213e-04, 1.1236e-04, 1.1260e-04, 1.1284e-04, 1.1308e-04, 1.1332e-04, 1.1355e-04, 1.1379e-04, 1.1403e-04, 1.1427e-04, 1.1451e-04, 1.1475e-04, 1.1498e-04, 1.1522e-04, 1.1546e-04, 1.1570e-04, 1.1594e-04, 1.1618e-04, 1.1641e-04, 1.1665e-04, 1.1689e-04, 1.1713e-04, 1.1737e-04, 1.1760e-04, 1.1784e-04, 1.1808e-04, 1.1832e-04, 1.1856e-04, 1.1880e-04, 1.1903e-04, 1.1927e-04, 1.1951e-04, 1.1975e-04, 1.1999e-04, 1.2022e-04, 1.2046e-04, 1.2070e-04, 1.2094e-04, 1.2118e-04, 1.2142e-04, 1.2165e-04, 1.2189e-04, // NOLINT - 1.2213e-04, 1.2237e-04, 1.2261e-04, 1.2284e-04, 1.2308e-04, 1.2332e-04, 1.2356e-04, 1.2380e-04, 1.2404e-04, 1.2427e-04, 1.2451e-04, 1.2475e-04, 1.2499e-04, 1.2523e-04, 1.2546e-04, 1.2570e-04, 1.2594e-04, 1.2618e-04, 1.2642e-04, 1.2666e-04, 1.2689e-04, 1.2713e-04, 1.2737e-04, 1.2761e-04, 1.2785e-04, 1.2808e-04, 1.2832e-04, 1.2856e-04, 1.2880e-04, 1.2904e-04, 1.2928e-04, 1.2951e-04, 1.2975e-04, 1.2999e-04, 1.3023e-04, 1.3047e-04, 1.3070e-04, 1.3094e-04, 1.3118e-04, 1.3142e-04, 1.3166e-04, 1.3190e-04, 1.3213e-04, 1.3237e-04, 1.3261e-04, 1.3285e-04, 1.3309e-04, 1.3332e-04, 1.3356e-04, 1.3380e-04, 1.3404e-04, 1.3428e-04, 1.3452e-04, 1.3475e-04, 1.3499e-04, 1.3523e-04, 1.3547e-04, 1.3571e-04, 1.3594e-04, 1.3618e-04, 1.3642e-04, 1.3666e-04, 1.3690e-04, 1.3714e-04, 1.3737e-04, 1.3761e-04, 1.3785e-04, 1.3809e-04, 1.3833e-04, 1.3856e-04, 1.3880e-04, 1.3904e-04, 1.3928e-04, 1.3952e-04, 1.3976e-04, 1.3999e-04, 1.4023e-04, 1.4047e-04, 1.4071e-04, 1.4095e-04, 1.4118e-04, 1.4142e-04, 1.4166e-04, 1.4190e-04, 1.4214e-04, 1.4238e-04, 1.4261e-04, 1.4285e-04, 1.4309e-04, 1.4333e-04, 1.4357e-04, 1.4380e-04, 1.4404e-04, 1.4428e-04, 1.4452e-04, 1.4476e-04, 1.4500e-04, 1.4523e-04, 1.4547e-04, 1.4571e-04, 1.4595e-04, 1.4619e-04, 1.4642e-04, 1.4666e-04, 1.4690e-04, 1.4714e-04, 1.4738e-04, 1.4762e-04, 1.4785e-04, 1.4809e-04, 1.4833e-04, 1.4857e-04, 1.4881e-04, 1.4904e-04, 1.4928e-04, 1.4952e-04, 1.4976e-04, 1.5000e-04, 1.5024e-04, 1.5047e-04, 1.5071e-04, 1.5095e-04, 1.5119e-04, 1.5143e-04, 1.5166e-04, 1.5190e-04, 1.5214e-04, 1.5238e-04, 1.5262e-04, 1.5286e-04, 1.5309e-04, 1.5333e-04, 1.5357e-04, 1.5381e-04, 1.5405e-04, 1.5428e-04, 1.5452e-04, 1.5476e-04, 1.5500e-04, 1.5524e-04, 1.5548e-04, 1.5571e-04, 1.5595e-04, 1.5619e-04, 1.5643e-04, 1.5667e-04, 1.5690e-04, 1.5714e-04, 1.5738e-04, 1.5762e-04, 1.5786e-04, 1.5810e-04, 1.5833e-04, 1.5857e-04, 1.5881e-04, 1.5905e-04, 1.5929e-04, 1.5952e-04, 1.5976e-04, 1.6000e-04, 1.6024e-04, 1.6048e-04, 1.6072e-04, 1.6095e-04, 1.6119e-04, 1.6143e-04, 1.6167e-04, 1.6191e-04, 1.6214e-04, 1.6238e-04, 1.6262e-04, 1.6286e-04, 1.6310e-04, 1.6334e-04, 1.6357e-04, 1.6381e-04, 1.6405e-04, 1.6429e-04, 1.6453e-04, 1.6476e-04, 1.6500e-04, 1.6524e-04, 1.6548e-04, 1.6572e-04, 1.6596e-04, 1.6619e-04, 1.6643e-04, 1.6667e-04, 1.6691e-04, 1.6715e-04, 1.6738e-04, 1.6762e-04, 1.6786e-04, 1.6810e-04, 1.6834e-04, 1.6858e-04, 1.6881e-04, 1.6905e-04, 1.6929e-04, 1.6953e-04, 1.6977e-04, 1.7001e-04, 1.7024e-04, 1.7048e-04, 1.7072e-04, 1.7096e-04, 1.7120e-04, 1.7143e-04, 1.7167e-04, 1.7191e-04, 1.7215e-04, 1.7239e-04, 1.7263e-04, 1.7286e-04, 1.7310e-04, 1.7334e-04, 1.7358e-04, 1.7382e-04, 1.7405e-04, 1.7429e-04, 1.7453e-04, 1.7477e-04, 1.7501e-04, 1.7525e-04, 1.7548e-04, 1.7572e-04, 1.7596e-04, 1.7620e-04, 1.7644e-04, 1.7667e-04, 1.7691e-04, 1.7715e-04, 1.7739e-04, 1.7763e-04, 1.7787e-04, 1.7810e-04, 1.7834e-04, 1.7858e-04, 1.7882e-04, 1.7906e-04, 1.7929e-04, 1.7953e-04, 1.7977e-04, 1.8001e-04, 1.8025e-04, 1.8049e-04, 1.8072e-04, 1.8096e-04, 1.8120e-04, 1.8144e-04, 1.8168e-04, 1.8191e-04, 1.8215e-04, 1.8239e-04, 1.8263e-04, 1.8287e-04, // NOLINT - 1.8311e-04, 1.8334e-04, 1.8358e-04, 1.8382e-04, 1.8406e-04, 1.8430e-04, 1.8453e-04, 1.8477e-04, 1.8501e-04, 1.8525e-04, 1.8549e-04, 1.8573e-04, 1.8596e-04, 1.8620e-04, 1.8644e-04, 1.8668e-04, 1.8692e-04, 1.8715e-04, 1.8739e-04, 1.8763e-04, 1.8787e-04, 1.8811e-04, 1.8835e-04, 1.8858e-04, 1.8882e-04, 1.8906e-04, 1.8930e-04, 1.8954e-04, 1.8977e-04, 1.9001e-04, 1.9025e-04, 1.9049e-04, 1.9073e-04, 1.9097e-04, 1.9120e-04, 1.9144e-04, 1.9168e-04, 1.9192e-04, 1.9216e-04, 1.9239e-04, 1.9263e-04, 1.9287e-04, 1.9311e-04, 1.9335e-04, 1.9359e-04, 1.9382e-04, 1.9406e-04, 1.9430e-04, 1.9454e-04, 1.9478e-04, 1.9501e-04, 1.9525e-04, 1.9549e-04, 1.9573e-04, 1.9597e-04, 1.9621e-04, 1.9644e-04, 1.9668e-04, 1.9692e-04, 1.9716e-04, 1.9740e-04, 1.9763e-04, 1.9787e-04, 1.9811e-04, 1.9835e-04, 1.9859e-04, 1.9883e-04, 1.9906e-04, 1.9930e-04, 1.9954e-04, 1.9978e-04, 2.0002e-04, 2.0025e-04, 2.0049e-04, 2.0073e-04, 2.0097e-04, 2.0121e-04, 2.0145e-04, 2.0168e-04, 2.0192e-04, 2.0216e-04, 2.0240e-04, 2.0264e-04, 2.0287e-04, 2.0311e-04, 2.0335e-04, 2.0359e-04, 2.0383e-04, 2.0407e-04, 2.0430e-04, 2.0454e-04, 2.0478e-04, 2.0502e-04, 2.0526e-04, 2.0549e-04, 2.0573e-04, 2.0597e-04, 2.0621e-04, 2.0645e-04, 2.0669e-04, 2.0692e-04, 2.0716e-04, 2.0740e-04, 2.0764e-04, 2.0788e-04, 2.0811e-04, 2.0835e-04, 2.0859e-04, 2.0883e-04, 2.0907e-04, 2.0931e-04, 2.0954e-04, 2.0978e-04, 2.1002e-04, 2.1026e-04, 2.1050e-04, 2.1073e-04, 2.1097e-04, 2.1121e-04, 2.1145e-04, 2.1169e-04, 2.1193e-04, 2.1216e-04, 2.1240e-04, 2.1264e-04, 2.1288e-04, 2.1312e-04, 2.1335e-04, 2.1359e-04, 2.1383e-04, 2.1407e-04, 2.1431e-04, 2.1455e-04, 2.1478e-04, 2.1502e-04, 2.1526e-04, 2.1550e-04, 2.1574e-04, 2.1597e-04, 2.1621e-04, 2.1645e-04, 2.1669e-04, 2.1693e-04, 2.1717e-04, 2.1740e-04, 2.1764e-04, 2.1788e-04, 2.1812e-04, 2.1836e-04, 2.1859e-04, 2.1883e-04, 2.1907e-04, 2.1931e-04, 2.1955e-04, 2.1979e-04, 2.2002e-04, 2.2026e-04, 2.2050e-04, 2.2074e-04, 2.2098e-04, 2.2121e-04, 2.2145e-04, 2.2169e-04, 2.2193e-04, 2.2217e-04, 2.2241e-04, 2.2264e-04, 2.2288e-04, 2.2312e-04, 2.2336e-04, 2.2360e-04, 2.2383e-04, 2.2407e-04, 2.2431e-04, 2.2455e-04, 2.2479e-04, 2.2503e-04, 2.2526e-04, 2.2550e-04, 2.2574e-04, 2.2598e-04, 2.2622e-04, 2.2646e-04, 2.2669e-04, 2.2693e-04, 2.2717e-04, 2.2741e-04, 2.2765e-04, 2.2788e-04, 2.2812e-04, 2.2836e-04, 2.2860e-04, 2.2884e-04, 2.2908e-04, 2.2931e-04, 2.2955e-04, 2.2979e-04, 2.3003e-04, 2.3027e-04, 2.3050e-04, 2.3074e-04, 2.3098e-04, 2.3122e-04, 2.3146e-04, 2.3170e-04, 2.3193e-04, 2.3217e-04, 2.3241e-04, 2.3265e-04, 2.3289e-04, 2.3312e-04, 2.3336e-04, 2.3360e-04, 2.3384e-04, 2.3408e-04, 2.3432e-04, 2.3455e-04, 2.3479e-04, 2.3503e-04, 2.3527e-04, 2.3551e-04, 2.3574e-04, 2.3598e-04, 2.3622e-04, 2.3646e-04, 2.3670e-04, 2.3694e-04, 2.3717e-04, 2.3741e-04, 2.3765e-04, 2.3789e-04, 2.3813e-04, 2.3836e-04, 2.3860e-04, 2.3884e-04, 2.3908e-04, 2.3932e-04, 2.3956e-04, 2.3979e-04, 2.4003e-04, 2.4027e-04, 2.4051e-04, 2.4075e-04, 2.4098e-04, 2.4122e-04, 2.4146e-04, 2.4170e-04, 2.4194e-04, 2.4218e-04, 2.4241e-04, 2.4265e-04, 2.4289e-04, 2.4313e-04, 2.4337e-04, 2.4360e-04, 2.4384e-04, // NOLINT - 2.4480e-04, 2.4575e-04, 2.4670e-04, 2.4766e-04, 2.4861e-04, 2.4956e-04, 2.5052e-04, 2.5147e-04, 2.5242e-04, 2.5337e-04, 2.5433e-04, 2.5528e-04, 2.5623e-04, 2.5719e-04, 2.5814e-04, 2.5909e-04, 2.6005e-04, 2.6100e-04, 2.6195e-04, 2.6291e-04, 2.6386e-04, 2.6481e-04, 2.6577e-04, 2.6672e-04, 2.6767e-04, 2.6863e-04, 2.6958e-04, 2.7053e-04, 2.7149e-04, 2.7244e-04, 2.7339e-04, 2.7435e-04, 2.7530e-04, 2.7625e-04, 2.7720e-04, 2.7816e-04, 2.7911e-04, 2.8006e-04, 2.8102e-04, 2.8197e-04, 2.8292e-04, 2.8388e-04, 2.8483e-04, 2.8578e-04, 2.8674e-04, 2.8769e-04, 2.8864e-04, 2.8960e-04, 2.9055e-04, 2.9150e-04, 2.9246e-04, 2.9341e-04, 2.9436e-04, 2.9532e-04, 2.9627e-04, 2.9722e-04, 2.9818e-04, 2.9913e-04, 3.0008e-04, 3.0104e-04, 3.0199e-04, 3.0294e-04, 3.0389e-04, 3.0485e-04, 3.0580e-04, 3.0675e-04, 3.0771e-04, 3.0866e-04, 3.0961e-04, 3.1057e-04, 3.1152e-04, 3.1247e-04, 3.1343e-04, 3.1438e-04, 3.1533e-04, 3.1629e-04, 3.1724e-04, 3.1819e-04, 3.1915e-04, 3.2010e-04, 3.2105e-04, 3.2201e-04, 3.2296e-04, 3.2391e-04, 3.2487e-04, 3.2582e-04, 3.2677e-04, 3.2772e-04, 3.2868e-04, 3.2963e-04, 3.3058e-04, 3.3154e-04, 3.3249e-04, 3.3344e-04, 3.3440e-04, 3.3535e-04, 3.3630e-04, 3.3726e-04, 3.3821e-04, 3.3916e-04, 3.4012e-04, 3.4107e-04, 3.4202e-04, 3.4298e-04, 3.4393e-04, 3.4488e-04, 3.4584e-04, 3.4679e-04, 3.4774e-04, 3.4870e-04, 3.4965e-04, 3.5060e-04, 3.5156e-04, 3.5251e-04, 3.5346e-04, 3.5441e-04, 3.5537e-04, 3.5632e-04, 3.5727e-04, 3.5823e-04, 3.5918e-04, 3.6013e-04, 3.6109e-04, 3.6204e-04, 3.6299e-04, 3.6395e-04, 3.6490e-04, 3.6585e-04, 3.6681e-04, 3.6776e-04, 3.6871e-04, 3.6967e-04, 3.7062e-04, 3.7157e-04, 3.7253e-04, 3.7348e-04, 3.7443e-04, 3.7539e-04, 3.7634e-04, 3.7729e-04, 3.7825e-04, 3.7920e-04, 3.8015e-04, 3.8110e-04, 3.8206e-04, 3.8301e-04, 3.8396e-04, 3.8492e-04, 3.8587e-04, 3.8682e-04, 3.8778e-04, 3.8873e-04, 3.8968e-04, 3.9064e-04, 3.9159e-04, 3.9254e-04, 3.9350e-04, 3.9445e-04, 3.9540e-04, 3.9636e-04, 3.9731e-04, 3.9826e-04, 3.9922e-04, 4.0017e-04, 4.0112e-04, 4.0208e-04, 4.0303e-04, 4.0398e-04, 4.0493e-04, 4.0589e-04, 4.0684e-04, 4.0779e-04, 4.0875e-04, 4.0970e-04, 4.1065e-04, 4.1161e-04, 4.1256e-04, 4.1351e-04, 4.1447e-04, 4.1542e-04, 4.1637e-04, 4.1733e-04, 4.1828e-04, 4.1923e-04, 4.2019e-04, 4.2114e-04, 4.2209e-04, 4.2305e-04, 4.2400e-04, 4.2495e-04, 4.2591e-04, 4.2686e-04, 4.2781e-04, 4.2877e-04, 4.2972e-04, 4.3067e-04, 4.3162e-04, 4.3258e-04, 4.3353e-04, 4.3448e-04, 4.3544e-04, 4.3639e-04, 4.3734e-04, 4.3830e-04, 4.3925e-04, 4.4020e-04, 4.4116e-04, 4.4211e-04, 4.4306e-04, 4.4402e-04, 4.4497e-04, 4.4592e-04, 4.4688e-04, 4.4783e-04, 4.4878e-04, 4.4974e-04, 4.5069e-04, 4.5164e-04, 4.5260e-04, 4.5355e-04, 4.5450e-04, 4.5545e-04, 4.5641e-04, 4.5736e-04, 4.5831e-04, 4.5927e-04, 4.6022e-04, 4.6117e-04, 4.6213e-04, 4.6308e-04, 4.6403e-04, 4.6499e-04, 4.6594e-04, 4.6689e-04, 4.6785e-04, 4.6880e-04, 4.6975e-04, 4.7071e-04, 4.7166e-04, 4.7261e-04, 4.7357e-04, 4.7452e-04, 4.7547e-04, 4.7643e-04, 4.7738e-04, 4.7833e-04, 4.7929e-04, 4.8024e-04, 4.8119e-04, 4.8214e-04, 4.8310e-04, 4.8405e-04, 4.8500e-04, 4.8596e-04, 4.8691e-04, 4.8786e-04, // NOLINT - 4.8977e-04, 4.9168e-04, 4.9358e-04, 4.9549e-04, 4.9740e-04, 4.9931e-04, 5.0121e-04, 5.0312e-04, 5.0503e-04, 5.0693e-04, 5.0884e-04, 5.1075e-04, 5.1265e-04, 5.1456e-04, 5.1647e-04, 5.1837e-04, 5.2028e-04, 5.2219e-04, 5.2409e-04, 5.2600e-04, 5.2791e-04, 5.2982e-04, 5.3172e-04, 5.3363e-04, 5.3554e-04, 5.3744e-04, 5.3935e-04, 5.4126e-04, 5.4316e-04, 5.4507e-04, 5.4698e-04, 5.4888e-04, 5.5079e-04, 5.5270e-04, 5.5460e-04, 5.5651e-04, 5.5842e-04, 5.6033e-04, 5.6223e-04, 5.6414e-04, 5.6605e-04, 5.6795e-04, 5.6986e-04, 5.7177e-04, 5.7367e-04, 5.7558e-04, 5.7749e-04, 5.7939e-04, 5.8130e-04, 5.8321e-04, 5.8512e-04, 5.8702e-04, 5.8893e-04, 5.9084e-04, 5.9274e-04, 5.9465e-04, 5.9656e-04, 5.9846e-04, 6.0037e-04, 6.0228e-04, 6.0418e-04, 6.0609e-04, 6.0800e-04, 6.0990e-04, 6.1181e-04, 6.1372e-04, 6.1563e-04, 6.1753e-04, 6.1944e-04, 6.2135e-04, 6.2325e-04, 6.2516e-04, 6.2707e-04, 6.2897e-04, 6.3088e-04, 6.3279e-04, 6.3469e-04, 6.3660e-04, 6.3851e-04, 6.4041e-04, 6.4232e-04, 6.4423e-04, 6.4614e-04, 6.4804e-04, 6.4995e-04, 6.5186e-04, 6.5376e-04, 6.5567e-04, 6.5758e-04, 6.5948e-04, 6.6139e-04, 6.6330e-04, 6.6520e-04, 6.6711e-04, 6.6902e-04, 6.7092e-04, 6.7283e-04, 6.7474e-04, 6.7665e-04, 6.7855e-04, 6.8046e-04, 6.8237e-04, 6.8427e-04, 6.8618e-04, 6.8809e-04, 6.8999e-04, 6.9190e-04, 6.9381e-04, 6.9571e-04, 6.9762e-04, 6.9953e-04, 7.0143e-04, 7.0334e-04, 7.0525e-04, 7.0716e-04, 7.0906e-04, 7.1097e-04, 7.1288e-04, 7.1478e-04, 7.1669e-04, 7.1860e-04, 7.2050e-04, 7.2241e-04, 7.2432e-04, 7.2622e-04, 7.2813e-04, 7.3004e-04, 7.3195e-04, 7.3385e-04, 7.3576e-04, 7.3767e-04, 7.3957e-04, 7.4148e-04, 7.4339e-04, 7.4529e-04, 7.4720e-04, 7.4911e-04, 7.5101e-04, 7.5292e-04, 7.5483e-04, 7.5673e-04, 7.5864e-04, 7.6055e-04, 7.6246e-04, 7.6436e-04, 7.6627e-04, 7.6818e-04, 7.7008e-04, 7.7199e-04, 7.7390e-04, 7.7580e-04, 7.7771e-04, 7.7962e-04, 7.8152e-04, 7.8343e-04, 7.8534e-04, 7.8724e-04, 7.8915e-04, 7.9106e-04, 7.9297e-04, 7.9487e-04, 7.9678e-04, 7.9869e-04, 8.0059e-04, 8.0250e-04, 8.0441e-04, 8.0631e-04, 8.0822e-04, 8.1013e-04, 8.1203e-04, 8.1394e-04, 8.1585e-04, 8.1775e-04, 8.1966e-04, 8.2157e-04, 8.2348e-04, 8.2538e-04, 8.2729e-04, 8.2920e-04, 8.3110e-04, 8.3301e-04, 8.3492e-04, 8.3682e-04, 8.3873e-04, 8.4064e-04, 8.4254e-04, 8.4445e-04, 8.4636e-04, 8.4826e-04, 8.5017e-04, 8.5208e-04, 8.5399e-04, 8.5589e-04, 8.5780e-04, 8.5971e-04, 8.6161e-04, 8.6352e-04, 8.6543e-04, 8.6733e-04, 8.6924e-04, 8.7115e-04, 8.7305e-04, 8.7496e-04, 8.7687e-04, 8.7878e-04, 8.8068e-04, 8.8259e-04, 8.8450e-04, 8.8640e-04, 8.8831e-04, 8.9022e-04, 8.9212e-04, 8.9403e-04, 8.9594e-04, 8.9784e-04, 8.9975e-04, 9.0166e-04, 9.0356e-04, 9.0547e-04, 9.0738e-04, 9.0929e-04, 9.1119e-04, 9.1310e-04, 9.1501e-04, 9.1691e-04, 9.1882e-04, 9.2073e-04, 9.2263e-04, 9.2454e-04, 9.2645e-04, 9.2835e-04, 9.3026e-04, 9.3217e-04, 9.3407e-04, 9.3598e-04, 9.3789e-04, 9.3980e-04, 9.4170e-04, 9.4361e-04, 9.4552e-04, 9.4742e-04, 9.4933e-04, 9.5124e-04, 9.5314e-04, 9.5505e-04, 9.5696e-04, 9.5886e-04, 9.6077e-04, 9.6268e-04, 9.6458e-04, 9.6649e-04, 9.6840e-04, 9.7031e-04, 9.7221e-04, 9.7412e-04, 9.7603e-04, // NOLINT - 9.7984e-04, 9.8365e-04, 9.8747e-04, 9.9128e-04, 9.9510e-04, 9.9891e-04, 1.0027e-03, 1.0065e-03, 1.0104e-03, 1.0142e-03, 1.0180e-03, 1.0218e-03, 1.0256e-03, 1.0294e-03, 1.0332e-03, 1.0371e-03, 1.0409e-03, 1.0447e-03, 1.0485e-03, 1.0523e-03, 1.0561e-03, 1.0599e-03, 1.0638e-03, 1.0676e-03, 1.0714e-03, 1.0752e-03, 1.0790e-03, 1.0828e-03, 1.0866e-03, 1.0905e-03, 1.0943e-03, 1.0981e-03, 1.1019e-03, 1.1057e-03, 1.1095e-03, 1.1133e-03, 1.1172e-03, 1.1210e-03, 1.1248e-03, 1.1286e-03, 1.1324e-03, 1.1362e-03, 1.1400e-03, 1.1439e-03, 1.1477e-03, 1.1515e-03, 1.1553e-03, 1.1591e-03, 1.1629e-03, 1.1667e-03, 1.1706e-03, 1.1744e-03, 1.1782e-03, 1.1820e-03, 1.1858e-03, 1.1896e-03, 1.1934e-03, 1.1973e-03, 1.2011e-03, 1.2049e-03, 1.2087e-03, 1.2125e-03, 1.2163e-03, 1.2201e-03, 1.2240e-03, 1.2278e-03, 1.2316e-03, 1.2354e-03, 1.2392e-03, 1.2430e-03, 1.2468e-03, 1.2507e-03, 1.2545e-03, 1.2583e-03, 1.2621e-03, 1.2659e-03, 1.2697e-03, 1.2735e-03, 1.2774e-03, 1.2812e-03, 1.2850e-03, 1.2888e-03, 1.2926e-03, 1.2964e-03, 1.3002e-03, 1.3040e-03, 1.3079e-03, 1.3117e-03, 1.3155e-03, 1.3193e-03, 1.3231e-03, 1.3269e-03, 1.3307e-03, 1.3346e-03, 1.3384e-03, 1.3422e-03, 1.3460e-03, 1.3498e-03, 1.3536e-03, 1.3574e-03, 1.3613e-03, 1.3651e-03, 1.3689e-03, 1.3727e-03, 1.3765e-03, 1.3803e-03, 1.3841e-03, 1.3880e-03, 1.3918e-03, 1.3956e-03, 1.3994e-03, 1.4032e-03, 1.4070e-03, 1.4108e-03, 1.4147e-03, 1.4185e-03, 1.4223e-03, 1.4261e-03, 1.4299e-03, 1.4337e-03, 1.4375e-03, 1.4414e-03, 1.4452e-03, 1.4490e-03, 1.4528e-03, 1.4566e-03, 1.4604e-03, 1.4642e-03, 1.4681e-03, 1.4719e-03, 1.4757e-03, 1.4795e-03, 1.4833e-03, 1.4871e-03, 1.4909e-03, 1.4948e-03, 1.4986e-03, 1.5024e-03, 1.5062e-03, 1.5100e-03, 1.5138e-03, 1.5176e-03, 1.5215e-03, 1.5253e-03, 1.5291e-03, 1.5329e-03, 1.5367e-03, 1.5405e-03, 1.5443e-03, 1.5482e-03, 1.5520e-03, 1.5558e-03, 1.5596e-03, 1.5634e-03, 1.5672e-03, 1.5710e-03, 1.5749e-03, 1.5787e-03, 1.5825e-03, 1.5863e-03, 1.5901e-03, 1.5939e-03, 1.5977e-03, 1.6016e-03, 1.6054e-03, 1.6092e-03, 1.6130e-03, 1.6168e-03, 1.6206e-03, 1.6244e-03, 1.6283e-03, 1.6321e-03, 1.6359e-03, 1.6397e-03, 1.6435e-03, 1.6473e-03, 1.6511e-03, 1.6550e-03, 1.6588e-03, 1.6626e-03, 1.6664e-03, 1.6702e-03, 1.6740e-03, 1.6778e-03, 1.6817e-03, 1.6855e-03, 1.6893e-03, 1.6931e-03, 1.6969e-03, 1.7007e-03, 1.7045e-03, 1.7084e-03, 1.7122e-03, 1.7160e-03, 1.7198e-03, 1.7236e-03, 1.7274e-03, 1.7312e-03, 1.7351e-03, 1.7389e-03, 1.7427e-03, 1.7465e-03, 1.7503e-03, 1.7541e-03, 1.7579e-03, 1.7618e-03, 1.7656e-03, 1.7694e-03, 1.7732e-03, 1.7770e-03, 1.7808e-03, 1.7846e-03, 1.7885e-03, 1.7923e-03, 1.7961e-03, 1.7999e-03, 1.8037e-03, 1.8075e-03, 1.8113e-03, 1.8152e-03, 1.8190e-03, 1.8228e-03, 1.8266e-03, 1.8304e-03, 1.8342e-03, 1.8380e-03, 1.8419e-03, 1.8457e-03, 1.8495e-03, 1.8533e-03, 1.8571e-03, 1.8609e-03, 1.8647e-03, 1.8686e-03, 1.8724e-03, 1.8762e-03, 1.8800e-03, 1.8838e-03, 1.8876e-03, 1.8914e-03, 1.8953e-03, 1.8991e-03, 1.9029e-03, 1.9067e-03, 1.9105e-03, 1.9143e-03, 1.9181e-03, 1.9220e-03, 1.9258e-03, 1.9296e-03, 1.9334e-03, 1.9372e-03, 1.9410e-03, 1.9448e-03, 1.9487e-03, 1.9525e-03, // NOLINT - 1.9601e-03, 1.9677e-03, 1.9754e-03, 1.9830e-03, 1.9906e-03, 1.9982e-03, 2.0059e-03, 2.0135e-03, 2.0211e-03, 2.0288e-03, 2.0364e-03, 2.0440e-03, 2.0516e-03, 2.0593e-03, 2.0669e-03, 2.0745e-03, 2.0822e-03, 2.0898e-03, 2.0974e-03, 2.1050e-03, 2.1127e-03, 2.1203e-03, 2.1279e-03, 2.1356e-03, 2.1432e-03, 2.1508e-03, 2.1585e-03, 2.1661e-03, 2.1737e-03, 2.1813e-03, 2.1890e-03, 2.1966e-03, 2.2042e-03, 2.2119e-03, 2.2195e-03, 2.2271e-03, 2.2347e-03, 2.2424e-03, 2.2500e-03, 2.2576e-03, 2.2653e-03, 2.2729e-03, 2.2805e-03, 2.2881e-03, 2.2958e-03, 2.3034e-03, 2.3110e-03, 2.3187e-03, 2.3263e-03, 2.3339e-03, 2.3415e-03, 2.3492e-03, 2.3568e-03, 2.3644e-03, 2.3721e-03, 2.3797e-03, 2.3873e-03, 2.3949e-03, 2.4026e-03, 2.4102e-03, 2.4178e-03, 2.4255e-03, 2.4331e-03, 2.4407e-03, 2.4483e-03, 2.4560e-03, 2.4636e-03, 2.4712e-03, 2.4789e-03, 2.4865e-03, 2.4941e-03, 2.5018e-03, 2.5094e-03, 2.5170e-03, 2.5246e-03, 2.5323e-03, 2.5399e-03, 2.5475e-03, 2.5552e-03, 2.5628e-03, 2.5704e-03, 2.5780e-03, 2.5857e-03, 2.5933e-03, 2.6009e-03, 2.6086e-03, 2.6162e-03, 2.6238e-03, 2.6314e-03, 2.6391e-03, 2.6467e-03, 2.6543e-03, 2.6620e-03, 2.6696e-03, 2.6772e-03, 2.6848e-03, 2.6925e-03, 2.7001e-03, 2.7077e-03, 2.7154e-03, 2.7230e-03, 2.7306e-03, 2.7382e-03, 2.7459e-03, 2.7535e-03, 2.7611e-03, 2.7688e-03, 2.7764e-03, 2.7840e-03, 2.7917e-03, 2.7993e-03, 2.8069e-03, 2.8145e-03, 2.8222e-03, 2.8298e-03, 2.8374e-03, 2.8451e-03, 2.8527e-03, 2.8603e-03, 2.8679e-03, 2.8756e-03, 2.8832e-03, 2.8908e-03, 2.8985e-03, 2.9061e-03, 2.9137e-03, 2.9213e-03, 2.9290e-03, 2.9366e-03, 2.9442e-03, 2.9519e-03, 2.9595e-03, 2.9671e-03, 2.9747e-03, 2.9824e-03, 2.9900e-03, 2.9976e-03, 3.0053e-03, 3.0129e-03, 3.0205e-03, 3.0281e-03, 3.0358e-03, 3.0434e-03, 3.0510e-03, 3.0587e-03, 3.0663e-03, 3.0739e-03, 3.0816e-03, 3.0892e-03, 3.0968e-03, 3.1044e-03, 3.1121e-03, 3.1197e-03, 3.1273e-03, 3.1350e-03, 3.1426e-03, 3.1502e-03, 3.1578e-03, 3.1655e-03, 3.1731e-03, 3.1807e-03, 3.1884e-03, 3.1960e-03, 3.2036e-03, 3.2112e-03, 3.2189e-03, 3.2265e-03, 3.2341e-03, 3.2418e-03, 3.2494e-03, 3.2570e-03, 3.2646e-03, 3.2723e-03, 3.2799e-03, 3.2875e-03, 3.2952e-03, 3.3028e-03, 3.3104e-03, 3.3180e-03, 3.3257e-03, 3.3333e-03, 3.3409e-03, 3.3486e-03, 3.3562e-03, 3.3638e-03, 3.3715e-03, 3.3791e-03, 3.3867e-03, 3.3943e-03, 3.4020e-03, 3.4096e-03, 3.4172e-03, 3.4249e-03, 3.4325e-03, 3.4401e-03, 3.4477e-03, 3.4554e-03, 3.4630e-03, 3.4706e-03, 3.4783e-03, 3.4859e-03, 3.4935e-03, 3.5011e-03, 3.5088e-03, 3.5164e-03, 3.5240e-03, 3.5317e-03, 3.5393e-03, 3.5469e-03, 3.5545e-03, 3.5622e-03, 3.5698e-03, 3.5774e-03, 3.5851e-03, 3.5927e-03, 3.6003e-03, 3.6079e-03, 3.6156e-03, 3.6232e-03, 3.6308e-03, 3.6385e-03, 3.6461e-03, 3.6537e-03, 3.6613e-03, 3.6690e-03, 3.6766e-03, 3.6842e-03, 3.6919e-03, 3.6995e-03, 3.7071e-03, 3.7148e-03, 3.7224e-03, 3.7300e-03, 3.7376e-03, 3.7453e-03, 3.7529e-03, 3.7605e-03, 3.7682e-03, 3.7758e-03, 3.7834e-03, 3.7910e-03, 3.7987e-03, 3.8063e-03, 3.8139e-03, 3.8216e-03, 3.8292e-03, 3.8368e-03, 3.8444e-03, 3.8521e-03, 3.8597e-03, 3.8673e-03, 3.8750e-03, 3.8826e-03, 3.8902e-03, 3.8978e-03, 3.9055e-03, // NOLINT - 3.9207e-03, 3.9360e-03, 3.9513e-03, 3.9665e-03, 3.9818e-03, 3.9970e-03, 4.0123e-03, 4.0275e-03, 4.0428e-03, 4.0581e-03, 4.0733e-03, 4.0886e-03, 4.1038e-03, 4.1191e-03, 4.1343e-03, 4.1496e-03, 4.1649e-03, 4.1801e-03, 4.1954e-03, 4.2106e-03, 4.2259e-03, 4.2412e-03, 4.2564e-03, 4.2717e-03, 4.2869e-03, 4.3022e-03, 4.3174e-03, 4.3327e-03, 4.3480e-03, 4.3632e-03, 4.3785e-03, 4.3937e-03, 4.4090e-03, 4.4243e-03, 4.4395e-03, 4.4548e-03, 4.4700e-03, 4.4853e-03, 4.5005e-03, 4.5158e-03, 4.5311e-03, 4.5463e-03, 4.5616e-03, 4.5768e-03, 4.5921e-03, 4.6074e-03, 4.6226e-03, 4.6379e-03, 4.6531e-03, 4.6684e-03, 4.6836e-03, 4.6989e-03, 4.7142e-03, 4.7294e-03, 4.7447e-03, 4.7599e-03, 4.7752e-03, 4.7905e-03, 4.8057e-03, 4.8210e-03, 4.8362e-03, 4.8515e-03, 4.8667e-03, 4.8820e-03, 4.8973e-03, 4.9125e-03, 4.9278e-03, 4.9430e-03, 4.9583e-03, 4.9736e-03, 4.9888e-03, 5.0041e-03, 5.0193e-03, 5.0346e-03, 5.0498e-03, 5.0651e-03, 5.0804e-03, 5.0956e-03, 5.1109e-03, 5.1261e-03, 5.1414e-03, 5.1567e-03, 5.1719e-03, 5.1872e-03, 5.2024e-03, 5.2177e-03, 5.2329e-03, 5.2482e-03, 5.2635e-03, 5.2787e-03, 5.2940e-03, 5.3092e-03, 5.3245e-03, 5.3398e-03, 5.3550e-03, 5.3703e-03, 5.3855e-03, 5.4008e-03, 5.4160e-03, 5.4313e-03, 5.4466e-03, 5.4618e-03, 5.4771e-03, 5.4923e-03, 5.5076e-03, 5.5229e-03, 5.5381e-03, 5.5534e-03, 5.5686e-03, 5.5839e-03, 5.5991e-03, 5.6144e-03, 5.6297e-03, 5.6449e-03, 5.6602e-03, 5.6754e-03, 5.6907e-03, 5.7060e-03, 5.7212e-03, 5.7365e-03, 5.7517e-03, 5.7670e-03, 5.7822e-03, 5.7975e-03, 5.8128e-03, 5.8280e-03, 5.8433e-03, 5.8585e-03, 5.8738e-03, 5.8891e-03, 5.9043e-03, 5.9196e-03, 5.9348e-03, 5.9501e-03, 5.9653e-03, 5.9806e-03, 5.9959e-03, 6.0111e-03, 6.0264e-03, 6.0416e-03, 6.0569e-03, 6.0722e-03, 6.0874e-03, 6.1027e-03, 6.1179e-03, 6.1332e-03, 6.1484e-03, 6.1637e-03, 6.1790e-03, 6.1942e-03, 6.2095e-03, 6.2247e-03, 6.2400e-03, 6.2553e-03, 6.2705e-03, 6.2858e-03, 6.3010e-03, 6.3163e-03, 6.3315e-03, 6.3468e-03, 6.3621e-03, 6.3773e-03, 6.3926e-03, 6.4078e-03, 6.4231e-03, 6.4384e-03, 6.4536e-03, 6.4689e-03, 6.4841e-03, 6.4994e-03, 6.5146e-03, 6.5299e-03, 6.5452e-03, 6.5604e-03, 6.5757e-03, 6.5909e-03, 6.6062e-03, 6.6215e-03, 6.6367e-03, 6.6520e-03, 6.6672e-03, 6.6825e-03, 6.6977e-03, 6.7130e-03, 6.7283e-03, 6.7435e-03, 6.7588e-03, 6.7740e-03, 6.7893e-03, 6.8046e-03, 6.8198e-03, 6.8351e-03, 6.8503e-03, 6.8656e-03, 6.8808e-03, 6.8961e-03, 6.9114e-03, 6.9266e-03, 6.9419e-03, 6.9571e-03, 6.9724e-03, 6.9877e-03, 7.0029e-03, 7.0182e-03, 7.0334e-03, 7.0487e-03, 7.0639e-03, 7.0792e-03, 7.0945e-03, 7.1097e-03, 7.1250e-03, 7.1402e-03, 7.1555e-03, 7.1708e-03, 7.1860e-03, 7.2013e-03, 7.2165e-03, 7.2318e-03, 7.2470e-03, 7.2623e-03, 7.2776e-03, 7.2928e-03, 7.3081e-03, 7.3233e-03, 7.3386e-03, 7.3539e-03, 7.3691e-03, 7.3844e-03, 7.3996e-03, 7.4149e-03, 7.4301e-03, 7.4454e-03, 7.4607e-03, 7.4759e-03, 7.4912e-03, 7.5064e-03, 7.5217e-03, 7.5370e-03, 7.5522e-03, 7.5675e-03, 7.5827e-03, 7.5980e-03, 7.6132e-03, 7.6285e-03, 7.6438e-03, 7.6590e-03, 7.6743e-03, 7.6895e-03, 7.7048e-03, 7.7201e-03, 7.7353e-03, 7.7506e-03, 7.7658e-03, 7.7811e-03, 7.7963e-03, 7.8116e-03, // NOLINT - 7.8421e-03, 7.8726e-03, 7.9032e-03, 7.9337e-03, 7.9642e-03, 7.9947e-03, 8.0252e-03, 8.0557e-03, 8.0863e-03, 8.1168e-03, 8.1473e-03, 8.1778e-03, 8.2083e-03, 8.2388e-03, 8.2694e-03, 8.2999e-03, 8.3304e-03, 8.3609e-03, 8.3914e-03, 8.4219e-03, 8.4525e-03, 8.4830e-03, 8.5135e-03, 8.5440e-03, 8.5745e-03, 8.6051e-03, 8.6356e-03, 8.6661e-03, 8.6966e-03, 8.7271e-03, 8.7576e-03, 8.7882e-03, 8.8187e-03, 8.8492e-03, 8.8797e-03, 8.9102e-03, 8.9407e-03, 8.9713e-03, 9.0018e-03, 9.0323e-03, 9.0628e-03, 9.0933e-03, 9.1238e-03, 9.1544e-03, 9.1849e-03, 9.2154e-03, 9.2459e-03, 9.2764e-03, 9.3069e-03, 9.3375e-03, 9.3680e-03, 9.3985e-03, 9.4290e-03, 9.4595e-03, 9.4900e-03, 9.5206e-03, 9.5511e-03, 9.5816e-03, 9.6121e-03, 9.6426e-03, 9.6731e-03, 9.7037e-03, 9.7342e-03, 9.7647e-03, 9.7952e-03, 9.8257e-03, 9.8563e-03, 9.8868e-03, 9.9173e-03, 9.9478e-03, 9.9783e-03, 1.0009e-02, 1.0039e-02, 1.0070e-02, 1.0100e-02, 1.0131e-02, 1.0161e-02, 1.0192e-02, 1.0222e-02, 1.0253e-02, 1.0283e-02, 1.0314e-02, 1.0345e-02, 1.0375e-02, 1.0406e-02, 1.0436e-02, 1.0467e-02, 1.0497e-02, 1.0528e-02, 1.0558e-02, 1.0589e-02, 1.0619e-02, 1.0650e-02, 1.0680e-02, 1.0711e-02, 1.0741e-02, 1.0772e-02, 1.0802e-02, 1.0833e-02, 1.0863e-02, 1.0894e-02, 1.0924e-02, 1.0955e-02, 1.0985e-02, 1.1016e-02, 1.1046e-02, 1.1077e-02, 1.1107e-02, 1.1138e-02, 1.1168e-02, 1.1199e-02, 1.1230e-02, 1.1260e-02, 1.1291e-02, 1.1321e-02, 1.1352e-02, 1.1382e-02, 1.1413e-02, 1.1443e-02, 1.1474e-02, 1.1504e-02, 1.1535e-02, 1.1565e-02, 1.1596e-02, 1.1626e-02, 1.1657e-02, 1.1687e-02, 1.1718e-02, 1.1748e-02, 1.1779e-02, 1.1809e-02, 1.1840e-02, 1.1870e-02, 1.1901e-02, 1.1931e-02, 1.1962e-02, 1.1992e-02, 1.2023e-02, 1.2053e-02, 1.2084e-02, 1.2115e-02, 1.2145e-02, 1.2176e-02, 1.2206e-02, 1.2237e-02, 1.2267e-02, 1.2298e-02, 1.2328e-02, 1.2359e-02, 1.2389e-02, 1.2420e-02, 1.2450e-02, 1.2481e-02, 1.2511e-02, 1.2542e-02, 1.2572e-02, 1.2603e-02, 1.2633e-02, 1.2664e-02, 1.2694e-02, 1.2725e-02, 1.2755e-02, 1.2786e-02, 1.2816e-02, 1.2847e-02, 1.2877e-02, 1.2908e-02, 1.2938e-02, 1.2969e-02, 1.3000e-02, 1.3030e-02, 1.3061e-02, 1.3091e-02, 1.3122e-02, 1.3152e-02, 1.3183e-02, 1.3213e-02, 1.3244e-02, 1.3274e-02, 1.3305e-02, 1.3335e-02, 1.3366e-02, 1.3396e-02, 1.3427e-02, 1.3457e-02, 1.3488e-02, 1.3518e-02, 1.3549e-02, 1.3579e-02, 1.3610e-02, 1.3640e-02, 1.3671e-02, 1.3701e-02, 1.3732e-02, 1.3762e-02, 1.3793e-02, 1.3823e-02, 1.3854e-02, 1.3885e-02, 1.3915e-02, 1.3946e-02, 1.3976e-02, 1.4007e-02, 1.4037e-02, 1.4068e-02, 1.4098e-02, 1.4129e-02, 1.4159e-02, 1.4190e-02, 1.4220e-02, 1.4251e-02, 1.4281e-02, 1.4312e-02, 1.4342e-02, 1.4373e-02, 1.4403e-02, 1.4434e-02, 1.4464e-02, 1.4495e-02, 1.4525e-02, 1.4556e-02, 1.4586e-02, 1.4617e-02, 1.4647e-02, 1.4678e-02, 1.4708e-02, 1.4739e-02, 1.4770e-02, 1.4800e-02, 1.4831e-02, 1.4861e-02, 1.4892e-02, 1.4922e-02, 1.4953e-02, 1.4983e-02, 1.5014e-02, 1.5044e-02, 1.5075e-02, 1.5105e-02, 1.5136e-02, 1.5166e-02, 1.5197e-02, 1.5227e-02, 1.5258e-02, 1.5288e-02, 1.5319e-02, 1.5349e-02, 1.5380e-02, 1.5410e-02, 1.5441e-02, 1.5471e-02, 1.5502e-02, 1.5532e-02, 1.5563e-02, 1.5593e-02, 1.5624e-02, // NOLINT - 1.5746e-02, 1.5868e-02, 1.5990e-02, 1.6112e-02, 1.6234e-02, 1.6356e-02, 1.6478e-02, 1.6601e-02, 1.6723e-02, 1.6845e-02, 1.6967e-02, 1.7089e-02, 1.7211e-02, 1.7333e-02, 1.7455e-02, 1.7577e-02, 1.7699e-02, 1.7821e-02, 1.7943e-02, 1.8065e-02, 1.8187e-02, 1.8310e-02, 1.8432e-02, 1.8554e-02, 1.8676e-02, 1.8798e-02, 1.8920e-02, 1.9042e-02, 1.9164e-02, 1.9286e-02, 1.9408e-02, 1.9530e-02, 1.9652e-02, 1.9774e-02, 1.9896e-02, 2.0018e-02, 2.0141e-02, 2.0263e-02, 2.0385e-02, 2.0507e-02, 2.0629e-02, 2.0751e-02, 2.0873e-02, 2.0995e-02, 2.1117e-02, 2.1239e-02, 2.1361e-02, 2.1483e-02, 2.1605e-02, 2.1727e-02, 2.1850e-02, 2.1972e-02, 2.2094e-02, 2.2216e-02, 2.2338e-02, 2.2460e-02, 2.2582e-02, 2.2704e-02, 2.2826e-02, 2.2948e-02, 2.3070e-02, 2.3192e-02, 2.3314e-02, 2.3436e-02, 2.3558e-02, 2.3681e-02, 2.3803e-02, 2.3925e-02, 2.4047e-02, 2.4169e-02, 2.4291e-02, 2.4413e-02, 2.4535e-02, 2.4657e-02, 2.4779e-02, 2.4901e-02, 2.5023e-02, 2.5145e-02, 2.5267e-02, 2.5390e-02, 2.5512e-02, 2.5634e-02, 2.5756e-02, 2.5878e-02, 2.6000e-02, 2.6122e-02, 2.6244e-02, 2.6366e-02, 2.6488e-02, 2.6610e-02, 2.6732e-02, 2.6854e-02, 2.6976e-02, 2.7099e-02, 2.7221e-02, 2.7343e-02, 2.7465e-02, 2.7587e-02, 2.7709e-02, 2.7831e-02, 2.7953e-02, 2.8075e-02, 2.8197e-02, 2.8319e-02, 2.8441e-02, 2.8563e-02, 2.8685e-02, 2.8807e-02, 2.8930e-02, 2.9052e-02, 2.9174e-02, 2.9296e-02, 2.9418e-02, 2.9540e-02, 2.9662e-02, 2.9784e-02, 2.9906e-02, 3.0028e-02, 3.0150e-02, 3.0272e-02, 3.0394e-02, 3.0516e-02, 3.0639e-02, 3.0761e-02, 3.0883e-02, 3.1005e-02, 3.1127e-02, 3.1249e-02, 3.1493e-02, 3.1737e-02, 3.1981e-02, 3.2225e-02, 3.2470e-02, 3.2714e-02, 3.2958e-02, 3.3202e-02, 3.3446e-02, 3.3690e-02, 3.3934e-02, 3.4179e-02, 3.4423e-02, 3.4667e-02, 3.4911e-02, 3.5155e-02, 3.5399e-02, 3.5643e-02, 3.5888e-02, 3.6132e-02, 3.6376e-02, 3.6620e-02, 3.6864e-02, 3.7108e-02, 3.7352e-02, 3.7596e-02, 3.7841e-02, 3.8085e-02, 3.8329e-02, 3.8573e-02, 3.8817e-02, 3.9061e-02, 3.9305e-02, 3.9550e-02, 3.9794e-02, 4.0038e-02, 4.0282e-02, 4.0526e-02, 4.0770e-02, 4.1014e-02, 4.1259e-02, 4.1503e-02, 4.1747e-02, 4.1991e-02, 4.2235e-02, 4.2479e-02, 4.2723e-02, 4.2968e-02, 4.3212e-02, 4.3456e-02, 4.3700e-02, 4.3944e-02, 4.4188e-02, 4.4432e-02, 4.4677e-02, 4.4921e-02, 4.5165e-02, 4.5409e-02, 4.5653e-02, 4.5897e-02, 4.6141e-02, 4.6386e-02, 4.6630e-02, 4.6874e-02, 4.7118e-02, 4.7362e-02, 4.7606e-02, 4.7850e-02, 4.8095e-02, 4.8339e-02, 4.8583e-02, 4.8827e-02, 4.9071e-02, 4.9315e-02, 4.9559e-02, 4.9803e-02, 5.0048e-02, 5.0292e-02, 5.0536e-02, 5.0780e-02, 5.1024e-02, 5.1268e-02, 5.1512e-02, 5.1757e-02, 5.2001e-02, 5.2245e-02, 5.2489e-02, 5.2733e-02, 5.2977e-02, 5.3221e-02, 5.3466e-02, 5.3710e-02, 5.3954e-02, 5.4198e-02, 5.4442e-02, 5.4686e-02, 5.4930e-02, 5.5175e-02, 5.5419e-02, 5.5663e-02, 5.5907e-02, 5.6151e-02, 5.6395e-02, 5.6639e-02, 5.6884e-02, 5.7128e-02, 5.7372e-02, 5.7616e-02, 5.7860e-02, 5.8104e-02, 5.8348e-02, 5.8593e-02, 5.8837e-02, 5.9081e-02, 5.9325e-02, 5.9569e-02, 5.9813e-02, 6.0057e-02, 6.0301e-02, 6.0546e-02, 6.0790e-02, 6.1034e-02, 6.1278e-02, 6.1522e-02, 6.1766e-02, 6.2010e-02, 6.2255e-02, 6.2499e-02, // NOLINT - 6.2743e-02, 6.2987e-02, 6.3231e-02, 6.3475e-02, 6.3719e-02, 6.3964e-02, 6.4208e-02, 6.4452e-02, 6.4696e-02, 6.4940e-02, 6.5184e-02, 6.5428e-02, 6.5673e-02, 6.5917e-02, 6.6161e-02, 6.6405e-02, 6.6649e-02, 6.6893e-02, 6.7137e-02, 6.7382e-02, 6.7626e-02, 6.7870e-02, 6.8114e-02, 6.8358e-02, 6.8602e-02, 6.8846e-02, 6.9091e-02, 6.9335e-02, 6.9579e-02, 6.9823e-02, 7.0067e-02, 7.0311e-02, 7.0555e-02, 7.0799e-02, 7.1044e-02, 7.1288e-02, 7.1532e-02, 7.1776e-02, 7.2020e-02, 7.2264e-02, 7.2508e-02, 7.2753e-02, 7.2997e-02, 7.3241e-02, 7.3485e-02, 7.3729e-02, 7.3973e-02, 7.4217e-02, 7.4462e-02, 7.4706e-02, 7.4950e-02, 7.5194e-02, 7.5438e-02, 7.5682e-02, 7.5926e-02, 7.6171e-02, 7.6415e-02, 7.6659e-02, 7.6903e-02, 7.7147e-02, 7.7391e-02, 7.7635e-02, 7.7880e-02, 7.8124e-02, 7.8368e-02, 7.8612e-02, 7.8856e-02, 7.9100e-02, 7.9344e-02, 7.9589e-02, 7.9833e-02, 8.0077e-02, 8.0321e-02, 8.0565e-02, 8.0809e-02, 8.1053e-02, 8.1298e-02, 8.1542e-02, 8.1786e-02, 8.2030e-02, 8.2274e-02, 8.2518e-02, 8.2762e-02, 8.3006e-02, 8.3251e-02, 8.3495e-02, 8.3739e-02, 8.3983e-02, 8.4227e-02, 8.4471e-02, 8.4715e-02, 8.4960e-02, 8.5204e-02, 8.5448e-02, 8.5692e-02, 8.5936e-02, 8.6180e-02, 8.6424e-02, 8.6669e-02, 8.6913e-02, 8.7157e-02, 8.7401e-02, 8.7645e-02, 8.7889e-02, 8.8133e-02, 8.8378e-02, 8.8622e-02, 8.8866e-02, 8.9110e-02, 8.9354e-02, 8.9598e-02, 8.9842e-02, 9.0087e-02, 9.0331e-02, 9.0575e-02, 9.0819e-02, 9.1063e-02, 9.1307e-02, 9.1551e-02, 9.1796e-02, 9.2040e-02, 9.2284e-02, 9.2528e-02, 9.2772e-02, 9.3016e-02, 9.3260e-02, 9.3504e-02, 9.3749e-02, 9.4237e-02, 9.4725e-02, 9.5213e-02, 9.5702e-02, 9.6190e-02, 9.6678e-02, 9.7167e-02, 9.7655e-02, 9.8143e-02, 9.8631e-02, 9.9120e-02, 9.9608e-02, 1.0010e-01, 1.0058e-01, 1.0107e-01, 1.0156e-01, 1.0205e-01, 1.0254e-01, 1.0303e-01, 1.0351e-01, 1.0400e-01, 1.0449e-01, 1.0498e-01, 1.0547e-01, 1.0596e-01, 1.0644e-01, 1.0693e-01, 1.0742e-01, 1.0791e-01, 1.0840e-01, 1.0889e-01, 1.0937e-01, 1.0986e-01, 1.1035e-01, 1.1084e-01, 1.1133e-01, 1.1182e-01, 1.1230e-01, 1.1279e-01, 1.1328e-01, 1.1377e-01, 1.1426e-01, 1.1474e-01, 1.1523e-01, 1.1572e-01, 1.1621e-01, 1.1670e-01, 1.1719e-01, 1.1767e-01, 1.1816e-01, 1.1865e-01, 1.1914e-01, 1.1963e-01, 1.2012e-01, 1.2060e-01, 1.2109e-01, 1.2158e-01, 1.2207e-01, 1.2256e-01, 1.2305e-01, 1.2353e-01, 1.2402e-01, 1.2451e-01, 1.2500e-01, 1.2549e-01, 1.2598e-01, 1.2646e-01, 1.2695e-01, 1.2744e-01, 1.2793e-01, 1.2842e-01, 1.2890e-01, 1.2939e-01, 1.2988e-01, 1.3037e-01, 1.3086e-01, 1.3135e-01, 1.3183e-01, 1.3232e-01, 1.3281e-01, 1.3330e-01, 1.3379e-01, 1.3428e-01, 1.3476e-01, 1.3525e-01, 1.3574e-01, 1.3623e-01, 1.3672e-01, 1.3721e-01, 1.3769e-01, 1.3818e-01, 1.3867e-01, 1.3916e-01, 1.3965e-01, 1.4014e-01, 1.4062e-01, 1.4111e-01, 1.4160e-01, 1.4209e-01, 1.4258e-01, 1.4306e-01, 1.4355e-01, 1.4404e-01, 1.4453e-01, 1.4502e-01, 1.4551e-01, 1.4599e-01, 1.4648e-01, 1.4697e-01, 1.4746e-01, 1.4795e-01, 1.4844e-01, 1.4892e-01, 1.4941e-01, 1.4990e-01, 1.5039e-01, 1.5088e-01, 1.5137e-01, 1.5185e-01, 1.5234e-01, 1.5283e-01, 1.5332e-01, 1.5381e-01, 1.5430e-01, 1.5478e-01, 1.5527e-01, 1.5576e-01, 1.5625e-01, // NOLINT - 1.5674e-01, 1.5723e-01, 1.5771e-01, 1.5820e-01, 1.5869e-01, 1.5918e-01, 1.5967e-01, 1.6015e-01, 1.6064e-01, 1.6113e-01, 1.6162e-01, 1.6211e-01, 1.6260e-01, 1.6308e-01, 1.6357e-01, 1.6406e-01, 1.6455e-01, 1.6504e-01, 1.6553e-01, 1.6601e-01, 1.6650e-01, 1.6699e-01, 1.6748e-01, 1.6797e-01, 1.6846e-01, 1.6894e-01, 1.6943e-01, 1.6992e-01, 1.7041e-01, 1.7090e-01, 1.7139e-01, 1.7187e-01, 1.7236e-01, 1.7285e-01, 1.7334e-01, 1.7383e-01, 1.7431e-01, 1.7480e-01, 1.7529e-01, 1.7578e-01, 1.7627e-01, 1.7676e-01, 1.7724e-01, 1.7773e-01, 1.7822e-01, 1.7871e-01, 1.7920e-01, 1.7969e-01, 1.8017e-01, 1.8066e-01, 1.8115e-01, 1.8164e-01, 1.8213e-01, 1.8262e-01, 1.8310e-01, 1.8359e-01, 1.8408e-01, 1.8457e-01, 1.8506e-01, 1.8555e-01, 1.8603e-01, 1.8652e-01, 1.8701e-01, 1.8750e-01, 1.8848e-01, 1.8945e-01, 1.9043e-01, 1.9140e-01, 1.9238e-01, 1.9336e-01, 1.9433e-01, 1.9531e-01, 1.9629e-01, 1.9726e-01, 1.9824e-01, 1.9922e-01, 2.0019e-01, 2.0117e-01, 2.0215e-01, 2.0312e-01, 2.0410e-01, 2.0508e-01, 2.0605e-01, 2.0703e-01, 2.0801e-01, 2.0898e-01, 2.0996e-01, 2.1094e-01, 2.1191e-01, 2.1289e-01, 2.1387e-01, 2.1484e-01, 2.1582e-01, 2.1680e-01, 2.1777e-01, 2.1875e-01, 2.1972e-01, 2.2070e-01, 2.2168e-01, 2.2265e-01, 2.2363e-01, 2.2461e-01, 2.2558e-01, 2.2656e-01, 2.2754e-01, 2.2851e-01, 2.2949e-01, 2.3047e-01, 2.3144e-01, 2.3242e-01, 2.3340e-01, 2.3437e-01, 2.3535e-01, 2.3633e-01, 2.3730e-01, 2.3828e-01, 2.3926e-01, 2.4023e-01, 2.4121e-01, 2.4219e-01, 2.4316e-01, 2.4414e-01, 2.4512e-01, 2.4609e-01, 2.4707e-01, 2.4805e-01, 2.4902e-01, 2.5000e-01, 2.5097e-01, 2.5195e-01, 2.5293e-01, 2.5390e-01, 2.5488e-01, 2.5586e-01, 2.5683e-01, 2.5781e-01, 2.5879e-01, 2.5976e-01, 2.6074e-01, 2.6172e-01, 2.6269e-01, 2.6367e-01, 2.6465e-01, 2.6562e-01, 2.6660e-01, 2.6758e-01, 2.6855e-01, 2.6953e-01, 2.7051e-01, 2.7148e-01, 2.7246e-01, 2.7344e-01, 2.7441e-01, 2.7539e-01, 2.7637e-01, 2.7734e-01, 2.7832e-01, 2.7930e-01, 2.8027e-01, 2.8125e-01, 2.8222e-01, 2.8320e-01, 2.8418e-01, 2.8515e-01, 2.8613e-01, 2.8711e-01, 2.8808e-01, 2.8906e-01, 2.9004e-01, 2.9101e-01, 2.9199e-01, 2.9297e-01, 2.9394e-01, 2.9492e-01, 2.9590e-01, 2.9687e-01, 2.9785e-01, 2.9883e-01, 2.9980e-01, 3.0078e-01, 3.0176e-01, 3.0273e-01, 3.0371e-01, 3.0469e-01, 3.0566e-01, 3.0664e-01, 3.0762e-01, 3.0859e-01, 3.0957e-01, 3.1055e-01, 3.1152e-01, 3.1250e-01, 3.1347e-01, 3.1445e-01, 3.1543e-01, 3.1640e-01, 3.1738e-01, 3.1836e-01, 3.1933e-01, 3.2031e-01, 3.2129e-01, 3.2226e-01, 3.2324e-01, 3.2422e-01, 3.2519e-01, 3.2617e-01, 3.2715e-01, 3.2812e-01, 3.2910e-01, 3.3008e-01, 3.3105e-01, 3.3203e-01, 3.3301e-01, 3.3398e-01, 3.3496e-01, 3.3594e-01, 3.3691e-01, 3.3789e-01, 3.3887e-01, 3.3984e-01, 3.4082e-01, 3.4180e-01, 3.4277e-01, 3.4375e-01, 3.4472e-01, 3.4570e-01, 3.4668e-01, 3.4765e-01, 3.4863e-01, 3.4961e-01, 3.5058e-01, 3.5156e-01, 3.5254e-01, 3.5351e-01, 3.5449e-01, 3.5547e-01, 3.5644e-01, 3.5742e-01, 3.5840e-01, 3.5937e-01, 3.6035e-01, 3.6133e-01, 3.6230e-01, 3.6328e-01, 3.6426e-01, 3.6523e-01, 3.6621e-01, 3.6719e-01, 3.6816e-01, 3.6914e-01, 3.7012e-01, 3.7109e-01, 3.7207e-01, 3.7305e-01, 3.7402e-01, 3.7500e-01, // NOLINT - 3.7695e-01, 3.7890e-01, 3.8086e-01, 3.8281e-01, 3.8476e-01, 3.8672e-01, 3.8867e-01, 3.9062e-01, 3.9258e-01, 3.9453e-01, 3.9648e-01, 3.9844e-01, 4.0039e-01, 4.0234e-01, 4.0430e-01, 4.0625e-01, 4.0820e-01, 4.1015e-01, 4.1211e-01, 4.1406e-01, 4.1601e-01, 4.1797e-01, 4.1992e-01, 4.2187e-01, 4.2383e-01, 4.2578e-01, 4.2773e-01, 4.2969e-01, 4.3164e-01, 4.3359e-01, 4.3555e-01, 4.3750e-01, 4.3945e-01, 4.4140e-01, 4.4336e-01, 4.4531e-01, 4.4726e-01, 4.4922e-01, 4.5117e-01, 4.5312e-01, 4.5508e-01, 4.5703e-01, 4.5898e-01, 4.6094e-01, 4.6289e-01, 4.6484e-01, 4.6680e-01, 4.6875e-01, 4.7070e-01, 4.7265e-01, 4.7461e-01, 4.7656e-01, 4.7851e-01, 4.8047e-01, 4.8242e-01, 4.8437e-01, 4.8633e-01, 4.8828e-01, 4.9023e-01, 4.9219e-01, 4.9414e-01, 4.9609e-01, 4.9805e-01, 5.0000e-01, 5.0195e-01, 5.0390e-01, 5.0586e-01, 5.0781e-01, 5.0976e-01, 5.1172e-01, 5.1367e-01, 5.1562e-01, 5.1758e-01, 5.1953e-01, 5.2148e-01, 5.2344e-01, 5.2539e-01, 5.2734e-01, 5.2930e-01, 5.3125e-01, 5.3320e-01, 5.3515e-01, 5.3711e-01, 5.3906e-01, 5.4101e-01, 5.4297e-01, 5.4492e-01, 5.4687e-01, 5.4883e-01, 5.5078e-01, 5.5273e-01, 5.5469e-01, 5.5664e-01, 5.5859e-01, 5.6055e-01, 5.6250e-01, 5.6445e-01, 5.6640e-01, 5.6836e-01, 5.7031e-01, 5.7226e-01, 5.7422e-01, 5.7617e-01, 5.7812e-01, 5.8008e-01, 5.8203e-01, 5.8398e-01, 5.8594e-01, 5.8789e-01, 5.8984e-01, 5.9180e-01, 5.9375e-01, 5.9570e-01, 5.9765e-01, 5.9961e-01, 6.0156e-01, 6.0351e-01, 6.0547e-01, 6.0742e-01, 6.0937e-01, 6.1133e-01, 6.1328e-01, 6.1523e-01, 6.1719e-01, 6.1914e-01, 6.2109e-01, 6.2305e-01, 6.2500e-01, 6.2695e-01, 6.2890e-01, 6.3086e-01, 6.3281e-01, 6.3476e-01, 6.3672e-01, 6.3867e-01, 6.4062e-01, 6.4258e-01, 6.4453e-01, 6.4648e-01, 6.4844e-01, 6.5039e-01, 6.5234e-01, 6.5430e-01, 6.5625e-01, 6.5820e-01, 6.6015e-01, 6.6211e-01, 6.6406e-01, 6.6601e-01, 6.6797e-01, 6.6992e-01, 6.7187e-01, 6.7383e-01, 6.7578e-01, 6.7773e-01, 6.7969e-01, 6.8164e-01, 6.8359e-01, 6.8554e-01, 6.8750e-01, 6.8945e-01, 6.9140e-01, 6.9336e-01, 6.9531e-01, 6.9726e-01, 6.9922e-01, 7.0117e-01, 7.0312e-01, 7.0508e-01, 7.0703e-01, 7.0898e-01, 7.1094e-01, 7.1289e-01, 7.1484e-01, 7.1679e-01, 7.1875e-01, 7.2070e-01, 7.2265e-01, 7.2461e-01, 7.2656e-01, 7.2851e-01, 7.3047e-01, 7.3242e-01, 7.3437e-01, 7.3633e-01, 7.3828e-01, 7.4023e-01, 7.4219e-01, 7.4414e-01, 7.4609e-01, 7.4804e-01, 7.5000e-01, 7.5390e-01, 7.5781e-01, 7.6172e-01, 7.6562e-01, 7.6953e-01, 7.7344e-01, 7.7734e-01, 7.8125e-01, 7.8515e-01, 7.8906e-01, 7.9297e-01, 7.9687e-01, 8.0078e-01, 8.0469e-01, 8.0859e-01, 8.1250e-01, 8.1640e-01, 8.2031e-01, 8.2422e-01, 8.2812e-01, 8.3203e-01, 8.3594e-01, 8.3984e-01, 8.4375e-01, 8.4765e-01, 8.5156e-01, 8.5547e-01, 8.5937e-01, 8.6328e-01, 8.6719e-01, 8.7109e-01, 8.7500e-01, 8.7890e-01, 8.8281e-01, 8.8672e-01, 8.9062e-01, 8.9453e-01, 8.9844e-01, 9.0234e-01, 9.0625e-01, 9.1015e-01, 9.1406e-01, 9.1797e-01, 9.2187e-01, 9.2578e-01, 9.2969e-01, 9.3359e-01, 9.3750e-01, 9.4140e-01, 9.4531e-01, 9.4922e-01, 9.5312e-01, 9.5703e-01, 9.6094e-01, 9.6484e-01, 9.6875e-01, 9.7265e-01, 9.7656e-01, 9.8047e-01, 9.8437e-01, 9.8828e-01, 9.9219e-01, 9.9609e-01, 1.0000e+00 // NOLINT -}; +float ox_lut_func(int x) { + if (x < 512) { + return x * 5.94873e-8; + } else if (512 <= x && x < 768) { + return 3.0458e-05 + (x-512) * 1.19913e-7; + } else if (768 <= x && x < 1536) { + return 6.1154e-05 + (x-768) * 2.38493e-7; + } else if (1536 <= x && x < 1792) { + return 0.0002448 + (x-1536) * 9.56930e-7; + } else if (1792 <= x && x < 2048) { + return 0.00048977 + (x-1792) * 1.91441e-6; + } else if (2048 <= x && x < 2304) { + return 0.00097984 + (x-2048) * 3.82937e-6; + } else if (2304 <= x && x < 2560) { + return 0.0019601 + (x-2304) * 7.659055e-6; + } else if (2560 <= x && x < 2816) { + return 0.0039207 + (x-2560) * 1.525e-5; + } else { + return 0.0078421 + (exp((x-2816)/273.0) - 1) * 0.0092421; + } +} float4 normalize_pv(int4 parsed, float vignette_factor) { // PWL - float4 pv = {ox03c10_lut[parsed.s0], ox03c10_lut[parsed.s1], ox03c10_lut[parsed.s2], ox03c10_lut[parsed.s3]}; + float4 pv = {ox_lut_func(parsed.s0), ox_lut_func(parsed.s1), ox_lut_func(parsed.s2), ox_lut_func(parsed.s3)}; return clamp(pv*vignette_factor*256.0, 0.0, 1.0); } @@ -40,4 +43,4 @@ float3 apply_gamma(float3 rgb, int expo_time) { return -0.507089*exp(-12.54124638*rgb) + 0.9655*powr(rgb, 0.5) - 0.472597*rgb + 0.507089; } -#endif \ No newline at end of file +#endif diff --git a/system/camerad/sensors/ox03c10_registers.h b/system/camerad/sensors/ox03c10_registers.h index 575a2cb93472be1..ffa0b795747bd04 100644 --- a/system/camerad/sensors/ox03c10_registers.h +++ b/system/camerad/sensors/ox03c10_registers.h @@ -31,6 +31,7 @@ const struct i2c_random_wr_payload init_array_ox03c10[] = { // delay launch group 2 {0x3208, 0xa2},*/ + // **NOTE**: if this is changed, readout_time_ns must be updated in the Sensor config // PLL setup {0x0301, 0xc8}, // pll1_divs, pll1_predivp, pll1_divpix {0x0303, 0x01}, // pll1_prediv diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h index add514b117bac42..1651fd8061f8260 100644 --- a/system/camerad/sensors/sensor.h +++ b/system/camerad/sensors/sensor.h @@ -5,8 +5,11 @@ #include #include #include + +#include "media/cam_isp.h" #include "media/cam_sensor.h" -#include "system/camerad/cameras/camera_common.h" + +#include "cereal/gen/cpp/log.capnp.h" #include "system/camerad/sensors/ar0231_registers.h" #include "system/camerad/sensors/ox03c10_registers.h" #include "system/camerad/sensors/os04c10_registers.h" @@ -19,7 +22,7 @@ class SensorInfo { 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 {} + virtual void processRegisters(uint8_t *cur_buf, cereal::FrameData::Builder &framed) const {} cereal::FrameData::ImageSensor image_sensor = cereal::FrameData::ImageSensor::UNKNOWN; float pixel_size_mm; @@ -57,9 +60,27 @@ class SensorInfo { std::vector start_reg_array; std::vector init_reg_array; + uint32_t bits_per_pixel; + uint32_t bayer_pattern; uint32_t mipi_format; uint32_t mclk_frequency; uint32_t frame_data_type; + + uint32_t readout_time_ns; // used to recover EOF from SOF + + // ISP image processing params + uint32_t black_level; + std::vector color_correct_matrix; // 3x3 + std::vector gamma_lut_rgb; // gamma LUTs are length 64 * sizeof(uint32_t); same for r/g/b here + void prepare_gamma_lut() { + for (int i = 0; i < 64; i++) { + gamma_lut_rgb[i] |= ((uint32_t)(gamma_lut_rgb[i+1] - gamma_lut_rgb[i]) << 10); + } + gamma_lut_rgb.pop_back(); + } + std::vector linearization_lut; // length 288 + std::vector linearization_pts; // length 4 + std::vector vignetting_lut; // 2x length 884 }; class AR0231 : public SensorInfo { @@ -68,7 +89,7 @@ class AR0231 : public SensorInfo { 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; + void processRegisters(uint8_t *cur_buf, cereal::FrameData::Builder &framed) const override; private: mutable std::map> ar0231_register_lut; diff --git a/system/camerad/snapshot/snapshot.py b/system/camerad/snapshot/snapshot.py index 4ba38c1df4b19f9..b3369891d7f91df 100755 --- a/system/camerad/snapshot/snapshot.py +++ b/system/camerad/snapshot/snapshot.py @@ -10,7 +10,7 @@ from openpilot.common.params import Params from openpilot.common.realtime import DT_MDL from openpilot.system.hardware import PC -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.manager.process_config import managed_processes diff --git a/system/camerad/test/debug.sh b/system/camerad/test/debug.sh new file mode 100755 index 000000000000000..44ff0ffa89f9848 --- /dev/null +++ b/system/camerad/test/debug.sh @@ -0,0 +1,16 @@ +#!/usr/bin/env bash +set -e + +#echo 4294967295 | sudo tee /sys/module/cam_debug_util/parameters/debug_mdl + +# no CCI and UTIL, very spammy +echo 0xfffdbfff | sudo tee /sys/module/cam_debug_util/parameters/debug_mdl +echo 0 | sudo tee /sys/module/cam_debug_util/parameters/debug_mdl + +sudo dmesg -C +scons -u -j8 --minimal . +export DEBUG_FRAMES=1 +#export DISABLE_ROAD=1 DISABLE_WIDE_ROAD=1 +export DISABLE_DRIVER=1 +#export LOGPRINT=debug +./camerad diff --git a/system/camerad/test/intercept.sh b/system/camerad/test/intercept.sh new file mode 100755 index 000000000000000..e269929afc5feba --- /dev/null +++ b/system/camerad/test/intercept.sh @@ -0,0 +1,2 @@ +#!/usr/bin/env bash +DISABLE_ROAD=1 DISABLE_WIDE_ROAD=1 DEBUG_FRAMES=1 LOGPRINT=debug LD_PRELOAD=/data/tici_test_scripts/isp/interceptor/tmpioctl.so ./camerad diff --git a/system/camerad/test/test_ae_gray.cc b/system/camerad/test/test_ae_gray.cc index be9a0cc59f20f83..0620551ec64526d 100644 --- a/system/camerad/test/test_ae_gray.cc +++ b/system/camerad/test/test_ae_gray.cc @@ -34,11 +34,11 @@ TEST_CASE("camera.test_set_exposure_target") { uint8_t * fb_y = new uint8_t[W*H]; vb.y = fb_y; cb.cur_yuv_buf = &vb; - cb.rgb_width = W; - cb.rgb_height = H; + cb.out_img_width = W; + cb.out_img_height = H; Rect rect = {0, 0, W-1, H-1}; - printf("AE test patterns %dx%d\n", cb.rgb_width, cb.rgb_height); + printf("AE test patterns %dx%d\n", cb.out_img_width, cb.out_img_height); // mix of 5 tones uint8_t l[5] = {0, 24, 48, 96, 235}; // 235 is yuv max diff --git a/system/camerad/test/test_camerad.py b/system/camerad/test/test_camerad.py index ada9594895e425a..07a68e0020b62c8 100644 --- a/system/camerad/test/test_camerad.py +++ b/system/camerad/test/test_camerad.py @@ -9,7 +9,7 @@ from cereal.services import SERVICE_LIST from openpilot.system.manager.process_config import managed_processes -TEST_TIMESPAN = 30 +TEST_TIMESPAN = 10 LAG_FRAME_TOLERANCE = {log.FrameData.ImageSensor.ar0231: 0.5, # ARs use synced pulses for frame starts log.FrameData.ImageSensor.ox03c10: 1.1} # OXs react to out-of-sync at next frame FRAME_DELTA_TOLERANCE = {log.FrameData.ImageSensor.ar0231: 1.0, @@ -21,39 +21,40 @@ @flaky(max_runs=3) @pytest.mark.tici class TestCamerad: - def setup_method(self): + @classmethod + def setup_class(cls): # run camerad and record logs managed_processes['camerad'].start() time.sleep(3) socks = {c: messaging.sub_sock(c, conflate=False, timeout=100) for c in CAMERAS} - self.logs = defaultdict(list) + cls.logs = defaultdict(list) start_time = time.monotonic() while time.monotonic()- start_time < TEST_TIMESPAN: for cam, s in socks.items(): - self.logs[cam] += messaging.drain_sock(s) + cls.logs[cam] += messaging.drain_sock(s) time.sleep(0.2) managed_processes['camerad'].stop() - self.log_by_frame_id = defaultdict(list) - self.sensor_type = None - for cam, msgs in self.logs.items(): - if self.sensor_type is None: - self.sensor_type = getattr(msgs[0], msgs[0].which()).sensor.raw + cls.log_by_frame_id = defaultdict(list) + cls.sensor_type = None + for cam, msgs in cls.logs.items(): + if cls.sensor_type is None: + cls.sensor_type = getattr(msgs[0], msgs[0].which()).sensor.raw expected_frames = SERVICE_LIST[cam].frequency * TEST_TIMESPAN assert expected_frames*0.95 < len(msgs) < expected_frames*1.05, f"unexpected frame count {cam}: {expected_frames=}, got {len(msgs)}" dts = np.abs(np.diff([getattr(m, m.which()).timestampSof/1e6 for m in msgs]) - 1000/SERVICE_LIST[cam].frequency) - assert (dts < FRAME_DELTA_TOLERANCE[self.sensor_type]).all(), f"{cam} dts(ms) out of spec: max diff {dts.max()}, 99 percentile {np.percentile(dts, 99)}" + assert (dts < FRAME_DELTA_TOLERANCE[cls.sensor_type]).all(), f"{cam} dts(ms) out of spec: max diff {dts.max()}, 99 percentile {np.percentile(dts, 99)}" for m in msgs: - self.log_by_frame_id[getattr(m, m.which()).frameId].append(m) + cls.log_by_frame_id[getattr(m, m.which()).frameId].append(m) # strip beginning and end for _ in range(3): - mn, mx = min(self.log_by_frame_id.keys()), max(self.log_by_frame_id.keys()) - del self.log_by_frame_id[mn] - del self.log_by_frame_id[mx] + mn, mx = min(cls.log_by_frame_id.keys()), max(cls.log_by_frame_id.keys()) + del cls.log_by_frame_id[mn] + del cls.log_by_frame_id[mx] def test_frame_skips(self): skips = {} diff --git a/system/hardware/base.py b/system/hardware/base.py index 6cdb4a4d64e676e..620f2c71b8b9d2a 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -41,10 +41,6 @@ def get_os_version(self): def get_device_type(self): pass - @abstractmethod - def get_sound_card_online(self): - pass - @abstractmethod def get_imei(self, slot) -> str: pass diff --git a/system/hardware/fan_controller.py b/system/hardware/fan_controller.py index f32133f6bf09a6d..f72e183cde94790 100755 --- a/system/hardware/fan_controller.py +++ b/system/hardware/fan_controller.py @@ -4,7 +4,7 @@ from openpilot.common.realtime import DT_HW from openpilot.common.numpy_fast import interp from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.controls.lib.pid import PIDController +from openpilot.common.pid import PIDController class BaseFanController(ABC): @abstractmethod diff --git a/system/hardware/hardwared.py b/system/hardware/hardwared.py index e3a4c81711879e0..da3172e8d16975f 100755 --- a/system/hardware/hardwared.py +++ b/system/hardware/hardwared.py @@ -16,7 +16,7 @@ from openpilot.common.filter_simple import FirstOrderFilter from openpilot.common.params import Params from openpilot.common.realtime import DT_HW -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.hardware import HARDWARE, TICI, AGNOS from openpilot.system.loggerd.config import get_available_percent from openpilot.system.statsd import statlog @@ -148,8 +148,7 @@ def hw_state_thread(end_event, hw_queue): except queue.Full: pass - # TODO: remove this once the config is in AGNOS - if not modem_configured and len(HARDWARE.get_sim_info().get('sim_id', '')) > 0: + if not modem_configured and HARDWARE.get_modem_version() is not None: cloudlog.warning("configuring modem") HARDWARE.configure_modem() modem_configured = True @@ -164,7 +163,7 @@ def hw_state_thread(end_event, hw_queue): def hardware_thread(end_event, hw_queue) -> None: pm = messaging.PubMaster(['deviceState']) - sm = messaging.SubMaster(["peripheralState", "gpsLocationExternal", "controlsState", "pandaStates"], poll="pandaStates") + sm = messaging.SubMaster(["peripheralState", "gpsLocationExternal", "selfdriveState", "pandaStates"], poll="pandaStates") count = 0 @@ -230,8 +229,8 @@ def hardware_thread(end_event, hw_queue) -> None: onroad_conditions["ignition"] = False cloudlog.error("panda timed out onroad") - # Run at 2Hz, plus rising edge of ignition - ign_edge = started_ts is None and onroad_conditions["ignition"] + # Run at 2Hz, plus either edge of ignition + ign_edge = (started_ts is not None) != onroad_conditions["ignition"] if (sm.frame % round(SERVICE_LIST['pandaStates'].frequency * DT_HW) != 0) and not ign_edge: continue @@ -316,7 +315,7 @@ def hardware_thread(end_event, hw_queue) -> None: set_offroad_alert_if_changed("Offroad_TemperatureTooHigh", show_alert, extra_text=extra_text) # TODO: this should move to TICI.initialize_hardware, but we currently can't import params there - if TICI: + if TICI and HARDWARE.get_device_type() == "tici": if not os.path.isfile("/persist/comma/living-in-the-moment"): if not Path("/data/media").is_mount(): set_offroad_alert_if_changed("Offroad_StorageMissing", True) @@ -341,8 +340,8 @@ def hardware_thread(end_event, hw_queue) -> None: engaged_prev = False HARDWARE.set_power_save(not should_start) - if sm.updated['controlsState']: - engaged = sm['controlsState'].enabled + if sm.updated['selfdriveState']: + engaged = sm['selfdriveState'].enabled if engaged != engaged_prev: params.put_bool("IsEngaged", engaged) engaged_prev = engaged diff --git a/system/hardware/pc/hardware.py b/system/hardware/pc/hardware.py index 719e272aea1639a..a2cbafeae8b811e 100644 --- a/system/hardware/pc/hardware.py +++ b/system/hardware/pc/hardware.py @@ -14,9 +14,6 @@ def get_os_version(self): def get_device_type(self): return "pc" - def get_sound_card_online(self): - return True - def reboot(self, reason=None): print("REBOOT!") diff --git a/system/hardware/tici/agnos.json b/system/hardware/tici/agnos.json index b1862bdef9351fb..3aa712a6b0ea0f9 100644 --- a/system/hardware/tici/agnos.json +++ b/system/hardware/tici/agnos.json @@ -1,39 +1,49 @@ [ { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-5674ea6767e7198cf1e7def3de66a57061f001ed76d43dc4b4f84de545c53c6f.img.xz", - "hash": "5674ea6767e7198cf1e7def3de66a57061f001ed76d43dc4b4f84de545c53c6f", - "hash_raw": "5674ea6767e7198cf1e7def3de66a57061f001ed76d43dc4b4f84de545c53c6f", - "size": 16029696, + "url": "https://commadist.azureedge.net/agnosupdate-staging/boot-184b9edb429167dcc97110134cdeffaa9739a758b3069e3ea7700e6559b79a0a.img.xz", + "hash": "184b9edb429167dcc97110134cdeffaa9739a758b3069e3ea7700e6559b79a0a", + "hash_raw": "184b9edb429167dcc97110134cdeffaa9739a758b3069e3ea7700e6559b79a0a", + "size": 16414720, "sparse": false, "full_check": true, "has_ab": true }, { - "name": "abl", - "url": "https://commadist.azureedge.net/agnosupdate/abl-eeb89a74c968a5a2ffce96f23158b72e03e2814adf72ef59d1200ba8ea5d2f39.img.xz", - "hash": "eeb89a74c968a5a2ffce96f23158b72e03e2814adf72ef59d1200ba8ea5d2f39", - "hash_raw": "eeb89a74c968a5a2ffce96f23158b72e03e2814adf72ef59d1200ba8ea5d2f39", - "size": 274432, + "name": "system", + "url": "https://commadist.azureedge.net/agnosupdate-staging/system-93a86656670d6d8d99ea401bd5735cd1060c2355d65f2c14de522c77a80c57ea.img.xz", + "hash": "93a86656670d6d8d99ea401bd5735cd1060c2355d65f2c14de522c77a80c57ea", + "hash_raw": "93a86656670d6d8d99ea401bd5735cd1060c2355d65f2c14de522c77a80c57ea", + "size": 4404019200, "sparse": false, - "full_check": true, + "full_check": false, "has_ab": true }, { "name": "xbl", - "url": "https://commadist.azureedge.net/agnosupdate/xbl-bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5.img.xz", - "hash": "bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5", - "hash_raw": "bcef195b00a1ab685da601f4072722569773ab161e91c8753ad99ca4217a28f5", - "size": 3282672, + "url": "https://commadist.azureedge.net/agnosupdate/xbl-446e37054b4c2f08bac3ee9d98256cdb93e876fb3343acfc8881124900f11050.img.xz", + "hash": "446e37054b4c2f08bac3ee9d98256cdb93e876fb3343acfc8881124900f11050", + "hash_raw": "446e37054b4c2f08bac3ee9d98256cdb93e876fb3343acfc8881124900f11050", + "size": 3282256, + "sparse": false, + "full_check": true, + "has_ab": true + }, + { + "name": "abl", + "url": "https://commadist.azureedge.net/agnosupdate/abl-32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6.img.xz", + "hash": "32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6", + "hash_raw": "32a2174b5f764e95dfc54cf358ba01752943b1b3b90e626149c3da7d5f1830b6", + "size": 274432, "sparse": false, "full_check": true, "has_ab": true }, { "name": "xbl_config", - "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac.img.xz", - "hash": "19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac", - "hash_raw": "19791056558c16f8dae787531b5e30b3b3db2ded9d666688df45ce1b91a72bac", + "url": "https://commadist.azureedge.net/agnosupdate/xbl_config-80f3e644529d30e260bb9b8b6c765d76a4ccd0a2d3104cc07acf93b0eabb8995.img.xz", + "hash": "80f3e644529d30e260bb9b8b6c765d76a4ccd0a2d3104cc07acf93b0eabb8995", + "hash_raw": "80f3e644529d30e260bb9b8b6c765d76a4ccd0a2d3104cc07acf93b0eabb8995", "size": 98124, "sparse": false, "full_check": true, @@ -41,9 +51,9 @@ }, { "name": "devcfg", - "url": "https://commadist.azureedge.net/agnosupdate/devcfg-be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27.img.xz", - "hash": "be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27", - "hash_raw": "be44b73dda5be840b09d5347d536459e31098da3fea97596956c0bdad19bdf27", + "url": "https://commadist.azureedge.net/agnosupdate/devcfg-8ea8a9e779b0bd43af41ed367e3c781ba666012eebb4707ce58328b81219f9f8.img.xz", + "hash": "8ea8a9e779b0bd43af41ed367e3c781ba666012eebb4707ce58328b81219f9f8", + "hash_raw": "8ea8a9e779b0bd43af41ed367e3c781ba666012eebb4707ce58328b81219f9f8", "size": 40336, "sparse": false, "full_check": true, @@ -51,27 +61,12 @@ }, { "name": "aop", - "url": "https://commadist.azureedge.net/agnosupdate/aop-5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f.img.xz", - "hash": "5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f", - "hash_raw": "5d764611a683d6a738cf06a1dcf8a926d0f47b5117ad40d3054167de6dd8bd0f", + "url": "https://commadist.azureedge.net/agnosupdate/aop-c1dbeefa20e742dde97eac76aaa00d1e6c2e2b01cfbd4c1242bd4e26c7d2aed4.img.xz", + "hash": "c1dbeefa20e742dde97eac76aaa00d1e6c2e2b01cfbd4c1242bd4e26c7d2aed4", + "hash_raw": "c1dbeefa20e742dde97eac76aaa00d1e6c2e2b01cfbd4c1242bd4e26c7d2aed4", "size": 184364, "sparse": false, "full_check": true, "has_ab": true - }, - { - "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-1badfe72851628d6cf9200a53a6151bb4e797b49c717141409fc57138eae388a.img.xz", - "hash": "328e90c62068222dfd98f71dd3f6251fcb962f082b49c6be66ab2699f5db6f4f", - "hash_raw": "1badfe72851628d6cf9200a53a6151bb4e797b49c717141409fc57138eae388a", - "size": 10737418240, - "sparse": true, - "full_check": false, - "has_ab": true, - "alt": { - "hash": "bc11d2148f29862ee1326aca2af1cf6bbf5fed831e3f8f6b8f7a0f110dfe8d26", - "url": "https://commadist.azureedge.net/agnosupdate/system-skip-chunks-1badfe72851628d6cf9200a53a6151bb4e797b49c717141409fc57138eae388a.img.xz", - "size": 4548070000 - } } ] \ No newline at end of file diff --git a/system/hardware/tici/agnos.py b/system/hardware/tici/agnos.py index 7e3536f775c932b..f5261953d5c4686 100755 --- a/system/hardware/tici/agnos.py +++ b/system/hardware/tici/agnos.py @@ -29,16 +29,23 @@ def __init__(self, url: str) -> None: self.sha256 = hashlib.sha256() def read(self, length: int) -> bytes: - while len(self.buf) < length: - self.req.raise_for_status() + while len(self.buf) < length and not self.eof: + if self.decompressor.needs_input: + self.req.raise_for_status() - try: - compressed = next(self.it) - except StopIteration: + try: + compressed = next(self.it) + except StopIteration: + self.eof = True + break + else: + compressed = b'' + + self.buf += self.decompressor.decompress(compressed, max_length=length) + + if self.decompressor.eof: self.eof = True break - out = self.decompressor.decompress(compressed) - self.buf += out result = self.buf[:length] self.buf = self.buf[length:] @@ -83,8 +90,8 @@ def unsparsify(f: StreamingDecompressor) -> Generator[bytes, None, None]: # noop wrapper with same API as unsparsify() for non sparse images def noop(f: StreamingDecompressor) -> Generator[bytes, None, None]: - while not f.eof: - yield f.read(1024 * 1024) + while len(chunk := f.read(1024 * 1024)) > 0: + yield chunk def get_target_slot_number() -> int: diff --git a/system/hardware/tici/amplifier.py b/system/hardware/tici/amplifier.py index af82067467eaf18..f6b29ec0cebad8f 100755 --- a/system/hardware/tici/amplifier.py +++ b/system/hardware/tici/amplifier.py @@ -125,13 +125,15 @@ def _set_configs(self, configs: list[AmpConfig]) -> None: def set_configs(self, configs: list[AmpConfig]) -> bool: # retry in case panda is using the amp tries = 15 - for i in range(15): + backoff = 0. + for i in range(tries): try: self._set_configs(configs) return True except OSError: + backoff += 0.1 + time.sleep(backoff) print(f"Failed to set amp config, {tries - i - 1} retries left") - time.sleep(0.02) return False def set_global_shutdown(self, amp_disabled: bool) -> bool: diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index a5dee88b562dba1..8110a0808e44b17 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -123,12 +123,6 @@ def get_os_version(self): def get_device_type(self): return get_device_type() - def get_sound_card_online(self): - if os.path.isfile('/proc/asound/card0/state'): - with open('/proc/asound/card0/state') as f: - return f.read().strip() == 'ONLINE' - return False - def reboot(self, reason=None): subprocess.check_output(["sudo", "reboot"]) @@ -431,8 +425,8 @@ def initialize_hardware(self): # *** GPU config *** # https://github.com/commaai/agnos-kernel-sdm845/blob/master/arch/arm64/boot/dts/qcom/sdm845-gpu.dtsi#L216 - sudo_write("1", "/sys/class/kgsl/kgsl-3d0/min_pwrlevel") - sudo_write("1", "/sys/class/kgsl/kgsl-3d0/max_pwrlevel") + sudo_write("0", "/sys/class/kgsl/kgsl-3d0/min_pwrlevel") + sudo_write("0", "/sys/class/kgsl/kgsl-3d0/max_pwrlevel") sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_bus_on") sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_clk_on") sudo_write("1", "/sys/class/kgsl/kgsl-3d0/force_rail_on") @@ -473,8 +467,9 @@ def configure_modem(self): cmds = [] if manufacturer == 'Cavli Inc.': cmds += [ - # use sim slot - 'AT^SIMSWAP=1', + 'AT^SIMSWAP=1', # use SIM slot, instead of internal eSIM + 'AT$QCSIMSLEEP=0', # disable SIM sleep + 'AT$QCSIMCFG=SimPowerSave,0', # more sleep disable # ethernet config 'AT$QCPCFG=usbNet,0', @@ -563,8 +558,10 @@ def has_internal_panda(self): def reset_internal_panda(self): gpio_init(GPIO.STM_RST_N, True) + gpio_init(GPIO.STM_BOOT0, True) gpio_set(GPIO.STM_RST_N, 1) + gpio_set(GPIO.STM_BOOT0, 0) time.sleep(1) gpio_set(GPIO.STM_RST_N, 0) diff --git a/system/hardware/tici/id_rsa b/system/hardware/tici/id_rsa new file mode 100644 index 000000000000000..3f269afe2283572 --- /dev/null +++ b/system/hardware/tici/id_rsa @@ -0,0 +1,28 @@ +-----BEGIN RSA PRIVATE KEY----- +MIIEvAIBADANBgkqhkiG9w0BAQEFAASCBKYwggSiAgEAAoIBAQC+iXXq30Tq+J5N +Kat3KWHCzcmwZ55nGh6WggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXB +t6gEvZ8nd04E7eLA9LTZyFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCt +Z+004ikLxmyFeBO8NOcErW1pa8gFdQDToH9FrA7kgysic/XVESTOoe7XlzRoe/eZ +acEQ+jtnmFd21A4aEADkk00Ahjr0uKaJiLUAPatxs2icIXWpgYtfqqtaKF23wSt6 +1OTu6cAwXbOWr3m+IUSRUO0IRzEIQS3z1jfd1svgzSgSSwZ1Lhj4AoKxIEAIc8qJ +rO4uymCJAgMBAAECggEBAISFevxHGdoL3Z5xkw6oO5SQKO2GxEeVhRzNgmu/HA+q +x8OryqD6O1CWY4037kft6iWxlwiLOdwna2P25ueVM3LxqdQH2KS4DmlCx+kq6FwC +gv063fQPMhC9LpWimvaQSPEC7VUPjQlo4tPY6sTTYBUOh0A1ihRm/x7juKuQCWix +Cq8C/DVnB1X4mGj+W3nJc5TwVJtgJbbiBrq6PWrhvB/3qmkxHRL7dU2SBb2iNRF1 +LLY30dJx/cD73UDKNHrlrsjk3UJc29Mp4/MladKvUkRqNwlYxSuAtJV0nZ3+iFkL +s3adSTHdJpClQer45R51rFDlVsDz2ZBpb/hRNRoGDuECgYEA6A1EixLq7QYOh3cb +Xhyh3W4kpVvA/FPfKH1OMy3ONOD/Y9Oa+M/wthW1wSoRL2n+uuIW5OAhTIvIEivj +6bAZsTT3twrvOrvYu9rx9aln4p8BhyvdjeW4kS7T8FP5ol6LoOt2sTP3T1LOuJPO +uQvOjlKPKIMh3c3RFNWTnGzMPa0CgYEA0jNiPLxP3A2nrX0keKDI+VHuvOY88gdh +0W5BuLMLovOIDk9aQFIbBbMuW1OTjHKv9NK+Lrw+YbCFqOGf1dU/UN5gSyE8lX/Q +FsUGUqUZx574nJZnOIcy3ONOnQLcvHAQToLFAGUd7PWgP3CtHkt9hEv2koUwL4vo +ikTP1u9Gkc0CgYEA2apoWxPZrY963XLKBxNQecYxNbLFaWq67t3rFnKm9E8BAICi +4zUaE5J1tMVi7Vi9iks9Ml9SnNyZRQJKfQ+kaebHXbkyAaPmfv+26rqHKboA0uxA +nDOZVwXX45zBkp6g1sdHxJx8JLoGEnkC9eyvSi0C//tRLx86OhLErXwYcNkCf1it +VMRKrWYoXJTUNo6tRhvodM88UnnIo3u3CALjhgU4uC1RTMHV4ZCGBwiAOb8GozSl +s5YD1E1iKwEULloHnK6BIh6P5v8q7J6uf/xdqoKMjlWBHgq6/roxKvkSPA1DOZ3l +jTadcgKFnRUmc+JT9p/ZbCxkA/ALFg8++G+0ghECgYA8vG3M/utweLvq4RI7l7U7 +b+i2BajfK2OmzNi/xugfeLjY6k2tfQGRuv6ppTjehtji2uvgDWkgjJUgPfZpir3I +RsVMUiFgloWGHETOy0Qvc5AwtqTJFLTD1Wza2uBilSVIEsg6Y83Gickh+ejOmEsY +6co17RFaAZHwGfCFFjO76Q== +-----END RSA PRIVATE KEY----- diff --git a/system/hardware/tici/restart_modem.sh b/system/hardware/tici/restart_modem.sh index 3c67d9d21d7dc75..741dc72050fe326 100755 --- a/system/hardware/tici/restart_modem.sh +++ b/system/hardware/tici/restart_modem.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/usr/bin/env bash #nmcli connection modify --temporary lte gsm.home-only yes #nmcli connection modify --temporary lte gsm.auto-config yes diff --git a/system/hardware/tici/tests/test_hardware.py b/system/hardware/tici/tests/test_hardware.py deleted file mode 100644 index 75f53e7cdb8efcf..000000000000000 --- a/system/hardware/tici/tests/test_hardware.py +++ /dev/null @@ -1,26 +0,0 @@ -import pytest -import time -import numpy as np - -from openpilot.system.hardware.tici.hardware import Tici - -HARDWARE = Tici() - - -@pytest.mark.tici -class TestHardware: - - def test_power_save_time(self): - ts = {True: [], False: []} - for _ in range(5): - for on in (True, False): - st = time.monotonic() - HARDWARE.set_power_save(on) - ts[on].append(time.monotonic() - st) - - # disabling power save is the main time-critical one - assert 0.1 < np.mean(ts[False]) < 0.15 - assert max(ts[False]) < 0.2 - - assert 0.1 < np.mean(ts[True]) < 0.35 - assert max(ts[True]) < 0.4 diff --git a/system/hardware/tici/tests/test_power_draw.py b/system/hardware/tici/tests/test_power_draw.py index 866f7d118809d08..0ef34549b584726 100644 --- a/system/hardware/tici/tests/test_power_draw.py +++ b/system/hardware/tici/tests/test_power_draw.py @@ -7,8 +7,9 @@ import cereal.messaging as messaging from cereal.services import SERVICE_LIST +from opendbc.car.car_helpers import get_demo_car_params from openpilot.common.mock import mock_messages -from openpilot.selfdrive.car.car_helpers import write_car_param +from openpilot.common.params import Params from openpilot.system.hardware.tici.power_monitor import get_power from openpilot.system.manager.process_config import managed_processes from openpilot.system.manager.manager import manager_cleanup @@ -32,7 +33,7 @@ def name(self): PROCS = [ Proc(['camerad'], 2.1, msgs=['roadCameraState', 'wideRoadCameraState', 'driverCameraState']), Proc(['modeld'], 1.12, atol=0.2, msgs=['modelV2']), - Proc(['dmonitoringmodeld'], 0.4, msgs=['driverStateV2']), + Proc(['dmonitoringmodeld'], 0.5, msgs=['driverStateV2']), Proc(['encoderd'], 0.23, msgs=[]), ] @@ -41,7 +42,7 @@ def name(self): class TestPowerDraw: def setup_method(self): - write_car_param() + Params().put("CarParams", get_demo_car_params().to_bytes()) # wait a bit for power save to disable time.sleep(5) @@ -94,7 +95,7 @@ def get_power_with_warmup_for_target(self, proc, prev): return now, msg_counts, time.monotonic() - start_time - SAMPLE_TIME - @mock_messages(['liveLocationKalman']) + @mock_messages(['livePose']) def test_camera_procs(self, subtests): baseline = get_power() diff --git a/system/hardware/tici/updater b/system/hardware/tici/updater index 1c5775120054945..5773489ecaa783d 100755 Binary files a/system/hardware/tici/updater and b/system/hardware/tici/updater differ diff --git a/system/logcatd/SConscript b/system/logcatd/SConscript index ac2a79a1f2e017f..39c45d10931fae0 100644 --- a/system/logcatd/SConscript +++ b/system/logcatd/SConscript @@ -1,3 +1,3 @@ Import('env', 'messaging', 'common') -env.Program('logcatd', 'logcatd_systemd.cc', LIBS=[messaging, common, 'systemd', 'json11']) +env.Program('logcatd', 'logcatd_systemd.cc', LIBS=[messaging, common, 'systemd']) diff --git a/system/loggerd/README.md b/system/loggerd/README.md deleted file mode 100644 index 714e4242a04508a..000000000000000 --- a/system/loggerd/README.md +++ /dev/null @@ -1,30 +0,0 @@ -# loggerd - -openpilot records routes in one minute chunks called segments. A route starts on the rising edge of ignition and ends on the falling edge. - -Check out our [python library](https://github.com/commaai/openpilot/blob/master/tools/lib/logreader.py) for reading openpilot logs. Also checkout our [tools](https://github.com/commaai/openpilot/tree/master/tools) to replay and view your data. These are the same tools we use to debug and develop openpilot. - -## log types - -For each segment, openpilot records the following log types: - -## rlog.bz2 - -rlogs contain all the messages passed amongst openpilot's processes. See [cereal/services.py](https://github.com/commaai/cereal/blob/master/services.py) for a list of all the logged services. They're a bzip2 archive of the serialized capnproto messages. - -## {f,e,d}camera.hevc - -Each camera stream is H.265 encoded and written to its respective file. -* fcamera.hevc is the road camera -* ecamera.hevc is the wide road camera -* dcamera.hevc is the driver camera - -## qlog.bz2 & qcamera.ts - -qlogs are a decimated subset of the rlogs. Check out [cereal/services.py](https://github.com/commaai/cereal/blob/master/services.py) for the decimation. - - -qcameras are H.264 encoded, lower res versions of the fcamera.hevc. The video shown in [comma connect](https://connect.comma.ai/) is from the qcameras. - - -qlogs and qcameras are designed to be small enough to upload instantly on slow internet and store forever, yet useful enough for most analysis and debugging. diff --git a/system/loggerd/deleter.py b/system/loggerd/deleter.py index 2f0b96c90e02b90..7d83b490b0ff7f2 100755 --- a/system/loggerd/deleter.py +++ b/system/loggerd/deleter.py @@ -37,9 +37,9 @@ def get_preserved_segments(dirs_by_creation: list[str]) -> list[str]: except ValueError: continue - # preserve segment and its prior - preserved.append(d) - preserved.append(f"{date_str}--{seg_num - 1}") + # preserve segment and two prior + for _seg_num in range(max(0, seg_num - 2), seg_num + 1): + preserved.append(f"{date_str}--{_seg_num}") return preserved diff --git a/system/loggerd/encoder/encoder.h b/system/loggerd/encoder/encoder.h index 72848609efbf4b7..1296f78f6101cce 100644 --- a/system/loggerd/encoder/encoder.h +++ b/system/loggerd/encoder/encoder.h @@ -1,5 +1,13 @@ #pragma once +// has to be in this order +#ifdef __linux__ +#include "third_party/linux/include/v4l2-controls.h" +#include +#else +#define V4L2_BUF_FLAG_KEYFRAME 8 +#endif + #include #include #include @@ -9,11 +17,8 @@ #include "cereal/messaging/messaging.h" #include "msgq/visionipc/visionipc.h" #include "common/queue.h" -#include "system/camerad/cameras/camera_common.h" #include "system/loggerd/loggerd.h" -#define V4L2_BUF_FLAG_KEYFRAME 8 - class VideoEncoder { public: VideoEncoder(const EncoderInfo &encoder_info, int in_width, int in_height); diff --git a/system/loggerd/encoderd.cc b/system/loggerd/encoderd.cc index 1b45df68278fb29..feb9a921ec8bb5f 100644 --- a/system/loggerd/encoderd.cc +++ b/system/loggerd/encoderd.cc @@ -18,12 +18,12 @@ struct EncoderdState { // Sync logic for startup std::atomic encoders_ready = 0; std::atomic start_frame_id = 0; - bool camera_ready[WideRoadCam + 1] = {}; - bool camera_synced[WideRoadCam + 1] = {}; + bool camera_ready[VISION_STREAM_WIDE_ROAD + 1] = {}; + bool camera_synced[VISION_STREAM_WIDE_ROAD + 1] = {}; }; // Handle initial encoder syncing by waiting for all encoders to reach the same frame id -bool sync_encoders(EncoderdState *s, CameraType cam_type, uint32_t frame_id) { +bool sync_encoders(EncoderdState *s, VisionStreamType cam_type, uint32_t frame_id) { if (s->camera_synced[cam_type]) return true; if (s->max_waiting > 1 && s->encoders_ready != s->max_waiting) { @@ -59,7 +59,7 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { // init encoders if (encoders.empty()) { - VisionBuf buf_info = vipc_client.buffers[0]; + const VisionBuf &buf_info = vipc_client.buffers[0]; LOGW("encoder %s init %zux%zu", cam_info.thread_name, buf_info.width, buf_info.height); assert(buf_info.width > 0 && buf_info.height > 0); @@ -85,7 +85,7 @@ void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { } lagging = false; - if (!sync_encoders(s, cam_info.type, extra.frame_id)) { + if (!sync_encoders(s, cam_info.stream_type, extra.frame_id)) { continue; } if (do_exit) break; diff --git a/system/loggerd/logger.cc b/system/loggerd/logger.cc index 8234cd84ade9d4b..213aa69d3e7a802 100644 --- a/system/loggerd/logger.cc +++ b/system/loggerd/logger.cc @@ -40,7 +40,7 @@ kj::Array logger_build_init_data() { init.setOsVersion(util::read_file("/VERSION")); // log params - auto params = Params(util::getenv("PARAMS_COPY_PATH", "")); + Params params(util::getenv("PARAMS_COPY_PATH", "")); std::map params_map = params.readAll(); init.setGitCommit(params_map["GitCommit"]); diff --git a/system/loggerd/loggerd.cc b/system/loggerd/loggerd.cc index a324479fb5de8fe..c9632c0dd60c7ce 100644 --- a/system/loggerd/loggerd.cc +++ b/system/loggerd/loggerd.cc @@ -15,8 +15,8 @@ ExitHandler do_exit; struct LoggerdState { LoggerState logger; - std::atomic last_camera_seen_tms; - std::atomic ready_to_rotate; // count of encoders ready to rotate + std::atomic last_camera_seen_tms{0.0}; + std::atomic ready_to_rotate{0}; // count of encoders ready to rotate int max_waiting = 0; double last_rotate_tms = 0.; // last rotate time in ms }; diff --git a/system/loggerd/loggerd.h b/system/loggerd/loggerd.h index 7c80ba51a214cd2..e8cdadda065f541 100644 --- a/system/loggerd/loggerd.h +++ b/system/loggerd/loggerd.h @@ -5,7 +5,6 @@ #include "cereal/messaging/messaging.h" #include "cereal/services.h" #include "msgq/visionipc/visionipc_client.h" -#include "system/camerad/cameras/camera_common.h" #include "system/hardware/hw.h" #include "common/params.h" #include "common/swaglog.h" @@ -51,7 +50,6 @@ class LogCameraInfo { public: const char *thread_name; int fps = MAIN_FPS; - CameraType type; VisionStreamType stream_type; std::vector encoder_infos; }; @@ -112,42 +110,36 @@ const EncoderInfo qcam_encoder_info = { const LogCameraInfo road_camera_info{ .thread_name = "road_cam_encoder", - .type = RoadCam, .stream_type = VISION_STREAM_ROAD, .encoder_infos = {main_road_encoder_info, qcam_encoder_info} }; const LogCameraInfo wide_road_camera_info{ .thread_name = "wide_road_cam_encoder", - .type = WideRoadCam, .stream_type = VISION_STREAM_WIDE_ROAD, .encoder_infos = {main_wide_road_encoder_info} }; const LogCameraInfo driver_camera_info{ .thread_name = "driver_cam_encoder", - .type = DriverCam, .stream_type = VISION_STREAM_DRIVER, .encoder_infos = {main_driver_encoder_info} }; const LogCameraInfo stream_road_camera_info{ .thread_name = "road_cam_encoder", - .type = RoadCam, .stream_type = VISION_STREAM_ROAD, .encoder_infos = {stream_road_encoder_info} }; const LogCameraInfo stream_wide_road_camera_info{ .thread_name = "wide_road_cam_encoder", - .type = WideRoadCam, .stream_type = VISION_STREAM_WIDE_ROAD, .encoder_infos = {stream_wide_road_encoder_info} }; const LogCameraInfo stream_driver_camera_info{ .thread_name = "driver_cam_encoder", - .type = DriverCam, .stream_type = VISION_STREAM_DRIVER, .encoder_infos = {stream_driver_encoder_info} }; diff --git a/system/loggerd/tests/test_encoder.py b/system/loggerd/tests/test_encoder.py index 75862a9d457969b..cf38c8bc31e21c4 100644 --- a/system/loggerd/tests/test_encoder.py +++ b/system/loggerd/tests/test_encoder.py @@ -61,7 +61,7 @@ def test_log_rotation(self, record_front): time.sleep(1.0) managed_processes['camerad'].start() - num_segments = int(os.getenv("SEGMENTS", random.randint(10, 15))) + num_segments = int(os.getenv("SEGMENTS", random.randint(2, 8))) # wait for loggerd to make the dir for first segment route_prefix_path = None diff --git a/system/loggerd/tests/test_loggerd.py b/system/loggerd/tests/test_loggerd.py index 6a24540acf75107..34abe553a186875 100644 --- a/system/loggerd/tests/test_loggerd.py +++ b/system/loggerd/tests/test_loggerd.py @@ -7,7 +7,7 @@ import time from collections import defaultdict from pathlib import Path -from flaky import flaky +import pytest import cereal.messaging as messaging from cereal import log @@ -136,7 +136,7 @@ def test_init_data_values(self): assert getattr(initData, initData_key) == v assert logged_params[param_key].decode() == v - @flaky(max_runs=3) + @pytest.mark.skip("FIXME: encoderd sometimes crashes in CI when running with pytest-xdist") def test_rotation(self): os.environ["LOGGERD_TEST"] = "1" Params().put("RecordFront", "1") @@ -150,7 +150,7 @@ def test_rotation(self): pm = messaging.PubMaster(["roadCameraState", "driverCameraState", "wideRoadCameraState"]) vipc_server = VisionIpcServer("camerad") for stream_type, frame_spec, _ in streams: - vipc_server.create_buffers_with_sizes(stream_type, 40, False, *(frame_spec)) + vipc_server.create_buffers_with_sizes(stream_type, 40, *(frame_spec)) vipc_server.start_listener() num_segs = random.randint(2, 5) @@ -281,4 +281,3 @@ def test_not_preserving_unflagged_segments(self): segment_dir = self._get_latest_log_dir() assert getxattr(segment_dir, PRESERVE_ATTR_NAME) is None - diff --git a/system/loggerd/tests/test_uploader.py b/system/loggerd/tests/test_uploader.py index 6591198281b9929..961a8aa36f8caec 100644 --- a/system/loggerd/tests/test_uploader.py +++ b/system/loggerd/tests/test_uploader.py @@ -62,10 +62,10 @@ def gen_files(self, lock=False, xattr: bytes = None, boot=True) -> list[Path]: def gen_order(self, seg1: list[int], seg2: list[int], boot=True) -> list[str]: keys = [] if boot: - keys += [f"boot/{self.seg_format.format(i)}.bz2" for i in seg1] - keys += [f"boot/{self.seg_format2.format(i)}.bz2" for i in seg2] - keys += [f"{self.seg_format.format(i)}/qlog.bz2" for i in seg1] - keys += [f"{self.seg_format2.format(i)}/qlog.bz2" for i in seg2] + keys += [f"boot/{self.seg_format.format(i)}.zst" for i in seg1] + keys += [f"boot/{self.seg_format2.format(i)}.zst" for i in seg2] + keys += [f"{self.seg_format.format(i)}/qlog.zst" for i in seg1] + keys += [f"{self.seg_format2.format(i)}/qlog.zst" for i in seg2] return keys def test_upload(self): @@ -73,7 +73,7 @@ def test_upload(self): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(1) self.join_thread() exp_order = self.gen_order([self.seg_num], []) @@ -91,7 +91,7 @@ def test_upload_with_wrong_xattr(self): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(1) self.join_thread() exp_order = self.gen_order([self.seg_num], []) @@ -110,7 +110,7 @@ def test_upload_ignored(self): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(1) self.join_thread() exp_order = self.gen_order([self.seg_num], []) @@ -137,7 +137,7 @@ def test_upload_files_in_create_order(self): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(1) self.join_thread() assert len(log_handler.upload_ignored) == 0, "Some files were ignored" @@ -155,11 +155,11 @@ def test_no_upload_with_lock_file(self): f_paths = self.gen_files(lock=True, boot=False) # allow enough time that files should have been uploaded if they would be uploaded - time.sleep(5) + time.sleep(1) self.join_thread() for f_path in f_paths: - fn = f_path.with_suffix(f_path.suffix.replace(".bz2", "")) + fn = f_path.with_suffix(f_path.suffix.replace(".zst", "")) uploaded = UPLOAD_ATTR_NAME in os.listxattr(fn) and os.getxattr(fn, UPLOAD_ATTR_NAME) == UPLOAD_ATTR_VALUE assert not uploaded, "File upload when locked" @@ -168,7 +168,7 @@ def test_no_upload_with_xattr(self): self.start_thread() # allow enough time that files could upload twice if there is a bug in the logic - time.sleep(5) + time.sleep(1) self.join_thread() assert len(log_handler.upload_order) == 0, "File uploaded again" @@ -176,7 +176,7 @@ def test_no_upload_with_xattr(self): def test_clear_locks_on_startup(self): f_paths = self.gen_files(lock=True, boot=False) self.start_thread() - time.sleep(1) + time.sleep(0.25) self.join_thread() for f_path in f_paths: diff --git a/system/loggerd/uploader.py b/system/loggerd/uploader.py index 832a227798e49d3..965d74bef8653d7 100755 --- a/system/loggerd/uploader.py +++ b/system/loggerd/uploader.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 -import bz2 import io import json import os @@ -9,7 +8,7 @@ import time import traceback import datetime -from typing import BinaryIO +import zstandard as zstd from collections.abc import Iterator from cereal import log @@ -26,6 +25,7 @@ UPLOAD_ATTR_VALUE = b'1' UPLOAD_QLOG_QCAM_MAX_SIZE = 5 * 1e6 # MB +LOG_COMPRESSION_LEVEL = 10 # little benefit up to level 15. level ~17 is a small step change allow_sleep = bool(os.getenv("UPLOADER_SLEEP", "1")) force_wifi = os.getenv("FORCEWIFI") is not None @@ -83,7 +83,7 @@ def __init__(self, dongle_id: str, root: str): self.last_filename = "" self.immediate_folders = ["crash/", "boot/"] - self.immediate_priority = {"qlog": 0, "qlog.bz2": 0, "qcamera.ts": 1} + self.immediate_priority = {"qlog": 0, "qlog.zst": 0, "qcamera.ts": 1} def list_upload_files(self, metered: bool) -> Iterator[tuple[str, str, str]]: r = self.params.get("AthenadRecentlyViewedRoutes", encoding="utf8") @@ -151,14 +151,12 @@ def do_upload(self, key: str, fn: str): 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 + content = f.read() + if key.endswith('.zst') and not fn.endswith('.zst'): + content = zstd.compress(content, LOG_COMPRESSION_LEVEL) - return requests.put(url, data=data, headers=headers, timeout=10) + with io.BytesIO(content) as data: + 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: @@ -218,8 +216,8 @@ def step(self, network_type: int, metered: bool) -> bool | 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" + if key.endswith(('qlog', 'rlog')) or (key.startswith('boot/') and not key.endswith('.zst')): + key += ".zst" return self.upload(name, key, fn, network_type, metered) diff --git a/system/logmessaged.py b/system/logmessaged.py index 46bf79b0b21cb6c..c095c261926b8c3 100755 --- a/system/logmessaged.py +++ b/system/logmessaged.py @@ -31,7 +31,7 @@ def main() -> NoReturn: if len(record) > 2*1024*1024: print("WARNING: log too big to publish", len(record)) - print(print(record[:100])) + print(record[:100]) continue # then we publish them diff --git a/system/manager/manager.py b/system/manager/manager.py index 6d1b8d9c22726c4..9ebbdf422def831 100755 --- a/system/manager/manager.py +++ b/system/manager/manager.py @@ -10,7 +10,7 @@ import openpilot.system.sentry as sentry from openpilot.common.params import Params, ParamKeyType from openpilot.common.text_window import TextWindow -from openpilot.system.hardware import HARDWARE, PC +from openpilot.system.hardware import HARDWARE from openpilot.system.manager.helpers import unblock_stdout, write_onroad_params, save_bootlog from openpilot.system.manager.process import ensure_running from openpilot.system.manager.process_config import managed_processes @@ -41,8 +41,6 @@ def manager_init() -> None: ("OpenpilotEnabledToggle", "1"), ("LongitudinalPersonality", str(log.LongitudinalPersonality.standard)), ] - if not PC: - default_params.append(("LastUpdateTime", datetime.datetime.utcnow().isoformat().encode('utf8'))) if params.get_bool("RecordFrontLock"): params.put_bool("RecordFront", True) diff --git a/system/manager/process.py b/system/manager/process.py index 36f299ae628b229..10c8f74f9dd8eb4 100644 --- a/system/manager/process.py +++ b/system/manager/process.py @@ -30,7 +30,7 @@ def launcher(proc: str, name: str) -> None: setproctitle(proc) # create new context since we forked - messaging.context = messaging.Context() + messaging.reset_context() # add daemon name tag to logs cloudlog.bind(daemon=name) diff --git a/system/manager/process_config.py b/system/manager/process_config.py index ced31077c9e14c3..f5f983700ed67db 100644 --- a/system/manager/process_config.py +++ b/system/manager/process_config.py @@ -1,4 +1,5 @@ import os +import operator from cereal import car from openpilot.common.params import Params @@ -16,31 +17,49 @@ def notcar(started: bool, params: Params, CP: car.CarParams) -> bool: def iscar(started: bool, params: Params, CP: car.CarParams) -> bool: return started and not CP.notCar -def logging(started, params, CP: car.CarParams) -> bool: +def logging(started: bool, params: Params, CP: car.CarParams) -> bool: run = (not CP.notCar) or not params.get_bool("DisableLogging") return started and run def ublox_available() -> bool: return os.path.exists('/dev/ttyHS0') and not os.path.exists('/persist/comma/use-quectel-gps') -def ublox(started, params, CP: car.CarParams) -> bool: +def ublox(started: bool, params: Params, CP: car.CarParams) -> bool: use_ublox = ublox_available() if use_ublox != params.get_bool("UbloxAvailable"): params.put_bool("UbloxAvailable", use_ublox) return started and use_ublox -def qcomgps(started, params, CP: car.CarParams) -> bool: +def joystick(started: bool, params: Params, CP: car.CarParams) -> bool: + return started and params.get_bool("JoystickDebugMode") + +def not_joystick(started: bool, params: Params, CP: car.CarParams) -> bool: + return started and not params.get_bool("JoystickDebugMode") + +def long_maneuver(started: bool, params: Params, CP: car.CarParams) -> bool: + return started and params.get_bool("LongitudinalManeuverMode") + +def not_long_maneuver(started: bool, params: Params, CP: car.CarParams) -> bool: + return started and not params.get_bool("LongitudinalManeuverMode") + +def qcomgps(started: bool, params: Params, CP: car.CarParams) -> bool: return started and not ublox_available() -def always_run(started, params, CP: car.CarParams) -> bool: +def always_run(started: bool, params: Params, CP: car.CarParams) -> bool: return True -def only_onroad(started: bool, params, CP: car.CarParams) -> bool: +def only_onroad(started: bool, params: Params, CP: car.CarParams) -> bool: return started -def only_offroad(started, params, CP: car.CarParams) -> bool: +def only_offroad(started: bool, params: Params, CP: car.CarParams) -> bool: return not started +def or_(*fns): + return lambda *args: operator.or_(*(fn(*args) for fn in fns)) + +def and_(*fns): + return lambda *args: operator.and_(*(fn(*args) for fn in fns)) + procs = [ DaemonProcess("manage_athenad", "system.athena.manage_athenad", "AthenadPid"), @@ -51,7 +70,7 @@ def only_offroad(started, params, CP: car.CarParams) -> bool: PythonProcess("micd", "system.micd", iscar), PythonProcess("timed", "system.timed", always_run, enabled=not PC), - PythonProcess("dmonitoringmodeld", "selfdrive.modeld.dmonitoringmodeld", driverview, enabled=(not PC or WEBCAM)), + NativeProcess("dmonitoringmodeld", "selfdrive/modeld", ["./dmonitoringmodeld"], driverview, enabled=(not PC or WEBCAM)), NativeProcess("encoderd", "system/loggerd", ["./encoderd"], only_onroad), NativeProcess("stream_encoderd", "system/loggerd", ["./encoderd", "--stream"], notcar), NativeProcess("loggerd", "system/loggerd", ["./loggerd"], logging), @@ -59,22 +78,24 @@ def only_offroad(started, params, CP: car.CarParams) -> bool: 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)), PythonProcess("soundd", "selfdrive.ui.soundd", only_onroad), - NativeProcess("locationd", "selfdrive/locationd", ["./locationd"], only_onroad), + PythonProcess("locationd", "selfdrive.locationd.locationd", only_onroad), NativeProcess("pandad", "selfdrive/pandad", ["./pandad"], always_run, enabled=False), PythonProcess("calibrationd", "selfdrive.locationd.calibrationd", only_onroad), PythonProcess("torqued", "selfdrive.locationd.torqued", only_onroad), - PythonProcess("controlsd", "selfdrive.controls.controlsd", only_onroad), + PythonProcess("controlsd", "selfdrive.controls.controlsd", and_(not_joystick, iscar)), + PythonProcess("joystickd", "tools.joystick.joystickd", or_(joystick, notcar)), + PythonProcess("selfdrived", "selfdrive.selfdrived.selfdrived", only_onroad), PythonProcess("card", "selfdrive.car.card", only_onroad), PythonProcess("deleter", "system.loggerd.deleter", always_run), PythonProcess("dmonitoringd", "selfdrive.monitoring.dmonitoringd", driverview, enabled=(not PC or WEBCAM)), PythonProcess("qcomgpsd", "system.qcomgpsd.qcomgpsd", qcomgps, enabled=TICI), #PythonProcess("ugpsd", "system.ugpsd", only_onroad, enabled=TICI), - PythonProcess("navd", "selfdrive.navd.navd", only_onroad), PythonProcess("pandad", "selfdrive.pandad.pandad", always_run), PythonProcess("paramsd", "selfdrive.locationd.paramsd", only_onroad), NativeProcess("ubloxd", "system/ubloxd", ["./ubloxd"], ublox, enabled=TICI), PythonProcess("pigeond", "system.ubloxd.pigeond", ublox, enabled=TICI), - PythonProcess("plannerd", "selfdrive.controls.plannerd", only_onroad), + PythonProcess("plannerd", "selfdrive.controls.plannerd", not_long_maneuver), + PythonProcess("maneuversd", "tools.longitudinal_maneuvers.maneuversd", long_maneuver), PythonProcess("radard", "selfdrive.controls.radard", only_onroad), PythonProcess("hardwared", "system.hardware.hardwared", always_run), PythonProcess("tombstoned", "system.tombstoned", always_run, enabled=not PC), @@ -86,6 +107,7 @@ def only_offroad(started, params, CP: car.CarParams) -> bool: NativeProcess("bridge", "cereal/messaging", ["./bridge"], notcar), PythonProcess("webrtcd", "system.webrtc.webrtcd", notcar), PythonProcess("webjoystick", "tools.bodyteleop.web", notcar), + PythonProcess("joystick", "tools.joystick.joystick_control", and_(joystick, iscar)), ] managed_processes = {p.name: p for p in procs} diff --git a/system/manager/test/test_manager.py b/system/manager/test/test_manager.py index e5960d1113632c2..497f4f8240014aa 100644 --- a/system/manager/test/test_manager.py +++ b/system/manager/test/test_manager.py @@ -18,7 +18,6 @@ BLACKLIST_PROCS = ['manage_athenad', 'pandad', 'pigeond'] -@pytest.mark.tici class TestManager: def setup_method(self): HARDWARE.set_power_save(False) diff --git a/system/micd.py b/system/micd.py index 8b738ebe939bcfe..af1aa3136063a71 100755 --- a/system/micd.py +++ b/system/micd.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 import numpy as np +from functools import cache from cereal import messaging from openpilot.common.realtime import Ratekeeper @@ -10,7 +11,16 @@ FFT_SAMPLES = 4096 REFERENCE_SPL = 2e-5 # newtons/m^2 SAMPLE_RATE = 44100 -SAMPLE_BUFFER = 4096 # (approx 100ms) +SAMPLE_BUFFER = 4096 # approx 100ms + + +@cache +def get_a_weighting_filter(): + # Calculate the A-weighting filter + # https://en.wikipedia.org/wiki/A-weighting + freqs = np.fft.fftfreq(FFT_SAMPLES, d=1 / SAMPLE_RATE) + A = 12194 ** 2 * freqs ** 4 / ((freqs ** 2 + 20.6 ** 2) * (freqs ** 2 + 12194 ** 2) * np.sqrt((freqs ** 2 + 107.7 ** 2) * (freqs ** 2 + 737.9 ** 2))) + return A / np.max(A) def calculate_spl(measurements): @@ -27,16 +37,8 @@ def apply_a_weighting(measurements: np.ndarray) -> np.ndarray: # Generate a Hanning window of the same length as the audio measurements measurements_windowed = measurements * np.hanning(len(measurements)) - # Calculate the frequency axis for the signal - freqs = np.fft.fftfreq(measurements_windowed.size, d=1 / SAMPLE_RATE) - - # Calculate the A-weighting filter - # https://en.wikipedia.org/wiki/A-weighting - A = 12194 ** 2 * freqs ** 4 / ((freqs ** 2 + 20.6 ** 2) * (freqs ** 2 + 12194 ** 2) * np.sqrt((freqs ** 2 + 107.7 ** 2) * (freqs ** 2 + 737.9 ** 2))) - A /= np.max(A) # Normalize the filter - # Apply the A-weighting filter to the signal - return np.abs(np.fft.ifft(np.fft.fft(measurements_windowed) * A)) + return np.abs(np.fft.ifft(np.fft.fft(measurements_windowed) * get_a_weighting_filter())) class Mic: diff --git a/system/proclogd/SConscript b/system/proclogd/SConscript index 9ca8e73542f5dca..08814d5ccb0a0c2 100644 --- a/system/proclogd/SConscript +++ b/system/proclogd/SConscript @@ -1,5 +1,5 @@ Import('env', 'messaging', 'common') -libs = [messaging, 'pthread', 'common', 'zmq', 'json11'] +libs = [messaging, 'pthread', common] env.Program('proclogd', ['main.cc', 'proclog.cc'], LIBS=libs) if GetOption('extras'): diff --git a/system/qcomgpsd/qcomgpsd.py b/system/qcomgpsd/qcomgpsd.py index 21c7995a779d184..43ddb8993994ca5 100755 --- a/system/qcomgpsd/qcomgpsd.py +++ b/system/qcomgpsd/qcomgpsd.py @@ -173,7 +173,7 @@ def setup_quectel(diag: ModemDiag) -> bool: os.remove(ASSIST_DATA_FILE) #at_cmd("AT+QGPSXTRADATA?") if system_time_valid(): - time_str = datetime.datetime.utcnow().strftime("%Y/%m/%d,%H:%M:%S") + time_str = datetime.datetime.now(datetime.UTC).replace(tzinfo=None).strftime("%Y/%m/%d,%H:%M:%S") at_cmd(f"AT+QGPSXTRATIME=0,\"{time_str}\",1,1,1000") at_cmd("AT+QGPSCFG=\"outport\",\"usbnmea\"") diff --git a/system/qcomgpsd/structs.py b/system/qcomgpsd/structs.py index bde4e0049c8d245..f97704bbee6791a 100644 --- a/system/qcomgpsd/structs.py +++ b/system/qcomgpsd/structs.py @@ -192,8 +192,8 @@ int16_t latency; // Age of the measurement in msecs (+ve meas Meas precedes ref time) uint8_t predetect_interval; // Pre-Detection (Coherent) Interval (msecs) uint16_t postdetections; // Num Post-Detections (uints of PreInts - uint32_t unfiltered_measurement_integral; // Range of 0 thru (WEEK_MSECS-1) [msecs] - float unfiltered_measurement_fraction; // Range of 0 thru 0.99999 [msecs] + uint32_t unfiltered_measurement_integral; // Range of 0 through (WEEK_MSECS-1) [msecs] + float unfiltered_measurement_fraction; // Range of 0 through 0.99999 [msecs] float unfiltered_time_uncertainty; // Time uncertainty (msec) float unfiltered_speed; // Speed estimate (meters/sec) float unfiltered_speed_uncertainty; // Speed uncertainty estimate (meters/sec) diff --git a/system/qcomgpsd/tests/test_qcomgpsd.py b/system/qcomgpsd/tests/test_qcomgpsd.py index ef23737dd7e68c4..716bc33ed21b6aa 100644 --- a/system/qcomgpsd/tests/test_qcomgpsd.py +++ b/system/qcomgpsd/tests/test_qcomgpsd.py @@ -85,7 +85,7 @@ def check_assistance(self, should_be_loaded): if should_be_loaded: assert valid_duration == "10080" # should be max time injected_time = datetime.datetime.strptime(injected_time_str.replace("\"", ""), "%Y/%m/%d,%H:%M:%S") - assert abs((datetime.datetime.utcnow() - injected_time).total_seconds()) < 60*60*12 + assert abs((datetime.datetime.now(datetime.UTC).replace(tzinfo=None) - injected_time).total_seconds()) < 60*60*12 else: valid_duration, injected_time_str = out.split(",", 1) injected_time_str = injected_time_str.replace('\"', '').replace('\'', '') diff --git a/system/sensord/sensors/bmx055_accel.cc b/system/sensord/sensors/bmx055_accel.cc index bdb0113de3e14c5..bcc31e1d6cfd522 100644 --- a/system/sensord/sensors/bmx055_accel.cc +++ b/system/sensord/sensors/bmx055_accel.cc @@ -10,12 +10,15 @@ BMX055_Accel::BMX055_Accel(I2CBus *bus) : I2CSensor(bus) {} int BMX055_Accel::init() { int ret = verify_chip_id(BMX055_ACCEL_I2C_REG_ID, {BMX055_ACCEL_CHIP_ID}); - if (ret == -1) return -1; + if (ret == -1) { + goto fail; + } ret = set_register(BMX055_ACCEL_I2C_REG_PMU, BMX055_ACCEL_NORMAL_MODE); if (ret < 0) { goto fail; } + // bmx055 accel has a 1.3ms wakeup time from deep suspend mode util::sleep_for(10); @@ -36,11 +39,15 @@ int BMX055_Accel::init() { goto fail; } + enabled = true; + fail: return ret; } int BMX055_Accel::shutdown() { + if (!enabled) return 0; + // enter deep suspend mode (lowest power mode) int ret = set_register(BMX055_ACCEL_I2C_REG_PMU, BMX055_ACCEL_DEEP_SUSPEND); if (ret < 0) { diff --git a/system/sensord/sensors/bmx055_gyro.cc b/system/sensord/sensors/bmx055_gyro.cc index 411b2f445e25d57..0cc405f6547236f 100644 --- a/system/sensord/sensors/bmx055_gyro.cc +++ b/system/sensord/sensors/bmx055_gyro.cc @@ -46,11 +46,15 @@ int BMX055_Gyro::init() { goto fail; } + enabled = true; + fail: return ret; } int BMX055_Gyro::shutdown() { + if (!enabled) return 0; + // enter deep suspend mode (lowest power mode) int ret = set_register(BMX055_GYRO_I2C_REG_LPM1, BMX055_GYRO_DEEP_SUSPEND); if (ret < 0) { diff --git a/system/sensord/sensors/bmx055_magn.cc b/system/sensord/sensors/bmx055_magn.cc index 3d0d3d2fc600b49..b498c5fe3d8979e 100644 --- a/system/sensord/sensors/bmx055_magn.cc +++ b/system/sensord/sensors/bmx055_magn.cc @@ -78,7 +78,7 @@ int BMX055_Magn::init() { // suspend -> sleep int ret = set_register(BMX055_MAGN_I2C_REG_PWR_0, 0x01); if (ret < 0) { - LOGE("Enabling power failed: %d", ret); + LOGD("Enabling power failed: %d", ret); goto fail; } util::sleep_for(5); // wait until the chip is powered on @@ -139,7 +139,7 @@ int BMX055_Magn::init() { goto fail; } - + enabled = true; return 0; fail: @@ -147,6 +147,8 @@ int BMX055_Magn::init() { } int BMX055_Magn::shutdown() { + if (!enabled) return 0; + // move to suspend mode int ret = set_register(BMX055_MAGN_I2C_REG_PWR_0, 0); if (ret < 0) { diff --git a/system/sensord/sensors/i2c_sensor.h b/system/sensord/sensors/i2c_sensor.h index ba100c3b0128c20..e6d328ce7244180 100644 --- a/system/sensord/sensors/i2c_sensor.h +++ b/system/sensord/sensors/i2c_sensor.h @@ -39,7 +39,7 @@ class I2CSensor : public Sensor { uint8_t chip_id = 0; int ret = read_register(address, &chip_id, 1); if (ret < 0) { - LOGE("Reading chip ID failed: %d", ret); + LOGD("Reading chip ID failed: %d", ret); return -1; } for (int i = 0; i < expected_ids.size(); ++i) { diff --git a/system/sensord/sensors/lsm6ds3_gyro.cc b/system/sensord/sensors/lsm6ds3_gyro.cc index 0459b6ad64779c9..bb560edeabf3706 100644 --- a/system/sensord/sensors/lsm6ds3_gyro.cc +++ b/system/sensord/sensors/lsm6ds3_gyro.cc @@ -110,7 +110,7 @@ int LSM6DS3_Gyro::init() { uint8_t value = 0; bool do_self_test = false; - const char* env_lsm_selftest =env_lsm_selftest = std::getenv("LSM_SELF_TEST"); + const char* env_lsm_selftest = std::getenv("LSM_SELF_TEST"); if (env_lsm_selftest != nullptr && strncmp(env_lsm_selftest, "1", 1) == 0) { do_self_test = true; } diff --git a/system/sensord/sensors/sensor.h b/system/sensord/sensors/sensor.h index 1b0e3be0dc6065e..ccf998d161fa4a1 100644 --- a/system/sensord/sensors/sensor.h +++ b/system/sensord/sensors/sensor.h @@ -5,8 +5,10 @@ class Sensor { public: int gpio_fd = -1; + bool enabled = false; uint64_t start_ts = 0; uint64_t init_delay = 500e6; // default dealy 500ms + virtual ~Sensor() {} virtual int init() = 0; virtual bool get_event(MessageBuilder &msg, uint64_t ts = 0) = 0; diff --git a/system/sensord/sensors_qcom2.cc b/system/sensord/sensors_qcom2.cc index 9cbc24864d35f96..f9f51539c9e3cc3 100644 --- a/system/sensord/sensors_qcom2.cc +++ b/system/sensord/sensors_qcom2.cc @@ -39,6 +39,7 @@ void interrupt_loop(std::vector> sensors) { } } + uint64_t offset = nanos_since_epoch() - nanos_since_boot(); struct pollfd fd_list[1] = {0}; fd_list[0].fd = fd; fd_list[0].events = POLLIN | POLLPRI; @@ -62,15 +63,25 @@ void interrupt_loop(std::vector> sensors) { // Read all events struct gpioevent_data evdata[16]; - err = read(fd, evdata, sizeof(evdata)); + err = HANDLE_EINTR(read(fd, evdata, sizeof(evdata))); if (err < 0 || err % sizeof(*evdata) != 0) { LOGE("error reading event data %d", err); continue; } + uint64_t cur_offset = nanos_since_epoch() - nanos_since_boot(); + uint64_t diff = cur_offset > offset ? cur_offset - offset : offset - cur_offset; + if (diff > 10*1e6) { // 10ms + LOGW("time jumped: %lu %lu", cur_offset, offset); + offset = cur_offset; + + // we don't have a valid timestamp since the + // time jumped, so throw out this measurement. + continue; + } + int num_events = err / sizeof(*evdata); - uint64_t offset = nanos_since_epoch() - nanos_since_boot(); - uint64_t ts = evdata[num_events - 1].timestamp - offset; + uint64_t ts = evdata[num_events - 1].timestamp - cur_offset; for (auto &[sensor, msg_name] : sensors) { if (!sensor->has_interrupt_enabled()) { diff --git a/system/sentry.py b/system/sentry.py index 5f4772fa711a0df..63bf789b6fa2509 100644 --- a/system/sentry.py +++ b/system/sentry.py @@ -63,8 +63,6 @@ def init(project: SentryProject) -> bool: max_value_length=8192, environment=env) - build_metadata = get_build_metadata() - sentry_sdk.set_user({"id": dongle_id}) sentry_sdk.set_tag("dirty", build_metadata.openpilot.is_dirty) sentry_sdk.set_tag("origin", build_metadata.openpilot.git_origin) @@ -72,7 +70,4 @@ def init(project: SentryProject) -> bool: sentry_sdk.set_tag("commit", build_metadata.openpilot.git_commit) sentry_sdk.set_tag("device", HARDWARE.get_device_type()) - if project == SentryProject.SELFDRIVE: - sentry_sdk.Hub.current.start_session() - return True diff --git a/system/statsd.py b/system/statsd.py index 2b5a7bb3a7721c8..b8a7f2c661ace8d 100755 --- a/system/statsd.py +++ b/system/statsd.py @@ -2,6 +2,7 @@ import os import zmq import time +import uuid from pathlib import Path from collections import defaultdict from datetime import datetime, UTC @@ -102,6 +103,7 @@ def get_influxdb_line(measurement: str, value: float | dict[str, float], timest sm = SubMaster(['deviceState']) idx = 0 + boot_uid = str(uuid.uuid4())[:8] last_flush_time = time.monotonic() gauges = {} samples: dict[str, list[float]] = defaultdict(list) @@ -133,7 +135,7 @@ def get_influxdb_line(measurement: str, value: float | dict[str, float], timest # flush when started state changes or after FLUSH_TIME_S if (time.monotonic() > last_flush_time + STATS_FLUSH_TIME_S) or (sm['deviceState'].started != started_prev): result = "" - current_time = datetime.utcnow().replace(tzinfo=UTC) + current_time = datetime.now(UTC) tags['started'] = sm['deviceState'].started for key, value in gauges.items(): @@ -164,7 +166,7 @@ def get_influxdb_line(measurement: str, value: float | dict[str, float], timest # check that we aren't filling up the drive if len(os.listdir(STATS_DIR)) < STATS_DIR_FILE_LIMIT: if len(result) > 0: - stats_path = os.path.join(STATS_DIR, f"{current_time.timestamp():.0f}_{idx}") + stats_path = os.path.join(STATS_DIR, f"{boot_uid}_{idx}") with atomic_write_in_dir(stats_path) as f: f.write(result) idx += 1 diff --git a/system/tests/test_logmessaged.py b/system/tests/test_logmessaged.py index 3baf5300c0c13ea..9ccc8ef53bc25c7 100644 --- a/system/tests/test_logmessaged.py +++ b/system/tests/test_logmessaged.py @@ -19,7 +19,7 @@ def setup_method(self): self.error_sock = messaging.sub_sock("logMessage", timeout=1000, conflate=False) # ensure sockets are connected - time.sleep(1) + time.sleep(0.5) messaging.drain_sock(self.sock) messaging.drain_sock(self.error_sock) @@ -35,7 +35,7 @@ def test_simple_log(self): msgs = [f"abc {i}" for i in range(10)] for m in msgs: cloudlog.error(m) - time.sleep(3) + time.sleep(0.5) m = messaging.drain_sock(self.sock) assert len(m) == len(msgs) assert len(self._get_log_files()) >= 1 @@ -45,7 +45,7 @@ def test_big_log(self): msg = "a"*3*1024*1024 for _ in range(n): cloudlog.info(msg) - time.sleep(3) + time.sleep(0.5) msgs = messaging.drain_sock(self.sock) assert len(msgs) == 0 diff --git a/system/timed.py b/system/timed.py index 2b9a42c455154e5..31d0d0658868798 100755 --- a/system/timed.py +++ b/system/timed.py @@ -1,36 +1,14 @@ #!/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.time import system_time_valid -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}") +from openpilot.common.params import Params +from openpilot.common.gps import get_gps_location_service def set_time(new_time): @@ -48,25 +26,18 @@ def set_time(new_time): def main() -> NoReturn: """ - timed has two responsibilities: + timed has one responsibility: - getting the current time - - getting the current timezone - GPS directly gives time, and timezone is looked up from GPS position. + GPS directly gives time. AGNOS will also use NTP to update the time. """ params = Params() - - # 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) + gps_location_service = get_gps_location_service(params) pm = messaging.PubMaster(['clocks']) - sm = messaging.SubMaster(['liveLocationKalman']) + sm = messaging.SubMaster([gps_location_service]) while True: sm.update(1000) @@ -75,25 +46,15 @@ def main() -> NoReturn: 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: + gps = sm[gps_location_service] + if not sm.updated[gps_location_service] or (time.monotonic() - sm.logMonoTime[gps_location_service] / 1e9) > 2.0: continue # set time # TODO: account for unixTimesatmpMillis being a (usually short) time in the past - gps_time = datetime.datetime.fromtimestamp(llk.unixTimestampMillis / 1000.) + gps_time = datetime.datetime.fromtimestamp(gps.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__": diff --git a/system/ubloxd/pigeond.py b/system/ubloxd/pigeond.py index 5711992cfb1aa0c..8809689dcddf3c7 100755 --- a/system/ubloxd/pigeond.py +++ b/system/ubloxd/pigeond.py @@ -6,7 +6,7 @@ import struct import requests import urllib.parse -from datetime import datetime +from datetime import datetime, UTC from cereal import messaging from openpilot.common.params import Params @@ -196,7 +196,7 @@ def initialize_pigeon(pigeon: TTYPigeon) -> bool: cloudlog.error(f"failed to restore almanac backup, status: {restore_status}") # sending time to ublox - t_now = datetime.utcnow() + t_now = datetime.now(UTC).replace(tzinfo=None) if t_now >= datetime(2021, 6, 1): cloudlog.warning("Sending current time to ublox") diff --git a/system/ubloxd/ublox_msg.cc b/system/ubloxd/ublox_msg.cc index 26b33a1e32e5758..16b8766cf0276fb 100644 --- a/system/ubloxd/ublox_msg.cc +++ b/system/ubloxd/ublox_msg.cc @@ -174,7 +174,7 @@ kj::Array UbloxMsgParser::parse_gps_ephemeris(ubx_t::rxm_sfrbx_t *m int subframe_id = subframe.how()->subframe_id(); if (subframe_id > 3 || subframe_id < 1) { - // dont parse almanac subframes + // don't parse almanac subframes return kj::Array(); } gps_subframes[msg->sv_id()][subframe_id] = subframe_data; @@ -286,7 +286,7 @@ kj::Array UbloxMsgParser::parse_glonass_ephemeris(ubx_t::rxm_sfrbx_ glonass_t gl_string(&stream); int string_number = gl_string.string_number(); if (string_number < 1 || string_number > 5 || gl_string.idle_chip()) { - // dont parse non immediate data, idle_chip == 0 + // don't parse non immediate data, idle_chip == 0 return kj::Array(); } diff --git a/system/updated/tests/test_base.py b/system/updated/tests/test_base.py index 928d07cbe35892f..52287c58f9b744f 100644 --- a/system/updated/tests/test_base.py +++ b/system/updated/tests/test_base.py @@ -133,7 +133,7 @@ def _test_finalized_update(self, branch, version, agnos_version, release_notes): class ParamsBaseUpdateTest(TestBaseUpdate): def _test_finalized_update(self, branch, version, agnos_version, release_notes): assert self.params.get("UpdaterNewDescription", encoding="utf-8").startswith(f"{version} / {branch}") - assert self.params.get("UpdaterNewReleaseNotes", encoding="utf-8") == f"

{release_notes}

\n" + assert self.params.get("UpdaterNewReleaseNotes", encoding="utf-8") == f"{release_notes}\n" super()._test_finalized_update(branch, version, agnos_version, release_notes) def send_check_for_updates_signal(self, updated: ManagerProcess): diff --git a/system/updated/updated.py b/system/updated/updated.py index d43f439af583c2e..6f9fe173d89fe25 100755 --- a/system/updated/updated.py +++ b/system/updated/updated.py @@ -17,7 +17,7 @@ from openpilot.common.time import system_time_valid from openpilot.common.markdown import parse_markdown from openpilot.common.swaglog import cloudlog -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert +from openpilot.selfdrive.selfdrived.alertmanager import set_offroad_alert from openpilot.system.hardware import AGNOS, HARDWARE from openpilot.system.version import get_build_metadata @@ -60,7 +60,7 @@ def sleep(self, t: float) -> None: self.ready_event.wait(timeout=t) def write_time_to_param(params, param) -> None: - t = datetime.datetime.utcnow() + t = datetime.datetime.now(datetime.UTC).replace(tzinfo=None) params.put(param, t.isoformat().encode('utf8')) def read_time_from_param(params, param) -> datetime.datetime | None: @@ -279,7 +279,7 @@ def set_params(self, update_success: bool, failed_count: int, exception: str | N if len(self.branches): self.params.put("UpdaterAvailableBranches", ','.join(self.branches.keys())) - last_update = datetime.datetime.utcnow() + last_update = datetime.datetime.now(datetime.UTC).replace(tzinfo=None) if update_success: write_time_to_param(self.params, "LastUpdateTime") else: @@ -323,7 +323,7 @@ def get_description(basedir: str) -> str: for alert in ("Offroad_UpdateFailed", "Offroad_ConnectivityNeeded", "Offroad_ConnectivityNeededPrompt"): set_offroad_alert(alert, False) - now = datetime.datetime.utcnow() + now = datetime.datetime.now(datetime.UTC).replace(tzinfo=None) dt = now - last_update build_metadata = get_build_metadata() if failed_count > 15 and exception is not None and self.has_internet: @@ -429,7 +429,7 @@ def main() -> None: cloudlog.event("update installed") if not params.get("InstallDate"): - t = datetime.datetime.utcnow().isoformat() + t = datetime.datetime.now(datetime.UTC).replace(tzinfo=None).isoformat() params.put("InstallDate", t.encode('utf8')) updater = Updater() @@ -469,7 +469,7 @@ def main() -> None: # 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)) + timed_out = last_fetch is None or (datetime.datetime.now(datetime.UTC).replace(tzinfo=None) - 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") diff --git a/system/version.py b/system/version.py index 94964526b3f7a3b..2d8a387bf740d58 100755 --- a/system/version.py +++ b/system/version.py @@ -11,7 +11,7 @@ from openpilot.common.git import get_commit, get_origin, get_branch, get_short_branch, get_commit_date RELEASE_BRANCHES = ['release3-staging', 'release3', 'nightly'] -TESTED_BRANCHES = RELEASE_BRANCHES + ['devel', 'devel-staging'] +TESTED_BRANCHES = RELEASE_BRANCHES + ['devel', 'devel-staging', 'nightly-dev'] BUILD_METADATA_FILENAME = "build.json" diff --git a/system/webrtc/tests/test_stream_session.py b/system/webrtc/tests/test_stream_session.py index e89e42e440b47ac..113fa5e7e648ffe 100644 --- a/system/webrtc/tests/test_stream_session.py +++ b/system/webrtc/tests/test_stream_session.py @@ -3,6 +3,7 @@ # for aiortc and its dependencies import warnings warnings.filterwarnings("ignore", category=DeprecationWarning) +warnings.filterwarnings("ignore", category=RuntimeWarning) # TODO: remove this when google-crc32c publish a python3.12 wheel from aiortc import RTCDataChannel from aiortc.mediastreams import VIDEO_CLOCK_RATE, VIDEO_TIME_BASE @@ -48,7 +49,7 @@ def mocked_update(t): def test_incoming_proxy(self, mocker): tested_msgs = [ {"type": "customReservedRawData0", "data": "test"}, # primitive - {"type": "can", "data": [{"address": 0, "busTime": 0, "dat": "", "src": 0}]}, # list + {"type": "can", "data": [{"address": 0, "dat": "", "src": 0}]}, # list {"type": "testJoystick", "data": {"axes": [0, 0], "buttons": [False]}}, # dict ] diff --git a/system/webrtc/tests/test_webrtcd.py b/system/webrtc/tests/test_webrtcd.py index d4b659a3aa0e5d3..4fa6d8953f7312b 100644 --- a/system/webrtc/tests/test_webrtcd.py +++ b/system/webrtc/tests/test_webrtcd.py @@ -4,6 +4,7 @@ # for aiortc and its dependencies import warnings warnings.filterwarnings("ignore", category=DeprecationWarning) +warnings.filterwarnings("ignore", category=RuntimeWarning) # TODO: remove this when google-crc32c publish a python3.12 wheel from openpilot.system.webrtc.webrtcd import get_stream diff --git a/system/webrtc/webrtcd.py b/system/webrtc/webrtcd.py index afd346857f0d821..79c5b4888f31be8 100755 --- a/system/webrtc/webrtcd.py +++ b/system/webrtc/webrtcd.py @@ -11,6 +11,7 @@ # aiortc and its dependencies have lots of internal warnings :( import warnings warnings.filterwarnings("ignore", category=DeprecationWarning) +warnings.filterwarnings("ignore", category=RuntimeWarning) # TODO: remove this when google-crc32c publish a python3.12 wheel import capnp from aiohttp import web diff --git a/teleoprtc_repo/pyproject.toml b/teleoprtc_repo/pyproject.toml index ffdef0380d56847..b93df69fce7d3ba 100644 --- a/teleoprtc_repo/pyproject.toml +++ b/teleoprtc_repo/pyproject.toml @@ -25,7 +25,10 @@ dependencies = [ [project.optional-dependencies] dev = [ "parameterized>=0.8", - "pre-commit" + "pre-commit", + "pytest", + "pytest-asyncio", + "pytest-xdist" ] [project.urls] @@ -41,3 +44,9 @@ target-version="py38" select = ["E", "F", "W", "PIE", "C4", "ISC", "RUF008", "RUF100", "A", "B", "TID251"] ignore = ["W292", "E741", "E402", "C408", "ISC003", "B027", "B024"] flake8-implicit-str-concat.allow-multiline=false + +[tool.ruff.lint.flake8-tidy-imports.banned-api] +"unittest".msg = "Use pytest" + +[tool.pytest.ini_options] +addopts = "--durations=10 -n auto" diff --git a/teleoprtc_repo/tests/test_info.py b/teleoprtc_repo/tests/test_info.py index 893d8a426b4e101..5e939cdfeaa2943 100755 --- a/teleoprtc_repo/tests/test_info.py +++ b/teleoprtc_repo/tests/test_info.py @@ -1,7 +1,5 @@ #!/usr/bin/env python3 -import unittest - from teleoprtc.info import parse_info_from_offer @@ -9,7 +7,7 @@ def lf2crlf(x): return x.replace("\n", "\r\n") -class TestStream(unittest.TestCase): +class TestStream: def test_double_video_tracks(self): sdp = """v=0 o=- 3910210993 3910210993 IN IP4 0.0.0.0 @@ -90,10 +88,10 @@ def test_double_video_tracks(self): a=fingerprint:sha-256 70:3A:2D:37:3C:52:96:0E:10:F6:4D:7A:EB:18:38:1B:FD:CA:A5:90:D7:6C:DA:A9:39:76:C9:2F:FB:FF:56:0C a=setup:actpass""" info = parse_info_from_offer(lf2crlf(sdp)) - self.assertEqual(info.n_expected_camera_tracks, 2) - self.assertFalse(info.expected_audio_track) - self.assertFalse(info.incoming_audio_track) - self.assertFalse(info.incoming_datachannel) + assert info.n_expected_camera_tracks == 2 + assert not info.expected_audio_track + assert not info.incoming_audio_track + assert not info.incoming_datachannel def test_recvonly_audio(self): sdp = """v=0 @@ -120,10 +118,10 @@ def test_recvonly_audio(self): a=fingerprint:sha-256 40:4B:14:CF:70:B8:67:E1:B1:FF:7E:F9:22:6E:60:7D:73:B5:1E:38:4B:10:20:9C:CD:1C:47:02:52:ED:45:25 a=setup:actpass""" info = parse_info_from_offer(lf2crlf(sdp)) - self.assertEqual(info.n_expected_camera_tracks, 0) - self.assertTrue(info.expected_audio_track) - self.assertFalse(info.incoming_audio_track) - self.assertFalse(info.incoming_datachannel) + assert info.n_expected_camera_tracks == 0 + assert info.expected_audio_track + assert not info.incoming_audio_track + assert not info.incoming_datachannel def test_incoming_datachanel(self): sdp = """v=0 @@ -142,11 +140,7 @@ def test_incoming_datachanel(self): a=fingerprint:sha-256 9B:C0:F3:35:8E:05:A1:15:DB:F8:39:0E:B0:E0:0C:EB:82:E4:B9:26:18:A6:43:2D:B9:9A:23:96:0A:59:B6:58 a=setup:actpass""" info = parse_info_from_offer(lf2crlf(sdp)) - self.assertEqual(info.n_expected_camera_tracks, 0) - self.assertFalse(info.expected_audio_track) - self.assertFalse(info.incoming_audio_track) - self.assertTrue(info.incoming_datachannel) - - -if __name__ == '__main__': - unittest.main() + assert info.n_expected_camera_tracks == 0 + assert not info.expected_audio_track + assert not info.incoming_audio_track + assert info.incoming_datachannel diff --git a/teleoprtc_repo/tests/test_integration.py b/teleoprtc_repo/tests/test_integration.py index 5377bcece9ef4b4..d804af7b479aea5 100755 --- a/teleoprtc_repo/tests/test_integration.py +++ b/teleoprtc_repo/tests/test_integration.py @@ -1,8 +1,8 @@ #!/usr/bin/env python3 +import pytest import asyncio import sys -import unittest from aiortc.mediastreams import AudioStreamTrack, VideoStreamTrack from parameterized import parameterized @@ -65,7 +65,8 @@ async def __call__(self, offer: StreamingOffer): return answer -class TestStreamIntegration(unittest.IsolatedAsyncioTestCase): +@pytest.mark.asyncio +class TestStreamIntegration: @parameterized.expand([ # name, recv_cameras, recv_audio, messaging ("multi_camera", ["driver", "wideRoad", "road"], False, False), @@ -85,53 +86,49 @@ async def test_multi_camera(self, name, cameras, recv_audio, add_messaging): stream = offer_builder.stream() _ = await stream.start() - self.assertTrue(stream.is_started) + assert stream.is_started try: async with timeout(2): await stream.wait_for_connection() except TimeoutError: - self.fail("Timed out waiting for connection") - self.assertTrue(stream.is_connected_and_ready) + pytest.fail("Timed out waiting for connection") + assert stream.is_connected_and_ready - self.assertEqual(stream.has_messaging_channel(), add_messaging) + assert stream.has_messaging_channel() == add_messaging if stream.has_messaging_channel(): channel = stream.get_messaging_channel() - self.assertIsNotNone(channel) - self.assertEqual(channel.readyState, "open") + assert channel is not None + assert channel.readyState == "open" - self.assertEqual(stream.has_incoming_audio_track(), recv_audio) + assert stream.has_incoming_audio_track() == recv_audio if stream.has_incoming_audio_track(): track = stream.get_incoming_audio_track(False) - self.assertIsNotNone(track) - self.assertEqual(track.readyState, "live") - self.assertEqual(track.kind, "audio") + assert track is not None + assert track.readyState == "live" + assert track.kind == "audio" # test audio recv try: async with timeout(1): await track.recv() except TimeoutError: - self.fail("Timed out waiting for audio frame") + pytest.fail("Timed out waiting for audio frame") for cam in cameras: - self.assertTrue(stream.has_incoming_video_track(cam)) + assert stream.has_incoming_video_track(cam) if stream.has_incoming_video_track(cam): track = stream.get_incoming_video_track(cam, False) - self.assertIsNotNone(track) - self.assertEqual(track.readyState, "live") - self.assertEqual(track.kind, "video") + assert track is not None + assert track.readyState == "live" + assert track.kind == "video" # test video recv try: async with timeout(1): await stream.get_incoming_video_track(cam, False).recv() except TimeoutError: - self.fail("Timed out waiting for video frame") + pytest.fail("Timed out waiting for video frame") await stream.stop() await simple_answerer.stream.stop() - self.assertFalse(stream.is_started) - self.assertFalse(stream.is_connected_and_ready) - - -if __name__ == '__main__': - unittest.main() + assert not stream.is_started + assert not stream.is_connected_and_ready diff --git a/teleoprtc_repo/tests/test_stream.py b/teleoprtc_repo/tests/test_stream.py index 7882eed9c92f084..7e697e503f22a69 100755 --- a/teleoprtc_repo/tests/test_stream.py +++ b/teleoprtc_repo/tests/test_stream.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -import unittest +import pytest import aiortc from aiortc.mediastreams import AudioStreamTrack @@ -29,7 +29,8 @@ def codec_preference(self): return "H264" -class TestOfferStream(unittest.IsolatedAsyncioTestCase): +@pytest.mark.asyncio +class TestOfferStream: async def test_offer_stream_sdp_recvonly_audio(self): capture = OfferCapture() builder = WebRTCOfferBuilder(capture) @@ -42,8 +43,8 @@ async def test_offer_stream_sdp_recvonly_audio(self): pass info = parse_info_from_offer(capture.offer.sdp) - self.assertTrue(info.expected_audio_track) - self.assertFalse(info.incoming_audio_track) + assert info.expected_audio_track + assert not info.incoming_audio_track async def test_offer_stream_sdp_sendonly_audio(self): capture = OfferCapture() @@ -57,8 +58,8 @@ async def test_offer_stream_sdp_sendonly_audio(self): pass info = parse_info_from_offer(capture.offer.sdp) - self.assertFalse(info.expected_audio_track) - self.assertTrue(info.incoming_audio_track) + assert not info.expected_audio_track + assert info.incoming_audio_track async def test_offer_stream_sdp_channel(self): capture = OfferCapture() @@ -72,10 +73,11 @@ async def test_offer_stream_sdp_channel(self): pass info = parse_info_from_offer(capture.offer.sdp) - self.assertTrue(info.incoming_datachannel) + assert info.incoming_datachannel -class TestAnswerStream(unittest.IsolatedAsyncioTestCase): +@pytest.mark.asyncio +class TestAnswerStream: async def test_codec_preference(self): offer_sdp = """v=0 o=- 3910274679 3910274679 IN IP4 0.0.0.0 @@ -115,7 +117,7 @@ async def test_codec_preference(self): sdp_desc = aiortc.sdp.SessionDescription.parse(answer.sdp) video_desc = [m for m in sdp_desc.media if m.kind == "video"][0] codecs = video_desc.rtp.codecs - self.assertEqual(codecs[0].mimeType, "video/H264") + assert codecs[0].mimeType == "video/H264" async def test_fail_if_preferred_codec_not_in_offer(self): offer_sdp = """v=0 @@ -147,9 +149,5 @@ async def test_fail_if_preferred_codec_not_in_offer(self): builder.add_video_stream("road", DummyH264VideoStreamTrack("road", 0.05)) stream = builder.stream() - with self.assertRaises(ValueError): + with pytest.raises(ValueError): _ = await stream.start() - - -if __name__=="__main__": - unittest.main() \ No newline at end of file diff --git a/teleoprtc_repo/tests/test_track.py b/teleoprtc_repo/tests/test_track.py index 3c8fcbb274fff3f..52b4483558d1dfe 100755 --- a/teleoprtc_repo/tests/test_track.py +++ b/teleoprtc_repo/tests/test_track.py @@ -1,22 +1,22 @@ #!/usr/bin/env python3 -import unittest +import pytest import aiortc from teleoprtc.tracks import video_track_id, parse_video_track_id, TiciVideoStreamTrack, TiciTrackWrapper -class TestTracks(unittest.TestCase): +class TestTracks: def test_track_id(self): expected_camera_type, expected_track_id = "driver", "test" track_id = video_track_id(expected_camera_type, expected_track_id) camera_type, track_id = parse_video_track_id(track_id) - self.assertEqual(expected_camera_type, camera_type) - self.assertEqual(expected_track_id, track_id) + assert expected_camera_type == camera_type + assert expected_track_id == track_id def test_track_id_invalid(self): - with self.assertRaises(ValueError): + with pytest.raises(ValueError): parse_video_track_id("test") def test_tici_track_id(self): @@ -26,13 +26,9 @@ async def recv(self): track = VideoStream("driver", 0.1) camera_type, _ = parse_video_track_id(track.id) - self.assertEqual("driver", camera_type) + assert "driver" == camera_type def test_tici_wrapper_id(self): track = TiciTrackWrapper("driver", aiortc.mediastreams.VideoStreamTrack()) camera_type, _ = parse_video_track_id(track.id) - self.assertEqual("driver", camera_type) - - -if __name__ == '__main__': - unittest.main() + assert "driver" == camera_type diff --git a/third_party/SConscript b/third_party/SConscript index e5bbfaa07a8d67f..507c17c4a5c7151 100644 --- a/third_party/SConscript +++ b/third_party/SConscript @@ -1,6 +1,4 @@ Import('env') env.Library('json11', ['json11/json11.cpp'], CCFLAGS=env['CCFLAGS'] + ['-Wno-unqualified-std-cast-call']) -env.Append(CPPPATH=[Dir('json11')]) - env.Library('kaitai', ['kaitai/kaitaistream.cpp'], CPPDEFINES=['KS_STR_ENCODING_NONE']) diff --git a/third_party/libyuv/larch64/lib/libyuv.a b/third_party/libyuv/larch64/lib/libyuv.a index fdbcda2517a96c5..d3be4725f9a9176 100644 Binary files a/third_party/libyuv/larch64/lib/libyuv.a and b/third_party/libyuv/larch64/lib/libyuv.a differ diff --git a/third_party/maplibre-native-qt/.gitignore b/third_party/maplibre-native-qt/.gitignore deleted file mode 100644 index 9adc6681c022997..000000000000000 --- a/third_party/maplibre-native-qt/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/maplibre/ diff --git a/third_party/maplibre-native-qt/aarch64 b/third_party/maplibre-native-qt/aarch64 deleted file mode 120000 index 062c65e8d99c642..000000000000000 --- a/third_party/maplibre-native-qt/aarch64 +++ /dev/null @@ -1 +0,0 @@ -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 deleted file mode 100755 index a368026f0fe00ef..000000000000000 --- a/third_party/maplibre-native-qt/build.sh +++ /dev/null @@ -1,36 +0,0 @@ -#!/usr/bin/env bash -set -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" - -ARCHNAME=$(uname -m) -MAPLIBRE_FLAGS="-DMLN_QT_WITH_LOCATION=OFF" -if [ -f /TICI ]; then - ARCHNAME="larch64" - #MAPLIBRE_FLAGS="$MAPLIBRE_FLAGS -DCMAKE_SYSTEM_NAME=Android -DANDROID_ABI=arm64-v8a" -fi - -cd $DIR -if [ ! -d maplibre ]; then - git clone --single-branch https://github.com/maplibre/maplibre-native-qt.git $DIR/maplibre -fi - -cd maplibre -git checkout 3726266e127c1f94ad64837c9dbe03d238255816 -git submodule update --depth=1 --recursive --init - -# build -mkdir -p build -cd build -cmake $MAPLIBRE_FLAGS $DIR/maplibre -make -j$(nproc) - -INSTALL_DIR="$DIR/$ARCHNAME" -rm -rf $INSTALL_DIR -mkdir -p $INSTALL_DIR - -rm -rf $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 deleted file mode 100644 index 38b03d498e89399..000000000000000 --- a/third_party/maplibre-native-qt/include/conversion_p.hpp +++ /dev/null @@ -1,241 +0,0 @@ -// 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 deleted file mode 100644 index bd5ad495db6a85c..000000000000000 --- a/third_party/maplibre-native-qt/include/export_core.hpp +++ /dev/null @@ -1,20 +0,0 @@ -// 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 deleted file mode 100644 index a9863468841fa09..000000000000000 --- a/third_party/maplibre-native-qt/include/export_location.hpp +++ /dev/null @@ -1,20 +0,0 @@ -// 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 deleted file mode 100644 index 11bc28819033d15..000000000000000 --- a/third_party/maplibre-native-qt/include/export_widgets.hpp +++ /dev/null @@ -1,20 +0,0 @@ -// 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 deleted file mode 100644 index 8387f70c4b193ba..000000000000000 --- a/third_party/maplibre-native-qt/include/geojson_p.hpp +++ /dev/null @@ -1,30 +0,0 @@ -// 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 deleted file mode 100644 index b2630daea755489..000000000000000 --- a/third_party/maplibre-native-qt/include/gl_widget.hpp +++ /dev/null @@ -1,56 +0,0 @@ -// 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 deleted file mode 100644 index c97781fd29d5cb8..000000000000000 --- a/third_party/maplibre-native-qt/include/gl_widget_p.hpp +++ /dev/null @@ -1,42 +0,0 @@ -// 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 deleted file mode 100644 index cd56996185be72d..000000000000000 --- a/third_party/maplibre-native-qt/include/map.hpp +++ /dev/null @@ -1,205 +0,0 @@ -// 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 deleted file mode 100644 index e68c72b17b0571a..000000000000000 --- a/third_party/maplibre-native-qt/include/map_observer_p.hpp +++ /dev/null @@ -1,54 +0,0 @@ -// 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 deleted file mode 100644 index 9ca0c7e6f5a9830..000000000000000 --- a/third_party/maplibre-native-qt/include/map_p.hpp +++ /dev/null @@ -1,79 +0,0 @@ -// 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 deleted file mode 100644 index b9a087c392ee80c..000000000000000 --- a/third_party/maplibre-native-qt/include/map_renderer_p.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// 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 deleted file mode 100644 index 5eb01805034bff9..000000000000000 --- a/third_party/maplibre-native-qt/include/qgeomap.hpp +++ /dev/null @@ -1,54 +0,0 @@ -// 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 deleted file mode 100644 index ce415d9bcf0af7d..000000000000000 --- a/third_party/maplibre-native-qt/include/qgeomap_p.hpp +++ /dev/null @@ -1,93 +0,0 @@ -// 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 deleted file mode 100644 index a8dc445e2b6c465..000000000000000 --- a/third_party/maplibre-native-qt/include/qmaplibre.hpp +++ /dev/null @@ -1,9 +0,0 @@ -// 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 deleted file mode 100644 index ebe9a8eea4cd675..000000000000000 --- a/third_party/maplibre-native-qt/include/qmaplibrewidgets.hpp +++ /dev/null @@ -1,6 +0,0 @@ -// 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 deleted file mode 100644 index 67cb4b56ced996c..000000000000000 --- a/third_party/maplibre-native-qt/include/qt_mapping_engine.hpp +++ /dev/null @@ -1,31 +0,0 @@ -// 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 deleted file mode 100644 index d6f88b871b7a7de..000000000000000 --- a/third_party/maplibre-native-qt/include/settings.hpp +++ /dev/null @@ -1,125 +0,0 @@ -// 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 deleted file mode 100644 index 257bdfd5a9afdbb..000000000000000 --- a/third_party/maplibre-native-qt/include/settings_p.hpp +++ /dev/null @@ -1,57 +0,0 @@ -// 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 deleted file mode 100644 index 991bb4077ea0d1f..000000000000000 --- a/third_party/maplibre-native-qt/include/style_change_utils_p.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// 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 deleted file mode 100644 index 96f63b353492f51..000000000000000 --- a/third_party/maplibre-native-qt/include/texture_node.hpp +++ /dev/null @@ -1,42 +0,0 @@ -// 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 deleted file mode 100644 index 696fab1a88f229d..000000000000000 --- a/third_party/maplibre-native-qt/include/types.hpp +++ /dev/null @@ -1,206 +0,0 @@ -// 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\n", + "

Longitudinal maneuver report

\n", + f"

{platform}

\n", + f"

{route}

\n", + f"

{ID.gitCommit}, {ID.gitBranch}, {ID.gitRemote}

\n", + ] + if _description is not None: + builder.append(f"

Description: {_description}

\n") + builder.append(f"

CarParams

{format_car_params(CP)}
\n") + builder.append('{ summary }') # to be replaced below + for description, runs in maneuvers: + print(f'plotting maneuver: {description}, runs: {len(runs)}') + builder.append("
\n") + builder.append(f"

{description}

\n") + for run, msgs in enumerate(runs): + t_carControl, carControl = zip(*[(m.logMonoTime, m.carControl) for m in msgs if m.which() == 'carControl'], strict=True) + t_carOutput, carOutput = zip(*[(m.logMonoTime, m.carOutput) for m in msgs if m.which() == 'carOutput'], strict=True) + t_carState, carState = zip(*[(m.logMonoTime, m.carState) for m in msgs if m.which() == 'carState'], strict=True) + t_livePose, livePose = zip(*[(m.logMonoTime, m.livePose) for m in msgs if m.which() == 'livePose'], strict=True) + t_longitudinalPlan, longitudinalPlan = zip(*[(m.logMonoTime, m.longitudinalPlan) for m in msgs if m.which() == 'longitudinalPlan'], strict=True) + + # make time relative seconds + t_carControl = [(t - t_carControl[0]) / 1e9 for t in t_carControl] + t_carOutput = [(t - t_carOutput[0]) / 1e9 for t in t_carOutput] + t_carState = [(t - t_carState[0]) / 1e9 for t in t_carState] + t_livePose = [(t - t_livePose[0]) / 1e9 for t in t_livePose] + t_longitudinalPlan = [(t - t_longitudinalPlan[0]) / 1e9 for t in t_longitudinalPlan] + + # maneuver validity + longActive = [m.longActive for m in carControl] + maneuver_valid = all(longActive) and (not any(cs.cruiseState.standstill for cs in carState) or CP.autoResumeSng) + + _open = 'open' if maneuver_valid else '' + title = f'Run #{int(run)+1}' + (' (invalid maneuver!)' if not maneuver_valid else '') + + builder.append(f"

{title}

\n") + + # get first acceleration target and first intersection + aTarget = longitudinalPlan[0].aTarget + target_cross_time = None + builder.append(f'

Initial aTarget: {round(aTarget, 2)} m/s^2') + + # Localizer is noisy, require two consecutive 20Hz frames above threshold + prev_crossed = False + for t, lp in zip(t_livePose, livePose, strict=True): + crossed = (0 < aTarget < lp.accelerationDevice.x) or (0 > aTarget > lp.accelerationDevice.x) + if crossed and prev_crossed: + builder.append(f', crossed in {t:.3f}s') + target_cross_time = t + if maneuver_valid: + target_cross_times[description].append(t) + break + prev_crossed = crossed + else: + builder.append(', not crossed') + builder.append('

') + + pitches = [math.degrees(m.orientationNED[1]) for m in carControl] + builder.append(f'

Average pitch: {sum(pitches) / len(pitches):0.2f} degrees

') + + plt.rcParams['font.size'] = 40 + fig = plt.figure(figsize=(30, 26)) + ax = fig.subplots(4, 1, sharex=True, gridspec_kw={'height_ratios': [5, 3, 1, 1]}) + + ax[0].grid(linewidth=4) + ax[0].plot(t_carControl, [m.actuators.accel for m in carControl], label='carControl.actuators.accel', linewidth=6) + ax[0].plot(t_carOutput, [m.actuatorsOutput.accel for m in carOutput], label='carOutput.actuatorsOutput.accel', linewidth=6) + ax[0].plot(t_longitudinalPlan, [m.aTarget for m in longitudinalPlan], label='longitudinalPlan.aTarget', linewidth=6) + ax[0].plot(t_carState, [m.aEgo for m in carState], label='carState.aEgo', linewidth=6) + ax[0].plot(t_livePose, [m.accelerationDevice.x for m in livePose], label='livePose.accelerationDevice.x', linewidth=6) + # TODO localizer accel + ax[0].set_ylabel('Acceleration (m/s^2)') + #ax[0].set_ylim(-6.5, 6.5) + ax[0].legend(prop={'size': 30}) + + if target_cross_time is not None: + ax[0].plot(target_cross_time, aTarget, marker='o', markersize=50, markeredgewidth=7, markeredgecolor='black', markerfacecolor='None') + + ax[1].grid(linewidth=4) + ax[1].plot(t_carState, [m.vEgo for m in carState], 'g', label='vEgo', linewidth=6) + ax[1].set_ylabel('Velocity (m/s)') + ax[1].legend() + + ax[2].plot(t_carControl, longActive, label='longActive', linewidth=6) + ax[3].plot(t_carState, [m.gasPressed for m in carState], label='gasPressed', linewidth=6) + ax[3].plot(t_carState, [m.brakePressed for m in carState], label='brakePressed', linewidth=6) + for i in (2, 3): + ax[i].set_yticks([0, 1], minor=False) + ax[i].set_ylim(-1, 2) + ax[i].legend() + + ax[-1].set_xlabel("Time (s)") + fig.tight_layout() + + buffer = io.BytesIO() + fig.savefig(buffer, format='webp') + plt.close(fig) + buffer.seek(0) + builder.append(f"\n") + builder.append("
\n") + + summary = ["

Summary

\n"] + cols = ['maneuver', 'crossed', 'runs', 'mean', 'min', 'max'] + table = [] + for description, runs in maneuvers: + times = target_cross_times[description] + l = [description, len(times), len(runs)] + if len(times): + l.extend([round(sum(times) / len(times), 2), round(min(times), 2), round(max(times), 2)]) + table.append(l) + summary.append(tabulate(table, headers=cols, tablefmt='html', numalign='left') + '\n') + + sum_idx = builder.index('{ summary }') + builder[sum_idx:sum_idx + 1] = summary + + with open(output_fn, "w") as f: + f.write(''.join(builder)) + + print(f"\nReport written to {output_fn}\n") + + +if __name__ == '__main__': + parser = argparse.ArgumentParser(description='Generate longitudinal maneuver report from route') + parser.add_argument('route', type=str, help='Route name (e.g. 00000000--5f742174be)') + parser.add_argument('description', type=str, nargs='?') + + args = parser.parse_args() + + if '/' in args.route or '|' in args.route: + lr = LogReader(args.route) + else: + segs = [seg for seg in os.listdir(Paths.log_root()) if args.route in seg] + lr = LogReader([os.path.join(Paths.log_root(), seg, 'rlog') for seg in segs]) + + CP = lr.first('carParams') + ID = lr.first('initData') + platform = CP.carFingerprint + print('processing report for', platform) + + maneuvers: list[tuple[str, list[list]]] = [] + active_prev = False + description_prev = None + + for msg in lr: + if msg.which() == 'alertDebug': + active = 'Maneuver Active' in msg.alertDebug.alertText1 + if active and not active_prev: + if msg.alertDebug.alertText2 == description_prev: + maneuvers[-1][1].append([]) + else: + maneuvers.append((msg.alertDebug.alertText2, [[]])) + description_prev = maneuvers[-1][0] + active_prev = active + + if active_prev: + maneuvers[-1][1][-1].append(msg) + + report(platform, args.route, args.description, CP, ID, maneuvers) diff --git a/tools/longitudinal_maneuvers/maneuversd.py b/tools/longitudinal_maneuvers/maneuversd.py new file mode 100755 index 000000000000000..6c6e252a57b1c61 --- /dev/null +++ b/tools/longitudinal_maneuvers/maneuversd.py @@ -0,0 +1,185 @@ +#!/usr/bin/env python3 +import numpy as np +from dataclasses import dataclass + +from cereal import messaging, car +from opendbc.car.common.conversions import Conversions as CV +from openpilot.common.realtime import DT_MDL +from openpilot.common.params import Params +from openpilot.common.swaglog import cloudlog + + +@dataclass +class Action: + accel_bp: list[float] # m/s^2 + time_bp: list[float] # seconds + + def __post_init__(self): + assert len(self.accel_bp) == len(self.time_bp) + + +@dataclass +class Maneuver: + description: str + actions: list[Action] + repeat: int = 0 + initial_speed: float = 0. # m/s + + _active: bool = False + _finished: bool = False + _action_index: int = 0 + _action_frames: int = 0 + _ready_cnt: int = 0 + _repeated: int = 0 + + def get_accel(self, v_ego: float, long_active: bool, standstill: bool, cruise_standstill: bool) -> float: + ready = abs(v_ego - self.initial_speed) < 0.3 and long_active and not cruise_standstill + if self.initial_speed < 0.01: + ready = ready and standstill + self._ready_cnt = (self._ready_cnt + 1) if ready else 0 + + if self._ready_cnt > (3. / DT_MDL): + self._active = True + + if not self._active: + return min(max(self.initial_speed - v_ego, -2.), 2.) + + action = self.actions[self._action_index] + action_accel = np.interp(self._action_frames * DT_MDL, action.time_bp, action.accel_bp) + + self._action_frames += 1 + + # reached duration of action + if self._action_frames > (action.time_bp[-1] / DT_MDL): + # next action + if self._action_index < len(self.actions) - 1: + self._action_index += 1 + self._action_frames = 0 + # repeat maneuver + elif self._repeated < self.repeat: + self._repeated += 1 + self._action_index = 0 + self._action_frames = 0 + self._active = False + # finish maneuver + else: + self._finished = True + + return float(action_accel) + + @property + def finished(self): + return self._finished + + @property + def active(self): + return self._active + + +MANEUVERS = [ + Maneuver( + "come to stop", + [Action([-0.5], [12])], + repeat=2, + initial_speed=5., + ), + Maneuver( + "start from stop", + [Action([1.5], [6])], + repeat=2, + initial_speed=0., + ), + Maneuver( + "creep: alternate between +1m/s^2 and -1m/s^2", + [ + Action([1], [3]), Action([-1], [3]), + Action([1], [3]), Action([-1], [3]), + Action([1], [3]), Action([-1], [3]), + ], + repeat=2, + initial_speed=0., + ), + Maneuver( + "brake step response: -1m/s^2 from 20mph", + [Action([-1], [3])], + repeat=2, + initial_speed=20. * CV.MPH_TO_MS, + ), + Maneuver( + "brake step response: -4m/s^2 from 20mph", + [Action([-4], [3])], + repeat=2, + initial_speed=20. * CV.MPH_TO_MS, + ), + Maneuver( + "gas step response: +1m/s^2 from 20mph", + [Action([1], [3])], + repeat=2, + initial_speed=20. * CV.MPH_TO_MS, + ), + Maneuver( + "gas step response: +4m/s^2 from 20mph", + [Action([4], [3])], + repeat=2, + initial_speed=20. * CV.MPH_TO_MS, + ), +] + + +def main(): + params = Params() + cloudlog.info("joystickd is waiting for CarParams") + CP = messaging.log_from_bytes(params.get("CarParams", block=True), car.CarParams) + + sm = messaging.SubMaster(['carState', 'carControl', 'controlsState', 'selfdriveState', 'modelV2'], poll='modelV2') + pm = messaging.PubMaster(['longitudinalPlan', 'driverAssistance', 'alertDebug']) + + maneuvers = iter(MANEUVERS) + maneuver = None + + while True: + sm.update() + + if maneuver is None: + maneuver = next(maneuvers, None) + + alert_msg = messaging.new_message('alertDebug') + alert_msg.valid = True + + plan_send = messaging.new_message('longitudinalPlan') + plan_send.valid = sm.all_checks() + + longitudinalPlan = plan_send.longitudinalPlan + accel = 0 + v_ego = max(sm['carState'].vEgo, 0) + + if maneuver is not None: + accel = maneuver.get_accel(v_ego, sm['carControl'].longActive, sm['carState'].standstill, sm['carState'].cruiseState.standstill) + + if maneuver.active: + alert_msg.alertDebug.alertText1 = f'Maneuver Active: {accel:0.2f} m/s^2' + else: + alert_msg.alertDebug.alertText1 = f'Setting up to {maneuver.initial_speed * CV.MS_TO_MPH:0.2f} mph' + alert_msg.alertDebug.alertText2 = f'{maneuver.description}' + else: + alert_msg.alertDebug.alertText1 = 'Maneuvers Finished' + + pm.send('alertDebug', alert_msg) + + longitudinalPlan.aTarget = accel + longitudinalPlan.shouldStop = v_ego < CP.vEgoStopping and accel < 1e-2 + + longitudinalPlan.allowBrake = True + longitudinalPlan.allowThrottle = True + longitudinalPlan.hasLead = True + + longitudinalPlan.speeds = [0.2] # triggers carControl.cruiseControl.resume in controlsd + + pm.send('longitudinalPlan', plan_send) + + assistance_send = messaging.new_message('driverAssistance') + assistance_send.valid = True + pm.send('driverAssistance', assistance_send) + + if maneuver is not None and maneuver.finished: + maneuver = None
%1%2%4%5%6%7